From 33549de273d538bf376c5b2828810f03e76f2490 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sun, 30 Jan 2022 03:16:38 +0900 Subject: [PATCH 001/223] ci: add sync-upstream.yaml (#4) Signed-off-by: Kenji Miyake --- .github/workflows/sync-upstream.yaml | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) create mode 100644 .github/workflows/sync-upstream.yaml diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml new file mode 100644 index 0000000000000..cd0d5af4883a3 --- /dev/null +++ b/.github/workflows/sync-upstream.yaml @@ -0,0 +1,28 @@ +name: sync-upstream + +on: + schedule: + - cron: 0 19 * * * # run at 4 AM JST + workflow_dispatch: + +jobs: + sync-upstream: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@tier4/proposal + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/main + sync-pr-branch: sync-upstream + sync-target-repository: https://github.com/autowarefoundation/autoware.universe.git + sync-target-branch: tier4/proposal + pr-title: "chore: sync upstream" + auto-merge-method: merge From acf26eaa8c16c95cddcc527c02ed473da6ed748d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 3 Mar 2022 16:34:55 +0900 Subject: [PATCH 002/223] ci(sync-upstream): update settings (#19) Signed-off-by: Kenji Miyake --- .github/workflows/sync-upstream.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index cd0d5af4883a3..3e164c07dbec1 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -2,7 +2,7 @@ name: sync-upstream on: schedule: - - cron: 0 19 * * * # run at 4 AM JST + - cron: 0 0 * * * workflow_dispatch: jobs: @@ -17,12 +17,12 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@tier4/proposal + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main sync-pr-branch: sync-upstream sync-target-repository: https://github.com/autowarefoundation/autoware.universe.git - sync-target-branch: tier4/proposal + sync-target-branch: main pr-title: "chore: sync upstream" auto-merge-method: merge From 4a3e529bde03d9470e3c84868a460726ee641959 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 5 Apr 2022 12:59:33 +0000 Subject: [PATCH 003/223] chore: sync files (#629) * chore: sync files Signed-off-by: GitHub * ci(pre-commit): autofix Co-authored-by: kenji-miyake Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .markdownlint.yaml | 2 ++ .prettierrc.yaml | 18 ++++++++++++++++++ CPPLINT.cfg | 1 + common/goal_distance_calculator/package.xml | 2 +- common/path_distance_calculator/package.xml | 2 -- common/polar_grid/package.xml | 1 - common/tier4_api_utils/package.xml | 2 -- common/tier4_datetime_rviz_plugin/package.xml | 2 -- .../tier4_localization_rviz_plugin/package.xml | 2 -- common/tier4_planning_rviz_plugin/package.xml | 2 -- .../package.xml | 2 -- common/tier4_state_rviz_plugin/package.xml | 2 -- control/shift_decider/package.xml | 1 - launch/tier4_vehicle_launch/package.xml | 1 - localization/ekf_localizer/package.xml | 1 - map/util/lanelet2_map_preprocessor/package.xml | 6 ------ perception/tensorrt_yolo/package.xml | 1 - .../package.xml | 1 - planning/obstacle_stop_planner/package.xml | 1 - planning/planning_error_monitor/package.xml | 2 +- .../image_transport_decompressor/package.xml | 2 -- 21 files changed, 23 insertions(+), 31 deletions(-) diff --git a/.markdownlint.yaml b/.markdownlint.yaml index dbd5b9703d834..df1f518dc0d48 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -1,3 +1,4 @@ +# See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. default: true MD013: false MD024: @@ -5,3 +6,4 @@ MD024: MD033: false MD041: false MD046: false +MD049: false diff --git a/.prettierrc.yaml b/.prettierrc.yaml index 48b0552e3fe47..e29bf32762769 100644 --- a/.prettierrc.yaml +++ b/.prettierrc.yaml @@ -1,2 +1,20 @@ printWidth: 100 tabWidth: 2 +overrides: + - files: package.xml + options: + printWidth: 1000 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.launch.xml" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.xacro" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore diff --git a/CPPLINT.cfg b/CPPLINT.cfg index 1e2521f0b6442..ba6bdf08c10ca 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -11,3 +11,4 @@ filter=-whitespace/parens # we allow closing parenthesis to be on the ne filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon filter=-build/header_guard # we automatically fix the names of header guards using pre-commit filter=-build/include_order # we use the custom include order +filter=-build/include_subdir # we allow the style of "foo.hpp" diff --git a/common/goal_distance_calculator/package.xml b/common/goal_distance_calculator/package.xml index d191ffd3945c9..66a911d8e9786 100644 --- a/common/goal_distance_calculator/package.xml +++ b/common/goal_distance_calculator/package.xml @@ -3,7 +3,7 @@ goal_distance_calculator 0.0.0 - The goal_distance_calculator package + The goal_distance_calculator package Taiki Tanaka Apache License 2.0 diff --git a/common/path_distance_calculator/package.xml b/common/path_distance_calculator/package.xml index c69f961f271ef..e85c8ccd93850 100644 --- a/common/path_distance_calculator/package.xml +++ b/common/path_distance_calculator/package.xml @@ -1,7 +1,6 @@ - path_distance_calculator 0.0.0 The path_distance_calculator package @@ -20,5 +19,4 @@ ament_cmake - diff --git a/common/polar_grid/package.xml b/common/polar_grid/package.xml index c11858c4dcc98..ea5b9dd9986e9 100644 --- a/common/polar_grid/package.xml +++ b/common/polar_grid/package.xml @@ -24,5 +24,4 @@ ament_cmake - diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 4141904db9945..ba307d694a56c 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -1,7 +1,6 @@ - tier4_api_utils 0.0.0 The tier4_api_utils package @@ -24,5 +23,4 @@ ament_cmake - diff --git a/common/tier4_datetime_rviz_plugin/package.xml b/common/tier4_datetime_rviz_plugin/package.xml index 853b22b49be10..bb6b72797290b 100644 --- a/common/tier4_datetime_rviz_plugin/package.xml +++ b/common/tier4_datetime_rviz_plugin/package.xml @@ -1,6 +1,5 @@ - tier4_datetime_rviz_plugin 0.0.0 The tier4_datetime_rviz_plugin package @@ -22,5 +21,4 @@ ament_cmake - diff --git a/common/tier4_localization_rviz_plugin/package.xml b/common/tier4_localization_rviz_plugin/package.xml index 7d054c46c5083..a48dfb3ac3d73 100644 --- a/common/tier4_localization_rviz_plugin/package.xml +++ b/common/tier4_localization_rviz_plugin/package.xml @@ -1,6 +1,5 @@ - tier4_localization_rviz_plugin 0.1.0 The tier4_localization_rviz_plugin package @@ -25,5 +24,4 @@ ament_cmake - diff --git a/common/tier4_planning_rviz_plugin/package.xml b/common/tier4_planning_rviz_plugin/package.xml index 9d47827548843..3a937abeb5eb4 100644 --- a/common/tier4_planning_rviz_plugin/package.xml +++ b/common/tier4_planning_rviz_plugin/package.xml @@ -1,6 +1,5 @@ - tier4_planning_rviz_plugin 0.1.0 The tier4_planning_rviz_plugin package @@ -28,5 +27,4 @@ ament_cmake - diff --git a/common/tier4_simulated_clock_rviz_plugin/package.xml b/common/tier4_simulated_clock_rviz_plugin/package.xml index 4835e2b4bc3bb..25f701a6ce56f 100644 --- a/common/tier4_simulated_clock_rviz_plugin/package.xml +++ b/common/tier4_simulated_clock_rviz_plugin/package.xml @@ -1,6 +1,5 @@ - tier4_simulated_clock_rviz_plugin 0.0.1 Rviz plugin to publish and control the /clock topic @@ -23,5 +22,4 @@ ament_cmake - diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index e949c0c6a6148..2d33d6f1aaa7d 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -1,6 +1,5 @@ - tier4_state_rviz_plugin 0.0.0 The autoware state rviz plugin package @@ -26,5 +25,4 @@ ament_cmake - diff --git a/control/shift_decider/package.xml b/control/shift_decider/package.xml index a6640725a1597..1c7e2b1913944 100644 --- a/control/shift_decider/package.xml +++ b/control/shift_decider/package.xml @@ -21,5 +21,4 @@ ament_cmake - diff --git a/launch/tier4_vehicle_launch/package.xml b/launch/tier4_vehicle_launch/package.xml index bc2ef43e0a6bd..b0a3ea6a21485 100644 --- a/launch/tier4_vehicle_launch/package.xml +++ b/launch/tier4_vehicle_launch/package.xml @@ -7,7 +7,6 @@ Yukihiro Saito Apache License 2.0 - ament_cmake_auto robot_state_publisher diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index e4a380039ff02..0f27207fdc08d 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -29,5 +29,4 @@ ament_cmake - diff --git a/map/util/lanelet2_map_preprocessor/package.xml b/map/util/lanelet2_map_preprocessor/package.xml index e71adaea8bc73..7ec500da53ebb 100644 --- a/map/util/lanelet2_map_preprocessor/package.xml +++ b/map/util/lanelet2_map_preprocessor/package.xml @@ -9,25 +9,21 @@ mitsudome-r - Apache License 2.0 - - - @@ -59,10 +55,8 @@ pcl_ros roscpp - - diff --git a/perception/tensorrt_yolo/package.xml b/perception/tensorrt_yolo/package.xml index ff47dff04d845..9e393a56f1eef 100755 --- a/perception/tensorrt_yolo/package.xml +++ b/perception/tensorrt_yolo/package.xml @@ -24,5 +24,4 @@ ament_cmake - diff --git a/perception/traffic_light_ssd_fine_detector/package.xml b/perception/traffic_light_ssd_fine_detector/package.xml index 223dbf0b0f8c1..cf37f7f9baa8f 100644 --- a/perception/traffic_light_ssd_fine_detector/package.xml +++ b/perception/traffic_light_ssd_fine_detector/package.xml @@ -10,7 +10,6 @@ Daisuke Nishimatsu - diff --git a/planning/obstacle_stop_planner/package.xml b/planning/obstacle_stop_planner/package.xml index 45100bec069f6..a665fd8fcfe9c 100644 --- a/planning/obstacle_stop_planner/package.xml +++ b/planning/obstacle_stop_planner/package.xml @@ -37,5 +37,4 @@ ament_cmake - diff --git a/planning/planning_error_monitor/package.xml b/planning/planning_error_monitor/package.xml index 8bef053fc095d..e35554a392d7e 100644 --- a/planning/planning_error_monitor/package.xml +++ b/planning/planning_error_monitor/package.xml @@ -2,7 +2,7 @@ planning_error_monitor 0.1.0 - ros node for monitoring planning error + ros node for monitoring planning error Yutaka Shimizu diff --git a/sensing/image_transport_decompressor/package.xml b/sensing/image_transport_decompressor/package.xml index c6238d4fd7ae6..9f131490dea3f 100644 --- a/sensing/image_transport_decompressor/package.xml +++ b/sensing/image_transport_decompressor/package.xml @@ -24,6 +24,4 @@ ament_cmake - - From 3dea07d2c4a90c6729ab23525955c5a62e628b8c Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Wed, 6 Apr 2022 11:05:46 +0900 Subject: [PATCH 004/223] chore: sync files (#637) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 7e3d186886b6b..51e93d53049fc 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -42,7 +42,7 @@ jobs: - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} - uses: codecov/codecov-action@v2 + uses: codecov/codecov-action@v3 with: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 125d209ac1603..a7476a607d7e9 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -41,7 +41,7 @@ jobs: - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} - uses: codecov/codecov-action@v2 + uses: codecov/codecov-action@v3 with: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false From f037c18dfa92a52a637d5ec1031e7036663bd989 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 6 Apr 2022 14:03:11 +0900 Subject: [PATCH 005/223] fix(dummy_diag_publisher): use anon to make unique node name instead of diag name (#639) --- .../launch/dummy_diag_publisher_node.launch.xml | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml b/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml index ae1042fc006bf..5448fb0269c09 100644 --- a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml +++ b/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml @@ -5,13 +5,11 @@ - - - - - - - + + + + + From 3a3724243f701818db9ccf890eee0c833679163a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 9 Apr 2022 07:09:58 +0000 Subject: [PATCH 006/223] chore: sync files (#648) * chore: sync files Signed-off-by: GitHub * Revert "chore: sync files" This reverts commit b24f530b48306e16aa285f80a629ce5c5a9ccda7. Signed-off-by: Kenji Miyake * sync codecov.yaml Signed-off-by: Kenji Miyake Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake --- .github/sync-files.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 1cb1b399efe4d..494ab9300f025 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -35,6 +35,7 @@ - source: .github/workflows/build-and-test-self-hosted.yaml - source: .github/workflows/check-build-depends.yaml - source: .github/workflows/clang-tidy-pr-comments.yaml + - source: codecov.yaml - repository: autowarefoundation/autoware-documentation files: From a8272006e59cd73db96adba0abe68a68e930a03b Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 11 Apr 2022 15:58:38 +0900 Subject: [PATCH 007/223] fix(autoware_state_panel): fix message type for /api/autoware/get/engage (#666) * fix(autoware_state_panel): fix message type for /api/autoware/get/engage Signed-off-by: h-ohta * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp | 4 ++-- common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index b0cad0282cf9a..78681106b3d61 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -109,7 +109,7 @@ void AutowareStatePanel::onInitialize() sub_gear_ = raw_node_->create_subscription( "/vehicle/status/gear_status", 10, std::bind(&AutowareStatePanel::onShift, this, _1)); - sub_engage_ = raw_node_->create_subscription( + sub_engage_ = raw_node_->create_subscription( "/api/autoware/get/engage", 10, std::bind(&AutowareStatePanel::onEngageStatus, this, _1)); client_engage_ = raw_node_->create_client( @@ -209,7 +209,7 @@ void AutowareStatePanel::onShift( } void AutowareStatePanel::onEngageStatus( - const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg) + const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg) { current_engage_ = msg->engage; engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_))); diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index af562dd055f7c..45cd290e5f4a3 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -23,10 +23,10 @@ #include #include +#include #include #include #include -#include #include namespace rviz_plugins @@ -48,7 +48,7 @@ public Q_SLOTS: const tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr msg); void onAutowareState(const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg); void onShift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); - void onEngageStatus(const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg); + void onEngageStatus(const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg); rclcpp::Node::SharedPtr raw_node_; rclcpp::Subscription::SharedPtr sub_gate_mode_; @@ -57,7 +57,7 @@ public Q_SLOTS: rclcpp::Subscription::SharedPtr sub_autoware_state_; rclcpp::Subscription::SharedPtr sub_gear_; - rclcpp::Subscription::SharedPtr sub_engage_; + rclcpp::Subscription::SharedPtr sub_engage_; rclcpp::Client::SharedPtr client_engage_; From 9f5837ffcd8246fa8f9a377c23d2d0e7b1251346 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 9 May 2022 11:10:17 +0900 Subject: [PATCH 008/223] fix(behavior_velocity): avoid insert same point on trajectory utils (#834) Signed-off-by: tanaka3 --- .../include/utilization/trajectory_utils.hpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp b/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp index 93b3d9c3d9617..729af3099f814 100644 --- a/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp +++ b/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp @@ -91,7 +91,7 @@ inline Quaternion lerpOrientation( * @param [in] point Interpolated point is nearest to this point. */ template -TrajectoryPointWithIdx getLerpTrajectoryPointWithIdx( +boost::optional getLerpTrajectoryPointWithIdx( const T & points, const geometry_msgs::msg::Point & point) { TrajectoryPoint interpolated_point; @@ -100,7 +100,9 @@ TrajectoryPointWithIdx getLerpTrajectoryPointWithIdx( tier4_autoware_utils::calcLongitudinalOffsetToSegment(points, nearest_seg_idx, point); const double len_segment = tier4_autoware_utils::calcSignedArcLength(points, nearest_seg_idx, nearest_seg_idx + 1); - const double interpolate_ratio = std::clamp(len_to_interpolated / len_segment, 0.0, 1.0); + const double ratio = len_to_interpolated / len_segment; + if (ratio <= 0.0 || 1.0 <= ratio) return boost::none; + const double interpolate_ratio = std::clamp(ratio, 0.0, 1.0); { const size_t i = nearest_seg_idx; const auto & pos0 = points.at(i).pose.position; @@ -154,14 +156,15 @@ inline bool smoothPath( // calc ego internal division point on path const auto traj_with_ego_point_with_idx = getLerpTrajectoryPointWithIdx(*traj_lateral_acc_filtered, current_pose.position); - TrajectoryPoint ego_point_on_path = traj_with_ego_point_with_idx.first; - const size_t nearest_seg_idx = traj_with_ego_point_with_idx.second; + if (traj_with_ego_point_with_idx == boost::none) return false; + TrajectoryPoint ego_point_on_path = traj_with_ego_point_with_idx->first; + const size_t nearest_seg_idx = traj_with_ego_point_with_idx->second; //! insert ego projected pose on path so new nearest segment will be nearest_seg_idx + 1 traj_with_ego_point_on_path.insert( traj_with_ego_point_on_path.begin() + nearest_seg_idx, ego_point_on_path); // ego point inserted is new nearest point - nearest_idx = traj_with_ego_point_with_idx.second + 1; + nearest_idx = nearest_seg_idx + 1; } // Resample trajectory with ego-velocity based interval distances auto traj_resampled = smoother->resampleTrajectory(traj_with_ego_point_on_path, v0, nearest_idx); @@ -182,6 +185,7 @@ inline bool smoothPath( traj_smoothed.insert( traj_smoothed.begin(), traj_resampled->begin(), traj_resampled->begin() + *traj_resampled_closest); + out_path = convertTrajectoryPointsToPath(traj_smoothed); return true; } From 69fc674ae3d0f668183b1661fd3dbc0843253a73 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 9 May 2022 11:59:02 +0900 Subject: [PATCH 009/223] refactor(behavior_velocity_planner): simplify CMakeLists.txt (#855) Signed-off-by: Kenji Miyake --- .../behavior_velocity_planner/CMakeLists.txt | 296 ++---------------- 1 file changed, 27 insertions(+), 269 deletions(-) diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 6acaa54b6481b..47f6f999ecb08 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -11,292 +11,50 @@ find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED COMPONENTS common) find_package(OpenCV REQUIRED) -set(BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES - tier4_api_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - tier4_planning_msgs - tier4_autoware_utils - Boost - Eigen3 - diagnostic_msgs - geometry_msgs - lanelet2_extension - PCL - pcl_conversions - rclcpp - sensor_msgs - interpolation - tf2 - tf2_eigen - tf2_geometry_msgs - tf2_ros - vehicle_info_util - visualization_msgs - nav_msgs - grid_map_ros -) +set(scene_modules + detection_area + blind_spot + stop_line + crosswalk + traffic_light + intersection + no_stopping_area + virtual_traffic_light + occlusion_spot +) + +foreach(scene_module IN LISTS scene_modules) + file(GLOB_RECURSE scene_module_src "src/scene_module/${scene_module}/*") + list(APPEND scene_modules_src ${scene_module_src}) +endforeach() - -# Common -ament_auto_add_library(scene_module_lib SHARED +ament_auto_add_library(behavior_velocity_planner SHARED + src/node.cpp + src/planner_manager.cpp src/utilization/path_utilization.cpp src/utilization/util.cpp + ${scene_modules_src} ) -target_include_directories(scene_module_lib +target_include_directories(behavior_velocity_planner SYSTEM PUBLIC ${BOOST_INCLUDE_DIRS} - ${tf2_geometry_msgs_INCLUDE_DIRS} -) - -target_include_directories(scene_module_lib - PUBLIC - $ - $ -) - -target_include_directories(scene_module_lib - SYSTEM PUBLIC ${PCL_INCLUDE_DIRS} -) - -ament_target_dependencies(scene_module_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -# Scene Module: Stop Line -ament_auto_add_library(scene_module_stop_line SHARED - src/scene_module/stop_line/manager.cpp - src/scene_module/stop_line/scene.cpp - src/scene_module/stop_line/debug.cpp -) - -target_include_directories(scene_module_stop_line - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_stop_line ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_stop_line scene_module_lib) - -# Scene Module: Crosswalk -ament_auto_add_library(scene_module_crosswalk SHARED - src/scene_module/crosswalk/manager.cpp - src/scene_module/crosswalk/scene_crosswalk.cpp - src/scene_module/crosswalk/scene_walkway.cpp - src/scene_module/crosswalk/debug.cpp - src/scene_module/crosswalk/util.cpp -) - -target_include_directories(scene_module_crosswalk - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_crosswalk ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_crosswalk scene_module_lib) - -# Scene Module: Intersection -ament_auto_add_library(scene_module_intersection SHARED - src/scene_module/intersection/manager.cpp - src/scene_module/intersection/scene_intersection.cpp - src/scene_module/intersection/scene_merge_from_private_road.cpp - src/scene_module/intersection/debug.cpp - src/scene_module/intersection/util.cpp -) - -target_include_directories(scene_module_intersection - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_intersection ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_intersection scene_module_lib) - -# Scene Module: Traffic Light -ament_auto_add_library(scene_module_traffic_light SHARED - src/scene_module/traffic_light/manager.cpp - src/scene_module/traffic_light/scene.cpp - src/scene_module/traffic_light/debug.cpp -) - -target_include_directories(scene_module_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_traffic_light scene_module_lib) - -# Scene Module: Blind Spot -ament_auto_add_library(scene_module_blind_spot SHARED - src/scene_module/blind_spot/manager.cpp - src/scene_module/blind_spot/scene.cpp - src/scene_module/blind_spot/debug.cpp -) - -target_include_directories(scene_module_blind_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_blind_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_blind_spot scene_module_lib) - -# Scene Module: Detection Area -ament_auto_add_library(scene_module_detection_area SHARED - src/scene_module/detection_area/manager.cpp - src/scene_module/detection_area/scene.cpp - src/scene_module/detection_area/debug.cpp -) - -target_include_directories(scene_module_detection_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_detection_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_detection_area scene_module_lib) - -# Scene Module: No Stopping Area -ament_auto_add_library(scene_module_no_stopping_area SHARED - src/scene_module/no_stopping_area/manager.cpp - src/scene_module/no_stopping_area/scene_no_stopping_area.cpp - src/scene_module/no_stopping_area/debug.cpp -) - -target_include_directories(scene_module_no_stopping_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_no_stopping_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_no_stopping_area scene_module_lib) - -# Scene Module: Virtual Traffic Light -ament_auto_add_library(scene_module_virtual_traffic_light SHARED - src/scene_module/virtual_traffic_light/manager.cpp - src/scene_module/virtual_traffic_light/scene.cpp - src/scene_module/virtual_traffic_light/debug.cpp -) - -target_include_directories(scene_module_virtual_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_virtual_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_virtual_traffic_light scene_module_lib) - -# SceneModule OcclusionSpot -# Util -ament_auto_add_library(occlusion_spot_lib SHARED - src/scene_module/occlusion_spot/grid_utils.cpp - src/scene_module/occlusion_spot/occlusion_spot_utils.cpp - src/scene_module/occlusion_spot/risk_predictive_braking.cpp -) - -target_include_directories(occlusion_spot_lib - SYSTEM PUBLIC - ${BOOST_INCLUDE_DIRS} ${tf2_geometry_msgs_INCLUDE_DIRS} ) -target_include_directories(occlusion_spot_lib - PUBLIC - $ - $ -) - -ament_target_dependencies(occlusion_spot_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -ament_auto_add_library(scene_module_occlusion_spot SHARED - src/scene_module/occlusion_spot/manager.cpp - src/scene_module/occlusion_spot/debug.cpp - src/scene_module/occlusion_spot/scene_occlusion_spot.cpp -) - -target_include_directories(scene_module_occlusion_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_occlusion_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_occlusion_spot scene_module_lib occlusion_spot_lib) - -# Scene Module Manager -ament_auto_add_library(scene_module_manager SHARED - src/planner_manager.cpp -) - -target_include_directories(scene_module_manager - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_manager ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_manager scene_module_lib) - -# Node -ament_auto_add_library(behavior_velocity_planner SHARED - src/node.cpp -) - -target_include_directories(behavior_velocity_planner - PUBLIC - $ - $ -) - -ament_target_dependencies(behavior_velocity_planner ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(behavior_velocity_planner - scene_module_lib - scene_module_stop_line - scene_module_crosswalk - scene_module_intersection - scene_module_traffic_light - scene_module_blind_spot - scene_module_occlusion_spot - scene_module_detection_area - scene_module_no_stopping_area - scene_module_virtual_traffic_light - scene_module_manager +ament_target_dependencies(behavior_velocity_planner + Boost + Eigen3 + PCL ) -ament_export_dependencies(${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - rclcpp_components_register_node(behavior_velocity_planner PLUGIN "behavior_velocity_planner::BehaviorVelocityPlannerNode" EXECUTABLE behavior_velocity_planner_node ) - if(BUILD_TESTING) - # utils for test - ament_auto_add_library(utilization SHARED - src/utilization/util.cpp - ) - # Gtest for utilization ament_add_gtest(utilization-test test/src/test_state_machine.cpp @@ -305,7 +63,7 @@ if(BUILD_TESTING) ) target_link_libraries(utilization-test gtest_main - utilization + behavior_velocity_planner ) # Gtest for occlusion spot @@ -316,7 +74,7 @@ if(BUILD_TESTING) ) target_link_libraries(occlusion_spot-test gtest_main - scene_module_occlusion_spot + behavior_velocity_planner ) endif() From 063a95d3f9c88e3e4fe69c4adf8be2c0d3be2a81 Mon Sep 17 00:00:00 2001 From: Shark <71419791+Sharrrrk@users.noreply.github.com> Date: Mon, 9 May 2022 11:31:50 +0800 Subject: [PATCH 010/223] fix(system_monitor): fix build error on tegra platform (#869) * fix(system_monitor): fix build error on tegra platform Signed-off-by: Shark Liu * ci(pre-commit): autofix * Update system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp Co-authored-by: Shark Liu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp index a9ae72321efd1..8da0d071de582 100644 --- a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp +++ b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp @@ -127,8 +127,10 @@ void GPUMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & stat) } } -void GPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper & stat) +void GPUMonitor::checkThrottling( + [[maybe_unused]] diagnostic_updater::DiagnosticStatusWrapper & stat) { + // Please remove the [[maybe_unused]] tag after implementation, it's a temp build fix // TODO(Fumihito Ito): implement me } From 35a1f0a28b141491997e342b25153998bbc4f56e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 9 May 2022 14:07:00 +0900 Subject: [PATCH 011/223] feat(ad_service_state_monitor): limit odometry buffer size (#514) * feat(ad_service_state_monitor): limit odometry buffer size 40 Signed-off-by: Takayuki Murooka * Update system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Update ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../ad_service_state_monitor_node.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp index e5a59692983ca..076f8d3a9f399 100644 --- a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp +++ b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp @@ -120,6 +120,11 @@ void AutowareStateMonitorNode::onOdometry(const nav_msgs::msg::Odometry::ConstSh state_input_.odometry_buffer.pop_front(); } + + constexpr size_t odometry_buffer_size = 200; // 40Hz * 5sec + if (state_input_.odometry_buffer.size() > odometry_buffer_size) { + state_input_.odometry_buffer.pop_front(); + } } bool AutowareStateMonitorNode::onShutdownService( From 82c6ad85bc0193021f94a28c4ce16c99525d5090 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Mon, 9 May 2022 17:53:57 +0900 Subject: [PATCH 012/223] docs: fix 404 error caused by typo in url (#871) * docs: fix 404 error caused by typo in url Signed-off-by: Shin-kyoto * docs: fix typo in url for yolov4 Signed-off-by: Shin-kyoto --- perception/tensorrt_yolo/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/tensorrt_yolo/README.md b/perception/tensorrt_yolo/README.md index 5dfae272f143a..5811fa88a6b7a 100644 --- a/perception/tensorrt_yolo/README.md +++ b/perception/tensorrt_yolo/README.md @@ -72,15 +72,15 @@ This package includes multiple licenses. ### YOLOv4 -[YOLOv4](https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). +[YOLOv4](https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). ### YOLOv5 Refer to [this guide](https://github.com/ultralytics/yolov5/issues/251 "guide") -- [YOLOv5s](https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") +- [YOLOv5s](https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") -- [YOLOv5m](https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") +- [YOLOv5m](https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") - [YOLOv5l](https://drive.google.com/uc?id=1xO8S92Cq7qrmx93UHHyA7Cd7-dJsBDP8 "YOLOv5l") From a7118b62a065c02a70266a2dda3e4b296ccad886 Mon Sep 17 00:00:00 2001 From: storrrrrrrrm <103425473+storrrrrrrrm@users.noreply.github.com> Date: Mon, 9 May 2022 17:15:57 +0800 Subject: [PATCH 013/223] fix(image_projection_based_fusion): set imagebuffersize (#820) * fix: set imagebuffersize configured Signed-off-by: suchang * ci(pre-commit): autofix Co-authored-by: suchang Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/image_projection_based_fusion/debugger.hpp | 5 +++-- .../launch/roi_cluster_fusion.launch.xml | 2 ++ .../launch/roi_detected_object_fusion.launch.xml | 2 ++ perception/image_projection_based_fusion/src/debugger.cpp | 7 +++++-- .../image_projection_based_fusion/src/fusion_node.cpp | 4 +++- 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index ff790894658ec..9ecd336818b59 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -38,7 +38,8 @@ using sensor_msgs::msg::RegionOfInterest; class Debugger { public: - explicit Debugger(rclcpp::Node * node_ptr, const std::size_t image_num); + explicit Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size); void publishImage(const std::size_t image_id, const rclcpp::Time & stamp); @@ -57,7 +58,7 @@ class Debugger std::vector image_subs_; std::vector image_pubs_; std::vector> image_buffers_; - std::size_t image_buffer_size{5}; + std::size_t image_buffer_size_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 8fe94963ff8ca..e5824dfcff97f 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index f6466e6512a09..be981478e78a2 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index e1254fc136304..0bcfb019d93df 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -34,9 +34,12 @@ void drawRoiOnImage( namespace image_projection_based_fusion { -Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ptr_(node_ptr) +Debugger::Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size) +: node_ptr_(node_ptr) { image_buffers_.resize(image_num); + image_buffer_size_ = image_buffer_size; for (std::size_t img_i = 0; img_i < image_num; ++img_i) { auto sub = image_transport::create_subscription( node_ptr, "input/image_raw" + std::to_string(img_i), @@ -54,7 +57,7 @@ Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ auto pub = image_transport::create_publisher(node_ptr, "output/image_raw" + std::to_string(img_i)); image_pubs_.push_back(pub); - image_buffers_.at(img_i).set_capacity(image_buffer_size); + image_buffers_.at(img_i).set_capacity(image_buffer_size_); } } diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 57ed245f67bd7..5d33303ca1bf9 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -127,7 +127,9 @@ FusionNode::FusionNode(const std::string & node_name, const rclcpp::NodeOpt // debugger if (declare_parameter("debug_mode", false)) { - debugger_ = std::make_shared(this, rois_number_); + std::size_t image_buffer_size = + static_cast(declare_parameter("image_buffer_size", 15)); + debugger_ = std::make_shared(this, rois_number_, image_buffer_size); } } From 880967342402c09f33615805ffe8a1e12360c930 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 9 May 2022 19:18:23 +0900 Subject: [PATCH 014/223] chore(avoidance_module): fix spell check (#732) Signed-off-by: Muhammad Zulfaqar Azmi --- .../scene_module/avoidance/debug.hpp | 2 +- .../src/scene_module/avoidance/avoidance_module.cpp | 8 ++++---- .../src/scene_module/avoidance/debug.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp index edfb7d7f84d71..d3f8f80606784 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp @@ -93,7 +93,7 @@ MarkerArray createPoseMarkerArray( MarkerArray makeOverhangToRoadShoulderMarkerArray( const behavior_path_planner::ObjectDataArray & objects); -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index b03282c735ece..876e5fc3112c3 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1939,8 +1939,8 @@ void AvoidanceModule::modifyPathVelocityToPreventAccelerationOnAvoidance(Shifted std::sqrt(v0 * v0 + 2.0 * s * parameters_.max_avoidance_acceleration)); // apply velocity limit - constexpr size_t VLIM_APPLY_IDX_MARGIN = 0; - for (size_t i = ego_idx + VLIM_APPLY_IDX_MARGIN; i < N; ++i) { + constexpr size_t V_LIM_APPLY_IDX_MARGIN = 0; + for (size_t i = ego_idx + V_LIM_APPLY_IDX_MARGIN; i < N; ++i) { path.path.points.at(i).point.longitudinal_velocity_mps = std::min(path.path.points.at(i).point.longitudinal_velocity_mps, static_cast(vmax)); } @@ -2619,7 +2619,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData using marker_utils::createAvoidPointMarkerArray; using marker_utils::createLaneletsAreaMarkerArray; using marker_utils::createObjectsMarkerArray; - using marker_utils::createOvehangFurthestLineStringMarkerArray; + using marker_utils::createOverhangFurthestLineStringMarkerArray; using marker_utils::createPathMarkerArray; using marker_utils::createPoseMarkerArray; using marker_utils::createShiftLengthMarkerArray; @@ -2652,7 +2652,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData add(createLaneletsAreaMarkerArray(*debug.expanded_lanelets, "expanded_lanelet", 0.8, 0.8, 0.0)); add(createAvoidanceObjectsMarkerArray(avoidance_data_.objects, "avoidance_object")); add(makeOverhangToRoadShoulderMarkerArray(avoidance_data_.objects)); - add(createOvehangFurthestLineStringMarkerArray( + add(createOverhangFurthestLineStringMarkerArray( *debug.farthest_linestring_from_overhang, "farthest_linestring_from_overhang", 1.0, 0.0, 1.0)); // parent object info diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp index d7c3b1325f7dc..88c8d102bd00c 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp @@ -512,7 +512,7 @@ MarkerArray makeOverhangToRoadShoulderMarkerArray( return msg; } -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b) { From cc43203bc87745624b6185ef73b783f42170e8c9 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 9 May 2022 21:08:53 +0900 Subject: [PATCH 015/223] feat: isolate gtests in all packages (#693) Signed-off-by: Maxime CLEMENT --- common/autoware_auto_common/CMakeLists.txt | 2 +- common/autoware_auto_common/package.xml | 2 +- common/autoware_auto_geometry/CMakeLists.txt | 2 +- common/autoware_auto_geometry/package.xml | 2 +- common/autoware_auto_tf2/CMakeLists.txt | 2 +- common/autoware_auto_tf2/package.xml | 2 +- common/autoware_point_types/CMakeLists.txt | 2 +- common/autoware_point_types/package.xml | 2 +- common/fake_test_node/CMakeLists.txt | 2 +- common/fake_test_node/package.xml | 2 +- common/had_map_utils/package.xml | 2 +- common/interpolation/CMakeLists.txt | 2 +- common/interpolation/package.xml | 2 +- common/motion_testing/CMakeLists.txt | 2 +- common/motion_testing/package.xml | 2 +- common/osqp_interface/CMakeLists.txt | 2 +- common/osqp_interface/package.xml | 2 +- common/signal_processing/CMakeLists.txt | 2 +- common/signal_processing/package.xml | 2 +- common/tier4_api_utils/CMakeLists.txt | 2 +- common/tier4_api_utils/package.xml | 2 +- common/tier4_autoware_utils/CMakeLists.txt | 4 ++-- common/tier4_autoware_utils/package.xml | 2 +- common/time_utils/package.xml | 2 +- common/vehicle_constants_manager/CMakeLists.txt | 2 +- common/vehicle_constants_manager/package.xml | 2 +- control/trajectory_follower/CMakeLists.txt | 4 ++-- control/trajectory_follower/package.xml | 2 +- control/vehicle_cmd_gate/CMakeLists.txt | 2 +- control/vehicle_cmd_gate/package.xml | 2 +- localization/ekf_localizer/CMakeLists.txt | 4 ++-- localization/ekf_localizer/package.xml | 2 +- localization/stop_filter/package.xml | 2 +- map/lanelet2_extension/CMakeLists.txt | 10 +++++----- map/lanelet2_extension/package.xml | 2 +- .../detected_object_feature_remover/package.xml | 2 +- planning/behavior_velocity_planner/CMakeLists.txt | 4 ++-- planning/behavior_velocity_planner/package.xml | 2 +- planning/costmap_generator/CMakeLists.txt | 2 +- planning/costmap_generator/package.xml | 2 +- .../freespace_planning_algorithms/CMakeLists.txt | 4 ++-- planning/freespace_planning_algorithms/package.xml | 2 +- planning/planning_error_monitor/CMakeLists.txt | 2 +- planning/planning_error_monitor/package.xml | 2 +- planning/planning_evaluator/CMakeLists.txt | 2 +- planning/planning_evaluator/package.xml | 2 +- .../dummy_perception_publisher/CMakeLists.txt | 2 +- simulator/dummy_perception_publisher/package.xml | 1 + simulator/fault_injection/CMakeLists.txt | 2 +- simulator/fault_injection/package.xml | 2 +- simulator/simple_planning_simulator/CMakeLists.txt | 2 +- simulator/simple_planning_simulator/package.xml | 2 +- system/system_monitor/CMakeLists.txt | 14 +++++++------- system/system_monitor/package.xml | 2 +- vehicle/raw_vehicle_cmd_converter/CMakeLists.txt | 2 +- vehicle/raw_vehicle_cmd_converter/package.xml | 2 +- 56 files changed, 71 insertions(+), 70 deletions(-) diff --git a/common/autoware_auto_common/CMakeLists.txt b/common/autoware_auto_common/CMakeLists.txt index 4f7846c89eb72..b0957ad726856 100644 --- a/common/autoware_auto_common/CMakeLists.txt +++ b/common/autoware_auto_common/CMakeLists.txt @@ -9,7 +9,7 @@ include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR}) if(BUILD_TESTING) set(TEST_COMMON test_common_gtest) - ament_add_gtest(${TEST_COMMON} + ament_add_ros_isolated_gtest(${TEST_COMMON} test/gtest_main.cpp test/test_bool_comparisons.cpp test/test_byte_reader.cpp diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index dca22e9b29ea3..17d666e2273e6 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -14,7 +14,7 @@ builtin_interfaces eigen - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common geometry_msgs diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt index 0e964e3b064a2..454e0e7ef044f 100644 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ b/common/autoware_auto_geometry/CMakeLists.txt @@ -23,7 +23,7 @@ if(BUILD_TESTING) test/src/test_common_2d.cpp test/src/test_intersection.cpp ) - ament_add_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) + ament_add_ros_isolated_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) target_compile_options(${GEOMETRY_GTEST} PRIVATE -Wno-conversion -Wno-sign-conversion) target_include_directories(${GEOMETRY_GTEST} PRIVATE "test/include" "include") ament_target_dependencies(${GEOMETRY_GTEST} diff --git a/common/autoware_auto_geometry/package.xml b/common/autoware_auto_geometry/package.xml index 976cf59013370..e19ac4897aab0 100644 --- a/common/autoware_auto_geometry/package.xml +++ b/common/autoware_auto_geometry/package.xml @@ -18,7 +18,7 @@ autoware_auto_vehicle_msgs geometry_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common osrf_testing_tools_cpp diff --git a/common/autoware_auto_tf2/CMakeLists.txt b/common/autoware_auto_tf2/CMakeLists.txt index f4b3223391a7b..a8ae9ec2d962e 100755 --- a/common/autoware_auto_tf2/CMakeLists.txt +++ b/common/autoware_auto_tf2/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(autoware_cmake REQUIRED) autoware_package() if(BUILD_TESTING) - ament_add_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) + ament_add_ros_isolated_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) target_include_directories(test_tf2_autoware_auto_msgs PRIVATE "include") ament_target_dependencies(test_tf2_autoware_auto_msgs "autoware_auto_common" diff --git a/common/autoware_auto_tf2/package.xml b/common/autoware_auto_tf2/package.xml index d6fbd4f4ce3d8..c80ce45a217ac 100644 --- a/common/autoware_auto_tf2/package.xml +++ b/common/autoware_auto_tf2/package.xml @@ -20,7 +20,7 @@ tf2_geometry_msgs tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/autoware_point_types/CMakeLists.txt b/common/autoware_point_types/CMakeLists.txt index e46081c5ea96f..c149f79dab71f 100644 --- a/common/autoware_point_types/CMakeLists.txt +++ b/common/autoware_point_types/CMakeLists.txt @@ -11,7 +11,7 @@ include_directories( ) if(BUILD_TESTING) - ament_add_gtest(test_autoware_point_types + ament_add_ros_isolated_gtest(test_autoware_point_types test/test_point_types.cpp ) target_include_directories(test_autoware_point_types diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml index b7449dbbd13d5..8829bd7538d9b 100644 --- a/common/autoware_point_types/package.xml +++ b/common/autoware_point_types/package.xml @@ -23,7 +23,7 @@ pcl_ros point_cloud_msg_wrapper - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common point_cloud_msg_wrapper diff --git a/common/fake_test_node/CMakeLists.txt b/common/fake_test_node/CMakeLists.txt index cc80077163ab1..8ad71df2777f3 100644 --- a/common/fake_test_node/CMakeLists.txt +++ b/common/fake_test_node/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(fake_test_node SHARED src/fake_test_node.cpp) if(BUILD_TESTING) - ament_add_gtest(test_fake_test_node + ament_add_ros_isolated_gtest(test_fake_test_node test/test_fake_test_node.cpp ) add_dependencies(test_fake_test_node fake_test_node) diff --git a/common/fake_test_node/package.xml b/common/fake_test_node/package.xml index 6d337906ff3b7..8e919d719fc6c 100644 --- a/common/fake_test_node/package.xml +++ b/common/fake_test_node/package.xml @@ -11,7 +11,7 @@ autoware_cmake - ament_cmake_gtest + ament_cmake_ros autoware_auto_common rclcpp rclcpp_components diff --git a/common/had_map_utils/package.xml b/common/had_map_utils/package.xml index 2baa56aa12c73..aa7f7a9e78840 100644 --- a/common/had_map_utils/package.xml +++ b/common/had_map_utils/package.xml @@ -23,7 +23,7 @@ lanelet2_io visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/interpolation/CMakeLists.txt b/common/interpolation/CMakeLists.txt index bca79e0f23d98..7afed6fe57c41 100644 --- a/common/interpolation/CMakeLists.txt +++ b/common/interpolation/CMakeLists.txt @@ -13,7 +13,7 @@ ament_auto_add_library(interpolation SHARED if(BUILD_TESTING) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_interpolation ${test_files}) + ament_add_ros_isolated_gtest(test_interpolation ${test_files}) target_link_libraries(test_interpolation interpolation diff --git a/common/interpolation/package.xml b/common/interpolation/package.xml index 213616b007a19..665e26bab9a0a 100644 --- a/common/interpolation/package.xml +++ b/common/interpolation/package.xml @@ -14,7 +14,7 @@ tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/motion_testing/CMakeLists.txt b/common/motion_testing/CMakeLists.txt index 4e7006978ab22..f8428c0df709c 100644 --- a/common/motion_testing/CMakeLists.txt +++ b/common/motion_testing/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/motion_testing/motion_testing.cpp) if(BUILD_TESTING) - ament_add_gtest(motion_testing_unit_tests + ament_add_ros_isolated_gtest(motion_testing_unit_tests test/gtest_main.cpp test/constant_trajectory.cpp test/trajectory_checks.cpp) diff --git a/common/motion_testing/package.xml b/common/motion_testing/package.xml index 33e7b4798d0e7..f292a7e5bb54b 100644 --- a/common/motion_testing/package.xml +++ b/common/motion_testing/package.xml @@ -19,7 +19,7 @@ autoware_auto_planning_msgs autoware_auto_vehicle_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/osqp_interface/CMakeLists.txt b/common/osqp_interface/CMakeLists.txt index 4180461cc261c..996f8b6153cf0 100644 --- a/common/osqp_interface/CMakeLists.txt +++ b/common/osqp_interface/CMakeLists.txt @@ -49,7 +49,7 @@ if(BUILD_TESTING) test/test_csc_matrix_conv.cpp ) set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) endif() diff --git a/common/osqp_interface/package.xml b/common/osqp_interface/package.xml index f89810ddda953..5260a3f2b07c0 100644 --- a/common/osqp_interface/package.xml +++ b/common/osqp_interface/package.xml @@ -17,7 +17,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/common/signal_processing/CMakeLists.txt b/common/signal_processing/CMakeLists.txt index e93023e703eb7..93cb7aa225a08 100644 --- a/common/signal_processing/CMakeLists.txt +++ b/common/signal_processing/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(lowpass_filter_1d SHARED ) if(BUILD_TESTING) - ament_add_gtest(test_signal_processing + ament_add_ros_isolated_gtest(test_signal_processing test/src/lowpass_filter_1d_test.cpp ) target_link_libraries(test_signal_processing diff --git a/common/signal_processing/package.xml b/common/signal_processing/package.xml index 563715af77248..867f2d05da60e 100644 --- a/common/signal_processing/package.xml +++ b/common/signal_processing/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/tier4_api_utils/CMakeLists.txt b/common/tier4_api_utils/CMakeLists.txt index e65e538fe1df4..4eda0296e520e 100644 --- a/common/tier4_api_utils/CMakeLists.txt +++ b/common/tier4_api_utils/CMakeLists.txt @@ -6,7 +6,7 @@ autoware_package() if(BUILD_TESTING) include_directories(include) - ament_add_gtest(${PROJECT_NAME}_test test/test.cpp) + ament_add_ros_isolated_gtest(${PROJECT_NAME}_test test/test.cpp) ament_target_dependencies(${PROJECT_NAME}_test rclcpp tier4_external_api_msgs) endif() diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 99a03ab92b0ec..a8378b92352ec 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -14,7 +14,7 @@ rclcpp tier4_external_api_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common rclcpp diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index eeca0a2d83630..7ba9c2020a36f 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -12,11 +12,11 @@ ament_auto_add_library(tier4_autoware_utils SHARED ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_tier4_autoware_utils ${test_files}) + ament_add_ros_isolated_gtest(test_tier4_autoware_utils ${test_files}) target_link_libraries(test_tier4_autoware_utils tier4_autoware_utils diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index f1bd523a8eda1..63fd56ae09f86 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -23,7 +23,7 @@ tier4_debug_msgs visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/time_utils/package.xml b/common/time_utils/package.xml index 9b553289e09be..a248e72f125f3 100644 --- a/common/time_utils/package.xml +++ b/common/time_utils/package.xml @@ -12,7 +12,7 @@ autoware_cmake builtin_interfaces - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/vehicle_constants_manager/CMakeLists.txt b/common/vehicle_constants_manager/CMakeLists.txt index eb5f7b27663e3..1e84c5f781d39 100644 --- a/common/vehicle_constants_manager/CMakeLists.txt +++ b/common/vehicle_constants_manager/CMakeLists.txt @@ -18,7 +18,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED # if(BUILD_TESTING) # set(TEST_SOURCES test/test_vehicle_constants_manager.cpp) # set(TEST_VEHICLE_CONSTANTS_MANAGER_EXE test_vehicle_constants_manager) -# ament_add_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) +# ament_add_ros_isolated_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) # target_link_libraries(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${PROJECT_NAME}) # endif() diff --git a/common/vehicle_constants_manager/package.xml b/common/vehicle_constants_manager/package.xml index eecb3e8f2108f..8041ae90a2cb7 100644 --- a/common/vehicle_constants_manager/package.xml +++ b/common/vehicle_constants_manager/package.xml @@ -15,7 +15,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_cmake diff --git a/control/trajectory_follower/CMakeLists.txt b/control/trajectory_follower/CMakeLists.txt index 5c29617296780..67d157df835de 100644 --- a/control/trajectory_follower/CMakeLists.txt +++ b/control/trajectory_follower/CMakeLists.txt @@ -72,7 +72,7 @@ if(BUILD_TESTING) test/test_lowpass_filter.cpp ) set(TEST_LATERAL_CONTROLLER_EXE test_lateral_controller) - ament_add_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) target_link_libraries(${TEST_LATERAL_CONTROLLER_EXE} ${LATERAL_CONTROLLER_LIB}) set(TEST_LON_SOURCES @@ -82,7 +82,7 @@ if(BUILD_TESTING) test/test_longitudinal_controller_utils.cpp ) set(TEST_LONGITUDINAL_CONTROLLER_EXE test_longitudinal_controller) - ament_add_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) target_link_libraries(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${LONGITUDINAL_CONTROLLER_LIB}) endif() diff --git a/control/trajectory_follower/package.xml b/control/trajectory_follower/package.xml index 4bc005335f4a9..840cad74aeb55 100644 --- a/control/trajectory_follower/package.xml +++ b/control/trajectory_follower/package.xml @@ -28,7 +28,7 @@ tf2 tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 886842aa7f634..309a296acc9db 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(vehicle_cmd_gate_node ) if(BUILD_TESTING) - ament_add_gtest(test_vehicle_cmd_gate + ament_add_ros_isolated_gtest(test_vehicle_cmd_gate test/src/test_main.cpp test/src/test_vehicle_cmd_filter.cpp ) diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index cb30c913ad766..7cb8b18244d18 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -26,7 +26,7 @@ tier4_vehicle_msgs vehicle_info_util - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index fa894c8a7b1a5..3a3edd5338a58 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -13,8 +13,8 @@ ament_auto_add_executable(ekf_localizer ament_target_dependencies(ekf_localizer kalman_filter) # if(BUILD_TESTING) -# find_package(ament_cmake_gtest REQUIRED) -# ament_add_gtest(ekf_localizer-test test/test_ekf_localizer.test +# find_package(ament_cmake_ros REQUIRED) +# ament_add_ros_isolated_gtest(ekf_localizer-test test/test_ekf_localizer.test # test/src/test_ekf_localizer.cpp # src/ekf_localizer.cpp # src/kalman_filter/kalman_filter.cpp diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index c67cfaa400a0d..3e9d9735ae3bd 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -24,7 +24,7 @@ tier4_autoware_utils tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index b4b948c236af4..47fcf3282efea 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -17,7 +17,7 @@ tf2 tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/map/lanelet2_extension/CMakeLists.txt b/map/lanelet2_extension/CMakeLists.txt index d256029e4041a..709c7bdaa6858 100644 --- a/map/lanelet2_extension/CMakeLists.txt +++ b/map/lanelet2_extension/CMakeLists.txt @@ -62,15 +62,15 @@ target_link_libraries(autoware_lanelet2_validation ) if(BUILD_TESTING) - ament_add_gtest(message_conversion-test test/src/test_message_conversion.cpp) + ament_add_ros_isolated_gtest(message_conversion-test test/src/test_message_conversion.cpp) target_link_libraries(message_conversion-test lanelet2_extension_lib) - ament_add_gtest(projector-test test/src/test_projector.cpp) + ament_add_ros_isolated_gtest(projector-test test/src/test_projector.cpp) target_link_libraries(projector-test lanelet2_extension_lib) - ament_add_gtest(query-test test/src/test_query.cpp) + ament_add_ros_isolated_gtest(query-test test/src/test_query.cpp) target_link_libraries(query-test lanelet2_extension_lib) - ament_add_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) + ament_add_ros_isolated_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) target_link_libraries(regulatory_elements-test lanelet2_extension_lib) - ament_add_gtest(utilities-test test/src/test_utilities.cpp) + ament_add_ros_isolated_gtest(utilities-test test/src/test_utilities.cpp) target_link_libraries(utilities-test lanelet2_extension_lib) endif() diff --git a/map/lanelet2_extension/package.xml b/map/lanelet2_extension/package.xml index e817b06f1be86..d46d05a7f3064 100644 --- a/map/lanelet2_extension/package.xml +++ b/map/lanelet2_extension/package.xml @@ -27,7 +27,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/perception/detected_object_feature_remover/package.xml b/perception/detected_object_feature_remover/package.xml index 686c01621c546..b609ff0257f1e 100644 --- a/perception/detected_object_feature_remover/package.xml +++ b/perception/detected_object_feature_remover/package.xml @@ -16,7 +16,7 @@ rclcpp_components tier4_perception_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 47f6f999ecb08..6e9671c166518 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -56,7 +56,7 @@ rclcpp_components_register_node(behavior_velocity_planner if(BUILD_TESTING) # Gtest for utilization - ament_add_gtest(utilization-test + ament_add_ros_isolated_gtest(utilization-test test/src/test_state_machine.cpp test/src/test_arc_lane_util.cpp test/src/test_utilization.cpp @@ -67,7 +67,7 @@ if(BUILD_TESTING) ) # Gtest for occlusion spot - ament_add_gtest(occlusion_spot-test + ament_add_ros_isolated_gtest(occlusion_spot-test test/src/test_occlusion_spot_utils.cpp test/src/test_risk_predictive_braking.cpp test/src/test_grid_utils.cpp diff --git a/planning/behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/package.xml index a1f86fdf19419..16998b4f27f19 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/package.xml @@ -42,7 +42,7 @@ vehicle_info_util visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/costmap_generator/CMakeLists.txt b/planning/costmap_generator/CMakeLists.txt index a2c3f70b2f722..648d01ee4c4e4 100644 --- a/planning/costmap_generator/CMakeLists.txt +++ b/planning/costmap_generator/CMakeLists.txt @@ -46,7 +46,7 @@ rclcpp_components_register_node(costmap_generator_node ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) endif() ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/planning/costmap_generator/package.xml b/planning/costmap_generator/package.xml index 289e2be0197cb..070c160d3aa05 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/costmap_generator/package.xml @@ -29,7 +29,7 @@ tf2_ros tier4_planning_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/freespace_planning_algorithms/CMakeLists.txt b/planning/freespace_planning_algorithms/CMakeLists.txt index 093eaffa23bae..a08e89143ef3c 100644 --- a/planning/freespace_planning_algorithms/CMakeLists.txt +++ b/planning/freespace_planning_algorithms/CMakeLists.txt @@ -18,8 +18,8 @@ target_link_libraries(freespace_planning_algorithms ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) - ament_add_gtest(freespace_planning_algorithms-test + find_package(ament_cmake_ros REQUIRED) + ament_add_ros_isolated_gtest(freespace_planning_algorithms-test test/src/test_freespace_planning_algorithms.cpp ) target_link_libraries(freespace_planning_algorithms-test diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml index 72fc9d5a0dc45..db0ea35e9bb03 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/freespace_planning_algorithms/package.xml @@ -21,7 +21,7 @@ tf2_geometry_msgs tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_error_monitor/CMakeLists.txt b/planning/planning_error_monitor/CMakeLists.txt index 8bd30ea1fd005..66932c63e8990 100644 --- a/planning/planning_error_monitor/CMakeLists.txt +++ b/planning/planning_error_monitor/CMakeLists.txt @@ -23,7 +23,7 @@ rclcpp_components_register_node(invalid_trajectory_publisher_node ) if(BUILD_TESTING) - ament_add_gtest(test_planning_error_monitor + ament_add_ros_isolated_gtest(test_planning_error_monitor test/src/test_main.cpp test/src/test_planning_error_monitor_functions.cpp test/src/test_planning_error_monitor_helper.hpp diff --git a/planning/planning_error_monitor/package.xml b/planning/planning_error_monitor/package.xml index b70e2f319cd01..e667c81790875 100644 --- a/planning/planning_error_monitor/package.xml +++ b/planning/planning_error_monitor/package.xml @@ -21,7 +21,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_evaluator/CMakeLists.txt b/planning/planning_evaluator/CMakeLists.txt index 6641d08cc52a5..6865f8eef7005 100644 --- a/planning/planning_evaluator/CMakeLists.txt +++ b/planning/planning_evaluator/CMakeLists.txt @@ -26,7 +26,7 @@ rclcpp_components_register_node(${PROJECT_NAME}_node ) if(BUILD_TESTING) - ament_add_gtest(test_${PROJECT_NAME} + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_planning_evaluator_node.cpp ) target_link_libraries(test_${PROJECT_NAME} diff --git a/planning/planning_evaluator/package.xml b/planning/planning_evaluator/package.xml index f7e1d5c3480dd..8681543485c21 100644 --- a/planning/planning_evaluator/package.xml +++ b/planning/planning_evaluator/package.xml @@ -23,7 +23,7 @@ tf2_ros tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/dummy_perception_publisher/CMakeLists.txt b/simulator/dummy_perception_publisher/CMakeLists.txt index 85347b04b3be6..63d07faf0634c 100644 --- a/simulator/dummy_perception_publisher/CMakeLists.txt +++ b/simulator/dummy_perception_publisher/CMakeLists.txt @@ -74,7 +74,7 @@ ament_auto_add_executable(empty_objects_publisher ) if(BUILD_TESTING) - ament_add_gtest(signed_distance_function-test + ament_add_ros_isolated_gtest(signed_distance_function-test test/src/test_signed_distance_function.cpp ) target_link_libraries(signed_distance_function-test diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index e7ce4dc99c433..1635deda40a4b 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -14,6 +14,7 @@ rosidl_default_runtime + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/fault_injection/CMakeLists.txt b/simulator/fault_injection/CMakeLists.txt index 7cd78e35aadd2..0bc1663412960 100644 --- a/simulator/fault_injection/CMakeLists.txt +++ b/simulator/fault_injection/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(fault_injection_node_component if(BUILD_TESTING) # gtest - ament_add_gtest(test_fault_injection_node_component + ament_add_ros_isolated_gtest(test_fault_injection_node_component test/src/main.cpp test/src/test_diagnostic_storage.cpp ) diff --git a/simulator/fault_injection/package.xml b/simulator/fault_injection/package.xml index 961a0af1e5854..95e50e6448807 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/fault_injection/package.xml @@ -19,7 +19,7 @@ tier4_autoware_utils tier4_simulation_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common launch diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index d62a84e7d7b6f..6034697304059 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -28,7 +28,7 @@ rclcpp_components_register_node(${PROJECT_NAME} ) if(BUILD_TESTING) - ament_add_gtest(test_simple_planning_simulator + ament_add_ros_isolated_gtest(test_simple_planning_simulator test/test_simple_planning_simulator.cpp TIMEOUT 120 ) diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 761aef0e322f2..2c63c861039ed 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -31,7 +31,7 @@ launch_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/system/system_monitor/CMakeLists.txt b/system/system_monitor/CMakeLists.txt index 017e08393baae..65e933d072046 100644 --- a/system/system_monitor/CMakeLists.txt +++ b/system/system_monitor/CMakeLists.txt @@ -180,7 +180,7 @@ rclcpp_components_register_node(gpu_monitor_lib # TODO(yunus.caliskan): Port the tests to ROS2, robustify the tests. if(BUILD_TESTING) - # ament_add_gtest(test_cpu_monitor + # ament_add_ros_isolated_gtest(test_cpu_monitor # test/src/cpu_monitor/test_${CMAKE_CPU_PLATFORM}_cpu_monitor.cpp # ${CPU_MONITOR_SOURCE} # ) @@ -196,7 +196,7 @@ if(BUILD_TESTING) # target_link_libraries(test_cpu_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_hdd_monitor + # ament_add_ros_isolated_gtest(test_hdd_monitor # test/src/hdd_monitor/test_hdd_monitor.cpp # src/hdd_monitor/hdd_monitor.cpp # ) @@ -213,7 +213,7 @@ if(BUILD_TESTING) # target_link_libraries(test_hdd_monitor ${Boost_LIBRARIES} ${LIBRARIES} # ) - # ament_add_gtest(test_mem_monitor + # ament_add_ros_isolated_gtest(test_mem_monitor # test/src/mem_monitor/test_mem_monitor.cpp # src/mem_monitor/mem_monitor.cpp # ) @@ -229,7 +229,7 @@ if(BUILD_TESTING) # target_link_libraries(test_mem_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_net_monitor + # ament_add_ros_isolated_gtest(test_net_monitor # test/src/net_monitor/test_net_monitor.cpp # src/net_monitor/net_monitor.cpp # src/net_monitor/nl80211.cpp @@ -246,7 +246,7 @@ if(BUILD_TESTING) # target_link_libraries(test_net_monitor ${Boost_LIBRARIES} ${NL_LIBS} ${LIBRARIES}) - # ament_add_gtest(test_ntp_monitor + # ament_add_ros_isolated_gtest(test_ntp_monitor # test/src/ntp_monitor/test_ntp_monitor.cpp # src/ntp_monitor/ntp_monitor.cpp # ) @@ -262,7 +262,7 @@ if(BUILD_TESTING) # target_link_libraries(test_ntp_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_process_monitor + # ament_add_ros_isolated_gtest(test_process_monitor # test/src/process_monitor/test_process_monitor.cpp # src/process_monitor/process_monitor.cpp # ) @@ -278,7 +278,7 @@ if(BUILD_TESTING) # target_link_libraries(test_process_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_gpu_monitor + # ament_add_ros_isolated_gtest(test_gpu_monitor # test/src/gpu_monitor/test_${CMAKE_GPU_PLATFORM}_gpu_monitor.cpp # ${GPU_MONITOR_SOURCE} # ) diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index 8cca9d2c71545..559dc9c072592 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -23,7 +23,7 @@ chrony sysstat - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index d85b418d6fcbe..36b96a2a300c5 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -28,7 +28,7 @@ if(BUILD_TESTING) test/test_raw_vehicle_cmd_converter.cpp ) set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_raw_vehicle_cmd_converter) - ament_add_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter raw_vehicle_cmd_converter_node_component) endif() diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index b14b00c9d3963..4f36c95e5d82d 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -26,7 +26,7 @@ rclpy - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common From 0786fa1a9bc3d0f1abfe242059f301d64893efd3 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 10 May 2022 00:06:41 +0900 Subject: [PATCH 016/223] docs(virtual traffic light): add documentation (#245) * doc(behavior_velocity): add graph and fix link * doc(behavior_velocity): update virtual traffic light doc Signed-off-by: tanaka3 * doc(behavior_velocity): minor fix Signed-off-by: tanaka3 * doc : mediate to coordinate Signed-off-by: tanaka3 * doc: minor update Signed-off-by: tanaka3 * doc: fix pre-commit * doc: update docs Signed-off-by: tanaka3 * apply suggestion * doc: to intersection-coordination Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- planning/behavior_velocity_planner/README.md | 3 + ...iorVelocityPlanner-Architecture.drawio.svg | 1663 +++++++++++++++++ .../V2X_support_traffic_light.png | Bin 0 -> 91648 bytes .../intersection-coordination.png | Bin 0 -> 161821 bytes .../virtual-traffic-light-design.md | 267 +++ 5 files changed, 1933 insertions(+) create mode 100644 planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/intersection-coordination.png create mode 100644 planning/behavior_velocity_planner/virtual-traffic-light-design.md diff --git a/planning/behavior_velocity_planner/README.md b/planning/behavior_velocity_planner/README.md index a7feea30a3017..20ad38140d330 100644 --- a/planning/behavior_velocity_planner/README.md +++ b/planning/behavior_velocity_planner/README.md @@ -5,12 +5,15 @@ `behavior_velocity_planner` is a planner that adjust velocity based on the traffic rules. It consists of several modules. Please refer to the links listed below for detail on each module. +![Architecture](./docs/BehaviorVelocityPlanner-Architecture.drawio.svg) + - [Blind Spot](blind-spot-design.md) - [Crosswalk](crosswalk-design.md) - [Detection Area](detection-area-design.md) - [Intersection](intersection-design.md) - [MergeFromPrivate](merge-from-private-design.md) - [Stop Line](stop-line-design.md) +- [Virtual Traffic Light](virtual-traffic-light-design.md) - [Traffic Light](traffic-light-design.md) - [Occlusion Spot](occlusion-spot-design.md) - [No Stopping Area](no-stopping-area-design.md) diff --git a/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg new file mode 100644 index 0000000000000..4d2808a5be41a --- /dev/null +++ b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg @@ -0,0 +1,1663 @@ + + + + + + + + +
+
+
+ /perception/occupancy_grid_map/map +
+
+
+
+ + /per... + +
+
+ + + + + + Blind Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Turn RIght +
+
+
+
+ + Turn RIght + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Turn Left +
+
+
+
+ + Turn Left + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + Occlusion Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Private Area +
+
+
+
+ + Private Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Public Area +
+
+
+
+ + Public Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + Stopline + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Stopline 1 +
+
+
+
+ + Stopline 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Stoplin 2 +
+
+
+
+ + Stoplin 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + +
+
+
+ + /planning/behavior_planning/path_with_lane_id + +
+
+
+
+ + /pla... + +
+
+ + + + + + Behavior Velocity Planner + + + + + + +
+
+
+ UpdateModuleInstance +
+
+
+
+ + UpdateModuleInstance + +
+
+ + + + +
+
+
+ PlanVelocity +
+
+
+
+ + PlanVelocity + +
+
+ + + + +
+
+
+ RefinePath +
+
+
+
+ + RefinePath + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ + path_with_lane_id + +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ Updated +
+ + path_with_lane_id + +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + Updated + +
+ path_with_lane_id +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ Data +
+
+
+
+ + Data + +
+
+ + + + + +
+
+
+ /tf +
+
+
+
+ + /tf + +
+
+ + + + + +
+
+
+ /perception/object_recognition/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /perception/prediction/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /vehicle/status/twist +
+
+
+
+ + /veh... + +
+
+ + + + + +
+
+
+ /map/semantic +
+
+
+
+ + /map... + +
+
+ + + + +
+
+
+ Planner Data +
+
+
+
+ + Planner Data + +
+
+ + + + + + SceneManagers + + + + + + + + Crosswalk + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Crosswalk 1 +
+
+
+
+ + Crosswalk 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Crosswalk2 +
+
+
+
+ + Crosswalk2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + + Intersection + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Intersection 1 +
+
+
+
+ + Intersection 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Intersection 2 +
+
+
+
+ + Intersection 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Virtual Traffic Light + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Virtual Traffic Light 1 +
+
+
+
+ + Virtual Traffic Light 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Virtual Traffic Light 2 +
+
+
+
+ + Virtual Traffic Light 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Traffic LIght + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Traffic LIght 1 +
+
+
+
+ + Traffic LIght 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Traffic Ligh 2 +
+
+
+
+ + Traffic Ligh 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + No Stopping Area + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ No Stopping Area1 +
+
+
+
+ + No Stopping Area1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ No Stopping Area2 +
+
+
+
+ + No Stopping Area2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + /planning/behavior_planning/path + +
+
+
+
+ + /pla... + +
+
+ + + + +
+ + + + + Viewer does not support full SVG 1.1 + + + +
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png b/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png new file mode 100644 index 0000000000000000000000000000000000000000..19240ca64224200e0b4b5791465ccf563f3fd50b GIT binary patch literal 91648 zcmeGDS6GwH_XdpOYe7-KMi+P$=~AQgfB(~cwD-Zju5S*KdD=YBnl-c5z1G|lqo=D*O~p(_K|w*S@%)(q z1;y0~3X043u3sacQP({ukpHguDr+9d&w@9^5)HjXc6bO!)dS>iQgMxu4pecJqe+Hor~ z%}F*tqoN#R1Cp12mChH(ztzwaj;8Plk(~)@l-@a2Nx8YS^5M2;sJvtP`kM{QRbMP? z7MjpL%bxe`+c%|4e?Odp;l6QXW#?`I;QuaIKLSzyul`l*J?{Tb z2gT^I{$E|_4)pT>>c2Ua{r~TD>$7s2|J7fo{lAU>f1z9YBI?PyNKd@B)I3_<&*tKt z-|_Q}^-K{VXgsu=qoF#Hp7QFCP09VDD}P^>?)gVwLcyT0-K3B5zBv0>i-Fwvjw=~O z{zu+0gHW~hqTcoK0$%|ztVRox6D4_cglhd!Jf5y<&f+$Lk?FEuwkbBVQ}9*laA9gZ z>Fh0@K{%MRNVVAg^QZk6RgXF;D6|L1;6?0~!=CEZ;GQGjp|5Lm2Yu&h=AclylhOmizfcndu=BxO?Qf5YkZQ!HD-Nxu4o zzW^Yhz{<;N4=u`a7b17l!kXk=A~Mui-9cmia)O;L#`quwy=FWw0|5-npJk{{cLpkqy_uZ9 zFTk@x0||GEsgx8yx6a{#jT#c7a1&pgNvi;ufoG!Vy?wQ68q!u=faJheXjmsAu#0b5 z*Kc3|kf=-AeH#D(_u71)1KOft_nMDlm2ufDV6L=?!3x@% zx_R`|+C4e_c0o!Vp_bOjgNQ(^W4D|=XfhV4rl$|8#&$45+D-gDx-Y?)EaahI8x4}I zhmF^kCSarB5)(*THsDC3ZIa7^5Zhr^>74hJ{_uwWw|7s$hk^0X2j*5l!=iu)=BmP$ zHsIS#q4D)#yZo(tWoO+ZinUmM>@Tb>s;hNS=FsGzPDa}%fN|)Kh4_%M0*@hH_ zgL@duPk9|2D(m6qm7rJ+$Bs*c##1BwCP?+2R!IVlS&@#-GX20qPgc0|c*P*B8oIGT zu=M|aMN<8*t@-M1@oLur7?`G;<25qET&CO9L-on&v$XO?5sQNtGjxY&slVQB?V+1# z9^_NsQ=zG1an;xIJsT@WzE^vY{#*kR+C0}!7XtRjCGTT?c}^5~srLhnzpydEY#vJ^ zcjH2Mr1sawZ3J;^tgsXoT({GK6rmMc;n-DO$q&ac_5O@ZzlNO9Jpbx1H?DJf(gqIu zh-NCTW5|I@grXmFRSidk`_{azB6SV{N6`FuO8bk}i5=_`Y$@cP|IxW>SAV~W(ziF} ztPct%yzgML0gG9}fz;q79Lq5*clPS9kVvk!WiBDRxFlY^jPC)!yL$)r={jE5O15W}!dEHZrvp-nOrA-{xs)3c zqr1M@9_%fHNp5yl3fJVrKV~e#Z3gREpyOf62yenOG}K~QCo1Ka0!TqS*PeZ5FqED* z#3-G{$j_40z%QkpWui;i<@_T$#g36FV*%JIXU~1`X~Bv z3Z*;+NiIZXX!wa_n7$n4%c&25VFbG0NAqM-2K*H-eatf~3MtLQ^P~7@ODe9UcPlw8 z?5z*O5b?vUe*`$Xw!e9{87;C!96zQ0VZD*krT5tjsmA94x;?hi3<0gs<;Q&LduP{93F}x zHmvLhJ!+g6skiYa1P7I!Erv=2Bwt2Q z%J1KY+A{G*+xYksG!Ps01q;mJHFg-(Q&`VU=m&4?2jsZoj2+agGr^SO95xy6NXXH< z&;yw#n8wjZ8_!JMl<8Ppc)>NRjc`3P1!Hq&A{s+M6(>Rv)Y%f|-t};lRY)FDkOg@` zDdZNo8_de=3bAbqf#}NJ=ISfLVI146L(J+W8XlO)sw~os<36aGxA??JSm-2!E@;XR zXd@V%q(;NgU}XT39FIgE%~Nv#ra<;;D{#%C$-PRE~>gSQSUBS zO-iuJZI4&1cp3#Bz@|k1JwD+D>whv`-Nz&ppWcH23Lh{K-IM zKlBw5+GJy(_x|I#cjRQaw^HABBK9B6BzN|l5maK74L8>ud~{q@vg5O;E7i2zq#?H) zmQQXDYDjGbZJZJHJAbZp=~8V}Mhdf?@d}g&E)IP4X~Pxb1J$XjIiDOWJ?rwA^)hyA zn{2oCI_fUpC@9ju2r9HD7PvieKBh9NirIPD&1NKH?zd2=wG8*n=~(#O&yjJNbpIZ6 zjQJqKVgbg*Hiq<-^%{DUkI7KRwCcd@pdTxb)O3F{-^_nb=%+^ zX}$ig4RF*eL|7vug|o-h&Hg)yI<+Bc?W?OdM0dpA^uk9I1#vbC+Xnm8$&)lcCb0Y= zfmxdb556<44-#dw6*(~v>t+iVeDc%Dj>WLp7@r~CsbC|eklbAkAoierJ+FTqVhb_NX#UeRAA^NWgFb`^B z1uz%yXz;aU^}vwcs6?B4o#i@j`E7v8EXrIh4n{{A+desdb~~f7zQ_1!u~o%F!PUrN zyIg?~vh*sTZ+>$$2IsgepI+X^zj`|JUjP#1W&0ktueX4@UXsmPHCP#dSa-)gg0nTu z9e)Zhn>`u5U3?^DK>S$acuCAg$7iDqY16>hu=_T_8deyH z#5v_XTf?6+^m%U;QdwM!VxYY>Hb}`)cH#IuB8}>z1#`NCY_N#dji?gMxd8}`_*Hpr zqpDsDV~*j>Vo1hGG>GwD1d_n(GW;p)1M}{}ixie2AH78iRVHNL(7V??wS zuJq>8$EI^{d2@QHsYnTipc*Wi0YCg^&PK05vR`vFU!6GQimaI~vYSgt^*`9!*&nMN zrm%`gFNFcCHs)@$f21LdHQvE}eVy4X*VX$6rF?6TS|-^Ov%rML#m=i9_3_z;FD+H3 zGq4!AiAXB1L;ZHP4y8$5efz53I;4;O!Kb2j{orkXp5sz(92;nPYRLchSXE7)vGCpj zZf)H)LnTQq+~&!T|8UG}*!2k~Ez|ctcFYbPV)sS-0RDyRG;nJX?_Wz$--PSJ1Kyv( ze&*9K3m9649yti^i=5r6bzVga0FK*z*GQM4l|JRdB9?S{j9p9$a1zF6IVz!{ zu!8v$en_0-G9h0T(+V)(NQ-oF_>eb_=2!1`V1>Dk7L>XzXR%EUO}YkxYKekb-9E-n zY3@l&i)AUxpHWD`NnH0OD%`eVPMt~#gE_(2aPHOfiK)`ObFVK+>}Ddt)n~JwQ((?M zlS#(d_PiG(=&s9jD>CIYCJiW7IKZzaq_K8xaq`<T*+lao^s_U23ZNYZX-8Vhnr@%CkysmGjsyoS|lfS-g!=$N1rz&R#)DMO}R_| zFBzQ~?@X|WYNf#rE*NJGE#OPEmgqwxTv*@+;jx#>nRI6sKJ_sHw?_F#>QBNRx*v_} z#kFB7q{q}hmT{vMH`73-%Latu!U2C9*VU$O$*n9Y*zCCidJyVKcaD~3ZIoE|{-oMr zs-U~Uq_HPO7_Yer7*ROD)IRHFizU32kM1LgNgCdrV00!b5Q zgE*+@o!~qj2p@dWkPr?y=y<1+lEql@^Ve;Gn|t~|VD+E`Vtv@D>(qp784tYc+S#3? z25;_W{tZW8TrW7OyfI#MqW}}OZvJDqY&4SwZ&@4k_Atl~Iw}4rJ6!CWNLzAfKt1jS z{#7-_KC8aD0+?p}MtYhBVPB{jL0A|D$YKFI3fQEFS44$kCbn9f{?%?8g}y^Z$zT2E z*!C%-+}$o{+iTPnrU8TBL7k1QqAuLadrx2F%>u?M;r*rDXIZuR!uYd*xAor{yBw46 z7Ih*dykpvJf|ZWxx+LW+)0qA9B{YR9cOGREZ|JRD<|lMo6`5n-3mKsHoIR|K%DB&m zAD<$vg1Rf(^8B3f@9d0r4$1RG$jJ5jcv0GH0s105=5G8P-RIcP>gcmW^-T; zJ7$ipfy%>Q^E4urf1uy1V2!ipq+8Ms88CSGBiB0FBM=z&j%J+YAHohJYq))eftuw@ za@^XL5*Cp@*<(50lMIKlr4(P9l5Z)lJ2d5v&~&U12KfC34xqiRKM&VzQP5XC6l4w# zzZS(ieYbQI;(<9nHD_hzYY3b`Zyd+o0oxv*;V&;9jTgMr?Hc1cf5>-4)bvPXnNs6_ zDx&SS&3w}SB`|K}TEEPQ*0$bAL#i|3gD>whSehv!T(xK~!bHKZP8a9mHg?0QlIn@! z>65>xZY6n|KPS`f=j3$<=1!{KG~FpK-0bk;cuRbgBIozQ&62U;>mmLJKmx!Y-Z?&0 zEMODc+BYn(m=Vze%IHbyXIwiH8YOxK>6^*X!L6Wc?BN-Wk38-3<&|HLwtG%EcFl!g zWLjO@MC?MfF?)wam;E^u;JVfoX~}W%lCpfH%I;yi2-$Yc<17f+#V_CUg>|iVb+Kxk z^VNm&wqnDgQ(i4x1q}U0E6SK=zJ~9FSgwfu!L66!5_8gR&{gkW?{*=5DCNZ{USD1U zma|*;U?>l%!%k2~aceD=5o{~~e0uE2!IFN^Z6{M3vb|wl6jCq|%kvt4*d+zO(N7p% zQ^fL!DTj2>!Im~w>(onDdox1)<;ftOFw{)FPk)6+2H&F?_G@B0ws68QOXv}gYlZa% zk^Iz7pjKRNg5;U^F#KcbwDaKK`2VX1o~T*AlBpOwDI|L3kx4dSL^ynCVrF%P z_ho&}top+KOF5*aw*f4C*7vq+UA2zx8`C|g$Sce2y}lR*@u@b-DnlY>zlsXKEd2TP zt42VAO?vHiEzg*1`$^ps(^x0bdsL!si^X`oP>9c*fdh*{ZLVY4ES~LxHR*BQ3%HGR z@VwWNLrk7k8+b!Gx&V0k zX!#h5sjEAz zHK*HpQsfP>uUO|3FKKrT3w6$|(i2lm>|uFVdub|5jgv@9^B+C>{;XV;WwG^) z??$X~mG|sxnlxRj+)(Y2{rN_18KDLlVa1Ve=!nMnYee!lg!gvlN{N6u?PDIw3>HREp>4v8)ZGpmD^aO@Af z>$ZGO-HFnf|ClrkvJ5tT|DjjS{Q${TrKi6T7l-2)%ikC5VpYylEKwVJqap9rxOL;d zbaexzGGS_^?)enIHs6{3TFvn+O`FB4{z`caH>-^lwa3j+NUE@$(MLIWJmw^t%ZT~3 z{KD$3kJm%OmP-X1sNkPy=Dl6+z4kT77Sra=r3^}zD4VPJcyX@G9fdJF@C#V`t(#J;-^uPPuuz3k(6sPPEY;eXj@TztI*Mc+0t1Iy*r)s#m}Tz<1>f+{NI@A(RN-tYPHAD6%C7H(Vdf;PT>%=L_?TR3C3!hE&7?_h>c zygq!F)@bXa%XNt502l{qb4OGC8}<)`6#oow3BGx$tW1mY;#Z-jijm8wj(IVb&9MRn zGkkb&x(y`P4+oD2@v+s8IdWE@A=`C{(@^nr6BGH1yU%@>4_K zL!eV+c^*BBS3~eMwJQj@B4{oHrOqTeI7Lw*<5q8JLtrj(F5vOWkCaBz zm1{}n`YK&&m{zc2BQOfxv&s96=J_klk>+mRvagb9@n1OUC(h_EUcUhXF74Q-3`(?3 zNVGN{CtQc;xYq5v0j3W?87d_vQP!tdc=q2sYy0$y-O@k z3Ugfgk^1;fqTA22LGdjwNX{g z`gD708of{R2UX`w*&-JrQ=9eaGHO=#@(t5ESO2q0^vVS3hl+_@?_IY!(GygJbKSP( zHN${~398>X^D;h4>i(X&m%u%KUA*9_GB==_)CqJmG{Hr-c-DkHCns0Ur#!A}kPt+- zKt35+Jva6b!+i<}YUJ4`s6yb{*F9mprHJpmp5Ak^eZOf)3`;r*F~W}XS{O#VQw!#} z;#=egb7{%~E@t7)$Urxz8QB|?A*bWE*GqNI#~RrwWt(T5g7B*{FZcTYjbOj(B6Vwf zov>DlX*dY7&(0G2IkyqD$*8h_48V(D!L4xCfS0$^_#D)>Oa~HJ2Bn8ydse3^$%`Zg zf$htENCBAtWd8XurDfpG%CdeGZvWDhYqrVdwQrs|N1bx5FUrlDyc=Hq0?YX2R~koK zqM?1H6e99jTgrVOH>1UOSaKv?`uU!z;2&65W!#^xq-l3mG8Bu@L}PKS)oYYVV_ea&LVL()FvITT1b1 zlmcbswfG<_d~;#eeB-7BLUIox?suuA!=}l)?X<})DB>jAWpz%VQqd~uEq%N!WmbzL zG-BLxxh!3^=Smwep~{Tq)?bx2$SD(=I_D~99J;BdOs@T9al`1 z5u>j%rOaEzdrAQH=knr#L~GLeR#q84Din!%d9?Rn(@52K?kM&z5_!#}S}yN&#OG1s zAoZT;S8-5iLCoxjw$r~lNl(f7;_M1z_uE)w7j*U-L*BKw;hbZwHrb+WK^luBExC?w ziAKeMmSHI&X>R*#bkWantGpZv)hF31kpg4FeU4tRdNz`2pO+;`<2Y=8setUHGmP!} zv%;kT>haxZU~GIa0V0nK(jS-=P4@Ky13>0p*T>J4Q|QI5(rVSq+Si!x{3`n%2Uz`Q zz?{XSm1(5ZF0EBID#ruhYAG>ZiH!BKZETPM=2=RHRZ*9Bk&NUXiRirTOmSoipBh^j z*Qhq{r2Ro$^*vd+2wcGpSuhv@h9pRtYn%m|t+Tu?iuJJ`vshC`#`H4Dzv+95^p@)r zt4V9m9a!!9$$RM1qN1f>V~sLdI4T`9)C){7U-ta`$EXvaVrk#kH-c zFk_(VPNDcVo6dtZYJAi`2hN3NBWN@hra~7F%{^cwR*cU+&a!Pvf#{pd-4mEl*I8Q2 z<@N~k%*@OC+2cDoRq{~-P;`Khz%}g`(P!?T_7)TPZvn@H00*NsLO?cp8*f~>-BBwo z6|E5}G)Lp{BjpU+E};-X@pVP4Jp=ajCIk*mzu9{j(8TpOhtqIX*awVYkSblY2eqv9|tIxp^1O8S>)8FqfDPlart|ETzf z0^N%0Lx*LRzRYq@N3RmbRl8QB)o|+}p58t)yH`%)8*M@8$u?n_KS>$FY%Apyl7l&2 zl@On~Bz*LLT!6&jaGD?9BL%IsJ^H>(w@`A_w6Q-CYeqFFYSwUkdDX-u^hSc4R~k+D z@8Ot@n@28qE5l=&91e0X9K-eyMlnkLE~I>;!x9SPg6vTW%3_O^?JH9 z6h3u|LyT{*&$)q?^*ryig+|U=FY0`d7N0zNRg$yLra!>1u}3>`vMedXRH9D&xQ{WH zdjNeVREK+E{=U$wUh`Gur`95~mW$D+3u-ERSYwZ-hv{tHtX!$-)vk~E$)oP`YU(FT4NR9h%znQcAm_j|OuH@2 z`*W-e5b5kOE~dK$aQg>&E?7sEm5sJ|BPBSFlfmnH=puL~9^~hrTT2TDZh$8){Fj-Tp}9W6?Ok7r2j>fF4EV!q32HncCo7Q; zc*T^bo>JF}$30;c7m8(;?kkgI#vLr8K2N+J@TYNTpKm<&K7PL*84tTPjfE9OK+(K* zuiXumNtN5{TT1VVo=I00UHjDmm-R6t4I{gD{x4EG)Tk*y9JzTQ6YRFp(>S)B@{ z!shU|zFF6V$(yulaafw(2SpK0Fr8qdE=lf83v=Y@yGd^}1M6nl3cuvk7#BI1x*X=Z z<-hTrDOxu><4Ediq$(~F;Vk5}bJWKy!lT}xPP`e90T*~Lbdyv-I|8stT|eQ05%BtS z80tc0ap!#NRmF}<8Wr~g&3vD+tAzgyQrj844anhI>pCm*j& zb%>W(Yx*VxM;a+qZ%|!W_VJkXmd)Ez@?&TvG6{ZBK6-xBc^QmIp$IR`@D<#IP zXHn`|7i$l|=JtvSQI2@`^v0G(X)a^cxsTbztb#ImKpB!9yV(*7A>;Xj&OP24#e*9o zsb1KMx(h4VJ#?-!(`GVWxyXIda!je(6_>p5#t%qk^fg9sV?hy!0h7V5Wte_l{^vf?B*nl|ei4Je(}4+b$mC zz#-iNh9)IFP^ERm6Q!%(Z)WjA>jwCBOc>|1*E!F&B804_DvIkPHcGQprjUNCu&-Mk`4i+fH;slXBc)3gNtG@1Qp zetL<@smxaxUOZaec{?x(5!kJbg*5j7Gi+>1H$U~IWncW0k`a*hF^Pc}oWx?F^w5@^ zmXhN;F;B0Ia)4z4#3C&`>b{yxe!r4)6kUS4wZD)j)S(D(lT_*mv9B;5I^aDtx4j*@f%zgG8I|Mj9a&F)RwN5x0dvdxL*yG7|J`_$Y+yHlvZO0PIx4KcoKA^iqengy zl4UCp5FY>#RioWKJf*9G{w!SToSQQ-m8vfmA%lZ|3`7%^Y%xinD+y`j1;tiF?ksYn zSnf0@XO<_ih)L#(?K!0BY(UCqF+|4zW@fyqK@hP4>Zi-WZzjWRsP+z%r5`_s6)8iS z9%*i*WqO9s7}7CUFtAaBa5gOdh<1zB>Y(w()v~ou|CXoqaPzM?!x_0<>i3JDZ>9@k~)tm26sUpo0`y;|0t-mVKLoyC-f&KGr zdWoTQZ9ICgqMs;BrXqs(8!8-=SrOZkWb8%ij4t}|pGomTX`kuAgKWwHzc*K%cWMI| z^3VnRD%Ar|`39^@zq^jRtqY_aXFSo78{!gA}i?z9rM%UI!PJk&*(=D?FSFCpCha z{nqLd=9|PrwZUsN|D(To(*0r3?JGIK!oho5tfWfgET9A`+~KW*oG0YGMlEu1-sWoe zGd`Kn9`zf4TK@XB_gM)A#m~zV$N@fl`$-2YfpF5>FrC80UP0(*;1_?QxT4rMfuEd; z3SgB(7aE|y?qrcv5G1c6hn$>(zo7j~{%tZ5Pnh;`mG1CO)(J4K_0&}>&6>PON-`+P z3zyzyA(35Py@5q%uoU%Qan`>^*pi=MKf1yvif7Ato;Zoo+de;*uy}$Y{lH?{WM4#4 z{$>At#lO=e6Z=-EZ8*71jZ(gV60VhL3X!ArSPOrXlZkPed^Q^e)#xiO{`TdQf{DXm zw+}z-V6x)BSH1e7KOL&{Vm&iZ=FW2z@_bka5Cx~C5qb!joCl3l; zNE`T>QBIx29|b&l^&g|NGDRyHP2swk z_}aGJ?0Sb1zU@!GJqlH>UeLFT4HZ9Q6_L2PF*{wTged%eDeTs7dQ@xX&*n zue)Jg)znAZ+ym!m`t~uT*8Su5;R=T*K}y=FR?ddgMF_WJ$Sb0AO2IvBTI`QbjMm`2 z2sJ%5zR!D+Au@2rL>_;yr>XxEQXOAg#778Dp2Ig%+~Z9q>w1k|!jkGDRurUN>~am5 z6E}YJ^%)TO=-83`Te~`_>pAmEkv+WrI#CA3KOL_gnwD-$H37FqX)L0Ma#;`i4`>g# z%u)zvY@BUPDj~XtRb;yA>vh#X`gpx=Vo}`M8&F=XVAV2P3F_jG#N0on3kz7dwhZ^i z<=7=35abOj7o8RmwuU`FO^mWe4-VX-k*hURiCOCD^^2gQ!nR(z2EuwqhtfQ}oEk&m zNTyMUFpaO1qyN+KJm+I@kzvnlj|8GAM(R=}m6JLbXJynqj4>08%eB!~#-CNHt zR|Wm9!*{k~B86yjY)%;KRR`Gv(Fq*8W8}rQPY7vXU&oWtdEaC3N$wQepJ`1`#rG#Q zDoi>P=u*Nz`9Rvb=Fp_&ch=?&a6O#%I~(BR43kuMDMD#81L<8YjG=c6-_bqD$sgZj zfc5O$i4(%L6+3(*{ z9x^VbJ!T~w3jKy)gY3?(w{&R-U-pQp<&KrqYn7v)^OktT&vErVC6#0KHdEtL)-9P1 z(wLpsR=smo&4l}*=hb`*j<_B4~s+(7OI!1SjmjWo?gt%dv>_%1lqrK=JAb|If#;x$>xUl9eQn}2lvZ)|OQ8t2%(UjJ5yC+Ts@LM*VKsOk?;oYrZQxF&~J0rm<|5SCIcOGS0rxM~*huF4QZ0)GiZaJ^e z`!?NwFgTd95jMYgG51c>=3&YCi|CK-ry+EY!N{)CK@XE|Zu*j~2W14U2*^i;sr=gH zkQ9l+IdD;e`w)8fD2z`bv-+rj#N4r9lR{Li^kMr|!rJTOcNSuDXuAlLL2M+0+MH#o z&gfKNjglI?iS|5%7{BF40TlD%;^HJ`}UsaPDZ9y z9O3oFQCmKA9aH%SIxJ!jF1Hx%v8%cUg{B3_i2<%l@_K~45pj+6KN{kYS27#ge0l|k z4$mowqnv@B*e|4V#P?DeJ;Ueo~=nre6f*Q&FM62;#&_0`$`!$94*E zAp@;5UcB-&`o(9j+0R%N%8pEEHR1C=>nrx2vk9-YERC*BA@3i^E>5{03x&47wO)v) zb_F#)S)^M&CCf4qAK@O_VM(MjLoqx3Gm?_>xJjYfz^LPKgVl0gdP+T)!)Bz402RAe zs6Krp%!*nd+5HcY_|3`onml{I{^MZKQ%e0YWb;D;dIk0(@^KScd~c)z!bZABb_QD> zMPH^_-@_ZUAqDf*TF=3cO67EUB^Xi*cy?o1!c`#0gc0>_x0wYm@$!N}xSB;m=NzNc z=kSJubVE;Yx7nR;G|UtnH$T!C43NfpYkth?Og+l7 zPcq!9F8wA;{xr|ae|@28V|zxCPCu2=nPWUv?#DEMmful>rvvK`W~TTI7DWm3HY;i}Q#DPYn$P`KrMB1d{(>T1jVJbgR`HrzkN<*rbp~X~rBa`PGdc|1)NLK*PbF$9N$@;{ih;|5-z?QRx#p zd3h*CR?OJDz*C$@cQ6y|HL3LXFQ$VlTL;*Y%*d-%7%Dt#}4JN9bp%ge!BlWf)0P3ur_a0luM zOG<;|rr*Q?Tn=znC)HNRt0H|7@T^``+_e&(L~4k{q(Z7#J3P{7ZB;#n&o4~NGV>~1 zPJ&lm$4yN*r)ySI_J7bA$<+fx*s}h;k$}k$tG@r^z$aBC{EJO@84P4-QUo3A##}sW zuI;%s?ese0qsXW>^ytgWGuPdx-Fz1%kCw$Y4SG1HK}QxXt~h2R-%@S$a{={rmYYT+ zwx-~HdAtU%$v3-T@K(Bx(JItl!K{)5v@id?*yye7+ko5?vsMMbA54tN7HUoMVfOl*#-KfWZthH@2#&` z+kcD?uC_d76A@EB1R8uB5uuacn%vE^=N0F)G6T{>`CJk;t^3E)#YtN}kTxL)+1$ZD zffhx&g#0^lsgt`-KA_k)b&9FSHt3xAmsp3|Z+%B^H8k*?bJMfdZyWZ^F#UmSE7E^q z6~#>E@Dn=s_=#N`)=86*9;}Qw-^qlG=B&A5{vSu<@)ti+{7&U01$FE_7+PPq^W`x1 z3bjikHmtf0(e~zT(*1co)qjy7KuUs z@VA8r{@XpJeRE9mu>43d>0@5rfP`>7;H+Py@z38u`B0SL0$d$^U=L&Rxj= zziifeav#Zwfn-&^Z+sQm%jwqJH^p{aI8VwUA~=h!T}XF+eqQsJUUB9W+g*wmy8mrQ z6XtG&X(2B99+Yr*^U6w@ejB-=X`NieDwI~yBj-AmER*se4Z3nV8eueU_ zJp{JSAUtBHOIZ_F%YS4P$n~N?=d-qS#WM?l)jOxNe%+iNhGwfzXp2isgLl2n4@JB; z#p?pyp$9XUzk!cTW?5roNxX~#pvzxvDH#e1MmzS%ah^A3-7%oL0p(Pzx)PJ|vMd_3n+uc%($I3h!{ zJO2K`hL%aA=;s>xbuwG)!dBA@@@Br{^bjk{4AcB5 zsxf$N3P|rVcdvr)WXl#p0>7ijq3^$*zWg_sdp))MWO7V_FDcxz^yBK7eVlL77SM3= zaMA_M!GxO5t%9N@emv4RT-x|OV#d7fmsRTFJt_X9>4|E^&EINWpzoeDWs59MA@`HC zUBD;EtG7|QMbf_RT%&X4QEI&F?Zs1UePT~}1)o~)TF?FXV1kjXUOR%3L$uwqn9JMY zEeWj#RVmSR5b9oCOqUKW) z?$S@Uzi#ns=Rv}y@ozV|429W} z@h{OvrjlTdGIt@bvE~%1$mpy5vhqgK)3Nqs^tdB4&jIFdNnGZYa*1{)c^a`!mt-T} z!?tUO~OtqO>dH|pyngsH23n+QpexpjzGCrZrHJqaE?e7o6*i^O(vmak6c8fq- za01`=_x7rPV>+#-^j$ps5{M$=1eYr{j4c~&N!(ttj)nkkwGE*$3AZnM3GuntU&P^m zVhTyy!4X?hKn9oIC_m0;ls4E^jdj$iSq-#j-DpeJs+e`E!X%CMrb*{zY0NH5OOGrP zrgbn=THqhu%^R$fn;TN6HaO?0pY3lyx0%Eq$$u7;RHNV*w|^XEC)y`1AqJkZ#uj8# zR^_V9PlDvmib#AczJbyX7Xv>w!m-3hQ*F&R0+HLzz^`3=mHx0G!<~uT#c#B*FGSp3 z2Ot^O8rIC9x&BF@G2RKJa(JM**w+a=1#IEYwVwBnB+UKtoIyL~vS1WEC(ek{%MOf# z{nRZW%P>M~6S&QKLxZjAeTqM37aFE^`Z;T>-*EOaIn>Auds~vt7ffiZlFhBoHjS6d z)c`*#mQ5|AJ~Uf8SZHCVSmFEYb6!+!Al94I4ImMn#neM-<*iTy$TllT=_Q0Hn_9rS z9h`hHVC!Orx-MWiAMvY)HtwaQ^N`yq!lnBezfV6=JE}I9*JOs4iky7WJFW>siO}(1 z>{{`;vDx80%TRe%W!Y&tsGyZEDEUggzBjUFv(u%O?5s?8GQ*a8zfIT3SrYr$fq$EvtHI1pbH&4YQ7RuqRTo zwdjm4s@q%>f!}4V73v>rN6(JP3^`FFpL_S8Z`1N~w&;n|-okIt#u6527wjV>RMr)w ze7b5rSC!+?!KmZIYb6)HpHc2~d=Yq?lv&I2KY6pIcO>(}UxG&88P>WR$ZC( z>tlJMNyNyLllLO87PS8dnV*VO$y60KbU_ZEMQPi~vL+uqk6MtIuk4&lh?q=gJ7Hiw z_isOsAZ{tt!vS*_XJa1eA+?e@HLIyDM8VC56$|2|8K14q30-|@%SZj{`h<@li)Cny zBA?@@ua{!DK+SNki?v49isaW<#Gk*exT5)~{BCi@!qyCxN#-EhwqYin&d3T+4s1zP zVI2oDyR0GyiYi0rpAkCuWNOBWHBcK*l|}9H*thqOLkD@o@)GCRtEukB{?K%c`9Ll| zYKh(a;r+jEH^`qmo=BQh7Oc*s)+~Q8GXMCMUe86?G1&Z8e_dGKgrsF{)lZ~Kc;2$d z4RiJO%&()|U;d8^us5};(LcRV|MFdtXyS$SFCPge;~k`sXK2837frvj$df~2V5Lyi zY%>Ysp0@0=YatiWdTdri+Ua&v>JO4~iMPyYC(WQoo!wI%%t|ERrtS{6XRNZY*1p`h z)qgtLI~kXH?D$>tywg)Ukcf>V;XXh@8Do)38_#VWfwyE`OvReu3AAO2&HTn&d9tY^ zFB@j26MlY}KEZvUL&(5QS5}^~uuYrz8l%BoRBbYKi7@10lgZmuEK~jL@nYNnd^DOh zwWZq)FC)5Kx$k_)R2A;ty)9ZvZWDpc2ooo^y^KGrYXEoX5C%TcwG4Si&K|v735?jR zc`M+_pPREcg}!VYU3Wq>+0*EsTc~N)wYjh#XAT;5nTi;(%gJKvg52RhzS*_V-bmO@ z*^UZ#Y1nLug7%s_$PTS#N%#C>sJ<$2dXg?K9QMIV&WV7S5;*i_p9@tB%|)DvZ=DLw z<^<27{Rnpa?So%BNurC#M_0>KlgDsDUMtB&)J}WfsxG8#hdt5sVHs(1KOz^=dM$M~ zwpd(*1S*l|Z=L)ShqQ+A%aFiTrtBTR>*H(=Ont2fI=(+~()z`mzOMvW&ywe#S;%F) zH+Rdd<}};5H(GRhtoF&qjBSU5Y$jsREY-h6!JTQtla(b^+%@bB7~Vg-Q2$n_%`VKc zQu6wp&k$A73DsxhlG;M854K)^^h<qj@$Wv!j?$%qHXuqVvtO4yC=P~Kp?N)^e=KD!?7 z{J7pMC9!0UB{50%w!KCvSnmSlJ;KKuLq?but>{>fIk?mhpZ-86Fmfz!ufqS7%lPxI=Ut4 z)VyEh)qJRYbGZIk4oC^D=6U}`(uJ*QQmlk@zV9GA5f!WSIG<}?f<0ydp29W)w4%>o| zYU7^%MSRBi@wxn-_*Tea@{N})^gNho8I8?sHoeH7EG{1{k{&mhm|=XwvU3@*OS8|P zhW1MZ+{I2u27;n)>A<;dvJ823Z%5aC*5?nLBA>~^)prNx%Up*z6SX+W8WoBuqzZ++1Y=LO( zv>G)Rz;A1$pS|+Po!Nok5NepV;>d7)5hOd&Usd_^l~~g*DCEtX%csocakB*yathk@ zo16xVN56~1vJz42GjRW348_>8sry_DKSxhPKhEzVNa)B99rrUchI3I{C5w?XtrL^s z?*H6sd}*C=_SN1#=t>uRrM`8S?g7^KR;yHSSvLDag)NS?>dye1?~yXFgqnS`+O*L3 z^~M?om!r^H8^5Hf7;Fbm+xzl^3pxW^oZ5Mq*&l{9E5Dc~7zm37*Q@SWqCU4si3>{R zQo^pTe09ErKAFrA`btsM{iaK-VqEk}{O!K^J8F9q=f~;A5i9=>XI~i=SI})40zra9 zf;$8W9^4b$NgzRj26uP2;O< zs!pA=_wKqZvzTBX{;(a#G{D&;KqS@p*gjy@5Pf6T&) zf~P~&dMFc=OuH4In~Ex2LB6<-jf53iCw(p zC9&%cEFCogz&*;X3)&dF=7S~sV^B>TbS;Z7PE8FWPr$+Co<5pc%dr-9H_@ezPs>L@ zYuEJt=yTGV3Ly@Nzt}RuVRMO0^lGHu<@=hh1adpK>~RmTb|vk};?9pIlpp=ERv)T) zfVI_+g(4UPll%K);X=!%yR+Vqsmbd5Ibz%#eGQ_q#SZ+ zb85Hp?e9|WwGD-2+)Jjzvo@EpX@AjuIC3zjnbzhd{m78`?b8G&V;#9xV+LYDWmt-9 z30+rj_$yXFu<$HtlvOO~T!)7xh+Zdm8*S~hhpKRLD6`expgedL1GAIV?viwL5`<0F zJSlPHs1`XP(NQGSjTwz2kV?&G;0)O{w7>5qv@PeN*Cy-9kD7gX)oh#cLiY8Kqxt>b z^*7-Vr}ZDmK^`-@gz~m)tuE{kC?A2MmW5mb%a@-wjL~uuVZ10zAe6bsXkYO1J1&D)Of6cYZWVy*Zk~WpSz6tLiS~B(U9swr8MWto{4Q-RdxH(*NL^%ua=5^ix??Pa;U>dBvPJ z8?xo)C%#llHO3Al4ntNClxv9XUh+-7S({21_ccn{NIc&s3-JU(es+H^hw_CD)FM|w ziG9~Z-mk5WhoS4&Omau|hxbD_g5RN{;$+2fROCEO_Htr`*W5RHydDYcUgBs8{MH-sP9Kbdd{a7vdM|1% zrmidC*6r5Nz2mBEveggy?e*a~7>_-wM-L%XXp7dPHhNt>>D)uYza_V(z1h@%!j^n5 z-r+pc?L}II#MftP;+vym@=n;PYeTHu_)HO^k%DtnWMfTYwE zn)#C1-5w~IUI=ZY0@Rb;O&V{jhDk`Gdt7{Xq??~zU>|go99(VN;+KDELo1#A;woXY z%0Vh)%#U{<&o0QD&uU6{pW3N5WMgRncu1M6*%H#0R%ju2H}gWJFFZfmn7yfvTu_I# z7fSdp*}!q}T}zw%BeB=3K1~ywn0bN^>p=Ho(tX-CC*QedvlZRJ7&2$vCH9jcR2!*7 zD8QZyrYgfbNk(=S1@_rmDa7$&ulLuUIZ!IBCqDOU^SV~kyX=7)qOCBRDOb7^5Jbl; z3-<}lZqnV>CQn%`2At4#(EBza3jk2v9B#(2+v4tD)PFWZYl@=TEE*6 zd7v&;t3+JAYJU_;X3ZHywANU!|X|fi==tLaf#dP0J*9I!>)*W8n56m@vKW6 z-enm}DXf(M#e>iEc=m=-h0>YaA#KSSUVg2?&AVP^A!8~Z=CWyKwtKCU`X9L^fG00U zH7rzt1>@f8k~2YjZj6dQsl|U~(41HzXXDCdn@E$(##M;#f-9B1jmAgv6w(C|TAkfj zz(!-_eUs}QZ8?{s*;&bxBm)h&78W~;4=lOqn(V_=HwHp97(2EQV2tY~hSnadM~Dvr z#@IAY~b%3m0V9u4wIld4A zng8$Igr*6Lu5&;V<+Y_itiAscsrMo?ZO_^V_sgq~b7{0K7w)C=DCE0FKbR$11}CS*^P^7mJ16G0&CfJOiV%HFF-LT3BQ)<@|U3o@XUj*F=qjTUoDSS!!`XBot>u z1mnzbf-C|lMqxLUw>om{ra{u#A%fZZP5acRQ) z&Js&F&0zOq#H9k8`-b)reGgEw-%CfUa7(&`{TRU3(Qg~pzu<5ViNsl$k_8u1jJJ8c zn(ZOrjo;|6Z&GGMe1Ipc4t}1n9EQEPN&TxW9WeAkxzEG2p(`W&P(ycaY@Q7a;0sSq@`t?CJK?;lZJ&KnRb6OnRm zNWZfHV$JOq)-lVTMucDMMdc*7xfCMwEKmp)Ri6ugrD_up2M4e$E@Lg-=OO40#NC)Y z9@y1h@A0vV>l?&Q)qLJIZ|CV?-R~SCBm=k zeeRs-l)unpb48-Y!Hy+QJo(lv^x>t49NOVmYn1_sB-S(aSAEt< zVm;IdYL@ou;^Kzi%nJXc`yq?>gVdWtEQ{cTkN8h16DaR*9T2ie`c|Wv+$X4$Py~;I z(3@Iel#o`-1yO!%6B@P`@h)BreT`2XJ@11u>2S5u~Y^S5gL`?&l0|BU^of9cGBBmdiNvC5<}5(SlggKf*woF(_O z!L4^I-q1rFDVqP>4prf)2FL67xm9`$l_K{_c>2wLyxWl@je?n)x%Z6ZocnApeXAhK za6A?N-8q1Oa@B6l)VlCy8Od~sBnLXeB;jDDKlsS+J2WZdZ28dF57^DU3H46e#W7a5 zKAHNgI0@*LTCd@&ZxNK9I?TNvStmuYD9{LDZ(ZF#1Z})LXSMKs zlc^GsLv_OM^=j~wt9};21W#;BnB0@zwf0C#&Hi|@$%Tr=)nE4pPWz@3f`N<+Sn z=gJ!~_>{JkX~_8E)}>*iW#z+J8gjsFcw3spyLRuOKJMkRr6Z5l_$hMZnQ~UZ1Hs60 zz-Cd8sZPJ`FKV`Ve3q{PpD?oM4YCfpoqXu#&1Vhq2=Bfm^a--0rKj7uk!_@^)hzCI zo_xr)u$((W8T06*fw>`lMAG3`GG8eIkFA1JpF{Y|E~%DKOZR89X~ra1P}hTbo$6_f z6;mdI7q?g9$4#W1m3FJA^^-TZY+LR_3=t-Kt?jA1Rc6zkLmJA!1|^b)Cc?h^a>2`~ z4~VQ&pDtVkfgdUZ`q^Rfd!i=DzD1En-|l?C^^Bn8ew@rn_lMk0RjsH2XEZwNZX2Ec zG3bFo?K0#?(|jlVvU79vw#gJHzz8jSf78#ya!zmwEgF6DuxUvK30>(&;+Gx)k_R=_z1nelUaq2rZu=ZCch zEAvu&;7^k6`+0drgO?j`ZnGm}T6f<(EIbnnKzWYH#y#B0EUe$og-kve!zv-tJvh7t$5;CJ>>)K#>9->ONlNFqUc#r1SQ-NI5xWLGIriqm`>T_9? zl`P@v>}=|*4?GWY3=5#FZ?@*YE5_A(QS*O)(C?$PH}ze#jT&B~zf`dkWi_TBnJ47Z z8adVdp*GfDdo!j?iMW{vM+>uai)O}vl`*qp(L^`Lf? zL%&=HY16Pu5%N0(u13U5H7q&i25o`FoA($IUi7?X2Lt#y-j8wrQz{?=;J_YzNK}c1VbNwYr(skIs6+;4V;@xJNph|7mhG;C-nS4Lp*YOQ8!^GMZt+++KLbGR}n z?)9T8E^to@v!gj|ZTu~bWd$l+Hmp$BR!Dz%sXh1c-dE4m)COh~5_ws3l6i<-?Hw+Y zJ6&~Y8NBQ;ympPHE~@F~k>}e`59-cB%MznT6LfLlY?*aCwh8QOZ9C730%mm!gXHcm zUdCQYx|%=}Jhoyf4k1#ErJA=PQcGC7Ek@T44^wq+)mo$P31wl)!tzvql*IBSq|K4C7yn`LiCvWdUw9&*g z-^C+W=SFskyRazdp@~;NYS5x!V}`m8NHE!S_7)O}wkQ$EI{Bt-6R`@)%!nIHo!X>)P!41yzld*JmO<}PHe3y0 zipmU4mzgEbfN>%=w0A_GizED(zB}ALC|FZLJ$9`frtMw@bWCci;Oz56V}pphxEA|X zzYhS3tmu9UNy6E}mQ~mKt+MDllO%jcxn~_C zfw$;aJ-gl$A1(v@22$6(`RIF zsS&;hv`7CIV{fhpMoj+Uj?6vgQ4Y%|qAn>q6==T$QKy|tfUOn953YlK?t9dOfMjD~ z&>^Tf#HN4z>XV&LRZ7w1x%Nw(6(NU1+>JF}Z2|N4FuW$se@S}vbIu0d5}%WpY~Qwy zCZL)t3PHylma*<5azW)N`>zJl*#fv`GM{I&y~v@_MDi7&rN+`b(v>zYMNf+hzWX4! z-bOyC+h}wQ`4x6qEH>v?^Wm=-waY0tUg3C1h_uF}7cg1sEY~zK@P=t#PFPg4lujP4 zGI^%T;T6j$H6Dl3kpujrvCZ_MS(S>x6mX!0D{!agRc8CBa>h*ksBZV}0w2fTXQAEg z{cI5u8ogHpP2MY9bBgar*k8VnCk6&gQ#tC@`dWBdOdGb2uXlV)`;50{_fa^Lx}8Pb zRO|xMrh~anj*5$N-?I-&dUmM!ZS_6R{UmsS#|^pt6`kwKg=@{L49W%aVml^}5NYB~ z#hq=_F-Saf@w1RAo?FVXG5dr$YZ~`?cK3 zq{C;jmsmgfyU`+&h=8)OEh&TTe@db_pbcGj;?%0qn=vZZ3 zauj(@;X^+(hB`e-jm{npgR2MxV+}T=jouolH9pr<{mCg|vU2s0htNf5ssc3?&L@N= z3^RpBj?kEAE;w#vr=^tgBn{HPp8Vd&1>D=MaifvhZop{16gLxEjA&q%{>3Z~y~KKe z;;niruw*F4-(5hhg%4|gCjj2+X900+&u8X-cUy)koL}T#l*dOkRR3yE7f%nbfIdfP zKtQoZ!JS`kD!7x}E5&K-;xL(B(OcEo$vxEweK~dA)A8KwxM|$>ATp{Q1Q6MW1cSc( zcW$NaiCbX@W#uJEb?$xj_F)-)Ofy!=bsWeSB!T7bkqW&Eb6-0HiCNkABMVNQ2#=hU zfi|Av-c0|hFO5CCys0kxZ&z5tY=N`WQ8qsQ52Wypi;7X3{~I+@AglO9jfDJw{OV~f zwCg|~ci2YG`Re0gY2It+rD{%HB~J!a&u>rUe^r^X^B*k$sCidlQex|lZGKY2zQ{e~ zD00KII{BQDlw-)2v%B>IU{RZ?nrp{KrVt~v@CkaM9S^UD8xCqEzV{!s|L^?D1&OhSQ5)WFnmHRB&;cGz zNMvYe2XEF;)QhZ&(~P^h|MSrP$={MW^6e*prCtN;zTl9=XWE+f@G?3XrMiWR_(g%= z2$wYdUZYkt(~Rek(Dg4M-9Or*n80l;B*uQqFVyjBrtw$Pj2$X*ktEm_8)unq znV4A)Btz}Z_FD(Oo2;zTwRS39Cqt#PAawQ2lAFHi4#9V4BD>f0J;hhrVu!Ww=CxUV zYIUmbWEmk|f z6Nk-S!Rvk9*Vd_320Ftr!bwImThA+J*8!RNUDwD>9JGE`IVBucj0O%FOtHzQO^JQYvjd7Y8jakuD>b_h0;gB5pM@FxNyHCHt zbRy>YnMnb70mg45R7+2Ez%9W7p$)J1=9e@J6n>lrbKYm`*qrq2X>Nc?ikDC(rsGDo zaJKA_D!`;r+Xz?9*r_b@6V?7Br7;unP@C+PR!~ruNTe_iQDj@^iA&3sl-T{Vn&<|i z1B*j~EkSCI2X!`vRz9~QzAUR{x?EQgIlJTTVMb(#$2f zqmX;>^!rU0a4!6s%6UTJYHcooydjxzaY=Dg&0+XXNAeHJA!wL=iQ~FYvA5B+3B+f} z0>VvyluvfY3oT{O;&9 zZha;P3?3B2vYshABn*~?k_)WCw*`iwEWn5>C4~%+YuB(*=1rohZ#Tl#YznY||On3TYl#RG8$MQ#>z4-VO@3fq&J&M>oL~WZlDD}hk01eK| zJG1kqao2;3==K+lB1HR0#^g4CnVX>}=0>?Mm?2|?!&6XUJ@nZjWFAEjA#t29>g*$a z8!I27>)U>gN)rNM%^$~RNe}nfqDW!9_UBn#%+~N?h#!J{>EZT^5e!`;O0-F$| zmwg!x+p{FOQ|aX^*4K0oUTb^Lau^0KgACa3XmrBA0muryT+)V%Uc59pGmLVc1RNr7 z2TV%JzZvSZ6<8u4nV_Iz%=m|?3}yLwn4}GVBk#FtLAmj|uJ7F|McCs@{kFm^vO-pH zJ&)W33?DL4J;*?7Wkq9qmqAs1NpkOz7sy>V(aa$2XhYuP#Ev++$ys~f3H(+XrET8o0>J#hQPC}d z>%7Fn1^tK0^qKm(O)sAJvt5(bztL+a<19|&UCU9gQmy@oy%4UH+)#KxE?3{(b{wOY zeF%(fl@PM~B5f?__C(yJvxdhxoa_c~&JQz;qB9&@)2UlPVr!8m$X1RU?riT}eGs#x z528C zoo=kqNC{;i;)&HuoaGfIHv|716&P6eLCe@IYJ=b!)3BfH|zc)w>WP`>;uv(F^8s*M7+XgxGB=Q+H@Bbf#=;l7feV|!KyFD~$= zuDKxVJ{mZZRn0Y!P(nf0i`f@A7H4Y~;W2_3YgZgJe2-SrhcivurQ4j-M*r;Gz^LI7A zg(z@Luw@R?qZKnhot(KKuu}o98i;pu-2~FG`n3P$TH)DBDE&_L$yRmQCTZSIFAf2D zAqY4BS3~z03v(L-Rpca03GmcnUwnHP$Lb4;)C^^hy^X{tAYocv!n+-RGj*}3PPK)7 zY6O!5$^H!QzoY+0UQGC|gFaEUj{=!09g3r;sy_J(?3d0mQ^m6w5;irYFY7M1F*phF zB)xwlceMdzQ@5znGD-R6!|)t8w#9EbAnZ>v&)HE|l{k1w;U_{XEll3K!^w~}U~A~( zzt~Gw-I73rYt|pc3*WB2Pl1=5MJ(5`EURY~rLHMJ4Q&arw(cPifRUO3G|SwfUMUof zmU#SFv5AuZG>GCvday~GvljY&6-U6c5$2ucbU(V=e%LvG&%LOqcAKg=pJ=DpC2+yD zDqUx!^;b|9rBkQax?vQx=9gOu@ogp4#ISy}uRk46Ommc(KfnD)u`s4De-DG@N$t>< zc7y4XQ1WM97t?AHk&(=H;{Rb`s>hykZ4C-ckvq0OBz?LK;2-?|LPIk-gIn1K60d3?Ua#!oc?U&N<_@K ztTSFq_GFHTJQTRU_;5<`sUiH5CmcO%mp}f2F3qkjC3EMYM&qYNjegWS?h>r9B1O=|V@Lsi)wmCBH^Vo(~|g~JsGkI`dN547n~oQH7V9T ztNS<=38fT)GeLkHSx>YG(|WH^Wq5j}>~13r7-$Ta=Y$eYPG^uBu9k%#mv%0Im|p#1 zp?ZYny6`Hp!(i_+@CDy2uDAbC*OS!b(Z+O_1}sVJ8Udf|3u}zN#($X4{^zA^woGDY zQ7rmk6L0V$A@v-msI_a=c1cU<0kSgRI1l(><1QHf)r&uE1e5 zcsdKi>AqmX>z}?R9te-ME7nO$1-ocBuB*$&X%MexD;rDsBITKxm7Z~h(362fQe4ng zcDA$Ch6X>xhSuG3n`@=|@rmmQ8@qP~9QAOFpb}yT-xHKy3D91ykQCRD-TuB%@wW9{ z-^R+R{!F!Ihx?nryqwo~e*(SqnfeW<@Op?GW` z5eDH}VYYU+6llp`C zqadZ?!`D6Yn3K75A?4gj~gK7+{15pIlO#5u+r$YNpgWP5Vee*x%Cd8al-{X(zuc4B)3!!yT5v3e)r(X@^zoQKfN;}2FT zdZgAJEmKZUiez%3a^gre=e62Om@T0~BtNE+u@;xa&gF3+7d`=GtYfp}KOj?B-*zqn zT#wz+!?FnWHiQDRGTu;nxy4lMAlZ@=ecNqHH&R&yw;{A*_@}qX2xI5&;B#G)55>(T z=DN8g<@lT~r&t|%uaQ0ncU*nu**hdxDo$KZX@(9AbDTDju82(2-@ntLFmaA0j#vXM zI};0D^LTWuDDJG$?_juriF zXfDCL;cYbeUUCVSNlXEKMbiZA4rtz=sm8Fkjfv)H&c3Ei)FZ%D)C^zXACGuD!voH} z+=mE}4;2()2<{`Vv~9f1+S$B`&_A*F_13Uq?SItXne-p5b1a_$TOm zx595niNu)EFD479Bqk$URQWDwF~^slFjarFI9K-fC+aKyGw-r(S{j#FhS&MRN=pCe z0UVx$2C#M%A)C})LFUS$aEkw>)Rna?iGmbFVi=9i&Q)%mMMk57GEwCvi{~mRwOuQt zCl`rB>rB4vBmtAi*U6?Wx^gQ5f5Ok%&7n*7RSe@~4D=r(2Z^{kY(r}e#8-s+I>PIe z7igPQ_#*1D{7Mw|{y=WSc^NW!_n%ol_4>7KpIgIAMM5&t?;3~PB=?KUb&_uy!k6{} zhh9tKzkT(`v=+rMWl{h0`9?cx7&+}5j?a3!Bl74L3e%csNDelZis?8DA~AQqAHW*i|$p2 zf+?j&>e*(Ri@9!yWfNFZ6N0IEg@0BJG@@uSrhN4A02XCeC}!li31{v*uIVQX8m$7{ z4n(@{Ks~1By=)`=c&<-s*jRFbKlQq_g$3iEZ5X!k{MiM05(ZicDA|dq9javsV|va_ z1EZkIuqi?F5J%km?mUwXr46T_pk!K272%NELN8mXnS`zukx1wcjSbEL{4Y zm(%vA|2}E1KLQiO@mJB3p@4Dub@jAk|AZ^kjH^)OEFj{ph$f{26Few4u#he?-4lUZ z?8r4qb~=xV6Mlu39L;1vEpyE(ZV5^dJ8Lm5&U0*o@sW>D+8J&?aZy!-FSC*UQ}bsF z_;^MxeI^V{6-W1zFN_L4+To-~Mv|q@5d(=;#g9G@hsw>L{h>>|T!(**vi;+qO~M8T ztf@T00+)$@fY$_6B-%=X`9p*=OjgTjyoyM~oe@ii(Hd~Q*@HG*{f{=jsE%-kqX9B= zc(ZZnxOiQ|LEDPk>4N_0Z!A#@LZf6Hg=W1+m-n^7*ryx^S7C zkKGqBCQ1C4Phpe__dnZ&NtOb(*V{+~m#}Whc>5;7v+SYQ!vi#RH)gEkV;uRcOp=_| zzm*W^Tj%9w$Y`6J+}G!>CE@`0EJ6JK;@;E1<9VvB@E50a%8o(L9kc0~E!Cgoh%<_I zO3?0`QG5p7w``sV6tT=puj(&j7Ww7kJgic(Ts8=7f{=x$hgRucge8Z)5+=;Qf>p33 zGFzHl3rb(O+)!@OB}XGZvyM+}c5=*!(P#X4G|c*aGr+w>L}}H%H-DHZ)KAM=wG;44 zHxkE-OYFfj_P2=!qOMoa>L^oL`i$h6S@MZs6UXWWbla5uX`N$F|IxO@O2qiEN)&4O zwZUn5SXfSN8m**a$6*F&z#h{W!G%!0{rIHO#Sv>Uy`a&cUSk|_Ia!4EQ95k1R7iY< z{v#2Gtraqsdr9=7L+1-t^!3FPj3%fG4aNnQSNZz^PFtZ@G_3++x5*EDatR=q5-)0Z6TzOl}zpAi3$FxXi`*QyM6f|IJOsH|yQ9 zz;AA+KQu>`=hwP_KX^d6v65*f*Vu4+^QkK9mz}7c zf_wTeq<^WasV+FWfyL>SlPQV=4X(~U{hw}MJn8EU{j?fw{l1jadOzdj=C1$WHFJ01 z_6M+XFvXLRpIW&5-%#{)3t0P~wQm1&y`msT>KhU=)n}}s2M?;Vvz)E?c7NQ}?Njrz zv={|c5_*--{R~yzDBw$}dL0pyqNx6G3;;w^OyPS znf>WG)$;X)lIf1OOzBoK75@|yOKH<+m27#`%)n*BxOkuYf_2;Jhe-AY}p; zEv(L*Yvpm1?#}i?K-K5|P3hwuU75#G=jEiaYSW{~!_o=G3imzwY}vGI*&hWj%oEXR zPxTw4??{^TPm${-pKZw7N2Et*yNJij$K?Pgr`M&=pz}Uk%aAoXm@U#%U~lDl+<5HB z_QqRp$*$~6%jk(R`UZF9DblM1eAKP=JY^_-e8v@-ryT#V9lP+DHHNJ`>$P?J#|AN@*YVTT1T^Krbx- zjlJ1wOG7T;2Q|PwIJ@)hi25Jt>C=w?M@@;>4+Bax+T6LG6)2m1h}-8L%H4xP?7Tm% z`tW6T+77FA2gTnlrQOY>3090$ zcT}gO5jQZg0b0VqEv2{x`fu@O2Nht>2HpWhZU`)J?@l0(Jb?Q>U`PFJeWlXh$qieY zPbI%$YPAMly@kl}si#c?6{+gvO6R&+>qbm6T9O{F{H;IDt95hs77a|~V^n%9a=(&&Y|^)K zx+Rw0IAhqNp(^>W^GzvHn8r1BYp}X;rv=h@RZ8Up-Fi_5srdLUw_EOv>pHX!_OjBR zx3s70r784>`WxepqQmzWPV~(L- zqM;zT#jX*go2gTl*+-D`J-NlcA6ivK=sm4u!?(tGh(Ry}VD`|%%`V4J-jNVK_5pGba+qW!sStcJT@0MeBJ448J( z%vtC?#iGo1nk$71T@@@tq1+ygT% zJ5L1v;Op?W=7#&ngC!rw_^Zs_o2xVFAgOLF2Fggz?-=@~NbGCer|2eB3QZh%VpkNb z^F4q8>oJ8<#DXSbd58MBk$E`umSF5nl3qoi%z>d2PG^?m<|0bp=&~)Ai!7sYkm`{Z z5o2b4h?!Xe_pmxMjVew6IVdjcUaXoKbc)%bry^WQ(x48kgq(SK_umSVdjZhJtA&3{ zZO|x6nmOw3@Y_(Lf=NbkJPM;$*&{p7*l~&sYK8XGAd(~HT5<5!sOdWLE8UTWW)~V^ zJ{wAB2J^PQpUpxyvz+L|zBj9J)GQD7zf0Gt_$BWXR% zcrA)45T-~>~U2( zcQ!O)ZH>9HTXG++suvChrO{KBn+W1_V;CQBja*~)m00u#(O1TVu|$#WpaZRSsE<+f z?pD;1!D&D37FPAsvT(7#f-ORXmt+oNFu_jNboE`5zVu$f_p^0meMGFwkt`$&PTae+ z<0LGt#GQ4X08RV*ZFAjo73^Gm&p@T1dF$--dS>1x>ojd)We<10hwkfAlMk6)^8~RC zh{&yE1!iDT(=jLB*)SI|I&>2p&hku1@2e(&TgC=Z{wzkcW{u>^U-8a1VTva$5tkl zi@ojY5EKkaBiE;isCak!I&ZvWH!mPQs=E^%EkQr9^%^oR=xp#iE&{;MJ!WQyAvw!& zTKb`rzCwYkLy+_H@MoUh>c#I^q9NeZ2e^F~$Mreahr7;I{koXp)ZhIzQi< z;0+~#B8~A81E0q4qrp2ZuhqU;#mp{eKqQA_`4*B7zUx#oE>7KH2%0wHq3)9aVrVnF z5He5yqXlqS*JkaUCjL;vZ(EUi-=^Zx5dhT+?2k@2b+f&7tLdY1-1fXal9Nw~qdb+T zW;aRc1}QWSVw78y6R*@i17zwDk)f_B)UU>hu?9ANm%hQL3{?M#2LC2mYG8{UEzE6S zQe!%4T+i9eccQwQInV82Q2l)yQ-jxUXW0Vn2z_bq&7#Ig{SIvjLe1oFKQlC23hhKR61Ab6&Fx$)TO^|1>=Z@bq(+3I-6kcFh;-MyasH&Weu`Kvp z3w(^ZRHhrpB|=w1N~w4rd=^R}+!k+Iuo|9K2(EnYs*S-U$IPpx^BmX%J0f{|bnM|m zUwf^YTBBNOKMXTJnR{$p#9OH5a7Xr{eFIq5TThMH#96iT+|r)!mpT)#R=Vq{fL-WTrw2>8vfqJSw&ax%m9S_l)yk!h9suX3%v!amF~CvQ=aHsW04JzChS z-Ob^aSRuKihaL4({v#SCTeU zstcXOc1Nmn$))BXO*p17e*+Ve`+NAQ&#!S`kqB&TqjCt+U8wr3*vgZNX4O0 zjgmy|EAyb?V%6uw;h>6}()IW0+R-5OdwG&-8LAdy$>>Cbd)h3|suo8bLm4u&!cLVE zfkXA+s}uNcI?_swOS6jb4&@gGgK}WE%sC9rD(Cvj#8_&6Cv+&&l9VW?rB-m4YW;&s zeDpk5Chpcd?0u$}gSS`%54vAdq?GjAhwrxt1& zxmoS)&jKxEB@8;ra-?O@+xXf?*Pu+ky71{QFT+Yxj~-yLq{mC6!Q|Ap^!7V%xssLs z(%^bi-2(1vM<|1NxrvJ70ps$DrCj(`e1`-31P>>MRo+o3qAR25Y=N1vhlprCNaFZ} zs4=OE`9S!&()F+OH$P#q;y?3HR2YVt+$F&hDPc9l+i<_b>eZ&41plot|D2z%rq-24 z4fW?N^?#Lw!8yE6E*=O&NE@(L}X|(?Z3p#DrRk2mIPM>pxfqRL$=`^fv-%OUu_I5@PB1( zG<&f2uPLsfSw>z1N8`-Ry@xiXE|gBT^#%JVJ@4B%>~8juCb8Mlf9G2tlEKBS33Ir_!(*AcM1=5G1CfEFS&aN-Z-EnU+_}6`_T{$2=~gz zxRF##6ng!82L)@|D-e*rYWeQNthY!KZltS)3wG(T{Etcj@q3lbIkK0yhy02j^Y7E) zlh+Rxh-jRZ;F)dS?CwQP0+wX;qqBqXTlN;(^p5H3vm`L(GYJkkravTVttEV0@3kxC?(^OPStbf|rNFp#rYgpc4Ha&9!|- zcPc_A(!Fi%-0~4M`n7X!mGGkI&K{Y&Vl8eho$2z#d+3eXrI7)u5Uh9ba(K(a$nw!T zfaWri{N9;j>4TmeM`+@Qg=N_>hm!a<;)z>L0uw1}FM!^ZTf5f1j-h4Z4qO_NU6C?CM{5s67M)0oK)0zcwxbk!A_z10I zP3W3LI2)d(-T+QS$=jDDC}LkeeZl?tR#q6Pi3AO^>qk_s?gv5=!|^e;@H4k0G|U>N zSKwLUgGemwgr zjfY1ueXA|Ti1j?Kj=xHYiIgoAKA6;<_58WfhZ1@J;a-Hk_Cq3O(zRw_9pSTv$DD5Xw3EDFCr$IeLz>PuH!*w@DHFIcfEA)Y*B9PZk}3=t9jbMZD)}xv!^k8>yPRExB$J)VGgaXB-x0jeK+&cQB_j zk2E@TUemxVzWBDF^xf4;&Ms4JvM6mjEU6|3?rR-7_%szhxfnk?|E4y*elinbHllpx z!Z*4Z9j;a2c_7a@miH>rt=CJ~2aM~U;gzW}&d6{b6&-;r%ppzm+Ue2p^aAx2b=Ivz z9AzH#AtD+|n}!Luuc=WRZH0D4ucpSl8`FCOvIYf|`73`djE(*JvWUOyT^C>2uu(ge zr0bwxjYDf+BpB zdtr-IY;(}V#qK{vPG?_>`G|@>C&R(U&;iLm`Hr`)>9TflKGs^9+FO2fGMfgQQMsF{ zw6J73<{QDLLstqKJnjzy#1gmw+C;w|qPA%l+r6Wff$}>q*uj6;`-9Ud06nQT3%-5Q zX+7=$b1Iuxs69V@Wta=n@xwGA-~Hi&{9=bb5fJ9kyOIb9~rZf-grOJ8ku`Z~MyWSx3g3v~G!U(6Fm})m#x! z_$}2=5xxAY7-V+*8`Hg`?fB>O5`3h>p_kjgGsjVtct|J!Tok0j}ErqUtNd;#!ty69^JC z!JQD?g1fuB2A2eP5AH4@xVyXi;O-3W?rwt(yvaHD-uK>*`7`s)?%vha)zzz3RT;R< zR9C@(NeAmkDS2}9&k@nq*tw`oed<%Xx^dzVG?Ld?iD(cr6U~T-_2`9ZU?M+o*xt8z zuvw>x@0;;V>-bK9jfEDJ=4?{$;lkt*uq-)=S7hvz1v^;py2X1?6+At&w;*Z-mQR1; zi;7zwM<50?j1%|>AZtsfEOFE-INE<@Ah+Z5XrvS58+f&&^@wSP??5BH6aq;{e!u8Ip!OF#t&lTiN(xaM?E?p-CwEdE5bDFk6Vc- zoWzLRJhNH^)wh;A&jOCD!bMowj;(Yz4MN4W)c$e-qua>x1HaWl;VmgDJe4MWK$z_n6MC6Xv1j}ceig@(g7^F z!iRMT)K#fr+eYE2``^VuSuBO-k^<%8Eh_Q5GGN2OAV$EoM1i3K@)R5nXV&%sRG)hGl$U5clgakbdMk!G}&ejr1Gy25aR0IpQ zLoLw(H!GthjC~hqn^#*`Z$L&S>>$=eF&ONelQ}d9HBrFNv97G`N)CRWrdY*PSDEPO zk2z7~Y0Gp3-pdhB)C!h?Ern7Gb-6_*+sp}wh%3W^Y*q>=Z=Y{z?#~(;7tVXW zQ=^oBuQA74ULHBATP~lf0>Uj|tLh6pl6>(Uw+MLUujT4ON&$ZSQ}$9{Rnbn=v=Zb^ zCq^^42$1W(bBdqHP|-P>iyq#ugvbzdRNYZFxq-QHx-b_IrtCl2((xn@7&WVbsX>Wd?k6rykW& z3Qsu|XQC6Z$ye_EA^r$vOIEKm2`dRF{{`KTgTGsEAohy7HswQ z4*H#YVmTM%Mn&7V)Iz^XY>=rIcWY&y`Eq%$BT5_Qx1UF8*2Xpt0z92dQe&&Kz;ir; zNk~@j{Z`qXN~g7_uctI>U|5HB-qFO`|E3s^~2EBk|WMumFEq(C^ALF8`)PNNxZ z9k(V<>H3bcUYRKwoEcM&IY}poReE{&b44BI?)IBHYo^6sC}%rR1@NLw{Wx!o7DzZd-=}85@2bL?fFZlggC(X2%g_Ty?r>Q+wQ<+%9(8ArQqa>u88aS>EBAc=p_x*(xW-VVd>_=h|jZK9e;O~TI!T6ML*YI zMH3?$3e1Zh_R;?e4E)r@G^`4FEtpc?i1utMq#Q*?r1KWHFom}(vLp>|Ca?$U2;r!2 zO;?NII}4`j%4pbGr|!4r94I~Rt^L%gbv~y?>8J!rdP~yHwi3ekQfdQ z+IPrv)97Rd>!SJ=n&Ld`gekJ_T(iGatcW0!Y_D;zG|AQpERltQSXVdFy&8Yo7Gfv1 zRgZHXc!KJJZ-fN8;lLj{*M#>MzrC#BFE$*X9==Opsj0kE?3@WEAG$Zmb};;N!n)z*UO~Wls>LLeJo1x!s6a~p-C%f`TNewZja}CIPG7hE z40duYtowd1YwOzh`1(z_O~bt&d0FrKrT6t}6T@tCwlvt?glzTgXw)e6tB|@tSgh@O z0%s!WxA^0M%KXb91#q=Qn-32%C?w3O$Y4|!rYi80(bjL-zwWFrhFEvkmlz?G=JL{) z(OUACIBV)Gl}*G>UWGY<7mkNJ1|_(v>_g~m{r6ymk*=Tdqe)8Ne4-r+h;I_S$C3mj zj^4^2ZXQjkvLIhRGV2^kv^c=*jr@%7elIJ+eZ2Y3)8RAu=fV3tmDLi|>ziZp+r`AI ztK3o}YFrFeFSTq#-eCZn=+1!NHYFu8x)z1V%ba@a zde$nl^_hz>k50Zqzm!}{dqOH)dVU*veo?aVrUf&Yvi0YrF7m|yUM;0DS)s+If>9qs z%ayy0LnXN3{>Tct){@UHi83rB`8aaO?nM-JJ_>+4NYzaJ&jK8XqgJ9C_f3qu%5=S& zk-o~p#R9ogIF`fcH{`2bozE(O=pLNj71ig<7qkTJnAM65#>0G`10;Zt@Z&63~GBCe1g$#Q&WxTk)+Fn0r8a5w&41NQ> z4NbkNOMJU@4t~=h?u~iDZ3%&ZLlUp?-4d_RA}ep{tI-v^S>Ay!=Yzv?9U8><&z`u16E}b3p>Hl$BOs{fAWx(jpopLq;o{0%m3im})~+2R-N@ zNv;wX@H5FM5T(D6h~PZY(DWH#qEjUD0ie>d8}=Fp&D+u$l4_cEsZh@5eZ*NIK>;^+ z>$+mjW0<$aw9#y3EC-x=uG?v1AqHEW?>*#*_ejw4N)O%rIfr@X1HxGYZG+5sF^nB_ z^ol@vbc?4zlcP4`kDK028PJpzRV0q(8PO*n_t$z3D#2UgP@?dJrYz6zVc&@|)F47U)y8Hq}By5c{J zPF~NTw?(8D&owW->qQ9||5NZ66j}A3viWO+T;6!2C``i7N877^w^) zptR?A=^vGZ8FY=HF&fIOx5*Wz4bTPk%fkhAvMiPO)p##m3Pfw{AM}jPOGZCm!vgr2(#ycfIVJ0Z2B9;>vrNmoDQ*^pbfAd9-2ldJElTx{ zq}`RXdV*0SeS1D0PE;>$jl>1uwKVDLnYU*OV@}b_>|ze611C1X@aqz6?hSMGHrs8< zQqY2R!QGvDD{oYDsWs=qauE`98-Or}{<}nVV|3kfDm(;uD=d;CvLs zcQrK>YFy9@@DNL_#Qr*ac4ah2(5$XIDrH0Ypd5Hk|K2kV7)UHo^H*y0o|KA zsx!~;%n<;cVD{i*HCV$WTBbf}88ealWA@s8Ss!(}x+6N(HGq|WYp`uSOgG?ELTY>P zYd!H%H-J+7up7SM{vpnmBIw5p3!@fP+E3+k*ths+XT+A7bN!hb z z1Qe%^M<}X3_QXMMcSsYIxqS_vat=gTUz{0Q=loVw6gDOO2Qck3$DC$d{ggjd#N4*= zktG&ko0&(IEHyR8a_$s?A6=Fq)frlU2U);ZSb5qpJ@e@W`HI|Z+7Yl)Z?z$|(g z^aWsAXEv(q)&y%Vuul${lOY&oyV&r&J<_SMu_5tZmO1HmNo@+21O+&&Ap@){$Xsj( z`4p@HPyBP27nYRGc`2I%F1MI+1PTqCX*75SE}u^&tIy{cx3Dwwy-XS08=x0p1)_96 z`lr$AhuoNuG%lQy+zO+Yn5JG;EY$Ghk+X?_uc#}E4;p|Ux%I3_uC1VRP(8Yj^9vg@ zFNdk_Kx=&+9$zH8fYKMGU;MuFE7i`Q@4;O>9=WjzAJC51r_02h!Hu8i59|~jol!+K zaJ*f`e-hSV=*OvG`V#m_tn+EE>Y)w70e`d^xX4GnQ>#m@`aK!@c8h-g6k=@kawMRH zGyk|JPMq}Sh<+TtG1#1JIPJp~dDBT~+&@U1$Bc%ep*Rv=OEuCbdmTH~!u)h$--+v+ zd%2WLqg?6i`E*-{1A1c$ntW1}cdB{neCg!me@)h3+u4-x0U!gHpOwZVXsk?Y3kto@ zD_dFjZrLp7H*X$I<^&+-Kd||u!y0RwXa4=I!%G+p&K=g@FOw<%7*YKN4N6n1S8F0Y z0L`gl%YTd>6Jwhjh663W``Z^KcqX)HP86_8QD-SpmyPpFl1YhTLIfV;1hy1jcNLnS&)cdzybuhSkz`?$6&XutN=vcoW-wty)TpVBB^`d% zoVOZcKp&CDI&?82p&Mn3vy*ap{65nbC zDg7P)h7P~zF^BRfm31gj9whS_?cV*E57LYi@{@3Akc>qsB1s>?<4h7DaQFvQIJr}0 z();XE42&V@7SBxK9A6_vB)hb-p|n|}dp9O}ubv(R>4GHcsty~*+G1ucUqS@fU8Qg# zCov(lcl|g~bND7K#f2y95`UjQ#&W{lK8pUq^5hT~cemz^?y46KzM~Y~lO@nr2y^P+ zHSj_E$N8;@*RJ$6s-#IY5~3FG8aF{|czAwbX28rnM3=6Qq^M1TItpjTvSCQ{dEaYA zgA%Wms=*enZ>y}th#Pb@?f!ST)!frrV);$p8R1ddw#zfwxVi9v-e7r`8O|NSqQ8>= z)I|L8@7qGLYfZp>$%4!4GV^ne`zS&Wv&f_vS(76X!8Q|R^bT;kLAs|OS=;6DNI-hG zgdA_g-a3pV&7@7JhFg)Przjf-b@z`>seQK>_)PI6>IT4v1Zp8CnauBO2)apUH?k<1 z+uuqT#2aqto105jki#U+bZyk-Nv6n;rc9iohvmS4%x!^Vj2I)UCN1Ptpqi&UjQu4` zf*PX^7;(bD_>ENW?{xo}^ENxlUv<&+jkkZR@>LRSffUMoyG2d*NfgB;3iSDf3QQO! z#ncfmtBL%uB~d$(aIGXG!xEnq!88CfD6{pj$~a>C8YQ+?#Q5DB=jq)5!=&LMbU!jK zOjrrTOa0Fnjb#6f(S<xma;bjzfGTFD7sbS#?&q z+RJmXJ=vO{|7#^z|XV$cj7`5q?69CqC`?4r7c0Y0jzlUjKiBGRpb$kM!LTifINQ7x=fjsyKZU zv6dIEN09qw#v4k2SHWX=w}W#%(O4jzvvIjmgjS*{KQoW`_Y|DE6#tu1q}Pyfq^0wL zp*^bhtiFe7fm|J2LF#zvuK$f8ylV3Ac{gR|rmZ9hBc{Z34(4;f@02&(qltf=R8mw_ zF;(I}$8TC)WGvXZnWjweq?R!v7Whp~MZps61tXHy*dt9jP~=4=(u;GE?nmohGtj2$ z^ZCC*>a&*2xPXO>mz=63%UR^>r!-`Y0~0Ci*E99S^Paj;h_Ihg{3IWnwhPCY+)#Y9 z6XT>X<^`_6Pmc1#0Hz>YSNdqqy_f&hcdR@`9KuB>r_W*o)R_N!`kB-}e!4GiIF$62 zx-O$MbQl%_2LBtNC)C90}0c&j(MyP z#lqcGv@^L>dGDPW2cRw)@sv2EtI`l*NBN&IZdyRYKVLD8k7|{_<3cNT{peBLZ7Ki1 znkw**rgB~1K z(s7C{zP;0L^$;sX)Bly>7oAA;ZBJFpZA4a1rH?^Ac|YDoxRzd}Zc7_p|9`mv|5L2( z#(#JDl=OS&ymybhNC%q>oj-=*It2-day7JN-_Q_yQ-l16MTL|`VCm>9gp?RD6p^7D z3>33f({gN}eB>mb@;t(cv}s^b2VAZoXX#6ehC|0kL%O6Xio?+n(r+kB8*5-{S}AK*mMmhGC1b#lCW*WSFx=R)N4y4H zID$I$HXV+OFzU&19(idHEFia&A;E(GscAF#Um5~lui!Xx9tv_c66zmHg>^QM1218tI2c zwcB3O)a&Bt!P~9z`QronIp_1FPRldVbr1oU15R%MRRA=V2)8PIkD?q$O~8NU08g?X z!@YqFkqVPZ{;G`H{a4qwL(cuI^xXw$uOB$V;7tP8w;LYKDxLjnW_%I-7Sx?e2H(=e z+{6CgkCK9GIK$$^UUE4Gf&f))udwf1L=hiPa*cwYBukvdl!{w-P!h|vLuyQrEpoc} zhznbGOr^e|dWtXOkfl9xjlKaQeiFCGa2MxAV%R|<7fc`rDU@brcA%S+aSP{jlrEN_9@?XW08jKRH6YOH-Vq@lalV0JLi_$HX=c zC7?Cc&%b7-wYfw&mPGghh1N!o@az4wwXeAtP!_&zgKyUUI8dWlRaYPNYriDxnwbJ; z@PscWTtzB@L(iM#F%qdmA}Hzt>)j0k^CM%`DkFR6)GH?*&j(4(Y;jyD{=XW2a) zVu&|@_Djh^$Wc3%Q{}lw3zR2*h_Zgd#OWWp-}d2|tkrLic-%qSb)dq~ynifORa0cr zF!%JXBJ6$qi7^fpFWny>-bNM9tiE5M%0p;u<))MX5uI-8NJa$4m@(5Y9BTZ$)Z!=q zfKne3gBC7?KLc1A1RmOe!u|(N^xIN+U2f_YdXE@_PO8MS*Pm0b;22VdL6qA9KE8nsmb$1 zT{(gX&YY! z6_lp%KpfY;vm*$*<>IifhC%+IX*JR-+Hq$|M`1G-`k{&alij`Di}?XByAx44^7V4s z%~~kTvHBtYxCrnh^Uc>Ku)&ojuvu)_>z7OZO9aG6BMXNL4}U6{ zqx0Ssa6EW>$a>h$(BG8#mB4_3QL1>TU;ClA1@>l!hbcvMEZjd=m`SFi{6)q-NYGwT zxemegoASdpp-Fj!YN_f^x@>vsOMdoN>O!#y&D(xV99nfoE9RQ=ceK|Cw5o`mAWRM! zs5VA{=8w)&caiTQ&fF&>_wU^IO~03MD44%x^A9|2>g9S^ND}Z0$^xS4{;?7JvH#e~ z=$E6cS8CT)d$>nWBHe`+hrN;ftel*j6rbP_Tw!w4XQ<=r4daxho{ZqI{-ABad<`sy zLIdq+BlZM~6l|H+Vu+Rlf{ea+v3}I`JEjTpNK7uS#KVtw+AT68L((rli8eIQs{L^O z2-PapAK5eG-=kZs%Fq_!50*hPcV$#%G-=RRxs&>}@z*8MyB|C|yo1(Db-ERb#C(fov z{Ajs`JKO~9|6_M4s1?7{$yqmlNts)8>HCsIaj)Ym_YDqWuR<)*6}&0+e)&A9IPtCs zLU5sv5HZA_mM#G|tnb zdb=8ebV2~7LZS)P+%Nu1@5J5Fw#E8&zy585g_7y0-|nQM29W9ehq7s&{V3^h?JcK9 z`j&dHM)|mQG?9aJrr(rJh2Shv`y*x+bM&0vI@`Dvj<1EYOR2p>?@0 zU;UJ`PVyB9zHHL+gq(;tWiXr<{X_ps(`=dv?l&@SXp7z_9hO>9e(IOgT!oX|_f=`r z)Gf${5X;Ul3YXMmp}sd!a)ImZ+mdsQ_1{&E`dOP_rNZ-Klj>f5o%rMFjO~2B-Og_M z4^xX_+!MY~y&XF$qqA}Q@!7(4?}Rxm7eb-4($aTXKjRcUeHp{dF>Rk8;kem>A4iQ6 zP~e_WTMzc;AMhhAFm9S1IF3RNT$dcTBOaT%Yc@`O{%QWSqq|e6f7W=5cvW*_Q4%$m z`3_EAw!DGgS?<;zTn+gPGBRtY*48@no{ir4qnZ$f{PRTXcE_+X_j(L5PKS-b{UDoT zX-6|dbnWwxf}2xeo;0g8Gf26HS|@N!rlmpyQ1{5QGxHgE=(5w#q&xz0mY}Uc9ol82m*n)mlnPT);b+26M5ZEf3J{%Am9>SMX8s>^Cc^5!Us1f z^)l2(Re|P}a=*E7O)sFE?6yXKaPYaA-;GtHs-pt#xX(5RYfBl(zF>K?^ zcb%+81OLjoZOTE`>L-l(*BB3T`A2xjjvu#{7%dEQCD;_~NXpbe6D4lgd2&ey6y;n* z!OnMV=H58rRKaRFKejqe0Hy@V%qg3Bde$-VP&fn=7j20BnyfxRCb)9gmpb}~drto0 zJMpV*`h&jeD|@f=nPp|n0}-*VKuO9zK`r{}F?se$U#9)EBu@$Ui-({sqb-N^-aLs0xTqCYukO#?rEg-iQrH9YgH zPwE6+>6Ayfp3reCJ88ED5+VZUH;`qhoUIICxql1Z(m@1_GrdsmuvWbrj8!`nDPVL+5_)0)136myT7V%pIH}dmxn6*pJUD45z1!Xl` z@C{z)=eQ?%!u0@X)>B)O`%=U*E}7#WftUQm>!9d3w;U^-P+4pR8x*@$JTj;1IQAq= zaGs43L&!(BZPw1Y;q@vxT?Y5Y1+D$XxCd_cD*=28_o*-!CaD8QxerYyHJQJVeU>O{ z1(3Eju)41`lN*hzw#p~|a8Ju0;xepZZxg)Tt1e_=zV$j^s>W;1D}ehl7n~nJplvVqK1(=0&T(AjqTKp(&=w!z*2C7>&dQ$?a=@TM{)WWPE0tkUf)$PU z%Ihb<1R_-4xw#zk2L4g6#F&sOWiRoCm9-Q|_f-%l;?RpH-A&knVP z0|6`kD<~;HB8PIs+XvA^73#N$7ZS@niJQM^Ji89wflh=e|AipIU`LSdt-n$i4$-!Q zPoj8dO#dYXPU0jxZB~n11nFhd6?>CNKR;W)Y7e+K%4Gz1?I%ghi4P~(1bUSk*maKC+v-}G9Dw|vOabc+3a?Oq1*JY z$8pAUWuJU~Yl@f5q{ef3|1$CA!yes}K}cI7Zr!w&*Gq-3^_g~P(&D2}K&eY_2DVh} zi*EKms3G>2>g9Nf74PvH_teYL1%B--J9TI%yr|+RJlen6C+};pr794cUVx3k=Q_`L zY;#`CE=`|2xVgCuH1<>P?;wp(Zmh{nI78|!Xtmh-!M)*Lk8CKvIaUDa_vmf%%zK*; zM~$@x$%r6v)cYsARFLT6YsbL!v+&a%r8(~osY5H>@0t;*2WyVTDi8DZPQo{tpQyjT zImK#vr}xQVLPfRMd@brBlRxk0bDwB4bJRZ6CC)cYix}X5F#DqEj(VIsv7h^$XFD*+ z!G{3UH`B1(#PpEH5bCLb zxSXv!BE1#%d3jKPx2FW&B|pqb;mNDCgZ*;WMYji4zvWL5`avqYr=@|eSLhH+*bLL; zr==yy13r@Nnp$t2oj!=1>sDme&`EfQ**#U(@J)YJi1D*zcTr{;w`v?0aCHPalxyH&84iJ72tj?A0~=G zE3?UV-1T-xUOE1U&PbWAf$G%#3p=ORUKsVM$a~YJB%&}QgA+BHIH|W~;6IGiOHyww z0Q($5<@HPH7qB?3k|XIAM{gv*h~D0hivXhXSG=CdL3qHnMA}yKu>cDCYF6R--3JJt zl&e@i-IDKtqpf&laVU<#3c@+UJ5FRzPmsF3n}4ec&A8GUZ0600aS4CMw5&-pHW zYFS_CBJ?e_c{FtQ zxv`vhlR*^;fW{Fw1hoD2cA)Vxi&96Rj!92v1= zryQRiX5N`_M1@e8!dv{MM~cy~jnhZOYq>nS??lcNbGPn&hKQLqi+=8OdD@* ztZ`x~5-XkM{5l9kjcnnJO+stVw5CQZj;Rq?9a)bu|5`Ps;~=h$PNqX*IjeTk`-?RsmN*Tfx~l;t$%oq8{u&|*nhU1U!8iT9}%Zo|C`C|T^X z{ReM-oT%QBFQ39E=jJIRV#;N#yAq698>9gtT#kvqL`_Vi!3;-J4L|#{TBo&#ObkK_ z4eN>E-_m)3@uCrg_$wM?6TyBp{E&Q$XDR$BIFS6gMES#gP{~EijQ6d(jOX{OixRul z3Vu&~C*_N%jMbF93ek_%O+AZP^A&Qem2#iFER|!Um{OCTD%iIrjM1fqejM@Q4K~vI zDzx2Oa}gt>XFBOEUCp-+0g`fEj}sv|R`MFozo$4TLa-a2@juQNhWXfr{~@)TJJ29s zvLemW(|1I@%@o(A*MU&a*fm|^vH8m1_gozW+oKU$^G z*pA7s&EvUr{Qi=1vy*a;o@S}LC);g-kH_sUP)#rucT2{`yWymfobsK2>K*$m(4Z>M z*_7ub6Lp(92C3p2_)xJ_p5J%c_qd1fKD6PERUUI}mX*~Bwh(bh?*yQ?z~zLzU&_!x z9lZ+XZ`TUU1UYHub+>R{A+mjFRDG@N*mtR`6p%g^xs18(oC|X-t=dn^Xa?w%2w0iT zZEDt48ZqiY3?I;A__#|gX)Hx=-^qWMM&L{(UBIRZ5v&=mio&~(#CK6>@8+2>N|eGz zx8TrR)-h}CHvk@gP!C@6_W90`tUH^OAU>2H9asBoo^^~*tuBDvFy+SmUg4oChlzB> zd0R{WNKmWhJKNI}oOI_2nLPQF1%8p+@57$6Ml|^XgOPR(!}S1_CXA#ZyA~AM63!xjHNkssF2BRY(kSK7E~+PkW-rPQLTRYipL)QR*T=#&sI?vbX?X?~JUqj3DqD8eM4a_#~uLwkF?u&7CWu!s^}ju*CsZ$NuQSw-v==b!5cgl?pwG zq_06dmsW@kH=(97X{5i`mnsE>v?F!1?|J65%Vt3;dKKFp zczbLwd_o^ss42RT;kI9yx+S;ptb_;FA*iZw4(D>ZJvKPv2TBy8o<_F-OqZ8lr3voY z&`X`C>U$z=>rglL-SODl1`;k0!Nu6=cfi@rdAmx7-(F2gbh7#<9`d&{9zvABHQ%!+ zYLnrkYH}Vg##_I4ceI{PgrlEc#A|$5Y@L5=s_CoGSVT9nS$=nCIO067lLNasw>U1N z;cB>g%We5F)-+kO^5Gk-kszKgZ#(NZjmMbw(}9#Hr#yzk9p_k0`)DZTnQu*esip5C zja@gt$nT@|3y|&~zdGfl4bgr!5;!HfQ^L|EHh4Exhr7tTlCWyv=wO=;b{3EmIUGOa z?A%Xo^%<8>mp^Qo8ZAGEN8f<6DO}m)gZnp(lxT>9!AOMz%LRjgU>59e6bS=}+Kxo` z--o3cF-vS=vTs#JSXL>0U-&MZnSG54c1mI)#t#=JP8n$yTc1X8=zv=C=x-`3j*TdF zP}-1%tHJpFpCi-Y$uJ0+x$A1v3h>njla<)dTK=o8OYGCVo=$!kq^(v9J+D{cLxZi| z0N3rzWIEMZ06W}sZbd2Os+z)~a(G_}=US0bVB`7MHb87+Fa3jt&H?N###zkl=ck~w zfwidmbNekFy^)?a4D!t|+0GY&bI95oKPwaa=np~MtV9;;hoWQrI+&F^qRz*7=(Fxm zSEMS)vPj9+oFkw&@pQ_$Z;b*z>1S{(WD5OZS<%3T6&V)(RQ>R3SLMe)C2OZ6@Z6ga z_RtPb(QtW1CdDC~feX4@pVafT{LF?~pH%8Z-pBNq`lwO6j5zD@R2T5zlh#BP!fAt? z=p<__--6tWQ+i(s7L*5GjR1tO_jndJ8mh+H>l#scZ|hGGM+B>L0j74$#eLgRs<$3L zeTooY)ps$VJ=31_Wh(bRC&n2hLl3~- zV|sX7YJ1zHsB)YJ=`X?RQM&v_i<6{g4MpY|!gnXdbSGs?ucHrMk7^%AnkRRyrWpG$ zJ@%m`h1w-~DSMn)bqd#_h~)#hBfLM$Z~_Z@WyT64)^j4^G*`aE1k>OMKS?M>eQuOC zb&ydIr;xAJn!w9SBHa?!V%N>^r%iCpy!*nl$iuIs%sE7i0yyI301{hF^BL&wo7<@@ zwPGB+kxZh{6qd_QR_MGLwfrOEemz!2lmNqrZo`va8LD&JiK!uwUU+tM@>jLb%<7N> z*F-Dw0TZU-=|0A|-8#}lw)tZtWr?mpH)?zsV~zqwq`>e&*=(F~WrfgNF!9^cnj4Ll z`Pr0;V^_MzAPhI_FnrAiu>P-!mJT99YtgnLZhuB^YH4N5^e>;g$r6qfX_>Zbdc2nO zN*E2+esr}C_n$)>rdn8YvY)_bluV|}lPW-p2bzUynjdlcTkAw?I-k#P1RHm(*~sV@ zwuVJ}exsYpB|!-H?y;3x9iQbUB&&p6sudWYJbt5`K}q&)|4{hJEEkTo^Q0AdVp+1W zA!!$b{Ol-yn^mt^2DA2+upOH;70Nm>p1ekeX?9r{CeiWeZ9vXdS*X*=-OFfkx63X& zVLsy9v3dW7VV}L*?wn3@>vdjsnPRB!QRej!XjoVOSA5f|?6?C9o4|V1fiTMivizyX zUHV4Wj-$kMZdvH(lhn;;L|vs^vzlEVPA($SXjtpu$!co8tUp4$D_&+UK@VRlky?*Ww$=0{$u9Rl44;lel~`gZ`?S~Ty~Uea9Lbm(EsKEoU&n55D^7b z;>m)UZ(Zl6uzH8JVDAajQprVbwb^dlEL2;1+mK>36`(tyJBwz#ZVR6e@qt8ti91R( zqe&x^LGX7tjC(AI^Hv2F12x~IM)AEV@Y=DwR%8Tgb~Ih_qwlDBqW6@vHmoVH^$>IV z*%q@#j5{$YBFQuAU4P)Jq~g_iw&2Q$C3g*5#ew_Hd6vT5qu6B5H>eenG}S3SW(+fb z)XyYc%B5^~Q}|)#niBhzfx=1*_fa>+orOfInJ=)l)WlPeFq<;PW7ozn`p%{8%xtV)5pO;P>{vYS)@oKn-eD*SZzY32+*d0D~p@?qQ(y*_W&`Z1l+%ylt{Tdxp% zD8vzc_9cEXb}ug9^1BG=T+8?AgT!`2dB~*>tCKdHv$A*Ui7r2DpJm^F%RKy8KYMQ8 zWj7GDle87-2i#rqvRYXQGdJaHgi^4B7YvI{J%|*I@h~$(F?O5C)K}ED?yY&R<-JAD z%x(~i1iUq|yS<`P*I~f>NN5LKWdk%nc-Y)$%e5U>%%*&KXk~at zy&@%>d^B4;D&P}AnH6P~ZptNMgHlq$IF#CrrS&mGoz)@?Q|Q@wX2vY|rGVZ|Mn;L` zg0-*d*r=)`c~4fDo@rd`l_GawFA!@V6$*SQ%}V|y`bDK?+kINl%m*4EgNtyCu*pNz zvU4O}OQS+XF63J1*|s##rxsF1BfS${h~xzohU&$dMd%%hXGw@7a9?||`!MxmJ0IJp z(E#)zew3u0XZ3;k3_s?xg83Bk1Q$3ST|*7yVnX&z?$hedKozH*^%$XG+Dk`bigz8N z#E3-i`aRP76|yZ?&kr}!D>;KT!=m|10YzN?KkK|!LGKYXG`#E6bQaOPc?X$4Jhr~L z#fVMIvRZimSJju7)YtcV?apxVCmX!j~^=N73qK)*JR@x@!H9WUF2h;_Iehy>&)7H3X9l3r`LBX z(?-DiR(h6sV zcl11K9u>(Js}JjlXs?{I&qwO*JZH(Jct`7}gFg7mok+}9wZ@Tf@Sav(0Q;UJMhQig zx~7lXvvST+Y5PFKuh?Jfvo4jJCWJnLn>U-cFo{FP&N$0T?K=s{9H`}Qg?TCj>WtTB zg1uu~vR zdRqAxqvS4p=S7zfOzk=x$3Y=R^#-Trc}ERjVi7;*{`xRfuC1&2&8>RjJnycTF*au9 zV|z!8wdMS_R0#7f- z7eTgp1oFa>^lDxvV!(oKa%*V=D*+-JU{>GsQWJVkO+J-jJohqqKG5DUem;PInL#vE zM|!tLKH|oi_&yo`q?NlJ8jQz>o&RX+LYLO=k&}%2^TeNgyj^ib&$1BHShd%CcrTWGSpuX{NY8K88#Cm zcmFg}-DwAocTxp0zP{J>(nJV{wW zxUjFR)wE*n#v=Kk^Tx8+mWK!2|MJA>yT;ku=uY0isj04k03^R>w( zc13$4b6<#hH)F#oTHG6>fSA?tKdWpRP0<89+kn>gNnzoV-JBppF-zvMjn;sOHf1MCFItr zAX(O9!s1^O345<$`RU?`jGo6jITFi?!6U5vcFLuh;$YYPohoEzg!xBDH~>O+nxvyC zd}~%nEmJQx$xZ$7yp@hsF`yn|4fLEU9{uc3X-dZVaCa?v!k%TIzhwuEiW)NV;6&cq zy6|BIEWruwmUMKeAxShF+}XZ39*52#C_PNN4t?W?ityhZG-Z1Qybh1Pv_vTvhfHz8 z??4#wP9cig@UnHqn9RK%B~2-2-KuCS<3nOV(@|?$DH_Xpz}+DaUUem_;Tp>}`IhJj z*1X-WY-k~|Gq4pHJ)AvQ4?x*CfaNU`W{pmzQ|x}Idhh>C-xtkYQ^{_)H0vv1((keT zi7jOY>!97GewGON^Qz&O>nC?k++AkKQ5vDfdDW&T$Q?84*n(vxn*Od7cyS|vOL-PN>`#Y-t$dpXg^ z3s7#6N}d8G13!xUR97IiwHu8a9D%$GoqtT<8>S5bozJPW338PCtWu`&*4G(>O#qP4yBZ=wrcBX1G{v;^h0QoB{dQJ zyBOvR{8d**f#=X|SjR@}C`o*l^lLFTRZHUA7*ExoY3mR)GO$^uf5pt2!(csZ?qkudf%0vQN+OD!B=_%gu{nWsFIi4+gR$1| zdW$a!vUvN6Wxsk}6yo1{EyCmBoZf8XyHw(vM zXz+FVc8HNvq-7fJrZi^cirJzqHg5?i5|@f1uguL!@_+bx>#(T1u5B0GYu-vGs>Y0;ETcK`E+b;5jhFUt^?y&s-2*Zp?!*Zro9 zNX@&Uz7=O+A`%a$C5&GZxm414k_m-LU2fSV+(s>%TsYh-H*S;0x7tDwsm3YcZA%4Z zg-DxzpgKdM3QS*Z3((fd$MSzu@S2?CvWgFNkeyIR|Jdz(0c}=3i3X7iC(G=lyyZPy zj}DRh9}+ry5{@}gU!;1W;~SRe)(;CO`T z&3W>PKdq;VQ|AraeADj8mHhSICw+_@WD)%J&2IZ-eqt}S-I%pXO}ayoR@0&vHM}r4 z;MsE44BxBWV0tDm`7I}ifntT4oa4`+lwA=oO_jI<<$GVP`7%ZLUKc%iUx0Cc?EyVJ zFQ|Y_6UTNkL;TYl7ZHZEK^4#2U32@QM{4bbat*5IPkE_*o@%OYu?w>5{tS?z^8B!H z(mTb3y-d2a9md|e0??N1rjh@py$2*k+=cRf%c~}!LEnQwApZIv3ZAi!^>GDio69o5 zS}ny8w5CF@5f^vU0uC0bMYscGU-a)qa6=|n!bq-F9xfr zPl-jsvtN$q?&d`qX*^Sx^h)p0o|8Ho{vqS#k13}~I^OY&h={1g_`gd{bHMdCkANlb z{&+XNk6@d>4Us^9`OUYOGes|EF?i)8qNwl4dF}=;BKt-0cqIfzw@f?-A1=rvdmOpq z8TeWj1F5HBaDQ_%m)bkvWnN-yMO)@hKkF7lSc9%eMoAPnQ6#+rw9 z?F2GxJ!5uoa2p75sB^Tv{8rR4ZJdZcPN%iE?C|F8?t%VOh@`Q%;O;W$Q6F7+5|jA{ z>%^=|FE2iutM|qH^hbZpkG@V7YL(_%W<{U#cO{jWu`PlMqGB z|4+usn(vFhG>qB-LyWtLm zI>lr!aYtZt;YjfD({ze#C-XTByv`?vqiyM>1DtowY@>ugC!kMcdY2*pDYPl1~s z&Go7h5pf`FF+PS=$im-MJn`DiNPVV}i}4ahE3xv`4{nyphtr+=x-s5t$%5py?;+}& z3^o1Ygv24WNDg96d%@$#ku3!*>2v(VYkRnP!VpLm{0|qO!{(nLL1QZ*AI@7Ro6DpZ zTdNO~M1;c*7ErkxohZLz1ThE#dX{Iek_>$is*)L^;1vr2b1 z1ULnj|7Hv=JOtJs;=JWpCO$xotgu^{tNDh3nn7*&Ia~Z7go#g`5_K>8N{qo_&lVLr z%AP@pqCW5MQhzpI6~79-ChW)!(>R0Yy_Ti(*a4@lw=dt~P7OWVZFGJwdh`O4_wg)V zxQn$mFy)Hzvge{L)}S?J31i?rXi?&7V1Pgcpx^%^h+Uw+IrNT+?@Kgt!{m3;c%xFH z*w(hzl|S!OqwwSiz&RTyiO-B79jOP*&%kM!JM%CD_OyY-fy8k{m-~)7QM8tyT;9vY z8JRI{;|ar)r_R(~sTlp+IYRk)+NY0;f=E8ww3{!Cvt%B&b0!HUy7Z+Y#hSwZX9NL% zv)2|}HKcOox5WA=)bjFjxrj2sP97kE2&S|xSVdFgv)j~|iZE58cLHVNd2$j>Nv&r- z_M|MiNTgM3j&X;1Q?JE=$A7n&=HTUDKixY*j+?9a)=Tao#Ol#RK0;YlfX~m0BQ8!% z^?0yO`#&oH+-BHb-U(!bOrC1AboZ}?+}w#>4*mB`050&auJ$n{@80D{{kw<2PwrTE z2IHUqX(;GY=3TAS%GS?(S8YpP7V^VB`st6pTA<>NJL7-<>{G->H=5#n2?y(hik_Za zkv(QYvOr5gHr-o0@WQ*I)<_d*ByarD2P$_roU(C}mk-RoXfVgj8{xL_u^%Ku^w-W! zghLFz$#EZ7&yq4)}L1jt_$t-Hg^*ADoZ&s)$?aFtyEkdvDo}l;c&Kl6(>$9-!LoV(U>y)RSEl> z)!bgJbwRrc{ZD4;d90kn;MvcHOUwkl#bf)tPs6#)T5-l=y|%2>axgD@=sT=ry)+{_POc2NpIF+?mqo3Hjhh^ zn>sCP%BKeWfiwzF_rQ6TR}c9U=*G&QL*oO1tYv=g>b0h4o(+g{&4}qQzE;S2=90nZ z>=#EM4dwL-LWdN-)g1bd-AymKK1ngd*{@deUZhA?VUt%bP{kK+R^>&`Rbq{21>fxUA%Dr@pyk(W<^BVh6X4oktG>u71sRg z*0+q!X~lpf2X6U7COMrC$@{>PXU2?`yt%!JU6an3`4l$<$|> zfAsBcN8Ka3WJJi)xvM_Bd!4sQmQY$Zar7yv+1IF5s8fW}3;{TP&s0KH{4K z&H&>WRXy<5FSAiqJ)_WJllJ3Nw6QFqCC3&~CaF9%RS?U&H62%Q`m&SYkZ{fb=8X@z zjW+J~CbzJD5Tf&#-{TWZaI@sjiDIF_7y$3 zha;>Nx*C0Rtk;$hzO6r^ZsttJVf8k)_b}&{3v=cQCDe^Vr5!q2J7xIryRT_+Y>dNj zsZSg+@&X^tsms3XUHmg7e}%YfVPB-<2bpk)Z@+$^`40u~BX^c}c}(3%rI-tH8;lb^ z1PYXUVdVgPXU?lJ=q0F53*?>e%}8Nmw;52}6HI(@BTZ?e4SmHrrRv@Uc7+k+$Q$8` zzYKQ>0__;=YL$PSxB0qB|Crk5m%WjHc}tv{A$)sqnZml z-u9n-z$Y5gYe{@`WeX1$Fg_bkr++~vy4b~I^AU_<)A7%nR)l@q!%^_r$jRy%M^Ug+ zdT8xg(Q~fxKfU~c887$klg*b6pj~H;!mXV@Zq|dU2H2GjFg+#`tE-GYn>`>9x-qz( z4%4GdW`2pErc6KIwqj{>pB(BxcS~T zF=05Q{4_~fLf5XdaZIeJxB0H4#SAO@VyPcQ4UG*`}`UL)>vLUpsOxa$`pQq>myt7$;F zGAH&|3GQS8v=Z`Xu&~nR-PLR3OGJSym~k=DoMN^x6O@&Qx-p7eUFPyIq{l>=vG!O% zB(?DtWGKrh=CWy9W&NqGbyjf>`MiGY9NQbA1TI~nBPHp_%K;2CoYVF zhtFRu>2YTn^6XXAPBbls-cnZXThaU(lRYZLn%IueaBv}{@+3RipNJvzF?N}twCSwX zX!kn8b1^<(IByNZjD4AxeUbjwba6h?7e;fRa(h?E6Mg37mEs6lkuR;p3lGj2$*f#6 zbobfMtpz6YFviI-*_BK}yC5Lq`pDm$t*on0pmc=C$@d%9a*>jN@}<=qM$3f{z1{~` z4QuO%d~eDeURsx~|K2@KjdB@pTE;!(uM*j&6hH-P`vYUx!ow(gC2v^M-L%_Ev8pl^ z+$8E^&Mk;pY{T!89ecX^0(iCUsmH81oV|na(X_L1$t`H?CYy4Ep0@leYfWua6?Umo zsvGc$BgV3ZWn4!Qifq@4i1Ao97EM=l&eT-Npdjdwh|V@pc7rjkz^5TW%CfX-RfMPu zQl2c~h*i$}HK2n=?_B3Sg>$7_FP+gNB`v5xzW_6%rF&1)qD^Vz;-ey-->hU|5 zY8)Hgr-$w5d!X{N_ERm|+AyrYhBg(*AildH4Ek#86)i9M`=WMy)~@oTS)_5Mxp6$w ztH&+|vFjYk2n;z0tcB;QjA7I=K}uLv<9Z$zw>6}-Ljl`UXv3X#gGIP# z!`!Q0tbVs;N|Ck{LedWcHMNSD>&zFP#G4~_Pu7LqgYkU#B}M<#Z8jfkyO?_c@34o} zPO`Jwif%F=A~hxp7M@gFZ*G z_^Z1b0n^IXkJHahsN6veA=D1}&HO-O#%d0?(54Im2&}P@k1^pefG8$qSE$}w2Cfp~I?Ld^#CPI-b%@K|LZ39q(2_5tPR;X zwL>?iOmEO_1EvQdy7ginrX=nds--<>r}L}tq!5_k$yR)XT@rreNq<0w(PLzNRHW#HG!^!&M^Bxg$Z~u!(cXL5Y8TmMv`Bx~EEZNB2 zWYMhKC5s9%EMT2J{Ru4cghtZu_xrodKtN7EHC{Nfmwi-P5Tz0&*7WTER?Q@LG_y)- zscT9XE35KM&e^^wGwwB=dfyl=0rTEu+lS{QlB(%WW0hGc3GPmtFv`k>ck3nab?5VJ zlQK>Tx{ga9H5?Y#HP4Se_8t=PL?G>?VTw)>!Vr5E*k~kcreqXInHER02@`?GdmU2x zS*^{{CsV1p@t#b+m~jaHj30jcM7ueMe$^}dm$VpvND4DfxEGOoi7$?tqILxE(j!Pa zZsiTRT1y$vni9`d?X=aab7&;QK$&*R%}2Im`sx0S{hhPrzCpKeQs z4?@yF$xqh2g#%12)`P!Xz1h!aaH|Me6BODK`7y|?`ilOMwQ)HqN?cn1t3`A4Z%5SV zrEL1~>fz6|IS!G;x|6uDtEz4Kyw0YHFbn5Ej@vLhoy4ACgWnD}pc@ZDUy8lqHy8n4 z62j%1G&hGI$vx8wILYD7w(AVj;navVW&WeR+QcRK7MvTdXK}W_EjpFS`{uVyp z+a#lE`_Vp5HGpGQb&5-q)Jz4OeFY!Ah(ydH;{<;A{_st>e9MHnli_X#+2}=#T`;=d zG(-`1`#FQo6J_QiWOnwB)>ZCLYVVG+R+}u3NuKUn`i}SlIh6PR1~))2(hhP;PWcwW zdr77gbCcZp@{e#=Z3SY%zK18;(_P}|tslAJ?J-_cH+0~Bl z6)mTFa?bcV3W!E#zt!*ak$QETW8Pc*#?&Cy)HCE!t$?ii$Wb&&DX_gmNc0y|vPTN{ z2OjB9hPyu$JA8m?`g?b zCoj5{W$jTYs76;=@pAI%PdbhXPzq8hww2h`k$!8!RUD##DEq1x<-1UYGYKhY=)_9$ z?I$Cj4ttBWAu)X2T^7ec zLJy-HXYnHHQLn+a>W$2UoqE11CN$X?-So}=6EZhmcY^CRA=c*NG1poZ)E`K$q>?68cAZ>VoQH{4Ps{*m5z$*c`F1hr31r4>I<-^alv_zkoQ|at5RHo6XzWMe zE>I|>5?a+CTH7xTmnPr())?86;=ya_`c1AirrUO>pznQ8h@onZvCzBXxNfhru8?j& z@dEC?-hJqVPTX^Wv#@H1Y{OC+%BU@H#vpnbF6Fy5Z8TOowq8@egpjs+4x=^Ow@dYU zkKH7LyJKAnt}=xBm`yy`G6>ANnqs=<_br$De#$ao!U*ZIep$UY>spgN8`=4psGluU z5j0%>Je+z!gg-X?xfLJle#-BWx zCUG+dneqk^;OiONWtxV4J3_v&6KzyB62Stn!hceE-KOhLX0X!~Mn-xOkj!DGV-g4~ z2Ad~h?Vl=M7?pK@XI66;toWfjsT>ruYjNXOg)VdV1&ITFW2`ie z{3!CRAU8&HRqI|hGLZ@!i#sj>O_IN+UGB|DOw5lFl2fmL|pb?R=MkXD`4D z>nNdr9QQT*f`3R@tvESU7MMAtg!caXveq-op9B8krNutCdmh%C+3|&8I{`D_8E#xELKBbbU{y{+b+m=&5;!*11(3v?lur3=XrQOEG zW=m<~(@w{~fTg6Azf!Hy9S>Phs&7;#*%=#?t_drpJz7u9rmO9djk-!76|2cI@w@T} z=Oe3mK=`Sc#4?Lkn%6V3S7bgICdNCgP9vlowLfv-x8fz@vcr@qSd?k(RnSJ8D^Z{s z48o`HyYQq#`w!pi-N+WD$*;yK$#qj>)JCW9J)cA1){=}l?2!5^-OK+GUc?WlO}tTu z;`W~tiaUgNq2^c5`-=W44boMbZ=z@Cf4;Kg(<>44m%=o+pTvEHJEpa+lbE}SBTA@9 z`20UaFJ6YYxIyAN`Ozh+caU*^8tq>!Q?iA$Ke)HuvI~BBc2tKF`c#KZJFnZQC(NuZ zS-9*=3{bJ^tOzQUEhNuNcMD{hI83>j(Ul+l=BcpS_&^^0O^YS$@Iz;k zSH>1Ox{-a48a~5k&UqsIg8dJSQ100+yQFMRZn8BOi@hVdnd;4s5hsxJyhIl|PkUWes6u3$MubuZyZg5MyuRQ__g>NU3Hra};zm^6egg3}xEv<6+&fm@q`loXC4#seMW(jF@JiORn4RuugY@{bM10?W+d)#oW zZ;J!Es?ibQ@3<=|{g4wSZW~(oq^QNa3MB#?M72Xy;)S&60g!aStev9bc6F4>wKB?V zNlZS<^vJq?p08%n4>BkLiojRol-^KaZtc7mH$_}S(k#0%cr9WG1P~T3c=)PXpLbSI zg<4ew!j4bTQxL1Z`t7sUBYfGOzeBx}edhx0!iaz;6SQ_!8O;Nh5#t^&{oGbv=6Ln5 ztWM(Yh%EtCQ+hi~yIJ-*_>h>58!J&o@08$D{w@smp{{|V*JoBC_rg>aCjf3rvf=Z7 zuAM}i>POu;6&HNZ%6oJ*hc1QTeA61)bU6W0ylcRVRBeo3yfyvsO1grbn~4sUFmM%V zabP&F`d&p(3~{ykQW0BN+J%s9hGW6BFmUwko|7=siQ=s-PJO8ul$wvkS5@r}zs`&m zQ^c8)#e>%ppUK5o22mfD(CF}7v8hf^ts2l)^^Q~+;ko%zhHXA3F*enD6Xdkg6|L2(3;yta4wo0XanN)p`Vys$cG^Sb;_P*+7 zdz)w|s04o?L?AV#G%3MKHTDG=CO+R*x3_frWdg=Li#G!%&4E3q8UW55U@#G3CEQx{ zQ+qq*>jQ=5%tCAaH*y6jzSu6ql_O)8a(4AwoL=-Aa$J1q(fVZI@qvp8hkm8V%$Gxd z-0kMH0NhVXQCWpU4f^_@neGXV=yQ;={y_wd+B=X=@IHXs+UGiUy84X#DC816#tC1T zZd+mWsCl%ROWr&i@Nu07x0ZR50&A>pSr%@+GyG<}el)JYolt1KGu^ry(&z6Ro!$?h zKQiQ6<0o1hZ8C_ad3d^n)_zND7L=x=ol zO;X~Gnha{>{BQgbb2bpXNdkS@K@8msB-FtHZoz}I->e1|M&y>LA+`U zyBs4RNRW#Jh{%qm_mAbdPpYctdEnFfJq z&hS{nr1IXYN}Z=Cz!bUOt4^K2gPlV|k7?K1a$a{FrLDR*f^XKTFZUh5f@g@66DJ;r zrPOMlJFizkqB!l**ZAM%&+XWMS1NLZxp?Z@9GTi3en5o&un)hB#B-4T=dJ)SEy6q) zR~v9|%`gl90zV4z|3)vLt{KHV9zWXS(d*4KksU`iMSZUeBs*2$Qn-u%tS$W|qCa6s zQ>r#;zfa}0Lqp}Ua&K!mO{=UXflg@wUWCED8y2U$T>{Ut3iF)=Ou zDWYKC;S&ueBIoVlk7L22>X( z54X#{_8uk_YQjUL$fh1PRV_uL&;5->Au#XG@%*xiim29B5j5m6HHza9bW-JUyyhRT zt)ZbYda^b6qjN%86zA8BF?a|lMQ6cg*u=&BU~kujTATgWy`S2U;SMf)x|Uv$w`KYG zwn~}|Z^m?yiau-SO_E&$P$hFmC?TbXP=B(ul60>8Y8Vm$x^4 zX8JdyitP;KZpJ7K{&w-%Ke3Cu0EVi`ogL$Nz3Y;!!Nff=lmrhA3)2N2H9g%PNkrat z@i)v7&=7P707vs;7Ai0O{5Ws{Evfj_1UyRgZ%f%?|IiUy@4-KC_5pJCo*@?PRcOb} z<>?Pzhb23!nV}S3SvrD+2FI^10z)mHrye_5L9bX@A*}E`Z*SRNvom^vT!%$*_{!I3 ztU6-R(y^`?m#5nkGcz)((H|E6euh^r%D1k zP0NiS0;Z(e6-JxDzYSVEq6^Z!o}?-9=G6gj_C|c>8#G2;&0yBc(-8oID1y3iZbd*2 zt1QQ|Ur)`r!;OR)O+ygD=)7G-y1$&Es1P8i6Sq|v&Sr#=23v5SRefHHg`fDOAdUsTi|m( zYvJjzjMz*xKvkgP&&2F6`kIbYmcQR1z|{3Oj@*MOZ}VRM&t$q-?g$o=TJ-evr0Q+C zYOet+nQw@kt+u!XgzaR>t@s}N9SYFAXzuN6of&<-d#qNz)j&W&{;!N%xBEX_Pk^7FpIk4aT1{MCTwSBz z(=jaMe}{uEf!VhDcy`#SQG+xpue_R@-b=mANr->_#{E%#$N@|-OWdjHe_H%U({+V! zjyl&9ZZAi``4trvnedxUc5q)48&#C^dQXJ^G-6v6#Sd!&#u>6Cq~5gwn=Z(R)YlTJ z$o$K%`bRQ@1to!Up~0n8K1c1215M4%SVkku$n*MA7$BT_M^_9?Z#6S(*mL?@T&xy; zjyFE6kp8doiZ9%|gZ@8oSqxJEcI>VFCGWD2`cV@@a_O1dB(G}I50^*{F7@c)Hzy#5 z@qdie-wy}x#sXzrU*=?I4@LzoEiL)a#4A~hoPr8qwDC+HpdbCLWTL2&yY2Xo6~X$g zBTFMGUBuG9xwf_j{JE9n&3>taIAP64JvnJndz4#k$}-B=y2!5e_IzGed8t^9NEP`f zc90qDvd{zwwU?Jy{$zqe>lL&ld|9MHfW2=@{#%I*Ui`Etb6Lb_+BN%`wF}kDho1jPWGO+X&&jxyFCk{8<#-2Km@O+Efx(Ybbo&n;C2qC z2?|`g>+0&Z!@O4fFn*RdQ^Jd;prx=-PK99s!)}4ahL2!aD~~DLWr%`no6Omke?p>S z-HAOh;(L?cA6XMX1s3$NMeTCznoT|4F})L-lRdIyXLEjQ7bN-%)#7VeoBh^A_d#H& z;Qa6}Egak%7wX#0TF{yfchl`7|7hvK>Kn$&AJB>Bua9o6nLkO5{01v3x%eLDJA(@p z&XGUL4idJbfE1m136beMbKr6IS z_s9#_uHfdhY#@GEOkJzcwh-(Ic`!dxs^d1fsy`Fx{5kl@iBV<=a=PDAAe*5i76CWD z)v;(IHFNv!eMc|1i2+jSqo<}y)+b_pwgs0-dA&eQ#B2shu8TQQBK=?SL_B(-%)U2{ zp`76?8IdvIiy+5=HEk@>dw0U(c&PRUS>s3MUz5&qle_kh^e6=09g4bl8b+GPu3uMb z;>w~|6AT;?$_^+0hmj0-0&??$7ib*6^bOha4aPQfaKx@CFg|K5-&yH zW~mj8+Twg~`4jLl5uDe-G(SW`JA8J6*PD$eoBQwEP?WzB%NNn@cgoq#PpRN_NvT| z-t+aB>qbBC4H=^~v6~@lIqgH*m~cWLyDsjk-;!`(_I}PJqWgIVy6ULbO#vow4bGvA zxwq{Z|Bs!UEg?j#kTjatORmEjM8;PD{x;`!t*9j&5h7CajZwWXy4*7tFTjc@lgj4x}DgY9$iw8N{@Aao}qjK;%^u6Z}PMDEe_T@ST)P~!MCJ`n@ulZLNq zAj)>hfGx_YBx0*qto0MgA6AU2MqTg;EI?e?>H0$i3L`wDJ~VBN+mbWWwqPV+Z5kkd zO*NDqe2GvYGw)k^jN!rCybp)Ue%Fsh(6{tTJ(K zYa?trLjU|SqX|px`~!Ux@+)l7c<}uqAcXn5YHuT%1X}~XEe_ELjG*(KnLpS@=s32- zz7})FlXE3(yPy0-F%l=X=J2Q4Jdt>Pw|pifcJx@stHY&VXhM({*J8TT^Gri zQ;hvTQEujot2z51QMUD!CfF!peo;Qz$TovP1;)QSbGL!!?KC^!~fa6f!IR3E6E~b|t&uK)72ANj3Gj(z!%6e!;v)~{#kt*4l{k_|+I5zMvoms@Q& zBv<(yA=@orq=nqsmE(YDqlahzMxMVV}7h0C0QS5qua>u}&skQ9kt<_*PUJ9}zf z*8Aq^8_v=_dOf02@lLMiIS@Yn(2JF zGVjMXB$!&WLyid%^ietsb2kStfYv$1PDer3l%Q)-&!z~NOlOU7#_CnWN`b2(d6ssW z1YtN?0(q52SCP+j2&=)@!?=v(ENs6=*vjPZlNCLp>elBnJbxlEM;v6!okbhX!vSv5 zZAgg3J}Vyy-m|KXFOF$M6Ixj3xyiE1`kvD=6SBewl^IuA>{?Jqk&o@UI+c5(k{%N) zaDv|YMX7=NyzRg2!@n|m7g3qV z>?W}di64bae=BScIh3TW+jg!u?Xa;aojtp`OJC6M1Hj_0fIBZce1Mw_XGG`}o1R|% zy6-a_I>n+F2mV~&(voVC?iu*=XAw^K1rpH~B_i=fkbFu4@AwxMyNXcv4K#G92XIbE z>swAc5)EP}fx1pK47B*a!1rwh4J7WtX{?zKDEa+=xHoRZKlU@`t2}sYI=3AB_ImOa zT0qLJq!xfD@`EQDhUF| zEoKz%iqDHncbYp~lxXNdFUN4KDd(!bCG1okTIFUjMSL(!}`UhTKUV9!e?B z8kLvkjwB>#=u+Qbh_Q5yqmhZ3?}{KEl0@%8#v;B-gGJfmyH8Vn)4>lmqR(I$sDjN5 zZ7U}4TNww$_yGgSK+psoBgO^_l<=rTI7s|R{!mgL;vMY4vo2Qn=y4-YrR354WmYAx{Nf8zCf9lI?O+IU9Ad z#fT`pob-j9p=t_G(`U3rZ~TpX*|@s!Hr0#*Qpl)h^Lh@n(%NSAA%~-;X|{iIgcb3j zvkNR>nG(Ij8^6Aup3%=&ZqY;5*a&)OqLQvnHFNcg2$F94?wFAZ7p?>O9pNiw=n-k6 z8}JO}&CtW{&_fH3!>U_SVg1Ey?Y3%TnX7|K;U!?vk+W3X+Y80@Qe{)#XOnf0orw;| zs-xtC@FXC*i#gPm(k2SGB32)TX{zmw2Rksea%bNzHOUhT-EGGh@}ZbQSy@?e zX{iPfZTg)wzdv1W*gQEuUjhUi3hV26bLqoPpQ}BwpZS*yP+VNB1_D8}N_99Y^bFV% z@1j=RJUq~o%>gJ3HZiEMGkn;oRr`}DpRYn=)8Ra&e zw<3`SC7UXg0)34s&RZ%;JE^a=)b1<6H(E(-TY1<`8ZxZzb$=*eDaT#X2po}Yqjqyo zuiYMUaz0XX*z8?f;8Vl~F&=$u z@SFVNVmVDs%^13j5yrOV3X?Y;-onj`>ErM{SJ$62Q?lSAj3<#1eP>>IVq((1t+qr& zF{YBBTOeRCwYbPyM3d)w53Mq;L5^%{!DX9jNpWzox?sb?Qpz!`*|QM}6q%s7WLQ%B+FkmK-k+&bt{GpoSK!Mpw2HTe^JA64*mRE4E-xSPDY znJ8TG$IUeX+EZRC1lk%W2S*m3=#5I0&`Ge9vvbZ8?AT*X(klP6DN4rA1dlhWRy?TgmbO`~p#f=*!scrluIh!Z21jyM=NWvqiT+ zKx*NFB;Qg{+zGO#9~>u?gePj$M{dT9Esf`GyjH{5cV?-%p+32tLhEBQB_i>KS6hdN zYsqANg7n%FEq1(|%7F39li}LDtK%V+QyT{HygP|w^vlcD1!)G zYA@ZP80&eD2_uS7i)ifF0lD8d{>S4PuO_fptxE0;r{D}=y2y(kVZnrg^ilu^p$CxXY8uf=3G2kUfGOV(##FRpG z`(8fU<5^85f9MluN}@lvDQ~rq>7HeXeEf5Yf%b+y0E$My$-|Sse6z*dIRbg87nE1=C`Gu72FV z4m_)-KA7oyo;A5uAzU$3a2|xSa=o-rF{Ac$vdMt$613FNcEFY>f8r_O{e{F~Y%9>H zmI50`{%ugb0U2y)g!W+J(jLUS!4Anl=tk6)Syv`hK)Pf-AqDL!!ATo_^uVbx| z(9=0jn6WyQhb+6uQjvD+b+KNj4`vHB)u>G`@d!gy@ba>yIVPl6TKIaw9*#UCf=q)B z(|jo}n;!_Ib~zBCW*=NFArP?lNq7z|X=!ARL}0hdtq1Ho-MxafsOwcIym&Ln8+bwc z)a!Vls<}w!>U4dsK}!FIRp9v+0t6G?n`v+NSc+R~vgHe@ z+18~Tv})Z}`6U85UMx7<16yGd`hQ|dbVIGM*Ib`4&s{5n#vB%pej43YTSJgR&G7v; z{z6&{{VA_fsfybp-Th0|f?~oQe9FG7ef^6`@u3;ZUi-%M}pj&{S9h&=zE<28x5PgEz^eg1eHPe4m4oR7-!?L zBQUY{Ft5$#ltaDKZ*78^7TySJ1R=W>szSNAx>-5RLjPrFdUE^?S3c1)gy&A}%R<+SDQEI&oG`gL(hj7G~K0-v34Tf-P#k5JyS-mUZ5TcRLYZ+my0mYgNwf@(_khyqGFJfR#l_n@;&vZRt?+>Kc5ieLDB}1K#OrFFpLa%#CYHUvB>^#@zy*A%h8C_kz z138?UJ)WYUkpO2UNMM}pEs)P$PZ?SpEEU3)ef2Te?5A7n@n8-a!4N^+;xTowv&uD( zJM>qEP#)_LtacMtQS7=dQrmJH>b5K>wfOdmItUjwwM;%nz6{pVPbRP3>`QdX%+bAG z5-HWDin17bNU(Xg$4+4>j(0_bB?4?S){gStUK~kCfgj9I7d=>>&4JsH)ozw} zyS@RGiElg`9wyu2!d{ z1RkvW>K>i+Pc0$0c|=N6A*I)vIT5+q3cXoMO~N6oSv z%f!gq+PcPZT^dMlmDOu{ca>)UaCh~->#j6ki`4`}nQpc8Ht?#sg+*>oC~>6KBiGIK zjDGb->5t6dUZ@iqTBY-DLC=-WLYvuhOp zvhBG3YKfmQ<-;4>Lj z7;Xl^JJywVyYP&sPoqi`2i%QVQ5T7G*Lc3bJ>R?5+p&fTV?6t+5tX$(syagUPt&dh zVjXS=3$mH%nLmGW-oX<6u5)E<57EBRm+Ot(tee)}m{bd(ko5aYe+uDIVEt=$9-G7Y zAb7p)7SPMAPR^&5J-B zPEAuYJ~T}Inmv}5mX_@K^Ux*`!Bus39Ud_1n4S3sZ`(0xyck)o0k({t?p zO{b!U2A%l$cqV4%u!}k6W{B7NVr1MjA>ITwwBG@hm?u2NU-%5|?u+GN093XCIC1s# z^~>03nIj@1tUi6}fpR9ah`q>cY;61v!@sdfy5Otwu?-V|cS3yiMJ!zn+`q)p!e%9cYuqEq!D{C*WIVk7P`zY*c zX+TY<= z05p`w=lJpfE^@gMn=A6BA+N1XbPodqMn0gihl!&3r(rZ=_PMqfHa-W=8P!bzal3#^ z*66%VYzw)%^4i=85Mg68ZY>3TyFqUxaJkUb*6!V_T3TEz1F&9c3a~RQ#r^hn7)wx- zhidL%13>#V0k^O#eY^e)fhd7Mgr(tCcY*|{PA*)+Sz^{7p*8a9;lqbsN9`DZ1b$RX z6UfWT8qN6qca~_oQiYMFtH&N2Zq2}N>9?xi3XuZBXIfEk@@uKCt}ZFdtA?0mbq-Q9 zQ)4r8QC^9tudnaLo{F`)B(N*@mVj%zN(Df%SjG=O{%!D!$6t?ib90ks2EfTSPA}E! zq`}~}79)qQV?d1}!owvg+Ugg>XjfEve~z}o>ap?gU{`P$elNtR;?bi=*&3$SZf zF9m4@%~0Vsf4xmWB9Xa0F+}#mp)ubscQGfhtxFGE@_W5VJ_!Fa*1XVjcC_sNfdMRU z;kojY4^s0XRCbW}K{0Y;`oAPooLyYF)^vV$lxZg&PS*Y=-%3Q6$lr^h;M^RIP^rPC**yFF=&O^iA^P7|b%RwXe~SfHeUARn@Ia2fFC*}?leIO|nobRT&PGH~ zfs64w?Zg|R%7=7|j~CnxA5$00=(Er1{A6Hclqla6*n4fvXlTp1$)&(gq*3nA+uAyrq{8##CwZX4kCLd6*YLbdU%_c>smX3MBOC5P+y!>rNO+~7XUz2R2xcaho zoTrGPS-E6CR?j{~E#6L=zNd5{IgFz4!Qak4kczvaseZH3eJT6x+qc)oC545r)^u{= zxD~=a+L^xcvmUeiCbz@qZ;s1J>{xWWySr&-dKf;bwJOos2T5!;^51naEs`aDotr@F z8$bJLlVdB+2Ay@+758uZ-(>;qmLz(N&Ltv3|ThALdoUklf*<4tOSGlY6l_i8@=Bb@J_ z2v0?G3kV99vC)|0;NteLA1}Dt0mK;rSExomE(`1H*Q!9szUvt1)Ke(E`9AVI`8?R~ ziuM2F>pR1m3c7Bw7qBBJN>S+`C{^i-2%!Z-F9DRIfPey_1Su9kMGz^{K_Cev^bUc5 zSm>QV=!*0Nf(ij?awi1e_xtYi+NOCe~&g_}J*Is+gIpxo2%L(9NA6s)DyFY#U zlvU^B;DFWC(vntCNcvdyQdC?VT3TA_1*dQ>Ie3c2MXvG*bsQ9g?wUNyf7$%v%#twoW=%y+;BMzO-27ng0+Y6+`gai*V5gVOT=rV$jTal8LrHsE-uGyr(**(=N z*Cp-7?aVT(rmdxLh^C;uyp5$JS>%Yb0}%}w%&D3xJoT6 zU`r@KYGM@2xNnK`^Hxk>h`>|L&dx?qoceMO4frL$i4ie&1UG+m!MyNZ5a6WV5jo0_ zUXDQlXIj90ayYxJ%m~B@T}OiaW%Dv^`mZWS{q1-Q%b>V+s&U#?^$!fo z6{yht@?u&x+f8iy^q4y^5FPmd>&CBckw!%5(r+PbpJvE2QUEi+%1%jXKygad4 z8W_h?;QJ#e?D*SKGhwx<$h;EuS;MJ z#V#)|7gY7SySXiaWSPIzhEP~|r*=`kHtHvZ{;DLDXO6g4jRjy)3Lchy;qsIBq7p%b zIA!SyYJ13ucj^<5uHCE;Pgw|ET|2+e@LsE9rL(4pa}=(it5#Fl2tqBurmlzyG~>cbLlNAi}D@P<|c7 z{yV zB)C;t2#bo+`AnkcRpa#r+UT#&&l2voxG!;rg<*eZ7~>y$Hcc+@#dZLnN$d3oX9 zP{2cJ9=#G~Y-rd!|9zt(TvukU0m{pUCP0?w~UQrd-;a@dVA4e zp3{?rY@^)BhVeo?Z_B>jyWn^a2)md?=iCHJllQcS1n=tQ;dt;?t5v4nhlK_yjG_4` z2W}LWo{^ynvK?V@aWK3w&CSgQCMH=RN66OFs;aEKzWPK7#BRD7M@B}94m|&@AzY5X z#;_EM6<8{o6_S=Nop?x zX)xJJffx}NvKwNE@A_?bM^b0C;egaMcRBv#b}NBzZUbAedOolze55HHS+ex@E(3sl zOa>l=XO|2lC^+qAPYIrZ)R{~I^*EV+O!S3~%pTp1U^J0KM@NsxJ_VJuL!A=PEtqq6 z*U}df!{hLHe7B5j2cx@1dw@ymfeIv7Y}Z*qW7sQ~CA|)h;E@Yaao--wD-o!Oa}pMfk%z{Z-F8%Cu52TTfkjlFhthnsin0q1Pk&hv-h~ z4uZte&y+n)zP;lUnQq<8I?6*CKxB-B4v}wmH%Xn2OO9-_k9`;Agpg)*@@$Je;G(Vh z%2Aq^f2nL@-sO!aoS_ymfIm~Vv9i^|Fxx3#r_#U;TmZW-M%4W|C~Z;OtC z5ego0i5*Hll3aY^)dlQLpc+(ks=>8cUG=_eUeu&sKAteQBdU`a2gF&EiES*v z=$7rZn+V&m@bIJAS}FyYVlFf{cN+WLk& z@Qx`khi-5i!!!F8b52@&;qCfYUo$SydSLc&;2Q(`1h=!ny>_-oKkGp@jk2>Dop1D> z18qOn1 z^{jF6MgLi4^*7Lsf*6NpjiT7)*qSBqMis4bcN9on7}JC8jjHTmjkSNZV&I%;tw+J=sRFwH5*X(%-k`V8#O_Dz`E+GMRIvQN3v`{GDKuDB))UJ> zsZ61#=~vIVwRDGpkw5;R`6Rql#1S6Bb<9jMd&$z=0sVE(;FyVMou zwe>R;Qyb&0aMh8MM#eU;z+?cp>c5krBw&|y<;`DL%nla+y}HkS^S^VyADi+5xLJUE z#L`HAHvd+5YO=GlX9HB3Rw*DLfB=R4xD`;c#igfTOsn)$N(JfIy-{N$BMd0FzL?@V zcTV5c)wOjUuo#9g*hL84eRp>1-K1DQZmC^m4-ATpjm=C?Pk&)aXFtcr#^P2gM_f*` z@h?jX_Vn~{oIU%>$Lhw7r=V7JGQro;Q4?TnpUa2xztl}lZMC30ayx&1eF`DteO}7EUH|E;xkYus3J@K?s&gI8 zcjk+Ns_qg}mtMWS!}j)i6}+sv`h}&9u8vSj`_j{-q!-ghE-n`C2ROsOP&~orey`54 zmrgG9WQx0bF+SeZz#XcqTaQTnwgB~}VzJnYg(~UtZ&2kK z^e2Y|*`or|EZJIh3ULxr&KwDna|uT^i;Em?2k*wDeYmUN8NFM=R`YkiPK?m9i>2uK z`?}%vBUE4vx$D@!*QoCD=MQx#{_v=m_PVPZ-rOza72kvXv3Huw^V*LDUpF_2v9fK) zANaN5iVjkomyTbM)5%^rfP{+22t7aU2@#BqHhEYoWs#~gH}^F9s!rH)(tF8T10OzG zlgU$LxeC-TQ+2=!o^KIrgsJ8nCtKv594tZ#rY6)Wd##U`R^BkPp`6;yY} zJf1$jZ48w@x(EH!9a{s)9gFN1jaS9@JIKS8?jWSFzU4gt$V^FxsRzR)P8Qb_q+_R6 zGC`phsz{5b<0Sco>Ws9s3)wB(P4Q5U<1S_Q&wFNTH9CsT){mh~ST``>C9-fONp=5$ z9I^X1elmg+)1n&aR-Jc_7*Aq6#-2aKuA`~aL(Q)mn1>|86G2| zs~;rM^KN{VxndWYbz1V$KB#8chigkdKwM{BM{755DJ3FTSem2&A>#xl2dl?}PLD=| zsZ9e$8z1l82F^b>Df0IrB71AxY-hx5#5YtGJ7Wapj`w)^SN}%~ut!4#i4}k2(1W?q zgS`{gAh&bYyBa2qbD5|o*`bZQZS2F>p6j-$UH2V~NF&p>AfD=@yNwutrC0m-BkB ziR5GLt|53K{bK!$!|gig0^#j80_RkL6BmjR;1b1pO3y@gOk^|QSHYQxZYB+^LN>F> zJ*6WR(w~n3MxTC&a?sIny;zeo;)Irl(}#~_2EJr^bPU9*BZiXr zoD0S!q-bmcyVDO-``JxV1tzVEBOE~A5HTAq+ju{j@m1*A*&~6`jgmTGSv;_*JAWij zcW1#csj$o$sNcTYf8?^mFF(%Tyw`KYEU<&&bLfp*ZxAs$x$w>?O4wA0gIsW`{L5Iasd)V&yTjnIVi=k-X$!y%Nxb+vLc9RVVKvGE_2nvwlTWx z%4wGUApD_Uy*jj$hkgG1*(jEAf#d8T6@sLtA~*OiTI6SocJ86zh{F+oEvKKVsQ9i> zdqK#h#pFNXo2PvJ;Z|t?gQbIL3hDmyr-IHl13U_H#n5bqe|h-^+~KFBbT5Ny%n{Y7 zm6B$mM)#S*+?LXs!iP7U&TdywtU9H~Cx3a<>s0`O=z@(r#@jfDv1VS-^QL!+RVB+t zP=IF2%36wIBs=~nK3yAJJE{1~`uVUJSMAufWL?FdANK&xpu5nf0k(GGBg}WdMxPSn zo*Io%a*Z5NrBxIo)BQ5rlZl`XUvKHNLU!3AwJB6fGNZzfohvMmK_n7qfH;lh8n8YT zO*8kpb{+{f0O?DR?)~gDcLkW1ZVBsMa@UwN&ZHrqJn@=?SryxdfgObp?@Gth;|N^^ z12&$~OHK6Sy9|hH8ZT9!aIn8U3po{h0RjptJ$sHR9N+vKf0jn0HBo4wMx%*w5C&-v z*IRXZMMzXs+rh8SS`QS`0YK`Sm_Y4*8knS;slfFXRGYd_+IEzd3U&5meE(U{8h>_R z*kwRi*w*zy#OBmf^a>!f=`4M3cXv8qS))liY@Q&n?V-mU!5+}mM=uhjbegUJvc43Q z?q05dX+7FzEfzQDpZGZ8Ti`k6P;MupG zPYn<6a^82~Dbiv?wpJbN4UPUhcF-4k|9+-!(zP_}D`(tmD5QKko$vVY;Tw)_^?Stw zOJGZprGRcyCjfk{>meZ_h>6A%Kz!x|I#@I`e<=StX%L4E*ffr}vAMc%#G(p=4OnGw zOP0?Z2D-G%%3FEAKxG6FU^-xLn@$CT1q?Ju58V^^;wQx7q5sH(El|co(+S0ulJas2 zC{sP&NA?1xDk2C>+=y78YakmX25dA0Jg~RtPoo#wW(g~!T7Ohpf- zGwEIoNfvL-`wLjb=sZSOBMwSP*oJ{!f*_PiScW@j?)UA@s635hXJZR~0~QwgVeHyv zK+*wj@u0lSl`9cHcV+y_DfgToEUe9{$hle*fCa0%E-nc4Vlv2eF8I*pYD9GxV9=o5!sY|;zkQ&Awy?6uF(E*J# zH8s7o!H%NEMy~zw@br|Ki;Kr}%3YH~lJb*v@0;~8?)T+^ZPUbIK-h7VyjtHT<+pjU zEs<;_S=cApQ<6fBC)tm4!?!#BQI7W%(~o;mw&nPjYSebWG4SYbTLn(}9L}R5Zw@No zh)7IK{7pkOE_~J~x~wG{+~7{izce4saG53t0e5hmor|rjZDfP;zNrZUv;-pvXvJr( zY09WHb)xdp8yObWV~R@=bIYrKQZO?!j>oM=cdq7Fer`84;vY{ruFUD|yxkF|A723@ z^!S3oTk2?>*OMm-6DhByUbF)zccOs`@0fH8ny01UXl@+m(5wsf<@si(-JF+FxG0Pt zGt&t^iz)W6Vt$eECm5D?J6-j`zAZjDL@%oUz$Rww#XBI za^tVnUpGq%B+{uPCBg|LnUIchV#==WPs$8iFafC12sTanfTWq8$biim6p+X;|>qpdxY3AToU$a89x z;7^Irk8L?k+H4Quem_fdT>E_Nl-aZ{)%D4xiSPP7QoREM@k>dOOG`b_4hk)_2>?fs z+0YFVxUc`oVIHx1Mft*C@xJD@!*0L?1%zI{S+HLnW@BUX$>}sJ>r7z-7xTG3^r@H#Y86|xiB9%GV1{f zb6G`2Fc1xzJ33Oma)Hf};K2t(5-AgGum|Tm+`D)4KhYhmBwz(CNEIpx!#^n{?Lh5; zN`uIy;#K}^&mI^L&n0na*>AUja~u=>6?e*TxR;Ab*B;*+E#2uGNb4e=vM_swox-WJ zIcMT|LEvtl_jHbQ^=7y6yP$m-rip3GRtFVD9*=qf z_2LojsoAt6(hj)-=M&p74P3t3;I#rKKTD&of`U_q`deIPW&;_<_&t?QGK%egioEqJ zm>lUbV_UwqUtp>Ky<7|{zT2pWzycm{S+iWa&)iiBNYXL-nYv#Q-Xhz-{dkjJJUg{X z%wSHyM60B(hi6|RSIDJvt{6Hk;)PF7$@iGRrz-q6@gUIkCo^IVn>0W=R|gz6Pu|hf z6x6HjX_#JH`c*-?gzQ`;cNW^OY(((<>&9ec%2)NPr zrv7D7Rc%g=Hof=<_H=u!EzL%64oosAO(s|!oq1Fjer1U z8F-F{KN=MJMEesKOF`uI`@5J5c3b53q8TowO{~ZE)BbPn8I%xCB(%Q;9ul)f_fn{yO;^QK63ogwWUdQQdask z@x1l>_wU;!V1Nrw5UINB;-U+H#h6LlXV~=A6f4XAaby6f9rgmT7%NMAd8i_n1Spz*dMf~lQ0bpR@izd1o54RtmVgZehVSv0!q=ZD!7JU=000IiD&J#UHInz^ z$2}k^!Gc9)7jP7lnTY@dDA>B*OrengL}e8xZ2b{s$s}xrSyOe>;srKBs;9baP;SIhx3b6%j08=9n;n!e>vB-8KhMt_2y>=;{TaVvtf$ z$Qc{E3+n7xQ0F}-^Dv@iQWHriE0Y1s)zQU8Y_5Vti6K#XgP7S%KxNZ;ums}bHFMxN zsICeN3TohY;OT05rW_M09&FYCCBIMMbU&W#HTvpIR>&go`egc^8hTm((PfaI(dDM# zi5daMACxA}M)Go+`tnXlCnqPbwYmCd05~mBI;zg?hXRx277K9!@VbTsurD2Kd9NQ z+P}ttn*{|u9@`D0IDhZ?v4VU$1Uf@u2{pb1%QJ&@BW@oxGE?hu@&s$qttEU)2TZ4^$FLyx2w|{gR z*b-p8)Rhf@59GY47Om^_w3SMw7TDAdueD^=)0tBF*`cf^pgSpz3?L1R0Chch=vhsHi^mUUWoL{0_(P+Rz(yMk zsCj~oBBcI^`+^U-fu>_7EdT{yh?D|C!nCx;v?me(KS}94+v(ULdV81NHk@*EuJNn? z{K_+M=KJ>#+C4-t+QhD|$E5z;J(>%)%!9h{T5rfw5T&=8udWS>o0U}ZU{RyBpsiH_qqz`)Xv0uYjzP!PIE z$pK*3Nhh^L$!>b5d9QUOHdSq|beVm;B`+w&xzMq&5@I2#BRRQ)?!JJ)z~pdJXz56~ zuOi$@&3vJ~PdwmH9k*tr|H|+J&NiLbR$=tIO&DK`J@aORq1-YJSucdR#VF#s6CHo#Mk6%-#ILcBQMYrKKhG z+WVYGl$}(bNd(YADhYdc?*jFb5DRf(Va-)D;3y7-jT~;V`a9WT=IcBUw*jh_wMDCq zO0c#sQjNqfUk(K_rON%>ZM6SnL0k%Z|Oz5S6LOfexy0961tH z1{D$%)B|C?xld3;L|;u!?aSlL9xPzb!6d;|S6f7ulzBOSQQ2Is2A!N*|He{j35Xdm zMPKGivZ#Vd{02M%&08TQB0sjx9>j8n)%Mc6dI!)d{S@FFpaUGhOTF}gy1OsJs~T+f zk;|jQVuO-J-h;{5GU@iU^tLF_f?gnfZ z6lG@SpsyeBu8-#>-rBY$NFSQ_wgPe=@T{b#D3Un{Q`Fk6zZDDlfR9+7ABwWfuc@&F z5#~rG)kAJJli@Q(>6LDWzMh^8u&#nQom^b{z`3WC`oU{)7NCMWvO4<8TdN(DG-N4w zpwbI3q-%e{g@+$GwNzD~bNTAw!33`isZhs67~A*yo?FgOc@l@uUD#?B9wf3wU7 za#3*HwX!K6GPJVF2SFZJP;e!UMg>_m-Kh*wfQ!FXT@KVtAPDK3nm!Qsf&j2<6T4$I z`jCq<0e#AN!&~(cKfkTb6(<1v@c;qcR#%@~S?3#h-~|KHnb)shNAGLCe*HRrp=RCV zo8O9qx3>v5G$1D=gv$u1eCQ)NL>YL9U46XldbJ7y1FJI0mgGYqGvX` zVf>DoS`diuU#=(V3RDrd9d_U(U~jFTf@j4v-OuitE+eT|H(X%>%9(n^p9i>Tu)9-v zWFuA6V?19<7>Lv$kb9xm&L0Iib0+rUwz&iUbm?<4v30&G^CxT$iO@wfU|M}r9ALzQ z?x18c(>)*!>MFW+th*YhhgyAsjs&n(`Z88P>@$48wO-N+fhYw(vRH(_v8g$7PG;C8 zL&7Up?|D?WZ)QlT4gB4(*xGaTakt9o*w}wnVWx7hre11+SkUVGtPYe75!H);ph0`o z0I6AYyR5V{-`DHkK&0h`_^r(y?>=RWu0O0_`t`BSRo8frkC`Jb;2n6D!`v>6Nh`_< z++~3Vk05+bmPnB{(0_nSR<~n92vYktSXEi$~22}qim*xpf}K1LjSqfVedYzqwL ztLvoxeiT@T_eRU_eLW12)Yoc|-pzs+ivdv`SX*G4spgU1_Y*DF2Uhz5sFib@Xq>n5 zRY-|*-)XpwZJnVW0t3K9_fLIsiSc@mT!0XrF(eZ7pkTYJhXuF(r9-+KLHw5kY=6Nx zhY8egcXC@M9(vVu=lDYJHsc7q_Rl*rF&)o5pUup~gi5{JZ-Bp7b)I^UzP*lqG;ZSt zzQaz`;vL0e;2U+ou~Y!--7-t5NxX` zcAERY$KlV`P*pJ(q+NtC-r@7@Wn*p`l^kRn_2c55?#^QCoU`H)PwPGg9|*pBWv((| z;k&Dp?BBgIEaxs+nFO=k-RmS3apjrkyNl@2Dtxw6$K@Z2H7{Sb=D5H#BV*w3ku7eM z99(N-WBFpbc#4uYV`hQ^6@C0I_fr#+6pW;=Utfq~^v!}k%0Ev&s-$lGtaV!GJJ!A~ z$oPi+9|8b>YW>%y){y_&bh}N)*@1ljwP^uruKE}glZj%~Y%}{-%x~(N4>tp@eWxdU zfw52H`||u}tDy{|JsP{SwIixw`WX3NQ<{K8ozXa>1K@X6TpJq!PFvKs9qYXRdKs#@ z>pS0fw`7GHbll4S=zY|Grr!Uno4jDP?i}ywvq^kcl+c2+u=fKhcu?<+cimA>0qV@A=k?dv;LD7%k}P3;Ct~wG;xa-0XZy`{OxIqO_z53fd1Re=;)Npj#ju=z(zUQ z3aOeX`}b!xl;N2k-361&yBW|3(th(!R*9R`&uR6tt|{ZMQmhKU8H2|qLKXkY1}w_D zt+-$7YH+WtSC9xxnx)Z8lswuf~|aB{FbOIX7# z$_G6YBZrfEiQX^MXQ$kS;Cx^nLN?*+%iFo{V&Is5w(>F$7S|}1h~P7Il3(QUH``vw zaudQH9nGH5G=%XvFc^>pHv1Q{{9JEtiX*LnK%nJ`4kc`A!G{dYOk-c zwz2FQ2Wvc)D`u^>_ImgF+jQdEK5^Hc}1Fo*RK)tsoa#$O?=5OZd%cN@zeva#qVTM-4y?P-RfE^^(x(LCv~jv z$Y|L?${QHt=GFA)xoD8DY2oL zt-Ra)bjQ~#?F0Tw#JF-c+?o71o-$^FS6;R8i`Yv0p&lz$gw+&}iHsi9!SMHP&LDC_ zW#5`FR;4Y12O)Yo%(2<0#9nuDsmY(vr*+4D_S zkTqJnyYPO3U{(&&Bk?3Lj7Cq(s1^<<*;#4m$FXgQx9g*>J6fk%H6C>zz_fdXk3-=uN zjIK$KcdkMFvrnSc%cik-lzz_?bpOmejfPlcQmAZOBTaM8Dfw>s6j+8V@(bP87jl5{ z&%c3s_#m^K2p@D)0_Hr{Gk_pK4zoK zxmtO=`hv)!xVC4@>#$hv0F z*#E+E1!fmCFZ3bA3?uJFXlFiiAgjc^YP&ke|i#ySZB*rQ&iH>G-G@FXKJQ}=! zQ(ak>7OK2ifT!~Hj?WdVVG46!{t7y-)L0FRV7+M|kpbOFFSI}?ERd+vzPcc68+4DQ zSyCuij`f%htp)4j0WDTSV2=_Ndv{gu%MNMh^GWdf&`@#w^-wh%roGe8GvBlWZ!x;m z_~N*oY2HtR%^m3}~;|Q<_9p1P}R!)^(Wmx;8D#Wd-W@zqoQJq9c99ko@1BgzJM#H{+Mf-6X42)QoC8fFLY3qiuYG6_nWt-3 z8(*yiU*JiA6xyl*NF{)OMUk0b-<5)}Bjo9#e*!PCK#hT%ukQWV$G$%eGTR>@9 z9Zu#`Ps=+}ocvwM_oi0jzU6FIrWm;9$3|8?Gj$h>3VLMUD{gLX{<_c-nJ~Q?KfDN( zglooIZT|~+6u3DnYH>Zc$djlnGGYH%5;dE`YYe-dEEt2vNg3jV(Zm-&!DE|CLz_f3 zbO_pPl3(M5>??~DQiFzIaOUwyj3K(n4N=s&l%?)-(CyA9Ben-l0@P#@pDsw8WsOYm zM`Sx`VC-Ngo1G?{#kx)i1^Ad%{r5$i-q%qE4Ar|uA3(nR-vJx*>~(KD`zZbC>w zvbZF8N`Vj_u zd+M6f)&}$fHqhB?&50z0os$k_GX#iFsq>culj=3szj+J!A%u^&PZyq$Gtk4`65@enj*IE8Ne8!8DTAiO> zp4PrbTU6SC$U$@!Y-wu()gv|@8+8CqzQ5KTqqWwvGTNPOEOTG~hjUy?wW+>iLT^@; z1-fdPKX2r5H*clIvH>@~DbXy};%W!++>*4(xd&!OYrSm^GCb*^U`&|?9<$$E=o5TEu;9-{OdT$WYI+HLvF)!mt)`wgh4A;Yy z`T_`c$Wc9vom6aAIPfh)^*QEPo& z3gSDCQrG#AGDx(f{m|D}9HHuTj)qs5pNc*fVl&U3BDjz<>n+vWK4ub<@yaa*KQvFF zJjd2_D;mjG44r0ADSx0SIKV(Un!E;Ou#I2KD6xn5h-r_omS%G7iNKL#vVQT)c-1U{HR$ZnMan_$sA;UZP2ak+cPA<>?^zUC;C(W2+_M5`q?}I>oYxXp0 zL`vmpuW)gaXKYauv&5S)Y|3rrcsw=L0C`P2LF)5t9qJ5uVcyEREuq_|7Eday^6hSV zkTcQ{a=1|My&X(=(o#AfN>(Ewjj&e)bQwg@$AvE_aHs4*^YdoORo0U>-h}ZtaCY*F zCU)I=EOCb%XM5+^a>$_16V!a0^l6_sFO&cYGK;*XIhaaJo_5wp4z=EcZF-2EGOO z^?Pf)MLbHJ^%COsO;w8EHxcQXy>%xJA@nby+!W6k z$tCp_Pv5=!n!stlvV7lb_0+-w)h)Ju{1untD5)ZP|7Liw`ugBpVjsyDx#5i}7h73^ zI_Hq2leX;sJX^*lYJ(hBSIIZMLL1xtf?Ze0QA(|hO(x)k3+D@Ays(4m3R00 z^sisGOCZ;WQG~Tfqkm1NActWOsOvuCOLUBSVT^I=Q50UKd50gu(y*rYsXZ4;s+wRFNln{0J77usT5$+HMA zbTrvxBnSKas$r8fhp}dJ@2scvS#Bry+zjJ9tFB~u`QHX1i&N0{$^cIwPNa_hSj1I-{yIroGT*b zUN$;FmH2u*+KYKoO}%IKmgcDuZ(8sgLD%n`Bwz0?@T}ET_&>=XJ3Ad>YEpmm1Rb}v zZ!XGeF?SlYSRjv$n)q}XW|s3iVOr7lgHL2`xad4^DQ*~4QRHjN@z+fVnX}h{ztJ`{ z6h0zgc5VVW-P1l-&wLod`W=7sqTN)8_)*HSO@!Ow8Hazk|jkUh&1%tQ(g;b@QQLC4R3+~f?epC$k9!y^f!)iSr4TXe0i zV1-lHaLuoj)&jQFjw%0HZcqZu88`wbuV8_rwQ!4iwr`(gWqgrn&(xI4NV|;=A$p>X z=%a{E>3(t%-gd7W!-SbNPBqLTxjq(t;)>}_43N-vz@3T8vl=pbbEB9m9wWoAmqtTcwf-l+HH-_nRSfU<(E@RA%FjQ%W#q-tU(hS znJK4t>`wFIl~g$>;!iHfTcv4N7K1R(myqlIPvRYh+Ni&yZP}!_!VKP{b#L2*HJsAn z*N^GZOvyAovvslQ^;4vIzEg#lQ`rn{{0f@Ev;Ld~pv9ZNxrjI~UnQr|9~^#eD=(uu3b!TtEF~B>+2al$hS?Z7h;7vB3Zd`U%F!BJy*~|qdu*$W91N|RK%o2 zFLP(xz#=EGmPe6x>qYxFEll4F@sWNtnfPR8TuDSNgD0a9UX{daq#6t zO~%Y5P)H zarZ|M2wBVPA^$G;kbc4Tgd2+r9boP`T$yoFNWl%w3%1$SNZYC^}Up{1<&IiB~{m6dd6C|PL?ig6)UrVz|Z0L^REZs*3V(+KZ))xqEXyy+QhdfRfiaH~L{YC%x@(${_HzNLI|kDRKGn``(e zLW-tqs9gdJJP+tNOP4Lh%i68YzgnC3M8PZNnKc;}RXV^A=CMIh7H^_qS*w%T;Gtjk zuZJo9zJ($L(I`xhhvP160!agAScwyELy}Yr28`u%xtdPU71&-W-P7FV_f#3 zX?Whs;i$-}?oT)Mi+S`PxIGCtWZ#P}oiFEuY_?eGHR7kAaBSNuFf??HohiG=BQ|s3 zmXD&Lzub2jQ~A=G&X7?hW2o^E)+~0)6g_eHf~a;u)$sHP1tIQB$nv-vSI#5UpA$Z1 zcRaLaE!L7`ok(WXvjRK7ei2|Q5eSSWGEt$IbH<@BfXhHONdOx!k#9AX$rdHHoKk+l zTT_X7crx;t{U#YvLH#`uDezT4REy$nV23s^gn1BtCTgDBoG-`vGY0h!y)c#&ZJw3c zqYsPGHO}?MJzw}f&(VdHAmjzUWBa`1c~cSn)rIE6^i8)&);N3M&R}(!v#YVbbktNG z0kRBZ{n#pE&6uBzu@rJQz5_D z7*|mer-y}cew}7bAq_iI@^W&>;Lx{NNP@1`k&sKLM~*mqiA%TKrjSabrY-sSX0a)V z#Wlc#`LtEbU~&TwwK?eqt8V_uJhoJq@1GlIM~7>$K*xat z2U53!8JF~?(i6=?UZl~ncQq@2#Y?x^4V&O0>J5V=Q-ynnQ#5Eqjo*C z7V}~%t%E%FIV6=r+qvvtFgLHcJ5R5UZz^uiZKgW?Y_8Q4>|1Is6&V~nFZlKbgr23{ zJ{1+9?S;2>f&~kn7A=~`i>#KRo&l&S!8}eD(!Q3jMSu|f;^X1g^Ex^_`+#O_}4S6&$0RwwB5uam~=7@*L;6D zo-u&m?=jbcht&R=>-I=D(BYFkt(GQwJIMO5QOE>;+xr(rF{GY(OK57tnP@xyVxJq@ z>lG!(Q>t1NOO0EX}= zl-ipZMCqQj_ABJLJykqLL&;S`g@n+W^N)N@ye~5v`#H4T#li0iFFu&!=MjC$u*eq5 ztKX)_T^#oym?J9{yKkVBZ_S|X~?me4L=2looUmA#6Ht3RWC0rPWY=q+b9ET zGW~&X_pJ$@B8-;V=X$#hp7+Z(o$%a7N7I;PAZHDoqM2W-;M0?48PN885g#x@INHcw zOQs}HX`;q4+VaP^ofIw`mJVs5G5Lf%G{kl%%QQI&im*m4Q-oQ2TJ1Q1PV&dRN*8BT z@@^h3JTyvid~aV3#~=?YO2Ow+z%w3dGf@-#P@N#{IA}>C`Ny(ohvAgs2%$D}zU3HV zyq-3&NKLpbp(qkSGY;t0p3wTX+V17CzC15kCCeC=lw;d7F0M%*m)Qf?G(X^sEUmMP&QLm|Z{;0HSg|5;TMQ7)SLN7X((n)uboJmeH1ThC0ICYWR4o9(X#=#8v zl9S$)22|t=FJuo{_5Adq!n$UOgNE&-(ROMOJ zpp;jiD|hFH9hr~0vqJqw${5*WH*y5w>y+>&47gU<-xAYPhE63G`A9$B#$7a~Z{F9t-e;ex5ZT)M0`f4y^rxDo3^$vQqHXg;?29 zKjVC7l&LciYtWCML)+}!jq=R=n#$bGoO}mz<2`;!{erBnpL&E(G<3P^3`j?TdvcQu zD$^pY<_$bTj$|qw>!d6g$$rgBc9zW+m>?bS^P8O~NzWjbimgV8V}J8x%EYpVxEn`$ zo0#E;Z3qNU)!0upyPyA?Q1orjF$MfQ3&9^+pB2S96_jC{ymLMiICEE?*ZiK8r8Uz; z$cWH^TgXIbQm;6(D!KS8+L3%$`$pu@58CL9dCYO0O-prG!mrmz!cFD1rV!+kxB8H= zrJGAW8)@#jX(Iz;q8TNTx(K+uvav|H5GT7VFyqIGt z;Rw6Zd!w@B67?&fp<=4BA*NYoP|I3=QPl6g4doUI0&)|FS5sHs__dB-`I%CdKcaU+ zr%uZhmyqWPLf!VU;Szn2PSHn;2pRL~k9fIgA}0s!;DctyDQf#5eMEd5X_pU-;2~AY z41pIPT9Vn)RXWx)v=W(M{rA;TPsyJ8dX@ZIPaPk7O+)Mh%qNRVzWDCqRTW0-kH)S7 ze`cqhmj^8!Q&lWL#F$2#W2~wJ^bHMXnZeYc-GG8wy+10%=WD2~TWs@0@g#~SRn>+W zh^o4`Xkxx6icKb--^KJ;R}NGJd%lqbwp`0 zzv-!>7QQGLPMrkL!)Xe)XxbTKMYWPy8jwG&jmuq>JL`U#P!f$xDhv6FKj?BeeTEVZ zO~1WX`N#YNnPGt(RU#^H?Wx$%t6-z7qO4L{3kQpgw8C{F)ZYi%3k}GA-jrSjb0 zm|&?+a8XxFX}YO*@P!jWiL zw})I;-J=}!10li!Z=+#oYuK9`7vgSa)wZCcyL0~XRf-tqO~4M`xeAtC&~K_894^jk z6J5zlFnAwnaf8A^DJ{v?l6zP9VJEz%Zm$IiNW4YWzCl=vsjJ?wYyo1TGJMt5};(_ND)`h*mGdC6H)t@CP+mPwkA6)&J^R zzhL_^{x8oy{tx(hG5^a!fAcNYdly~&Woo7^>$Yl>{t}v z_J4`Uy`b}6HzoO3)<2fMKjW{B4Bz>0&mif$LJw3FSx#2*e-*X#j!NqK)mwx`FE2Fv z{w^!|`#Q7J&bfQ)e1A{3($Wo2bqu^zw&qKg{mSXPo337dQMzitpd9sV<--ixTgFE>) z)@enqQwu?*!nT*EX5E?=skrOd*Y~-m-l6rC!cEb0JG>_?TGD5K@u854{F9*np(o>4 z#tS!1ni*8x6Z-cjB&CgumpnwoC}#? mMK|y;cf>-(QNssmu>61o<1zM~vPLZ}0x8gyAv{1abdm#je;981nN^y59#fk=(0xb~S9n#+Q({!?S^E7w0!U8!uIaqN)EM2Xv93eJN zZihG>l9+?|!CHE5vaVL8vx#9NV#l%kisf*WaH z_yEX=Fn;09l5gTaMXIo{UScV{lh*Re+*>l#TG-6mx~+QiHAG4VKZI8fH`wn1=y_(b zW>HpH;lz5{Txi>w*haBAx9z#bp1jr|2I7u z552@|5?nCD$~NLZjm#@<=&A_?Bk^=AA$f;sL0%0C|60{rIzv9-h@i_VV z3-a>$>XnlZOtjs3$%nZF^$qGCPNEb6KZ3?W5ClApVZlv|QNX`cO_N?RweQ6|Y-A$f zQ4hD>V$pXA)IK-ni+QZ(lc^^nlc|K6)f)&_p8PzmXvY$$c7#9^{Rza~OA_@#9zA0( zK*4z@*p~}brovZ?gKX%kSNb=m7lUjf7%{zYj{?)@Mk1)PU4V4K(byNPao#UAu`gh6 zje`R+qp`h`m}H$=l^&LCQ=RZUTD`r_|NLl2k`0cf1WehWJ2rmE3UF$d8o~V*u*+thg6ba6& z8v`6J9$g5`wna7f=?nB(KyTUzj@OKT7_R1l5dGKLr8BRL>Vo}kA?Ncmm#etI{S2_( zTk5*!et{GcDYwL2u`6{Dk&DlR*{o}w0Lr_b&I;ilvmRHY|9l@P;^AuJYx*9BxHXcI zH5wA<-L166WV>ywvZbU?=6=RA3lNJe_vg>nP7_ShX)a)U` zb>>aUGHYKQS5AA&CEk*e7nOmYOWru-%urjPlCT|Tt?OC9B4szp+ZToV6R&9OwFQ3v zu&9~H*EG6c%pvn@Og6Z@rmPT1+~O^>yZ{w!9eeEI_j1=ZE`($`sMT_BAqPNzx;%}u zgK#q*%bRnD(xg6tuMx>L9TKgcyf5Q0DHwb1y9`-4{J0JFuczJQS#k^M0-l5@Nysf% zOdX!YKgM|A5yHovpol=%FM}P#t2YKjGjTMZgj%19anbhzQ*PAOJ}{%7JG==CluW;w zL!*DPF-m=kD(}eY%))n@C0S_FYaZqtg^_pYyJb5!b0mfQE?!e`#7kk=i5l=a7emgb zd=ao!4r}9Y(f_nS??fuJkbTxtdg~=pk%d5#w)*;==gf7W4F;NCL#OOKhr5xz>1rpx_zr>}$G5I^0>QotJZj0TzIJfK!hYh-kpdU}$DRt7fe)9*vAR zrPieYozVC+c_#zjaZKH`{Y;FYAPb3M83R?GFa1X_Si~Y8x$}89nx&4#T0Ng1f?`56 z3v;@Y>li3c)LmMBPM@dYAO_d};$F=rWV7xlccEP>!EYz18OQutk2(o>gGjTS>>!D@ zkAdmj%M0S%gcJUe@0)Ea=3*Msy9Ibg=QwD7qx+tR@IdQ1Mh^FX&2DL5WJkmP3v){P zxZmCj36SY4BEjn>Jz($Y${A!TA$5){r=Vb$w{c)!;LkYZl}F<3h55nkmnNBy2A?{c zW3l;+6-0pdJWPw{@I3wv^O1zP>Y+Husk9B)Lw|pbk4Cszw~XuW@%b)*pT4VVLKBpT zUouPAXT3=db*;`Qw2zA2KNT`(S(x|{CBLQp!&=&|(|oR`;F;LI_o1iFv528v{(c+- zaMfSDJC>K9Qt3>`pXr~Ik{eH#tZ0=P?l9lpC@M44D;bet_f7Bu2(L zYFowuUx5TA+q=NX25%rSb@VEhxJB%gh6;CRVSI{~%-1YIPuyH1quusULgw-q8`4;Q z3=tPj{kC7(T!JhgzSY(jsRu-I(&yh2tjMVP{lgIANo^tzW*uCQMNFMk4dUkcw|eR= z@!o_yZBZ8Q^o;_C731^@46?uacWlHGW69U#;K4!CwqS&UZ}vZ!Vqy2@kxJOs89A!i z@yl87;*+4463?ogzM6C$qFq`>~mZ<7;HAiM>RR!M%+lIN0amLTupWK&gRQ-y#B$+&>EC! zc_mX#HZ)WiYJc1~ySE8d8(q%0xG`Jz9EA5;4(Hfv}8sd+P;#@Jyz~>s>9Rki%;V34($`2?ehp{Qi)m(%;)^{m1rAl zonj1wC)_T(n|j7V`F_Cjx{W%^ui=>u8N#jYFT*ChQ-pmdJ6q%@S|lk3VxX!{Pj$`c zodj@giKhMN+?gH;=p>CARjRekLHwcy?-!L8_PS-WDx$JyD5j^wZzbm$lt+2R6a0)* zkDav=k2ZMu&y-Cl8A;tZHv;5kd!!*dh#Yz({5)qhrb;q^=`a}24>6GziZ_6!%_(RZ zQM&$|Q~BrV!KjR}4SYsJ*CHSFThc(WwlO|C(EiI=`!Dazw0v;^Z~q{chDlVs#aKH6**Q(;4JQ4`dQ`8fJwG&$o_WI#vC`BjOt zYRL1MVOJ5G(mDBZF6}m&0z?7Ob(qf3tCSa|8l5F~O1lJ=yC`XAYxaBAivB#@4ezMT zf2EG=VVNPdjeX$f#4!EgtKqqv4TExG1?$!T$96yg0F}))KM^Ep8@Oxesj0sSIxoGn zzpQCHW2Iw3qgv=uv0_0*Guvki7h7V}lb2JVw#-XYM^Q>pEApW!xf*7Vy71SXn|=F$`DS;Yf-9IyGhAibNUgqD1-1{8>__4_iBtx4f;g^p%0z1rYHN zF$qiu8hHYNZ>kzSvHU*+h-#E0a@Pd)4C@r_3a1@(~bW zUHXU4^1AmTv}rwplHqpZQr9VrlMD?m`&I-E@DqN^XQGn(h>Gy8P?a8?_KyDWK?I_Y zQjS~nJHRx1P09$+87qckWQq{y2?PT7&*g1O#eOgFkXyTH^4uRirIe)3gLw2ZkZtZw zr_j@=YM~lj(1#4!C$5(XujW~FvpYli7A0Qf`OfyA0%-u(r?%YM#S<>jHCLE-xo_ry zHsfWlo#mJ8wa1P(>N$7y@yV>`49(uVB%~+rbndw10JJ^i**$_ACHr^yah7;Z$K%X{ zpV+(DDpy<}{;WSmzdnmyKgHWV!Q0+LI~V=#F4A?VBXd~C%6I8T;SX08PoxTI` zh1+qW=or$QZVUt~def+5JV`EGcqE7ZY@XiEJ!$I0m+t~f4nXfMQw{HuPIU+m-6Dp! zpJv@!*3p%%mzWBJJY?Hqhb`YkiSY$50A=N?!UJb@yBFdx6oW=9XnJReGx?gX5+^cj zYl~*JzmmGOJfN29&I}*)HU#3Fxtp^&aplTHSw4<$;aKv+xK`b$vg>qr-Z_L`ErcEl zec>5y12E}Y;7QlS9ZZygxTF#}FU^gd=E2Bkx-GJ$i6xfiOlKJu@pI>>vrytjpzKEYLse%N$Xj+eQs-vWUtiYuP? z1gPE%@scufLEQX~KSM}#@K$uwh@4L`P>bFOlsu|)(Uy5VBX6XzDc--i)jBh{4P`kh z_Hj&aJ-}A=tbFEYx?6jAcD%7P7dtpJaL%w*vfbdjk3Frp_EI?D`VojeL_^#qZg|CC zVIr&kfy{qdA1)x`PkphJ4*>diZm(33hZxEF5pPo7W**S0IK9jYJDSA@-PNa*+dVRv zUd_o|)#%6JCMkq;Mvg>01Yd7qgW5k7WaD4K7U$IDzw;%=c}0*&MC}gR|BA1O)ItFc zSR4b6c3JEmuINUMp{sK`Zp9(-B}ad^Wax6Hy<^tsPMtSWpiR8(T{YGf!$TIZl{L|? zM`XHzr%aplKgj(|5!NOki5k>pTer=~7;`=NF7;YCgKvt{xYgG{ z`$R|wy&mI5d!I{;HvnCJr}D6XvF=_-tm}N=h7|wOtDGOF>)c4i_0qJ4?Tc!8t7M&) z4Jl>#w6YTHwJTLtUQgC{9*QD}vm7epuj}{urn1gjZWhXxb+3d0^|&Mc!oM z=3~%dA+_Jg#~hRL3FfSn*j+BV>BW*46wSu|0=HKRKK`;V#rHP{@JO0O(+^HbHO97KR0%6_?0Zvtd1nuuumR5PUXTXWJ09&(AhEH z_8)QZ%a#vEQghuLH(@=RMwtUg*_}WGOwMvB0s?=@_{Ya-5M6+ZT_ou@uP7yrqH)k*1}A@U83#-1 zGi~e${C$RV7k|G?J$GEjiv9|LxtK|Eo6l4M_k>yg1xEMX9RhkNV#&4fl+f0U;pe}- z9+rUC0#&R@D+DQMbtK3Qjz&VZXtHyckfy|qcwG5;LSVU2rY1_gbh;OgP%B>m{fg{6kF7&V3A6X zyC)*crXnyf6q0&qH<3j1mSLMP|@b(W9}fD`~}V1+~Fm29pA$SGAq3&` zyqQ9Y7DU$eE7~kNbrzd8ogF}xM?C`VFZ-+kok>u7%lmS68XfY&y{R;Pj&m_%Jh|Y- zizALo4kz2cTVQdEqWYgtThxOc1BlNr$QtRr!G=$q<+cyD5t(Oi4=csPXbE)FQzo9i zDe}NfY5i5=yI&^o1;8;!xVq#C!zwE(>W&N2Lz^2u()IES#@3Duo-QNL&xlD}HY|w_ z1@(0C;-*ItGdt$BLrC$?5VW|;(TN%Z*GfE3buFi8n@n2$&1iE|@NfW?eQmG`R z+dK;cdpT8#4H-A$!(W7S{wDMCDntM|=+FPd9xM(2p^U54Bq?*z z%BVSmvN*Q)Iul=A&wG8W|8sXxDz+!#7h><%?p?;^FRyMGqShg*9z7S)jWM9Ea~1 zax8|vmg>go*|3gTj$_5+pUbm&AKu|RM6WnW{&L@Z8F#N0$%rf!kQVHu#tSC!bG*Qt6EB{k+xjI0yRE$!epPV!} zT~$q7xTJ3Gvk*ucT$K1XJ1u{MmBZGKl{3Ujzqu>Yn$Pg}$|Az!y;Qe}CcGt%yo^ME z#=eMRI62*giox~D(PG0_{M`Z$1IW~v(dl>(AbdqW@%&iX$gXapP#OHSpk%nXWY{_n zKs1e~w1q>V}hL4d!bEoGm@sNeJK&WKM`LPKgmnBzC^)aWRTCD@U)foYFMrB)>94{Pz?)qS%qY!hD{mOA_7Ci6z(mBpBC-x2e=NP#@>@v*Z zy}?U~vu`r#aR%ELKyL1nBH^C6OSVct+X?5RmHIkBoO6+Z_XEM%b4tq<({~f?lB)N^ z9dE1S!kfmBYbRw>RzxfKPHei~f2jcX`!w9lMUM zgXc6Bx!+w=M(Llhb5#U-Bo2}fjObYM)SL0tj~XqHY~Sm(^CEo&l=~lxsTgt#Jexlh z&y#g|@B@kGb-r-@4J~3vq!)`zD_E4-T!5eZUYOtO(depIUb?4=05b`N3hvH8G??2R zkevoy4rYlD8 z;_u39BiK{X52-6mgL*rtivoSWY4sa&*tcGTboK@Ssnef(96Mb~L(Wzt*T>ffGFBg^ z-0Nlj)^6kUb+>L9xK*7AT5Ud0Ew>!R7BvnEZR~)2Wkv>28W6eTO1KMgI5l5^ji1oI zcUkryI>qVNIHas`;PZrs$%i)`6}`U5F4){_B!-l|hE)nO4f{s>hd`pFsy&Y$r!bJY zqHWTHvT1QZ9r|!4!(+6=h99jq6Cl&nx!7}C70`HH++<(-NitS0J6@?u8`AL3n|G&% zlG}D5T%dkE*V6Av-+WUxD9cACF6IM$(~#R)UL#1LpQ7@Yc*B`RZhj zJnt6W>w)(&MXuj`xonIDs8U`u+yHHklChQa>O`)+TM&{^FbotS_Vsb7uI&89B+pcF zEi_~8bn0GC#VL?PjG#5K0cjNHrRA)jRp-<3)HvI|pNH+!F%WI=y~? zydtZ5{tsRF{1x($8*-r+a`!gKNAfn*ZeEUJlxT$zHBb&&N5)56C=}> zEj13}q|V7xs^MHTsRzOevfohl4+4aI#;S{4S^6**q@6(Gi2!nMpg~mBRkr1 zZ?0*F*V42{AVhd%Y`6jf9eVBgkhCE!lP+(o%B^kc%-y|=`fv5eFM-}L=iAKsM--K< zCdmR)r^H^_+{iFcNI5h`Y_#|m&ucU36iu_MH~>5Q_PX>r3Jo+W)2O%a+(hPNvw~F8 zynMBfjHL@o#>_W0MEQ|e=P5l3LG@R_GLvV1x*C>Zt`Uvp$#|k`DBk7MAATl@aV;jz zDa3}d2#zU^FNc4WkwVMf>b#$`NJf_%dsn#lWK+~oO-&*EDjRZ z$}^t{iw%OnCK&qnI&rXFa5h$7b-J7%b>{h9=iv%DhA_Nm8MqSe^FJIa9)DZ0{sPH> zM^;9vT(oFJ?Wa4w1-_i_Dr}xz0=Bo7naN-#g7!(*S(P}Te%O_i3%{D(-|-jPf4a`! z*xH}5JGPdl!WoEM3w*^P+s@gF%vEzw_m>b+)ZbwO{{B`+5^0r%F`gzI+9x0jx8)c4 z{8?H8>|9(cKlCwxx;SsG$X|eUNA&*h(EM#?2_{BxH)4yiF==uZstZ9k@!ba|#)Vsg zldv@vL=M~4v-4K3hwB~#eXT%W4zWsO1lT}0@}Q=AN1AjhRiv^-Qg*TIrM_e*p*k3R zxnW*uPv#fSdAeQ8`8-z>wqE*cpeU)!lPM{CnvyF@`zLQEBesc3gp zfn|PY|9B!@0&9~VPCcsTyN#jg&znMY?9(z7!AlEdc*Ay1CEhP^VklMoH0=Ayd<@ax zj!Ndc&rwv{tx2jat*>iGJ%B6SY6?zkk^UCAoTPXVjXgN`_JC@#idI(6@{b5ZJ=+&U z8b%fQp{BOTVD()#Bg^3C>f;ryols=Ki|S;`30qArq%#+%o&;5e?;5M8EhR%4@3tn9 zp5UZG-P^>ilip3L%(yO}p!y<&p!3;#r5)r-vBt2jkINY|t}mK@kv?i%t2PPCJZ3nY zbddkE7KVgZY|~mXutZKSVeLnD2A-2LEK?3N)VVE99V$IBnWQiOAd#R|R8qv8!%=V- ziw8teFT1lnFvR5#^c0^`wk9I#kE$l|q6kRw3K{OA=1yYA9WrM)s@KLTCT zJ4-y9Lz6&Ve47Dm)%A>g-tf3sRORar#T;Bn3-=wf#LBwNj;idx@LmtsY58lZ#4xh` z!tKrg?m3Ot!0c!8uiUtcUDAjUaWekQz9n*`Dr}mGrDbC3s*pq1jOS-pO>~R$yK<*V zib}gP1JfO24d8_p<{RUI<0OCgDGJ*TDuu~B-ez3pBYI=Yo_?Fp#J$QEL)J8&aK)t9 z?XwaW2`P*h*DvN;pAQsb8&3mk%&fe>oGfiq0&Cq&tkuo0ULndB&XwC8C73fp!$xiv z6@M)6&>pQ->2naN5N>{6FIHE@hU4j`1UtN7aFENU$iQtT6%M)SdTY|KtoF}iXL~;X zY^uaLkjoR|*e0pW**EJJ;Y$ysyOqq8wjz^N+2?%$nxT5SE`^=rfqEhhb8j7V(+bTVeD;1`Mb&PMUe`k`uv zR9Swe9l7CUHTg!#h4UMcl>O~nFmZMaQ{5gzA572jL4asU?r>|DohwAgp}T=X(}cL1 zsyBwz=X-2pz85HI42!5pKlZGYO|THf1c9)@&GS?rr9ydob?}m3Wim!Fu(9N91aBL6 zHn{SuFs8q|E$D9k88E1ml@{yTfpA}?%?ggn2w}%5At~{0lusG~`%2EVJWn$6OCHV> zF@S!uX!xu7dsT3k=7dAzU8#$f;kdG9UY|=LzHbglWT|VEY%M)jvv=!61ibhZu2M;2 zp)Lb?bFMl8>qv{NBQPLUA&1rREZancZyop9R4kUN4j&Qq(%F!*d-QzhG?Ia!@Fgq> zNO};Gj%tU7{y6rN{ozqz?d{`V{1=Fiw^IqXjYvL~spUA>Dtl)T-F#2z2cQ6Do4Vy} zT(gQnOFO$lxq=f$m1{cpG8vR-%H!1BCRxc`J8I3~PoiddE)@`%1EN6Xall?(e%{Bkc(#Xo=q6f;4~IkLNi!bA^_s>ziWiR=5@xH?8uAhvZ-@+oEqpWubf( zs?w5iDw9DCx0kcp{7TXr*OtS2mdoJ?$#Fl;-{R;HDjmHhWK)k zgUlHiESWemRr8MK+ZHF?0e*!-hGO3q{Rzie#cws=Z(Z5nk|b|cBi89MitQ{YW=?3A zodve%nJHA+cYUEW^6syu?;=C_M1b)9t|<bWUAxcM%0S079j65?fGU7|uXkKunyNXIWcqsBqM~G>ulMaH;Z2qSE`jGZOAy zlhXC$cRVTK6q?UMx3*j+#t?F#QAG6y zImmn59M0Sn^dd`DP1cH+tN({U;Q$c8P`EVLj|}?Fz5To5w-ZC`&!m_aYrp-h+ttL| z>xs{ejyHGfz}%jyN`!%LWD7p)S)|#o3zLj+ILVYvDAOgH)8JH8F(7{V3*UP}q4e*u z@$qEch(oq$sW#co_-I75jfc_-DE7)Ur<_<@Erc}l9258f^)x5!$r=LhUbjF*_4`uZ z9}4jzRhUM>lWFj>%nDKd9%MlOZs&(%@3&w~JPZ#5u53RRG8uSvfL>#%C04s4v>doY zGolv2tXkRUHg4uQscp{|RC06@+*ViwI@*$E(BsTM*hXXq?_PTIS@mv2*xe?V*W@j~i70-%V925D%hqqT7~Vq#xIZy?|A~(VTq!j1F!3Y+s-CNNgZ>QlY!&Lq@Jz;|9&@ zY8dKFr%SBiwh6btY3i`R(u-myD#8Fjn~zu{6{YufrWNT-N}#Z}Yj=n^3k>{K^r|=a zV|hux|&I!H<+Em z5O4tU#!4A`9I0Q)&#!;rX-L;J*UW^QXRLQ_J!pN%5awaVTzp$(;A1-9N3u9JS8V6S zyby9~V^hlgYe%*4Bw}O~1(31Zmr-cD*Q*Ja#^AGUdzsxOjXJ{YBBXaWfxfrB{)2Fu?xr&US!-UhtD!FpY^BatofhQs+@)Xq^8gM z+taHpYXg?78~a&lEGnruzp+Pc)WwQ%m-dX0JDoCEvzFAzx;zC>kErJG=FFgA%#03@(8djdrJHTcXB*8>;Zje}()JH;_&LkL|} z?-?5*x>PJ3WW7hL-xp6P5J|QT{|)adv<9D91LA!}_<_GN!U|oMkwrdJxw}%g4zlFZFD7a?{?aZu`=Pbh?CtXI*Rg zp+jVD5gPUIV4lzZ;Wn+oa1ChQDbHN~I(C6Y%>Rlodc+x_`Toebpa`k9Z&bN#^rT3l zY*t1yFT7k*?}G@U$EnfcwcL!9naFKS&DY}b)7=DP5y`0jZwv2YcjkaO7=Zqc;*bB{ z{&UpWonCxq17?h``XqVLt{6w*3k#i2VfWtTG0ANyOOHlI>C28i6%G*ob*lou(y-*C z23M!JY#WAeU+hvgot~~2s^GQBsx>W&HLklqa|9mqkX%7xjIK6R@m7L9JZ$8v&K)dr z7$*|0$!nDx+PIL#Nd2bjhk^_?^WLnt4v4soY{`95yO z!8@U4*p(z~3quFeA+ivcQM*D>=mX37h9-`rN~shrYooh4_na1r^F&u1L&1hGS?#IQ z`FS6!Y-}ymiyOWnz`_$q3vDvQk^Mt8xn-~LouP{4e{_Vq=#QukE^)fPwzQdRSwePt z19bh!hbwBSBBfV^7YkFOr%%p z^LKlQl>=Q+@}v+D&?1)sP z$^FtEhA7+&ox^d|GxeJR1>WYxJ*XkZ^F@GW`2l|OMSjvgWLZ?#0i+Fd0K%+4Lzgoo zkTN}&9URTYF|7ALazch=%)?1Zu?;y>ZCws z&H3S>+j_^G!*BO;!O@Fj^8nX(&t690dIy^E$8$caeRbKF1j5yw=gBTuD7Y|6N^V|X z0x)T-gqnz)3PpKF17|9Wct4gH=^v<79tx8|*NK=1oSl0K_m(t3#fJY7!z2};><11G zc4mfN)**eGzN$+QjW3GZCYMi6);NCsrdJjaF02kx#of|a1n}z<&gQ_Rlw+=!zgmRG z;bwTh&~@&Fj5FK6Q}K`WhS~Q9FVf?$(VtAzdO7So0awo2t#F9_94}dUaDK6OtnB3K zLi;;V^~)iFy|(oZ<>1~8A)VR=zOSDfcLR`JLS^bj9ZO45g(;g*xV$%mf3J!M1|`VY z$6+L_gHcvp+eF(sL*jZ$pE4o$PLzT`!;7l3nS#PS&+-$2`ID%?)P9L9@!g9%jPOUL z6$HO;9Yn58%Gl>9QZQjC7j7T7g`=5ArJhzKLY!Nm*IFZK3B#j>zBm1n$Be zS@~S~R6c&a#_5Zv#DYkM7^Qq#em{K<^7iiJb=J21w=xc{UwQb1O$^Y9w4k&hj+Ms# zeI@?Yr+?-8CE8IP&+q;Jsu-W?K6XKzF(g;zoJopmPzVd2V&ryT)RwoohEJx_ZK~Pv zhDlq6)2-9evU80u7ax!kwFsDoReWp|r-F{~0@|W=L_USkWA3a2eb{vSrfq=xW=gm9 zY$THJW<<^YOFP70z?-aB!~)DW=X|%f7+tFs}PvX!NsfS!zJF{yHz?1%fRb13rsE<`Wfwkp5f0 zRJqnyv?>RgRYOQy{+;CIge}^v1F4->IEpH-&?v}Od4SrLM#YueW<_~CrdbdQ@e8?M zZdq5@cAG`Kn!kIS?X$X$K7!&zVSB1#mo$jiDk?$h)t}kKjGk@dpHFOS^)oIuPxPPW zC4qf~`gN>|1GbMW-GEg2j8jj}Y`!*xPn3;R4J$_PE+D$Z#6c!z-ejc#XEyKXoo5Z>+q@vig=og!G~&x~ZK z7=2!a-9z00+0=r9gs9(UqGaJi&IJ9cR6%m&*rY1U)ktfzEkS+Ms&)U;m_X$% z{^2=$Wm~2n?Lbvg&DRXOt7IV*%d2 z>R{dya_QWoBmDcfU*(L&B)fqp9N8(L;v!d)_fo<9ZdV#W_-XIk{irjHQgGw6b&qa( zK098>{5_TjHG+LxLNH0$Y-GweaL=Nm5^N)cgL9SDqBoo8(ql;}D& z=>^#x1N1YE$drYYG@ka{{)UsE%i)|-ogaFCvsO3Yy8J_@s)EhJH9%V@S$Pxi;4q!8 zkLmzh73WvY+!o84@zs~>SGXXb)F7W1?Fp$LF6(atqAc0+crgw%=wRi(r z6^B35Gfy(u2SutyyELOPompav$oqNDxmPyLtQ zkF3*$XMekn3~J;A#H&-MK}R4f=WfE{lygexgvz9BJV(cvDo9%>$Oa=JqP)`e^Kf%= z8g=}x6_c?J@uKXAVa9N2Y||1>=nGckgFhcNTD-=u>?@v-V&GE4f(ebxzJmcj@cZ;Q z%9-~GuYCVud!b8psxU|FEP+-Ch_R_3r*-A9#Mh(3M2qa6w%S5YXDRZD0q&KJnlbo|*&pdouIeI#B8VQk5XYf`?U}iTV}tcNdSH_@cc!Y;XqHyDyH~t6QQt47QJTKI;s$yk69xr5$k0PD{st^8v#^=a|tB=HJ_645_&f?`tVTl zn1#glc*w{H#Rk#=W1>8^)Hyc`uKlxOqQ6W#4hxW}NySeX-TP?WexdM+U5HhgbD&;{ zUk%V?O5%b7?OLjcBP_be^Ao7A7n*WHfR4M^yCdjHR+RG_nZqrz{k8;vaIMyyR$u)U zmP!scZh5|2;Mm}K7(7!#M_D!v+cz6GAKk=K;u3&FZs_t43QOnnj#l!1=jKN2ivmjy znFb8s{GJNj?b5d_s-GWHsHI3?j#~l3!~IPhnX|+M<4A=J8Ucpdy6VHd$86k0OvHR! zi0+PnKl_Y22J8fwNP4isqdT*R>jKI7juTfUeIbIVi!n_&?$pH94z{S+q8syY+QNSE zHl-%UA{k3>Nsr(#XMoIM1oRBApbp9*Xa9pnE zKWk)8=}U1C@VZwKn==P=zw z=U+F`(mc0d+LUK-5qyUA1dkbT9{p0KpQ7C`ixjUFRRp=&d7Bz)s!q#v074ZZuY z`b<OnkdrPf3(qXTQa5IfnRZ8g{#kRNI$ZExmivV1!7hq*>6X#$9BO}4{N0E~RmY{> z<}^oHTj*}#<5!6P;KZxj1j)+4=HV-6ZElR%Y(XF^Cgjb@f_lKk;WBcLZSCcL4$0`_WRXez%lO z{F+ie6q_QYNNr@5P->|*S$WcIZ9feEjwCGk0Vtp&XV+6BQ$9G7g9s0-hd3}j+ZozR zx~8kb5xmTF0)*TLS2g8bI5r-@VD3%@hshT=lsQPEhk^i;8i+%{`-NrUU$FMr9fP+? z$*6;zea)fV6~;Q4o+ZSKaXS%vlsX!=QGKxYB%*DZd5g0ykz@=;6%!-Bbs-C+3)J(n z`To85+VI7Dw5y1=c4yM7z;VLGVp&7|?S_6#T!AE)gC~FPt@MILSn3>>F7Pqu=@Lyl z>a}nqUz)Vl>Yng`^PM&RriCVX?C3U4J|s)UU)h>bur>&pfmi!#5%RGEeoYUG3k$Pl zWNzfy4y!B}&(tygiHSM5y~hENms9;zz-h((IGP>I*RjsaszyJ1h!@nT}I zubl$#VWwy|QW2?K%W7O;xA}Z5DG_yGss#z?5NhiTQj~R=!d@1$>Zv&(s1s=S$viiy z`IuoXAOm{qdbc1C^LA^ac7+Lu#yQstVKn-2nZss(Z|wS;F7tW8orlK{KRly<&=$nd z=8ECU9535oSokU{}xDcYG_D*lzEc+%wvd|+VFTgDf(X#);7d$F!G zglya{Nx1ze+xd2I-s}Ci`mkooxMQBGq%pm(Cgc`;8L*orgi+bD&8H-#V8oV;w-N{| zIb~!{7izU3JVEYSgQA*=E96dz{=w91biEv3sD-WOj$ed~v;(y9S+f6hM*8-{H0p)r z%7rq#y*DhxfA4n@?ya^EY)1_?rJZ?eSvDr2(H+$j7A94+RyF@o;ckn5ZI$89678#J z46AF;;7&OG<5;3mx4*5$K*L3ZVb-QR2g?>-OsVksKLcK(aRe$dTdQ&Hz-+=Dx(YoF zn*pW{PK}RgXiO_}x7iMg(ukAatRxC#fQ>9I`fFLm{C%V}fA>~VT8?zzQX9Ka3wPKl z`Dc|0OzJFn9cl>%78rrah}IXURa*GfbWMiXtd`<6rO;h&6Aktg7py94>I@9rJa!wW z!Ns79zPf*GrNk%P8;=QUk!v|Rcn_lP^y=apSHnBvg#nFW zyc;F{Sodb{n`)2Gxt&A3hp8fBlG468B%69)uYAp|eDw%sr(P2QQDg5!F|GQlEQ z^i5&S1==@CD%8X6k43{C_-zny(L%^ZZK^l6t0|FVW*m7iJ_ft*joM%^z&jDThZ){7 zb9?xEZns0v`L`jZZ^@6Yx?Za;5Y&J_d+}}(%cp=ezH3L0EU)sr3Q$2#1VrM-oG}?a zc%+MGL*run{}QhpxP>5+L=6_p;@>VZ2`ADxjjpoOYO@uV4>JlOoFR5T^oM@-=E3vg zT<+F5amTOIZTSKTi~X$@?S&A2TSX2prBZ-jgrDQY;u^MRU;UIxhw4!dNY4%qgh-d^ zaSV8Geonf^K`grBU3_}|%j_-cdc%fQ5R($Zmb+%Q@h;rw|7ZaobCF*Oh#f>8dz8iu zFY}6q6>lGhx`gM4Ows)ChH0guF+E`DpzGa{yMo^9DvWnAQWVLw9`oq}Jxs!|pcLpWSUDT%lC^iO4@v~e^|f>3zW zf2TJ!5(ToOwOeU)KI7mylptQs#9zx+@zeDu7VMQ%rTaN<0G>5I-7#?_eG&!p zP#pY&$&HaDEA$jn)GO$+9bIEpMKA}+$%45#H-vsv)tQa#U?1}7Z%+i5<$pVGw_Ckx za}jNQwHQy;yl7-EC&3b{Cfuv9`w2OJ4$s_2A0Pb7_6ik!1eej5(6=sz^(k7Sx@#!t z*^0C~Qrk5`1w~2r!d`qZEaV+`eVO7hBNN~|flUybaVfgME2*eN2)L8K z8`CRLb^lgVnD8zBm%~sVf_Lp*0kJUuSTgR~UXvV6Z6J+VQ~~Q(Nz=_pTOAiSl|a(? zm=?ciN@S{yigT@-d(6hs=OVOxv zasCSJZO2b+A+ya?OM$e767lUyx>^HB1mCsszw}$Oxe#rPyiI6)^yp_Sg&M=YG(I%e zd96J%C+F?nNf0LAc-FC2Ix_+CG3uz>J-VtCHLRElS4wznLYcgz4nsNl6ix;Hx74@XN`Q}HqeCJ z46>2I7~xVT%ykX~&%fjxP=#k`Fqu=O-`N~Jd{oG>9=Hr-=n;Q9g`o@v8x z%#6DA3`{D-Cq6H+dg7?UbpsDa3lEi~JYaF)M^;^iC^MWE4WILWf6r{D<#Gw`t%f_P zb;b>QZxH_Ei|BP#QMql%KffmTzit+@SiC?UXaEb=*G$aus~(g_A%B%;*D6*?IYae} z65^&!X;L!0D5~SWpe)F5Nr@u;-AFy5p>fnG)@v1Y`;zs%5?r(Sy^eqRC1M3W!mJA` z&lKV?s!3~U;)-c5PV}~~67uJVPYSQo4n7%uQSt!%oWMrDK7R_@Y)*pHC64T0H;%IN z_797UBD~=(|GI2A#KIwHTXf!R=BVdZ9p$qBUky5Xi=5zd{+syUpZ^ElH}0Pfm%uI) zung$kj&{5lC2gGAt{(c_`$P{c)TT1$TE1x(kx2dv=Bs#MX~+c zMHBebV<6bHwfm(}Yz(&UZ2({;w%J&0KWW(yEcw4-K}`Rd0PFvZ6r{JSQvbUrDVZDi z%IE*w!-}*0`NHV`zWM)t^nbMY|Cda4eL0v?Hj6VN6BD)N*+tyVV4Oj9NlA-{Su4L+ zl$3l82*??mNR>dmgVwS5}n0YXVRj^j2<$y=xDO8?5|@DJdz>c)p2Fe%uPd z?>ELAywE8AODI^QU3ybT-!Pptc;NtFR&EA-$b0VMZV+* zUNMJDnuS<2^$T_iR2W)^ZR_y zO8I$8&b25;+`VU*KGUN-w(o2YhBd-z4X@IGy*#ue$H6>mbr}QV??Q~>LY3}dQN<^I z6Ns@-p4@qrr;k$nCT^ZQ?}%Z9hm>9MoQk#jN9EXM`4jO~OVF}cJ0L>kOgySy^9EqQ zCn9FBU|31E5Dw;SxukfjUR|EC---McU*Q3lt>R~dA(UFTsW`RwjJJS5`TP|ArdG*% zqhZgZ7x&Y|gDVrdKBKN*Nod55epof#CrhUjW>Kg27m-Tid{?E$IIO}<_utuI?1mJ+ zvr9%GrU#!L!$%*F1k{<_U2ZbZ5WEHk{k=SoEc;w*&fH;Rr|c<`T+Gy}ra#%Nsi**p&3xiCWsl!`M5lz&*gBQjUS8ml!Q<6*bB&Uiog&y@kZf7PO76nCCe3F%x z^XyJ39DY7#FPv|1Vqw+!|3Qon3j?uaK$^b&wVYN^Ht$}{5EYB_wav}@K*{Ng8dM1) zZx{G>Z)KHRJXKX3~(NP1vxNcTfFK;aV)mDc#0eHX{@dxu{FYULwN4f-5y7Erha!!2ZNw-q3NX?A4X_e>cclE&vEO6 zheK3S;?GNKF)cO<-p5=r$=KLp(HN1V?y|BU7vc14G9czuXzS@iH>mKNglYeFaqcPg zN51G4ZxceK9}Viiy|m2;k-8UO3^jeb4#wB@JkIOaN! zf(HRNUY74P!1&bERTDGM@1?$r7|3sKoU%#p^I_RhusT5domW5}omgBPcE_IY7PN+O6zblqY3s1a0pGT{k)zxRcd36{0)}%ekpZtu0kHE(F5X7`u-YGL^<} zEAFpj>M$0Kj05gvD?{X($XZ>W_-Cwx+&ORTO?qmYU-dL=nKfxcV&OY7B=-`&BVi}- z0>U%+HGIJhKiAzscKgOBuA9Nc#4$>4nF{f}RF>D7&OH^jbYov+c4uoMN8_o{F_YA8 z^vpcor7K~9o8w#U8SY28v4m#DE^^)v!|ea~l>44F6>%AMLh^s!8Vcc!@L>VqH@EEM zFhWjC@@aS(8x-6(w_XJD0Z*KxN3V=pI3c8BUOU~qz`-wW6nREE? zy*}}*8TT{!%Pk;gZ%+rg6zlJ~PYgtx%627Z5=g25MAo>U7@zYIEas7v!97Xsy zBYhe9JFJ+-mdMd{rFQ%K$zuwEPpQXEX{S$r@a}E}Q?I<=ITvM9E=gY2r%*!r8IPEf>elrrcy9cj; zuuB|ruRbyeVOFX%`MBUVV&3K(V0G3od|HaY*bk|><)4$>SjzyN9PDSECJD<=G?Mp| zFUwAxMmy*a{;?wdI{u(T{`)HDJ=sW-QMLa;o@VFOjH(eRr>!B} z0cDI6pul{~oP)5UrgNC(p^3Pq@2~Mlui(3*bl=e}2Zh5kLrU}HX|)x#O|#)m$?Y{1 z>E8!Qrs@1mzZIOZdqO+^7<2vV>Rr>)i}Cy8=XkG-acIwrU5acopY&^gY~ZdW?}`_T z1!J_lfPKHm^L6F{%>q+2nCYOBH0bO;8TGSe;f(y&^XE!BGRfS&}U$ z$18r>juLo~@8b{zf#&JYRp%g%ppsRJ@Zf$1;wP;$d9E4j$}dsjO@h4}U)I|$>nTR& zL9Rw7b@6V(fU1Xl$37j|0G|pqtnl`huJc7I|(Yvns=B}Y%^;I zXzJ(EZtIF%9F!&9r%ojl_|2FMbEB;lObL=k6k`}&T5`Kx`>JcrO^dN3koO#O82r3! zB$>s;hNebpQcHk`;1J}l zhL?i)X~xf%2=!2`+I-CbE=>vpZXY^=?CdDqv4DA&?TojRWv>lUg?+jQMt2ZrufBV0 zID6h9e6X9j96cNMIr1;=sxm-$fk_^lLDf@yVyz)5xk;P*Y!`0w&Ww+9`WQRfNNy&U z^LGyK^oIeoB{n->FOWIXO&iLY9QokY(r6SjQF*>s+Bta-G9t=B?U`NNZr@Xwm`ID| z!)ZBLbK`eGYpAP{3_UXG;ZO?O*WK%I=WL5xYg%eo8dEz^&>(G^bqX+wX*daz=hIorcDUeauq)PcNlpy&2;Tlj!&US5rJkZ;bO4Ybwh zn8Nx|Dae^TYs(f|OXWckHc?j^6hUJSFxK0r@n;q@3*zNA%mcRWwF@i@Fjt#XocnM6 zu566D$Ropv0c#d-5x+3$5g3u$_kiIB5Wa`oaF@UEx#6~4O<5cs^bQ8y0j}JUpYM!h zW)X#lDX@&F3!$_eP~CgHegaOJvuVx!_>Ia33EqfRFCYCz3-_%7YVt_D$(ahrlr@?K-P# z``#o^Q)Ulju*w)AbO~cmblgR;1ny#N9w|vAE^D~F{0_HS>pW*09e@G~ z9+t`TOFt^_Z5na!`p1mxT^j6$v4v++@2ry9zh=Ch(Dyz3Z6<+u)uV4KpsQ%}(xbXM zUPnuDihpV)sq6H zc+Ug%yoN|8gYSb4)k{mT`n4t2cp`eD^O_cJL%MpG#M-=~+u3H`PdQv44;o~}m2+%- z`DFKU3&v(lNte;Z8riDH{e(Mt;icF*awnIjK!T)IR;8Vmu2P?V`|BQ)9+45HnLUVo z@w`|4(zpGN=978-huU=3-MtS#)(XHC(EZ~eUn7GVuidfY4dRR6ex(FLd5;SOa2_V+VPtfxa-iGJP)$Er2D>OMApcPM`cDHfwR7E){G@O1cdqxy>=N0DF@$ndR zr_DA>n=JEJlSrU@9VS!~?@CGNN+SYNW@Jt)H3F|^xgqvQ5KifCItc++(!iBK$MfdK zksMFvtAoz^=$^0ptD2UKXA;o9or@(Ea6_<$KZh_YKX)ZZ2wQfXJSH2vnLnnxuwXbP z=-|#IZL)_on0g(;R30q4F1}8tyk;3X%1#Ua{foPCIow;~+nGK3BgG%uN=Dg@Ddk|Bl0GopzHyOYP|ZaSB`~5ScC?SXG72R=(Yt;bVEWdzVgY3 z4g{XBS~U49g43RXlQLMT00@77HL%GC82gQ%V;CuK!G_R0U{50YaB+w7BpKWetMKi(m8cjNYmSZT3-zKVaESBZcFJ{#nuUBm0u1 z@?iJ%qc$N}iX{#vBnvsDy>a~>q8RY1;m85lgaJOiZ2FqR)L#mXRjDaS=p1{!M8&lb z8l=H;OkH1s`gGf>Swg2@9zfN+F~m&)Q>}8kSiXWzk6omvRYwQB0@&w1xWpghpa{Zv z)YR9qy;f>H*JrGZ@X*<`;}?xm0Lx?4OLRDu&^a*^MV9cY%gLe)`ekx2!|BP<+7cH- zj2@du-4`n%(t^W=rWmOH*Z9<76r^;2*mNTvGUT+Jqu)I!26c`pnKjtw8)(bGZvEQr zi%(p~+u@AhF9|^_HCGl2&ql$fkg{E@Pi;-}_mKuMZKM{roq7o>C9S3XbbgkaL;n?? zHa^$n7@^1r*B{@%*koFr3Xzt~)pU-J`9kIa*{wUPR_|8YWhmu;F`oG&*(S3>L73{OOXn z$4I5C7{PU)TmgGdt!?~H2P<)Z>`A<3k(l?$R5oE?f#{Z)zloH#Je}b1i_bzonTG> zp{D7cjPVe|P8eQHjT-}bN$jdTnNPKJc#E#*7ADc#nVhvdkxC~_mF-Ivc>_Q^0qXOS`CEKbtu{ zvAHu&P;79xRYBNcA<2fn@8!(R=Uz_b5 z?pnr>G-JMb{mQ4ws45FS14G>M%BP9&w?PNRElbg8+Txd}JSTQ6(LL6FtlA%zWS6e! zmv=g5njSyHIdSG0X@dJaQ8Nb_>>!GFZ(b(@z>nz3a7;0!-}Hvhi_4KHB)(b9*_i=mF#@$`K0xb885HFNA-viW64?$_m^@DAsq5BD3#5 zakdTYNway#_s+HU7&v>Z4bSCq-CwRn(HlD~$>UI$Ul_pKJtu_IgG}L6@C2^V;Dgf^ zRUG8P$~{q$Ox~q=c-t6j$R!fH5R`D%VxR2@-$0_meOrB=iG+9X&$;5ZMuzpGdyj~~ zN?q2(U$7d~ezdmU8C3cNXNBisLHrMXS#*ITb6d@K#~aU={>m*JhmrZu6OtBse_p|@ zU?*85T4~nExS@}%s3~a4w7FGpI-EDCa zJ`ixQa}@C^6r%sta?>J7M#?o^oF!oS&wEfBGdiubpNBk0SRW^q5q3*;!lc6hfLL_|H((LgA?H~kkll=wGd*p|_k+_?C+{AN#6Y;0R zxeI+}o#y*=-KWQrn->AYq|B%-eZgJeuDyoDF=tm3vy3?$xP1RNxc&hUi)v^Son}@k zNsm#;%1zN5-cOx7C?x*IbERghy&wB>c(<>1N|R|#%mhi(FGV`%)}e8(bx1v&?gCK; zG3yCW-AhoZ6wfnElhjSLFOgbb*sS!g$B}Xo9V!%>e>8P23LWQ8T(gm8-cjt<46EWj zLmu$a>!|Q-9xigizdXK9@^p^v^#0&!RlkWMpi)s z_;80SkMk6L4))|Tggk{Sj4``uX|_lHXAO%n|JZ`1ja?Cqt0%p}TIW`b2|P#M<;M_g ztK*W#7C-Qt12yZ;mukhR`!!lCJ6AG+UlvqYx;blb>q{DKi0wA8i-2)n5vSKO1^A(7 z5tU$#iGH7>kCZdndrzHQn0W1}&?g<>H&DA-yMY8j`7hLdQ?K%@Tx&uMFb;AenT0Q6 znQwgnQr7C}T#Br(1SUGUhd}c&94BlFt*<_(82|J%NqF@oFf$rt;*91I!iNOoiw5a9 zZ~kOMCs0Tb8bljTXxUgedcth-9@!aeisWF?s>=TFSJe&uvwQS|Xp(YjcTn-kZ)J}8 z&k=XrAAWPBpbzq*JJf-ajck~?2#YZ%>oJ%4&d6*+)cm+ws#O2@^|aD|g$m%fC2xNI z`;q{?)+YIaQ1@6VGjDU&bg>7+-RV)}LTKBB*iMS-KMdt2R5p0=8h&1KgJ{w$AH!GN zW(dHo@qOPAtkT%|tXJ95BhV0-5b%z+OTnBzfRz}l)i`l#=g+duK>;Q!fpWg6CWsD% zgS=V%$ljZ1ZXa2#%>bF}$AEi`o;nB!mE?afRrKGNI#Nq@P8aU}yNqkaikurB9T?%w z)l$4qcoz*~ULjfTL*O7LvKFWq^&gwapE;slKE8~Zp8>Vm?o*=!wy`g{~OJs|5$FQ z=v}cs=ff3}c)l+*TcnHe{q zz_4&s*78YR;8BHcltS*iX-v}p ziA5*mXFUWrn+H?4sIgJ7!(X@DEkTRznI{Ha^P$4V_xi{?kJm(2xqzpy9FuxhI)Q@S zA74O}*HKw43IC?@^@Z*TD3m7$-`y;n#GG!Inj*t^Le+WKY5tcBfbTuzoVhVRrw)p{ zw!R&Pv=3UIfA}XN6f$sB+hebFHoex|*mAtUYo`i)WyTIxo_mxA=Z3XSmVcLZrRnKNc+*?q3*>XL~-O$H$6jB68e|&)(UUTSVMAJ>#J?WR!^BuFAO0w+`~@7U#{irxwa?sTM*)n+N54P^tY&u` zlEy{Z^|)#~PA8-dR2su9RG?iX(gP1BvDmc!nRu>>mawp>f9QgnI+r32m-Tq&9-Vn= zHsb`>$6+&JFAs_@(YQFB~<9{jwvg5OMm%DHz0veD9 zmd=wslW;0*@I$5|Y;}6^^&0hAl3?JG(EB+Qi zBJzI9PrDJZE;Tqbce1j z&!vT3@85(g5H0juKX!zX^cxLV*YsOE{eLVPEfS9zUjglJFbV#b&3oT;!}A*4haS&C zqguiUD@@)HzED^I-}#5S;PwfGy@nKLWAnDxXoCg;z>VV@LR9=96nunUEB2A}?Z_|4 z{1qj^cNi3A0o&LirrXXoN1AYf7-t(tlvk!it4QoJ>%99M8GU$f-6gL}daMzfdBx+4KSu6UVvDW=p%#?9qXx_trYCr6zjJ$vVAw zPCCql_^2UML0xuTrMhi)UCgP$d-q7veXp!W$~OjsrnotV0ugl;@t)19DS5i^M-W$G zQiH1iDgQRxufsKBV!*ASH%X>wSsuaKJZ`W;{O-t?zgP9H{G{;M$=v+_;gont(q=y_0mkRzt9^ib)L@VDSLZ9R7-0r}$^*&+XTv7amT@}Q@;@ZXjW$-r zmjey?w~=fV5q{eSbOzq-&5mNwk?4xd$aJ`V@+Zx@TI0kY@?LdefiFZaH8zHf&>QM( zQUPW-uEQWbmb&H*u@yIFw$(L+oO7wITU!!_1lp^Azc@t# zNg+wcr42zb0RYQG{`6nxRm56s-Wx8p`9wPWKe)ra+h1$r4|f^xMfM|19v?S?AW$S% zLZo9Bj`2`$6)kQv^uQnJ)WGc5hQXJwn^%&d6Pb3oZpV~%0Af$KU67E%PY_mdUGRaX zszk?Q;r01++D~8LXU%sUQf0S*6ha=D;G1Kj(-@)yXhOsg zcO#(hA@Jgq9$i@rqe&EM7c|0?KzM`H?@^vTDYkWt>(OJgSe}{#+lJ|CkX!UL7w)ow zIi))i+d0TE3}CF5m$^v4=(+{ANtQgI&hKkE!I1udX@N>bMzM2uF^~~oaor6Je6ph& zZ~m~Bdgv-8Nh|j69Nwc*Q6v-e528<4c(L}}b6LB9?qicPGd~+#l^ZG~w0#EsTp6^C ztif>LQh5;d`P&YN5>F%U_-uf2en=D*P%3v*?;QTwn% zjiz@r5dQW!m^YSQ`cJ2#%z0Q(jDoYH|LB6OgeHw=Pyd@H;+zeWs9t2t0qSRRL; z(&fqAK)_+7M5X8Ds5@iZux3(bCKVgVEeDtFeH2>MXaU$4w!<_v7%787x`Lm z8@&*PH`dB=-uh04#EzNa*J22HOyh1(vjYi*2YeR0-Dy1ZHHKo7owD|kqN(pu>4&3u z@2i(WpHjSp)4Z?`gxli~;P6uN?^9EXHg8%iLThYpt(*L1)Ib8gu$rFmX2Q-ofMnN% zYQ3~0m}lqOZzqZRtTxufodR#92IIlMoLScVN9?MQ_T#q?Re-1#;ZN%G%GXEyGJ+eG zqQ-&d#&1>%h<}-*#VPS(!2{!ihC{>N8y<(wYjb$A`xGee9*3wCUyIIvvh@9&YXn&H zUMH0${qU%jd^QpNS_`oUL~&Ian(tSRIMdmCMzXqa2alB#Pm6<8v2TH8%{baHPtF>u$y($37)VWiI z1+Fr4i!8Fj=598Uo_MUzIz3g>v!mN9qAjn1MD)C+$}yjGbZmdrh?PKSK zo^DSK$MnvbLH!oc5;yB!#sq1w7X&0JBju6NS0i{CoTu~4&|;>%F3QxxS}>OJJuU44 ztIHgbc-diAo*p7dWCIfqfBmgRhEDtaQszh@JtCX%?YqR%Y z%G+X^clE#vPxx4^B^Mr;r}x%YtM*48t7`a@Y?6MwRP`0WVr~sYokB&$WIb1_?^d3p zr3kD{SQ}_D8WLzezJUv3)67s8Yn%mqOo%2tOsHxFTLYTXWsrmvKhfvYSEUhu0!&LE z(mbtZz8o=Q+p>S~nZC_m-p{V^-LM4Hbs2}hvx`=3v9rN4fPN`*S(LvXB3uh)><+-( z!jwDbG8NR4`qZe&bFt%;6&n?v*9&&9-3$uS#u6|GoSD#5d;v=^`K61<2W=$7H z1lt7%j3OZVCJo%WD-fIm748l;;s;}F+zUjx8@FjQM3oGiJupg*)!|N0CJ~At)R0GM zU?#dVT<nn@gxCiY*M0{qOPIr^BqxAjGkn^85oI7l}Z^~aqe+mPPVuZlo0?) z$na3uj(nNoMQnWZ)4_hJ)TOa?o8}_ng+G)Rhs5ZozCl~HH7!x|j@ZtiMzcf*eyRW;6*%FpE&M|@=?PRFH<4?T!N zLwt(sLw_iyzvhn5+ih=FDNNRMDuRM8rM+CieZCvoH|<$KWh%v#_nsqnGEYSGtdRCmj$H~o*umu zg7iRg{QAPQ-MQO`o1E+*6mM6MS^nf+aS)Vw>%C=(Dc*V(Apb(Zi!QKbAX_9p%d6G) zU{q3J{xxUr1S=CWJ?4vLPlA+|qV<8fin|i!*l_V>TSz6|J@RSCnp^Lr*W}v?!M$XaVEG&8`pRG7afauN1%c1Fc^{6*=sp3 z)n<;^9)a}d$S`1Layjf zH+I9P>kP>&5sa^BesDY3TI|VBeNRFou{A}^%2X(2vt7U2n4RH{J`FT6ZDwLR8L_8c zhL|m^XNCJD0^vx@z+TWYxf&7eryM!@r!gNeYEVb_s(3?3?Aoc1G+D*n$MoS~JnoqD zWk#0E_~o?sae;0NRb=p!O8E~f3u)Mh5vtvR0AIkf-3~otlQ0JrnWfhv4Yim+=AzYj zD_i%C&h6kkyyKA=^U8;n7q}_3QUVFT3^4RrL%X<ICR-}dm|Lt0h zH+AVV8+9)G#)Zb*TGx;cI-OYweY(gjdoedxaem~WP-?b@Pp^gxcZOLqsOuZzru|(7 zV>}b~kFqh}XHZ(A4qqJReqGvYYuH4paod#}{}F>_bo^d;n0Bu+^eq2P6Ws?-M#OV@ zmzCrW!?~!;Ox$p9D#@$PFuHh;JioInAgvs#*jg9aY*N*P~7Y zGry9g1Q;K8sF|_BkZfF*c?(PXvp}5Nj?-;;+|yDJ6jAl#nu57b{M(|Gwm0#J_tJ*5 z_4(@Q$DTgc+6ZX4LVuqZWr<8!z@*svIqsgvBecz<;4Y#l13FpiocJ$#u7799A*9V(*9nM32|{>y zYE?xz8(|e!Hl#%Y*X${cI76>zLTp-UQXQ2iu^0^_fIn|99^NeD>xNwm(I1S{(N2 zUm9&)K2bdodN{ntGt zr0$RWPV72}fKtuJ=5Sl$n=U$X#6`#t!=D+$!GIx z_FP|f=x(IZt55(e$UQnLliTUJi4?4hG`84F48=EZaT{Fc8+MOVEzIK!1$t882b=xM z*XW+4@tW_e&sCQaF|XD;(4^vhD{uEBYXpgRxQMaT@GOgEFSRV>H7tnXo?J#ydMWWu zvGqFWBw>up-LNaIZO==h0P{|KWS9J8!p8tB?xo&WO*pV-7h>ARyD*#qzS`kWKj-*6 z4f^EtA|%kX!qio;PmpwzIdMR+jHFxT1j02m@X8wrn)U^TT<%^`$`%rcV&N#|(qj;% zThV6L=j^x%t6p-Y^Ike97;N59V#a^4)|Ql{{V*YRZ$i9MAHh+`qux{_{RAU1`&;Um zLh;myp$CgLSogH@A!qLJ|w9UX;pr(>_pXPd6&COR=aVjk{$c}Siev$p$qAc^gwP-mq{3SUs59IdWYvv%QNVB#SSjJKP zCFA_;VjPK8CYN+&K`X`J|a3T%^XcIT4$TY7U1Z1qRW=NigG>93-`DDW+MB&J852q z;#~4;w>RAa)GU1lIE9m%dTw5`kj2-vxgjSsjLny?EF>ER0$ay(17E@j`|VzA|@6Xlr&r{c>^M&1Ub;cx4N5op57wfjj8oT%ICErJ*VA zisSYwFJ9K~a2SQDL7w;P8|)AF?S#-V4>}=8_-I9S$m-XfUB)4%HpTcDW%X=`+*5Ag ziO^EQlgoY}v3Ozpq_g9Dj&2gZOVzL2vFhqzIM=;GgdY_*d3KIoVx(LYq6zA>p{>Gs z#a2DZZYvt=D2&nQHUnXbGRzB4J~k2|W3o&x_u#uPhO6hX2z7xj%j~5(A&&_5dPT|j zX?i2@u!ZJHxvM;)NC_f}@QlKtO3?61r_G}jdf|ZmCqMu1zk#37Q77UX_|)sl0*BN7 za*Hl4NS#T#E$Vy2cHcRSJHRvcl-8Z$fp1rMjQF_iWb|(0jnIHlzHU|O{1S(tvd4sf zW5VpQ9;3GA1ZW)z@(C!gmQ*0yq9(O9{bno{hZ+O!g=8o8dt#}f(&=gnw;eR;sk;Uo z=7`Dx7i@fJq}OeNHmOBrPMqJa3F*n0Y+&dC_NiU}Wb7^o%{IF6c&51ZABp@fK0goU z*r_jwF;xDYZ>%kQbW9lDeh~fW#`UPkA!q!@dZTuz<6MrsFt3<2A$y1z>RGIoEQ87 zi@Yw;Tm_fM?e@slE7R^R&U_k5eY>xOXan*MdfcD+Mg4JC6}d?N)nqeP_PNU=h}Ws; z_u&{JezUCd>;-2q5%h)D+@VTfrH%d?aMw7g_xGHm%0=p zp8dF{CA4yi!h&Oc-8(m`IAwf=rBGBHdbW<504|}0BaNe&i7RoQA51^3b#feGWf<$o zI37zDFG1@`KbX&$iDBDDn#y-P+G+FoKE-kSb*cs0tT_&bBBz064n_rO8=Vj)nj0&0 zyc}}jEqEre>>5x&X+c>&FMs8FHr?JE8(4xrl7&>D{X?~y@uLrgMibfA99}|3-|G^X zonqIGF7~fAUkXDut@6rAnIRn(6=}Wd=tP+JI@Iw)<+RLP0i&HaMV5s;>S>J~O0nVF zygYM61-eH9^G*mG-Oa5PXyCkruW?1`vShtdc&+a29WPs!ahHujQm!Qs(K1Jr5#mI> zRz!8H^-Yz^U`n8Q_-5!_y#*lMAz>(4tyOvvzy}$BYnKK*X~Ctsg>7j!LWX%RJ252x zDAcGm6r;t~L`57GUHr9sA7DbDsh--5z@P7PiJ({g{T-O&v$GV@qoSweM8H0*X6#xL zuelEXOFDPn%R!7@WMLC059E3^$n@ua^!oY|o5@M_u#L$Q;_ILG5wT2^uLyJVp`DRo z2C+>**!a{G54@rxpINv3Yk4{6i(!a}yuSXzA4jDTqh5lmmfCflkd)YQLok2aQ~i#n z95%%{a3>=jbSOL6ax>zxvy|MoqBeOAEvaYI6p3S$(du!S9~q(rMo9jvw0Qx)vvgI5Q+*jt>n;6EDYD zS@;CpjO5yyT|qj$Hs4h+<1;uK4kQ8!2^ib)y0ju4SP4;qK6Q8t{ zdommx`Lz{Vfe@JQh<2GVc|WGc;Lh72`@cJCgYy)Y!=X=PkzL{~w&JwfHr&pfb-7&d z>D_>gZTfb3)%`MVK(eX>`O{f7k3)Ovdk`uOAiUghPGLm#8PoakoVZX&LnweFpG!ey z9n{t8G1ykQz!A9E#a(w!(97XK!|Cqf*e;o)nziLc>T7yKx_yW^S+e(F6 zk6)y*7@s~)36xs2+ELk8WD!2sM|E%b7X)9&OYa-!Q(dbC6<3nMI02e$U2gzh<^*5y z;5(83pCDrG@v+n6P39BPXZfUVW19=RoTcw+m$j|Gd)hcI{d?#Ry?04QkUmQQhIb<>_^A1Ps(bY;Hs4ZX=I?&>V0n5I0k;tP( zfxmMO0b?5U7eGE_@UYD3jl~jsRNKPGsz!l=&mt|MQ`}`&hM&2N&5RVx@p(xZbNS9; zaJGFOo7LI>!m;Q`o6OUoH<+7);nN%NO(>;;QU%$2Deebxt7k78(CD+B?PzY=H|%)Q4U^zv2XQP;6a0}=+eb62xm_v9lHJ9dG`5_PJL*~PQR(qALZ&H0PzQJ zc$Uq7g3WG){}BVk3hZvW?9r!a1g8QZEV|AQ<3%e@ZQVM!0=rq`<{Dx!+xirnS8iLpmVA-6gvEWfmD;S%7H+ z98*5KVdRDGLGItf(eDesZ|Uv6Ik49Z3(KO1SeS5a@JIdnzY9|T^zYnaBjIcEpyKV< z8Q`CrQEWS7y3bIE=J6+VhzHC~qK#r2ykaH##=H6}u4TpfBY-xEJ@mogy2f-gHtwm$ z^c&Avk<;HfH1`ommlt#3+_|Ocm}W)k=Rz7V&Wl4-ra$(@InXZ0N~Kdl_-~Ghmb|`u zPQv;(oEYrH;F$z9uW{Z+mTvzXy`u5nS00oDwJ$=*hw*f8yhFcSqzhPBjnG<`Z8J>{ z88ojiaU%n3%(u^`&T?gk2Tcj_OW}s{d2YDrc4;!4?a-wB{c(+V&9$Crte%c*E*|cn z>`#aKgkO%FD&HK?!>tot-JW58h5~ZWSKn@H<4#bEsQm(?$VNg0_cIxD4yuMGn@RFE z)MxKq(#Ly<^H)?}{g!RSp>1qP0L2&wJwb_myrw?dr{NxzOsduJq40jPmOFX+9cVps zHFocTu6RU7tuD(L%bK&_WvIa>i{)DzbWE@=+z@qt?Hr2IvLri?v{y+6&GwuGsHS4> zab+Cp=*sjliN&)??Fwh)<{|f2ADiuDLpY4RZhe?MN4Uo!uY|sNCF1y%#S{eJ?3gPj zjWr5KxjT!LjVx(EZ9i0Azb&cY6Wgp~9|~0qe$wVU6aG)GK(B(@znqiT9o!rWIH>q& zIK3AMcMsOMPx`OmNhs;`3|TvX2WaxZfXT68GX9rzfl;jGR&K@8%>*}86Bh2|z7*Oz zkUB|J`>#T8oi?6@pY#jLxd)i(PQci@rwe7=r~Jr@Owvw+n+H=x`>1=+Cg<`Nd3-pv z%3B!{6w#TkYCb@#@hgjXZs)hysRTKD`G%E6_P+;?pAb87dJ<5zr%vmfslM2m8H^rXTaS8v{I(HFuxo%ajg_}8+;|(ILtj(B=&2IrLt+W z56tc&*uP!1V6!wMIn^uhUkan={Z~|d8!-J=qB4?ki*qm9mjS*lbH*}o4+%;&rS$^}`7-{b4n^ImNcbRtD$vt->=E_S4a$ctri=A^-H4@%+ z(mMCtgp7s{lX^ceb6#%W@9Vjud7U{Yz1RABM^mM&G3HuzmcKlyvFLlMh~jr< zLOVBe@SmXaVk>N-li3%C*VSM18NWicK^cJ4RUm6biG|KVx^DpEG3JCT>9Z^LJdFQk z0d9sgK%4Kb;Yrx&ADx}qj*gDBXU$1-QRJ}F z54Vg&Z!Dx!E~^Zil;31-=kdc$%{{8aVC)D}wu$_R@9??s&hG4Ex=iK{ImxYfRp}e1 z@4H!ynTa9dFUZ;H1?368yNpmGT zD^8AP?{5*U;2B@aGWn#U?x@;tmsOIAEMI%7=m}c`X99-w>+bHo0VY>A+gv7uA6l(8 z9lQlm5q6WKw-K5JW-Rh!X9@I2`H*{OlRC6MRIf%VIo*C4Zoh(nS5{0Oa}JyJAZZ{iYM z7H(D+et#&AY+y6aF%BIlBt!dqOY$Aj&NSq1)x%p_5j>KYGSB8#)`Sv3PkpxA^@`%oNpHLvH|FAX5 zBhir)Nxf-M?-LpIr77RlrPogqIi@#_V@fVJ+;+wk&SlAqq5gIUaCCLg617#$<^TEt6vrvF z!Mnt{$}`pZg_i@;El%fFvJCd6X6_i^jG6inbXF+9%3?G))uJ2eHp9tINH4h*T0N4N z)(0-Z6v_S!dHP_>O`l9aOs_2;V%>~MAcl;VE5&?$)nriR|3%G2ig#c=()br9+9>#v zF=q$Rb=IJS4}#RiNw}Zak9N0VAU`TvwZ@ox@||wX?KwLax5gb%yE+BUXd-)=M-+2t z+CgjHJq&SQsc*N61r?*3FD%La>IvM?o927?`6HRtx7zyre+K<9hyc%u6ykGy`2f0ulRZ_pM_4@Wo}L$_ftgD%05|jb7E_^(CzLcc5>( zwvK-cws&7*G#b{Ls#=L1?a^`({^ixep0%Yd&ko;I5f+i(iTv=(`bBm^>jv@IL)n^R zc?S1UWW4G*gV7`>&U`R=2#h~yOm-=OG0sp`?F(WhH%kM_ST*8_!N3l3(n48|Stl~I z&Bk{A>Z@&wi|_jTdyR+An5Msx*LPpo?0zrX{XF%-XEl}}f%nOHZaE=7C@3pN1@ASF zpUYlq!!hUS^qmtGc5nQI3`Bb8$alZup+EgF-%!&JT zhUk9fgz_({+)o3Rw#L!cpmwk9-Hs=EB!uo9D>*GtB$H(%hf!l#)yiinc<{CCY=z`8 z1yJ&oX;6i0wYDO*XU&@T>$-)2L}}N|OYNMEqg|8ANqSLR`G5&ayrFO|SzXorXYnP@ zvN65+74{#&PbLr2qzlBh{`27v;Z}OlAH-uFsO<-x%~yyi8wFd!AM&kIjU3*eG|_TX zea0K%8aixhDIGz7dC!LA;uyBNvNF6}Fm_ZeI;Oyd{$uYhs0wTwsnTs_8~By39z z8{x8Pf zGAOQS+ZKl40fM`9f?IIc1b26L*We!9A-H?c1a}Ya?(XjH@HWXg@7}NK{rI|yqM>)M zy>#w1=a_4Z`WU`ns~MHFLZjrq4Bp=oU{<^WY%-pZ#7j*PD9*&@^+zndf_+3Fuv^Vw z1mLjIWzhq@9`-xU)*N|2vO2oojq*`XW#Xd#fY#I(a%Sc zsMb%2+Hc$E?qx4whwl_*MIS)t$%yC)oi%JP}d7=iHzhOLxOl_v&IK*wS>9B zWtC*U7+NsU`1z;VMG}1pQgm8QY(Ec1QY)5Tsj~byCvIVR1N+$vkj1>oYBm4{l~w32k5#yH+{QjVwU9_?H~ zx8hrtzJ5@eOGu*sTv0L5fbyC_kzTnqT(U{PmyhAtMXnLMLl*y3gqNBddFS}s6K&P3 z^GbA3%09hiet{`lGVXwsmLD|aEZ|@7DEb~3SYUO`1Oz;@K{wqx^$U+s4}ZWKOYN0> zx*PCUAI`kTFZanc)vFR-LQltDOO*DUSN&QIDIYc%(UpYgD53no6^eX};KfzN`2t({ z!Fc$#dD_Y}Bf+H%*5v6LR>H2lUpPFMGqavgNE%9S88`MU=Vm z=AI6aLSq(Ekdj_9K6CM>wM(AlIuWUGI=wy~}8z-b_r$hL&*5egd{l+;xF zeUT_n9NPXp<4|Pun!$GaJ%kGLH!M1S8Kl6`SKsxjQHuL5wD3%$a?O1MvsbV%hdqIU z-mFO&nlVSWwx=|{w4*KYZa2)&FSw-6svlf{G1X_Bsd1VZg)v)*(LMFNoC;1W*B97x&A| zP~wi*eb;vTgQNRxOJQOOT5qb!!WEWq3f^R*os%$y`*UHNWDoF4lgzSG3Rulb*wkly z);a6L6#XV0?BqCyQyOxp7SH&ac%*iEUGVel6`O0GOzc#5yhGv6Iy@P5{DM&dMN32| zZ+*)D?GIo{>+=vxNqNCEr(v*V9UjKV`&W&W`{<_3#~i~OBNtXjXG^v7o+^9T+~_Jc z2IAxbq z{KVl~Ff6?mK%c=BG1ZckvR+HXS0y*+F?B;-FS^xu?lRAGS)|LOH1S?Y--{Qe<}=||SYe_IwQrdb@f5E) zM4pn22+f%SRkBPlT(4J6K<|0zhfT){jnmoK_|s3*uW~R~KN8q)m|JRK7%N}>+%?+c zNPMv1^nFgSS4v`ckjpYjl1#Gp$u6VNBcGT*eYU&U$nV+eL4&ad+RohNg z&0LXbZL-OUhdCK+@REAo%l&*Ak(34_8tDo$H|e>V&OAM=;Iu^BZUWh-Sw==!dNc4g zYj;$S&Tlx%)X7X*k5VwzpA1!hZlP3ndc5fM2!TqiN@>h=j%k3JML^bX6$8@-tf19b za*#iWV#`~lZ`5N{r1g?g$ARbdxR3r$mxK6y9%tMEXC5cb7|uhh;4J0WURjDVbooAt z08SVO0kfN2kLcz*-PM@nIAaUA2*AmeouP2k56p${~!9fsI zhpTp+v~Nw_5gASbS>-=^An}0M6f~5Z&3l;`8b_TcU*ZTH2fx19wgzQfE?4t1h*c(P zrX;9itzb3U9b1#VtW%-};T3XYWjC60SrKn)VCh?y73c4##Rk@)rirH$*|GZ<)Zx5B zgQE8%+alpiW4ALqdkBgI#nRi`sR@Iq&e#9}JCgkfd|FC@tNlZa-n;N@y{51aE zaMD0E2~0CBz+`^LyDF@5fUb4wf4=j+_kL^dIp0e=;xd|IVTZmX9pEcDa`gQb>(AhxyxLp!F(gU%Hx!70iy3cP;7ob6Z4brQ*Z(45&rz45BE& zid~-r0u#K8zTT6;txi3FU=vZxYS?QD+z8Gwx)jSabG{a&PUN^Fk+efldg(K-haVeM zf&B=k{b$bN zg7|SY+V|C^BN=>>r`oWu@VMD6l9$Z*KDQ)O77Cn97WJHzPNEdI2m@UWUJ zc+HTn>kvb7|9N`zC}m8KGV19J!tQ|1W>)1yWE;R;3GdZ-!zB`L^H?6}B9b&9$7aeX z=nQG5g-JxX7-oOA_PciT_l11Jpwujpc8}4jBY-S(zo*o;|>$=T;&~=7k zEoOQV+=|=stbB1eEQ2kD?whDB%ecFs52;;GdycG;=1xs#R#eJePtivhoQQ4n8fYUjf^wM`hfa(2{ueA24#)O#a8~fW;wz=%LoqR*TRN;UCUZkCd zSuau7ZFfi%wnXoO_)&{iy|xwEy@S_M0jEh=v$}j<&P$T*6Q`G(V`3eQsV{ z*J!=J=0jR4cYSTcxtZ~fb%@p{Yd%JZH5|kMX>PBA@o)Y-yxoq?6#9AM{}VJ=fcT3si8F9-q{e;kzSiyW+!6j8hWrrb7up1 zV{n@oirl`X3u>Qq)KGKdL*f}aAba%mZab?7W8uaQ-+Z4BbUeytSvWto_?bPxTC!|T zfH)_W?_nNW5oPqUUQH-)Ou|Qq1PS|FZ0t!nT1GC-jBG)#x2*&fV=UD3yN%TM88kRt zHZx|v{SM<_x|^Gb0I{5yF)OqOYgF0z*W;0t^RF5fi0cH>@-}QyVx)%o#wwjjYh1RB z;#)}pYxcyxr^L1ANAL=hi;`Q%N4B69(am`r+z+itr)eqV7UlR+D5p?k!7b={?h?VW z({mkE@lC!iBemmCUN6Z*i&D&+CZ|jzc5G%t8V7KtKpmymdEz3*Js_K#Lbs0C++mMX zRw6RyIZePRF6G;LxnA;TaQPzWrlMd!AjzLAD)Ccw7xnYXy6MHVCMZpmcPdnu9UOdI zH|dSa%N_80){H4NlWfi$0|tNLICM@4h?hg@p4+EgH(pU*&Lv(;2i%l%9ZGRM<7P%D>QLy3 z>u3$EoCiPfd(HJv>(0P_ib>g+k`P~Exqena!s3x&yIhnka9M=MvrsaTFlk>wt6rNwbD&5TOx(jUe6`2xt=7zK`xde|b zne*6zkG%gJ&Y z)g&QEN>ps@VF?98;dyt|{K0U2yX$XW)5Vn!c$!IX!xw|p7<3E)2C!@$QbE1NQFu4s1 zX|c%ms>=-Bm16(J?NZ#VXmc&!-~laS9}*GD5-BGCE!?7eOl777yxAStEd>@W$Ub9e+LT(S9Z*F?q zyR2K5Ou`Zq>X{dD1OsHRTm}#_s+LPDmW_uy8m%9$AS`25b~(+_A17rsL!Yd8*ffm- zLad&uA7o@%3)*)&YSum2c#07_%byUtp*;v zm!FJk)!G=?c6X2FF`rWX97MLDEyRKjJYrF12Jd8!7|DBpL36f-C^X9E3#%)My8l&yYCH1$EX7f{=Uh`c>PL|cN zyfEnfC?9@sqzYGYCVw?Pu&5gf4PY+35i_yEGSF5K8%_~7_o_}j+sAyT@$T+s5!jG# zYgRizVvN>;-5|=PjLx8HCgk%M%hkhHae@{=RQj_qYuRamv@d zgruY)v(JsR$>-ve@Wf@xx1zQ@lV;n;R}B-EV{ROEGN{FTx4O;xn`EyQOrdm5!?;^H zf7|4_ETh=gE6_PAUtfnuE;IurVZPjyva#w9%`ie{sy(a3;K|2xN0gX0nu~t8OXgAs z`?1+WCV0=3q3}{JCQFHA#Ht0U{70w9@Ob1)k$(>J=PL*m^Z=iZv@5UBZLQH=r%{** z__AFUo6pUqxzzW}j1Zj?O*1~Rk=kJD)H>V!D9nP&E|ENhAlc zLrBkdoo~uDC9GfBJja131ySRGYenJYVf=U}{ezr$IXTO{AvV+u(xN1u5Pw&{Ix{Wn zi%r^`ovlj4<@&(1wB|PDMlZQ4#l0kYTY--%CViu=&G)Woc7?LrBKd}PsTmqey#*k$Fw55H#GA&nr3e-z!@bw!DKpbRy7h9XqZOjLjQoC~TnOppBRr}Na3l#EjtJsbPy15uw}@9xNx?0EYcS-v0+``<|6(~RJo5xGr7noKHIttu&E zRIki)vrlPgdC!GIci)dZeuzR6q=G2KmKCD`&he#@#$NBS(M6ffO2;BX%)S?B$M1XF?^Z3UX&A7nl zbfMAgt#yj?cJm?acNzd!DvG>;-?4gVpGAdP3&_}QWaO^Jcxd!UhE!p*t^t|&%ER&? z70MXssK=C_`!#no&9~(2CSl1DyiyBsIGWDJOPE}(B0LUl)2drMh2!_%;`{~I0+LYv zGI`hMQ3j%7CU_z~uD;5g6g`oL8)1se(NlCXP3vvI?Gc+)MR_>wJ+3>PcJ3PsL*Bp$ zW8p|rBT-<7=Xo5LX?Zjqpd`?0NQ;G_peMfv;&A$IL$~vy-0RsV-K?B4`J$f41>5Aj ztS2WO&zi(F#2csk0*ghZRz$9NP(o#eW+ng41(th%ENg^VhV!6Z0pVBFKz$t;LPJ*+0!J z!E{)pR|`fSGE7bvYnbOhRGyIby5%nOO?nZL)Js-*g zMowFX<+6W*ro^ zRNKEm!(r~)a;Q%Vq*u%+c2Jye9XOO5`!d)CPC<=@XC zMR=MPcW^`@b>r`)7xL;Ro2XI=-zZ~wRodghUOYCv_QLgrm z_=CQXv(;z)sz84(b*E1mlnc*8^#C~D86e0MMSjdU^UuYgyh~lG2SRKu@HIAFX3yh$ zPov3EjiPCyYhSw?$oZc=g@|~BVSExG&$XOl=&X8MMx=$}Gtc1g+G`%_; z7Jo;vPSkHRj*Dn2DnbWmWOV0$s5Qxqy~1;JNq0Jm=f(YCV%Nsp$a4VU9s-Km7_32Y zn~U%aNDm!e49T!V6$jtMUjZY2U7BKdtR`t>=42CfdC4Wta>L zLmDfCyt9jzy~vwQXrniN685Or0@cJe-XzF^OLn1<8&OAZFGL>6eRD*ny<{R4p{tD?eY;rKUqVkp%f zg_SeMg|lg{$*C2Oct_(#mZf$Vze^!vQi6-bAGu1DmJ4tvtl68EBRiur111(12g|&l z4-ZQf*y6H2SJ=*LM$W5-PI!~H?Ih%6AqbC(Ku*PHU!4pDYn~B9ToGUVL9*t(viYQ1 z7BxsE^CA7$dz$tyZH=&2`&w6Ys$kH`&$Pg<5{M^66pY79`YdxD#6kk#YwkbXjco}y z3CWN;oHT3<5Xduf#Zy6-(rEMFWNahQFzX3sw?RUOXW=34k&^B~3-Ep{L)YMUJn}7( zH5_@A?ay|-2=$eh_tjSK_%8R!MDdFpJ+64Yp;}LOQ^^&c1o`hbi3s4{cFz-K_vg>d z9K3Xo4aP(^w`;C5&mf@j{z*)=ju?h@Znoa&M9sO-iAuztL_O`EpHL5RL-^jD@UEwS z>LH8%@1P;DTCdqWS~s+nJzRZ+2HhB}>cd{z%08Jqv3e{-ykx$H`3RCfWWI(^B;qx& zfI<9`MfMWpOj*BTdXJ4BSIMZ_gt-lR0qd_-NR-Fb^c_;-HEs6t{EoDD2cve;tzHuP6WMmQGmzy z#Xs9+YV3y#f0i>}GMdV+zP`#k9J1*Jpv{!#+H`+w<$lFcX}e2{@!>_-vTwknfLyM#58{z7Oi{hki=ZCf=yS<^e_B|ap!OpOAVEwVo3zrBLhUMN3s`3T2LM&)H@W&S0F zj{7Yd0_cf)>G71p$OxP7F}(7XQ(!fo_dyPT3w3kpp_(KQO z9%*3qSySW(2u^WYk^XpUiU$0~oUFa~rYd8vmjb03oWozl;GXlSS|kSVCj(z2ULS&n zJsf9eap)5Uj^08we=D)^f$X0zi=ibqhDd5^Bys=z{OV`_0c+cvvy<)R5aQ%z3n8EG zg@0cKOU>n;8q+k9qW?NOG2z?24Z+pQt@Bm_O@DzG8#eYAk%n&=ES{K`-f6mDM|Tn8 z;wI{3^F|eWriF}vavNL#F|E}X4c_O&(=(%cwmr6l9K5)7Zr1;HhJQWrKd|OlL~bk| zRTjZir|N7Umppm;Q1xy)k*4vE1E@zw4xKx_XR?vc4F)vSgG$Lql?vPe$@>6hM*{S* z#|O%aWr?0E#5?iLfgDC){da7WV$voL-Vb=NsbJFOdAIXFL;_#e9iU+VfaXxr)2XSaD<3_AMNco_sXx@y+0!ldZgo0iVMt0zhR-q4v_ z3p@~0JDuWBDgC;{e{189EQGz&1pYsN0`IzxMUDT0rRyWsd9!X^t?raMy&7kG)Z;j{2mP8rJ zvpesBbQh_=1J*?_ux^X)`BK_+5(5}1*iSpEDP&Oqsw>PVE~RRTQ4cE4-8aRxYE4yB zOxY7)Rpwdg7{-qcKdsht`?*a<(0S-U+tKqk31pep`tY11x3(C5lwExdkf< zr;n7Qyjz0ZjQma>56Dm%9-UrSW~pqrw+7_dmKwt^m%-jTVF(Dk_Ihs}*RAecj`D%7 zJ(QHDxobqK7fK%Ff|If4sti_$txr7B6qzexp`CcX>z zxCM{{eC}hiG)~b!>Mq|(Vh4upXE6b29!>NOJN2*kE759lqBwob3Nh|^GpAKjEQ@x( zaUSh^eJ-1{J@5`}XD!LA_t9b4iY_NwH-=oimcmV1Q$KaFjEiO-_B4;Q&pB(~?kgCo zsBG3^F3SRKVu|^eOjJMpOXc$U)I0Ok`}L7=(Jdol_`20{o{@@*YNv?hZR*os?zs8J zFITt5CY|QP+PU|e>Ee4UNKAq$Z5uZ(lLC(uh<_%0JzSVL42#bAe50F2y}Hme`GxCA zKpldu@D&3CgGQq^JSGP93#JYRe{kwZ1G|)rbr%3a_ZxQX*lw;)@)tX|;yDq|Rg|&D z4jcAGdOT>R<-fu3_Y4)k3w1YZ$@ERa6tnX}o*lUGX6MV3B$EAeAN( z%h^F2?IH<(-gO%Z9*g1nI)fRV|l>iqW@l`O_>dUE+@OHzfgW!c{RWgv!Bt_5rCz)(X zVu?AOcIJ*~)0tp1+SBG?ljmn{q*C7d&|II96=_`jdlp!#8ET;W-ir zM36YTY&B@Gvj)ZFF5s-zycc3v=lUJ(YP4C;f=zYfkn^1HqZDwe#V5AS#@z^}977d)waM#QrGEBAyq@iS)H~=lU*g(GGRF%^XYVdDO!JFc6g|3J zTjBWn#}Pf^gxJv~!&G1yH@_h_Oi%;6Y(`R7f}nx{!!XLS_fnR)0APwHJj^*%Wy(fW zBSKP{y!+~Ok(K%X1lvE}$VqVuDM+zIm|?Xi8aSi}qb=(dShOLnh83M(YX{5K<@s!V zD3U`*(FM60wF~VMITQR zp31Q@PdEaJ1tTr&gK0;{N7=g`NFkmh3{3!zV5C2#)BxwHTX3??t_5-$ze$5xxmquc zkmlr#G}#350M?P{TxC^Y%uY{$uZ8;M@=_Gr9gu=r+1$>KLML9VnZA;LNtmN$JK;&6 zt0f>w;O;I$WB9;p{i$Nn@3x>nyW*02R%rCzT6?uv-!muvFP!Tl_VZopAbBtL8Rd=nF~RFV=sD*5vqEDg^AX?og+`b| z+nYdYYot){X&Blo)^4HaoO_dP%Yx*^KL0DspmVkTeFVvIRD|@q(iSYTaz3f+R5~L_rff-K+l{*Q`V;QT&G^F}*MGYxZE21mIJimv#9)uW{^18selg5xb z^)wfkTA-<`dI($b%n~1HaD3F_ZQJH_WU*LOt+ct|`F(C@_FP&q+PtUn+ff*9dXuN1 zJ-E6KcI%1Or?&-FGl~s)`GMLuw&gVdSs(Q;_U&Ka ziI|@q{kGe&L*tm|ub%v>I~u(9_^~SJOG)fj#oe6)ah=}^LcjBewZ(}qvk%DY*;#pk zo)SrY)~9!CSqEKJ?ZOA0DEmaT#{2E^B;~~$OPKj~sqXBvH3@kID&5K?!6nL2W=p5N z97g(<7^fL$!MZv=^L{2Rz}MDsCe=mYhjEbFwc`&QOqjD6)?AtR^8CDcYvD~3%r+~1)P-QdGxKE)BVz4WgiFv$-K^V-)a!GSYg35v z(~+m~Qw6I{5s=^X^^&V@ds-RR&aV&Q4KQQ-Ea1KB!L}ZGzUGItae2SfgabU{-&c~O z{`_stjW$&8z`fj4)T>x(*Lp5Re6PTk4=@D_3rv2|(hj+;Fh+GZw?%lKHqW~VS@U;H z4hPNx_<0~(c_Q*!ut;$cDK;Z#O>h!b*G@>BC8OXaHWaNOv_B)d00dbrHi92l_Of=8 z%{(UlnD$nbx@67iEAQ{Oa9>G2_|aBcc-DvY%qvYX>axlsa8L;k+k)hczX}N)LJ6;A zl`rT}jq@>4oGD2$irUo=768TB(vhgp~}1wpjYkT7QZxNHJSx zz+O_8i_m3UEKiVOTz=9dA6Lok@|qMn*rZ8uN*?^4FdQzeAitA+uFABo^{M#=xmFx0 zgNkltc-rNpE)ou3y~va0!y_)N(tM%LNl#V3pNRrut5oFq{+CjP8xPC`wTfZu8he4k zG0*mJPtC?3D9Q^JvDsV@ngU=i3Aj;2jeOF%>5-eY%u=%a0@U#I&TaF?Vl8N-4^C-< zR8nM%u}F=(%#|sKyK#%7ifqeRq2Bt2KV0u6eW!62oTkUk5m8pzb`+59y7`mqQ}HbRi{`LeqS1T7lk+IV)p?OejUQoFO}m;r1lJj1YUrvJ9yJ3E zMbZHH)v9TUc`bW=o5KB_{@Bgo~J}aFE)oP2o{A;k!zjCDjd_& z{=9WYUXZYe>?%5Tt@NXmJO11tyn$;rj<=D+2Pbux$zgeKMjI$N!WuNrR%c&D8GH8^ zv+tWl$_vht-#$}Si2>fD-SEi|ox{J40z91=J?gqY0oIHhJq3^r3TAd4Tsf*YBzH>D zar6mdIR@qp5Tl(RxRGGyA3b97)#+YDtVkkfnM%o~L+$N9j||sL@y&{QWMZungCBuv z<+-?u<{9X!Izp`7bO*X=chk+gl~<&08)(pKZ!}YwXV%df1MHQlwcXM*%(+A97cGCZ zgf~`-zR%=H@G6N6j0>7U6T;+XN!g_^wQM(@7BwQ{AkROPjQeu}S^5lj5SBO5kZ@@u zY&kcOEuv6SmVgdKgBm`CmH+2ZR+m&y^Gd{~rY}IrUS_gVYOqjZbK{mh=3KB z7XIvowG#`sfkj3^AB)psPjJT4c&1p~71cwgDah<93oYrFc@JP6-D=EMA(K&Z(drcP4qb9wo*PJ{kgT@; z*yI{~ZCSQzszv|MR2XyjW{q03TJ%59Xd_ z<=u;u7=IFHT2_8cuOZQGz`!$W=4_pR<34TfCqK}&F5ti-Upw)36W%yE4YH=O|9#jBC9m!=5AbO zx0!T)0;|h~O6E{43VS6PHwI6+#PzNdK0HN>UBwA4inJGFcEyIo&BLM0#D?3rP_kPv zA>&Z%?535|SIG?5nI)PEwQKl=OnmSWEg&kWsQ7)$JkD0A3WJ7~A)jOnu6ryIK*6Dd zW`|g<*5;GF@f;1B!f*rtovM-D3RBLy!C;(K zKEz9d7Ni}m(E1l$p$n!(&g9UnxICDfG09ySg(`C+`by0;qk1ZA$^~S2BjCPoibOz8 zQ?MYhAoHYkXT8Wfj=b3>|S!IkQ2u zGZ*0TfibS2Gbhc)dS}X4mhGkzH}^;>PafN)ZIR_B5qD$=FCA&y4APTl(YIbE=zN+m>zGYU9^`=Peh9Y6W=WFv z>!5hHF#Qp|%mcnNs zO?g&Abs|u_<^rAp(1k#5;x^qL`W7`}Xbn5g-SjAU^6CrQxRy56NsXSfo0;i;`z3$cTokp)R&TBR zqp$N}c|Z z7T@yFGS!MF$~y^tNLIzQg$Yr8>4};`_Dn1CanwH!+>%m8P)-FwjVcQ4H(g@YkUiVH zb$rv3Pp(MGZ13vRf7x0sNE;L+H`W<2qpO+OJM|a@hR6GB7x#MQfRA!wWq6)jAXU?r ztzU1#rL@ipELwwTg9v7KICDT8upo&s_H-eSSxB>m)BMMKbE-7!gU~!#Tnj6nlHLy+ z`&Oj&^AW#_0|NyL%1=y5&y68ohB0jQX!C7S&$&V5t!*(^zZUJvstn4mP!43_o*2I# zMv)-}lY7ncSF#B#*1or7)rby)8VxJr-%rl;W;&5lB0fhOzME!W7g<(ZI_$VqB@Vgx zSTQnNl$>`B@<(UXqSja>lA|G!Njuv^L0OfeMid>JE%U-#DkcdcEF@87`Q+f=I0W~}B> zlM?8?^CzFrl@gTUI*)R-g#6Dm)r~Ar7yBJDc6Uktf+g=@K~-BrXs#WM<~G!i z|C!5eGUgnZ&~{BRLaG7C8=U<_zwHGu_2S?D`d2`(M*7dJxAQXpc|rs4cD}z=DMDXo z>%X}G|Lfymj(=h2|M{2xhySsC{|ZTh=()H44m6HywB>eX(7E-J0Ic=tLgM9k^~EYf z1Hjz=^KFL5e_O#oYD!AIc3&v4xP*iedyD`3`KO)0|99p7=kEOf|0?t^PW!(K{@cd? zPcdh&RnD)Uq|+Z;dspp8ua+>z>`}{qd=CgwEscIJRXFB9U_@kHnhdbRH`(#Sv((Bm zVbtb#%xJ!rkMrODgyO0g!-bL%E;J#sOor9C!L3jDshf;W)#F}w1WO>A)nQl#qiK@K z;l9deJar#Egp_WVc5~_bG;V0bvwF>K@tJG&dh3zmO(gE^#W?Mf-cj%z*Q-M7{}4}e z-$Xsz3XmMoAd>!9Je;stfgPL3Zj<*0BfLXZA;;f=^6BMJ52IsZyQ+_(|) zV9UkuLA}l$+X@bBQr8OKnjgMVWFM4;^p((n_JF< zSoSxLSa>T31+AJ=+)z7Tv1-{Ku$Jn!qu$kX^CTHW&1zp)9nUqBCt5kVU3;WufQYt6 zx^3&|WbmY>s~k$Mqo2Gs_>R*lFGSY27Rf2;UZF^URt*Zm{bQ_Ad*}GDdV#_%*Irc? z)e)hw)R;kD195Q*4eO=q^7teNjm$v}xn87Po}?i$s-Nc;v7pr0d+EH>k4ZL zzoAyAInHTogSfG}k-<9IXx9qA7zQU!t@>if(ZC7~Yk9fBsLUBdcCsy&Q8@9uuh%^K z#bbocoujrk>dquS{=*x)4dLXZN5;Pn=TnFX14Q|T1x~NOZs38M4||?tGQTtV-pcwO zEqar*dbw`WA6av!ax<-5uX%nJG}J)yIrEC)vL3H90H2?hVi@siq0y7BM0;B0@Ex4* zV(M!sNc7>MCJ?gU9#u%vKvUFqg|0jWs}CWJi1A{QT2HU?SFR+B1jdvbbNG!ut)NuB zM4kej0{#6{=If=mGABL?imN^%G%ZH?F^8n(=8;Ugy8+~45M_dLZDgS5uHMEAE<|D& zHEs}hE=}xF0JN4(kV^H6YiPicl~VdEL~Ot zk5!UGQjS*10nuM+W5b(_0|6Y=vd6i#NjA?e`2RsC1u(6 zIyq13tv+K5Vi0R<^2~{{WYx?78_#`K#MGqr`iAIRf@fP&v+mN~d*eKr1V5yqk;e^1 zEn08iqsASh_oxmcw_&C5Ug^B~Ol!%C#Ur4Qsx7D!p|r<`+P>?gt8w^e8<1J9LcLZd z4O-ywcWR{6Ce)m^fC7f^NuKgQi&myj>S*a>OOwVBUaNE101q4CsQ4(g^;rGvpYp|m zQQKCPEE5&qiwBApENC2VjE?zlAk6JmtKLVqz=Ih`ld|QFnFwxAn+A$ZSX7r^nFm9H z2QCpW&cr`Y+(I%5b?Gxn#340fh&B8U~k~UZHpB#Rh zEEK=zu1O^JXJd(4XrPwN${=@cQ4_8o`9q2}dqVL7BP4zZ<;Dp?(&jvA-(z?eq<2x^ zYx{{mi;L?KyF}w>r`DCSXV)k?cB@_t&zkX_pnqQhe4&mPmxQ5)|B>pCt!|<^syYe} z)NWRE@^WG^vsRKPm-rWJP_~TuUE~(McfHWL{<~Mvz|xWDEvz36rJ77Q%Lg``th#oG z4*q=&a=t;82rs-MOI-Kk`VZ#K{ABnfPEbSz&=d)w=)95opineU)vOsJRvQyAk^Y}| zN$|681a1Rzi2t!1%G-2I=sKa}j|1;vzLASK^?h{Vq(8Q@F#YkkJAlwS&w2b}yJ(}( zC9SyMD7$rZ0<#Dl*}XtpSkJc5NPEtFyx)905z)czSI}e=J(n~+nIH=!XafJu00z;^ z$#oOtUEvziy8dZ7GuL71kwWeRy)~n4p75G3_U-R<>2JcpC!#-^6}t`)q+jzomhtan zg7$immQK?C7*St%0yQF+4 z6?z^zTNG`X9g7!bqg2U$a082#=yd)do~ONF`*FI+f<(|L42X!O~P(E4Yd)qL0 zD)D80y!VT0odBzd?AL1EYHuPAw$b?>Y(zfw`}wmrw{pt*BC_`W;hWYFrV!J=CyU{{ z>S`v5*81 zw|PbApuioQtUX{P72GMZE7nT)-9!fcR5Zf}r)sX`(DmXPY<>Cj&cF$`Hk~3wOgN@n7JPlVQxNFSOd)UWYfy4Ai8J{rtnkQ1G$T5A19>qRl$1i29SN} zd(llLDka+{jqB|6v+S<$Ev~SmUsMoSQuyw%Q8A}T9B`nBO`B`~KPNpcrNVhe&me%M z%vJfn%X%k)XGY^pU{yuD+dSRYxRTB26{p(zMZW3R(iE+- zqO&N@suA8VZxmYq#Sju@C#Z$iMuC4A^wVva0MJAj#*p^h8PVKtIyh+oI62)izWonDgGg0bu z5b1Anzu&Zb#n0nQNZ4(`hkzmc8G{(^R6ei8KKuDAq;mQK57$W~$4;ely`4gVGK@M& z94Iq&F9WO}?Kueq16Kn6o9Lc87cxqCr%;2>OzOvp7Hdx8duFEqa^tPlAtqa{FO~yG z_X|-9O#kc#0-=3lpy&GgUPK z?^W}9viCDKTlw&`bX7jqq)LPwZUTJNA;UET?-bc_cJ5hM^e3=H3PcRr&+0koD>1Ui;ryp23uc;T?c}_fsLkI`2;CcG1 zAOBhoG$_@9t(IxUCKlpATb0(Jt=wdZ0aX`Qac=e%HQg~vMac+@v zS+ox*jo5CetK_myd{@R;7AaP=Lscym8yJBdAAvlVfWmd}K&L~bUq~ja{Bsj-CD(Dt zkDzHb)>1d{XPe4LKx;Cl*C`Pm_m+VZQ#EB5u3?5_O*`U&J!*F4QW{^e-FEZDWr^a5 z{Rq+A0F!3p7B}qR7Ypr?aD_Y#InY^K^FML_vz0U~-pv&pofFj_ zK+Py1yDy$RA>L!7FT*rd3TgW0_+#MVqfg}a`wnSS8`#oq?0SQkHglAvs$eMX#b?3W zdU`rU*=JUfRzea^gPUgeRM6=1yZ=MkSwKbgz5N~q0i{DiN?HZ!lo;t!5D<{=knS89 z5u`)9L68t>knZl5F3BNh7`kTW4*K)A?)$&*eeb$wEf$M4hdKM~v(Mho^Lf6{em*TI z(E`=aO8n>CjtjmS?iydWAg061TS%Ge?2~V%5_N~ld~=jRcDXg*%AS8O!zH*=CIj=X zzXY$7Jx_W^Q>J?BLxLvqfGAsTwtdtcUFVlC+BUL9s58q7zz0_4lzv_Q1G2WFxa4?n$1# z3F1MD`sEyfKo8r7_^7H&gDz)>HAZObUbg2mi8K4SQMm_ZoEkc;wRap>VY7t@t`&D) z_U~nj(r1{3zEeubzM<#O6)h`Cb@}}YB+Y@mnVZF>zfEV!Thm#a$j;7=z>tBV@=9Bf zS9)b&O(>qezB|XDY}9Yb#z^d2#S)h=C4|ALz9q+rGZCf}w&+BTzH}#tZu99?fD&t6OgkcC>ke)fy1@ae!1NTqs%iOE3-q0WBpc2bA5 z;KQ9(U{+~<6*!}7#4Pk@EQZI)=X#y|7itCGlex%FY=1GzAmr6-@JwLZ#g0Lf6!%Am zync{wp14{b&rg-3Qw}vykgsS+gyw;>}X`gYG!LxOVp`XEh1szG! z6g;#$HePz7ru~-YqWd)Ac-TN~nE{res%-E~71cV?c-Cf4`5PbdOtR6EUBR%of>%jp zKTuUrL)fYQaf>!W6FAMD{G>{jL$A{-B`bSem=C&Rojm? zZp>uZUx`?t$_0l%$o$IEjbMJ~>aL!C5{gzG-8j3CH|An)@%~}JuVrkAJ8O1#e3njU>CRo^~S^i4v>qfNnq1WPt``KrBT=36ohUN?)8?t>6;y*Lz^^aGDIXV zWM4h-AfvoCx%$2&bz>7Z#1Zb#NDo{_%MPG?mPz^vXPm6+hALSryw2Tqb?TWtYIZA9 zUH~9q(V${iLew8~32a*5rpUB7Pm=5>^Iu;8#nBK)Nv&K$LP9oatv5*-algYS;5bnurkmS9DR!4nA)Sl7mSWGjK7-zA zMB+$V@EP*C$z4g2PJ+v|ZndomPd(?D}(GFLRz_!yj=p6&r%J49#RLC%2SGY@3{DL%?jDawcb zdlp8*00^vB#A(^(X&Go3Rk0aqlh^s@8U^_hm&dd<4o<6%LbHS;Y8f|OD0^-#5-m+1 zpSl#!_ROOK*?D&g_7Lx#^hW5vKtx45!F5a)wdeH7jEewu=`e-?l-{>Gta`$@wC(|G z?ffi4`*c-g`pw5-4mwuUJXgNOYp|8;;k^i8MfsyOPSIig-YlDzXu1(EZ00oH}+A%v#j`$JZ=$UTo6$&?;Krb z5**{4-4x}itF$Ywto_-McY}POyb)%5G~_uGa9&LqV<(2uajgKUlUczxm09y)u?urL z+e^Tg+~AI!DV%DrGT(Ar`QqIeHb@6d29gt9*1x&`&#>~^n)RS%fs}DO*4IsBhxEnP zNAu(V81?(+zH(Qp--GCqQth7su%T_H@f7$2WRfkJhPQA`b=bTtwUu_ID0dcL=j8BX z^4rY&S1qQruEu*Krc2L10~yq5T}gSt*U5!2 zJ9m?7)H%~HX3P0e;K2F#;J&=vfpW77%y7<~ZE=T5^n3^+;>bM<09 z+jG3$ei5GsEbGtzhe~XW>)!GQm5&p3sKl_?5Kw2ApTX?V8M^ksFhS4+cyb|vdO*$o zZU4;xw+H+zn^r({MmCLA;(f7n2d`=;=y?37_;m?U+)3lY+|5VR91t9}{A5%>`%_{1 zhSP-vd7<`cAuH#r@o@fU8-R#P-@$m(1&`Q{jJXU$&lyy0wrsEc*H;7|DjvY)7%mn` zoEn<+Pk@>^+=;AfRvOVuIX6?1*Vi!v!Q%7t^N#y$MoS7Lo~4mBV7>iT0aOSCTwsdc zGDC8*VsAjS)S&)rqvfe@^K;1~6LZMb&bn8Q&4QH=$IGiI8RM*gni>Jy_LI&}s^Dgb z?5hc^29~RlGb7sxQi!sMwX!{mtt`6pcsxH^;+^^6SdRQIv+3dAfBINpjF%5KJP|WI zD>*kev$0XX>0_LupTzp|#0rp5A>0UBOUAFWD3jpcG{><>c2DG3yWu6UPZmP<6p@OD zRW7ZkMmUIE1Ne0p!^vD)31g;Y|D9Tg--X7B0K5Dg2*owNysPgnv9SzwDE>T8$>e00 ziMui?8PL;=8MGwcjCs?1SFDjZenxJmnXB(tA)zuF`#|eL)cGmy6l!-8gU0R>DzB?$ zXH{_`rbA7@6lJ)@G$)j`{Fo^riKUh^EnVzaK9J$%FC$~`oMMA71-vhhd<4ZTUj>0E zSU}IP$r&&jswU6H4DwnR1=$>U@qh!@7%5CU9&?8z7GWt!Zty*1`Cn$NMW=j0h~ORdsaI!CEd(ru$Kw zAyEzrsli-ys z=+WkAK>!8SI_@;8DTR`T;GZSzyIN-?K#}MQ5gB`{WD{|jz5$|zDJkO~dchV2;*(yk zgQXLF$}P>gTqqvar+_;Rep>b!fer+5aHsh3`NyzG%=Sr;#Yusxb!)T=d&JetqCJRv z5C{b_EBK*%!4ziqMA=9#c0zRK^{=-nI;W#IUR!$vy@zE^#EVqkt~cT0NJ!_q z6xX`&pIN~F;8O`ZX`H)$^bAEYev5yWqN9jHKd^6By%I&fTI!FX;la+tf913A=+OqEo+rRT8Q{IQKw3ef(ZE3}+<4t?X}_3u6X@=_ zJx^wd1p6T_5N0|D2AQ2$n2uSGEDoFH3T4k_Iq#GO{Hnny6qGz^!F*GId=qiUgR{HL zw2l=S>+V6_**c|QW)s_$hmG#TO8f9FU`6Fd_VfN}RUlp9#45|F4`-C&J^A!)7FU*# zJC3}=t15fa9Jns-=K*qfv`u9}*qPCUp5y|YxvjF!X7*>WUVvy=^y}Wf5~}WVZ@PMs zCF*6NOT;iAZ1hpp{7DmW?p_i0vhVSaIeVj8DkBdgqhI9<6@uENH7A>B!61i;1>x#Q z(M8y2QOj5$f7e$@CbB#>jjPhMF2UE&Rn%C09*?vgD-3mTHxY=>Z}%)vc7UF|oLNw~ z*({tHSbN+0>hl%-OT+gc-t}&zrHOiqNO`W{jhRzoSo-Z4WbS8(hvDo%Q*cGx(chV( zVMe*R@AFpiu0M2!-*J`-h#sLA^=!t}P>I-2FpzXmKHE!HI6A#^RHkYV@5CX``rwV_ zlxW&Vq$6g95c!z-rHzWN9-(HeCDKu|C$GjN{oR6 zc3&;Mll0_RTVEsJh^{pJp>T8(-mP9Gvk}~Nk@(bDp^TppdPExbIp?{lva$llIrvE{ z>G~mLPC@QGO~E8B)lH4$z+jDTG-~t^>psQ9XX-3ViPtV~b$;wDrahj2=F}t)X@07f z!Mor{ynQluku7QGom;meDr-9#!M8rlo??T)R*=sGpsOSi&14WwWOUhavTWDtH{@~J ze=V-qqA~~Cmd6EE4OuoOb=|$bhRxomv2(_s3&5z=dF$u-^Ces@m0C3l-Xp@MV6)Q{; zooGRKdg`iA6iObx`M>3JTPv;92Mx|69-B+4ig=5dETNU4(o@vBq& z+vHqmW@C3-dno0P(><918hXj+v8x7USbHiDpRKpqk+^ipSy>*-YXL&lpXL~{74j(N}^CchKts6NWb^PvKzS)klA0y9Oq4WA9~m;jucHxThW~s;wmqvjqlU`373@C z{MXg+BGcA*0Os8&Bcnv9XY|baLeSsgJvtaqh_YAkTpr|h{3Y>dw#^DFZRwNC5(97B zUqq;=<@yH^3J82#s&Z`Ju+pAxe+TwUZYzSn>u#_kcFfhi_o13afLpx!8UG+teYb4o z)HI6oQM5fdRdsC0wBXK8usViK`4#(%EHYhQfADYYlv%%igqJKv;v5bHZ^KC^zyNNREi_^NYzl9Og=(qk1>p)jVMR)3|p+P%BNy->K#W z>$H#)XFj!RC)1_!qrD6XZx3ZaKqCA`_s^~Wb=WfbJy0upgt|9<&#H%7S96+^nEVs{ z@O9zJobl(Bw>YuTEn}b(NQIfIGzGr(8dHj?4;%zZ4=hv&ifJeR4A4%?__CLYaHGOg@skpwOe81E~O z9WMwilj{?JB)C!bkC`wTq5edL^&6qetOzHHU#~TCi#>X#qGkZsQFxC{Fu0+5_>tBj@(UbP8{IgQy!4ii86Y z@D*eR2zd?y6M!x{6@yU*z>zH_UA||hwf1Ne_u26`WJ~V6F9sZQYwB)E;##pDO>U*Q z{1^1Lw%REy<~Zj`>5@-gt|Bp`EV~wswU@BP=WptoKfE(|K&&VD3b8Ah_~FO8&zw~C zTiX_+jk@YX>7$Qxu;w-UB^E~{rOvOJ9fCE=r(B*@-I%5y)=_wAH23jYl*5n0(SRwHe#&tIrwoOqT0u?C_P>H8%en z&U|x=GsPb1I(U#m&ncA!LK~g5%97T^vY6!h#GgIEQq=R~XS_BJQE1xg6LMh5(#T=8@5=kvrP@%q2({xaHW#9Fu zkYeS(oJLe#)RhjK`^qc659T)nWs7g+-$CjVEWpLyirq<{eiHdqVRZKr?&?C<{QiKfO{0+{>&Fj zVN}Lkeo%?5x|^5w@Y%}ieL>HhAe(g_*J-6-1!TTLS}$Xu@>?g4AIm=`gFSo`Zg$x7 z79OIaLvX||g;zV*D4|1je+#norMKbdKCggI!(43Tr*tMOG^`D!ZL5OBCj<$Fi=}TG zQkg07W517ZFm3=FlYS=tS3V2Z{G17;R?*waeb`CWCL$nz#Tz$p@L;O9B&mht6|`Qc z2TcD54rjkm%R92mJZVA8&JVq$oEO7rat|Y)*k~%1;(EVfa`OHrebMY!cV|-*M(=Sx{D0)cy(57z@oWPOlOkMksD*cK9};w1n%0d5t|>rIXa* z?KgPNF(2kK0p`=Q-g12vqBDn{1H6f2nR}zEaV8*J_cgas?J%wNI{Opir5egwlrJ4; zycqm|bo5g}5}FR(*8VBOj$vf%t(?GVePK@OOodi$ChWvrIpxj*gnrtvOB9mlT^js( zCUSv}-l;<3mupNrLDS@Jf)CQ;&hgt1^Ys+%CE|B|h&QYyc(kst8xsr4Zdh3sZcHkN zm+m{Ce>5vSnJ^FbBCoz@bsi_`OK~2F(f(ZgWAE@KNprMmB~-oaZ9gq`#ifiOYHOAU z2Sk<3ac{v9bG7zMps=9HZD z(JR_)1+(nefmK2^K!NX z4>a(8arHOOUf=isSB#!cGQqaNN&0?~SHae8)tTStQeH1>5m*6UF?s&m6IA^_fw(mr zP0#3vA!2Z38zjDp94a;8yg4UA6qcMCiv32Fw=A=O;x?Xe!w``q@A>g<)HDU~I_Vl| zLa?MvGW+7?Oe90EK#40Citax8%e+HEUVS4_FKu-6cyft9c43?xw%SuQRw;@ChP?mM z%Oj-;E`_F+teavPx!>WP4C4-$q%nkcMGHV7S470rNzo3=w_=sG?xeN`E15j3FuOs*B9fSA*|{CxnY@7A{~v9uHBbvWGhhmpDp- zWjGTeZU$zhq8Qd(nRn#SEW}RM1sH^| zL_;9XTaW3GFuJOmafagGHD-VF;%Xbi9W<1SlmzZ3H|zo*-#JWbz4_GM-u^J^R&ntA zoSj09$iKW9wPgJ#asIahZ}IE@CsF_F2mB_t|9_zSf4=Mi8_fsQ7&%&O@l8WsgOE_g z;M<`2?NM3$TWs|Z6^pqs&66VhgXD>{HJ{y<)j}Od5!?g~*J+x=_=2Lp_ z|2iJ<;MdWKQPguGCT+<-0zECbn~8pyiBC3`3($XofO&TR$myuD*Vb_{7krOuT&buT zY?kfEF*7i!2DcRvfGP~AmntklHx>T9U$%~8#A6U*GE29`UO#F*X=BJ#f zaAp$z9C|`>dKCgki2DclZYXu)t~_x(^Q4$LXT9%T8;7t*yiKq%{m>@B$ze)==ea+O zIF#JZHN!zP50gCqAB7&ytH+!Jyxv1>{eN|Q6EQ=F5s@0kS?Ikj9g4xQSu$UJ)a&++ z>ankncBc;6pf`awg9_Y_6TtSj7a7<(${QUWTseW)S~s2!mi>M{$;(>ciulR-S{CEn+T!G3TjsrB&PqOk zZlP;bswDl1zk-t7@HwfgBv1r7fZ_`z|!+PApt$`7Uvg6;gg;?~KerBd6? z7e6+x8Qmp&2}r2>W190n;@v)Cv%i5KFU`p0+;cn2V;p>28yed~IeCNcHy`&dUTk}d z+)b+5fDTv84YSY12G8n>d#1-?jyxW(4G>xYLv}3OJ`M*^u?!eQXgvjznm6`-8n)=% zoEt%?yiR=xwgM(G6XBPydM#|!ppq-E3q`;2i)OMm)Sxi(-CXE9(lcQe>kX{Qw{$fk z_4aMI@;#RG(;{5AFEEW8R*uXxzoLJu5HI`FUF891tZV^p%_42FSC_RPuqc-?RK_x$wEbe` zi&Kk@$?MQ+qASavkWvD3`6h^IfQ>UA_V0MZ9C%nh=pgFA3?lGEB?{bmu`>K7bvMN?+t%us$l0lMd-%kJDWiYO@~?8%*IoZk6R zyRUQ)zj3(MkvSf4p1jjCDYi&;Yo+6KnGn%-E=0AE>vU!J32WI%gZgXF3BLplg@4)j zcrtP{9O6r$gvJ=iuLo+1$`Lr=>o>5DS!~O3<&dl9m31Yl zA~|#iNB~I1N8h|pIdq)#eIaLE0O$VLL||$@v5JbT9}xl6jV^)|&OW5Ak`OUuDbtDU zr7^YBC=AeW|EA~zT$k!Zb&puf*O{1cto~b;%Ukkc^gn3)NUzXcD?<8jpP7Ub z8F!&;8-h6Bs6b_Hh!KtnMgwBQhxHouGO)D`@fw-FMNCKH!5Ip8p{#uw&Gj;MbruSx zbIYA~8g{;m2i4L*_b9*Xl90?S{a4lIb&n_Bu~o>ddB9jGbvIQfsdBI5vOMu(Oq<@z zi_>sbpvdIgX0dddROb@IC?X)^ary9NSrKK;DbLO1ldpNEo->}pnvYODsv6eYJXxzd zRISE2Hc9#TvNJbAJJ?YQzl?S>@3H1CwvO5!!N_O(KjI8G zjK^K@XGICtf0RZcq5;LwXLY3ycYF^dGDrzBlL9XE^)I4WcUHt+p0As0X_YyBSyI}6 zPO#$wf4eLkWVvNnZOSsI^fgdf&QWa>Q5+a_tMeGr7sI&eWQt-9fgYI{cC` z<}^Y~4|b0G^hf*HQml{*4?qhJYtZ@nvPRx4WPH6)*j}xH;1l?@hKC3$L-T~t9p<_B z-6Nc^Fj45%$WZWl^#ea&AKb+pa|KvQg3_Z`B9#KVswJYDkGP&Ka^fkcgXEOeX1x+W zFGVe(O;ddEH_h<%2KXg0`%b;COkY2grG>DbIiqC}J$C#aeUypi%f0Y1>QV>uxUT*~ zOVBR(I&=j)w%IT7Fo0v%G486FytnKwld>zx3zA%~IS|1r1g+mic%U_d=-4yGzl;q7 zKah?koqTD!S#(asmlR3Z2{&3vi;B?|41=DEJ9{(~oUGd7&{dI%TyV&oct%<+=hjXl z4zDYc&}{|oVi24XH^b^oHU4+5-m&msxO&SR^Vj@u2Cw35qD}oWynhHt1*e&oT~!1F zbH$$$UNZz%^h8wzg}RW4j8K9jPwm2HL!arBhovvUjT{&21TXI&9FA2#A3==5Z(#7J z(cV35@e5c_5aKu6+0!hjj!ydqP+W_9(#dMU)Ku_@?X##_n~Qa_|2gf!%+hLm>%AJE z$=tGDR^rhf(V3}N2bk`ScigcsG4UH|eB$nTllztY+yRi9wk;{a_T<1{8`miiCCUuC zaZDUC6tg0|=mVb&u8*nr!Xl;^9s&l5v)q?Z;{DiQ5!zVrtJpH}x>`<&)`9PNlqeP1 z(NFj>0LhCy;zV||-VC;uTMSbplb)kKz_Hj5i38fXKO2Le8RytM*eGRhD(4kV1?B5mu$>34OzX1Z=GJ+976Ns zNgnYj^AmI<+lZK}HW9X%y&c>&+NZoXj+pt~R-GLcBitf8d$@5oObS-3Ha|_87Nwk_ zapDQ@-(2wY!u9Xtw@z%_`0y%Q0Y7&{-rL_T!;^L5Q^0)Wd7ihuL~a$cZy;o93N-c= zGhlGBpjgTN`8DtY{eX6@HPjL54A`Pxhc45wcnXfTo%4!caLD;F$)DSwuh&jNm|?K^ zjq8B*M1JY$u74wv8WzL6{(6cenuAM8q@k<2E-Yq_b?{EII<|Y$%Xxdu*?kn4Jza(*;=2E z`ErR~lQWNS6`~tFOL87o5*6cuFnBUaSv$nxG%!j#nnn&BY&I8gUg*^Sqrj~im7DIB zZ`x^V5*o|tn#^UcKhv@*ChME$%aXNnh&T=%rP{d`mGSiY`~)uICMas zIovF?!l_W{3y9GKe7Rfw;E#L-HL^Br!r2F%o4P6@Im}=$&R$2ay34)r?R|`a3$vaH zO6C@u_(fqCS+SdE^)B}o9lEg}p^<48Nr$6mq4hiV@ONK5AzXf6B_T$HwF`159xSJ< z3S*uEf>}?Sdi?!Aot7_G#f_DsRhPvwacEgE8Q?bg5RmxT5mnJILFPg;x*wIjX)<2j zv*jiMz783RWKclfJ*(z_)%8AB{Bt(nalfow$c2Ms6{x-Z9nQht0?SrN^w`K2!IQrv zKjUl3DN)CQ^+qelYoEpwH-8<=_`U#rfU@o$&{HJUb`jEMUrRxgw%*?s7d7V@)8Q80 z7WMe`s6ZougIt2*CQL2hbdTksWk{)(j;#>^(N5sn>00_V41&9QDK0fC$1+8Ex|mVc zE!5=U?(CHaGalN*yW6OfWO=k7_KWhVT9e4BKDusrMq}+g$LP0p{93+FjY*L6Mwr0f zFZVW-$Q6E>1LDDH(%hX1j~9^)6yTpDJMzSJAf!~PU zBm4f<*(53juUO|V1}T1qIpXI2==@QUAGhW$!tS3u*)#xXt<62I;|yC@OkDh_@O8z! ze+ie+XYzQv`7)L=hy+?nQOJo&iKtM7tv^1U)W=xXkzYDs1^asXU=kMXutDuBXDw@t^FUhWvZUM+8Jfko$P|qN_cDpq z4@F*0QD{49C=e)a;0l=D@)9!p1#ukzHnWupzg7(EfUeITs|vK1`@i%A^p76J%aS<> zXuDaT@7IZJ)wTW(Ow^1~eVF_d{^;}`lN;5_smqa3-~nRT*4?4)^drs;j)b=*;=9Q` zRP@0F<)S$90YEg+t%^r@TR^>XR5w3}o>J3|MOl4H{QsnBnN4vUgcBWLkAW%__XX|S zIz(qw?Bv3%dQBlemO{^m4KQnkuA5fRH4vY<&rpSE(b!0TRGk86T%>wqoVdE$QANmN9Zk8zFgdrT zMts3`MCPZIPVOfb^Nft({w1MT>+biD8x&B&#qDvS5y43_z)nxqm+)?Z^WN|bf6rhVfcfM~kRI?dp1?kDY)1Dy*$K%&B?k2Fdio0`zg!P2>2C}AV zrzRiGnB}*mziqnr3@%9`tNzD~@~BHn0cR~{myZF!^KSY7mZ1qO48=SLe*UXOJOyIbqPZq8pJ+9*R& zclsNf;fUpv@4cG05jM0HUT})*>NJk zi2}>okC?9j2L(TKAwe!$u@^OuwyKX#2xu9dOlR>TWCO-6s$_bpB1Ycf^8MncXfd!A zXY*=$b#;1>eq(`fFVf;MD}8GTD(@LwWmKhJNh2j!dtmZ3R)h22{Zc9xP_=?+xC!AR zRl7TXw6Gka-*1VoD4@4kuxjR<=)u_e(ybsw?0R1)6(~gbYzLUV?&?_hT=v@c~>p&ZqGXZcYa54fZJAqzcG6YS#3pk@F>qyy)0jG zjh3M|$%)v!*v%x}?!qz+3YAr;@JPN{Z?n^YATD~3#SBM{y@djG{~PP0@~^5TJl3;L zLn51(uqdxH`;T2Kr*A|P9{bexgBkBtCOyM>_Q}K+hlB^SpL&4HD)7ETniHYY>~sga z-%x%Pi8w{46SKmaVw}tP_gG}*OSffby5~K+n-s8-XDN*DpH+3({EfJbie0yO3oG2L zTlBvRpO40K6mohM*~3-dV^Nx5%~}qkku@2PRcT_F~d|b zi^#h>oCBU`(ghBH0N)InuLc&Ln&&!i#Z_XP`-^j(iuS(e@nZ@k8rk_L`Gk0A?uh-g zZTbRxorr*L`Ms^0wQ0SqC>?tDJdJr1MK+|lHck~*-x)So)K5!?c z;frl!@P`>?m}KgW$HQl}D_O*Jdk`jz?;ts3=B)!viyXJ630iIE1oFB60*3 zI;z-Snvy|D**AYn**~eAlPp@UWjG-ym(i9hBqp*_-r8$@Q)ZzQgPsrzRt6fXd~QbR z=6UL~Mt!hpcwp4~^n5EOrO`e^uRX>4CcvDNll2*0UU5eoPAOm#SGS(+*2Xq5Dv6v% z8d452$NeZm+ap5b{&}4*-BEMJ(AGo-kHu~ykI#L<@OXR8!j+OYEveb8q>r7d1we$) zdj}NuUnR;vSKx|&>|?j4_svi1F-kzc(bT@msfGa-B~O=*W_3bsZ~zpPT3vW>>YcHB z&N9cSFWt%$0%zeVsX5y!5s%1bFDx>DR?GIYWT*GV7>%dv(o%_0rpiS1*WjZXgOL`& zb%P1}-a1;=I!-upt`Rw#4-s8Kj@nM9te16^`reBzNmJxb^5cwp`Mu<5YBtrCRF3k# z++$-L*+`9Cll-E!_$fm2_ideY5yrX79orMhkeWIx9pMDbZh0B*i7zkaji-0?zf;^N z{hHXA|Ev+lz8Ja?O6DQR3r9$NxG9e#B$gc5qnF{W0DxVV!7f0(Bk`)w*@g;8uyu1E(MapAP|n_kotk^rn!O5_q*& zLzCk#uBR1Y!IevH;Z?P*7s}QoD9uM3C&-2`;raqHQyri92}qxrWX7;^+#wL9W7rlb zx5pt$2TR@A+6n-=3M&;qtaOk&tZlGzZ8&TpX7n9Y00(TwH@VK^C}E4=6{9!#B`ue_Kfe4CX7TUf#v7V5E~`(Ij`rER^1>5DHE!bgX7it z?T%x$_>;Pfy%2mt8ZK-&i^%$M?-kcluvkRXxa`+S zsotdtlA>l;JhN@YGIpr1_@gY;<`sIjREB@G09PR=QEOs}^l;vDQENXG-(maaMz}j1 zE4-0=Xpbch&R7ovzUgogRYL9^8y-$KcSd(Q{#sGZ+qz(Y*!a;NrVkta0>T-c>4GZs z_ZepALwvsmw`KF$D#gNIThY1|Sqf{N`Y9Xq5&N{fG>MMxu{@}&kyDt#l*hFQ;UD#_ zrd$z`-;(^;<{7r_PH<+q&u72<8dXwb_L5z!ME$zFWmaY;ae>Lb&dN1devu7s{0rEe zW$S=F`H8~MgVDVpDXR8Z2;Z#lO!I{%m7PO=s4xzbflcS8RoB$=Yd_P7q07<-Gh=*i z_6;MaBunoeBf`jMSU3?<&7^{|J9P4dFrSJ9x%?4GnY+G*`W}mS6UlWq_A)98T_w87 zTM&9Y1@BZEaM%xHNfH!@H6X4akS(Jqb#IZ?YpW{qzR0@5hqWvu6Pk4J&$m?~3mk$XpS zfGZ-A-o8n<%=vsD4vh~QOirydfeV^AEPA&=IQBa-4f)x9b%NO z=kjC)u}36(>It*wf-My!i9GmoBSc;lsp71tpqZYO6uNSOOMU0RK^(RJ=(gLm3orRR zwfFT>@0@P;wunT+Takij>+9<`s|29r@vUfNeHilk)DW;cMoU#2gltpiU)NZ1u($8A zs1oZ4`P-=yw}~xBpKp_N*gde>MzjolyHP*(#<{O6@)Qt8^+r+TYUclfULi| zTk^YSP~gP#UoHP_>tmSz&EH@TKdR+CuZ~K7Ii%lxKX>r`w$LwsL z>tI_(>V-;DPMu~oVXG4|@91TqY+5*D7Q5j)lu6F>H`fN$5inb<%-0gcGFaJyYG%$- zxEZL)e^O#q8coY3aHynkAzr!K*ju2(==7Q03awTntoUfm*Ddp)7b{fMCg(i`Iq$t=8E%uOEFNAS!Sg5&5CLUCW9nt7PF z{lgaUcN|3*QBgJ+zHdK`xEI$SIJ`>l`6cOQ)*0*U^OmY)&+G={k757!xJLjFRdw|M zbFI{)YI{+YnK#EjBA37g_UhCjBy+naCBuR56C$f2XfYm`DXQ_Cvgu?>IIult=K=-{ zfs*dZfxyiaSsjB=-gn$PhAf~Lisgkw3(rXMH4=B>S}u%I=a~X}XCmOqqgRa28ygf1 zvwm8938+S0W<7*UNIQr#33f_mHEJJmDgv+WG*2Hc6Y~6 z^t%%(9Vy{oVSn%V6o!93S|~T?I6);YI9P!W$K(*vDl$a<4QVd$CZ%D>85MH;;Q5s&*AlVO6aOhkjMR%N!!=j zK`z>A!M@2OpJ03*pEHS+Qeq}0fPj7zpNjAnfBMQo3jcXNniBCSU}dt>_;OGM^%6qB zBugyycdyI+fd^z7nO!6J-q4ZHjrvC0ss5&4@g}>J&XSa!kIa3l@hvo3;vYMIO9IYC zoEIqI3q*bvr)EZ6GnjX_=|LHt*&`b5Rq?m(kZzyVa65Y@mqG!%zTrTshau3&&o+vm zeMh5DA%l3v$_+HhY4h7aUiq_vs7+kw)giwI6$}{UWUXOd!4-ssfNHZPeZ9jql#KUf z1PzzHXgHY_&aaCQlHGRnuQ{(wUv&5Qu|GT02&;Z!W%How`ne!ov%pTHhp0+vP4s?n zT#rXHdhLSp7!8v%d*9eni&DbpfHso&Tb2~Zi;7#SIHr*V%~92OW0m`3Pwp?w|s=yf{u z{c`izi6@xH%x||za3l)Pe&1B8Zdp0j=XsEe$txU(0~X-8(prbYjR!$(yYjviYa*R@ z2(^8$M~5yPIPBB3B{Z#;+E;2nzsY|~G8f8mudle$m&RwZLLU4`BO%CktqDHKKKV+ig<4)?{)ofPRE4pd&xz>FS^Shg zIoUmk8(0L{W%qmZk$|52U%mv;!E2%ehA}_Yx|7i0#0&wu8~q+=BC9KA zAxp1YP-9H9@Wwx6Xf(lqH~?P~i-kED%HwmtTBJW?w0PTQsNsM~iaZV@k}qRez;@Id zdw(zAJAj%ioTFsjfkdA?0q#(t3 ze};fBuR&YnM~rnktjsJ!TjpuPmc^OoXWv6aKTmYCdlg|hBv4L8&8XqFlI#7@ZW`=< z2L&5J2^kG>Cq2I4EkugHs4eZT;eL5CBuWBXmonpsKeUAnzsgr}w7vhUE{561cVL-Y z<8q=>(5rlA=vnPQ@e|SsBC8TV7Smkw6mU!w3*DGggY}zv$KX-xN=yZCIN@#hYS8E zhDtnc5IL}3La!XZg4;9kC02HregJ!1%=2`r5z_NYR_FwI6u$pK5k7@WI z{fjH(@1nX|(4GTq8z&0@lDj&mT~a%7LNo{w?jN2Dvv5uOoKmNlWq0!SbJmC7niDL} z^99ys&=i?!yoH?a9XTB2+i9g|58iioz#|ma&;E8Wh0zESs>lkZOIiv%NH~!W;JG|! z#PFMyOoJ-3(?B;MtOY$T)J|CPz*vTPKk%$*n$Grx(Gl<$&m{rm#L1FQA`16gTWK*a zW4CJge7PpuBOS|b1AvP=EUbFo|9msxJ$c zdE{uR`2jEL)tEhOKBf>GmEIsss1;a-!FIQ+uICRX*2EkZIGbSO#rSw9%cjqv7Mrk zS5a1UW@DW76QuY@4;5<57ZLDFuKxG{d`r$20+qG23oShh6~;n4_{k4t*Xy|rU(y|4 zX6Xig1td2X<{QKYwjHNT1)l3_X6865UhioYIN|~5u-P0jaccY+s8yg~UpwK)u4ti@ zEbT&2j9ibj4(2OGMBqU;O5kf?Sv zR=|FTJz6b~bj_!btlcc4syYut}~FOS^Y0 zEy2O~KG>oh=UBaWI^|}%GkuUHDcRG3=B1ST1i}XAqGG*O8c6Og{5%?`}FTQ z;_Gcl5tYH*(N@J8)@sa9@n$b~-8FUu3}Jl~0ljpL-00)v({^l*mgbh@G~pn~O$q%zz*Qye+KC;wlPcy~H<~eGedO_w;ebvt(;W&k%xcIci=X+Oc!Fy5&Tx z6N>M)#sRV39WYmts9Dl|P044_nAOz%HI3c9sYu3A$gm?N!9X|U_k6zg8Wvw=#yL8k zVccEg9T-DZHDukQ`sKsJh4j#yM*65XT_39_)(V0ig16jXL}%s#48J&BW9y4Zo{S{E zdpdQhTFji*^WEdogFE%cjt#6~t?gsKZsbTny{QHc#HCgU+cn=RMI zlWj@PBOUkj@4zdcTG%2Vym<0S7t`XHM^vnGb{z%e*@FI<&4XP$=1worZS?(@vpfiG z35XXdnd*+QQ*<>1vlcA9WT%B4UwMtUU02ac@>+a|{yg}w55eGA*7SM-H5;8-eprZ5 z{=wt0!=Skm2_=+{uGT846$P0)w=TYRmJ$@xW$7`s4G~oqofI)V=&5=(I<}Piy2MV0 zXSnU#b9F>nsQ8ia+JT*V6zfU*6Im}xMS>8~$Hy!xpHer^AF6naRTg=C;^?r>2a2KU zBm`-f^)&L2gB9hc8x9-rc)$}H*MnJmtcK9;NiJWygavZUs)(N=@6+YmlFD+o{a8DP z(km#T{@5)rTsXO9C~W@moGw04m-^u{yGx^}X$!oAUG~U5fE>C@uLdSV?09d(?zXi} zZsfR%zpl~2M8xr>=qigsyjXs6n)fBp)NNJW-8az<{B6Dc5&XpTN_c(#2Ix3E&S3J6 zV_H#)1wtP$2dC!>B1xqvGwqpBx)nH`@|6Ne`b;oe!Q5a(f?e-?smcv7-SD_nh%S-E0tu~ zqlKtT+s5in5k%j`eI+XY+7Y$a&e81l;%m!;9;J(iSaV;Ah-cWEK#ZuT<2QZJl+Ls1 zJ9UwpPx9mYIdW|21gyWX89Pq4`AT zYX*k!;_7NQi0sRXcN<5W^_hj4Adn#tc2BF!K>r8g!Kb@3rTV%*5aRF?b#dg)vDf)| z_qHMI5?SJxBX#tT}Wypa)p7s2^PNwhKoY(33B{=IJ_3Gt_ zM@uL2f)4q0%?D}Ni5&E>ZmmDR?xh0_Wg$)qybg3VzbX0VmKay29h{SlubU4LsQayH zVbnj{-J4B4Vi}lUU&9VO%ZEqPA*A{h) zl0c9^un^qc-92b<2!Y@P2?Tey;O@aKcnB680yOUK?yikn({MLAC#UXr-~ILKy)L?_ z>fO7S?zQF`bIdW1kGj*2J1a(gRF-8Y?7oZc`ZE*8gRv(0Y-5afv3Y4mY+JbAIZwWI z6`nXAisbF~=v#&{?RdWNT2tM*y{EC)5_N4!lk|5_bRn^n2m$5o0PU$r;O+t#H1pfm zoQG(KsB`(qn2-8em^PPB>gF@I6;VK~hnF9NG= zmb12lwWF4$u+bCp*B(oGiw1;F*oOzDXtoqr!aWB_?)FxWoOLlGjxnDcfOPg4K`fMe z!l`-pvZm8p1V+YJIrHv?MpT#wEWOY|A0wP8X z=yx)RU?~DAvyjOO+6rH(oE`B2=Z*dB9yJLGb;>7jEU`6}%VOJ7m2uc6zqByR+g;Cz zzU5{;-0jkoJ>^GnaaxsbHfu|d(bN1&1$$pNI@CgdJoGzLD?SjL$H>A=_b|4Hc9O?) z7PW=Qh={@B7PVsaq2eV^p`Q=xi5>F!Q7eeHcGeQ}|6hd14t zvn})Z&jU)mbHEUpCP$hIeGop4yP%Tm`9(K8NQmsWK5D!zHDYN?d?j6`fS4g;XWNl_ zJ$B)SE(e1h7@5f@!1tn+*?NxL2kCrw@xj^Bm1(LOY!1;YO&itYu=4nQda+#kTHo;Gqb`a~s2Xh>#Tl*^ zNe)!P)jXbQu=y!4!)HXDZ3QEzM>Xd~vY94|e$D9m- zPzMUEo>wIYI<5<^jeXY3&vadq@K!>jcRi?O4cScbCgozS(5o^! z_$-BK@r-R`Y+g&9STh=Vv&lRNiA+7JeOVR2qN!#O`$4DJ0E&O`oXG$WBB&jZPNwCb zLYaRrAGOw%ixy1>b?i~u3d-$lrggm$T6G<=FWH`EX2$_Si6URmVdk@P+YwnFP&bxC zANWb*XI-fI=0*o%^+(O~HD=4$wKM9HlSK;U%Q-VS}CI6Vh9T$sUxLckG zk*4=3StrZ4UX0S~qTiN_U!&E`JgM@n>FeJr-H-R!`@*xb7c z#Jx2OD%%dV8sLkn4r+jgqf~&CWGpXL1XH(G;lE<;c?pxlQWG}*-u19DpG!JxSejkn znC0R7B`?$N8d89|Ud99vDar1MSw{2@lgwE5S=^G7wJNrb)>axvC?8g!Ob>+4}-SZv6N9-+BZqYK`f{-0O6q30m z`w~oTQUpdr_JZv|UVAOiLrb}*j}LV#jTq1*zEn5xp7miKt*X>x6n;(!-_3WcZAl>i zQa5&`Zs04xIMLV)Ngq^1uZAIlqM}`e(AJgU0u0Gj@nB zbPj1IZ6BQ=?ljAh@R`%Jx{aQlncDNbB?O09%ZL-rR0C~P%QG825!a?NO>zz4e_Q}` zE+@F`i;kcjy<=MX#)O=MBlaWHdCj+bE--}UQYV=q!6G|`tb(L+B;kibc;JJ55ce$0+z*ECoN3VFpRRGcl;cLy)l0D^T zX!Ta1ZK^8IT`XqHHN!0|5Ketlcu@Nb{gVkX;Clu(m86mCXACtzw?FvLV{gzDCMPFHoqtN~eIVfC;+iaZIVu2utMAS#L_nrW z)tLGiXljVU(5y{fGZAF<@wcqK^Ex!6hz^W{uNn&(Z|_2%3E*<@j^g8aJ)fGp$k)9&`W@3mwv-WVSi7r_^tNo9Q&lgRaL=A(H z!E0?ET!+EK8I(;R(Q9=YE1NA-YQF)h%HRdWCbf1CQkm^_^gW}ugF6Bz&1W#k*-_Ck ze5(|W-K{RXGFQN*4YCrPTvu%hW0Oth0TdE6bXOp}83YFbZJ7p>^TSNOhooE|G= zvETA6*dD)AUM9@7u}xk(r$H(oz_7Z+#7kb5Nm-v;a@AKfundnS#3fG)TVtR>vfBI6 zG-4KJ>bx=M8E_wjNHc=Qkv?E+ADywd=2qsWEI%=JNao(B*b|B(o)r9!=(648ncz`q zL;PkwN=i7lpn_UivAwT^$JZMLv@un@AowcEYY*B?#L-HI8n~Jnk_*DG6@B3z*`I^n z{N(}&if^yyAUs9i&no}bYQ{H`wBNy$K)d)fpGAF#Xi>QU#FIPEOB&k{`tV11MYVXI z*&I{bx5z1_K$NV{lZ~`Zj2!2)q7?YA>8m7m2 z^iFUTCWKV{<3V*H1u*9t&3hizF9i^!ECilWh@R;nJ%+0$B`{?u#FZhB&Ipbj(6IRh zOCc7pJ94d9SVAnKdV;bHq}jBB$HL+MEwjXkjL}ovOr390 zE-$Nih(=;~W4kI^EZ(0%g%7T*QMuo|YZ59Ylr4=vA;`w-^XfS2GTQ7Lse7(i>VMVz zkis$e*TGPj@QiI^1t&%NjHo`2)O%U%W;bsWlIPtNYnBjxM62x7qD^iku~k(U#}JG@)FQDB91 zT&VCGE`;Ci_)Qh!BB*e-m{%o|Ns-XMae`1d9F*DCx^UdX9g}Bc-~7#xqzIXN-ld-A zZXgb%+&!_Mzy2c`sK(39^LWD_H5;=Ud+`2v;d7rHEo(1d_M^N)HK=b^TjzQ0>5>d; zj`}Ht#bVsYb#qc$eh-@1`+l$KJslVzZ5`=1=hrZgJB^3?M&zSOx;4($fOvSF@~PPH zGZ;XF16#H(Oe+L9T7zo-Qbw>73~H1ZU+%S@HYHs#q0TS9ZBIL+tQ%snYtlF@zd{$< zAp6bZd)=YD)kQD;GU8LmvT`$tg+Gx)MeFW!L)&}auF+aEB;6`2Zvt(r*rd0sC{m6PZc#D`jT?zNYUqa+c~Gi}Xyp=Q@1JfmyKe2BNpz zpItkZ`T%=Y5dU9BN$G@#l)2sGowT z=dFY4hsZ;aC=LruXEw&8K_d>(k#Ix?-JNv+;*2p1sh zgVp&Z@X#2pjBylY3VeO@xPWJv_A^U5-l@Vof&lF?>4Fz`B|MIAN)HN>Eq$@T2w^if zXfw5`Faas;+4$~!YC@?gkVFLnwl`1zXplbDJ5R7V7<2K;1>>j2#6qjOP44|^hUPSy zw&uOB)oz}t4@oAhfx9*&nGNh7Nkjm}vW8K^R$$U&QLg1r*=f4$QYFj|d2z5GXl3ou z4R0z%8{uEGuJ7|%sx10b?R?^4cSr@_yEH!0eRF98_Zv8F%BGHTvQeOx4&71j!OV2Q2?Eyk45-cSEy6TjaE6=65(JT{HaE*CHMno$#0+Vkm?r81@mB=C;o0V)@6(RU}qu)#}2!E(m`lD1MkHcXrqrlTV=ZtY(esJ}mx_ zU@YtuXGDUJ{S(ban2i~rK{hcXz+094j!xlvfsb&(zaA&`#)ny=zCqN}hvzm$fYgCj zb{rAYyLbLR$UvExL5(iNaCK>|$D2-O)0X8$U6yEv|AjS8{gNbzN2-J;dZ(+k`flIk z-a}ktSSmD~X?U?ohxAf0wVgasx5652gMlhELbY=Tzr{I(&^RlkYF-Us(fDEM%awd|sg)MmW7xs5>Y3Z`%ZpJeENe)k+_RSuJ{bwoWmVBe1S6S4JY=NbfuY z6>-E%@ixS8!DZI(TSiptRY*l*z8g8jNa!Y)c?}2eF3Rpo__e;nDrXT}_l#L3!^pvLJI^_y)Vye)PMn{cRIL0;ESqVTeY1J|~~CXrQITl6@T zCM{bK-)oy#TRq{$F_90>EWTOS?5_Eur|y}H4ZK9cXt54zJE1It<|0cy3$%weja4nh zFT!}vP%?$ZzH^CrJK$6dRpr;wWF$?auJ2F}4(cvQ&d zEYF9Wz9nFSVCIPo$G4^&u+5pIa>iqu<6!z-VAlyP)9wB&DO$nYYEa-^nh;T5t z#KhYq4{Ic|Rip8w`lbHLHi?760u390P;d3bERf=4Oo}%l|Iuj&b9fmz z&zqzsSBb9IaO*@#=^QO>@^ts6gWDm$oILiS=}j?ISDwC|#3Yd;^LAFzab>S!a0k&X zyl>h?r*Rs0=k3!vQE?)V(L?w0)qr*0nU`(9>86h9(;FCzud6_27R!%%q&W9w_B-7riGl$vq*~uxYQzPR9(ZDIlLh&Y=Fp zc|9MpM<64wjQb-%eo)>5y7sWJV6d1jNpWZ#NMdmS@J+sjTTkJ^?S@Cz;Vt{k^C^qS zLQ}@AJ(Yl|-Q50GE(- zm4&(aY_-`$Is~rX{gPha>vF2Z%G|=j?l1It-{W)NQ(^@=&j6n+I=uPFkhkYEeYR8x ze)PUN)C8PC5Y;tLVG@8*dLAZ;Ju;NWbGrogme$wT@48O#EH5c9FJDhC)vSUK?r1}1 zX%aOu+F+NUKEnl&ovzqc0p8BGR|7x5ffRN^ z?Yrtxj}I%40#B|8{;e98mixFB=&{TFu}h25P%2l`Njvh>`}}t(9XW$S=JE$(a3%ta z2t}1E$p3_zMyT+tx&>6Z|04-uoigmLyWS)Xused5{=trl)`86t1r05JWXDtiG&4DQ z^5i@N)LjIDauZwbKX1Qg0_4XY-N274&126N8MGS>1NLkkJFQC)?uq-=YkG+TO1shyZ^#Z6zFQEw|eQ58E~m zK|&r^KfcMn0QTli!-_Dl*>+=Zon~nJ6h_!BmM$bd`TFxI!z1X1n~<`iJhJv<)T%5| zCv-O2F81O9oz4_ZbI2RWwng(V$@m-yLdJjY3&R3*O0)6(65axg&;14opWS*u+{wfT zSrEe>^H~7yfNdVvJNrdn8>P6(mkhC$alC*~Js~ot2aVF>hVU?~Zf6h01t# zd>|4uYhdaX@UZhoU6(&duN&q+M-#yNpZLQU5?;65Idtk-(98Jb=ajXh86W+yqt`#&tge9EQ+-&3prcUe(`qb!T|o$i z4orN`^xkI)|IP9*TStv4uu68m5H2vfiLvf9)7&C=H*0`(vu)6K z{l&-M8^Pp4$&l6kUPApZ?g;RXc=Zm9ctt!Pch1mLCUgV1vECipuFYj-S1-OD{?rBn zP?=n!a{z%Aez&Rl+NzMaMJ2A^@<7lvHGMWBcz4sBCsPd|7Bg#UM3-v{Z-lca0$70P zkv#$+6!r8{qVBNlsaR$^QbQO9Ll8NgR!_my^ZfEk2OHlEI5wb~m|**0GKM%O4;-(B zB!Ms+gvk7m60HAHA4C(KZ!5MRW84iJCkbEyLm2zwPiB^VCi%U$Oo@ z@)5s-{dPj-31C-G0sKq9rin<;hF7cEc|W_mB>y@Zk`JR(9H2*An)!Yq&TbqwUuX61{H zA;@wy5bVL&kqAvN47$n0#?Pvd_k8dpI-Zv5cW8WfmjBzlkpB+YZJP_K7?BEm$$6N4}F4P@)_Z`vmpFcV5`(zF# z_p(b~(+SGV;I0gAa=jWZ#P&*wts?q=0-U5mrT*gp@>%E1)AOGrdRMrM_`OIa2X_PB>oHI$v_@?KW~ z{maXkWJjXH=of6S0#2)?@Cc0_vQGE9!6hVXLV_V)AJO*0J5VwNWL&*`k4qKjmw(!d zf7c=RsE=&brfNcnGiFAO6~^xL1i`K_L|+>Y05Ktd-GaSF1t*F$720p_Sguw}8zDb4 zMjePPx1^r8$YYwlQljh!<(E;(py0Yjdr<4qj(L#wD?9kzdptm7Zs7&k>R=a%4Z)kI zkCr(F_cTbqN9IDe;~dKx7jA}ef1{vf<_c}r_SjB8-@se%2|8(t-Ps(tmYxEYA%OY6 zTu93t4k_*z`ke}%*6C6r+?}o*wEIq&Dcc6TOFwGA9+#NhLaFeQiTKE2ylm@G*WPU8 zPhg|UW2J!cCBw@Vr3%kz(eD|q6ZT-SDKnC`FbRzVt@w7~FdgJq^s6;@0h!~P(2bS_ z@9$X);O$)>vwfQ4d%K9ywdYpg&wLF>#~#jy2TM0vMAck@bI`=JXuUKpF0Cc8ZX-dZ z${CK9(=ua51xFwJo-wjJy=IcS<~CmsifZ1*JrH_9q1(Rjj#m_k^3@RB+6TaM-MAoN zE12bHftmw03Gp5YR{7rv?&X<_a zpn{bn2#*q?+S4SwF|oC>sIci5pNZ@hK;3oZx-7R)K$@xh)-Ww7L`cLemq2Fyqx;Qn z-E~jIC4x*DF|b?*Z`NGRm3v{t@_qT6@@K=uE2hjSBR&r7g6EpH6f?qcAHxwvq76X* zrcvm#mDUC?4!atQx)_de>}ALIK2W*x(WvpNhm&HVo5OKgzjZ`2a?NEqNJ_v4p9rU0FJ`V&XqLl zD9k4u4ZluVM?9Js@axu=NNBDM1JmGN2{#=`_3CE`U%Nf*+`OHu?Fr#hdc4;>R@f+mxw)!j;ypd6&5u+* z5+}%^!n-ZY68aV)8}=cE2YpCS>`2jmhl4|oZm7pKs56u?3aSfq-?e6)i^H!X(eb(Z_;un?HP;b(%*hiM%FJRdU^EO9?YB$=|PRElkSueBMoE8G=j zn4MthJ_hxt*s3zIy6JG=B580qf`KTdbZ)Iz!tElbOW?*~ z@dcAz0mAI-@#+%CQrJhOcGrU)-efI-sK|uZUD#D^yR%0gS3th9zMRI{{&dZ84+~Z2c)3W;9!<0NPE4O#kIt%viJh~me%Uw!!c88F7^^Pu{sMnAaa`K^xlZZFNFMH^ zP|L(Di&Lq3&|U7lX8B{ZY1(g2$Heh);lzr8d_ack%O4|Gf>?U%`JSrX`<+S@FZDc5 z=d=ZwEzJD+ReR|=TEcSby#)>xc6iuaY8UDto)&;zegwC-f)@LjBhlb#s?(pp zKFLnyr1yK6CiEzLy-K>Gq1iRf>xR2-&1;#TY0fMkdW1q4hHh0mrU`Ca*za1{ry1RE zZR+*mOR`S<6q)dt)eMQY+8=)1{K)-kt3IGeC_qy?ez+55sSD$9b&=d)CA69?=eiqX z>XS$*v0=@7HdQM-_@Yip{F808ZdR@C0?gN{MWt`e6F%U7`>u_ZEAWMIk3D)~=^}Ja zj>QB{z@%W$Xylux#lx6YN>9DGDMOO1b3T2a5xaZ7mGfKt9hVwp z@u3({e#Zw6@!M!1PK-T|qm@wB>06ahC5aQJcU`!KPn@IFXIh>_iH|nEw}I?%7ck>l zdCKKozxKpmBr2;g2w^#;eBa%mQE*qLn%EJ0^!9by`tXIYcq3~V#kVaadz4Mhtd(;H zS$Pl3EF#(bC5zz?w(NmC+|&)~0CYoU%4aP9=IRa~8d6-0)Vs?(8@ns z*Be9_z+Y-oaikt37^-67Wp-!_-pEJ&rYo%Fz20?JjRAF~wp|T*HS;ZuOg1uJwC?p| zDdp)hu2-|ly?}PF_0_mHe~8igk1JV@AsY8D!ii*K1QgD6QrFK2gb!~NC3yu)1$$wC zjt+zGuqPQShNb!Pf|rRk@4WZh-Ruz|-YlgyaI7B>dXDo*B_WCe6~TmKumir8LrRD8 z4r{k$^cT3{gK%#=?tgr}onm&s8nR{lh~E=;g`63fTBDA&eh^V8g?s%uxD~c9Esf~TG1~;Yxr!NSKA!(!?)d1FV*XYVW4I~pWKBYT~chHN@U}S z2j8>Kw_(wtT+8)FnBs>i*eB)-3BOzy5)RlgOmD3%$}s&Rh|yBL8zI#j^?eeHmVrZ> zgG59sLX9<#KAC$^kGESRKUmw0oo|~<3T8TmbzIy$#?Qsj*t$UZRbsx~btt;wTnzrn zzlqf=k~iT)u8Ut-SephXNkgyWmUbz;2O^A2K`OQT)$U70=LYRN=ki+`X4#kD37~*h zh4uy*pcaoVuoWmaAn_jtd-B?|x!>&=kaVYH7KvZmrO%c=NB+j1y6WF>B|aa zmC6^`GJ3mYnpQpP91jxts6u!_XP~#Ajb)E+-K?U?KVu@rO`+BVr#2tgSe}4{=}Yr@X5QI{o?X|B0pC+=s?RoauSO^ zvkUIP@@pkQU&XrJ9%^Pe0Dj^G&@DO_T(NJ`U9%zM8swpOIZpO(1GQD|dvbp?Y^lJ4 zDAnL2@^I_p0$;_C4DAP#-GfcPd$&7~NS`#P<&=?yILRvPS<-jK)kRc-iQ)T z;qROj&@Bw*^=)2gT%6Z2$TkxIVQx1PB*#Xo!W(HA?K{-q0Tc@{6;UF+-ii%=LWm$P z0qhM6?-!f&$_xUGdz!deRHskPX$GTH21PQjBZ1h-&*SU+(r?L=CS@qT?UW12&KA=X z$x^q8!ZXHG&#K9Q_Gr%7lCeooMOf(HR2$gOL*!zHMp(X2>TLDOl25q*=U)st+ZqQrrur54{$^H9z^p1Cy3|s^K3H<+Q79#G^wyzO53ka5JVtu9Ndr;Et@eXHz3L3J5j2UXkpT~+TIAEE%RdbtV7+X#b2wU zJUs_`^#kK2HKzFWKytDVRwqObXLyJ79ArDwow;)(F5&~^mCn3v{8^1@wH^dy2u*YonJgPm#9V6tN5I_{R2`@_9*^| zfWp^m$rYN80n4w(tS$}9CXMEKo&4t95U&xQ@y}!Ordpv8p^R1z_{pd=%rCs%eHUWv zCD7vSBz7D75;@b$xgBAt{_?G7qzM+6WMy6aYEiK=2UYv6dGz}$Gil^Zd;yTIhsuKB ztisE=Nf;q;;GTR+g_WQ21KItS>5q>0895N+fC6!D$1n_sNL1EUzBk$BW079cFCWR! zqK2e;_42_w$*o0LQHnT2l9oAn8-@KcC)GH?6TV)f(LPzQay5SZ$)tDcUq9&+t-+7n zv{N_H_;=z9&Fagpt?YEFzY?E;?A|nFo#+cW5>+pw<#h^MdkcwqBhpk5PRD@$E5l1Y9FBX&Y?;_KitanW6JRfS`7CoR9Y&D}d55Y<|UB4ha zAFX~91P^A(Y7iD}5|MF7N*toiMC~ckpQsrTy{|`JnC3t9crKwP(6&t6E@E$}og3G% z0I%lk*UToiFfM`0`@?HKq;I`-hA#jr5wR6E0mNfeJLwWai)#&PkP-)pnm}>0n8|rkYu--+sAF5vB@QN?uG(0{)#i z#*?*vTbIP^8N}5|&v{F0k{O+~mSqivu_%`JQq)HlF3b@sHk{cDg=QHKiWVx8K4nEE zR;hTpm0=Dkd3^gmE_)(|_Ao@(UOrp2VBRw~En`xZmAQ;4Tu79g%B1$idIguXRk?c{V*UK|!(FRar3h zB}R4c9&%1ZB(9&(av}Xfze<)PEJ%ej_m>z)|I1H-@SM51UpRjmI$k`q;BB!*npoZ< z%pU(vsME-9;LvX*>x?@y{WNpD^xjVj@igRpD9E@|0YMzh-%m71PI?4vt%hdtz$^(d z`&nF^q&Bo+%-)wF5Z8+pX!f;-OaJ_4ccx@KLWtP(u)?r_@pnP1&rTb?)PQ^1d|eCl zh~3)jp)c?g@GEjs%#!3qhVH|hkjm)iW@t|zrBkj3qPszX)FWOE;>kRH#+AT2BWYZ- zJ>0x`w~<;7G~&aFQ$vTAW2Wmm(lijF0)V((qobpP$PrOzD}et=P7h4-aGTXo6~U~| zOnu-x7K;&saUvG-nL+%Tfq1=9pdbORPY)5J!KB-vTc=>Q|Lr_rG<2R(A-Mt-7??L7 zBFbDvE#`6=H3z}x>BJ`FrhqjG_Zu;zaAN&xlk`GWGSL^=;9mMSYZG?9 zlWK#JXL6npU|TWj$9=^C_OX&hg?f?fTYO1};5Tu$z$av#vfpBk;o^RPCdyRI{s8 z8pop8NPoI(Aoi)d#2ERshKQ!W9G|?hFPVJTt_xHa{m(NT9{rAg12b)wO<+?7!;Dr9M@60tFS7otIbRn6;C=?zzUR56>B>_CUKjE#A%l`*$<{ zG)?eB>gjuqgw}q0g#RjrSn>6bnY*5?!N%X8`i4Ox()0GeLe|Gf`Oty3A@8$w%ME?u z{P3;_?{9yJ35xx>)3B`s&!;yj^1o&fOUAv%0J;lY9YM96V2?olUk|EC{TXgH8+G*=3Jo{q=7N?g{B3T3IkXyZ4 z?de?o!k#Z>Mjlnsy}@&pK@31CgMt6F6a8qH)+cxDyOCwP+EaA}>u0?w=C`dU?GY+J zy$?9l;=~_{Kr6kZ?XwTolB$48RkJuUk9dE-T3gs7kE?mjOF-dW0bBk;l*)NjaiWNG z8WxOx5cyi@O{36Ek}77>F@q8ah6C@7U0Ah%-!M8m^7l%AJdZJ@S zsR#WIUN?izalzvkO(kguTG-2m;pbY23)9RxP&+Li=0%gqWke!>=jS-EoCMTOw#8{D zDP-w|8*t7`R%jfF@ICD>IKUUlweuD9)YM)%Xhl{}Q=a*$+c(v;wY87Yw}*hl%>4kh z5k$q#6XgE>m3M$230s8%?D#Gwd3RC)4KrHCfQ46 zM=5!N?Q}yNISpr4h1z+srAa#xp0c>XsWEe1I2?*?`Cw=k|F0wg6rk6`{r(IFR_XIm z*m+5lVZ=xZsHl5&eJF{$}~I=bh4+X|E@-C{`6pV z`o*?|1OLNvUQCnqUFXYcHrS81JYMXGoZIl&oQbgL7o3k%xr;m`TV#3nXSLkq$YZ=D z3+T0AmHIN`Y@RiqtD9@uJQet8Y40`-mnCWW=zigm6C;NKO-VZftfNxwTsHxal@L1{ z_hB8LV=jD72CD$;9}?HQJ^OtN;(64iY;r4jBxR)sY-M9PK0l+5$^$|a=;li^opQNq z&7F*%Y#ZOQC3}#5(Eaw|?+_j_XerpU zGJwjy!mo-3tqFT>SMcB01Y>TTQuCURjbAti$=e{hK;17aswbhGb}dB9S+l6!70$fz z$%H$6JX(?P8z9{M9_b=&zWgg6uaHSwtU7N`;;*J1MoyDe8Jwk>(O{kl{NPRxZ=LB1 z*Xp~=NkDYvGV#4va|ri<;|8}`1(cBudP5L3W;p%cgOvLrRdxqiD*|HFRbwU0(_uL? z%qrb3OX0zyXckJKB390+Vu~-Ik2|zrSLYO$KCg1@ooHGa6N<6Sb4s|ey&GsIWZRSy z=UCfNkrKH(6LBeiJ(80L@Soz)#lDIDS?o+Mfhl&KP{l-x&2;or?S=lpQbPw#o%Lz? zO!>LU!=?V-!-@DXwER)>@$pvVe(UNe7&jkSyJdv;+N%bX#t*6Ng@;@7nV$=McZepM zNsC^e%%fmUC*8Cpw{1oR7tz8(*~lUCD1>%v?nX@t^yw19c!sn~{x1H0&`mJzon^=c z!ZPG?(}9jZ?Z7tuovO<(|Jj7%&XsEeB9w{AUrEPB4GTJ{!yk3vthG)u4|56^qOCjw zoX;YuEg^O}Jxh;e5SdYzUQtSJt0K1!I zFO;NuBRRQx8IMeevvX?0`I|!NJ-<+GMq{+&WO&i|Tgc_9kBbMZeB@;&V}(EWA#nSV z8BHQ^yByI?rVNJna1aFgJan_6I;Bl!w?2N*jwL&q#!IwwUMu8-tC@%)4Y(CbzTg~Z zjz%=&(*u65N&?$dweYoaOrgq2Ozz^YLVL;ahx0wSt06UH!mHEw$`40d9C=JIt2uSQ z6*wlFT#R}%4~yF11lJWHf>zrf*S?jwQ_ITvzk2-qnyJtbMF;OYB$;U0$-p8irhjO8 zQVj9*N8BHy_+?xi$3V{{#tFymK`$a~3zX^U4YR_9f7=N5PKxB>vMedm{Ei5$PxATR z-#T5{6i*ObRNYMmwGTBS6((zL_ZFwP+|K%?MXx*s#%gIRvNVpV_=nO;l7kR_coh40 zM#E~*i;nFn+q+|l7ER_Br|MWUU2f|&L7mBymfPIwURlV)3IF=;GaUqe#}TFaI9HL7UpTsBVO{VO{VuwkQ`r;9%7MN|0e2%=+>S z8VI9P-kBpPE5i_e+=SbRbi`56;e1GUx8dzApCH>l5*(w!gzOV;o`=FFX zLgwMkB0WN2*34_*F-HpoVou_Cgk=0$Imj(|Wl|F9EFbACh+s*{pGKoQ81hK&S0^C# zYwf|fZrk+tS`gmj9`1ux)F~(~`}}J#vuex@i%@d62#e~FL5cRO`r5nG45zUg?SA~1 zWD>&c&-H+fPVc?Fi5Z@{8v7h0&$!vc(e{u>w7xC~f*0Nd-ewaI{e$UtskLEkWG=bT> z4KGm81_#SA?TMFkK;dcr^*5|91Zk#`e$Z9lfz7@wezx;jYXYhk8lXoG`$ID*=uLzh z=8mj?(kcc|B0|aMGRqU}x)F!D^6}iZi**A*0vhSueM?s*_!G+%P*o7TfRlOL<`BZ1 zwXkN6jSFk#g!BQ2TU0zwGq1gn1jJNBvd_w-)r~x0!~JWbKBYlD+GBLbiM>EuP_S~f z@I)jKkQyY8aldeE!{Wd#FFmZV8sgiufDCa{ zE*cSeuUTQR@KQIlm{r^^D!=vK96=W{=%%kqA1P1pXi?V8Gw%^6EA*0npOtl?cin=` z(BG+^;JhxwutHg2@$DHkFL#tk5r;v4oojw%fz%1{seuo@=y@Vi-{4D*;h8hAwoKU4 zPQ&30VX}OI8T9?!Zm0H_j4(gH{$9@{+CHk#>*7fwde)ql@wfFN0A}$05LlP8Q$|mT z86n!UX}CG!m!qmbE(V+W(dTxk?y9qH@{rl-PnUW7qoVvMP7>S^u70wff*4B)j(I}N zs`zXc-7|=Tf_t~WzUs7V9)J~;vJi#G$jmGJ#5DXn6wS(n)gua?;**=%?8BSDz^1Ltdzr1jd7vEIJL+@gPu(DUfaq?>63Ady)?*p9tV8^2`+LLGQE7VJS%H*(4Ntz zX~F|#pgU8L0tx-EfH18+gS<^HWU|iOw}19z7*|4#aQW)rG4PMB@eDk|saH+vni(#) zEsw`8&wfmrpHolL{QQ8$jT^~f?W5)kcfYSz%=+{&=on5n*Q79-A z=!Cost0xvbnEbOl*l}^c)hd#)RjTKa**&JDTW3LDA^wgM`A42LDqB*XvrJjw>;m`K zBZ=oqzPE51d;|IQ<;0&Le9E=Ap&4e(o+Ao@#JR@F0qEo`d_pgQgA+h()i_4)6t8}% zA;2#iNU2XU8{(b@@bmCsrhHU6_P9zb@k=XHZORGcN_@`yoF=52l{mG@pn|l58=(wGFu6=Hug@OGyd^Bgz43+qxZ+2jOe7@+?4MctZ1^AIQWzZ+ zzm60QeZaJFMKTd`Ovi6unHDpaM$61u(I@9>8zXt~j!P<}CApjej}8A@h06XW3!ON# zq&a%Tlmlepy(y=dGhBW*XEXfM*;li#NEKK=R#!>={r$I4#RVx}o-o14fJXY30wBFf z`X_s)Ev6F9uOg@x3aM9Tgd3uKZdf8ehu9DPOkltxBI^1vQ&sUhwQ#zOss0d<`Xn(l z1`O`Ae$^n$!`o-;P-U0AD}0beQ53Su*cexk2H zC!LM4XL{l|aNiWJIBa!GFWzj@!w_Wt{M?~h^I4%9C#OWG&u5`BkZ9%cA)?Ra>FDC` zUXd}nwO2GSnSxIAGk3K!cAfc!!+VA2c`;5SzI-q%SMxalFyfzy-H&%Z zr)ZD)v4t(F0~0Hn=@giyKG!byk;i0H*>3#4_DR>ZA01}zc~oDJqzuARUeXWFGV-s3gLWTiWzMv=_3X#* z-2s<{f2j}xkUiTq-&BRgK3_sw_Ub|N4BCnbY%U;`HQnFlQc!6m>4(eX_ zYF5yT8g-aJUH%!Yd@p$vT6pv-zd&v@#<()Jdi%_s^Y zY4bA;iMWc*_6L;@rcciMd2WKPIu;Zb_>)vM_LRYDX>I{x?S%MMZ9UfsUuXjBSoC{i zcvVW~0JFI@(vy_%lRmutx{>~`J0IXa&PRJmBd;MNz4ym^PZFIGZ#fc-cXN>bkr{x} zGQWMt01N_UsuO^XT+ti(qYm$W0*rSzV0vx-dnb)it++(58tG|r%B5g;9p)dz$o^mo z*tvlzGGMi?p77)kdc5uHVrHM|=^xKi`^A{ue$vO2s`1#3f@~=$e=iGjknY_;&pY4l zdUbO$8LaZZ_F#c&8|m(D>FyGw8|m(D9^zZD_c`bN z_5BgAi^W>A=RL<5_n2i`2a=zv)xpqBcr)xR);^=~uJ~Wmr61$=Qi8B;@50vwR-S0l!^?ZZlS##Ho_&p^HI- zyZ(83JJ1-a@#5`k$Lcts?&j-imsGAV%S=|A_9m*RxJOho>+msK^30F?FS6>hvb1o`}}&6VZlHfMw|o>9Br}rU{5Fv1#~7Om0VQ%Y|Dl*w(xp@GZ0Ah4}vS z6!2&=?i(W5N3yA#PJt%2%#>+5l@@L~-NQoa-B?`k!arklx^+5MvtvC6hN}-9gAZ{%R)dNUvgnf3yy!c0stP%6348MW$*xhLfZjTp192e2836GK}8lNFLSQOb)Lu; z78U@u)YjsDW%7=0y?^oo`VFWhuIhYV>ZAj}FY*|Pc%Fco3Gjp+gj~4O#FP~77M-&4 zMC3Cvjb;Zj%lS$=SF9@oGqd9V!!X@MB;O7oi8&N(I2}v?h|fq+ihRR9FVH;v)*E2| zROSB|mHuxXDc`Z$K4xVY-Un#1HF02tYra4RZlz`cqhk4A@H0eI_$?@^j^ORqSh*7) zTG?(TUH!k>F91{?@X1hBUXLNyAEUULG5P-o)?yT(16~3^WZ#_}TG1A&?Hw zi0Tw%s|Cvu|I-&li74-50i^-wUaZ+)1FW}n__ghcVOdRlg1T(6Z3BCbzqxW*ALf7G z87~4g&@U3#{x~r*;J2goTB75Cs2ccxX($ zce;t4-7nylR6u5Hk^@0N-U3Ww}S$^uzKgo_S?7ykjWrT;h-gEEIq z-moR$l)6?`(%o#GM!NRat<{|HVqA~0k(zlJCpdgZKsGx*^mOA43pj9q%F#uby!HyH ztI>uHfV}_m`O~g= z27HAIFzN)FkTM*Ns1@TxO#sGumkc%7Vv--%BxfM0w4L7~(i!jBZ1{68lNXP6ovBq_ zW)$*SqprUD&Kq{(h@L+GCsvDPNcEh+ecq?T~G@5Pw6H9iHOtQ|R~ z`Exf&R|J-%r{`|4=FKK6nQB&R@b7Ym5j@+_2-!qJB zX&7{5IOchm25MCP*$D=ncj9&1m8X5}-NaUizfXbBYYtqnYbK%c*IH?k6-!-}S@EUE z%-f-&JFN}hiKx*w4n4K)an$YhCYE|qioadi&Tu2duy5Wc0@zHnkehF&8)fL+J^|k&-=z6CjTlRV2hVQl(75S% zU?^N`=o52D(PY>THqEUL0Ya8pzwQIlhs?lBf3SVI3fPN9W`*_Y* zQE(uGJ;18_SzpVL#HpgG|LQizVSoW6un)JwDeXBRlVhag9M5Q+HOKp(xL!5p#{q1P zh2OJUjP${iT99Z~X;LK4H!ienk2QTa5`TeYKiqEbT>m*8wUIR1bxMHu82Kf(E!fjcsah>t_GtJl|ILxKl&{T0kr^ za(ESqd&c)-xFyy>y(t(NVF<+5Pz7t)UnY`?@3-k6X5Edh26e<1zo z@X{E7qhzU#g>uObJl8<0H69}pc{#83^W=OrqP!iI+8=MAfIw^Qd&C6IQi-Qjv|3re zS;GeZjHJWj%q`mn7jl;miNs&rA(XYWg0l!hb#FScc8rsjn;E`&p(a;@$OO0z(|RB% zNF6g8$~4C*i|!Z@-CJRAJ1(*rb?Nape3f|_2~x}Jz7>PLNylv$^B2o2I5?@k!Jz*f z1H2G%-c85pS=rgjmrR6KZzxG7;=H3e^sr8o?y<;X@nuS}#g_K_6gO1i3ISe<9C15~ zm3SnwJ4c{*bnv%zTRw|XIk{cz4l7ObW)tOg$SpZ2D|zAo&s85RA*-V%JNc~4 zu{1hx@zR;mZi|*2Vhivf7HOw2$n9MEDXSQBRWsR4pncraUQ>dyBt1{F#Ly2Ew=qha z3|~O{AJ-h6%k_#x%k<<|9QnDcb}ShZwn0A2H}!XxCt5o9W2Bc2g1319wQp_JUXaP~ z2_Ot?DZE&u4cZ8g<|7)nX!IX#c085MFA`?Xq>fGBhuEi`)Jh?oGl!d6u;dJ&sF$(OZyF~Qe;tuZ0HevU__S~}t zy*|xHdcVX(pEhb-7C8gW4^TM896}3f78B*HHFul$AGWSw@SZuPH%BoVY}s>Xam)|! zJ-KeePt54Vi}cI@md47_kOgb{&Iu0TEor)&2C6EYUSU7thyZpLtQv{ z_=KlSGEGgp#e0-{Ip7Kc1Ewa7?%913^BZKhPJHQlA$DvsufFh#JL<`B@bbSKn&0b# z*Q;%;pfsURp4cjI!`7wzC19B%4x`Lah?eP!uI_oSCDbgMTlkG}k# z1@rfI!n>ND`IVn{hoA0xq_P}V)7UL~e4zH>46<5{rWp8r7W8^$H0tq5x0VcUJT;UG z*TwPW78fen?_S9czG2;viJX=YUfUlpF+&W8E** zNcwD1ovWe_uc|FBM}msvgLwcK120>Pf<7cU#>T)m1 zaevWC*k_=ipzQ6`wlO%%_*GnQPy;j%@HVty^L`7iBKF!58%tm+i3+C03-?z_L+NYb z?JSX7-+x3IlE;suI6ar6kB`x|ytvveYe^>VgY%p^dhlAGh#bl8JA8|6*Z%-@!pY2J zAW*%GYhC&>5bbRWNbkT`&1(&(N{mnx|3$l1-xP-25@fcMD$vUw|MLIy8~-c@;R8AT zqEY-UiO(^Q()IPH>T#xy*hlZsL5W)qAG}s#Gd;KopBH?Ygm1B!J@?q|Awc#?KyRnbs_Y>^>C4U_R)ZpXL${PL@VI=N_LYhYMlbf3WZj1{o~% zAg7Ls=ez*(0?@Q>94Be;za)|P4hD4yDeS7D&f0n6!;aJo&J1Jz;_x~Z=oAw|RdWp3 z>4a@od;%yL^a$^}5zGwyw0_}jB^00Eb;A?yAv;EiDs6kHda!B&z)g(&F1>tC#p%#f zRzCd|K)FbHezt?KiF`+~-ulm2kYj6{);=%wlFX7p zl`M+aEtEst|MPNl)f|YWB~x(Xj!!3mRG_}uzw{zM>}RZQ z7?RY!BBv?b06$zk{Bp4cmI(WUHY4~6j#WgWgJ&aGC^GcNESwtd&&D{;*CF0Sq$#TG z>AdXh`GW~n*`@2YzASZmN%5k{sMSo+^G6npaG~L2A_xAEt^NyVZ>+An2EQ{U#Nfu| zGx);DGX-_7fQPTY_RH`&oeixgyqRS@)S)g=??6!{0}-fExq?S252oV&efF29Fm!3l`a@WP~v~ zodd1@JS$t{T*>&GI-$#DOX~&Z17ttyl)LmB#+B*ru-uILhMm=D~j$JA70W@vV2p4%w?9ZUKe|0kUS1 zXabu_2EM!}po}i$F|@jP6gUydXzIOS(quS!P5pG-WOs;2SXkKYuC0!Wx{Gxy((P)V z6wIFw041YCDqKZsFYo7+bw>TE2Fp=Dg#JD-x8GGg9q3u){OB_pQ`0T|ee=(b{TqE~ z2=l4td&vg{rV}`%)x+e>2u0e3qsV|tQbi^PFTLahgu$GyYoFX&!?jYBme`L2xD=42i~HMwdiL9+}vXY=N&eFR`F3+>zo;;2oM?g zui#J{!YmCF8ea2p`M?z>uuhc5(w|?671Rlz@L83R&N6-MAGJX2z!c_OJtJ;i^0(=DR2quUjgEx8nx_@szaouB zr}g~s@n+;1PiffIgI;Xg2^N&IAHXAb%DnE?A8KnFzwkSFcNhhvN(E~Ab#ehFLr!wo zUzYDMa$z9hPMf0;h_pFbjWa=Cz0K1FFl8O4jI?DfXL)8#d@X)eZV?RPY)=$4_ws7z zv->@XpOi?!1#C~fF5abA(sB&~a#P=XGby^^zQ5RWsOzaDN?v*|e_}YXUYV({M>0R| zR#yJrZ0X&{jIkUUc)R*_dW>6BZa{JyPXqH&{j46Vx|@4B@{B^|=jTc>Ev5!S>K#c8Stb3RHZDDZ$((sAIQTV&hde7M3?Q1Kq%4kD zZvAQi48@?=WWua^{MX7*5@B@OR;`p0?x6tmJh};qLJ!vfrgI z(|4w_5J}Z0n_&aZ+XX8Mv&hK^{#&%5GUNhPKl~MNo>AQoZ^4GY{*gZe;%Ucsrq$%y-S(xgMI3E*y# z-D!lbIUq;{hH^_uBET%zA$SN(zFbjBUup;ZS;V?93X^d$qb3{{wpZVgep zH{(+Xw(rCSMOFLkEE{KKIRg2aXpY zlgFpvsKg==H3)=NRVNOmTC?*^B-VyeR!l`&t0tJg;}ZC})0fBmFFo6&Uq98mf_CS3 zSI}QNC3kKB^%KGek6b|PXu*dEC+)X@p zTdq&7hl+2BYO*=s0fpw-ple}hWzuKkFD8KXLEu~WKv5$2J)dyGdfT9DUZWmX;NoZ= z?AwxgRzxopU|pj-q1?-DsOb_b% zU6%&GGDkg*Zz_Nc5BH*rji-#{=JnnSC8%L~LOOv91NVQNYQ2P5oCduK?v(l?3~ZA3 zf#gr~bZ&@lF!;=dr8rrHJ8DoimPW(4P8xdN!S`h+`TP+8yG-I@!tfJ<8&8~AL^ne> zw}6x@ne|ii_WR_bFZ-~o-nzfY(d&hkFyJnWL5=R(sO^XM1AI@5>4Vm1@jN!#E^pcY zaL6eexf+24TkTi#AMOf7WlHQ(_FXnR6G&Ha^Qt()d`&+uj_UrChq9MRF%raY#<>B&B%T0jE+Wd$71U|5A4(LYPA zV`USqc0NBjcz$=Tlv;K#?-j9{e zn~MkC&V7BehM%>MupmJMh=q^P_#9~$bNTz6sJ+()a3Hvp`WX=alO)duiTh#2n$A_C ziMG}Uk;mAHrZ4@}*3z3n}z(q*;}d|4U-O@^BWiyY$QCRiVo);kh+% zowpH?I(9&c*M=vimLa+blEx9>CTQJcUnI<(nd-V&v4Vb;e*dQ+vgwh5+@4CBVch05 zxxDY}frUeymUmySSpaTW!0mE378J~*o;YR}a11Ran>oeFl4_`jvo@fFo5LHUWIXWF zh7G#XMIe+%vT#{nwI=l`aem^Fq@v2xoO1O@K!&iNYD|7M34z*IuRYsZP6Yg%+(-FM zYrm;v#1yE}s-BhsaI&b;%|0bfqQYgnl47Fvr4GJ#gqEJb*x4y>H(`ew7LE?pkZbk2 zn7BB$j^7nGG|{kl<7|*Sqa1M8^gN5H)7+>CJK;RaJD#(+9%!OeGygAxXtI)gGP zq;>_fGnQ*@tgq^}zMQCa)-{GzIN7b=c~Ol++VOKiTL&dn#)d2}d?rfmOtDvlJ5E4m zkriMTq5I)xOOE*2xk)dTOTQ9dZpynb?fx9@^NxxNdVGRtA0uJbcqIR3;|QnAt~5kR zMDb@09*^$FB&l46sLF0GzGiqv-hwBghUhU4?t{N_dNaSLqZ|2Uj}3C0WcSkCFePsK zCDpZxD^i8M$ZkMNiK@Tnmj37-ldH)zxGLjg82{*adHTGU;lzokQx8KHm*QiSDk+NJ z0EpwFWA+R+6$(9QcGDDd=fgDI_#c)2lg)NoJp4yyFPd2@0}+)!YmZm=|H+pdSEV$g z(cf2l(an}C`KCAJ`uORyv#O*)66|t|BZ=SADM@O5Zh`n2nq|lw-?CppI%Gl z+S@a$f*GfYlFYM17Zt=G8+$F5>5sZYXSp!sC+4_nBTubPZ8pSw{WY}9J*=~<#rYG-A`MKevf+5azSU=B zWeU;=nyG8NI~2||3jHMMI4OU99ppSiN68j$P$417B4th^N^+KKwERCU1F!hGGwE-0 zbxYwqnBA`V3}=_2cO-qM?BQcSO(~q7d3pJ4fR*&bOmPpY-)ex@D`9(-7^6cx*s&Ap z*} zml?YHgSCSqPezRLwA9|VfuTOeedYd2Z(*l~rsqh0Uqfn)6mv>X(@@*?%gZ-|`Og7J zh=0#~UqL_?^6Pbo=uJNWBr(U=tkl+_gBSUI|))_5LacL zomr)&)IRsUgo!+8KsL_z9#3Y8@=5>a0<;%zIjdPlr}pTmED+4=tnhp{Xa`5h^mfW& zQfA$WCXr0j!H{|<*NE_#fb| zX<2{d5O39|KHe^rlufe4HcORXQNG-v@vc+`v%8nrBw^0yoZPRmuOGOKb*xZRY`8u* zrKT0P9(RLkAeKx}KS9=Hk%nYMBk{BR*ib-wZTL2)sy|>diR{54(l{I5tQ2j&g-3qN z(sX{xA7+{Ld99+isY2|YR`SU!;G7Fxx;?Z{AyraY3+M2+O3^+)cFw^s_zZ(SZRO3i z`YUu_@LN7zE7PZ@RHEN&Kbw`voXN!QN}%oI(92LrJUQ<44*J$Gx_u_1Kx#h{bueVO zv05g@?_dOS%H#fo*J6fc3k5q2g?mTit`R^b;y~VbM4S^5#z-;nL7nQUP*MFC&jQpD z<_ri$5TIC z{o2ddMQrR=vw#fgo2E1+DCg=gScQ@r_+WP!iTEXY5-nVorcqnKr##0UnT6fw?)x}9PGfLz42KFp?#=YV5Fih z5sCkE0Zo;GZLFl$TzBU5_Xzo^9U=Wy!1Io9SJRh}xCKVx z5mzgktUQK0LG3ZN3*DKFac=rHOn>F7^&3L<8wArbB=Nb0t-19=4l?|D;mSvKF6$4- zEQ{7m6oZ0>kI5J6CMapai~36-12iO`wiXh{ntdf+kY6Q82cy!r-JM0~4))Xcyh!my z$K9{J*v;-;$up~_2ceH|w$_sTeSQ1QK5!?@t5SoK|G8<)lo~oCPa^nS8gTxB>Vh{QiOc7X*0apJp*x@69*&?uUCFlbKeoQ0C8uCJ zS!{Cw$Mr67o3;xv;3kly-H-qz^+44fR(uzwR!ffAv@)2CPoBE`tE00YvsS|_moeAQ zi%vd9e{CFKi~9kEeiy~vaCWD}b3q>-emU@^Os}%=F;Kk3vkjN-?@!B$=&;={JGkj_ zC^^kq7R6lJQLo)zE?Tf9{Ak-Lt)^5nF>bn5IVQGb9o88lv_C!U;;t%8EK0N~S(3b0Xi=xs*FPIIe9yPFMIPjpvPeN4*q)A>G zH}^&M^De0f|1QqT^9&5xki+qdmZXQaWIr~3?VV%9FY5gzA=>IQA!28YUoTKrc>I8r zf&81nabraa+kC6f!FVJE2;Qj75`cDQ?R02#)gOF7;ItUX&(k@l?et6w#}*qNoja#n+)%Y~PJ(T{VOMGwe^aF69K!=;M(7rqYZ7C;gW+UZc6*~?HFv0@k)*ky8N$^l+a1WxGpQHngkkLk-!zEsPJy4CuJKuJi`f zVMOqf{dkt<<{L95$_Ie*fGdx3*!a$647|paBAsittY2Q%w8Zgsv_ntttDcqMa5OHv zjF+Lt0aL6wFSjq<_;F7;>0*e|h$rClhz>}DUU@y9-#kF=n`4VbTBEENYXXmt%QpT{ z0-_3Sh?YZ*v(mw(xiJ>k0-ofuE=7TdG$9r5nZCKd$rGy3F>MV+>dGjUncXnc*Ksvp znf91jSd?ErRG8xcmV`;#HXA*G$ucE3_5@g1UvS!;lq~7zGZGR4V-4yZ_4Ei^D)k(i zFAP_fmT2N$bRf$~Jv#Lu$7d5H+VrAWS`uvGXcQ05=y$thqE-N+3UD}-Y&=_OO#)Kd zQwyY%#@tp|9<(LYn6n7Oa(^WNgr6LP-OJO1G(Ab^yQF2r5;8%h+_`pd7D+2BHW!v? zclp5Nwk=2LWo|af3plBU)2uVRY%<)Rx-!gyoeQ0HzVc`JzC4g6X*Js5b1d5lOC7z8 z+WN$)c%oO$r#XB8MBQ5gZ^j1n&C6>~qierXQc|W`5b-#_%8wUN+*8rh6Y$wjEH6hC zjy|#~8zj=PM!2tmygQEAXua~Z4hGYm`v08#j~3ump^xpj19TcLe;@Cs_k5_H&gE#L z#0*+)c07KoWTppf+>nU9J(G!}Mb+9f=uVG0#hN{BvCdps>Il-z!otAL?mYKzaVdA6 zbLYhXZj#LDxKaDN)J0v6erH@wsk0=k1xmBHsqf=}P{?0oqTkcNWM)G|7T5k+=CyzVxioW&?hu9~*{Zi7ke$~CVqv6?VJ21xHB{?H~I^znR@D_wi zvRb4o-O%0^|$3%iaD^506Jx${r)@>))05)-h={emP{h$WF(ef@fI>tp5D@lgjgXY@h`M z0>vHP@N^K`>gi=&|LFW+!VOaf*_85-_T%*?m=GmOr0MLmb*NtN;c5gkEx>t#@uDC` zGK)!1{OodwwESvZhTl;vYGuPN+4mvIH^rs-^3tJA*H-FC?iNcRj{jt+TuTuRgI+uN zvc=QWlc8BgO${TB-8xnmkes|pop(37ds&(RturOvqOM|a`M;!2V-nV+AJ%gBiQ%La;b z8=c+r)5mgbuz8?G{m)0VY4Ra~4Ke?x5HGj@VdS;U6YoUU$5Z}V6A+_hGq|LVn9fpz)u^zI#zZ{SRyxf6iY}))(d0r%=XR!EAtL3I7cn)Z z@Vq+lC60RbpQeH)s`Po+QPLQJU!7&+K5e7cs3e?i?-cN$1^pU!wLg(6{NS@#WBlfg z+KV0{_TOUmB@pugiQAj7DYmm`oq$LUjJHg!fD2_Jlw$4135vK6-Qh1?quuNCU9Iuo z#L1=UuOWHh|BBl1pcX+DkW9f3I<9>Sx2hRmQO-G*PH0tT-6uT?gWVw8k_B=n zi}9dL7IQ_zfeL45Xa88T?exCBee;ywdwRG6!{hUaU$SYX(;)&MAI7

A=aQo0vS9dKH z1dJU6>Pf~5hEI09)#$FN9c;mO^QhX&a+10p4R2;jA&W$GW&uF$6{hjKcxT0V!5RAM zZ2*Vm=~Z!m9?~eE=ZCul)K~!zG|}!)Ah~(dj#I3Pkk5lPauS*e#O>RWiD!urO^|#=r+8GK zLpdCXSr&;mXu*4@uH>1GN*Bmx5nQTq^2hWpy`7Gyq;su1EEpGNe3rcOM^_wz6(T!1 zUjx3t#k!p;%6`V;Ew`R_^k{op)cy#8@6b)Brr?fv0qZf{pgURFTJH^->E2ef{Iq|2 zaq2GqZxE>UKw>BGEj2yFUG%NEOoOyRKiO6UNr53I=L(%S1`f;=;Fkto=ueY*;-UQp z<`H5c-)2Z{-nvwgi2fyR$tn~VwKeGrzaxjlu+ilL>o-U=# z%+ap$MyYAQU9iA;d)C0pRb`T09A?+avHW`d+ui^Zp)avp3-)WJT*HeM<--l;Gf zZ(MtD7^d*STl#tc5)0|um^6qoroPGpd2*r<-49WCx!=;>Rca>8X#}AKItIneVFe`1 z!@|NYbovT_0g}kY4NRaUwZYMEf!Q$fGHcBR-- zi6TFgch7-mI37e=Q&u+YzB9@N!_pmfmxX&iwnM&~vpmYiYAxrArhIho&i1ojH2`*3 z@D?A8!kA~c*t)E)DPfiG-6zLOrwhF3%f=Sy3I2eYiFt)NqyO2M301g@#{fsZ2G#Qs*bhlGxa#*PMWw^p~Nw z`nfrovfYAwv!2dXAYjeP7(b0Bae8Wty|KhwutK0lj9hbqHJruGy*N<1%-~w6akOg+ zFY&65Ja?iCrlt471#ZuE+eLhy1PeMabhnFggDE_I7@k7zWE0y zs4soIZ2aJecH4hqSVf8ZcBaghR3+o4$WHMH<9vyXB(~%lt z6>$2yqT)xfEYrJD!rY^udJAdCt01=VM?kx$LIuP9+;>0!vHZD2|)Z&vR~{ePFkg?0B_^xztQu`EtT<)x(qKIe!%q4yLn)?3Z_1{ zI-hnaA@!<@8>o1=&pac4J^1v25TE2;3_VcC84Z(9$`K{yXrdd8&+>DTm(AC$h0g`? zrzhR56`6^RxW#r9r&7k{xkQIjZSiNpQ>JOq4Up#Em2jXOSTFeo<`pZxQ({CeYj8i7 z^d_~pxpokD+V%_B;-_caCtkhtZz4M{=?f~N2TkgimK_{*j-Eh@^*;lv-2|2rTE zH;E;4x9h#YwyVCT_A?9eru@Kl>5lM5cEytg)i2VJDh`PY)zLnN zj>@;$;r|9c{c~v*ny#!>Nh*-R{D zzFcSF++zNPelat!eYLl|f5=n8yHN7I zPpH<@+2$(oS&|*|CMb2W?!TMr|3?&P{`wnLT<~RPT#;4eN}TK?f~s<|^Tw7EcG-EE z>b=0Qsk|2Ij(e!;@=i~CxAY4MffO50M@d8HK%{h8!82z(noK>A#|Er=?^zAx-x{p2 zY1Au$K)!Yt2(^IYS)G+9J*X4+Q}z$P52Tfhm5nXAKlJTdd%I=BF=7e|JF%nCtabQK z+wXMC)ht_jlhK3p&re&=3V9;((a_K$$kzox$1E>TdjgI??2*q!O{9c$l6@P>JwpLu zCI9Na#?-FQjWDO&o|k%CKl`y!JJ~?>tg^3@EXCp(x`JVLx;ZCt4ysVY#~6}LelG4+ z3Ex_v7+X5l^kJc63uWkzw23`w!>2N;uy+i3SRVv|$+M$B*tj@&YaRJ9 z^J)_}N#t~SUgW$|={CZtlt*_w^BIA9X#iz7FEK&+MuDz_BQ?Z|ig1O(*%)$GzL|oo zNk>#SecWY&0Q@f2TnN+@^T>|5BQ8b$df9ba;8m8^;t$U4yPf*@QMfL$CF$SL+8kr^ zPE5aOKcaMrdwERPm9E$Hvm@m{$zs&>v?5$#9#!wZ!u#bDNNQP6Q*7?Tvt~>CFO-vYi>5>ClfGX z`R&aFH-3V^&Ne#RYkSxWBO`9uE6~qwn$B&O{MKX-SS+qvg{kGy8_Hi5+DZo4m!BkVr7M&F%G;Zu=vuH_i?_@R#0wl zd;35o_v9mj`1x^qhiIgwGF7Fi7IbDnPmISWpwL!MTi;ZL4m1UvL4GRHYSos&s$0-% z$5Zf^{>2V7z#P_?FzqGL+i1S6M@58_#$zY2&?VvResA|HikHxNI$gxRRmTh@9FQB4 zVPsd4+0w&D1BDJ>ftgGWPRNBq8h_NyBl{eD6lxO1moKNc;>-Irn%4(51Ge z@#lo(xvZx_aq#KyFz*%@Zw!ht9`d!MDGgB`XrFwg`##pQXj&ew>A+x!L6k@Z&JUR8 zzewLgrU&u&kV(88Nj_}+2h-y#tm4SEp>bFI&=$Ta zFbRyC{VeA<@ma@}c#cOZ8N;8IM^NyreEhLeYKnBxhGpO|i{ z9>Q|NdK;Y=)Ff98<;p8g%3zxrG3IN8P@6bGzzGkUOf{oNF7JOSUF?d85(V$i&r3${ zU}wJPEpn#YJy>9Pe$U50{l}}H1O5EZ9jeZtI zje{_=zGNlNvn*rT*UOR?D>+>1#t!<;xA4_6KcK>8->o)utOr)=YJd&{@}|}2LzPVi z|E%RuHnJxZ|tPvSLHtb_DW$A`FOh4Qcmu9XbeMA z*C{yK(;gJI(tMac5mcwh*xpPjBi>n78V)NhUYM6Ma)jyjmc2%sRZ88yopCmfr@ff0 z6X=xefE+Sx?FEkkpJ^l2y3!^ejK$+zk>wm7X=r3k!s8Zn-W*9YM{{vF zMsD$BQ!*z`p3*Sp`dzjX(5k%j32YLYul<){R)^%fZPzY^atj17;Vf0D*9ar~3f6u* zjMSz7+WgL0Sj}x3(rIsU*_H8mp~(Qek&bz?$UI>Dc6w!6zNsksG!tA-^wY!UF_K<- z_>?pMK*<&NN;~(4u79Ra#%edEe=n1PNA5|)&_@iKUW|mRUD}uY@3VNo3(SWqD9{^~^{%_r1b&PM?p$^Im(7_mq!>{Hv-!JgNueS{$@gZQmNtZ~tH zpi7i9ULN4aQ^xXu@O@}ds~ClILdqyrR0z0ZVWtbK-6!OeX+lmHn>6S1=LOLv^|8sVz?(4#oc zLAnj3tNR7LdC@~xowRl;*=kW|YZ*^LZ~?1Y>E~!I61OJ9Lr~to>sOO7mudWlEp3nQQf`pO_GU$YCne}qt0`kut4d=mQZ?pfd|D@FWXPA)zne6(D{%H&&ON}w8x zTCMrD0n?!LY#tMYHKkY;#?EmUlIdgceT)3oxG9Khc6u;t?Aqb-+FdS_UtV5Mpv;!> z;+gF;;M%~P_Ih+Hqef3ao~!ZTzqu|y3=e0h&+ajK4e_{BB^Git%y+lU^5_bHz9%Oq zZ--0LVwZGxxpbPMmhEiKFBJ3Wotd6&jT67OJlpUFUo4)W3MIO;iU(i4pvSj%4CCU) zew3C@;HESTws;#-@w0t>ZqU?ZB`m;ImL6^)r0sQYLVo=`dTmA9%VF;@(@Il9d6;ja zMVCXx+!J$m2teN}R3X?+mNYwoM2DHynO+7YIJp~p@J@T&MOgu=H%b@D;p?@kGg;}I zFO_PCcY*YZNb6lYHPa811&L{23aTBHTKc8$j@VdTWVMy@P6|ByrmdeuLKK|XDw~fh z-}ebFqBjUMnWRLuizZ!|%*x17cRbtG4$GP|h~F)$BZr7TQshB){>xxTsGosJHJv{$ zhDmH(fkUrQ0@*ie=~`8rF*SQy-LA&t&&@YMw3jv`CjC?W%RW~IHl5~7jVsBcbhm-q z^h)1aCWa$Ru?K}v*S^jCebs-UyMu$oih@7KmJX$Ca6^AGj_S3NognYKF#-^c?VX)S z-6U!^d)cs$3pz?NvsxQY;;|?!LFzt? z)}@@y)=hj(o?6A;OkeliLdHUc<9G6`;xZbZ!Rz1)?v?1mI?4iSR0VO?aI)Qo4J&M` zk@sf|g^ylbo|*J*`#9S2v$aLP{fBdJRN8T}w~Ug{LjlTDO;KA#Zfi)oU{>{VekTtf z21Tj_(aXXx0i*ywd-??(_wPb`Rpi745`J)MiFcoLe=vgfbb1ynA5eyr*#%(YEuLP+y+a@yS!cj>B*!ym0xM zQp)d2UllifX()d+>0r-y@pYsF=CZ$&(N)S)lJyI>%Jh9^xw1iRF>uI zk*sJ3U7Av3duBOTbg6xjd+JHP{;qzy1Qk}5X1gQ>pYDZyJGoV8_BF6XM?XtcN>9}G zDyhrD-pSn-L_DlfYOqNr-)b!nP)C3&X|D?2Es`E`@=xk!*DKw1d&|2mbIi}eFWBN-*TNA4b0<>p1J8=nX+__j%O)*t!C@qHCZ=B< z?@ou&{LL~v|7Gikx=abCTa|&~&D_mVFy}PZ)XdwMv)gsgny6o8sdMwgg(a8KNSsK0 z)j3#=Bb$JIxsbLqT5obBLZ^^SRY5_Za*f0&D)+Xb8f}_NKT5Sq^WlwY{)f?>U>iF7k5k)a8j&cOnV)LDpTvD}g zL5vrTBqmuMrLmvFYSx)A^A|@7iX`YhWkJRm`skdi;~2j%3355P{?`)i-b3XJ_BS|# zRDJv>uH**s(}MKK#RKdPA5c2|8!eWv;>S_;b~v$VJ!z=3_GQoDb`Eo0^X6F5&o3`3 z3if?0^2KS_Ra0}3#ZO}ZYCvaXYFY%C4DMFlm1(qd3CZrGdwn}V*wsYNxe&x;E7LSz z+mUl+H0-%St19VrEY2`Jm2zbS0)haEgmeKQjqo5&o?p@xTAfWAcF0v!apKQ%em12TF&AMcfu8G=#}jj69pN{6AN<@f^brn} zT2X8QEU{_$$D#E$10X2)$Rg7v4N56XDl~V%lc-Hk$2)B~qUV3PH~g|1wCf=S92n@u z@=iw8>LS_P$R7B^kK=j2iQNc0*V%ZI-OTYj=5OtA{|hfIPI@=Mv{!ut&kbTLE9qNW z$VcJGlzv@ztAa!L`;=eDb^k(^kJ3UzB}XAU4Bh66P-%;P_1xz7*PzY(L1-?Scl4KN*-H>;6u`Uw-)c`AvR& zqR8^{6b^dcAsE21tD zTY5N}*Q$==Y5%6r`p3{mlUk|{{^};@b z6sdRNRYK~dKQ0I9)SfdQeTd=51xb{(t=m8GD5nT zCNK2r9ujR@qGlEAhTjfS$Y+BqV*sWJv66Xy3#5sP3h6dP7JERd4igjp+uTsZ>T zez9DQ<}E;;-${ZI(jM<&wZ7V1+@|=YC31R-IVP>l88|q!0H7Zie|R zk^0%uV{|+nAAFtyDnc>Xq`Xot=&Zy%`l4mdEx^K%tNb`}k!Il^b9>XH5%lXts#8am zQhD3_qE>cRnNIeAm};arHvi-gYPHzP#QOXVR&6yp z^YGWng0zLG;gKq>xL5-k32o-rfB2d8Es4KX4cg-C3EFm#V}!T7q^Rf(1{o;3T*PcS|4)!CeyEHAsSMAh>Sa zo!~yWyZZoxyZZzif}KV7zyIf)i*v&j&#Yd(x~sdY-umipLp(T43v7nvd^;!iV=C~! zL`pfu-^=~y1e;4>tM(Xi1Y#nBSxJ>P9!a6!=-PBzVsxRKXz*x4uFVLV1>eaK&3-X6 zljP{*$Z}@ow_;N#W+onihU~&*o5Nh@7C2sAMQrUj$(NKllFCR`kTKR zsaC@-6*OQlV>x(^+3O#@_cHfTM`;~Q*Y|+TIXX585xr zWSiF;VOX7&Gz#ng#}n<&9^Lqje?tun4gQIy>xpy&jwHZRKYetn&;Py6?sr6F31|oj zdg!1yw^>&I#mCj_9?p=F29EMAFPjaucUrt{eN~6B1Wvhm)fE%Y2yLkx1W)0gVokc_ z?8$OTWf~(1(|_9O^_kiHKLtYeO@JI!F7y{V5HP)oC@MX$iL7Leq%S+W*IAu@DU*#h~WcQR@N=LtP~+j9rDndj6f`x1Y`ZZ-;} zi&PHuy&GfXJ4izwKXbk|s59#+866D?y_}rod|l_ofhiL0NNFj7r&t`NRvmRmuJ7zw z;Y!PaR^rfUESK*Z=tJ|ig4Fn{HHa>jhuEN2E2jKM)LXntJ&dO##D-V+5hSSusr##|1&Y~K!9NgW?XiJ$nRsX7styW zdvfO+QzZV-#Ps5Jpg2XxvqKk)35Pl%g6ADSNZx)D7a8kd2UIq^OXVY?gPGezL5t%( zr;Ya2P>kDwpYx?XcxTclvC~_6LjN1>=_=J~a%3#gDBFMorFTys;_t(QOMcWm>HmCA z_<}(~9?OH*YeSx{#FHN--)2Q*d~9Y=I^?zGEy>YGJ7q|-PoeKzO0p8SM`|ZiQ%5Ye zeemhBIj09o48dYC!y^PU>LFD0Ft5>H)+XC#s?7Pk{b==+v4C$z?eFhP8~?Yi-@f}d zBQ+e8QOd2nU!GK!6dzs3m34^XPSq(og>AOQ>Af)>eGD`hbGq*`@iM{-xy3ys9UY1i z5!HK3S>Zu>qsERof%Tr_6?tUL-E_4Ikjv9)+RgBI*Wmr+ze)Zl{7gms?~2Qp+glVR z@BU$^+iy~9lq3%e(Ih|?Q4X*Te`lW6Z?soMR5i!mEkPpjMNH!7JtmH2Pax0596J$* zT&S-!vE^H1nwUFSJAvd|j)Ftv-lIT{1!d6;*Zz()Eka%TZX2p@D@kciw9KUyjJIY+ zoqou%bjE;C)!$Xm;UkUn*J>4|&FdI|t2*+HRYnYGaL<|m`((_M%#KMee<($|N6jl7 zJX4zWg@A>wBiL|{Bd3Z;qPsgpmfIo3*QhHdI)q1pmRhwpC0ZH;q9ab`<>ch#NFL2~ zAOd+dOLW6fI5oo1XeTN3pt-QNbFiR{cyRL5jDYY?=@m1!!r0mj0M7sj?)}e_>rwj~ zwgIywBeehrBdgiTh_>&39qG+LO_KMUZlfF@rGom3%!hTo@V#dO7-cN&jA3a37@sY` zF{Z;k36``FD^p)9$u;g`%@bjPD{^MA%nHz+$%d78KM{e$8SGWRR zDV>Jt;d1e%rM+{6CdPGIA^U<7O_B2^RNY2>_&nKJ{}^(_8rIUaKK}VsLi)BRZD4%d z9N>s9E-w*aOs-F{&c7SG=Z@yDzhx>DgJyxOBxm*pv6~$MT_e^{I%;we&uoSj@W0Rv*X{uHAWyBy!%SwObm^rO5IeBn*8sGNyB zy{(A4u+zlH46Y9%{ye;Qg&FAd^Sm3yocrer15v0SBZp;)Gy-^D&J2X|`7=f%3`MAZ z<4C4rW@lXEi;@&yKi^&}L${OBrPxEN?z~)@`DIIq-x%fm8e1L$E zc=pS8iOi$Q|2wu%bcO`LUUx1+EHV6H`y-#(lf3r#OjZb3f}^HTL5`0-briGTsK-dq zAe4R;FL57g&W_I&jJcmS>xg1xJop;}vV#(eD<*AFr=^ut`!Z;g?zgRz!T8X}+8;AE zq1U;59Yz|J`C1e2Vk^-(u1{Ld6>NdtrIUx8#3lb8HsT|Sz-IMNnxcF-3jzp&nI@CA zFTNkTd(40GKFET1pA#bh!_7skl^@f zhvGDby^q<~N8d?+iFq;U%!5t@tK$jHG0*_fc}Ezkysy>Tgkl978EE8X-d+~h*K0;1 zp6h)0fWXSi`d%2}(FG8cgJcxq0ij;{o|D=ec$C%amD1w5#Kr-(3+1-5&@z`r2;K^< zMNsho;OpA>2#w?C38fr%$CG_`^R5s9GNs?@wkM_eUWrQhC{6JRBbYRjJDOL-4rpU6Sc zw}x%qR#Mm@7>C;_#|})BhM*FMXiGhi0L{FQ=0$Uw{05D74!+(f61^(%l^)$# zv|^jjx5&X7izlIvR%pLnKAj@>Yw(AmxynQM-7gpb6)gFuvniScilc4e=Ba~GX5nvd zF60Y6EM&0B+kSmIaW=6;6ZbCYz<&KRYB}wGH9#!pvX9=;>4I0iXH z3@qzNKz1CZ9K2#F&H!}e7cojQUAhq0EyEYb$kRC|GTwmH*Ly5=Ry`==xeVxEMm|EJ z=EM_$?3l(i?z(($NPtav;0g5T;>^R7r&%NjR%}AgojC|m6AD4$Hr_t(n6Qt_7;r;D z$Txf# zZr(r9eNQHKBCh+_MI_^w(4tS59DhOYX9=`t;A%-9zWXKcV9i9Q*5XMS0U@*S?NPX3e$TMQ~_Sn zx?ju#?d>s5*IoOOM?*^K{D~hF8$70T7eX|g#i}!AhQC*u?p7MmOrbF zDx>#t!{$xJ3L2J}j|7Rgs zvs<|_`0S%#;i`sA8yAeM^z(QwTVxMq_9iesj7?+P@1=d`XSUDrgp3r3&a2)dPK)RX zH=U$ymwbLavrSQygIRrYp5L#FCrT{7J^#F3X*ldG_o(AIQzg16af}vBRu&~@R)nRk z;K@Q7rFdgS{=G1UKm)lK&~UaRRR`2Wm9<)PH~o5R@XDq|6Xptz(%|P!;Ao|o-LmJ3 zV?Q)OeZBrNtvry(Ot9=#QeD2l^Y5{*%`)x)8W( znhT#P%8VO(4K@CLns40Yp)52xbW#>lHQ-RWpxt+ZXjt_<|sF$bn(Tp>f(=t0uYH2D$ej`^q15NG-q+ z>Nl!AJP<5*O+t;EbJK5Hs?T+D<7vWIrrJa9`VCnisz$sfb~ZDvYK7`h zT!WX7q1E%2Er`1xQnj6@pN8v+xnEe2Y$(u?3f)@*k9ufyDBpz$iJhrN%We~hz@Yee+}kCl)!u)G)g=o53&xot=LuRZy0 z6!~7l_lP?AiW!cIa~t-QQ`o+(P`jw2W!Q6J1r^BD`CBf$?tr}~4oH~3etQ8n5{^Qx z{92ZMIZy?!#u0jPaE1w*TF;&s}-3?cHC5}h->`}E59Wc#n!pXzJ4YQVsnLB63Rb54x?%a5 zL)b1KJdo1P4$<^brbtM%+q8f}Qqa4J;`-jnvAk>}{%1eGb6&Ctj?muRcJH}8b$Tpr z4$1N@Gt9f4_|n&k1iKc`ro69!N2#qSW;RU3?a<2Nu_-8{&fMO-(Jj9$D5JvT#R(bd z(!g7>l`c*aZng*LPqM=oQ!T?m$M2Cda%8^53Tr~Yw`5ey&p0+Q&7Eufb0r}!41Onm z->oO3pYczNJZvtnb+^B{Q&CFK&2vQjm|IL69Tfm}=Hyd(!KQ3+vTon`MD$%CmA#Q( zvWUz2*AwTGh}!*%{KUs^E4yXqOJ21Ik-Q+YEC5KKBUEOX$m~GgI*?U@YcbByFRQgo ze3S)KMhP|>iJ>CAzVm-1p}AYuU6|wBqhNO4ABOFC&vIaCCKqI#Oa{lt`4d zP?1|D{^RXy53bQ(_%C-d>5SR=_w#*B&m+T*%yCaC|Nm^#?TsUId}{HYmIi3lnzcsw zFia6Ub*hTC*Fk!RYeYr-{2MaG9v=8r%N#b4*_6CN#0 zUzfv>NH7%5#)@vW$&@i$QSlW--3UY{^>8aI*gS49uF`4r0YU%-VCIcFZ8#09k_JaA zjjED3Qst6H=&2ldNa zOS{=tPz_Hux8!fw%|LdTS8aXu^+)EE%8@~oltrC5kzEBZ${d7)47>hwonXy2F<$Jk zc#pGk{~22EgG|h7uWecsF!QIaedm>%PA$PcfNxq+XS!))DyIBhWiCM#lRFc4e3V}* z@Lqm$;G;JTx?(l+(?uK0RI1n^$^P4E*83p7pK;F1stCsJ5_L97rr(A z%qW+jsIeTY70a>?f$BE(cj(af7VQwo#Hfn_~ML7KZ_lOHd z)$Q*h@3#2g`fw#x9cQM6+nKo2gFJZcn+jp}YBq(m5_H&Cd*zmLKPex*0U^b3SvN_E z>3gcoKnYgk3PzoVWv2AmB?@uwl?YPp_@YRPf(PUqoXmp_^+VhYlE& zep7Ae{MkMr%T+ENW#!Qra%>mnv)W`&z}=1Z`k@u!ZZ-YkQsi(m@xXxwx%2g5kwsgN zx8A|MMACmSn?Rk|Sc^G>PO2<`_Nd>=ST1n#VlQM9qFgyo{GJFHx02~ki0h-h8E2od zm5SKOdTynGeN~jvj^SVA)8d!^%lmoR_!>os$1gmW=%}u*6rt^>1(n8kw`5ee*Aq?P z_>PA0cTn8`evie$M@d9-#gQX{R*Fx^0Q8?1;g|8LgV_wv42%Z;Y&eJ&_Brbd`vt>n zc)-W9u$zsvkX5fq#eVZwq7O&hlwMQv{rx^0?cUeKr}t0??1vqf8ZzN7HXNiIeY^JI z)OODx07}2NTX8+tJhJ}7^SHW*@X)%g`vv%;;;f?##iY2o&JKejdprj;D=7Xkdd z@`wMFq&o|KJX9P$v&D#cw87dQ?mNLaE&1iknQ@ctp+Ys-W+_Ba;>X<*UpROFFHR;T zLr33vq&HOGw9iiz{P z?ETBJ$(&?#idwvKcULD_kDyg}XC}=^u$rlZQADU-sEm+M9rYp7POF0%^V^4L&bEz5F0@A;t4$nx7LN|0fmr0q#Lv!jLVp+c`8oFyr6wA1B1q@b=R|{P%)f2$)gwKgdwY&0vj|BL@~Mx>F@q8K1Kp?ZVuzj$D))t$#mMmZlX4eS6U|>Db8@4&VkbyX3nE z#fQ0=jfTA6#0kYwhebk3620JYIT*1~e=|5GW(DQoN>>ZHqMW7RPtjneZaEd(SUL7W z#ZSuJ(YPl^i%J)l)yRk;#L5X7JlNBPoXpZ{_zJ`#dSjK}^v_YRtd^(oJ3f}yfM0y8 zGAH%F2ksMMwG);*>up9343xRT{wU-%^g zxd$E6G*afmIew=)Y4r~gR;t%#Z9|SnL;Ysph-QYlg!245c?N6Dsoy_g>KP=R5+A0i zRxL<_F&gcgkNt5!XAMNZ$=1PHu`KS^RpkDDR9g*Kyof@5;kdoI$nVrz{KVy56J^Ij zPQ$#6iF<1%Joo%iIJtRU*1YYlbM$y>z1|EXMs5c$}n!uW7|fJDP2Nf1x}5 z5h`e^ZuD-&=^YiN6OF=0BukOf^?7zlqgNdnQ9>256L31{6XKU&Qm3Y@TVAyI#-wCR zE3F~l)B9VcxkTRXM#Z;l5M?>eVd0(hk1;fQ(QoaVV^^%kAvtOZ=`;%pYxYRvbgMN4 zqvi6y8k+o&6eF7_H+pK#ilycTt4b~|uyq_C^AlakzcM6Ky`m^6KVR3K`cTOl5}qVD znqlt7pi}bdz=E=svDR4iU7I{blm4~prG|xgGY!FY!f~9>xadz)a|>zFlNLtX`YnTc z>x&Bo*Vg%TetHovu<(_tz>0ztH>KVB^mteb&m})U6c{r>86#z7G7TBgDY0J;T`KFak3M&%{3ZEP zm@KVwaz<6N!F)R_CtKICJn%5}jvbH@pBl(ZdWPrjNEB-XQpN`|hyqtO3SMr65>dS+ zlkzYYxCP~P&&Lw#M%bhV*XHl-CJOyolh90S9(+8)5?>x;6EE~83S*1POyuHZJFi1J z7BdVY6u>;=8PG+CzZM^{zFzu{(|&(!hp=~YveOfSSE}PyE( za?9np{6KidD&C`#aI$9>a2P_DLP44-x|hFx8fNJjFCV>inBOc*y`&*CMhYoqFYfGn zK{7#p;;Vz&2=O``9qJW`d4G8FzXapPUxINkfQ3z)Z=PWhfZ9~0g*$&caLMo7gr{ zis#R;gj+?}ozVA(m8H9JGwU`-ng>L8 z1srhmg)m2Mr0fBt0BiS}43f!R$?qVT-CB~GET-v9*68d`MP1SFj~^*NMxSC)t5)Tu zEgDI$3xnE4N5!DF7@xKiv!se@8XUEsSvU$SWY}5cr%Z3DavV=);KOQz>B> zA*&3)jOPH78UNB1BSlXY`%A8y5uWFxeD8q^DUbov*;e3HsjKp<+upW$ytQIlDsc$+ zoD|jaJ>0JW@mWuk(U+@lmMrPQUDPK$+cQ)8z0_8{)_;?%{rP~$8l`yRBh17cO(eU$ zXp67pHBC1E)2^xiv(1)H&4NxZcs}U36Xgpvtxc^&f2zDAp@vclU$@t@fp1lpH-vSf zr1_glKRVW*jV=nSt^Yds<(`o|J@kfWq2UoX;4!oH7RRO zL8BEm10UU>vkCvB6X!qFJP`0RTDB^hW)ODEd-y#zJ~RlBC$qq*f`*UVxjrHy)qjDV zV7_vI4gIsQHfBuAx9Xrd-PE2qhpR0`v%_-Rywg(!S>fo$bKlNsK zs{g|zLV&m5q_z*jf&oe)G3&DGOBZv>zPDxQ+Kg-X=OJ zi{D)7oE< zR$EITYId7IjkO}{AZQUS!=|^rQ}I#(mEKw1v&a-d>Fb=V$Nq8S`*#+K;Y7SkiNCn2 z$(!YQs$G+t$WV)jswgVi?l~jo@h=?MCD_3i)+RBYkXodNkuiq%0v zdQ#5hiA_T5(hleK!BLJK-vXmFXkY#r1_y>WLYh>mvk(o6aw4F}Z8mn;I?-sFaL!q> zY6v!I@5N@j#+Bue5A=#zfwXFUeGShKN+Ku%tielxn4(Gr537q|Ip5I&lnR6SF1Wu~B?*W5IZ3}lM;9bP zH_#YKLWnJw24dxe!KdEW&AHd(86v}^b}iA}lP})3#Z5a<^~XSFQx!0E$S+q5%yZ48 z$j5S{&f(c;tY?K<$8-)2_s>U_`n5D0$14U!6z<-WTi4f+)Q+E?tucxy+-3{Zf=P{w zI_d`%;O|MRpkFMaJkGunJ-!>WrHrwwg~8a)c`$$d$TvN+OCc8PeBxUIiZqdQ#}=N^=ZJ=aQGOl~ z+Rx7tgOQ%@k*Iw`0}NUF;o+EE_E#99H#D8eihpj7z+g-qtlR<~&RR$^x zwF#aS^(LZER)VcVpMhddUW@yKCl7?I&NM$-uFQBpR2MO@D%MU|e<$)apOHBJsX*0C z@*+LMNLVD@A6pLQE!SB)AGB$~?7Mt?QE|PV9@iZLUP(PD+<4Y&F~G%K>g>V95y z`dVQwQ||VmWv#QH&ZBXQPhlp0EE>fWFx7AD@4GwCyB}zbYs4VZN9Z?qy?WS6w>@ef zU^K0#^jSTiL9zsqOoG#H?<3ToNZ9hP1ceBw&P?#HySqj#f#%!DB7Mh6cJLs zecs$O_NYVG?B=N*{BY?6H&cp!=av_c0NE9z@X8P2ZBeruK#4JTv#q|Ef_-G|L{#-m zP-*RP?{v;}x*FC4P-Yrb+;jKnZ&%+>J8HXRuGiUjbvI=FExm20+)MR5NwbbAQ|NgS zMoZiGlh0a?SAQk9Gw%s=j>5XrouU+iQnsonELm(}B*7RgZoA&LW?&7Dp{aXzuV45mKQ6DfEx;OrCG0U|TwZ0;OEr z3ldk!Z|xrL_c**sZ`dB-VyDq$Bot6JbqQ!~NQ9OXbym4$U;BKi3+U%bzQgC!p}lr@ zI*6WZf${_~1qoF$nUSlj|N8nX5J<(Mh&zAeTs%0y(39})u%cao(=EXK6WZJS^}HQJ zwtK~!!j(xGcm%_8MS$gfkl?Jw^sDbpRkXL#;TQ}(S7Pr?bFohRZLWRrA!H2Wm%L`2U>qsWgVd|PT;ZNIi zr#Hy5W?&p^k{7n&cuQK+Yd0fF?m3RFOa6AoKk!NpVXHhpIX;)AxpqlhDr%#(6Ht2# z%0SN%nD}_2=cYdyENeyP{%L)~Ds<#HO*HIcns6#QEtd|J@6Ij)yRwOqwvi){1>Lz) z*yNwrGQeEZ=12|2qtrJ%^m-p-59IQ%Y!cGHIO{D~Ey2BK6`<0_dR@1OYUL%l9!}J^ z6e&R|fHsbftZ~gL_M{W1%!T6)MEQ&4CZzT(4mwu=jTm>i&Ne%kbwkT2%6Gd)KG2R@ zt)J2pPi2Z2zb_(!sp{4|mZl7m)1Muot8lr$vP{^`&tZBlv_$4J!o_P2Bbr>T`wic* zO2Jj1UOr5_uYRpmS4?*KDR?d0Hitg9XLmD=|FBULCaM!u!u;cO{pC7ePLF~!p7*+g zr!~b|gVQ%gQf76b)U&?lY8uEEB1T8D&`w}HH!n7m>Pxp|d3-cS+)SD_QAr!>b>b*=nR)(2v3uA#U#o zh;z6-{rbj{AN*M1GF8(nap@iZr{Je+dD2clM&@737X-rRvcys;;=a%H1|2!#6g=#T ztazPDh~9I5V2THEFeZ(no5fnzWB{-q<9S2$x~*`=*ABr2TPK~ylo9IW{s^BSl-RUC zo0gGxx2N!WpGWeF`|{N5l~ZI9ycRxbxNdNO$@Wlu?zNL{A`5V^vG?Dz`e&Aji{NK9 z<&a(Xq0T{msnm*z_rDX1FUe{*x4D4}^@os!O?k{9t@-})_KV_waf&`6a02u^m8V`e zW`$3)cX}+vE$c<@u7Ie1)jB#K=URF8I5cL~<$i@vEBK`j0Ri2}-SwAM@gJz9NMPYn zk=ki+ZEAm)hF}rxAn107va){pf*y#le}hg5u>K)b`+MT)+xe2DzH$lE~>R6sut3oA2Kj0-QN{ZYLWH59p}>i+3Eo&8FLGF%X6M_ zkVT`g6KZ1pZ>gw zsv7I`7r$h~<-X2-_t|w`&_`S2pZ|Dyz-gYu!?uNo)Xm27+%9~z>l5r9O5`0jLpj*Zt|a{ zCs>K=8v5y1ch)C;n!GIfa)suw@95}w)`?2Fp!CONf# z(NeZLz(6S!@BI~}VsO^mN0Dv4_CoXKjRPUxPkdGlW&8lZ9E%={g*CxZ%A42eM$9(r zEAvhDznV0VE>f19V&k1E&gGXYT1*KF$8Bw{TnGEulZd1bl@g$%zXm(*a}L>l8DWA1 zE#+lODqj#o{T`EKAsqMMn)ruk>+8e^R%DT+_$9CQTcEA!IDH(~=K%oTM)W>UT?K}m zIQk@%^lhUD?OB=vz1RaR>br1GVcF7JDV|2<=oGJg-LL)yt>iiynG}aqW zeHWZQ)MoZayCiS+{CV`8eu!6MtbGk^Dp43$d;~*44Y=9_;rCi3eaZR)KhSI&s;*cZ z93S6YYNWBtgi~kYF#U)@D`w8x%VM7Y=qyJ^i}!<)QU^NegghZNJZ6z1`qnkG>^dXS ze7%IvC!jY>U4@!4Fi?t!WVTXkgyBbs4Yz*z40@GPsZQfJ?q`${p#8(cTtH5QssfMz z0eA?_Hk$tC+_f`3j@6H^#C6jCc1k2uQkqcyl*$5%RVV-bo23x>hJ{IukwuL|dnC8$ zs80+;2$VoG;%Nm{eL2fL9OE_~T>KsuCCsZmi{zV$0*7ipQaKK(hoGOOH)&22A-Ld~)9Yc?lwZ?&~d_ z`fdsQ{)K~S^fMqXz7-tlmruI>HCBMs=1I;ZHT*W#cy-ff+UZjPPmLUskC7zDW?TM# z@=j^2btmbt)^9m{0)py1R}Lrvn;9%eoP`jBE|wTvZVc)=6=&fFC~`cjPD&wXmLMRH z{4^I}Q+;KSQ9bH)LcUxqRPKEH(&?iHl4Xnj)Bn@_4j=&hz=zxRM~{_R)-w9Oy&vV4 z3>NrWBU&T*a#=bbptWeVOHSmD@_f&)@~h;oZ3dG=J~(^nbkA1xhjVfh-CUz@eID7` z)n+$OEikIfeyML1N%}zj`Igw@xfp^gpj0E^^@kg% z${0S*`gfYb3thezkxv8dF8IC1Nu_J)Vx?;Oom|Jv;3*?b~~E?@Q}o~5691_4ExXE(c+9 zrodt?Go(_r_P&VuVZw}2HSvj<gCI_>MA1FA$ z%JW%Ud%J$y%zy3p1m4hE^t5OLps{S?yU|Pba_QFA)<%jho^?Q|;Z3^2_#Y?1fBLv* z8FisdHBF(ey!)%7)(A2Q_ING6T=5U?{Ei;?=?R=x4QstwHvpN)q)v3@6i zPprFA$W@WGMNG>6tJadFAylUskU&#b=K)OQK~b@cw6t`25C{EJ$&QS+HmT3uCM5zt zusnc51D{AKKp*JuGKLbOb%eQH10RSUD$!szxTH_fez(oGi~mFM5S>vj4@_%@kF2XX z!MSZz-RVqD9vj0dpR4$yM-e)}d7H*rZtubSQcN^=#fUfBoFmGIwkgLL5Mar^ zniEqXR_6a21s_qL?ae$Ktiz0)T-MWl&en1XEtiH`pK!klp!f1h1()I{3d!G zzbGzH8mfeU!}GRByw2@>XYzJ;EPeA=qTYXY0}z#2ppGVZ>py@j`2m$1f2s+@nVeT~ zstTBH>Zg0s%Hx}{4j@l?*lo@=3$aXBV~WVPOp-IP>NQWTVcHxTVPH?;u$%S{s@ld( zmUD^aOi|91`4zF&oMSKrVTb|1Yd@fgsCR5TJglAQ{-*b}{>cBBtiO+@1r&H+J*`fYp%F2q~ zk+aADHQ6YCcb{qgpChk%f_<(^ z_^X$c!>;2fvzL>gqRrHDk`j`V*A<8spuyDjbwkmcJ!;WE{E@}QS}bND&=e+}Q^U&M zKru6}=WC;EK&_{_sH}|q??i0%i#<4COFb2eJ{eFb_P+y(`qbVV4>>uP`$@_UlFf>r(SgxKzUxDs@N?OPo63RMLZfL>1g&I1R>#1nP+v9_ zVmQ@kUOq!dL>BX%Uhirw0ccqkO9-y`cmG6!HJgkGRe~O%4F= z3;d%{AZ;nwWMt;*nxtlh6r1x;rd@XB8_L=@nRhM1BXp|yX_)V?B9(VVJcbie2WQ>+ z!e`tw$r_-J6WkFk!WjCG3!`z(LvXPA>bjz)cdA&U7qOKg!X60_tx^*-ZF&EqD(mY? z3()IF@Xt9gA#qQ^seg};T8Zap0QicSlFz}(=@`q>DTx zqSRT0)P~RW`H5h%q!eSQ-@MIIAJmsJlhH1&iX)q_nB_}N@Ww{3Rt2+Bbg>a{@(0=6 z2u$Mn--#|(fO?I|`OawWwZ12;mn`z*|2(&x9QUa(hHS!df`BW(<$0VOyY8S#rFAkc zr#r7!Iq@S2mKHcdgG*lBiO70r$fC~UsW31s3oUWASOS-5=9kR@MO#Jpr=675Bi4>X82Z?u}XRN!UNLBoA?hMq^d{%s&LZ zA?tk+8HLhOJ0ee6cAn8{3SRJa*tWcw9J#jn>S|Dv7cp-`CAR7ZoHv}q1w7=jgP2W` z`PLw`v|&*J0Ht1oxx)MS+Bp7zK*HKWOiO0{V`l;SZZfA1I(UC~{ z*C%TdnS7cE2QGzq5E=;`w;B1cKV=xynq-r6wI6kjOIyWJjt(z0Ckvq{4#X7CJG5#+ z5?XFprA33N7hEy`XK`hepzeuh1@4huDb6vC6a&Jt83%d$(N;?eLbL%u$9Pv}(~=TP zS0=e5tJRx;{0j2SZiQ{tDxD}3_aa*g7lP`m*P3TU?fzQ`lmYeAuM|chDDEkrwRIHM zBHX?_;>SplFn|-!;fINKshZ5mvTw_E{(h=qxp9+*f+@kKdB5^QP^gwuvh4*C%StRI%Ls=MQX?N?86vIi+<42+OlT9+Q zCGkx!1tX6VMt#Wp2D=Sw+*@YGmR8^L8}#>PznUx>TK^fk4{=+Wc&=hn;8}|bt&Y)& zLQ>#ef9DKwNq9Wq8!0n(rrS4e~g*INLI2o5=3EMd`;h;sf_@*>Y6i zV24rx!NEg8Iynml(55PKpcE+BXS%=NTvQ_WS+B`pT<%*)lKNnrujVsWh($aa!nF;r zFhg=jGt7UGTSIomriz_A?`)7h)9`U9Vv8|fPJk2(JRfevk)37Co62@R0*DJi>f7(X zJ{*ldgsXrh~j2?_w0snrQMfC`GPZJgs%k#I}uREvDmq}2L|k8 zqSxPo0#Uf?fxkhYA~0iRuwqGw-=-^=r_>&3vA89jqlfsUt!;8;W?7P0%;WN+yIUdY z%0`=4W##U=5Ba}LoPe{ypEO@R|Lhk$?Zu50r_$K7A3+OJbSSG*1nMv6c77&G)LhE{ ztGLwD_2y~gG>qVP*zm^c*C46ti3*bJ#z@@3E>P2iFA;V@a$5u}MhrK|McGKSl9d;9 z1dCX1aroBw+c?qVyL%GmL?nCLNA#z^_oWKp@Sm%Y+Z8nTRj*X|E&ZMs+fdMH##XnB z&p7I7M&9m)w7bG%MwG{@G4Ojg$N}LNZfSSj9%(ml)j(Corx>3l7Hhn?VgY+{-d*@h z&D7CUK1KNF6rdP3;1CT`W6Ek;AE%@RsE!fLAYp%e?fn%_9M`6#=?1fNRN;R%nVA4^ z!nE3g(iv7==>=I^^KNTra7~(!wwE3CO_&}IZv%RrZOaPt4So1xF;r=A;0%tyX8dTm z{6+ePl@^~+6CyehS)uh|@H@njNqRQ{7hf`a0@CAOya8h$#nDtbVaTqm{3k|xNXuh& zvnDg8QwRbXS%|6S&QzFaZTCG;uUAn?``rI?)KT88({KmKfx$){=hc#$w9#SYL>|I! z9a7m~-*UB>J>O?D1e;ge>o1p8vEO}wsyeAP9raa5ek-mI+*9bWc<>$!IIO2E+ME?e z?wx-Reg7Iu0U)Xw7H7R4!Y}Q}Tr z84i}kJ!bjN#;W?X#TE#3_Us62!DA2{el_(q066Btni_Quj z;}a4Zxs-4FW(M_(o)-~QRM6}Vky&4Dh|AbAnjim^_or_SfMmP|x%9x(qR4~#1RB?q z%ZsAAKgP|Hi{|!AR&jW*jtdr?*hPm=K0vCxSZhf84R`k(hzf3Q0|5Ga`vEEBJ|1AD zRdnPJJ1)K_6NpXOv}9g6>_!#!Ed!Hp#3x_y2KHw}3{gB7BNi7Z{&OHU9qwdlzAFfC!<_hH^s~O5gpD(f$byeFNcG!$LCTXxo0sA7NyPf8%Y`_Z zMeF6jA!T71;V3xziK+L@J~VsX5Ct`eACmaSdxy)h?1j@LE=t=T{hwRNl1;lW5Dm#q zh$uHyezO`AByH7!;h=s4XvE5xn$nV!lmAc-+&O(XIsGQg1bD71cHQk9p!FRT@hJYP zDOnc}E?-uPrrRz@;jNL&7rW(MVFd$H=O^zxoAU?#>eXL)mJc;NS|mLLWjzL14LJ*0 z3X$}b`F)Ag<^Qm&fzy^Kdv-b}v1^4otLC>CZRQu{cGlPJ|G2{AAXKFHg|d_`rZ~sj zMI+v&ix<| z@_I!Q<*3wrM|GQdK-)4ZYtbQbJVxk;%^YGu@8OJcRvI?xkoRhQ55>IE4otlIYcA2m zZ(vMDyxmEqxh$aLSR=-+4$@GDZKwZsnQg{^R6D8sD@BXqhs#JaL8w3#okvIw-}>sy zJ`VfnwUq-CYLL} z_*r>KX2V1IGj+wZth-JiEN&CW&)KiR1S&LRb?PUZKADp+s72&?Mg3a^FY2*Fau?5V zf#RFO{Y`qbz=%|F<{2-}aYf>|K^y%yy$gQMK729wvy552mMCP)`R(^25c$RN1DM?> z1CctM(}sP8JKi5I#=%`4KaT_&aHN#|_Oi{MM>Xsppg~}T*4XDaM@3m;PW39E*n5fJRSYsl+aGb1We!rcCA|LgBZw`RAVwQzZE+<^;QabRCk3JjzbmdELMuclfy`VVBy22)X zxYF|+q)CtBFZz|dXUkSB*(Y$x8~@(r4XU&lJ{w7@qc@bV2@~OypWsh*x)wZ*xG?*Rmx3S zY^*H8QFK~-2A-v?C=@+~P36&wXFZ}_R#=3q_MVlg^NS$I6uw7x2%#+NdZM423196< z=T$RPrTZ|N=zPed894qRgOWK}Dn&k8izr}yH{b(GK(ih5B^#~p@X`^qR zb3pnhbZY7#fBRE^Lq`o>qAcys1)kts@b$`w7HSvLiCwfZHH)6(;GNsk?xsTDp`L#}uj;IP%t*K4Mo*HXBV<)+yeF+cOScnXKivJ4L295J9e*cDyY)IjNzIeI zj#P%>aVJwrMTdnL;FSVS+HP&toLC0VHp19;?778*_X`iL&^%A?CJHtm+&v}J0o=G9 zkm5I5Y>3+I|8iE8K3!2|+`cS-IZO8?s>e*%h~CmkwHayR+lT*H0HNT=vGd*Gx;_av zAm?|HM<3cUZFfG_)M-sMiK8J@H<((@59Cunb(7roY8pAHoPV0RNgk?W^22Ekrm!Gp zHRfFON*#s28*OVS^y(60{7E>Cj$_Ls!!3BFauAHtV=p+LqM=~2I#iSJ2IKv%=(cV5-!(0T1(y*S--HNzpU=rYzwGo7~6 zy^&)WcrL=H(X!}=2kt^Br4TNO`M659`2Oxa9xHtAA@&@+R7QGGq)U;#y^Rrv-}LN~ zSFDq=%WFspX6(wowE+Z9#rBWf3p>_XPXVO?(N&}boc4gd*25HL}H8^XLR*@2u!3A|) zJz?SPGceb!q6UpK6tG#wL z>@vdWzzd6m*>ZYwE zoU(b$i*FU~Y~Nb2Zp9gc<2h-3Oyitga(k8DK{W%}EZQe9#kc*x>o)A8+Ajv!8x3Ix z*O3Eb2J=PBax$AH{wFwB%yyuRv-fZ84_M-4++8EE8wEXXe`!1 zw&cPy@znouwYHgeKvC;w6!6cqs zk($wnjF`6V6h&`fb19^ktjWeTmi6!7KYwJJdh-(ndC)*2WZMT)^$G)vEC6o2mihfX zR;gqtC1rmXGp-FA{1ByE!6?`7kxZfzn9Q2tASb-T$M1h>(6a`m=}*XFO?i%~q45 zz9vrIWjxve(WU&2(C2a%LT>XGMXReHRaa;&c&uDbo!yT*G-j+}Z^wSuU7H+Cv5L(4 z2w9vujhBnf6=^s{ucyA-jvF<>SBOMYdCx9O-^wGtsW}tZ!Z7lsn6z|k!}SlFh&7{> zj_~KHd|cAlkJLtSnpU~H`wT}W#Ff1=&p+5Q90|D({}gHMrO6EfcKK-_R(F|9ddf21 zAUadP2jsOGr;~c3uT!O`&Ki3zU7O6_>Zy!BM0duMY4{Ppdp`my5sXJE7j$d5Nh9RLN#SufQqWqW0&~|B4GkHM zv9xTty36v_rk7ig;MiX`MzJA>Wj)Js)&6%Bzf4jB2M`1DDu0j04Mf8N^)T4abR;FQ zf6@sWs%uZ!MzUr-86_@vB_K~5idNJlr&uW>Ck3|}L0BG`*^-<>|GzX!+%#?S#Uwwt z`+WO(01H@a-5OFOP{Z4vr^^~y+1F+5>gSNIdlW@P2GQF@m-c5ghxt?SUr)MNAg}K4 zF8mN1n8Ycs=ocS}C73=6o$@4=0%)2yWmdRn)I7)8$SVNWwbpXn0Nj<$Lg z*}FauuL{p{7g}2b4cg}KG7kVXN8d?DsZc@Rm`%>nbJQNh)Jw{`)&BMcuT_snW+D%l zKy@onG@ccuE>On1xEx9PJ0cffWmK}@Ee$A1C|r3mYm^&TuZaHL==*Y7?2rN^u|ap6 z_=Rg>m#Z+IMPZT*>ciXn-)Sabstg40L#O{K!;~|?ZJt9br#ku?we{^U%gfH=Y_8E(23VSTKSZnHd>f)0iZX z|3vj>t5F2*R96&A`1P9ETWu2}aNpzzu%F1gN{d-F4$T32X113K$p(SeAGSx^7E=wH zn#JSapM*4b+1oxm8RR=z2!W4({bb8a>R><4Z@s!9EzoxT$G=3l4*MiXgYp9kutqv2 zlB}{=*_0n39k}m6(Q#m?&#g7$&`Nc1Z%^v!E!7$u@Z$i;`!pnR>cmXK;ZcSCYBV<`2KFV(Bo_aXVvrd`-{y1 zkJc&gK%405w)g65T#uxcf$fB2k^>+VrjX<9i(^@n{ZAyrj+jGQ%kqLfT3-(I=jbAG zFQzJndqo_~pM-EDFGUtHyct#yLAHMqs-vmk=;ec}L(EZ+xIiA%9>iYg< z(uxyVnr)GtAShB_^BAX0sa#EITFCFE_=Y4t%ezyN{%t!Xdd%2Dx{lFPlXeFc`wj^R zx%2x>GjDj(8n@MtnR(E6pJwNjxtDOy3OXI|nf@O#Ba`a6CEcK8u78xwl;WczY-XYF zXfktp`tXm)LP0W*BKt*q%PTpUiG0H4q1{Ta&)wnTAAn=5q4$ULFMf#!fke=#-QO4; zxd9SW#@s@MJn7#m4g@{IbI~$|pKxU^v`!(uS4H6vO5_wOBn|&I{uZ5?DC#A^`~KdQ zGIYW~>05Fyi;fZ_nK^Np0CoO1X70|j;7Bs<{GvN@cx>8U14iF+1^&@N}CHA(Soj&Txw0f8C_31LK+OSl;N#YuLaOD=eU; zrA4w1^z`&(inoGAPuHs_A?sp6en|mT!49IiTY?JM{>*#rb*~v#JxkY+wld33sh$lM zZnmyPJ;O*d;};pM6#xq@a5sR0YEE{&1)o;(2OcUUgiKAYYVnA)sVStOg}v`p+lpG` zFp|7e9CNPJFPZue{D7|)xp8E#)<+cfgZ4{}nLOi|D^R8n8Xg(8x+k@Sx;gf>v$E8% zj;zDvl>^(TdrEQTu;rQ&6G*a}{_pzYQP=gQ5h35U@!CU(dN`3q!SyzxeMgugy!bd@ z?&6Alo?DUUxbQvtJ2kdCIi_MM@uwY#C?eZ+zD)v8jyU8Rotcpxs`8Vh7-S zmI1jJi^(B3PB=%7Gs~1F(^G%iw2<)@7QyN-oi|+MJUFLh8Ppx|JgO(9xlYndNb0FY zZuu`Qj4~l>fnddw;-9AP!(d*qU@}%B94yW9a!j6L#G5j#3hcW@ZJw-(sRwYbA*wb# z=c7D5f46_8cPIDkW&aG?IcTAw6{6p8k}sReb4^7OnhWyB9g#F)q^HF8 zMe3E&4G5j@2`gR;5U9*}GT)vtNEiwsHEgJ#wohm$OqKvwtq?%*RA9Itwm`Mc?S`8jCQ1NEa-EfL4>XX~DS;S+DeQZ_Sfkl@6F z`^BbPa;AyYmmt~jQ3l0}m4BTd&i7X>I$d{M8MUY{U{7V#WIPw=box#xVWJ#nt26*hHK&Rw0E zx9Cs0+nT~JkRpT_f9@V=F2NBY$)}r9R1QRJVZj(45)nHL3ZL2d^BfwX!PY68Q~(<07KzKSjHSDO zq^M>r<8MpFVk7CcciVyXj~vBWHaj1Vy=uv^n+_oMcHN@IJs<(iN6=%7Xp!trRt) zoKQ@!60@Nx%dSRUMY~u-)0V|*c@X^azDXoi_R91C2IQP1f~+hd3G>-*4&Jr=C6b6~KYrUM@c(A64chk5~O@U7qnR_j&nEyO#a z&Cb`7d`fsghOr6E+R^XRrWy$9(aUaW@enz5e>|?g2NFqi4N_iSyw0nxdvRlBF9ka- zh=5|_rCTeFCa0{a{2P}fiH~Qb)G_ePfq<_quBVn}M)=p%cL#NPf?Mqei<|eNyTJU$ za$LJ~Ng&pedDkWmI5x0$pr?mM4V^eJZ zTH;995+*s2-fI3MGiW%SZ#nes6~+zwkzN9Oqk{C0^@7PS`i?Bh0fd>4abZ0k(axds z*gL0Mqe`I3C^>aG(a*Md*d!w>>vz{jluZdA#uAbG&VhtpOEgGtT-hs@uUI3()ZkN3 zo?PX;;096;WluhMR}cfBOTO_og70Hsr);#pp0qv|rJMxRP@iR+wuQf z3%Gwp`>)Y4#Za-WeD7m(vcQ~4!2FqEa8gapc?_JSk>3q@mI>mm)F{TWh4Tg(6qnb zSe*Yu2eECWDchO(TiZw|{PCyl3Q^w9i%vO=UBK^q;9g78^Z5T8oA*C|aLND1S$SKC z|9$J`{y+ZNzn_0Y{#P9M?-zhy9fo?_7T~)7B)EW5&_p@RdCVzRs9m4x?X|5hfRa|d zqwMpxH6CSi#Y)54oW%7p@;C>>t>u48f~rY0jfDRu19f}YFQaeHXqGQqwA2L3sbJ3L zEL;4i_$qWF_6Fkt{wnw1gg=dhe*b%s!T7)5O7j4~Uvf(+_FxcS&n9)xfI~k$E##|6 zTU>EJTZ=|YqX0j+(q5N+gAYTHPjovQW6tKCi5$bsE^m&8NAM@2D)e+@D$k9m$&?!R zF35~Qitu-Gt2C^?QDgGeJQj*=&kEfF5xaYV1v~Hl_tvW_|Mz;zT?b5pd+Vu9ti0n@ zq6jITycJW35KzasiM&^3Efa$ha#6LA+9dkW>Auhhh>x0@!*OPsWuI+ealY&*ed${~ z15NOsiS6#kj@&u*7P&nrX+0;ZxL%(TQb$g2dUM!{-~1C)e!KG>lK&xGX8@_Wi`yM59i&2VM|6q8H6G#*w1NG*Nj=@@w^}Q}95~=$ zWzlYcGY=tH@^1@;m&ajdTvqs&bINtL%z93Cka+j?Pq$He4dbUHNyt_Q=RUAUNz6%R zggY;bSoQR`zHs;dY^w3C%M;kF;IJwTt%8R`@&2!cH;o_7615VL{lnF_b7GUxVLhYfE{-<}7MO0-F|G zfJogtui5FQ8mQ|6_G?t>L0NALNLMoNt2PVLV&9jK4{ft1ae3^~wr*w&be^5MQDpKhi}(LQZ3aKhUNS};NT7Rl%NVwVyd;{@DbU9ZQ7#B~1)8ZHT{9Dy^cuc*q~eb` z(5m^bBoK@3QE z&&;P|aTEWs@Jf=*YPTAW?J$urRbqr>=|l2?YzzgD?E&9KrM&A<0#65aXO0;hpK%l@Np$@|ls0R`I81^N4jWpM$L3fe+J# zsr!S>N(w4>MJvoVFjM%-nk>sO08?P4uv(dNifIbjCmEUC>cVp zy_4W!UWPe_(YK#Z`riiwY!!cA0To}IL<}^1MN5v-+dk3p{|+_$a$PXJQv}rgZp_I zP=pvW97(Y#Z7)q0&-bbMUK=bbJ?f?YW(!Hl-PWltI`%A}%z(yC?=8ae+zTSmaKJrj z*{u@#L9+n~AWd(@qnkpgA^DGt1Q2VQ&MnQ!IDa4dYI<#mTICx^Qsn8q^10s~bM*A(36`6l3UX7_hfpp zE>7M>h;`eXB8}#eR>dT#9STpHk#^y7>z7`Y7g-&O#l=t%y0y|9nd;r}oRi$Ur*7k^ z!RH~+I{JgNRh|7j{wNajbfv%n>qpFej-?F&Dvf@vVLwN(ZVbJgVIOG4%_fO8mdBIl zdSWBG-B`*)EVV)PYKsD$dlxf%R`BGB8@v}lf!_EQ=UoDKn!Is(VV7{0&0W6L+O2I* zb22c+hgfZ@ZMNZ^zg%I5?Jp8l7y>RtZYJ-Bguv)uU-ZQv=nI37mB4)9-e)5#lW)Jm=8efD0(hTFNbyCz1@?_X zIv-!EJT7*)c?iFblDsd4*~}}~Ao1k%u_TsI@MH=Zs9Lh~&ET;TWTUx@x|vLb)gvNo zjCcPF_qd8to53(JG}n+IJyAO))zszdxyFp`ZagIe@r;YAg1+&@yu`hBjBBl*^pZ*@ zk?cg{h_%Q>Cc!3|$3>oznZPKZ;qLYggz_Z=Owy$Jo;l|6cz%g7$=Nx2SZix>hg6d* zA`h9}CK6fAI#Ql8zQJkUx27(h2s`iq=l(0{Go_`-;qyWAeNiE$*$|usOO9w(~9BjxZh0QyN1B;`k0f+*hMoK>-EZ=vy$@iS7pxh0}}M99xAS4*|&WZtd251-CqoA z(!%g5>kGBB zK);LI1ECWM^v1gZ^c8I4=5Hboapp7-jgzwV(!#6rLWk;FlNHiTzWe%OTyw&Jl*<9j z5SSygX*Q5?KI+;f?P%yT&4=FxIK>u1ka?UW7Z)KgFHcJ&cl2Drng_islZ{_71y9u( zyyj%qvtahBY&)iXq4#$@^P)H?v|4Bjg9-Qhyx2u=%d60(4VADXl`4BNN$cpP&Eq*h zMrIT~UY{lYkg#mAj+r<2GKuw9Lsz51!R6AB$c~Oh%Is=nluJ@QmGs45=>Bep3u({i zU7U;HsVF_^RZ|gMAtJy3fuG2&9Hj+AtgAs6RbcsEXJP!IcZcx;ac%CQhj@g76cYQv z#M>)R>%E~R5vx7=EL1uv970>2Z`*WLO2bIT>j z{vIq9A0{bFr4tEo%}MQXFqL8V&J>ct9YtoHf=L_=EPQ;cC37uy}t-Icv)1dU*AJ}{6X`e5VrYc@1jjL`FBmU0*(AR1KIHI`G<0yzPfd1E3epk zca?;)i(l2?YIUmt(=;azDIN!OUP>i@Tcvp<9vOo$|T< z793J?5l1*bV%W~k=J*_YYyYcw_OfR6U>U-N_h1$M8kc1kXE$4SNKz}rHo4KMzhlx< ztn{ntBhYK`>#M2wKf|7qiM67f9a=MFDH6+K7uSUL`nHy)e$AohvTL?N{;=Q^*T$afZ>B_IjF|aZc;VTPg}gmI^%C(>|IMV&5WYanhSHO>@!Z zkLn<=TB4#^*C3XiTIAfXR7FQF!l1T{lDBZRGM|QxH!evFJ@ukt#g_1NGg5Kj(lRpNgFD@>IdiS1+6k24~42pu4hTugW3W7Oqli}u~VMk>JYg*!ebs%;m=2n)3**rsuscB2Cug!%O(~8)1se1M>$!{9c zXaB-HIVt%&?lvBDu7Q0nzV>Uk?6cr?>>Pt`g~~+vHf1=sBag@&2NNw!pWkV&@*V6E zLk#E2Be?Je9a_Le3~LS6h14PlfPaCoR$-AJ=B@QR&-K#g6E^6P7eXpP2x|}0Ma^AT zAd8NguQF*60(<1l;(m-p>N(xoxOgmIcnex#?jHy`Jcz+=T!f0e2D zEM~Jr&iu0L3)c#DDWW_d*N4$9iHGO_)l+oKo@eB$|=x;kFw^&+nxANf#MpM^z;IeGa|%w7fyfUm4>Z2fu8F@$mMK?CCiL4r;%SdlnQho#7Z>p zO5&-+#lXv2U<|Sy{QV)$**a>Hhr=`>`of7qyf~grUMAOI{FAQgihx~ z`OFLPGC4}C`eDMte2F9~AC|s^GXg$n**ffMoKk-QlN@CJV3;O4$xgvdk$rNI;t2P3g|s`QeXeivLpEpYBDr3P#mfK9xU^jE*F zO^D!Sph_<`5?b=C8aE&t)^OmU#ET+6PH)sS@84Fd-URlNYiVzMKJ!37N1Q+CQ#xzG zJKWG>G(=$i9t}dMZHO9}nm+6c@;|uPz=tC*las#&<|$(Pj72vX^u~TdAS`P3yCaXV zORWP6kJJMeet)T|Q;@?D2PIptl+|RaH}MGsD7NPJiS4M7B0kbQ>Z?lWSNxnC>PFzy z5sJRdV{*kug8z~J>x>Ucb2`hc6+OsO;*jS~L<9m?vGglE2J`w9Y2#k&_YP;D9htN` z%2-A+giew&IU3&qZYPW6(oz2(v@1Pdz6`)09KfWB6#g#EDum@#m#iH8(p0XKsubyo zp0Py*hD9l5n`-Ke%UI&)OmWP%lr?Ex9{N_eAQmZWGiS$1jCUFp4PNN1V&-^ouj4YNVPnv+#jt)z!( z-8=gS1V62x_8kJ?c7|}thClW3QK;K+^G$=2>nkRmkd{!sh=i-EGi?aS9Xvxj{WRir z)TaBz>Oj(@sPg4pBzW4`=iSvIhYM=E|DI~nb_gZyDOLlm`uWM_mIm1fNUQ6PkZ?|x z3~B#xrtk>eUsxcmc!kf9-wqA59Pn3-56|pddC|q9fg^PWiKoj)%mFQ_=%%+)IU32{{C$En-y9-{Yo(tWlpD?CQ==6 znV2D6xo?gW7Lu4gvC0B@s@42L+#xziQ4lY$^S;)T0vrI@+ABc|eJbXlM9O+-2^}C&i zQIjyY<-pxJj(Qh<9&~BLZELVO`EqBIDf@)ar0$%;uzyDw_(~_I=L&z`;C}P>Z6sZH(f|! z{TPtLtkGs4O##QDc$foB(0E(J&Sh~Vt?<201Cgyd&PL>FlO!8v@Kpw3Dm;VtH)${S z#4^v+fUAk_`Mkm&=!qe$<*mP?5vn_#^5Fm*w}XZIr~0*VQcd82Iflk?EN(UsN91wE!A7 zoN>1^PLgdAJID$-c|_d&i=)G`16PUzQQIFR!X{Kd5>HKM1q58yx38V1eVO<1;NcJJBhk{gShbE`d8Az+S zWv~I0>9*V4^g362)~F{3Bp%H?E!uP9Wc(1laY##L$S86Fl|G><*N18lA|G|W}++O`_`-4+X1X|XncaOidI{Ntz zV@%$9B}eoJ1Y&pCRt(aH5hO>n2jU|7KpP4E88>5`&S-pSuIfAIrjP-&>9UT}<=6dl zXkCG_>-E0@A@~yO?tLt_9@ZS9Psi*5NLt@qOw`a~pdZ%rFh0jXy%J&`W9G(nhD2z3LrX@NM;q0Oj{n3K3Fk5&YMi50 z4}>QS#C+wV*rlM~+uslVJxNA`zytRcZ4|q8x=B#zhRZ~o%eJKEQa%S@Wz@#eGTich z1vU=9pn*lE$QImsfgd^Eyec~c2jfXUdKQwVzjlEA>uz=Wyp4!36}bR%N||r9OUo~) zCGX=RIjGGoVYKd3elO+f{(~Opq1xG;DBMxhx?3Bj_k+7A=OdV*C2FU4$LA>C)|(~e z&b@U?tK$++&(Q{KoIG5QjnAK?RH?YdF`h)b@^C%bop#|)9Cfwd<;ya5d!vv(5b?Sp zhp(8$@-0XWy^kN~DpSRpxF+|kWG$PZC2&;!e-q4y7C!f=EVx*S(qI8(2~`D4|5 zXXu1BXk3T*&5G5X-|yt`AANu39E7z*z!sv zq=?iDUMHkbM#m^84IzL>om%d8FBn+kB|!)2e`Ac$!bfuTv*b-1OA%-m*|mrpui_ph zWXo_(qz7^qF6wbqCNb`*z_?t!()5Vm)&AfV%d_W)hNXgXr^%;XC=gGDMEc@AaXNMZ z&I}7mej^D}3AGW8xnd;P_tCK=?d?g%Ey5d$N+7+T6YEMJ;F^1#%_^QG6Wy)Ovn}HF z5vhB>*|3Lh*ANpcb%xiC{(3V$#=lNY9%R^4#U}D{kFp=8i@&w$)Fb;Ku01NRYOs)C zXU%#Zejzo(XYZLb+#)I?$ z6QS5MYB#}RBWYNcmS0=3n`{toHmz&)%bZc!U6H0%wI&N8UGV1G%ZlG^yHjkjr+sl8 z7kP1Ex-kx_V{?)3ywyrsO%}=PI(j_Xl6eZcWJeaYk;aWEKRWnQ!z-;*pvY{$zZ7Px zH|J<)-R#vSmjlqmImURA2>Qes%-DP-@v?{ECFa9*pY z)7NxhP&QrV|({A6<#b` zcHS?0-lLQGlA=U-FWa*GDQ;%BZ<>)AjCu9GO)fP}ydP8nbv8L3QiJNw zmp*_vXUm?zqI@aiyoFN(p_pH(OR1Kz-6At0Q9OnD=hhdLbG-K&5{2GHMRQMJbIPNw zV2ZZ$(E#ZK$i9b0O9;>L;7hqrYX`#2G^+mqEU=P&og@w^%+3!%@?Z8I2Q=Y`Es@3- z*-v6l_+v(Y!NJG)^HSv==e);`YFKNa#_r(S#o=1cJm={=|=-7 zRbM#~vD&dnTO@_KCZx<|3Y4Mxd>JxkAUFqrk?M7H+(Yj!gl?|Z*=Hj!bmPX|UHQMq zrqvMHAw^79$Q61NB=c*sX-3F#uZe>-;0Cg?XE;pxz$xraZAoA3*u~!wSdNG9>2O8b zrj|z~J;trkLo#} zGZa_Bqfr};?GgvuB$X?C9>#X-r@JHNc*7}Yl{+DzaVfiO&=&7W-hTVhkM5ClnHwPl zt3HbKnj$@WL|LIP+1#|z6T|?tJc&i?kPS?jV3A{K*XhxDBz=0I`u5j-IWS1K?%9b% zV(N1MXlt~wjN-qWK11Qjc<0hkNIUgSZw)UcMg`npf%pn#gV6s`)dP3zh1Oi3PS-xM@^uEv)-048%vc z*ZzfK+^lvKPK4|$yQ6Nl(k`oMuTHP ziV^F=f$N&d7B-1GZjhyGPPtJ|;Vby%gKF)$az{Oe0(?%p9p9 zo@o^KB13Y?Knm2_P}G}g|1GH-cz6jdw)}}ojKV!9xd1y*%iNWO#m#=Lo0%6knN9ud z#G?1mcB+O+Py{dKwy=>_=H!R}ZmT@wL*DhEa7+c;){V=#+j7HgZ~w=S*sj^{Zx4Bd zZdtZg_6zo#wQ`8Y4xAw0>JI;~q5Dlzqz~JMsr}@_gkYA8AW*`1&d$DK!s41FBoYwx zC*RA(sroF&fY)AMi2b)T7f;iF_K%eNpSsZiMwIRvSC=%k^w{w*4oG*k-_mGqKRetj z)dIHqWgt_z;7$;T=X{MSrxrg)!N1IFnXj9AdPDOW|CLB zpNtQ8R?;I~Rv=;;vx9PmZ^b?;QIoBbA1=Udp>eaKr(DNk;Jlm0{fB;W@cp^@?teKy z7{mhD20;VXz^akmIRy^c3q4xTQ-|D7{9MO9?u=1em;q1fUO7L4@7$@;fGnbxAhtW) zTojURBHrRY;qa6qkTj2h8y|@Hszrpq8mMs4QYS!-EvETr85Cj_`%=j5d%03G`)-cJ z!px$>wjlA&9PK;DHB@)~?Plzc|8MGaXA8DN@}u6Vd*I~0$EWV|muai1vG=e@5BofZ z0+6AnP3P%0led2|ty*)2g*jX!)vkKD)UGdZC(PtJx5VO}Y<!_gQ7__(A!N1pXi7<|jGvOiObK8Xk+i^UW+D2Y$C!p4YtOg-jWr49=e(X-0Wypjam-@l-+{eU1`wlB;(G# zVY}2^_X+Pc2Ec^8GG>s1+l=ylN!12Ky`DG2vLQen3|Re{R}CkbugPRF%=yCuhC^-l zNZK!b-r<^`k{o<>@`ekoR`Uw#oJ?AqnjR;E{3?Hw4)|Ipa;6PR>y7+Hx7?l&ib z!6C~T+c%L#Ji`I|sxV_cU5sdy=FUyo)mF1@JV$I8<|8xaN&@N@duEJGcgo@USyazc zY1yxAxwZ}AL93hyv(zu@9{*lx#+HZAu8O~-NsWR9!VMJU@%>Tmj6f$Ixqh3>aVYB9 z1J}^~P?a-%FV!ZguwXEnH87YhNo49MnMT>AuzmWcM=#Z$mbi=Ufgv2~TVG|G-)-aKmkrqu`RXER zoF-(y+jzr3v1At%zq;v=_qrw?sAw|xJB55>I>KEA&*67>a08-iIMEk1xa_(9$Cm)_ zSi!LEKpt_~+WCb02#XuVIg!qDUK*&9DHU#dkcFeKiy)7<3x0~tUdYcX9t{3zyUycP zu`~Q5-m-z{vTA6^kY=f?tJsTt5J#Z7xC@bGZ|wq=T24E$1(&fLoMz2^gy2t0;^ zoM;&Rk8y)xz2N5mwQpGDg)I)a5+Gs3ZLtPQ2Z4&IP)`$tP_R(%z)=_ zVW?>lu6w3|2`bC05-P@kVnYnRDF*ep4Te^k8;{T@u{klcm~y40SkWFOpsIJGnrVjJ zMJla@|K)4K|9yeU!3n@7BR<}bd5_+LZh1iWBi7aWeIG%u&!?Aw`rc*6P?@WsNIQv0 zJ3Vd^4nA-(iJBxGA6OsqeH9CNzBjsod&R1)5tg5Aq`F` zgjF72qp!^gP06EID-NZ&!6dWbbg!|^jihsRB3Hnvmz@x+5Zn+=; zu2k4|0TM_5o*x_8C5`U4Co4fK!R~govAYPsu$Yzc2hs3@u#Cf=eG-p3;*&_#TO)E%HRxgWQ;`=BNbX!%sV*EIqr7w;JJJudj~ zfo@w*&!11dGuvJc+sd0(fe7U*=;>l;qA&3E(wn@6?)tjw==9Y~7w-}FLHbJv_Umz* z{AGl-&25QxS%Xw#=L$p{Aa#GA=zX6!(dYft=Z)Cj_L?23{!ndth>wq-c5@AoTR=Cp z6(iGEKY@YapMK{p2>oAYv8ghY9XVfoU-kF_#|8W5hJWbYOca|INuWoKu z6RW?zKPY*Bx`%$I-CvFPMX8Tu|8k5k^I|#5>x#tdDwpWI9uT4Qczs+m?u#Vg1_C$q zg!_NeY_HAECud7iMxBR}p~4x^fq-OU{_9SgT)hzzOYPsx?K42;|JuLr_2u;SW4m?R zonHsnt&{FC5LhyOnAywGprbc&&Gde8?RoyV&gSgZ6_Y|i>KXl?sRB1sfMtkL=>nws zOp&(i;1=Z8>s+@3FrvG};lU=qjJRPu!KWf(TBEV%Oj~^54mwW=!tN zF5oRfZj+O+P8R}R#mLwyqXft*0Df|S6Q7I5TY|Hcr_3<}(EXs8Lcb}PYbr043MJjq(>2mBR z5PE})#s<8dPnMINguq*yL-cJzbB+$ryi!fhM4u1?gPcC=lsnS4261oyT{-o-h|N5U z&3y8I8_A*znAyAq>uk9u0{;lM_L(+C#Tm48=R=A1bLg7Usic$Xf4~v&0RF`7IeZ6TA)4y!e-;D+$JzWz$Pjs{L>^}AdH%lhS zQDWTv%s#73{qldC0T6qNsd~I~;m;X_b}3o*|JX?0nv&|8jI5w=m{efAOLQ}eYAUJ6 zf!6yON`<6GBdIAa67_Kv<=C8}tl53nk%(eSTIR0ktv7^lUf3_7!KHG3Pb*^-$o1TJ z5xuk%0SOxzwbKYZwg%g+52vlSgs-RCPw$slE!Mq@y0Eu1enW8USwa1u8vuu;U1JdN z{yrANRS|>#wUmK*a9O8E%ZkjaE5Mp8Yi|H4NnS;+!sS8sakCS7o)hdIZk3^m-QkKa*@+A*jGORyk{~p-}Z12(S>(0 z_1a(6JMWiEK6xW8$BE`(&04*x zyL#`cy`S1v?-O21IU~CuII@nD^ow!-b`|>l%ZBQ~_v$kO{+W`dh$Gs}g1EKTi#lXh zpOh(Ngg2OUHQubv8R#yPymK&@If_&ERU@`CBDfPjapw_=f2>JaaB!YX){N9Qz@FP8 z?C!sos1rm!LHgu9`vT0@^vi%?afjq$j&2&mS4H`sqQ{$NT9CPR%f8TOZ37=?`n#b4 zl6s7MbCvc;{WNacS!YS$smls=QvGzepI{0-T9h|J((Hy0LQsA;2%?ce+^y8;wGzRSCx zO?$urOmbHDr$m+C!C^ORh^Bp;<>~jV5k{2<#y^_{%RD7cJQ*BhHJ|z!>&!k_)8cL} z|418jf>7QbVln6Ngxu0zE%81~zKoktX#TKn&#h9f+X-#{N5u1b!A04F`~tOlqKINX zlq!_7IwRQMl=IaIe1-Xh4S1F^Ow1TT>*9i!Yw5(it8jJ~_Asx~q@$EwU{+{UZ?H-G@zu4)`KY~Qq9wXLhQ-yLh)NY<**XASGm ztY^O4jF%k{u6*YIi5OLv@txwk{u~d%eL_dQEn3-*a{m?2swnWgHfCvxZu5EE1ESmB zr|2{Y6Ih`cyJb&&m2X-Wa=xyKErn`qjqW)oyOZ*2s#IvV(oCPhWWl4yXlxe5ro7xE z-TZSSn`b#-7)IT=>maoCO4Bw^z4Ep8&UTW@xnOA9l%@n<^p+gnK%_IRAYEkUlgmpa zobv*<8C<@qgL9pRZVsC2VX3c7g1daO)i^7JzY8Ee>TiT+v%AXZ_l6Jkj*8;v+(qur zG&l{1#X~q|KuNPg21* zQ=Q-Qf_kt3sm&%8@D zzY|5h7w9=7jxwWg!ecs;k@>F4TsXtQ{Uu)3O_K+YoPCG5%DX(O)R0jgy(5JeVI94iXR(%DkSh4n&fw#R`I&2n$exRF zz<1&lfOy`W!bz7D=*Al2RF(Yxq*ygk#+N>P*jb&uj0cbKzug|E4ZbNFF#AZ|h}^#6KAI z)KInXr@#Sa1(!6W9T%fEKP zDv)YE2;(eAG{nCY8AI2k0%F@J^L@pdmxH+(K$#_=m6^59^679_(YLPbp@%jIFBE4* zeJN*(VOH0E+Y48{4l(mOpH_>}q2wYHb*oxl#x{c;lV|#HhOzV+{k|Ok?V(_?Fu! zPr(!S(9lZ20Q@m|#t+^`%Ll-$Ku}r~ZPU$GQk2+RLdoiDCW~JP*9?@mPP%qr+6}p~ zSI{S1nee(B$4aLzaT|VIF&=#4wsAGZ^f42UhAvw+{eF)8V%sMX>1%#uv#qd}zliB{ z0bt41s{Qlv(Zl0zJnih-^Xd8-yH=`R=jUOrX8hxn6kXO1PX#<6!I5(YA_H+0s!M%e z)O{&aC#i43eXZSab2kTZY!hWOBDrunnrx5^_2{d$JmK~c>4h1?hs)*3?iN)|O-+rt z^D|P+GjntO6Adg~M1}(Rk##jdK|3uY?F)F0re>yP%?Y9c`<=>Pg`}nFr78XUic>KK zN$r?_xIVD_il5YVo9oNvLzRz}2S3M)vm-UtR99oCX}0I4q>%A9MSR+4rkZ!>4B_iw zkog*sO5#Wpp;r@u)77hFXuGnw*`ohjUX;trNd<{b@=%z6Qv8Tr{_9tvVp8TyUajG1 z=f!@CNhu2pdP4{FL95)~&fL5|Nto+ookYc!uxkc7F;i7kg~D)&S$@4wpZfCkYkMN- z;9{QDgD61~QaHjNit60j$D&o5Gj;Q33JdB&y>vp0yKekbBi^*OrlRB_Gt2PI0*s6y z?UmP+TX0#Q_WELl5wo=FFBPE<&U{jYN3yNZ0GBR0(Raiiv8Ft*YhW zQla7PaBWA_>+C_1HO`T=$Qj?mG_=?yOUKb<@QY6BF7CDZ)>z-tHy< zVFp>Xur;-b`*IBwxl2v;mo0V1D-BJ}2CLNZUAUg6C`{>7zA{#saJg_d&U|C(G7w6m zJjN40!(hKpy~>fzlRV8HuPnwq2T#m=g_dKduSCDKuU#_X$78vY=K9<}UhO9aqGw6o>Xb&H1?r|(&%u{>aC37j}?7J z+PM#=L-U;T1|dv|re?ptvx_+bSqIGa>c!vLIjbJd4+~#!_*3B5L|u4ro>xR9e#T~# zKP5`tM)8`(KA>cZe{oNVfM)lQa`Uq%?EM^`f63=fMv5J*m(HKCf%M?g=0|SK{sp6* zxJ}VZu>PtI$b7aUVDT9fta{LF2iD`?40%DmFz!kvZs;(ceHIvU7k`b?;ErhG7jg2Q zXBxSBfSZzIlegSL5g(p~s-Zzl6D;y{Yk6OIF05HLa&aZLGU&@Fmu_GA(XAo0kxypT zFlfxkhWFc9ZDA=H^#a|d-Wj5;ujAH4u}*WK;*`C0=6Fs_7|ZkFgj;v!s1I5yeW_`nU5B`gxx<%Ggij1x zb>og_SnlLmPydZn_8)bZxINbk5zN_(a@)d;3L!=7Do70?Mz9OK+ z?g7Xw*qJjVs~eUX-{7LKyjUrALLWb+Et9BW2^+?Z#CgE%Ii&5%@XRdg1< zEHPHW_0iEU{v@CO4w)-pd}3!~$+WG4-hT-@lfy2|46FXMv=7bP`fV-eMC)E5HIQ&| zzxEs2BsL8!2z)%g#^pNgXr1Fk7$gNP{DJ9iDPld%l7oT5B)B(IC3R>}hK1BnEhXLcj#lNG)%kYjYwk%xJ%*~V9V+3*X(A!7NaN~Od?@)yH$Y1iGCIC>)aE3s~o^t z_g?xFSmh(_R>pg&X=GRcjS@=8M}2G{U)_1Nt^zv;FDH1s`4UOmcFd#4&$cOgi?k+^ zisUKc3GZAM{lZ8eiqaGTY>byg08Y-zqnD_s^U8g1g@DR>jp|mD_GtSvrfrLrsuTTx%o+kaZEm1vhwfu5u}1veC>#&d9l?cD?rEy&XISjO zQ8(d?{lN9eUl#wwQGR-xD%=_U(p#y>-oWLw7~jLTI5?-(%b|v#hGE_97m~VmUkQVt zQ4!45XB+YdDwgE@ttC?m>t4a>98I@E5y?;POP|JF7_SyJ1@|Ecd?@lMp$hO7FvNPQ z{Ov0U;v#V^R4?I3f#eAmq?(@Q#n7h;pP3v>byAzV*w-1?^w`a2l-46Y=QAT*ijVfb zwXL#yO(V+T7qPDo@yvTvw^NSqCm>o2!=D)4T*RDk8j%>elqQNH9SAm)h^!1gC zi;S1eclk7@CC4S&*e!FfyFBCJ9o$J0spQ@<6>$vfN!%C11BP!A9-gclc&^kx7WBpR2-ObL_aG>nyQU zv3&MjBaoF%s(FW^x-|-}JG{2L3k6(4N5S$90-u*_-9LY?!-Gha9ld!wf2Ma|=nu)y zik%34yW25?54Wd^7%qb7bw^=e#L^UEU7cpG(#gm5dHlnJE>X>L?^uoA*yn}_L1&)V z&gj%_m!!vj-c~6oY*7T=j~|wRoSgP<;ytpDxZH5kkD;-4WF@s?8gF!xY~*)H_#o~V zG&*C)w;~axeSMDR`_i@3@CeB^;|&^ytyej9fWjcG8M>eSCA~Z_Ey_f)jp04ZS-cKb za@#*pCg-^l($KH*-@;KC`kOB_Q9C>>A+X4f@m&wS*y_7@GyA*q{>K*4o!oe^qz0!* zy-SXFeQS8dcz7wjKg50c3s>c0=^ML+E-pISUgjuu#0iq&^IC2milY5@-tm>jzgavu z1SBw5U)|XBeYfRAAV3~>pz*yGM44sY7$Vb_#aboRuqU$l+5F3=_5X+gK+yp8@0+~> zk4x`(dZ2hFA?}M1t)2p5(~j`Q1R+k7^2Uwu$t@% zjx+a_IS%{vV1|)3OlT$n;Eyowz$-KImX!C=5y1yGFN&PW4Wq`HA?)58dUu`5M%90h zm#{rH1dYg(sX*1;N4#zOop-l?&E@RI4hZVEnoyN_)taeU_oW4%CYz}4&7R7s8|FAW zsv8!}>SIBEeyjEe?GM<1Z3D1Wgg;vWd3Db&Qe|`&2=NiY5zMQm=K}oEYT@!H1V}o= za3)+#?Nk%C!87HodtN8CD-i7QsaJ=1=N;jc+dt*k2xC};BQEt8iEyzvaSgwmHm_}6 z%@WGDhmBUD^%zP;FAMp2H;_uDFYy+dUWUAknaj9%`}GlgM9%bmz5mT+Hyjao(q!#e z5&P4PN%G8R*kemPv~(p2gt9r&<4x98xRe`0TElZ(_QN-CxuP>_e-JPfp8<9d=FJ6# zVyE;s`nyB~6Zu)dv4MOm$+)4Bbe!yoy&Cz+!5gj7HlS}avik7hm)v!nHV@^_~JS00J5(oOXI%u2{uYI+sn?Rz{+UCv^84G%8%cg z`m=~sK+Y6`_>708Qj1C(gT*&Wc|mCe{JF;BYuhb#&29K_6+SDEvl=&J{JnC@8R-ft z%Bs_X){qU&330+Oxfy&iWr6Rqv1NzX>$Q=@kE3+BA11WbA<&htz|hlr_9-mmwj&&u zYg@00ya+_(^IQXtgH_VqO@^{nJlT(uo<^v2ir(_Zl^r0XE?J~`79E(Pl!peF7PoCn zI}OvZeyoKL))g7nO0u5r z(k-inK7nHag^`lB4N^IfOZ=GA&a$QxyO8p4Y!!!u(5OpCf>TKrFv(^x$&yDu5pg$C z?OU)6t2UJ&u;FE%3r7tgv7{>TeYIrl*XpY@?60LQQN!O!c+8lh?wk1raq-i2Tq~xH zqo=8}<4PA>Hb}@t0#*)%Q(cI*+D~mYeuE;$u_X#Wn0jitnx*8C`oshz^B* zZFL7<7L^8SJIP1@SDVrD<5kTp$O3O3WU>BSV~o(z?hnKq%`_6%iY&7zijqy2>AKNY zyU;E=8=ur6UmO)Y=wj{H82(A4YR#b-0+nDqXa2b%CiR=ltg9p6XVaG8%JMUn9R2b# z!;?AV4`X9H!VjDh{dm-8(PQ3;;PosA$izq8PTMrA97Z5;DyLZr#wbUy?*+{gAF^#; zu8e-XJEh3bRyzlCMU6VSIlbBm!O`ZN5$xD;m2R|c$2HfNceG1H*_ei@P!7_Yk+}{c zWcC-MU>2SE&F*TDZRsSgKWIJjRSVv`2_xD=N@fw2OjgdgGf~yUw&s30F2(oHc`$^B zM(9I>j<1j55RwO_B^b$cW|xAGc`9*eY2?%lw!gB^$-&vGH?XB$4O%p(JydY-hL~i# zP+kQeDwZqj+t#hF98P*v7|@2(D1F$hpY=mWtdStbD~xDVjLG*pvQ69|Cvf%2I{U3L z8*E^Zs%{yF{)qD~#%j>=-s)67@j!xdXfjr-Mp@xP*0vp8hj9YTDr$FQzQD1sQ7cVN z;+myTp(U-p+wl~P?vR>wSlw@8OTiQV8Y}GOL_E4W&n7`Ii$`L{Q(UmSUaZ)rKk=^l zyZDZ$;iZRec8BfTX3w$Qly)gqnflef*^CBf(BxX+(3&~z!NT_6 z@JBH7%mZr0pb0_kzrs5>i~WOkkyjK=V-;{?h%q{gFei;OBwT7Rjux4j#?Oiya22oU zX1k=uZRc!yA4mmW-F`wtqa#cjw=JNVs=kOVArwzy0-k+|Z|l zZjq&VpE|*n+?YbQE}}~aGvRu@>Y(_2b-kB0YD^K*+d1X~D1HtXEYf%NzXdi(ASUpq zdM`~~Xo4O$?jqN|-g$wG(6+q{(Xgb@u9a44e~^8yt?`@TJ1Ecf%BP{I6v$eEJ0$wu zmJmK>(<(Bi8D!<5i9zz*?1Vr`Mc=%$^p}wAh~gg-M7+BfU}{898`-)Rw07T_NR%-W zG!V_p^B7XFv3RBfH6@EVTLUoB@UwypW^Itj(1?&xT?+&6QrKdSv;ys_;fGBbG4_E9 zZ&GV!9cIilscA_PU_}yOfA8 z3_@#zAG|a$YSHE9k_stN=UHoKK3#l?nc*=Kf8-A_&{%z~ZNO4yNCBN7qY~AfDIC#d zBAeTz-vEi4;|eMI);6MMe`TZ=hyn9^Sx%(a5k8g8efry`3(8ecXcS>Yu`k-1e*MZE zmgCx~^j>|M^*rlt2xdY!P4E&v=}|JQS*7w18*1qqIlOqXS6~IJ%u-&^sdneeSpF zthBuq8pH+u&$M9`PH_QrytHq2-0No%_L}+h-j;nzD|6p;7u|h2F5+@Y(rZDR88S3Mp`}9GF$d%=Z8O zPR?{WEQnl!=fk^uL*cY2TU89pnQDS_UO9ccN@-76lsu)cvwXcJo;vzCx)~cV6i#4P z5uKZNZr!xi0#sXbD|(>dUyTm`aMYT{^&K2%snazkAy}M}?YS(o&O#_L#^k+!5W`PM z>}d0vV7X)X+z;Kv9({UJKb*;GTaU(H7MWjkpkHe@xlr1hXD<)~SD6nJI0TrA^_7J< z+Kg&|2}_x+qv=(6lsS6}XM^{|;{wTr-f=ZE0|UoFeoo13M_EOg3&$f=%Wl`q9;sO1 zh(EEH@XxtJ?Wj(ge2SZ@S&qKPadyFmxiS}KeJsc;0dCvrt4o=&?urSNP-jn8u@9&% zHPwD-<83qrWL0ir0}o*W2(anf1^{q_XgpfY^280x=u9_jyNll&<#`-hV-M4V5 zgZu}yS*-4=VV)+zxzlSi9G#~ND^Ze7IK;m$-p=w!G+lb7Dk*%eCK0Y8MKJ58%3@6^ znv7cf@;4TMGs8kI*s=QjDnjHjOp8@iKrp}E0Vax2b&1E@>86*Vc67%K8j_{y7U6Qr zM?_)Qh-~G6;ULMwW$QCmwceKv5!u9)WdrwWTyt2?b0jv+GnWZ`@ani+Lklh<+ok*9 zCwKDM5Y^r(dXVX~NHrrYO0e*FHwE6%aZju=8>T|(LtMB#?zX?>nd;thx4O&(UMDgy z9=@ z@(sLY-scS|sHw0sj-F!qVeSZgf#A2!{n8IZhMAH9#p+va8u%oRB%dFCd+He&^Vne8 z89eN;b>z+4qNJ|9DyEdbNyA}8`1RhSHmJxg{^f^r*A1Zx`WLtyXzf&Y1g&b zuN^!Dw|za~W!kK*l`!-zMAxV)a9oaI9@epP4wWrt9Bh{cdY}$Bm>-MV_}KPKrDYY1 zp-pGsx^Zu#h8AW}xZ}X&C292h3%+(RygrYy2fg3JuBm$a-24>mX=!N1u|Cw4%u3e~ z_9f&i!C`iMEj2wj=!U{!Q8u^O%Pc49z)Nv0Zrh(D;)SxN|G07HIv?UP6~cxbB>|yd zT}OCi?@u@iw~+kwH`fxs1qdk{%54)v1{Qv~=OA{MV3(i2PwwwF;U$=s&k#q&sTZX; zva-oBs@kk%bl??y!}#dX4vxU$&R(*PW2%Fp+F+w=rpYfWk>li;OA|o$=@;S7DEpIbkj>KaSgFCUaDuIKU*c z=eE#8HazJ(hBa>8>~vtuU-SFBinj;_sbqKQ-bs_D;NV?C6Cy41ID-_sbph^8m zDF`DRv+^||JPoY*+}%obc+LlH#hL%~?Pt{bB}_O<;fAI2iIu|`Sb($d)@z`g7$P%! zYH_K_@p}5ho1)Z%i{-`-yf-!6#-28U&L-j+J?n)Pjs zKUpZ^Sk>V*Iybk(Y_58u0=31W$CR}84YxCc&->lJ3ndTl7nD6O2yyKB+;3U zNjLV=r8%i|z&+>oPS$r4^h=;3vZ}Z< zu(%V@&6C=ElMipEr^=3v;d{@;(ehMHW)51PJ|TqbG&kgF7UpEudv)+i4B(+mqd&+Y zhd-RFgaMaG0^sIU556eFQ?JUMqV<_^-TCRq1p}}FbUCuO;Xz@t5yaacFqRjVd;)}TmykF(C zb(2rmXBR&1^N7o1eI=9qoUaDhQAT8)yQ`CEqJypErys}!NIPSFwJ!A<*E-J?po@>M zx*sfQk&+gjOC<-AoUcVr9{I&S8~oh*>b{J~9WMI&ToIMlTFPAiPM+h4TzqahX~9A7 zUL!D+d@i7J_YgeSYaEPSlK{eV|U2ySr;1o{=mbQgd)LZyK3HmI;$(kN>fD zOo9E|;Y4l{O0;YSL$Q>Q@%u`e1w4}EhsNezdv!@z8Mk@fY|WC4txfEpbLuFf4ion} z%;7Fhx)hf)le?iows3l#dy$wvN+@B-u-ulQ_YAFrvr~tSc`4r6MueA>8o^LFG247* zhk#fVcN+2I7QdZ9z|AK`Zd2tWPdNu&+5s%Cf@rCH&cS_7(=j3hOF zz_Ht-v$NtxM%(5A&v=#@3WTE%#q@GsT zQ&}XxU-aUh)t~$AFd=2W(*6ne;f%&Nn5BU=ertE$uB?Wjv>^FdGxFNjum=yG95b^Z zO=~pnS()`j95?1!U{&w5IHwydY@>qPXahdk@#j2yC z%mJM|a|?pe2m)Uj5W1%OVX{njwZ3O=(2WO5f|7e}%5s*uH2o@abbS^R)Hu_f9ry6y z4_$zMHn@b+=!>g47p-UqGK^kZmb{FeK@S}c50~Y-9K}|!}1QEd|FKoAwWgs>~VLeSi~O=<8zROGt`rLgeo%|&~wEkvNHs0+k)tMrPzklVrML%c8=S` zEv`=@U^xqj%>o70QPh5e-JkSP6XXbZB=ZM+#lZZP=TuSwT#6NhJ)H>V{cm{{__k$0 zfdi@Id9u(Wv$MT9lJPML$iJdc`z!EmzRTP3E? zGbrhy-(BUtkKi9~h{&}ATamGUZMIr|5lN_+ni7HxUjvgo0t(uW@H5=2y6hp{pN5!?`SS%gVf zr}cz<97|z+#W$fI@U`bdJY05Lp(2;T3oR|l2rs^U`{tr6{M__wHyeVEey8j1^Y^Jj z&g4m$ALOlW@+B3}_;ypGvzB$jDOQRVFd>qnCs;lXMRE1$m?aK}!n%&$@b|wyUKtZ) zplh}{imBwVvIUey<~S(9A7QoEzF8T6RSnN`a^MhFBZ->OuBxgEr{#G*$U!4S${e1- zQOwQ5*p7-n+5-7FvUR>b~1CzqI1yt%Xq5 zeK@MoA*--vkb!&;p>3FhC@N#t-fc0}2&}ci{WPO|w504>B6c5tFsPGXY4HvkUZ5qh z>l+zkdC}C=M5kQ#17PvjZ{OG?<$Ak`JO?P#+@LPpr8lOSfBu+8Cw-npH9_PaOOFcz z^Kt{9C`yQGF1LRP>(5~*j$s!jA5!I-%TTO{#`;86zZ6vSpN!_>C|ZR6=Brtx(5A7$ z&SX!<*y0U~2p3QLQot2_yM+h*l4g;GM40S{VECAxpAR%`fN7T(~Lz`&E`4=SDD%fjw`b z$qgkWB@y6!ri%*;3UG^_N|;$mrr&tdYyh3G?Na_3ZD6P@f-`DDyi6KDpXr%<%SW`w zfdm#7{Dhujlbd9OToXV@kQ_A}^QV`x4z_F*{X={bW+sW2kRD(lV>wLG$It}@1=gJS z5;Vcq53jDZKlA|A-UrhjX4A@DF85l=8dI^KmnqN^@X1#`>ucUU#~mY71H+QnFheCy zI7kZS#eO5Ns>)s4SWpl=S*TR$e7e@k{@=@BD+zuC1}=CUHJ-~nA2#@+M6;<+Nz0wB zA9ZmFZc7R~)s5)G2ctGXuGHD@Mp>!`{quEFKhaKrsj^P!cJisOukS^z+by$&g+(R) z=;7hT?zkSsGW;8|)z}|c{|=8cHXZn{ZjkS4Mvp@ZjDjuJ7V^)NdODtw1&M7^(m>!< z5ZT`6f5@F3@%)1S+V^yT^#3(6!asff-i?9>X!hUDzzwheXI;O1n130#@TJ5jy)sI% zGA62Fr&-scmL2w$xvlPyt#iA>0ZrCpD#e`V!LP$F|IQOYV#QIvWUK*0akQ?}E1>Al zyGF4dU#v>|1~zRZD5LSmYcKb`y+RkdODG6IrAe(Y4xQFJ*4miEpj5OjT*Q1^cX@y0 z)V!V*!4H*QQ{x1b3jeqDqQs_0*5!?Sx@@H|Wq^6rq&MiuI!(*U6gG=2xG^<7Ki>~< zxX$IW;6DN|TLD9{iy>GZN7fxYoW?X*V>K^HzdyC@X@6f37u?;Se-iig(HRLMqyIt-EHBx)^~y*f zR30LX;g$8!?|GEFX1%3~axC)OH8a`P3U)Kqw!jf|)j7ckZVIi>A`o^`kXxnieh|aK zXwX&P*ZGx7HcId<#`R9mqtV|zucR6jKJ^8Zm9PV{?MpV8ARG+$OkTgB{>x+%4pDMr z{UK(2gI@vB`X}0z+^_gCGIlyCmON%)=%Pv|R_0AeJ- zG~clk;{B8yZLEXyv#Lz8O(uF3LJotz{)Gl2`&q5qea@YP^kdlwJ1cyIn zi3F78|Etgs6n}vILW9Y4dTQJyGpKJ3teCGSCtu2LbCqrZ)omj6TlOzIQ4@H>e#F=H ze^547QGZ#{jk~Lilli#nbx`l67eeGD%5o}KIHBBu!mi`VKNBAVM^*N;V+I|4Vq*EcAYi1!tKlFv;Xjt`SU zQF-(|G27hB^(A!D`g{SoC8Fr-Rx%?-b+d0(xv49AUOu?noRl+p|1Bh`RFRhc1p|XR z-CuMtQ9&^IUtiKJHI%$uoUu{+xOx&cPKHK3H>@OgdiJxE3-NW~E+~r3<_nuS|2Lp` z#)+@DWHhIix9ju?g34j7k}|7@@h8u*rVhh~5`WaCGCCvPZm%JA~+|wxGrNe{t;k5~{mo(x`@k75)BuGTle7pz;sWrqevidzGMsL-tST zn-idG^cZ<1?;pJM>p!1`y;x;Ysb!vGU&r5;zWkphg`R=NYP;WGjb1=U$?aS{XKfMs z)^)B|+wW2kYgJDN_v(hq6E+kIQ3?x;RS21%$zPC{nDl2}V-OHUzAY>LowphLsx<{8 zX8TPjK6by^tHZ;>UQ1vL;2#ftLul1Pvol}1Eh>HBQR|ro_$l^8+#+JuXYg}3XLY`f z$4`%++4{Cj*^+QULnG?>MdS)is%u@kd%wn?XkN>*3<#(Yz>upNX#s;$N3K}Q%`vex zt-#A+;gv0pcJ9Gaqkt+51FDsNY;d`x;p1~T5d4?sTWPQWnrf;f@C_6L=g3n#9xn~% zN+&5dI38AAx!>Q|jP0_HI4RjJR$cMexWU{zLLJ7@tBI(n;Jk=u)XFU`wh&Hw0=weG zV|h5aKqm`5?nMx|6<+r#DB_BqNUb&O16fZZV<#?OCS* zh8$PGsY)D6O-LH!eoD?W)0pSTwu$I?<<&rN3klD@iqjDF}3yg-?wcz zW&)aZKoU4H25Kcw;9>W-_{~4?3OPV8R|x&zH$~3-0y>4+iVGk4IY06_dU|Yek+0T` z_!jJZsvDd3cSMnma=@o-6?YT5zWFiC4+(7#K>2fmSgW`a{8azI{^22ce1ByBCJ@+d zWypj7_xX)fzYbpr3!mjwRmDJ#8X}&%4huZt|B#|!sntZdnLTeS=yIFrcBm6U1o2J)lbS|gR#`y1{^3P+bE*GgYyJ+~k^f!{8zoZl?CIhFWpuiL} z^S`0b2R+|8F4kCQdJM~7=jkX# ze^Zyf2*t9~UdAF-;58VXc%Jp<3=w!|xV@YsLORx&U!c%cq^!)9iDp3uNPC-mluIg#kKE+Go~ zlRE-9i~h!#yoy#(6!T3Bv&PMJz;E@}jYJuSR_Fv+EXnSf-eONy?2AOXy<{}MojYX) zy+jHGO0q7L$y4C@UMOR!A{+*dM6$J1e2DvoK6l*C)kSp+pd4>TP}IRoTevHv_ie+R zOqDi!Q>-h_Sx8S6V9*rLCtd+fv5gJOWZ2>f&iQ;vUnZ1kG|s7^S(J>cAjjk+5?_v) zl6l!JV*+rycu_04k{D$ar>4YcMK6FytY8qpku5YY`kAfG-=Hq79W=CBGYNJYhOAU# zjZW^tu>0SH!b2$ci?{ z!5uHm?5^R#xrf1J4Tk-5Im(quB(J*A;1$|hsS6I1=7XDWBA>~gmOEYqQcsTYlDbbb zr^q-Q%IX6X?>yc~$DWNc0ZiI)`rgSrClaw!F<$q7KxtHRWQLt}45ZUD%c&A@y-6d8 z2g&SfloJ|cLXj@k!T0+SoB7=g<6G4TD5q4E7Ki-)6Y1#G;xAbD?fxbf@9X8etAy|E zq8g$YqD!y!IDV9HdR_99lvb~LYM*H_{j>IPk|=b5^&F`d=;f;RvoGf%s~RzRg1{ov zqq7={xhqSvZww)-j;S77^h(+HDz^2#J1%D`@*1sJ6z*u==X-7Rt8E|mUZ)>WJd-@M zVgzB4u%VOhaS1Imj<5(it|p?3EVDgs2Rj{8q-Y=cOx)o2ZQi}8g9(GDcZ0tN`n_nE zxs-evDul`nr_0d<<8jb>(2S$QyVnU+_DLyK_wJf*dD1n|IwMG*5n7=(=1WcVPya{E z>r;h2%l}9<3Axh|rX4s?8`+=$P_gvj2r@_>|9;e<+co+jk6%W|v&ZJ44T|znC`5kC${c!YWtY!!>f1vILDmI}c-^~E3mwd(;8nG`=Avyn z@ni+0(sy4E+T3N)jaXKoLOaQ4N+3v9@8Oj0`sOZ@$rGeT!v<~gB0`XDajkZEIaB%?S1kc{Xg3vvVWDKr3O*e+sa#nl4>o< zgl)Q_Bsu|TZ6{7Ka`g7N+`xx|*o~ekPC_ws0lTcxRTWhy-<_pLb_)TiFU@&+J!A#Z zMos8#o?}A#rTcgDFn-ARRdyh=88{7sDkmOmDShN`mG4ALe6B*izWR6fMIrS^uhu!x zmw$~4MIF9qu92@gdObSju$dcuvc*l5%JLp}NJBC@FZ_t~g796KvBk>b7HPw>?8SZc z)gQoB#rS(5$wRR21rpvN5Y>>qrOxLStw(l%81kVWBGMaCKr6CxO9u97fKb>F6tsvh zD*E(4pUg!EYW|-+YESmgsva=8 zfia$r*H(tlIT-kcl3*_BwVz7`u5?l@YP5v)wT0%42<=qUwQ69*7$IGCW@TZSR7yr(i~;~*w;$DLR9=+ZE+T>5));Wk>z`31*W&`Wcg zNpWAizzh`^{-nTT9?G+^kVyG^PL|2 z^4^2(z@;qzEm;UAec$|Jn(Gml)cA%UmS)d9|Gzk8i|3C4;jcda|Dh>109>6N9G!17 z4JG5$>9%^0E~BU{@hHwS&B^8-ukMR1PAflzj@A&|Yz;pppLnZzT_aK&+ac9?b)oNHL*izZG^_IIXt9GN{-7eERVhJ{ih+NRB8| z>k1TRxaB0-0!kU!^@2oqcKY@;yRT$^jOD39G=YO6FSU`1`6}Q2Z&r!{v+q(ZMnQ+a zGrhP~Wvb5|?=64vL6E=V#*JL3?jczSbrw^^L5q4%e(4&hlLadr3QUb;Y8xW zjO1Fc+fH52&r8j$t4laKI+{f`^1v;Y3i}u2^jJ`NBHXC+6zBE*_FVGgQr_um0l$~h z7DpeI>w7=UI&L`R_=<$N9UwE1u$c}dsXb$^vol+d(-5tb)c~R)N8^9>4+-<|h7F7x z0;ug>kZb@W$H|dZ#v|(gx&Oy`QG{3wWl(-T_bkEk=Q7%6{Uf=FFKboZibLR0<>&YQ5 zGl|Hh+v@M&ZPj{~$%y{X+Q|=EOW?CG-|D_cP~k(viff3xV;_OsFva=1M+s8f2q?I0%zW z?wF3Sy-G0`hx1bs^+5+VBbpF*8e7}pts9NtXoz&rM_>=eqR@lA6GY+=?FxG1i22#hvCJ_hx==cd-Zb|^#t0Sp}=!3^NvzmBM{v^ zpKy2-S5@_aQ)Dm=Z{~G0>l2-XT15k6o4UVnJi+l##m}ANTFuXf0DiRg6$z!~eSMNo zdkQ~-ul+$~J6+-PP)J@_33!&QP>&)@?$;X6zem6joB%m)_O#Z&NAWoE*`M3|v5Y)_ zg}36BG*|fVqz@c0xRq?V))zCB#+URD)%R@idD0Gz%3JUapB|~wi4p!a`KgTg)iBZf zJ9JkqO&+Ygq1oh`FO+@NS$?@;eN`a~H2hEZb_{@Xhdqhl`pIiLLCWwxy!#Zg{FEvb zfNZlf^8ToH9T~89-pn^Yr~%j9)&Dk9`rsZdsK=(a-%4vuo}}5P^Jb+FB;QobGVOuf zMg#}8^4yCb=F-oS{n(bW3%+kT_k3ED;+Ybebj3ZD(W_o4R7Jo z{w0N!$|Kqd?Zb_Srq5HEPY>p{Hrf(5)_eO*-#)#EP0iPUDjSaK^=f*dteZ!MLz~?!*PShr?0#sd4tFZ(GKK;yHzaoKvhg)1$qAO6x;!*b`$P3t}jZaOn z_oM!6Lk1iv_v9;x_!Bkkqm2T>gX=hSKNc`PEGjfl`C6HH@{EUAIgo-y`)tgS$Ipt= zx>6h_N@z*--<6*b;-wl1!Z3>L9zn&0Hc1*)qv%EBT_8Ju^ybt zJ-)_<#r(zK#)wR`%E-)dad9C<<;6c$&)9r#3qsNHWl;-&+K|GenL6nxZV{8q*?j_CfbPEEx^IZLHFt0Ge>^r zarkN1mF0xK=ILo)ezH9t$&6>NeiW3Zu)JQ>kf8i{(sUeY%Uu@<&^3$)3cRo8+53cD zb9_;a@_72j>C%I5>kjY~MSTvz+_ZQa=DWtvH92cTWZd}2?+8f3bB#w4z^U*H{CKxd zO*vxq+0W1Kt3*0p*T6to8Q`kKqgV+E4xXuZparADPAin+cPaO8Q?tC6iE`m1vj z)BwF$hwxm-BnEA#M)wwo^Tm|nG~ri-dKlt4PCjh^^>&=K4)8AoZhD?`c(VL*W~3Ua z5&f?}uEDPj(D?j3&#K&(UU9>>{+iHu;^xsi*W)H9fEitH80Swr&}GXU_7!PpXbh=I z{_7bL^CO;Xd%v_fRiVPI%Ah8*t*uQwjGYKHf;j-z0It{d&4?h#m0 zsasoH^QIHc|4EfbUc>teGED^3+mSZbmOUn$<5%)c13%80be&Hbl7yWUy=QRHj}v)w z(}oYTuJqYNJ@oU|w_lFQ2IN;slckbHrW`t7L(Zb`hY8JykKWkn`*5*rzmHHXQSaqB zZe*F)3AMgnbdsep;dgsDiK4JILxh269|sYB1aT zmz?~TIcyxgFmA&ts)|7rW@b`Hc>mG#+-^vJLOh zJ!@2}-un}r-Q<%{@6&YOEOKR)*9x>>m)v)Twv(*}++H1F576*Bvu8 z0wOg!+6Jw4|EsR+fNCmfqqL>Tf&_&~FVZAJDAGlWNKXV=ih#6GBmxnnOEt8mgP<4$ zktQxRh=4!RHDx>rtqEnb*U;U~;X|-baQ08i%a!!GThvIHE|e0pJ`t|` zicT#lY!^im)?01THgBWjxIBy^!0o$j2Z9R+t^1m5F!ZReg?3KGoZC)P_S+E-wIHG{ zdOYo1a^%O{QZ*L>AdyN~K3=>;{PKcWWlom(i6ul8!hm1GajtCD^!ThY*Usdbr{k)% z=a(7s&?*6!F~_d7F*c&O&vYtj-Jr33&=8y8%e+8qVI^%gByxksAyODP>LEA@*;QrX z5csls!qtUyc24B#sPP*UWxP1EkGE(&PLSQe(3hF(8si5LX^LCC>7~)u5JM%3xOd@qUGn<~Q{)!I3Td-Mm<-*5`bUl_|Z9(2@q!zq&tL&%q7a!md4dGYzG zd;iwW$<9lw+*r2(ZXg`0i)P6FZ!Bg3RM?V8BwVt$itFm*=52^|cId>vddm@v5==RM zd%$JR!TOVCK}l(3HidHn4Z;WBtBbtYqGMzv?Z&a~``hK1nNJd!flQKN`fhl-(}6O< zo|AB3oE{L&NPLcA*U;|-tv%0{9mau9zpYD;EjC0r*o<0Rc{EPjPWlVJq}SmIeRB1+ zX&B=fR%28pztoj0F|9S2)wv~PiOvTP9V`TG!t$CdqoTFue{*ug&Ytk+yPbE~_Usi6 zNiNMGMQ^G_0+?jebU;)@?(g#wZ~u{Di4{jJ{?QW?>L+R5!|^RR!(wiPO>Z(e*9MZ;w)W?wmeTgth{w z6CZ_zE%#_Ne^z`@>}<`pWa6wTfvSprk+pCm^GK>MnH-t9!3Ge93t4c$84uUWU4i}# zVH?Y-E!%m?uTc>HmGD(otEz*5Xj-*nQKW9jM|w)^M3}ng!6m$Md27B(h%_l0^-8J63%!8!P{eKLk2UF+J8neWtRVULOZZ`V)Uos)o7By}uY zA5cZX5mKSDX6j3ip0!;J{n#34(PTc{JxZxUx#oF^s*RFdG7%Gav!CA!&^bRYdNZ^% ziCo+s5Lph~%0||PLX4j?>|J`KF$1;>XJFyH>S*?gT_~W}1j=eG6^ifbPaQAh@~}>y zEU-gIkRIL&IoYeIGu=!#maimV3$>cyy1H8EqsP=S6mY+rk#PnruGgTj<`ZDiP?-~m zVbRxD_2!<5Qd7!bVp7JMw+;;8&Id5C{#qf6T4kQ2Q4ka5Ep5N!8z8WaAxcRrL%FAF z({iGO0tIz}^IM;fJ5RDz!!$`HZ2}j-w#OebK%Wl#TLqx`XKb71pdC+-EH9%Y54nkmn zUFUnSs|!InCN;iD`trUT08j0g1U9VVfWPE8Jsbc0DBorzN&{THPk*M@%Mo}hW~|&w zU1(z-!rz?Iq};V?L=IB~#%~(NdhD3I8CR6Otbs&U?qWhQK->dvC;!i{#eoOh9S*|j z!QmW^5nsh=0L8(5eZISnzvRcbkiu&J8gO`yLEKa>^otKqG?(DLDxaEixp<_f{!6?vvH zda#@^rt&&A_e2HDo5sG>fM+?{bDX>rfIUCei2^1G`a#M%~Fe6^)Kx}pYAtmLAfj;rgX+ghH!3MY% zb~Je;B&(%oS9N((=w5Bdj3x2>WDhumx z%FP##ha|RTlx|!G!)a~GcoS|r&DpCXBnhw=LSCo8C)4Iio!gsQua+v>E>U%pJ7?~| zW}j?Pzu6y9tEP;8VuJWIjl&r8Az-COC&&B|ZS;oNFXiqazMuv0TVWo_$vKJdUgC`D z!6nh;3Z^ffr*=gu(iHEKF2q!WD_rZx9@d~Lk&>V~F3tD73|Ipq^TRdJH4jrtF%U4P zPsex4e|!O0RZb-zJs%Ct*b;0#e#Mc-o*&Cq#5Phy36qvB#P_=_X66kwJ&{@U zb**!i<1cH`(P62|rcaCqkz!|VIX1jYnGh6S+w^Hc%B*Q#N%N;$YDWd5c6yzseLD>i zbM|@UO>XPJ`kl%e2+ECiiXjx(gwdB)=;j$GcO>Ry^kKd}mdtgJspjU?eBWtBlRL5O z$sl#hJQA-@e#1WBOEAoGlJU^O8kl z0?>7#t%a6c8^6m~Wo^$S&?+#`kf)^d0PH&efD0O%Ccj09f%uPHs-QBHF*4lz=2XT0 zM4zJc4H)08lA6^ZCm9;N-*d6VUl4Gm;~_$WC9-ECEz>kkN;-=t?u%aPshP7`5PR15 zs7Op>KlK>@-BT>{4wNs=3dNN&MbGGER66c7y*2LSla>m6PiW+8JFoM7eixJC70b6^ z$<-H~1?+>v665TE`8b&H^ywMXH~gkJxoa)=fBVB~$j|a9%llu6FldjQyyR)kX9bTV zxd_b}(B2LPu!VaVi+G$);t+d*-Ti;H%?|JRZF<9~I~^2sSnwE!bFIM@My!{WE5> zV|(e)DaQ-zpZ)^KLv>5Ql3c3{UcjjI_32Sev4nhDSy>q}8CfEm2R(hz74%ZT%l|DVml{%2N0a!;$Zf|Hz+ETM<84yn@uTU* z($!P~yY|r=pg?H7W(KO~-pp}ZCwLUlu6 Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure\n state + +'' Vector Map +vector_map -left-> behavior_planner : vector map + +'' Autoware API <-> Infrastructure +autoware_api -up-> fms : lock\n request +fms -down-> autoware_api : right-of-way\n state + +autoware_api -up-> automatic_shutter : approach\n notification +automatic_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> manual_shutter : open/close\n command +manual_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> remote_controllable_traffic_light : light change\n command +remote_controllable_traffic_light -down-> autoware_api : light\n state + +autoware_api -up-> warning_light : activation\n command +warning_light -down-> autoware_api : warning light\n state + +' Layout +'' Infrastructure +fms -[hidden]right-> automatic_shutter +automatic_shutter -[hidden]right-> manual_shutter +manual_shutter -[hidden]right-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]right-> warning_light + +@enduml +``` + +Planner and each infrastructure communicate with each other using common abstracted messages. + +- Special handling for each infrastructure is not scalable. The interface is defined as an Autoware API. +- The requirements for each infrastructure are slightly different, but will be handled flexibly. + +FMS: Intersection coordination when multiple vehicles are in operation and the relevant lane is occupied + +- Automatic shutter: Open the shutter when approaching/close it when leaving +- Manual shutter: Have the driver open and close the shutter. +- Remote control signal: Have the driver change the signal status to match the direction of travel. +- Warning light: Activate the warning light + +Support different communication methods for different infrastructures + +- HTTP +- Bluetooth +- ZigBee + +Have different meta-information for each geographic location + +- Associated lane ID +- Hardware ID +- Communication method + +FMS: Fleet Management System + +```plantuml +@startuml +!theme cerulean-outline + +' Component +node "Autoware ECU" as autoware_ecu { +component "Behavior Planner" as behavior_planner +component "Autoware API" as autoware_api +component "Web.Auto Agent" as web_auto_agent +note right of web_auto_agent : (fms_bridge) +database "Vector Map" as vector_map + +package "Infrastructure Bridges" as infrastructure_bridges { + component "Automatic Shutter Bridge" as automatic_shutter_bridge + component "Manual Shutter Bridge" as manual_shutter_bridge + component "Remove Controllable Traffic Light Bridge" as remote_controllable_traffic_light_bridge + component "Warning Light Bridge" as warning_light_bridge +} +} + +cloud "FMS" as fms { + component "FMS Gateway" as fms_gateway + + component "Intersection Arbitrator" as intersection_arbitrator + database "Intersection Lock Table" as intersection_lock_table + + component "Vector Map Builder" as vector_map_builder + database "Vector Map Database" as vector_map_database +} + +package "Infrastructures" as infrastructures { + node "Automatic Shutter" as automatic_shutter + node "Manual Shutter" as manual_shutter + node "Remote Controllable Traffic Light" as remote_controllable_traffic_light + node "Warning Light" as warning_light +} + +' Relationship +'' Behavior Planner <-> Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Web.Auto +autoware_api -up-> web_auto_agent : infrastructure\n command +web_auto_agent -down-> autoware_api : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Infrastructure Bridge +autoware_api -right-> infrastructure_bridges : infrastructure\n command +infrastructure_bridges -left-> autoware_api : infrastructure state\n as virtual traffic light + +'' Infrastructure Bridge <-> Infrastructure +automatic_shutter_bridge -right-> automatic_shutter : approach notification +automatic_shutter -left-> automatic_shutter_bridge : shutter state + +manual_shutter_bridge -right-> manual_shutter : open/close command +manual_shutter -left-> manual_shutter_bridge : shutter state + +remote_controllable_traffic_light_bridge -right-> remote_controllable_traffic_light : light change command +remote_controllable_traffic_light -left-> remote_controllable_traffic_light_bridge : light state + +warning_light_bridge -right-> warning_light : activation command +warning_light -left-> warning_light_bridge : warning light state + +'' Web.Auto +web_auto_agent -up-> fms_gateway : infrastructure\n command +fms_gateway -down-> web_auto_agent : infrastructure state\n as virtual traffic light + +fms_gateway -up-> intersection_arbitrator : lock request +intersection_arbitrator -down-> fms_gateway : right-of-way state + +intersection_arbitrator -up-> intersection_lock_table : lock request +intersection_lock_table -down-> intersection_arbitrator : lock result + +vector_map_builder -down-> vector_map_database : create vector map +vector_map_database -left-> intersection_arbitrator : vector map + +'' Vector Map +vector_map_database .down.> web_auto_agent : vector map +web_auto_agent -left-> vector_map : vector map +vector_map -down-> behavior_planner : vector map + +' Layout +'' Infrastructure Bridge +automatic_shutter_bridge -[hidden]down-> manual_shutter_bridge +manual_shutter_bridge -[hidden]down-> remote_controllable_traffic_light_bridge +remote_controllable_traffic_light_bridge -[hidden]down-> warning_light_bridge + +'' Infrastructure +automatic_shutter -[hidden]down-> manual_shutter +manual_shutter -[hidden]down-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]down-> warning_light + +@enduml +``` + +#### Module Parameters + +| Parameter | Type | Description | +| ------------------------------- | ------ | --------------------------------------------------------------------- | +| `max_delay_sec` | double | [s] maximum allowed delay for command | +| `near_line_distance` | double | [m] threshold distance to stop line to check ego stop. | +| `dead_line_margin` | double | [m] threshold distance that this module continue to insert stop line. | +| `check_timeout_after_stop_line` | bool | [-] check timeout to stop when linkage is disconnected | + +#### Flowchart + +```plantuml +@startuml +!theme cerulean-outline +start + +if (before start line?) then (yes) + stop +else (no) +endif + +if (after end line?) then (yes) + stop +else (no) +endif + +:send command to infrastructure; + +if (no stop line?) then (yes) + stop +else (no) +endif + +:check infrastructure state; + +if (timeout or not received?) then (yes) + :stop at stop line; + stop +else (no) +endif + +if (no right of way?) then (yes) + :stop at stop line; +else (no) +endif + +if (finalization is requested?) then (yes) + if (not finalized?) then (yes) + :stop at end line; + else (no) + endif +else (no) +endif + +stop +@enduml +``` + +##### Known Limits + +- tbd. From 4f4644f1ff02e6a22fef45a6555a6e3d5b9d5761 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 08:29:37 +0900 Subject: [PATCH 017/223] feat(surround_obstacle_checker): separate surround_obstacle_checker from hierarchical planning flow (#830) * fix(surroud_obstacle_checker): use alias Signed-off-by: satoshi-ota * feat(surround_obstacle_checker): use velocity limit Signed-off-by: satoshi-ota * chore(surround_obstacle_checker): rename publisher, subscriber and callback functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use parameter struct Signed-off-by: satoshi-ota * fix(surround_obstacle_checker): use alias Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup member functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup polygon handling Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use marker helper Signed-off-by: satoshi-ota * feat(planning_launch): separate surround_obstacle_checker from hierarchical motion planning flow Signed-off-by: satoshi-ota --- .../motion_planning/motion_planning.launch.py | 35 +- .../motion_planning.launch.xml | 13 +- .../surround_obstacle_checker/CMakeLists.txt | 2 +- .../surround_obstacle_checker.param.yaml | 1 + .../debug_marker.hpp | 20 +- .../surround_obstacle_checker/node.hpp | 136 ++-- .../surround_obstacle_checker.launch.xml | 12 +- .../surround_obstacle_checker/package.xml | 1 + .../src/debug_marker.cpp | 105 +-- .../surround_obstacle_checker/src/node.cpp | 632 +++++++++--------- 10 files changed, 433 insertions(+), 524 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index e8661322215fe..89d04bc5b3a00 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -92,20 +92,23 @@ def launch_setup(context, *args, **kwargs): surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] surround_obstacle_checker_component = ComposableNode( package="surround_obstacle_checker", - plugin="SurroundObstacleCheckerNode", + plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", name="surround_obstacle_checker", namespace="", remappings=[ ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/trajectory", "surround_obstacle_checker/trajectory"), + ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), + ( + "~/output/velocity_limit_clear_command", + "/planning/scenario_planning/clear_velocity_limit", + ), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ surround_obstacle_checker_param, @@ -114,22 +117,6 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # relay - relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="skip_surround_obstacle_check_relay", - namespace="", - parameters=[ - { - "input_topic": "obstacle_avoidance_planner/trajectory", - "output_topic": "surround_obstacle_checker/trajectory", - "type": "autoware_auto_planning_msgs/msg/Trajectory", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("tier4_planning_launch"), @@ -173,7 +160,7 @@ def launch_setup(context, *args, **kwargs): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "surround_obstacle_checker/trajectory"), + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ common_param, @@ -202,13 +189,7 @@ def launch_setup(context, *args, **kwargs): condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) - relay_loader = LoadComposableNodes( - composable_node_descriptions=[relay_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - - group = GroupAction([container, surround_obstacle_checker_loader, relay_loader]) + group = GroupAction([container, surround_obstacle_checker_loader]) return [group] diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 0fa8707e4fda9..3d195185d9bd6 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -19,22 +19,11 @@ - - - - - - - - - - - @@ -45,7 +34,7 @@ - + diff --git a/planning/surround_obstacle_checker/CMakeLists.txt b/planning/surround_obstacle_checker/CMakeLists.txt index b40b7c22c98ca..ab61405c9f335 100644 --- a/planning/surround_obstacle_checker/CMakeLists.txt +++ b/planning/surround_obstacle_checker/CMakeLists.txt @@ -18,7 +18,7 @@ target_link_libraries(${PROJECT_NAME} ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "SurroundObstacleCheckerNode" + PLUGIN "surround_obstacle_checker::SurroundObstacleCheckerNode" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml index b57d7506b0574..afcc532b7c604 100644 --- a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml +++ b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml @@ -9,3 +9,4 @@ # ego stop state stop_state_ego_speed: 0.1 #[m/s] + stop_state_entry_duration_time: 0.1 #[s] diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp index d076e26afc009..2891ac63c5df4 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp @@ -25,8 +25,18 @@ #include #include +namespace surround_obstacle_checker +{ + +using tier4_planning_msgs::msg::StopFactor; +using tier4_planning_msgs::msg::StopReason; +using tier4_planning_msgs::msg::StopReasonArray; +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + enum class PoseType : int8_t { NoStart = 0 }; enum class PointType : int8_t { NoStart = 0 }; + class SurroundObstacleCheckerDebugNode { public: @@ -38,16 +48,16 @@ class SurroundObstacleCheckerDebugNode void publish(); private: - rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr stop_reason_pub_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Publisher::SharedPtr stop_reason_pub_; double base_link2front_; - visualization_msgs::msg::MarkerArray makeVisualizationMarker(); - tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray(); + MarkerArray makeVisualizationMarker(); + StopReasonArray makeStopReasonArray(); std::shared_ptr stop_obstacle_point_ptr_; std::shared_ptr stop_pose_ptr_; rclcpp::Clock::SharedPtr clock_; }; - +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__DEBUG_MARKER_HPP_ diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp index 7e4bbb9ffd15a..e437787c234ac 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp @@ -16,9 +16,9 @@ #define SURROUND_OBSTACLE_CHECKER__NODE_HPP_ #include "surround_obstacle_checker/debug_marker.hpp" -#include "tier4_autoware_utils/trajectory/tmp_conversion.hpp" #include +#include #include #include @@ -27,30 +27,31 @@ #include #include #include +#include +#include #include -#include -#include -#include -#include -#include -#include - -#include #include #include #include #include #include +#include #include -using Point2d = boost::geometry::model::d2::point_xy; -using Polygon2d = - boost::geometry::model::polygon; // counter-clockwise, open +namespace surround_obstacle_checker +{ + +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; -using TrajectoryPoints = std::vector; +using tier4_planning_msgs::msg::VelocityLimit; +using tier4_planning_msgs::msg::VelocityLimitClearCommand; +using vehicle_info_util::VehicleInfo; + +using Obstacle = std::pair; enum class State { PASS, STOP }; @@ -59,70 +60,73 @@ class SurroundObstacleCheckerNode : public rclcpp::Node public: explicit SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options); + struct NodeParam + { + bool use_pointcloud; + bool use_dynamic_object; + bool is_surround_obstacle; + // For preventing chattering, + // surround_check_recover_distance_ must be bigger than surround_check_distance_ + double surround_check_recover_distance; + double surround_check_distance; + double state_clear_time; + double stop_state_ego_speed; + double stop_state_entry_duration_time; + }; + private: - void pathCallback(const Trajectory::ConstSharedPtr input_msg); - void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg); - void dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg); - void currentVelocityCallback(const nav_msgs::msg::Odometry::ConstSharedPtr input_msg); - void insertStopVelocity(const size_t closest_idx, TrajectoryPoints * traj); - bool convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose); - bool getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose); - void getNearestObstacle(double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - bool isObstacleFound(const double min_dist_to_obj); + void onTimer(); + + void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + + void onDynamicObjects(const PredictedObjects::ConstSharedPtr msg); + + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + + boost::optional getNearestObstacle() const; + + boost::optional getNearestObstacleByPointCloud() const; + + boost::optional getNearestObstacleByDynamicObject() const; + + boost::optional getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const; + bool isStopRequired(const bool is_obstacle_found, const bool is_stopped); - size_t getClosestIdx(const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose); - bool checkStop(const TrajectoryPoint & closest_point); - Polygon2d createSelfPolygon(); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint); - diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose); - std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose); - - /* - * ROS - */ + + bool isVehicleStopped(); + + // ros + mutable tf2_ros::Buffer tf_buffer_{get_clock()}; + mutable tf2_ros::TransformListener tf_listener_{tf_buffer_}; + rclcpp::TimerBase::SharedPtr timer_; + // publisher and subscriber - rclcpp::Subscription::SharedPtr path_sub_; - rclcpp::Subscription::SharedPtr pointcloud_sub_; - rclcpp::Subscription::SharedPtr - dynamic_object_sub_; - rclcpp::Subscription::SharedPtr current_velocity_sub_; - rclcpp::Publisher::SharedPtr path_pub_; - rclcpp::Publisher::SharedPtr stop_reason_diag_pub_; + rclcpp::Subscription::SharedPtr sub_pointcloud_; + rclcpp::Subscription::SharedPtr sub_dynamic_objects_; + rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Publisher::SharedPtr pub_stop_reason_; + rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + + // debug std::shared_ptr debug_ptr_; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; // parameter - nav_msgs::msg::Odometry::ConstSharedPtr current_velocity_ptr_; - sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; - autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr object_ptr_; + NodeParam node_param_; vehicle_info_util::VehicleInfo vehicle_info_; - Polygon2d self_poly_; - bool use_pointcloud_; - bool use_dynamic_object_; - double surround_check_distance_; - // For preventing chattering, - // surround_check_recover_distance_ must be bigger than surround_check_distance_ - double surround_check_recover_distance_; - double state_clear_time_; - double stop_state_ego_speed_; - bool is_surround_obstacle_; + + // data + nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr_; + sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; + PredictedObjects::ConstSharedPtr object_ptr_; // State Machine State state_ = State::PASS; std::shared_ptr last_obstacle_found_time_; + std::shared_ptr last_running_time_; }; +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__NODE_HPP_ diff --git a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml index a0dd4b307f495..53f26a05c87c3 100644 --- a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml +++ b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml @@ -1,24 +1,20 @@ - - - - - + + - - + + - diff --git a/planning/surround_obstacle_checker/package.xml b/planning/surround_obstacle_checker/package.xml index 5dfed9ddb19a7..b74ad2ccec25b 100644 --- a/planning/surround_obstacle_checker/package.xml +++ b/planning/surround_obstacle_checker/package.xml @@ -14,6 +14,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_auto_tf2 diagnostic_msgs eigen libpcl-all-dev diff --git a/planning/surround_obstacle_checker/src/debug_marker.cpp b/planning/surround_obstacle_checker/src/debug_marker.cpp index 64dbc2f349f14..8abdb67e8b2c6 100644 --- a/planning/surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/surround_obstacle_checker/src/debug_marker.cpp @@ -14,6 +14,7 @@ #include "surround_obstacle_checker/debug_marker.hpp" +#include #ifdef ROS_DISTRO_GALACTIC #include #else @@ -22,13 +23,23 @@ #include +namespace surround_obstacle_checker +{ + +using tier4_autoware_utils::appendMarkerArray; +using tier4_autoware_utils::calcOffsetPose; +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerColor; +using tier4_autoware_utils::createMarkerScale; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createStopVirtualWallMarker; + SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const double base_link2front, const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) : base_link2front_(base_link2front), clock_(clock) { debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); - stop_reason_pub_ = - node.create_publisher("~/output/stop_reasons", 1); + stop_reason_pub_ = node.create_publisher("~/output/stop_reasons", 1); } bool SurroundObstacleCheckerDebugNode::pushPose( @@ -70,87 +81,25 @@ void SurroundObstacleCheckerDebugNode::publish() stop_obstacle_point_ptr_ = nullptr; } -visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() +MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() { - visualization_msgs::msg::MarkerArray msg; + MarkerArray msg; rclcpp::Time current_time = this->clock_->now(); - tf2::Transform tf_base_link2front( - tf2::Quaternion(0.0, 0.0, 0.0, 1.0), tf2::Vector3(base_link2front_, 0.0, 0.0)); // visualize stop line if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "virtual_wall/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::CUBE; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 1.0; - marker.scale.x = 0.1; - marker.scale.y = 5.0; - marker.scale.z = 2.0; - marker.color.a = 0.5; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 0.0; - marker.color.b = 0.0; - msg.markers.push_back(marker); - } - - // visualize stop reason - if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "factor_text/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 2.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; - marker.text = "surround obstacle"; - msg.markers.push_back(marker); + const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0); + const auto markers = createStopVirtualWallMarker(p, "surround obstacle", current_time, 0); + appendMarkerArray(markers, &msg); } // visualize surround object if (stop_obstacle_point_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "no_start_obstacle_text"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; + auto marker = createDefaultMarker( + "map", current_time, "no_start_obstacle_text", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); marker.pose.position = *stop_obstacle_point_ptr_; marker.pose.position.z += 2.0; // add half of the heights of obj roughly - marker.pose.orientation.x = 0.0; - marker.pose.orientation.y = 0.0; - marker.pose.orientation.z = 0.0; - marker.pose.orientation.w = 1.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; marker.text = "!"; msg.markers.push_back(marker); } @@ -158,7 +107,7 @@ visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisua return msg; } -tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() +StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() { // create header std_msgs::msg::Header header; @@ -166,9 +115,9 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make header.stamp = this->clock_->now(); // create stop reason stamped - tier4_planning_msgs::msg::StopReason stop_reason_msg; - stop_reason_msg.reason = tier4_planning_msgs::msg::StopReason::SURROUND_OBSTACLE_CHECK; - tier4_planning_msgs::msg::StopFactor stop_factor; + StopReason stop_reason_msg; + stop_reason_msg.reason = StopReason::SURROUND_OBSTACLE_CHECK; + StopFactor stop_factor; if (stop_pose_ptr_ != nullptr) { stop_factor.stop_pose = *stop_pose_ptr_; @@ -179,8 +128,10 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make } // create stop reason array - tier4_planning_msgs::msg::StopReasonArray stop_reason_array; + StopReasonArray stop_reason_array; stop_reason_array.header = header; stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); return stop_reason_array; } + +} // namespace surround_obstacle_checker diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 09fe48f35b571..9e1fc6711bd3f 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -14,9 +14,17 @@ #include "surround_obstacle_checker/node.hpp" +#include + +#include +#include +#include +#include +#include +#include + #include #include -#include #include #ifdef ROS_DISTRO_GALACTIC #include @@ -34,313 +42,381 @@ #include #include +namespace surround_obstacle_checker +{ + +namespace bg = boost::geometry; +using Point2d = bg::model::d2::point_xy; +using Polygon2d = bg::model::polygon; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::pose2transform; + +namespace +{ +std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose) +{ + const std::string json_dumps_pose = + (boost::format( + R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % + pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % + pose.orientation.y % pose.orientation.z) + .str(); + return json_dumps_pose; +} + +diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( + const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) +{ + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; + no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + no_start_reason_diag.name = "no_start_reason"; + no_start_reason_diag.message = no_start_reason; + no_start_reason_diag_kv.key = "no_start_pose"; + no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); + no_start_reason_diag.values.push_back(no_start_reason_diag_kv); + return no_start_reason_diag; +} + +geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const double z) +{ + geometry_msgs::msg::Point32 p; + p.x = x; + p.y = y; + p.z = z; + return p; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) +{ + geometry_msgs::msg::Polygon transformed_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(pose); + tf2::doTransform(footprint, transformed_polygon, geometry_tf); + + Polygon2d object_polygon; + for (const auto & p : transformed_polygon.points) { + object_polygon.outer().push_back(Point2d(p.x, p.y)); + } + + bg::correct(object_polygon); + + return object_polygon; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +{ + const double & length_m = size.x / 2.0; + const double & width_m = size.y / 2.0; + + geometry_msgs::msg::Polygon polygon{}; + + polygon.points.push_back(createPoint32(length_m, -width_m, 0.0)); + polygon.points.push_back(createPoint32(length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, -width_m, 0.0)); + + return createObjPolygon(pose, polygon); +} + +Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) +{ + const double & front_m = vehicle_info.max_longitudinal_offset_m; + const double & width_m = vehicle_info.min_lateral_offset_m; + const double & rear_m = vehicle_info.min_longitudinal_offset_m; + + Polygon2d ego_polygon; + + ego_polygon.outer().push_back(Point2d(front_m, -width_m)); + ego_polygon.outer().push_back(Point2d(front_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + + bg::correct(ego_polygon); + + return ego_polygon; +} +} // namespace + SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options) -: Node("surround_obstacle_checker_node", node_options), - tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) +: Node("surround_obstacle_checker_node", node_options) { // Parameters - use_pointcloud_ = this->declare_parameter("use_pointcloud", true); - use_dynamic_object_ = this->declare_parameter("use_dynamic_object", true); - surround_check_distance_ = this->declare_parameter("surround_check_distance", 2.0); - surround_check_recover_distance_ = - this->declare_parameter("surround_check_recover_distance", 2.5); - state_clear_time_ = this->declare_parameter("state_clear_time", 2.0); - stop_state_ego_speed_ = this->declare_parameter("stop_state_ego_speed", 0.1); - debug_ptr_ = std::make_shared( - vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); - self_poly_ = createSelfPolygon(); + { + auto & p = node_param_; + p.use_pointcloud = this->declare_parameter("use_pointcloud", true); + p.use_dynamic_object = this->declare_parameter("use_dynamic_object", true); + p.surround_check_distance = this->declare_parameter("surround_check_distance", 2.0); + p.surround_check_recover_distance = + this->declare_parameter("surround_check_recover_distance", 2.5); + p.state_clear_time = this->declare_parameter("state_clear_time", 2.0); + p.stop_state_ego_speed = this->declare_parameter("stop_state_ego_speed", 0.1); + p.stop_state_entry_duration_time = + this->declare_parameter("stop_state_entry_duration_time", 0.1); + } + + vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); // Publishers - path_pub_ = - this->create_publisher("~/output/trajectory", 1); - stop_reason_diag_pub_ = + pub_stop_reason_ = this->create_publisher("~/output/no_start_reason", 1); + pub_clear_velocity_limit_ = + this->create_publisher("~/output/velocity_limit_clear_command", 1); + pub_velocity_limit_ = this->create_publisher("~/output/max_velocity", 1); - // Subscriber - path_sub_ = this->create_subscription( - "~/input/trajectory", 1, - std::bind(&SurroundObstacleCheckerNode::pathCallback, this, std::placeholders::_1)); - pointcloud_sub_ = this->create_subscription( + // Subscribers + sub_pointcloud_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&SurroundObstacleCheckerNode::pointCloudCallback, this, std::placeholders::_1)); - dynamic_object_sub_ = - this->create_subscription( - "~/input/objects", 1, - std::bind(&SurroundObstacleCheckerNode::dynamicObjectCallback, this, std::placeholders::_1)); - current_velocity_sub_ = this->create_subscription( + std::bind(&SurroundObstacleCheckerNode::onPointCloud, this, std::placeholders::_1)); + sub_dynamic_objects_ = this->create_subscription( + "~/input/objects", 1, + std::bind(&SurroundObstacleCheckerNode::onDynamicObjects, this, std::placeholders::_1)); + sub_odometry_ = this->create_subscription( "~/input/odometry", 1, - std::bind(&SurroundObstacleCheckerNode::currentVelocityCallback, this, std::placeholders::_1)); + std::bind(&SurroundObstacleCheckerNode::onOdometry, this, std::placeholders::_1)); + + using std::chrono_literals::operator""ms; + timer_ = rclcpp::create_timer( + this, get_clock(), 100ms, std::bind(&SurroundObstacleCheckerNode::onTimer, this)); + + last_running_time_ = std::make_shared(this->now()); + + // Debug + debug_ptr_ = std::make_shared( + vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); } -void SurroundObstacleCheckerNode::pathCallback( - const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onTimer() { - if (use_pointcloud_ && !pointcloud_ptr_) { + if (node_param_.use_pointcloud && !pointcloud_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for pointcloud info..."); return; } - if (use_dynamic_object_ && !object_ptr_) { + if (node_param_.use_dynamic_object && !object_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for dynamic object info..."); return; } - if (!current_velocity_ptr_) { + if (!odometry_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for current velocity..."); return; } - // parameter description - TrajectoryPoints output_trajectory_points = - tier4_autoware_utils::convertToTrajectoryPointArray(*input_msg); + const auto nearest_obstacle = getNearestObstacle(); + const auto is_vehicle_stopped = isVehicleStopped(); - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + switch (state_) { + case State::PASS: { + const auto is_obstacle_found = + !nearest_obstacle ? false + : nearest_obstacle.get().first < node_param_.surround_check_distance; - // get current pose in traj frame - geometry_msgs::msg::Pose current_pose; - if (!getPose(input_msg->header.frame_id, "base_link", current_pose)) { - return; - } + if (!isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } + + state_ = State::STOP; - // get closest idx - const size_t closest_idx = getClosestIdx(output_trajectory_points, current_pose); + auto velocity_limit = std::make_shared(); + velocity_limit->stamp = this->now(); + velocity_limit->max_velocity = 0.0; + velocity_limit->use_constraints = false; + velocity_limit->sender = "surround_obstacle_checker"; - // get nearest object - double min_dist_to_obj = std::numeric_limits::max(); - geometry_msgs::msg::Point nearest_obj_point; - getNearestObstacle(&min_dist_to_obj, &nearest_obj_point); + pub_velocity_limit_->publish(*velocity_limit); - // check current obstacle status (exist or not) - const auto is_obstacle_found = isObstacleFound(min_dist_to_obj); + // do not start when there is a obstacle near the ego vehicle. + RCLCPP_WARN(get_logger(), "do not start because there is obstacle near the ego vehicle."); - // check current stop status (stop or not) - const auto is_stopped = checkStop(input_msg->points.at(closest_idx)); + break; + } - const auto is_stop_required = isStopRequired(is_obstacle_found, is_stopped); + case State::STOP: { + const auto is_obstacle_found = + !nearest_obstacle + ? false + : nearest_obstacle.get().first < node_param_.surround_check_recover_distance; - // insert stop velocity - if (is_stop_required) { - state_ = State::STOP; + if (isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } - // do not start when there is a obstacle near the ego vehicle. - RCLCPP_WARN_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "do not start because there is obstacle near the ego vehicle."); - insertStopVelocity(closest_idx, &output_trajectory_points); + state_ = State::PASS; + + auto velocity_limit_clear_command = std::make_shared(); + velocity_limit_clear_command->stamp = this->now(); + velocity_limit_clear_command->command = true; + velocity_limit_clear_command->sender = "surround_obstacle_checker"; - // visualization for debug - if (is_obstacle_found) { - debug_ptr_->pushObstaclePoint(nearest_obj_point, PointType::NoStart); + pub_clear_velocity_limit_->publish(*velocity_limit_clear_command); + + break; } - debug_ptr_->pushPose(input_msg->points.at(closest_idx).pose, PoseType::NoStart); - no_start_reason_diag = makeStopReasonDiag("obstacle", input_msg->points.at(closest_idx).pose); - } else { - state_ = State::PASS; + + default: + break; } - // publish trajectory and debug info - auto output_msg = tier4_autoware_utils::convertToTrajectory(output_trajectory_points); - output_msg.header = input_msg->header; - path_pub_->publish(output_msg); - stop_reason_diag_pub_->publish(no_start_reason_diag); + if (nearest_obstacle) { + debug_ptr_->pushObstaclePoint(nearest_obstacle.get().second, PointType::NoStart); + } + + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + if (state_ == State::STOP) { + debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); + no_start_reason_diag = makeStopReasonDiag("obstacle", odometry_ptr_->pose.pose); + } + + pub_stop_reason_->publish(no_start_reason_diag); debug_ptr_->publish(); } -void SurroundObstacleCheckerNode::pointCloudCallback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onPointCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) { - pointcloud_ptr_ = input_msg; + pointcloud_ptr_ = msg; } -void SurroundObstacleCheckerNode::dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg) { - object_ptr_ = input_msg; + object_ptr_ = msg; } -void SurroundObstacleCheckerNode::currentVelocityCallback( - const nav_msgs::msg::Odometry::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) { - current_velocity_ptr_ = input_msg; + odometry_ptr_ = msg; } -void SurroundObstacleCheckerNode::insertStopVelocity( - const size_t closest_idx, TrajectoryPoints * traj) +boost::optional SurroundObstacleCheckerNode::getNearestObstacle() const { - // set zero velocity from closest idx to last idx - for (size_t i = closest_idx; i < traj->size(); i++) { - traj->at(i).longitudinal_velocity_mps = 0.0; - } -} + boost::optional nearest_pointcloud{boost::none}; + boost::optional nearest_object{boost::none}; -bool SurroundObstacleCheckerNode::getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose) -{ - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, tf2::TimePointZero); - // convert geometry_msgs::msg::Transform to geometry_msgs::msg::Pose - tf2::Transform transform; - tf2::fromMsg(ros_src2tgt.transform, transform); - tf2::toMsg(transform, pose); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_pointcloud) { + nearest_pointcloud = getNearestObstacleByPointCloud(); } - return true; -} -bool SurroundObstacleCheckerNode::convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose) -{ - tf2::Transform src2tgt; - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, time, tf2::durationFromSec(0.1)); - tf2::fromMsg(ros_src2tgt.transform, src2tgt); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_dynamic_object) { + nearest_object = getNearestObstacleByDynamicObject(); } - tf2::Transform src2obj; - tf2::fromMsg(pose, src2obj); - tf2::Transform tgt2obj = src2tgt.inverse() * src2obj; - tf2::toMsg(tgt2obj, conv_pose); - return true; -} - -size_t SurroundObstacleCheckerNode::getClosestIdx( - const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose) -{ - double min_dist = std::numeric_limits::max(); - size_t min_dist_idx = 0; - for (size_t i = 0; i < traj.size(); ++i) { - const double x = traj.at(i).pose.position.x - current_pose.position.x; - const double y = traj.at(i).pose.position.y - current_pose.position.y; - const double dist = std::hypot(x, y); - if (dist < min_dist) { - min_dist_idx = i; - min_dist = dist; - } + if (!nearest_pointcloud && !nearest_object) { + return {}; } - return min_dist_idx; -} -void SurroundObstacleCheckerNode::getNearestObstacle( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) -{ - if (use_pointcloud_) { - getNearestObstacleByPointCloud(min_dist_to_obj, nearest_obj_point); + if (!nearest_pointcloud) { + return nearest_object; } - if (use_dynamic_object_) { - getNearestObstacleByDynamicObject(min_dist_to_obj, nearest_obj_point); + if (!nearest_object) { + return nearest_pointcloud; } + + return nearest_pointcloud.get().first < nearest_object.get().first ? nearest_pointcloud + : nearest_object; } -void SurroundObstacleCheckerNode::getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCloud() const { - // wait to transform pointcloud - geometry_msgs::msg::TransformStamped transform_stamped; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, - tf2::durationFromSec(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "failed to get base_link to " << pointcloud_ptr_->header.frame_id << " transform."); - return; + const auto transform_stamped = + getTransform("base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, 0.5); + + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; } - Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.transform).cast(); - pcl::PointCloud pcl; - pcl::fromROSMsg(*pointcloud_ptr_, pcl); - pcl::transformPointCloud(pcl, pcl, isometry); - for (const auto & p : pcl) { - // create boost point - Point2d boost_p(p.x, p.y); - - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, boost_p); - - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - nearest_obj_point->x = p.x; - nearest_obj_point->y = p.y; - nearest_obj_point->z = p.z; + Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.get().transform).cast(); + pcl::PointCloud transformed_pointcloud; + pcl::fromROSMsg(*pointcloud_ptr_, transformed_pointcloud); + pcl::transformPointCloud(transformed_pointcloud, transformed_pointcloud, isometry); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); + + for (const auto & p : transformed_pointcloud) { + Point2d boost_point(p.x, p.y); + + const auto distance_to_object = bg::distance(ego_polygon, boost_point); + + if (distance_to_object < minimum_distance) { + nearest_point = createPoint(p.x, p.y, p.z); + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -void SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject() const { - const auto obj_frame = object_ptr_->header.frame_id; - const auto obj_time = object_ptr_->header.stamp; - for (const auto & obj : object_ptr_->objects) { - // change frame of obj_pose to base_link - geometry_msgs::msg::Pose pose_baselink; - if (!convertPose( - obj.kinematics.initial_pose_with_covariance.pose, obj_frame, "base_link", obj_time, - pose_baselink)) { - return; - } + const auto transform_stamped = + getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5); - // create obj polygon - Polygon2d obj_poly; - if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { - obj_poly = createObjPolygon(pose_baselink, obj.shape.footprint); - } else { - obj_poly = createObjPolygon(pose_baselink, obj.shape.dimensions); - } + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; + } + + tf2::Transform tf_src2target; + tf2::fromMsg(transform_stamped.get().transform, tf_src2target); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, obj_poly); + for (const auto & object : object_ptr_->objects) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - *nearest_obj_point = obj.kinematics.initial_pose_with_covariance.pose.position; + tf2::Transform tf_src2object; + tf2::fromMsg(object_pose, tf_src2object); + + geometry_msgs::msg::Pose transformed_object_pose; + tf2::toMsg(tf_src2target.inverse() * tf_src2object, transformed_object_pose); + + const auto object_polygon = + object.shape.type == Shape::POLYGON + ? createObjPolygon(transformed_object_pose, object.shape.footprint) + : createObjPolygon(transformed_object_pose, object.shape.dimensions); + + const auto distance_to_object = bg::distance(ego_polygon, object_polygon); + + if (distance_to_object < minimum_distance) { + nearest_point = object_pose.position; + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -bool SurroundObstacleCheckerNode::isObstacleFound(const double min_dist_to_obj) +boost::optional SurroundObstacleCheckerNode::getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const { - const auto is_obstacle_inside_range = min_dist_to_obj < surround_check_distance_; - const auto is_obstacle_outside_range = min_dist_to_obj > surround_check_recover_distance_; - - if (state_ == State::PASS) { - return is_obstacle_inside_range; - } + geometry_msgs::msg::TransformStamped transform_stamped; - if (state_ == State::STOP) { - return !is_obstacle_outside_range; + try { + transform_stamped = + tf_buffer_.lookupTransform(source, target, stamp, tf2::durationFromSec(duration_sec)); + } catch (tf2::TransformException & ex) { + return {}; } - throw std::runtime_error("invalid state"); + return transform_stamped; } bool SurroundObstacleCheckerNode::isStopRequired( - const bool is_obstacle_found, const bool is_stopped) + const bool is_obstacle_found, const bool is_vehicle_stopped) { - if (!is_stopped) { + if (!is_vehicle_stopped) { return false; } @@ -356,7 +432,7 @@ bool SurroundObstacleCheckerNode::isStopRequired( // Keep stop state if (last_obstacle_found_time_) { const auto elapsed_time = this->now() - *last_obstacle_found_time_; - if (elapsed_time.seconds() <= state_clear_time_) { + if (elapsed_time.seconds() <= node_param_.state_clear_time) { return true; } } @@ -365,118 +441,18 @@ bool SurroundObstacleCheckerNode::isStopRequired( return false; } -bool SurroundObstacleCheckerNode::checkStop( - const autoware_auto_planning_msgs::msg::TrajectoryPoint & closest_point) -{ - if (std::fabs(current_velocity_ptr_->twist.twist.linear.x) > stop_state_ego_speed_) { - // ego vehicle has high velocity now. not stop. - return false; - } - - const double closest_vel = closest_point.longitudinal_velocity_mps; - const double closest_acc = closest_point.acceleration_mps2; - - if (closest_vel * closest_acc < 0) { - // ego vehicle is about to stop (during deceleration). not stop. - return false; - } - - return true; -} - -Polygon2d SurroundObstacleCheckerNode::createSelfPolygon() -{ - const double front = vehicle_info_.max_longitudinal_offset_m; - const double rear = vehicle_info_.min_longitudinal_offset_m; - const double left = vehicle_info_.max_lateral_offset_m; - const double right = vehicle_info_.min_lateral_offset_m; - - Polygon2d poly; - boost::geometry::exterior_ring(poly) = boost::assign::list_of(front, left)(front, right)( - rear, right)(rear, left)(front, left); - return poly; -} - -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +bool SurroundObstacleCheckerNode::isVehicleStopped() { - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double h = size.x; - const double w = size.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - boost::geometry::exterior_ring(obj_poly) = boost::assign::list_of(h / 2.0, w / 2.0)( - -h / 2.0, w / 2.0)(-h / 2.0, -w / 2.0)(h / 2.0, -w / 2.0)(h / 2.0, w / 2.0); - - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} + const auto current_velocity = std::abs(odometry_ptr_->twist.twist.linear.x); -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) -{ - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - for (const auto point : footprint.points) { - const Point2d point2d(point.x, point.y); - obj_poly.outer().push_back(point2d); + if (node_param_.stop_state_ego_speed < current_velocity) { + last_running_time_ = std::make_shared(this->now()); } - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} - -diagnostic_msgs::msg::DiagnosticStatus SurroundObstacleCheckerNode::makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) -{ - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; - diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; - no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - no_start_reason_diag.name = "no_start_reason"; - no_start_reason_diag.message = no_start_reason; - no_start_reason_diag_kv.key = "no_start_pose"; - no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); - no_start_reason_diag.values.push_back(no_start_reason_diag_kv); - return no_start_reason_diag; + return node_param_.stop_state_entry_duration_time < (this->now() - *last_running_time_).seconds(); } -std::string SurroundObstacleCheckerNode::jsonDumpsPose(const geometry_msgs::msg::Pose & pose) -{ - const std::string json_dumps_pose = - (boost::format( - R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % - pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % - pose.orientation.y % pose.orientation.z) - .str(); - return json_dumps_pose; -} +} // namespace surround_obstacle_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE(SurroundObstacleCheckerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(surround_obstacle_checker::SurroundObstacleCheckerNode) From 1f5ade6a6a5c2f26cc94a5c10d0ffde82b165205 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 10 May 2022 10:15:23 +0900 Subject: [PATCH 018/223] feat: remove deprecated package in prediction launch (#875) Signed-off-by: Yukihiro Saito --- .../launch/object_recognition/prediction/prediction.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 4749bd45d3e3e..fd9d1ba6f3cda 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -9,6 +9,6 @@ - + From 399c13366100a710090486ae6cb7370a0f77a59e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 12:43:47 +0900 Subject: [PATCH 019/223] fix(surround_obstacle_checker): fix ego footprint polygon (#877) Signed-off-by: satoshi-ota --- planning/surround_obstacle_checker/src/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 9e1fc6711bd3f..cd7117f360143 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -131,8 +131,8 @@ Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) ego_polygon.outer().push_back(Point2d(front_m, -width_m)); ego_polygon.outer().push_back(Point2d(front_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, -width_m)); bg::correct(ego_polygon); From eca2944b058d137c6a1c7dab582f28f109be4d6e Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 10 May 2022 15:21:49 +0900 Subject: [PATCH 020/223] fix: update nvinfer api (#863) * fix(lidar_centerpoint): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(tensorrt_yolo): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(lidar_apollo_instance_segmentation): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_classifier): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_ssd_fine_detector): update nvinfer api Signed-off-by: Daisuke Nishimatsu * pre-commit run Signed-off-by: Daisuke Nishimatsu --- .../CMakeLists.txt | 3 --- .../lib/include/TrtNet.hpp | 6 ++--- .../lib/src/TrtNet.cpp | 2 +- .../src/detector.cpp | 26 +++++++++++++------ perception/lidar_centerpoint/CMakeLists.txt | 10 ++++--- .../lib/include/tensorrt_wrapper.hpp | 3 ++- .../lib/src/tensorrt_wrapper.cpp | 14 ++++++---- perception/tensorrt_yolo/CMakeLists.txt | 3 --- .../tensorrt_yolo/lib/include/trt_yolo.hpp | 3 ++- perception/tensorrt_yolo/lib/src/trt_yolo.cpp | 16 +++++++----- .../traffic_light_classifier/CMakeLists.txt | 3 --- .../utils/trt_common.cpp | 14 ++++++---- .../CMakeLists.txt | 3 --- .../lib/include/trt_ssd.hpp | 3 ++- .../lib/src/trt_ssd.cpp | 14 ++++++---- 15 files changed, 72 insertions(+), 51 deletions(-) diff --git a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt index 4fee2ecdd2f3b..433999051097d 100644 --- a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_apollo_instance_segmentation) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability diff --git a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp index 30d560135cb4f..14c1ff6d44c63 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp +++ b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp @@ -56,13 +56,13 @@ class trtNet } if (!mTrtRunTime) { - mTrtRunTime->destroy(); + delete mTrtRunTime; } if (!mTrtContext) { - mTrtContext->destroy(); + delete mTrtContext; } if (!mTrtEngine) { - mTrtEngine->destroy(); + delete mTrtEngine; } } diff --git a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp index c51adc83e07c1..0f1da4bdac8a6 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp +++ b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp @@ -100,7 +100,7 @@ trtNet::trtNet(const std::string & engineFile) mTrtRunTime = createInferRuntime(gLogger); assert(mTrtRunTime != nullptr); - mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length, nullptr); + mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length); assert(mTrtEngine != nullptr); InitEngine(); diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 7d628173b2e4c..af8b29f55f340 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -63,17 +63,27 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * const int batch_size = 1; builder->setMaxBatchSize(batch_size); config->setMaxWorkspaceSize(1 << 30); - nvinfer1::ICudaEngine * engine = builder->buildEngineWithConfig(*network, *config); - nvinfer1::IHostMemory * trt_model_stream = engine->serialize(); - assert(trt_model_stream != nullptr); + nvinfer1::IHostMemory * plan = builder->buildSerializedNetwork(*network, *config); + assert(plan != nullptr); std::ofstream outfile(engine_file, std::ofstream::binary); assert(!outfile.fail()); - outfile.write(reinterpret_cast(trt_model_stream->data()), trt_model_stream->size()); + outfile.write(reinterpret_cast(plan->data()), plan->size()); outfile.close(); - network->destroy(); - parser->destroy(); - builder->destroy(); - config->destroy(); + if (network) { + delete network; + } + if (parser) { + delete parser; + } + if (builder) { + delete builder; + } + if (config) { + delete config; + } + if (plan) { + delete plan; + } } net_ptr_.reset(new Tn::trtNet(engine_file)); diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 1f5c869136eb0..0cf1f51654bb1 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_centerpoint) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations -Wno-unknown-pragmas) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability @@ -144,6 +141,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) centerpoint_cuda_libraries ) + # To suppress unknown-pragmas error. The root-cause is CUB library in CUDA 11.6. + # This issue was fixed by https://github.com/NVIDIA/cub/commit/7d608bf1dc14553e2fb219eabeed80b76621b6fe + target_include_directories(centerpoint + SYSTEM PUBLIC + ${CUDA_INCLUDE_DIRS} + ) + ## node ## ament_auto_add_library(lidar_centerpoint_component SHARED src/node.cpp diff --git a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp index dd49723a5265c..b334be9e2230b 100644 --- a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp +++ b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp @@ -29,7 +29,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -82,6 +82,7 @@ class TensorRTWrapper bool createContext(); unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; }; diff --git a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp index 3691128137c39..f9882afac8f92 100644 --- a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp @@ -104,7 +104,13 @@ bool TensorRTWrapper::parseONNX( std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return false; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return false; @@ -116,9 +122,8 @@ bool TensorRTWrapper::parseONNX( bool TensorRTWrapper::saveEngine(const std::string & engine_path) { std::cout << "Writing to " << engine_path << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); return true; } @@ -139,8 +144,7 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path) } std::cout << "Loading from " << engine_path << std::endl; - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size)); return true; } diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index c05fefc38d15c..a50af6bfa9abb 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -4,9 +4,6 @@ project(tensorrt_yolo) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp index 813811226a0a6..c951154820f1a 100644 --- a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp +++ b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp @@ -59,7 +59,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -130,6 +130,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp index 1be5f279714ba..748680266ca9c 100644 --- a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp +++ b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp @@ -65,8 +65,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -253,9 +252,15 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!prepare()) { - std::cout << "Fail to prepare engine" << std::endl; + std::cout << "Fail to create engine" << std::endl; return; } } @@ -263,9 +268,8 @@ Net::Net( void Net::save(const std::string & path) const { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) diff --git a/perception/traffic_light_classifier/CMakeLists.txt b/perception/traffic_light_classifier/CMakeLists.txt index 08897bfa3cf5a..8ebd5f32db99e 100644 --- a/perception/traffic_light_classifier/CMakeLists.txt +++ b/perception/traffic_light_classifier/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_classifier) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability option(CUDA_AVAIL "CUDA available" OFF) diff --git a/perception/traffic_light_classifier/utils/trt_common.cpp b/perception/traffic_light_classifier/utils/trt_common.cpp index a920d47fa295a..cae9f0cd1682a 100644 --- a/perception/traffic_light_classifier/utils/trt_common.cpp +++ b/perception/traffic_light_classifier/utils/trt_common.cpp @@ -45,6 +45,7 @@ TrtCommon::TrtCommon(std::string model_path, std::string precision) is_initialized_(false), max_batch_size_(1) { + runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); } void TrtCommon::setup() @@ -86,9 +87,8 @@ bool TrtCommon::loadEngine(std::string engine_file_path) std::stringstream engine_buffer; engine_buffer << engine_file.rdbuf(); std::string engine_str = engine_buffer.str(); - runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); engine_ = UniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size(), nullptr)); + reinterpret_cast(engine_str.data()), engine_str.size())); return true; } @@ -117,19 +117,23 @@ bool TrtCommon::buildEngineFromOnnx(std::string onnx_file_path, std::string outp return false; } - engine_ = UniquePtr(builder->buildEngineWithConfig(*network, *config)); + auto plan = UniquePtr(builder->buildSerializedNetwork(*network, *config)); + if (!plan) { + return false; + } + engine_ = + UniquePtr(runtime_->deserializeCudaEngine(plan->data(), plan->size())); if (!engine_) { return false; } // save engine - nvinfer1::IHostMemory * data = engine_->serialize(); std::ofstream file; file.open(output_engine_file_path, std::ios::binary | std::ios::out); if (!file.is_open()) { return false; } - file.write((const char *)data->data(), data->size()); + file.write((const char *)plan->data(), plan->size()); file.close(); return true; diff --git a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt index e82c790f4fd1e..eb172b7faf981 100644 --- a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt +++ b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_ssd_fine_detector) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp index bbe5ae8da513c..cfb6c8a6d5754 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp +++ b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp @@ -31,7 +31,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -87,6 +87,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp index 766de7eb4cde1..ba9f94b014513 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp +++ b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp @@ -36,8 +36,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -136,7 +135,13 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return; @@ -151,9 +156,8 @@ Net::Net( void Net::save(const std::string & path) { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) From 3e5e6db3a707510f92f3f2fe634dc3491ec81f5d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 10 May 2022 17:39:28 +0900 Subject: [PATCH 021/223] fix(avoidance_module): ignore object instead of creating zero shift (#731) * fix: ignore object instead of creating zero shift instead of creating zero shift point, the object will be ignored. no behavior changes should be observed. Signed-off-by: Muhammad Zulfaqar Azmi * refactor: sync continue with upstream Signed-off-by: Muhammad Zulfaqar Azmi * fix: fix debug message for insufficient lateral margin Signed-off-by: Muhammad Zulfaqar Azmi --- .../avoidance/avoidance_module.cpp | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 876e5fc3112c3..2923996ca8697 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -490,24 +490,19 @@ AvoidPointArray AvoidanceModule::calcRawShiftPointsFromObjects( avoidance_debug_msg.max_shift_length = max_allowable_lateral_distance; if (!(o.to_road_shoulder_distance > max_allowable_lateral_distance)) { - avoidance_debug_msg.allow_avoidance = false; - avoidance_debug_msg.failed_reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + avoidance_debug_array_false_and_push_back(AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN); + continue; } const auto max_shift_length = o.to_road_shoulder_distance - road_shoulder_safety_margin - 0.5 * vehicle_width; - const auto max_left_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto left_shift_constraint = std::min(getLeftShiftBound(), max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? left_shift_constraint - : 0.0; + + const auto max_left_shift_limit = [&max_shift_length, this]() noexcept { + return std::min(getLeftShiftBound(), max_shift_length); }; - const auto max_right_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto right_shift_constraint = std::max(getRightShiftBound(), -max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? right_shift_constraint - : 0.0; + const auto max_right_shift_limit = [&max_shift_length, this]() noexcept { + return std::max(getRightShiftBound(), -max_shift_length); }; const auto shift_length = isOnRight(o) From 7b81507c8074c6b4a547d3165856993f77ea72bd Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 10 May 2022 18:33:56 +0900 Subject: [PATCH 022/223] fix(motion_velocity_smoother): curve deceleration not working with a specific parameter set (#738) Signed-off-by: Takamasa Horibe --- .../motion_velocity_smoother/src/smoother/smoother_base.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index 2ecf683fd3028..31c6420a67870 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -105,7 +105,7 @@ boost::optional SmootherBase::applyLateralAccelerationFilter( for (size_t i = 0; i < output->size(); ++i) { double curvature = 0.0; const size_t start = i > after_decel_index ? i - after_decel_index : 0; - const size_t end = std::min(output->size(), i + before_decel_index); + const size_t end = std::min(output->size(), i + before_decel_index + 1); for (size_t j = start; j < end; ++j) { curvature = std::max(curvature, std::fabs(curvature_v->at(j))); } From 66688730c654a76629ace36961351667e5694c69 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 10 May 2022 21:29:41 +0900 Subject: [PATCH 023/223] test(autoware_testing): fix smoke_test (#479) * fix(autoware_testing): fix smoke_test Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * restore smoke_test for trajectory_follower_nodes Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * add support multiple parameter files Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * ci(pre-commit): autofix * minor fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_testing/smoke_test.py | 39 +++++++++++++------ .../cmake/add_smoke_test.cmake | 10 ++--- .../trajectory_follower_nodes/CMakeLists.txt | 14 +++++-- 3 files changed, 42 insertions(+), 21 deletions(-) diff --git a/common/autoware_testing/autoware_testing/smoke_test.py b/common/autoware_testing/autoware_testing/smoke_test.py index 2753861269124..8c361474034ad 100644 --- a/common/autoware_testing/autoware_testing/smoke_test.py +++ b/common/autoware_testing/autoware_testing/smoke_test.py @@ -16,6 +16,7 @@ import os import shlex +import time import unittest from ament_index_python import get_package_share_directory @@ -26,21 +27,24 @@ from launch_ros.actions import Node import launch_testing import pytest +import rclpy def resolve_node(context, *args, **kwargs): + parameters = [ + os.path.join( + get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), + "param", + file_name, + ) + for file_name in shlex.split(LaunchConfiguration("arg_param_filenames").perform(context)) + ] smoke_test_node = Node( package=LaunchConfiguration("arg_package"), executable=LaunchConfiguration("arg_package_exe"), namespace="test", - parameters=[ - os.path.join( - get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), - "param", - LaunchConfiguration("arg_param_filename").perform(context), - ) - ], + parameters=parameters, arguments=shlex.split(LaunchConfiguration("arg_executable_arguments").perform(context)), ) return [smoke_test_node] @@ -55,8 +59,8 @@ def generate_test_description(): arg_package_exe = DeclareLaunchArgument( "arg_package_exe", default_value=["default"], description="Tested executable" ) - arg_param_filename = DeclareLaunchArgument( - "arg_param_filename", default_value=["test.param.yaml"], description="Test param file" + arg_param_filenames = DeclareLaunchArgument( + "arg_param_filenames", default_value=["test.param.yaml"], description="Test param file" ) arg_executable_arguments = DeclareLaunchArgument( "arg_executable_arguments", default_value=[""], description="Tested executable arguments" @@ -66,7 +70,7 @@ def generate_test_description(): [ arg_package, arg_package_exe, - arg_param_filename, + arg_param_filenames, arg_executable_arguments, OpaqueFunction(function=resolve_node), launch_testing.actions.ReadyToTest(), @@ -74,8 +78,19 @@ def generate_test_description(): ) +class DummyTest(unittest.TestCase): + def test_wait_for_node_ready(self): + """Waiting for the node is ready.""" + rclpy.init() + test_node = rclpy.create_node("test_node") + while len(test_node.get_node_names()) == 0: + time.sleep(0.1) + print("waiting for Node to be ready") + rclpy.shutdown() + + @launch_testing.post_shutdown_test() class TestProcessOutput(unittest.TestCase): def test_exit_code(self, proc_output, proc_info): - # Check that process exits with code -15 code: termination request, sent to the program - launch_testing.asserts.assertExitCodes(proc_info, [-15]) + # Check that process exits with code 0 + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/common/autoware_testing/cmake/add_smoke_test.cmake b/common/autoware_testing/cmake/add_smoke_test.cmake index 2998db4960de4..ee2cb0f06e789 100644 --- a/common/autoware_testing/cmake/add_smoke_test.cmake +++ b/common/autoware_testing/cmake/add_smoke_test.cmake @@ -19,18 +19,18 @@ # :type package_name: string # :param package_exec: package executable to run during smoke test # :type executable_name: string -# :param PARAM_FILENAME: yaml filename containing test parameters -# :type PARAM_FILENAME: string +# :param PARAM_FILENAMES: yaml filenames containing test parameters +# :type PARAM_FILENAMES: string # :param EXECUTABLE_ARGUMENTS: arguments passed to tested executable # :type EXECUTABLE_ARGUMENTS: string function(add_smoke_test package_name executable_name) - cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAME;EXECUTABLE_ARGUMENTS" "") + cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAMES;EXECUTABLE_ARGUMENTS" "") set(ARGUMENTS "arg_package:=${package_name}" "arg_package_exe:=${executable_name}") - if(smoke_test_PARAM_FILENAME) - list(APPEND ARGUMENTS "arg_param_filename:=${smoke_test_PARAM_FILENAME}") + if(smoke_test_PARAM_FILENAMES) + list(APPEND ARGUMENTS "arg_param_filenames:=${smoke_test_PARAM_FILENAMES}") endif() if(smoke_test_EXECUTABLE_ARGUMENTS) diff --git a/control/trajectory_follower_nodes/CMakeLists.txt b/control/trajectory_follower_nodes/CMakeLists.txt index 7996ac0713107..fa005c1c0bfda 100644 --- a/control/trajectory_follower_nodes/CMakeLists.txt +++ b/control/trajectory_follower_nodes/CMakeLists.txt @@ -57,10 +57,16 @@ if(BUILD_TESTING) ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} fake_test_node) target_link_libraries(${TRAJECTORY_FOLLOWER_NODES_TEST} ${LATLON_MUXER_NODE} ${LATERAL_CONTROLLER_NODE} ${LONGITUDINAL_CONTROLLER_NODE}) - #find_package(autoware_testing REQUIRED) - #add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe PARAM_FILENAME latlon_muxer_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe PARAM_FILENAME lateral_controller_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe PARAM_FILENAME longitudinal_controller_defaults.param.yaml) + find_package(autoware_testing REQUIRED) + add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe + PARAM_FILENAMES "latlon_muxer_defaults.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "lateral_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "longitudinal_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) endif() ament_auto_package( From 31147a2cea1221677fae2a6bcc1a4aa8a41a18fb Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 11 May 2022 10:22:56 +0900 Subject: [PATCH 024/223] feat(rviz_plugins): add velocity limit to autoware state panel (#879) * feat(rviz_plugins): add velocity limit to autoware state panel Signed-off-by: tanaka3 * chore(rviz_plugin): change ms to kmh Signed-off-by: tanaka3 --- common/tier4_state_rviz_plugin/package.xml | 1 + .../src/autoware_state_panel.cpp | 23 +++++++++++++++++++ .../src/autoware_state_panel.hpp | 7 ++++++ 3 files changed, 31 insertions(+) diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index 2afbe9c315f75..74f7a7418815e 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -21,6 +21,7 @@ rviz_common tier4_control_msgs tier4_external_api_msgs + tier4_planning_msgs ament_lint_auto autoware_lint_common diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 78681106b3d61..825e06dac1cd9 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -80,13 +80,26 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa engage_button_ptr_ = new QPushButton("Engage"); connect(engage_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareEngage())); + velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); + pub_velocity_limit_input_ = new QSpinBox(); + pub_velocity_limit_input_->setRange(-100.0, 100.0); + pub_velocity_limit_input_->setValue(0.0); + pub_velocity_limit_input_->setSingleStep(5.0); + connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); + auto * v_layout = new QVBoxLayout; + auto * velocity_limit_layout = new QHBoxLayout(); v_layout->addLayout(gate_layout); v_layout->addLayout(selector_layout); v_layout->addLayout(state_layout); v_layout->addLayout(gear_layout); v_layout->addLayout(engage_status_layout); v_layout->addWidget(engage_button_ptr_); + v_layout->addLayout(engage_status_layout); + velocity_limit_layout->addWidget(velocity_limit_button_ptr_); + velocity_limit_layout->addWidget(pub_velocity_limit_input_); + velocity_limit_layout->addWidget(new QLabel(" [km/h]")); + v_layout->addLayout(velocity_limit_layout); setLayout(v_layout); } @@ -114,6 +127,9 @@ void AutowareStatePanel::onInitialize() client_engage_ = raw_node_->create_client( "/api/autoware/set/engage", rmw_qos_profile_services_default); + + pub_velocity_limit_ = raw_node_->create_publisher( + "/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1)); } void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) @@ -215,6 +231,13 @@ void AutowareStatePanel::onEngageStatus( engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_))); } +void AutowareStatePanel::onClickVelocityLimit() +{ + auto velocity_limit = std::make_shared(); + velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; + pub_velocity_limit_->publish(*velocity_limit); +} + void AutowareStatePanel::onClickAutowareEngage() { auto req = std::make_shared(); diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 45cd290e5f4a3..97c559bdfb3de 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -28,6 +29,7 @@ #include #include #include +#include namespace rviz_plugins { @@ -41,6 +43,7 @@ class AutowareStatePanel : public rviz_common::Panel public Q_SLOTS: void onClickAutowareEngage(); + void onClickVelocityLimit(); protected: void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); @@ -61,12 +64,16 @@ public Q_SLOTS: rclcpp::Client::SharedPtr client_engage_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + QLabel * gate_mode_label_ptr_; QLabel * selector_mode_label_ptr_; QLabel * autoware_state_label_ptr_; QLabel * gear_label_ptr_; QLabel * engage_status_label_ptr_; QPushButton * engage_button_ptr_; + QPushButton * velocity_limit_button_ptr_; + QSpinBox * pub_velocity_limit_input_; bool current_engage_; }; From da41a37d19434b62ccce549a83777b0d469e48d7 Mon Sep 17 00:00:00 2001 From: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Date: Wed, 11 May 2022 11:00:51 +0900 Subject: [PATCH 025/223] fix(dummy_perception_publisher): publish multiple layers of pointcloud (#882) * fix: single -> multiple layers pointcloud Signed-off-by: Hirokazu Ishida * refactor: share common among different pcloud creators Signed-off-by: Hirokazu Ishida --- .../src/pointcloud_creator.cpp | 56 ++++++++++++++----- 1 file changed, 41 insertions(+), 15 deletions(-) diff --git a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp index 6c964625a3e69..d55c42a0c28bd 100644 --- a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp +++ b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp @@ -25,6 +25,18 @@ #include #include +namespace +{ + +static constexpr double epsilon = 0.001; +static constexpr double step = 0.05; +static constexpr double vertical_theta_step = (1.0 / 180.0) * M_PI; +static constexpr double vertical_min_theta = (-15.0 / 180.0) * M_PI; +static constexpr double vertical_max_theta = (15.0 / 180.0) * M_PI; +static constexpr double horizontal_theta_step = (0.1 / 180.0) * M_PI; +static constexpr double horizontal_min_theta = (-180.0 / 180.0) * M_PI; +static constexpr double horizontal_max_theta = (180.0 / 180.0) * M_PI; + pcl::PointXYZ getPointWrtBaseLink( const tf2::Transform & tf_base_link2moved_object, double x, double y, double z) { @@ -32,6 +44,8 @@ pcl::PointXYZ getPointWrtBaseLink( return pcl::PointXYZ(p_wrt_base.x(), p_wrt_base.y(), p_wrt_base.z()); } +} // namespace + void ObjectCentricPointCloudCreator::create_object_pointcloud( const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map, std::mt19937 & random_generator, pcl::PointCloud::Ptr pointcloud) const @@ -39,14 +53,6 @@ void ObjectCentricPointCloudCreator::create_object_pointcloud( std::normal_distribution<> x_random(0.0, obj_info.std_dev_x); std::normal_distribution<> y_random(0.0, obj_info.std_dev_y); std::normal_distribution<> z_random(0.0, obj_info.std_dev_z); - const double epsilon = 0.001; - const double step = 0.05; - const double vertical_theta_step = (1.0 / 180.0) * M_PI; - const double vertical_min_theta = (-15.0 / 180.0) * M_PI; - const double vertical_max_theta = (15.0 / 180.0) * M_PI; - const double horizontal_theta_step = (0.1 / 180.0) * M_PI; - const double horizontal_min_theta = (-180.0 / 180.0) * M_PI; - const double horizontal_max_theta = (180.0 / 180.0) * M_PI; const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; @@ -206,7 +212,18 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr pointclouds.at(i) = (pcl::PointCloud::Ptr(new pcl::PointCloud)); } - const double horizontal_theta_step = 0.25 * M_PI / 180.0; + std::vector min_zs(obj_infos.size()); + std::vector max_zs(obj_infos.size()); + + for (size_t idx = 0; idx < obj_infos.size(); ++idx) { + const auto & obj_info = obj_infos.at(idx); + const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; + const double min_z = -1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + const double max_z = 1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + min_zs.at(idx) = min_z; + max_zs.at(idx) = max_z; + } + double angle = 0.0; const auto n_scan = static_cast(std::floor(2 * M_PI / horizontal_theta_step)); for (size_t i = 0; i < n_scan; ++i) { @@ -217,13 +234,22 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr const auto x_hit = dist * cos(angle); const auto y_hit = dist * sin(angle); const auto idx_hit = composite_sdf.nearest_sdf_index(x_hit, y_hit); + const auto obj_info_here = obj_infos.at(idx_hit); + const auto min_z_here = min_zs.at(idx_hit); + const auto max_z_here = max_zs.at(idx_hit); + std::normal_distribution<> x_random(0.0, obj_info_here.std_dev_x); + std::normal_distribution<> y_random(0.0, obj_info_here.std_dev_y); + std::normal_distribution<> z_random(0.0, obj_info_here.std_dev_z); - std::normal_distribution<> x_random(0.0, obj_infos.at(idx_hit).std_dev_x); - std::normal_distribution<> y_random(0.0, obj_infos.at(idx_hit).std_dev_y); - std::normal_distribution<> z_random(0.0, obj_infos.at(idx_hit).std_dev_z); - pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( - x_hit + x_random(random_generator), y_hit + y_random(random_generator), - z_random(random_generator))); + for (double vertical_theta = vertical_min_theta; + vertical_theta <= vertical_max_theta + epsilon; vertical_theta += vertical_theta_step) { + const double z = dist * std::tan(vertical_theta); + if (min_z_here <= z && z <= max_z_here + epsilon) { + pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( + x_hit + x_random(random_generator), y_hit + y_random(random_generator), + z + z_random(random_generator))); + } + } } } From e2e557d63e4c342da067a32ff6d8ddefe4ea8d47 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 11 May 2022 12:56:26 +0900 Subject: [PATCH 026/223] feat(vehicle_info_util): add max_steer_angle (#740) * feat(vehicle_info_util): add max_steer_angle Signed-off-by: Takayuki Murooka * applied pre-commit Signed-off-by: Takayuki Murooka * Added max_steer_angle in test config Signed-off-by: Takayuki Murooka Co-authored-by: Tomoya Kimura --- .../param/test_vehicle_info.param.yaml | 1 + .../param/vehicle_characteristics.param.yaml | 1 + .../test/test_simple_planning_simulator.cpp | 1 + vehicle/vehicle_info_util/config/vehicle_info.param.yaml | 1 + .../include/vehicle_info_util/vehicle_info.hpp | 5 ++++- vehicle/vehicle_info_util/src/vehicle_info_util.cpp | 4 +++- 6 files changed, 11 insertions(+), 2 deletions(-) diff --git a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml index b1279b50ef04a..8941b92b4e78e 100644 --- a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml +++ b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml index 12b6efa79d1cd..ef594927dac4d 100644 --- a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml +++ b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml @@ -10,3 +10,4 @@ width_m: 2.0 front_overhang_m: 0.5 rear_overhang_m: 0.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index d983aeed4d8c4..fea6cd16db9d0 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -190,6 +190,7 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) node_options.append_parameter_override("left_overhang", 0.5); node_options.append_parameter_override("right_overhang", 0.5); node_options.append_parameter_override("vehicle_height", 1.5); + node_options.append_parameter_override("max_steer_angle", 0.7); } // Send a control command and run the simulation. diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml index b1279b50ef04a..8941b92b4e78e 100644 --- a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml +++ b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp index e7ba446051889..8df6d4cfe04c1 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp +++ b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp @@ -31,6 +31,7 @@ struct VehicleInfo double left_overhang_m; double right_overhang_m; double vehicle_height_m; + double max_steer_angle_m; // Derived parameters, i.e. calculated from base parameters // The offset values are relative to the base frame origin, which is located @@ -49,7 +50,8 @@ struct VehicleInfo inline VehicleInfo createVehicleInfo( const double wheel_radius_m, const double wheel_width_m, const double wheel_base_m, const double wheel_tread_m, const double front_overhang_m, const double rear_overhang_m, - const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m) + const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m, + const double max_steer_angle_m) { // Calculate derived parameters const double vehicle_length_m_ = front_overhang_m + wheel_base_m + rear_overhang_m; @@ -72,6 +74,7 @@ inline VehicleInfo createVehicleInfo( left_overhang_m, right_overhang_m, vehicle_height_m, + max_steer_angle_m, // Derived parameters vehicle_length_m_, vehicle_width_m_, diff --git a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp index 6cc2d2f27e9ce..c295155727e61 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp +++ b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp @@ -49,6 +49,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) vehicle_info_.left_overhang_m = getParameter(node, "left_overhang"); vehicle_info_.right_overhang_m = getParameter(node, "right_overhang"); vehicle_info_.vehicle_height_m = getParameter(node, "vehicle_height"); + vehicle_info_.max_steer_angle_m = getParameter(node, "max_steer_angle"); } VehicleInfo VehicleInfoUtil::getVehicleInfo() @@ -56,7 +57,8 @@ VehicleInfo VehicleInfoUtil::getVehicleInfo() return createVehicleInfo( vehicle_info_.wheel_radius_m, vehicle_info_.wheel_width_m, vehicle_info_.wheel_base_m, vehicle_info_.wheel_tread_m, vehicle_info_.front_overhang_m, vehicle_info_.rear_overhang_m, - vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m); + vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m, + vehicle_info_.max_steer_angle_m); } } // namespace vehicle_info_util From 952510b3427c7af5dc09cc25365c56f248e33780 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 11 May 2022 14:52:58 +0900 Subject: [PATCH 027/223] ci(deploy-docs): remove mdx_unimoji (#883) Signed-off-by: Shumpei Wakabayashi --- mkdocs.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/mkdocs.yaml b/mkdocs.yaml index 2bd16349b24bb..02c3bb42383e8 100644 --- a/mkdocs.yaml +++ b/mkdocs.yaml @@ -66,7 +66,6 @@ markdown_extensions: - mdx_math - mdx_truly_sane_lists: nested_indent: 2 - - mdx_unimoji - plantuml_markdown: server: http://www.plantuml.com/plantuml format: svg From b2727f066bcf842777734f5c8c649d669a91105d Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Wed, 11 May 2022 06:17:37 +0000 Subject: [PATCH 028/223] chore: sync files (#884) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 23508e63bc43d..93533b54e1dd0 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -54,7 +54,7 @@ jobs: - name: Select verb id: select-verb run: | - has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") + has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true verb=create if [ "$has_previous_draft" = "true" ]; then From ae80db9ad2878ff44c80a7aa9657be45da2ea829 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 May 2022 15:45:49 +0900 Subject: [PATCH 029/223] fix(lidar_centerpoint): fix google drive url to avoid 404 (#889) * fix(lidar_centerpoint): fix google drive url to avoid 404 * Update CMakeLists.txt Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- perception/lidar_centerpoint/CMakeLists.txt | 4 ++-- perception/tensorrt_yolo/CMakeLists.txt | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 0cf1f51654bb1..4f15575181348 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -86,13 +86,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) message(STATUS "File already exists.") else() message(STATUS "File hash changes. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() else() message(STATUS "File doesn't exists. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index a50af6bfa9abb..e8ac60c30ed37 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -93,7 +93,7 @@ message(STATUS "Checking and downloading yolov4.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx + COMMAND gdown "https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx ERROR_QUIET ) endif() @@ -115,7 +115,7 @@ message(STATUS "Checking and downloading yolov5s.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx + COMMAND gdown "https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx ERROR_QUIET ) endif() @@ -126,7 +126,7 @@ message(STATUS "Checking and downloading yolov5m.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx + COMMAND gdown "https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx ERROR_QUIET ) endif() From c396b9d75dbb49c1ce0a288b54f7bf8fa907fc1d Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 12 May 2022 21:01:04 +0900 Subject: [PATCH 030/223] chore: fix typos (#886) Signed-off-by: badai-nguyen --- .../src/blockage_diag/blockage_diag_nodelet.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index 3f3665bf06531..821e2de462bdc 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -42,7 +42,7 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options updater_.setHardwareID("blockage_diag"); updater_.add( - std::string(this->get_namespace()) + ": ground_blockage_validation", this, + std::string(this->get_namespace()) + ": blockage_validation", this, &BlockageDiagComponent::onBlockageChecker); updater_.setPeriod(0.1); @@ -93,9 +93,9 @@ void BlockageDiagComponent::onBlockageChecker(DiagnosticStatusWrapper & stat) if (level == DiagnosticStatus::OK) { msg = "OK"; } else if (level == DiagnosticStatus::WARN) { - msg = "WARNING: LiDAR ground blockage"; + msg = "WARNING: LiDAR blockage"; } else if (level == DiagnosticStatus::ERROR) { - msg = "ERROR: LiDAR ground blockage"; + msg = "ERROR: LiDAR blockage"; } else if (level == DiagnosticStatus::STALE) { msg = "STALE"; } From ffb0553a1915806df75e17dac2d9a237318f30c9 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 13 May 2022 11:22:08 +0900 Subject: [PATCH 031/223] feat(state_rviz_plugin): add GateMode and PathChangeApproval Button (#894) * feat(state_rviz_plugin): add GateMode and PathChangeApproval Button * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/autoware_state_panel.cpp | 40 +++++++++++++++++++ .../src/autoware_state_panel.hpp | 7 ++++ 2 files changed, 47 insertions(+) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 825e06dac1cd9..33177729e8359 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -16,6 +16,7 @@ #include "autoware_state_panel.hpp" +#include #include #include #include @@ -80,6 +81,15 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa engage_button_ptr_ = new QPushButton("Engage"); connect(engage_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareEngage())); + // Gate Mode Button + gate_mode_button_ptr_ = new QPushButton("Gate Mode"); + connect(gate_mode_button_ptr_, SIGNAL(clicked()), SLOT(onClickGateMode())); + + // Path Change Approval Button + path_change_approval_button_ptr_ = new QPushButton("Path Change Approval"); + connect(path_change_approval_button_ptr_, SIGNAL(clicked()), SLOT(onClickPathChangeApproval())); + + // Velocity Limit velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); pub_velocity_limit_input_ = new QSpinBox(); pub_velocity_limit_input_->setRange(-100.0, 100.0); @@ -87,7 +97,9 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa pub_velocity_limit_input_->setSingleStep(5.0); connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); + // Layout auto * v_layout = new QVBoxLayout; + auto * gate_mode_path_change_approval_layout = new QHBoxLayout; auto * velocity_limit_layout = new QHBoxLayout(); v_layout->addLayout(gate_layout); v_layout->addLayout(selector_layout); @@ -96,6 +108,9 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa v_layout->addLayout(engage_status_layout); v_layout->addWidget(engage_button_ptr_); v_layout->addLayout(engage_status_layout); + gate_mode_path_change_approval_layout->addWidget(gate_mode_button_ptr_); + gate_mode_path_change_approval_layout->addWidget(path_change_approval_button_ptr_); + v_layout->addLayout(gate_mode_path_change_approval_layout); velocity_limit_layout->addWidget(velocity_limit_button_ptr_); velocity_limit_layout->addWidget(pub_velocity_limit_input_); velocity_limit_layout->addWidget(new QLabel(" [km/h]")); @@ -130,6 +145,14 @@ void AutowareStatePanel::onInitialize() pub_velocity_limit_ = raw_node_->create_publisher( "/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1)); + + pub_gate_mode_ = raw_node_->create_publisher( + "/control/gate_mode_cmd", rclcpp::QoS(1)); + + pub_path_change_approval_ = raw_node_->create_publisher( + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/" + "path_change_approval", + rclcpp::QoS(1)); } void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) @@ -258,6 +281,23 @@ void AutowareStatePanel::onClickAutowareEngage() }); } +void AutowareStatePanel::onClickGateMode() +{ + const auto data = gate_mode_label_ptr_->text().toStdString() == "AUTO" + ? tier4_control_msgs::msg::GateMode::EXTERNAL + : tier4_control_msgs::msg::GateMode::AUTO; + RCLCPP_INFO(raw_node_->get_logger(), "data : %d", data); + pub_gate_mode_->publish( + tier4_control_msgs::build().data(data)); +} + +void AutowareStatePanel::onClickPathChangeApproval() +{ + pub_path_change_approval_->publish( + tier4_planning_msgs::build() + .stamp(raw_node_->now()) + .approval(true)); +} } // namespace rviz_plugins #include diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 97c559bdfb3de..a53bea54452fc 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include namespace rviz_plugins @@ -44,6 +45,8 @@ class AutowareStatePanel : public rviz_common::Panel public Q_SLOTS: void onClickAutowareEngage(); void onClickVelocityLimit(); + void onClickGateMode(); + void onClickPathChangeApproval(); protected: void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); @@ -65,6 +68,8 @@ public Q_SLOTS: rclcpp::Client::SharedPtr client_engage_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_gate_mode_; + rclcpp::Publisher::SharedPtr pub_path_change_approval_; QLabel * gate_mode_label_ptr_; QLabel * selector_mode_label_ptr_; @@ -73,6 +78,8 @@ public Q_SLOTS: QLabel * engage_status_label_ptr_; QPushButton * engage_button_ptr_; QPushButton * velocity_limit_button_ptr_; + QPushButton * gate_mode_button_ptr_; + QPushButton * path_change_approval_button_ptr_; QSpinBox * pub_velocity_limit_input_; bool current_engage_; From 80f3f1c8455381c040d2f166bf622d4f5cb79a5c Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Fri, 13 May 2022 13:50:09 +0900 Subject: [PATCH 032/223] feat(map_tf_generator): accelerate the 'viewer' coordinate calculation (#890) * add random point sampling function to quickly calculate the 'viewer' coordinate Signed-off-by: IshitaTakeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- map/map_tf_generator/CMakeLists.txt | 17 ++++++++ .../map_tf_generator/uniform_random.hpp | 33 ++++++++++++++ map/map_tf_generator/package.xml | 1 + .../src/map_tf_generator_node.cpp | 18 +++++--- .../test/test_uniform_random.cpp | 43 +++++++++++++++++++ 5 files changed, 107 insertions(+), 5 deletions(-) create mode 100644 map/map_tf_generator/include/map_tf_generator/uniform_random.hpp create mode 100644 map/map_tf_generator/test/test_uniform_random.cpp diff --git a/map/map_tf_generator/CMakeLists.txt b/map/map_tf_generator/CMakeLists.txt index 1170dfef00474..506f763c4bb36 100644 --- a/map/map_tf_generator/CMakeLists.txt +++ b/map/map_tf_generator/CMakeLists.txt @@ -16,6 +16,23 @@ rclcpp_components_register_node(map_tf_generator_node EXECUTABLE map_tf_generator ) + +if(BUILD_TESTING) + function(add_testcase filepath) + get_filename_component(filename ${filepath} NAME) + string(REGEX REPLACE ".cpp" "" test_name ${filename}) + + ament_add_gmock(${test_name} ${filepath}) + target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) + endfunction() + + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + add_testcase(test/test_uniform_random.cpp) +endif() + ament_auto_package(INSTALL_TO_SHARE launch ) diff --git a/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp b/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp new file mode 100644 index 0000000000000..345703a19bc06 --- /dev/null +++ b/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp @@ -0,0 +1,33 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ +#define MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ + +#include +#include + +std::vector UniformRandom(const size_t max_exclusive, const size_t n) +{ + std::default_random_engine generator; + std::uniform_int_distribution distribution(0, max_exclusive - 1); + + std::vector v(n); + for (size_t i = 0; i < n; i++) { + v[i] = distribution(generator); + } + return v; +} + +#endif // MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ diff --git a/map/map_tf_generator/package.xml b/map/map_tf_generator/package.xml index 9aaf14bc5fda7..3adcf80690668 100644 --- a/map/map_tf_generator/package.xml +++ b/map/map_tf_generator/package.xml @@ -19,6 +19,7 @@ tf2 tf2_ros + ament_cmake_gmock ament_lint_auto autoware_lint_common diff --git a/map/map_tf_generator/src/map_tf_generator_node.cpp b/map/map_tf_generator/src/map_tf_generator_node.cpp index 378d739ffbef3..b99514f18e658 100644 --- a/map/map_tf_generator/src/map_tf_generator_node.cpp +++ b/map/map_tf_generator/src/map_tf_generator_node.cpp @@ -12,6 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "map_tf_generator/uniform_random.hpp" + #include #include @@ -25,6 +27,8 @@ #include #include +constexpr size_t N_SAMPLES = 20; + class MapTFGeneratorNode : public rclcpp::Node { public: @@ -51,19 +55,23 @@ class MapTFGeneratorNode : public rclcpp::Node void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr clouds_ros) { + // fix random seed to produce the same viewer position every time + // 3939 is just the author's favorite number + srand(3939); + PointCloud clouds; pcl::fromROSMsg(*clouds_ros, clouds); - const unsigned int sum = clouds.points.size(); + const std::vector indices = UniformRandom(clouds.size(), N_SAMPLES); double coordinate[3] = {0, 0, 0}; - for (unsigned int i = 0; i < sum; i++) { + for (const auto i : indices) { coordinate[0] += clouds.points[i].x; coordinate[1] += clouds.points[i].y; coordinate[2] += clouds.points[i].z; } - coordinate[0] = coordinate[0] / sum; - coordinate[1] = coordinate[1] / sum; - coordinate[2] = coordinate[2] / sum; + coordinate[0] = coordinate[0] / indices.size(); + coordinate[1] = coordinate[1] / indices.size(); + coordinate[2] = coordinate[2] / indices.size(); geometry_msgs::msg::TransformStamped static_transformStamped; static_transformStamped.header.stamp = this->now(); diff --git a/map/map_tf_generator/test/test_uniform_random.cpp b/map/map_tf_generator/test/test_uniform_random.cpp new file mode 100644 index 0000000000000..76ee174a34871 --- /dev/null +++ b/map/map_tf_generator/test/test_uniform_random.cpp @@ -0,0 +1,43 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "map_tf_generator/uniform_random.hpp" + +#include + +using testing::AllOf; +using testing::Each; +using testing::Ge; +using testing::Lt; + +TEST(UniformRandom, UniformRandom) +{ + { + const std::vector random = UniformRandom(4, 0); + ASSERT_EQ(random.size(), static_cast(0)); + } + + // checks if the returned values are in range of [min, max) + // note that the minimun range is always zero and the max value is exclusive + { + const size_t min_inclusive = 0; + const size_t max_exclusive = 4; + + for (int i = 0; i < 50; i++) { + const std::vector random = UniformRandom(4, 10); + ASSERT_EQ(random.size(), 10U); + ASSERT_THAT(random, Each(AllOf(Ge(min_inclusive), Lt(max_exclusive)))); // in range [0, 4) + } + } +} From ef379533fdf2fdf5d8599d2c34af7ce38eef7ab0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 13 May 2022 17:45:37 +0900 Subject: [PATCH 033/223] docs(obstacle_stop_planner): update documentation (#880) Signed-off-by: satoshi-ota --- planning/obstacle_stop_planner/README.md | 13 +- .../docs/insert_decel_velocity.drawio.svg | 273 +----------------- .../docs/insert_velocity1.drawio.svg | 4 + .../docs/insert_velocity2.drawio.svg | 4 + 4 files changed, 22 insertions(+), 272 deletions(-) create mode 100644 planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg create mode 100644 planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg diff --git a/planning/obstacle_stop_planner/README.md b/planning/obstacle_stop_planner/README.md index 95274b6a4829d..9c8fc714fb9c1 100644 --- a/planning/obstacle_stop_planner/README.md +++ b/planning/obstacle_stop_planner/README.md @@ -11,13 +11,20 @@ - Adaptive Cruise Controller (ACC) - embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory. -When the stop point that has 0 velocity is inserted, the point is inserted in front of the target point cloud by the distance of `baselink to front` + `stop margin`. The `baselink to front` means the distance between `base_link`(center of rear-wheel axis) and front of the car. `stop margin` is determined by the parameters described below. +In order to stop with a `stop margin` from the obstacle exists, the stop point (`v=0`) is inserted at a distance of `baselink to front` + `stop margin` from the obstacle. The `baselink to front` means the distance between `base_link`(center of rear-wheel axis) and front of the car. -![insert_stop_velocity](./docs/insert_velocity.drawio.svg) +If a stop point has already been inserted by other nodes between the obstacle and a position which is `stop margin` meters away from the obstacle, the stop point is inserted at a distance of `baselink to front` + `min behavior stop margin` from the obstacle. + +

+ + +
When the deceleration section is inserted, the start point of the section is inserted in front of the target point cloud by the distance of `baselink to front` + `slow down forward margin`. the end point of the section is inserted behind the target point cloud by the distance of `slow down backward margin` + `baselink to rear`. The `baselink to rear` means the distance between `base_link` and rear of the car. The velocities of points in the deceleration section are modified to the deceleration velocity. `slow down backward margin` and `slow down forward margin` are determined by the parameters described below. -![insert_stop_velocity](./docs/insert_decel_velocity.drawio.svg) +
+ +
## Input topics diff --git a/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg b/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg index 80cb8c2ed5016..a49853974a2f9 100644 --- a/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg +++ b/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg @@ -1,269 +1,4 @@ - - - - - - - -
-
-
- -

- - backward - - - margin - -

-
-
-
-
-
- - backward margin - -
-
- - - - - - - - -
-
-
- -

- - - deceleration point - - -

-
-
-
-
-
- - deceleration point - -
-
- - - - - - - - -
-
-
- -

- - - v - - -

-
-
-
-
-
- - v - -
-
- - - - -
-
-
- -

- - - x - - -

-
-
-
-
-
- - x - -
-
- - - - -
-
-
- -

- - - baselink to front - - -

-
-
-
-
-
- - baselink to front - -
-
- - - - - - - - - - -
-
-
- -

- - - output velocity - - -

-
-
-
-
-
- - output velocity - -
-
- - - - - -
-
-
- -

- - - reference velocity - - -

-
-
-
-
-
- - reference velocity - -
-
- - - - - -
-
-
- -

- - forward margin - -

-
-
-
-
-
- - forward margin - -
-
- - - - - - - - - - - - - - - - - - - - -
-
-
- -

- - - baselink to rear - - -

-
-
-
-
-
- - baselink to rear - -
-
-
- - - - - Viewer does not support full SVG 1.1 - - - -
\ No newline at end of file + + + +
Obstacle
Obsta...
velocity
velocity
travel
distance
travel...
baselink to front
baselink to front
slow down forward margin
slow down forward margin
reference velocity
reference velocity
output velocity
output velocity
slow down backward margin
slow down backwa...
baselink to rear
baselink to rear
slow down
velocity
slow down...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg b/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg new file mode 100644 index 0000000000000..dd1054e17fb14 --- /dev/null +++ b/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg @@ -0,0 +1,4 @@ + + + +
Obstacle
Obsta...
velocity
velocity
baselink to front
baselink to front
stop margin
stop margin
reference velocity
reference velocity
output velocity
output velocity
travel
distance
travel...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg b/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg new file mode 100644 index 0000000000000..941668f909b60 --- /dev/null +++ b/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg @@ -0,0 +1,4 @@ + + + +
Obstacle
Obsta...
velocity
velocity
baselink to front
baselink to front
min behavior stop margin
min behavior stop margin
reference velocity
reference velocity
output velocity
output velocity
travel
distance
travel...
stop point
(inserted by other nodes)
stop point...
Text is not SVG - cannot display
\ No newline at end of file From 94704421ff6435eb68c38688d1cf9cbdb7f1914d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 17 May 2022 07:12:30 +0900 Subject: [PATCH 034/223] docs(tier4_traffic_light_rviz_plugin): update documentation (#905) Signed-off-by: satoshi-ota --- .../images/traffic_light_publish_panel.gif | Bin 416094 -> 552084 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif b/common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif index c1063c27ea98291c0af9e1fd6d90f1e3d20b1f9b..23aea952a0fd0d964b81384c2e3691617c055e7e 100644 GIT binary patch literal 552084 zcmW(+cR1Y7^M5->^j?ERIij72AZm0@jdmh>k8nf_iIO0Q?({B*dOAnc=)Lz-qxT*X z;o^Ru-}k?L_L-fTXLn|I%4^lsRV5^?`SAg~KM$V(000317yuvu00{tS0KfnM_J6Yw z2mpfs2nc|L0B8t+fdJV5kwRbq3b}OVEuy7<6j>f_R=rK%#Bo>9nqA*w#7K;J^90b6@02~6q zApsm3z+nI!7Qg`z90Y=cL2w8N4hg}bAvg>KhlSt(7!Cr%!C*K942Oi_&@dbZhQq>e z00IX=;9v+G0)ay!aA*V$gTP@CH~@)*AaO7x4uQlWkvKFGhe6`7NF0F1LC`oD8izpR zkZ2qljl-aESTqj6;2;^>nrPH{yxl`>MRhpUBBA{yUwT&Hk8Ivo-`xwcEpK zPn}msn(B6kDxXI^&~8TWPnQ^!S&TNU{VZ;evBj(N-F$!xbN?$gQ2d+)R5=|r`5i+>;fEG-Rx zl9PM>@AmhvPyOwd?H_R41OpE~;jUg=1rd=D{R|?R>t7256tCBUi8YKlLdj{;tV5Vg z8rMT8ESNYwA&P&P+-W5pq9S8M=ZvAyT1;A0ML8xdMroZXmRu{6YVl~2T;i3Ha-g#s z+aHom_5#VTg&HH(VbptHgTp9p_P(Z4?Cs}g=13hB)K&T(mi1HI9#zes+#CnHDjv%g z3Qx*Y>s(W~S^q(v@5$}Na}IWmJeAQwX#fBim@%k2_oydgeBxe-1O-B38fpkY8KTYN zL+3RKfspRdETFX+S{z8Tx z`l?mP2Uiy|imXj8i{=)5{ddSDB_ZWI+Md}wec0keKcyM6{n%Y{#44XA?FU_vNSykJ z{Y7ospk2|EulrhdioY^u5k;ck)JI)x>Yg;)!sxxPNd)}Y>EP_ajGUlG6ZxShnI*lv zM>P@gf0bzU9KW33ea6+WQ&m5qAqu_};>A1Qwx&CF?54X(1wVs%_^LZ9?Sdo-f_OUL zv(u&iQJrKGfhhPgyM%&3ZsJ6QuY(=AdhdiVX`vgGc=KFJz`#T-6zS#5A!7xi&yasM zLQO<;W+nhag73Hkza3XU^q@PFs9P76xTggue@9LjC9UWA)0OISbk|V$)+;|K*LvA` z1E)=XSMI=FW->iwgl?V{c}p)~w#z@??2%mQQ}1m2YiPdh=BoVtzeAJF#g`oiv(=$& z2rFs)L{Z@+y*p=A%iWy1pMd!K2c@o@X z@)1!=QN+_@@8ykMA_27U^wfpT{0P#m6yffq9NF?T<-B;C;tp})8@JNjNW9sW$Kk8^oR=`+2q7E z_A05?#z*+uF-R};X&QMX=E-ccYo-qxGi05ROo#9YuallMhSIYFGSTQ?**!r*z+%uU zm`)i-a!W_=^{SKNSrRAk(ku3l_)rW)j zGW1{~H+Wn@08$>T^n+MVv6{hP?cr5IwnSV?(l(7Z*}KGHcXT0|KAX&5y!g#%p=aIx zs@Ki47WH=}FU>PwzLuJ+7`v+QGe5NYbTi-k;CHD{+mZeYznS@*ceO2S8SB`7zE(4W zpYPI%tE`IcsKm35jZRPb3}&-l;Xwhj7sVO8pHXUg)5nscpxE|rMfmcsx9ki*uW}I- zsm(F*$yBltU&|EK3;(r!ECZMzH*7Vmuh$T%MI|}~>!vH$v8pdfuDgGA;kh}l#&uoZ zkjm2)l!Sn1m^<*mc}hR$c|p$brHS!|%Np%}E^6&J^WX0->*M|%t9`1&HLBqF?pys~ zOTptH(lZs{QT$F{y0EugsPE{Ob58p0?V29Y6#7iqYz4wdyt+X`J0a%jrLr5WIu~kQ zF8rT;3+c1tg-l5f5LiKdJXXG0)Vm4AxChJBf978mi zLNxb6w3$K;i9(ISLtYw(z{5k$NU$^xio}DDs}zcc1+omc*F9YGhT~_GWky6K+pQ)!NCo3 zG#$i@A?CKZd^xF43;=N7ri2?4n2Ps##XakcN9J9Hj`MXe+YXXOBl(Io^RNwPBq3se z$1v}Uh^a71-nv;qM?gnfK-XSC4RXTjH}P)4zN=>YbXY-|8oSs_(Eq;38mllp_uV z_uK35<_GO@tIyyE)mIaf=*qsCVNw^i#yO|~Q~*raYL!Un(3n*GokZ-qr{lDkRZo0n zb?mMp35XbMtE;{ZH%;Zxx~okPTu2c5n;^`bC?c5{hbPR`NiBir4dU0W%>nVp2fhO^(x&S!kxcG za=%d>>LHQc#KN}2^lgDBBVFhzC+yv4Zs{;-^ta3gF6p+W%pZf9UCdcM#94iRGY2HI z`b)D0-#m&a;hoqweHQF6(&*x{W(dfe4>e}bE@ThxWsfrDEaU!WZ}H`3e!of0$Gq$hYi{baBF74cft(okbFI6fJV+fesbV_3 zVsEKppN!)7&BeZp#r`+NAMck0N|gkgl!W+}gk_Y3H7E7XUN@DMqBBe?bOiGh{ zOH&St`K@WSYM5BoOCvjJqSmRXIZ$HfrTH1C&(>50i=}x|OvN{-N?%$+4(bZuGR`2> zeGZy}3?{P4vNlxNTrH|cs=SW`Rme{}AXQ$sSl)b4UVBqMb-!XpqkO`tVmh*7cBp(| zsA8$Pd<}(~Kd4wVsoe6dTt}5}ELQAGRUQvj9^O=(J5`?YR~`6Pok&&fp{lMls<1az z*CbVV&Q*08rD-Ik-0szcE!8AT)nvET6f8AV(ls=uHFSP844E}dEj9O-YV3zfLz!zI zKB?t2t%dm2@?_TXw$$=3)e7F$vT;xgN!JPA){5Xv>qIl_BwFgEmg;0~>z=cq<)zVz zrf6k9v}z_A)`HepLTlZkby(_khwE5P>mT^l8)eoTx73>~)tlYcTd*`(NjKP-HhjLJ z0y3-c538J8s$7<;T+14?IH+0h%FBJf_wtwf-lF<6zJmp-JxCjaZ@-5OHw2kBx=S~P zl{H30HM-q4z8P*r-ZsP^HYT?;rf4>0_%)_2HN_k@B_7f`NH^P=HW&Cc7iBh=v^1ms z+qT>0O6gKAzdC)>76a!NDb1Gee(2_?mX^boj@y9!ipwmH)_j9=SgX4`U0+bT=VFWgXRf?v~D(;ra^bqi9po6_{`)Xj&(P3}uS zwhn)!leQ0|7`@{eA1_tdEVf(Uv|HWpu<#8~bf+#Ec34Y*t}F7Ak!6w`b&zLukjr#Z zYIQPTJNof!5Z;}vW}Od~JK3?Foc^86%WVvPFJkv1(Tz}2n73Z=~K8#Nmp#g5nuj`EPzBqK(vqDLjmM;!(G zw-9|h*uK4yUYym)u1x=l851IFY@4h*WMS+jVjRXgu75Q4OQz>YaQvEV0#q?JWkdRE zWMs;w+ar2HQBW9fbQ~r)=44W_VcLFnGg77nWp;tyUzue6H6i2Bl^`lUY8a zl|7@xHmq4O&FRuZ5kH|CFsm0ctJQ|mIUY98p0!$;c_>S@$}?vjF!Mtfif=oo9Wb@! z+bkY1E#Q*)>1c$8W!@uuUY~Zz>t9<6$(V0Ncc6B6z$mqhf1jFv;$;@b9o0uwfpKca ze0Ik~$6&Tu$G@`^;7^ZlNB1Sf^yta-{`IE{_2@A^!lcCXAkB;9wHC_R7OMX(BFRVJ zX)k@1?M>3|H6)*G(1sdm5nfe~mj*0VLnj{|)}@)Hz4xzu&xWZgpR!;T77joU%GQn^ zFAI>b49TpBMtxMnEuqGjP;4Blw^4QTF)Ns^!6oyw46`YN(ZNP7syp3T)#afs?5ga@ zT$k2x`x*%m)$%CoNI(DDSpYPAoys7Wz&Tr#>~2{9-OGaBC#@7TntknOaB3ajZ+vw1(I% z^!0&lRe#D#0Q{S38!#W=*OF=1^#`c%s^3xK8*jdCU8L0RG1nQR@)m#ii!vo_7qOgX zMK*5wqeljZ*dZnakXw|`O2@4bZwjgh;%NH^Y$Y71QKWv z17#Lk6-@tTTV;L<+#PUeLtW&d4b{Y^?8K%WvyY%Lzu9U2tR3c4)Oy~Mu8h$BkzEJJ z{u~fGM7tg~R345WP=0r#%)6ugUS0NVeXpJUxRMHQ`r8Y2_5rGO5(6rNe^#{j;>#G^ znK%?slGLcPk?%S8=LvO$;pV5e|EAQRI!{9nC$1@yNHszPEbOhx=$m;-lC zP_uT8dmtA3{Ng_Oxq>!Tm%YpvMJkqDunXd-dx$`zIS;nj7lt=~A*&Q%gt^(Bvi( zFBOOS_qLzOO_}Sudv-H!ZxI7)nm>n=v()1MMoUO;1>KQ~_qr2dFy2nn-e|RVPFoozH;6vSe<-;%HX)ZmJ0zZR*vlG0i! zQv^`jBZ0x4ZfjSwI@xY7Xs7larSwN^iqrO{?gq&Omdtuv9l4*-JQi_4N-Rupm3#ag z$NH8=xBq+K+bdnB2Ed#>G2(=Tm)Sdkaw$zXsu0n_}aYNMC;t_UXFShyuCA}`ZG zvY=bk5sC{`#xg!FE&~&@Q?$G1}d zm>$QK2oBWiZJ>fV)pIMfSmGk3?&fz~Ehb{6Q&r8Sj;p*Y%o06Tt}V+N>TwIM>KntW zNsx-g_;?zt#H!XmUR(_;MhzSKMB?>&R4O)32eTEHFWQ=~4l%KB+OKv`Q<8@5U@i-2 zjGOybJ9gijHctgp4_BjPmqt%{=o)%dgKzN1$q$~0}7vGrp*eh8Im6aUHH5UHp*`cGzg{5_U1yj->k zV=rnL(`#0d&i?SE^MO_kyuj?NyGeHvu<9EnjWH9v+y`x(^1(s`2}G3rPj*CT2Dz;5 zhPBwa?ds}GLCCIL`c0c+@(T%4RJM47{F(-!nkRtA9q!2;0bM+&!u3Et`=6IEjce%# z$657Mr1&DJtCCDi&WSXHlFmj`J~c2IwkOCyY%6^|OuS&dSVb#%?sB&tsrNvjaFq}h zdoj5Vz#dwWk8s~*cu8gT1q$}HwFdzR!OIEd+laSG6dXsV7+w=Tf+8ajQamu^hh|Mf zy6ZZiRY5n=^RQYfA-^a-g{?d~FTu+GF`usfaBiO>od$0fyOLs;B^g|hScm7PI0<}k z{s@Q?8X{_$f$h)N1PQx3T896TbxZ`yZ$W}k4z;hF{CL74d8UCSLpJHJf5h6>Gd28W z7or(Jaood02GV^})DJFMCFJkTuXJ*EgQoyQ@^}R7l7cv)Xbf|+?pHctejX7i#r%}E z@{}$$zs75#?N7owu&!o}c&la_)SZQtF1GZtkZ~ zMZ^AmH8p-tR@Oy#LlCZqsL5_vP`y(l$vRnhTfM-X5O85s5IEp~B%X>$`l6k&mdm$c z=op+Jp$BXXk)qViLv(_#bHoEnwo^n%Rs|y7ey znve(tkCH0~O0I)U98!y3HocLn|B%RVV@-;Y;KfSW6+ zda9p0@;HeqFJvuD!c1CQH!!d?6ca=`U^5w~-_5x|6ag!XA8?rx5AC4ZVIUp|mUB}P zGWy%g_{4MJ3+!8<`ou_-rI!}VeS*>j!!tNBQd#>hFVoZwgqPvi%X8P00%!%BT9Uko z5wfQwv34STW*z!P3&-|&9zE!aa((X^Wz=)Pc#E6VH+67~yEb-G>Ctk?aH1W9gl#?dtx>64 zD<~u-(WLc_AOkfg$1*}@TYbr!rhI^K2YF|Z|d0TSSW@DThj5<}{RwUXkOSl#Q>!3n1ZAr^*e`(1- zd6gX5RDpjJ9uZ8&Q@)fK@|n0=idsl>4)DpnTY3d@PDIoT_or zI?4!>&$be<>O-E&qm#S^@u+>s=ak1B{x6mNXqxTxw<5{G{);A;b4vw^u*A+C=Z_I8 z#P(M&&5g|FKNQDc=nkZRqUGnj=IRg1X{rfcV!l71G0Y5J0|f@ezGKZ+N4*-^m{156 z1>|%2{%cj|dNkQf3I(r6m*W`D-I9FIB7rEr#{bI3PJ63&M1Q`<=mls4&Te0Y#HP48RO@8?$jDz%Fjhdd&{0nQB;0)P(IMBBiM=UxitFR$fe{bW^{L?RJY;!10 zt}Z1-qx5nCyUxQG`#Cu5niGeu(4Zowi$&|-{kh*+T0tb!t{X=sYN?taYgi#mPDM$^ zAg9XL+)F4+eare`gm;m!WGE5U(u0I9!;c{*cAi(xB-Z$vooHq>-rG|@d{!6VLcy|K zdod0U1>;~Y>U?cp1x5Od*zU#o1gg-js9-qhT$PV3O7&j5$SWPVbSko-d*LXy^Jb0d zf)vt`%pUEzytqXx^KT{Qo#di1$VrcMEAll+7r8NTp!XBs;yt@*`24Mf7BU-Z-}C!A zd(n(EBROWfUO4J->U(Zr5Z1=446U<>uPJ$!^VmI#G?3>&fy9gta31_u@$u^)QXMd0 zS-k*;Z4E{0V{uPDHn0#l76L4#D~z?(&%%#hZ$v`9&f>DRvp*<3lfsG8V1T!C?&V{jEfafa2hUSR2S);C zVLn0X`^4)-l!M|HT-0U)T#O=xQ)gcUJQHUl#Czp4AtGI~5^+3+IoiTG6BCNQEJbfQ zQC1$ki-XiTR-&b-9zida4}QHyhGcb3ot9e2eLRueH=#@NplEi+Wk-Tf)dUBf;fs!; z?7}%+11eUn&&+!YX{ggfV9eC&WZ0A4CxQSWBR-si=bI)15^$Z$Lw*y*5^&Z`MT-1}xt%1c({xd3D@Q9mcEHlbn;SHEva zcYpNk`J5;FM+Igb%`~W6bn0aA2momP{Zf#KEC@>b=hup^P5-6);8dEZVv~_i7r?B6 z4@n49{UTaoVI#vCyGZT0(TXj_Y zi7GumB(tzCl$a`q!j~tTmNQErCMJqQSGCHID<2-6Ko&CXQPJrwL6j|BGc_3xAJ~X_eX@Jh9b3?zsZRx$4xg<5AMbE^OA6a z0Lzjun)rbbSQ#`kX3C4&C`vTy@(VPL&-ylXAn-*W73b$@kc6^koo4-vl1NvNkJ3^aq(g0EEng!j?>O~1_I=LQ9`Un|B(pm~NM`Rw<|#ONB?pJm_=Szcv6o^Q(>iQ1-+x#4IC)AOk4&=7>U_Z0_bX{^OAGgT zT5Ptd$I3G0n<(~l8tq$0DcwyYW1Z~lH$}%hC8RyZULV6PTPz8gdJv%hGV#A8D!0%5 zzJa^RfRBJk?|Vu-N%Ez}I8$N02iXyA!Vh=fJp3Y$To(+d&eP&`CxgwTDcc)Pq)~(^ z#HgvXbSP?f=w+r^@o$2qXM`Vh+>E1_S$~3tm%(G7!)2Nk$Mm_wfBz-;r2u!oY0jIR zX+RhnStpvfWKQkP)D^_G2b0$;eO-hYTB|UxLgolH#;lJSZQ({?)od@>ji&y460_i^ z%`?^&a}J|v+ky%vwckBAAkiLCo*-q(C@0&Us(*Ur-brl`O8oF zxwKFv@3vS$78K%=)VTKhUle(0SGtF&GP24(L!*h#dW75)J2mPKl zR>bPn8(!|SH_I<~!E!JmEP^(`!+w7aARZ*K4qG zrAP2&x=nYryV`(_oOt_+a)V$fpnm0aZ7MlQ>?gtM@%HM;)#@q1&og?jW( z_(`%M3>riDdqzdJ*~G zgX~OQ*-yF#CK@~QP(+k(Ax3m?{Z-AnvA@`@(`VOpig_vXI= zT2*h@(&)1jZMD-L+fut*(K&hfg2rBV_2r8qI~`SfgH^j1zm4_p>A17Xl(Iumx#P@W z>GWe~7EZeP&SHyTm+sBm|PX8#%@GPXBG#?z4a??>_M-0k1V$U;8EQ zzTer!TZ!czU zFLq~dC3+9ZupiH}pOE6<>KZQ7*DL64{BW*Is$o7QW&d4eu9U;;(E$8+%Q?u|5seu0Hk389l+E%{Hly@|#4D;@ia9|sj-Tjh67 zG}3o8I(Ia-b2Og9-NkS`$#XpQ z{LS-Y=O0GLGY-eI-p6yUE_(4+(?!RN|KY@bP~1P+dC<3xD~f$nNO%(bjwh4H^{2%* zb-ROHA*a$J?pwu8u_7Dsk0;`)c8cCM3OZX#bFK%gCx?};ies)P3~x_QPR@8v&&5wK z8(gml-yS+_!Tp^ZbetQ#5C5i|-t@h_nLE8*eOrBUS`+&gw{wcecm}%XHaoCCZ*(>@ z6G8AOeqm*eA?KLB@0jGC1&zWR$A&ZV-7|_uZ@Qm{kH#MP{W|JV)faa`eEhF+L+I#t zamM)U&AL4~Q}Oxz@8^y=jz0oj?)^Ns7Bjq;6U+Y9h2!1@$FmDgHIEKX4{kXRo);I~ zUoLp!E*_;`@E2bQ_;_?2RIuz`2>tPh$jQw=+0SRF*b;EUeb8}LZBj`0MEHH)&&rAC zfuD%R9eg#K*GqXSle(=x_v`uYFS&6~`Jcb!A6+Uu^OAe)rTow0@^^X#`RW4tg9!Jm9I9(!au(B}EzoO*Y%AVJ*8 zXP0LFMGMr@Zr6kL>bD!?pU30wcG*Vf&EcWf_v0MpNHj;ON147Tyupvv{(x(qyK{fp ze-WfR6Y$+5;NG{}e4t#VS;$vm=@K2b}HTnE8F6rZ&*fc(NC80Kn*p;?; z5_j@X^7M(bAom#?l3*T><1zQ#cXjl&0lk)YN_;}wqRgg;}Oxwak_ zuA4s;gv{dYGyXRGqK82C4||ggV$KFdB_64Ij<4<+!6)iQ*3XG9;)TMP z3_qXUGjMBDSjqN&A}FW_=s1SzNzefb;hTrsgx{TKwpbjjL-Wq!g$9PSYX}~dqB3?< z@~WA$-?MSZh0j>d%(kb`za^SW4Zx^{FT@2b`utm(|A$-b58xROSbfPdK_y83>3ZYY z$4)}`V9exLEe{r%kpBA1Ip%(zWaiCsOnPLX?{(+Q;sBVpZ;|)!mcM}bqN=rK_BDHC z24ftzm8kZ>_2i4#n}H`B(&w%Rls=CA;I!aO{!k)-h#e?c&PXU&t@3L>f+7aa^18#R z9*HBaPB+>u4f3yVuTG5sy?;aC(%H$My_O{CT&x5Eo?^6!?2y*0=^gD1v3Fyw>64FM zL@T(TfSp8lC-Y&c{4R@$e5!sGMfxti)kU-6$NnD22Uh}^YMcH9sPk{ZMYPj=t;^wW zs98DPqs7~oe=1kv>;q@Y4*7$UOpcCLJXBE0NjR|ScbFC2xr~mu0#W}f)lPGzC(|Up zHZ;{B(D&}lVl2z*R}r`Xn@p2iXyg?8od=eOpnRJSY^m8Qyezu9gOlq9o#gWqZk(_&sFa2xrIjzv0YwKPAYfg}kb=PNaK56^(ht4th<2eIT z@BN_K@u!-TPj}n&>_PbViPnNZoQ=7`}%stfh(m=xn~~K@=&68 zJ-U3t+>jk7;~OQyY_|H~4&FBpz>o3)qx2HBXp>jp)P4k}#VfMNq6vV_ZNfl#%i7Wo z9yY#9N>BoJI$pPwrjWJ_b%#ckRdh)mmemjahca!N@)f9R-e@kXs#u(g{F2z@L|4QQ|D#I>{MsdVpsQ2W*c zk#cB$ed*w+yd&PvF)2+pu~`FCbFsOX&e>w~rk}s(g-d@4V2pU25g@+!rmRhT$)O)s zuS{JUL1m2>eX%p3j-1qSwexV_%4WTD98YXV=5H!~ejKu$NlBmcTJ~A9h=ZJiH~2%Q zN%+oqOjI1Po?41HIzi55;!Rw_kL7eA$rFEY!rOhETl$!+7gM5e)R?af`dy-seEk)i;KeB z3U=c7=n#mISfpE~aX4MDd|0Xc*2AV(T<{|WRY}4?y5kPIbU`0d{f+{5B8d?r{~lzw zx^;{lCKw(jo}9PP^)QhI-6cnm%G9^eb)1 zpXVuFQnFgTlKEcnd`tNt)FsC`^L(SIrIJ_&5&0`~XJkimIAZJ_sxEugZdYaJU9$4R z+sCa7FWZlTOLO@GwLl}JT_?4|IC^zQ`Mm`>4WhtM(3&LM#V|u45?JLZrX!IblU)SB z$IG0=3S5pBR9xsF;}B!TvX~!@XEmnE9C!c*)L)P&awIbnuBTLzmz#)$+TGJ7+olsZ z;lRtqlLuv-X;CLSO&9Xlmudw#Ss;1odG+g2Ms55?Eh4?ylVcjs4p@~>@a95zb&@=v zST4&j&4n%Fx}R1I%w#i&7%A{PcFh+pOZiwp725O8Fd{SD-02Z!L9c*5>VEP8NP7HV zs}M(!Y{Vl*)4svg`pBeuggtlW!mtxVUCyzfqoly%Xu|KhZ(=TQly0eRp4bJv3Vh9978{#O>vt)QeNZ8fb51z-SVPlTfRNX4?d-`>f+vWe z$kj|0jsE%D}io8x16g0s`t97LEhNItrKW;|LWQo?k)TyH-%lO7{4{*`@l#1r1V zzfS!nEei)>aF38A8>jP0>lIL~(cV%YT7rE4A|b#z_MYn-%fs*e-U=mgpUrGJXg>_# zj9tAF%eT0de45v(1wZr+Asd5TtBoki4i*nrV0hjYA@vs)Tr|=czJ~w6<02UWFGn96 zD3_nFT%<2#{bwLeV_rY%vVTSI%8pZ1(Z;`4G8^7fplzPeEQgv$BMjF0llvn-qGz4f z?aqWVrecLeia09v*C|MCM#Mx*l%NL;>eS9R@2Z5m4?C~>=2PE6g;A6v2L_M5`!)z1 z%549Y+&X2o6k^Dg`P(kV4;a)q+g#_?#BGd*j$BrX0aUF$DA&VC$dRa z@!4D?FV%1J`+QI~zPm{8XWel@H`%|{@ywq0-<8BQ*?m}DjHGSbQ@ux;&vxPVTi590=$Ky{9q6^U zZsVTD{T+RsbMO);vzMOruH&}t)UUE-V3+k`HuJ|N>+7~d)5o`%>5spQ7`^s9t8RCA z{&8gBWOuu#DNI?5uCpY6oF~R%w*}h&j(qy@>l@|2ea-fpnf4!7b^k$3o!f7hi(CQ+D}1ROLMf|z9&3bzW}TA;XLvtPpD+gJ zfuRkG@FzbXJqtHIMj0E2NP38xTR1Q$OvW@Y^(ubxbU*nf`GA?MRCpB3nFMQ3M9Js?H z(x(n{D>Z@eOfQw1FDGYLz>RvWqsXP^szUPd2ub-sQUB%TRarLt`8IsD`TPwV{C%9N zS_W&OYariTsF9VB&6?21T+jih5Fr;)E$KFV(!hMNkU3odsqn~MO+=C0q7nb8hxHu0 zW?82mkr#uphy4cdtE$1{gP86)2R&OxS@Wp84Xle}ExU5^qjX|_I*)oIF=&*E3>a$~L zMGzuLfL)C^rpp$q#IZlZ!!GY5LpRIxg-_ud*s)WaJ4jO$ZOq@jYvS(UN4A< zFG)+W$q@eBo`$Nnne337F zm+wpQ&9Aoj@#==(&?EofocOV8j~AkPXXuJB`T~tzU?TEKY&TCDBS<3Y10JB36lRW% zhR$}q4hf6>r-a)hWfq>HWB>AkGf2}#;n66eo&t?L_m=qGXLok_iGox^K|1n%+Q@_? zAB2LZDqhGc{^#e(Vnb@ob|j(?UJYL3Gj>En1 zAb2d*U0~jz*MKT*Z6uAG@{8*T`}_7ZSVcYnkS_oEwmL+owR5+6NG5*#GGx4Bk^lGJ z!DZ5m%A12qkaN`?e+{8?4TbYB_OLIo&Q>b|i$O?=>fr+ij+mhSe}PEPi?Dn9aX-&e z^f=$(TZaiO>-z{!gz$9IaxIOxaRHU`VH|bcKf@K)D4q1}z|@B7>xh7OAmEE5SM;ZlyU^X>Np(O2|pn)aX{V z;x<^L`;vNpZR8=t$SxX`-8zVx>VAw?1iLu`%AMTxhowy5R3XD)5Wpt`j+oiu5z^qp zfMMZ|6=_ZYyL@rrz~d2ejv{cT*6VX@&*H(@nai$EVw zHWxRzYq?8F884}oo^OC+6HCv0UUfiM!NmdH!UhYPzjUVQTQ-hGb%mr;^{M7YtjH+S z993adNz^E;XLV9C0*O#m`AZJ!HWTDlC9#jKdZ24ALxkHtGZk0pAiMWULbF_DRFWRx7L1eIi@ywBH=e~pLK}z3ai0XO# zV@IlOYbK*!!Dy$ME;>V`yH%2G`aKXEp#=iO%&Llft|qW|2sP7{b<>45g6^?*6|>_B zBq=J_cR|_D-nbFQlg+ruzE#6h6-WXxheS4c2lwPty%kX==Ef5+?B|*3@|Oq6_WT#N zD#DRf*C`%d*+>2 z+-&c~6$SI4hYdSK;EFHgz77v{tbA5{G86Hud_w`&q_hKdzD7eJm(iN2V>V}Al%Nip z-KQAn1T5|>{APrZ{Q6*x>vN=e4a`)@BEhxj&tP!p2lb9Zo**4X_hMl>F@rRP7fg!Z z%tQGu6`p!2KE9O8dL;HrNX5X_U$s(YX?M#;RL#~^t$(`e4SAgG=7|Zp`liY=+ZpxL z%P}Ixww+#qBg(eQOMSd_o6vr5jGEiJ=!>_HlkU)bK5EG*5k0Q+p*bBpu{pwLa}Ln@ z)7Gq)+C40uVPMul2#ryCe2!A|tcATEn!F+Ih|(3%zs{)?be%})|(&Jo4>FQqp!F6VnKs1HkZq7MW#cZf|#4|dXH8wVa?LM zS8r|bn=0?Z>b3af6>fcj0TWoC%O#E}8~yqz^h#uV(R>`kJNeMyg@cO8hLlf(8rd-S z-J%K;Cudjof|#iCuZFjBmv5!fZhsntCpqa|(Q1$Ws0e&lwLI~V^YMHss_N{@{1<6! z`ukm-*W36Dr2TjMm%n$k=da(0fB2Gdlk$L;zdEPzd)i=*fzMXf)p7D9&(VaBpQrH0 zZl8~*-;V~r-y}T?v|Z5-{^LVCZ|7+Fj@L5y@y|4V%g>*_{!x(#dC?g1QXnR z-dk|R*=F0KxVr~}1ef6M4uv};NPq;l-~^AR5;!?&hqUAED^3xkS9V z`h0mG?s81|3TiIIDM3)|OmT9&MZ&H{at(1Q&BZy*F;U1)Iw9#hO{M*OWekKF_q^re zDoH1Lm|aa3Exak1%eAQdRroDcr2N%1E!E8YHQX&V!u++&_sQmxD zdbl^V7$CQw@(>~jPEoule|TS#GwkOf*yS-aPBGe_Gn(Tuy7@5LoilbLFrL#Am)tVZ zJzgGl?N*}^|0*jkM0UzADV~nn{o|rLG=K67&DK-|oV)u<6K8p}wt4JFZyl0;Qx8nZ zmoKU}7UvC?f;_x3v-GkJwb#Duj4E9;&XAw=Y#%s-nM2uA&oc5`2Obyu8Um}P?&1I(z5PLyL$6R4d2hOlj7Vc z#@Lto;|;xW-gpJe^DJ#Nh@)P>BjiYW`L0lWJ^6kU)UoOZCVKC@meCP*c&EHasp~YR z3hvg4fFuI-5L}iqqvM@k&f-}?kx|o&z!ZKz$!OERwxOF)Ju&F^ss~U(M3W&hcp3XH zu$i5{>yFULHM``orx*+*mdocTsx~U|0)OtbqJc&5rqn?YT8V`afubuzxU0ea@_xh% z-w&lHII{qU>nXfFmT)#6Cj_y6!T0VX*bl4hDN}Z``pQ_nMr|@au9=H|xz2p8KH%9n z9cgwx7}7|&DSy{$cMoTiSG}s&9fV1v*_vqgp+D-Cbi6>4z434YtLfZ>^XZV^HBunl zYA6RjL@59juZ@snR{?4N7Fy6))^e^v)By=&+4*ES4+^K=)6$oEvBc$xQZjJ1Be=^B z97Epea&_V> zSM}hgeHe`&H3(PfdtqKW*+*mt9syNN);jFw2Fi+Nru*6?iIKxB+y-=}51sXrPDAVt zrXyy<`0~+Fp223NxmoOF9uHt3(EB}sL_+l+nv9V{pp@T}aYF$hLLeUG)F2@&mMHW6 z@=xh$8HW+bWMMF>EwX<+EM^ZO9By8Wy3mk^*du|BB{TD-#7WF0 zqat28U^XZS2wSo&8`addYM8BGvgv%(T=4@iG{kWU#38LJg3s7k+Sg%UziZwqOZe)( zGo+>MaWi|v{26>TU*WR`uG3ogg{1!U)erx8e#4tob74Ig(`3OQL5OiU{m_OEI(XAc zWt~RzkhKn1tCY~bK+}TG3JGzkDlbmohHaqu642CNAN&bfA(T<1r3qINi=a0{jnkYe z8}Q^)neH6PZdUNaia`=W)yiinoeLm$o00I=d@+OW!O{&1UQeYEPZO@@Is922M#McU zBDXBM{1y9qV}dT`mt8fj#e3514;01?6E=$wA%$88Vm?k=2R5e=3m`O;%jEoZo1?Ac z)QfRJbmGfN$+Z``(=ttrS6>^aC$HuWqx7y9&F3fc4h8%|kYAxk;~sxi;hQCAik=8n zq7sM}iPqN@HAszP0TT{T(2ZGrPSuf@yi(tDsi4UU@J=Wz=ISq$X3*trlcv}>S|mqg zj9MaJwVzk=Kp zQ$?5pc|q7%4dlcojKIW|rS?Amd0BdjW(-)G3<0zfa>#}QVlT>pfy}8{b=r2#5b1gB zRCMx3-UJe_&_KbGu`1|VU93^FIW|Zv+LrQu-aH@*6{O03yTW+6ipx`B4Q;%-X{l)Z&YN8c!TfF-f`vXC>z){tUqtV znMh@bM{^WG1V^|WP9l{6I!Vg_5JayQIbbDdtv7>pZ4T8k(w(YE=UAtJBH|e91QBk? zs=f@=7_X$pq8;mUzcX6j@~T=HIu$#BFnwOg8=}P|R=4OmN?aA`!-Tv-K>R}ca|jZh zMeOrlQh4CBFcARhO4~WbJVZtb`rsvzeowF?DI?HNV2Px(A_p8roI9 z#8Ht7*vCRW?kT_q_4ZXSAslOw>}x|@zx|$ki`i1CxMI8#dab&p*^+N>ON_9Ywx?Bq0@Z4zwnE<3*JYF+0@o6=iYjC$KBI!ZuT zX24RBn+yia9W)Q(BYa-C+M+`CHJ%Jm%qkx`S!W@eCZ+qkgBFqAu3|%co7HGoXp-KM zO+w2m=Ll>ujoFxGDIAQA!GE{<}y%-Wa4N_ zn_zSou{<1{hu&mBXDB5o207IXmSF$_MkY-b>5xoPkZXO-x%PeK6~YX`f+!o0j1P`A zz&Dp{D%9Bu5`k@ahFSTW@QVf*1!lW$oJ2J^&8lx?NC2o8@i{Os1f!(R2oS+dTm;e8 z*~CT*P*B-qq68;{r0oWCrq#c!xaDkyi;9QGcAc@UH(eIo*sS$OP66a}blvU*ElyR*uq$g$$U+EUg zU}z)1gkb5Vz6SW>?Q;dB(?V)|u^SW|q9xUl5G5z(M4HXW?X zrjRcqf+K4ZcyZaoQwD)9xdivTCZvJ0%&GSk@uS4{QI)V&DUnh(C8kbrbc0K1G!9-` znzNaqGOWiODI!!Bk8Hx~h|NvQs`aX`LBhmU{Y~515dq1D;s|d*A=?M}N%xrx>Bqi8 z9kBH&Br4oz_!Gsxm&d2xULk4%oIE|OpU=YdIg$tyXggOe)PST^o8z+I#W%FhB6nuK zz1DXfHhi*AVs_eQD!3iBPQOUp^w?p3i!Zrar&)`XRw{Y3KiMC8Swkqer=Z_FHA?7I zhnBW4@6|m0eM&RrGu&6b8(j-P49xzgw8P^*Ma$85&UFQ8N0u(`&RfKT9^+}?W2b)Z zPaoMgK|MdbJm*{1-il!h5W5VqZr`tAqW|b&{(8c$CLJvr z8v514CIhM4MAT=>RBra~GEsL^VV|#xG9C_kSMGSj7AL&w?~m*<+zkl%sH|@UZRQ@` zH!ARsK6WTD7*W?~lX?9Z}_~@Jn~yhe|h`R z-Aj6YR-ylRR6%>Y2!7IUEZG)p01uUT*r%(dg74;CA0chQFsER+(gCZGHTZUICLe4r5Jc306LZd20)+ z2V6ATPALBfXI=@%PI0g4cjl;k_DQ)9uKWV+2A3Ng+WF{u(U?G!PK z1u4%Ksi+dE>=dbr1$l3n(rO&8?G(B5lTIP$J~PS&3!16z z8c=2vpa||_M&B5JBxl;ZWO=${d6crnfIdUNoj|_H~_ zs$fuIV$hvoF|zK80HIkia5yWWX>4)CK{&#dIKr5??6$Z{AgH>rZ_ghDn%m)7SK-;6 z;boLKZB^oXvfkKEaE03vgj5oQoDoE@z5v<1h^u;$boL^Rl`zZh4BUK*Uv@@_XpO=x zhVM{C)O1GF#`<#l6t$}A<)~eYFDnNJYuw!qrm@o1I_9;a5{W_u$y;WU59p*jtfYHq zB=?h7KUm3b?8uHV$q=VVVXMj3&PeguUSXb-q1s~!9*@6K!O@$ zoH7?2Z>QP$p?B%oxb#^m#G@&tRk_SBxJ(@=oY=V~+3@(s_*7|V`Eps{FL(}oS)_Y- zVz7DF#CUoAc{8SY^J@4KF8Fe=`NP!sX(%~%#O>d8@pr}W7pd{%J4k(t#2>H&rz9fEA+hH0pe@a*P|FF{V&_!3l+dV^RCClmhJ0;c z#XRs$^6iY27KgOnrIf3>^ldogP6gM28o(t6;K?owas;?f3&qp|oTe#-C3(dC$ZU(m zp8Qrz)g{VjxT|r*>m50pImFu?%SJ;eNYco6 zUn+itR=TNGYMN2%#8Do+lt<)LK#o%q-4qvhRJnJMcq=BjmnZEqBTa=XO>?EHb%7U~ zX|`k_j3Q?A-lY4yfVhzwl2Wv{a=3ujNrSacRWDA%?o#-LljeAgh|GitDyJ5vlQ?6o z7JIF@*Q{0^xwXAq42PjCoxcg!hMb&{vXh4Lq@xx%O+z~eR~vm+JL5{Jj#JqMj^6xA zr>>gy;+S=qoaSAfhT)Yiqm$l8b`Rs6YrvF|np&|7q`aP5t3n`uO)U z&W=;qx+=~L#Br1?CiKrXp~Zl|4Z!4s^SBwFiQTn{)0~Ox^@#JFsry{OXHBz$Je+s1 z9yq?l+I@IE7i1IAW>r*y7I+pR@fLYprheBJL7J8|&L%C+7G92&#jM7IbA;9!@1?n{ zI{L<2#Ce@)zXx2P=H?XJo~YOZ1og6rk4_VEDuT?ePvoy_4aM zlaiLx$4@~H3x@6sf&5tSIZd4D8iN@Yf1 zwC+=AQ{$^wQ(;vuVV!TnYZ}9bKZTDHgw67hp*DuB5)ky;`^0>TjB1SBBfw|=5pk7x z{NS9eZu@SYHGrEHn?Z#f_60UPF9_2Wgx&-~y#+zPh(_j(rgM#EOv3JDHdzTJf7=ja z$K&Kl5bN{i*^3R5Nn*}aA5o6xNUn}cIFHlgjW=|SH~zJUkUt0 z4al!Rg)pKi5peEatT5Q2th^)GetZ_||#!D=@O$n3HtsCEj zNCHv4h+%k<#+(G4ZAx3bO~YLTO}|JVea?E^rtZB>XXZ6fT8wr25hV8_Q}{OH{%xkK zTJT`VbMQIkgMpJgqZ8jrc4y#)ZXLAm3GBOokZrwpLQFAWwQmzUi zoTOV`P*D_d7yeR~F^PO{ZDqdoUA`S(fsK1C ziXzt~pVhHx(f>eH@6^&T9~UUF3oj$mxWtOOAFr}?`xve`zV8^}nK&QQv zzhjfAo!uxz?Y`rqQPn1UQ<8gAR0}z-pD^jBKT30F#@!d*ZU#t?F7w=K@l6r&mRf24 zZeEXWHA=r+F##E!9x%Udt%7d1QfrUSRsvmX?}whe!CVO!_dd^*22*$TCK2UiF*l@A zYObp4Jb8<_~?AFPWqo3NfL(LWqW+H(}JRbjB?Y z*U%SZYeyhXGIMh9!;Sqlz15M;;%#-a=>V zc}!4=f0@M|DiD~=^O&s4Q%c<;dl#M*4n+^h($KB9Un76jx9*2aJo!R!$Z&ZACT&8d zjrFyF>-7D&h9KY5E{P4~bC{e&U|ZAk*qX^G%!6VTXZ=l$pLRvvcnR);SDH?Ur*_rs zd`;cL@MW!B+aehILtQ{so#o*)Kk-c2Y6Fc3VrmbbGQEu3%Zv0Kl7V#ruFg+~8v{8o zh#sQ!{;)L9pJi2~Eg2IvF6RxCrVgJ84qtc1cVb=X{V!>b6a=Ej zFzJq}^^esA&TVr2P;LJ9y{{upa1*zCqTsu6!<=Oq-d2h8Ruk7&XZ@DUyDgP=C3ShI z=uAA6>@Ni5G^x4uc{1|pntp|^U#;kU_k7y&BC%9>x2s078oaF=X2r_J{MLuLn(pXte%?#YoZsfYb-r^H8qY`93kgnCD3U)6uGs$jh{; z?oE99w3jA)CSYfoF_~9L+J`G%zU}W~a-J9+qC$^Q!AHyQj&Q+L#U9Bgt81MrUppSo zZrjcwwMQ~^*1JDnl!+sq4$bC~A?jwKutd>8k#Ta>(eY6rI;JX8n10IPySI6NaIW5LUr!O=zll(4*p|~Fwu4eea#Cxf53_2T*-KY)0NNiF?fugFM z!B{G0H+AryJ(Wy6hv|~X;(3mIDyQq$6+{k`UM`+x;+Mg(2CBKz30w+yv3pa2YH^AY zvR4)wrJ89rkHws&T2;!Ok%Bt$rRsHWC(E6dxfoZ^6EsiP%3M@~~|UMl-0jTk*1Qk0$dwJRS0K>`rFO#RysRahi9A!D@M;^4A|O z)>wfR6jA?clFtb5gI~TUNKynZh#4@H0kgk_(${xphq87pd<$o7 zUOJcB%2KF<)=F%?H6PR-X&U+r-xb;7ncteds4D(zbic* zrME1r{c2%Z{%ehC>(hRTcz(UCRaGBJ*kSM*h|i*CMCickIbh0QUH5`I%=+0Z9R^!# zK(#F`D1d)#hKano^|w)u@2a&?JZwL(X%#F&K4}%Jvt(`;Ue!5izsn!4XnndyKJBYBfObsX( z!>MS?)}vf&;TM7HczCZXg>FzT$Hm|kE+?e$iA!BOCXyVc6@^iqY#?R17Xz58gRf?_ zO-HZh-npP&&%X~+xLzXt7vS~oQS+?(2xLI+Yk7!sd!`V#?Q~{%YT30$r zO$?z8omKz#k?t$rrXDZa?YC%dq1(+kX+_uVc+1G!?Q|EkyYJZ!LU%iPL5g6v{rr;1 zyM6D)Zf-~UC@cE`s^xe5M~x@t?kB*fcV|cK@EQE4WawTGqO>i@Nd`~h$ZhMsG_^Qa zGH;`BuA9s=5-+DZWNU7|MJas__D81F`|-VE{PTUeYC-$``M8p>wVFQsi}&Md<6hTK z=rh6)PZjPkCLewF6ln)_PwxSp_#O4oToHPT1khiL>keTM2gL#h zsOjYoH_$zIduZX#LexEwRgx(%f~cZCwX&xVw9*Q&;6;TE+>^iPUFc;87u$vPzK}Q4 zMrgxHwvDter9gUKn909w=l${_2=->DUj%I{D&&=s;p<>QF*G(-NgM?7oCFDhDV1oq z)GZQb^Feufj7a~G3>0C+p|dn4^C2Hp!eN3w&SX#op3Z>C?gw;zs|h@5j(I7#>>j^~ zX!;J@{zfF#u$aXu+)4gWEQ*jJ)@ru6VfF1k2N1KnabNE)54Uzz(Tm8zD%Ui755dO^j$}NY{r5L09>Ww0xIF z^;k5J@&`1~`;eNaV{aljP%WEaE7$Pdo6&F!4$~ZtNz^=qUOL}ea40#WIUvp+2m^qU zG-4?bw88XN@u#HJ74a6$2SPZP0-zuZB>^~<0ZC|ExR3?`!b2DkjFo<OO2dN-cB#b*GA5kT4@}-jgg7_o=2I&7M7&P zdlg1$B}&#{3ytx{4jI<0i!{=)K=`;bfRZvllMS_$l5i6V7T86q3WWH8#P?R(ej_ci zwZ!zGnJjFnJBEm{%sgy%@?avoX?d2+^6O#0n4gT67QX=hRUB)NceW zZ~Cb6?ZPY%zv=(*OWlI;#)5%XOJd5+?@WWjS@0o8>$xl#u^uAIEFM;%C4(qC4I+YK z33M(Tz*7Z?@ga6~E`%nvtTA3B!i(X=nAw%tSTpFZc?|KCoR`@vGNkStny`vZQ#rO( z27pVG^eGLH-5J6?p+gp2zP_)4o~y`)Pnw4)wM*AzQsr9!{_hT(X&JhiS=&(reVHsM_TF=x4FnWX_mZheg=lm@&# z@`oU!MiP)14pi%k!(eo?RGnkfXHg>yKZ!>5S-VOv)Z>p~Df1iDH;tBhHjWuYa|ijH zEu*L(ofu$~;XvC(ClMdlbshLT(Krji))-`mb*!GSzIbmqU|~6&p#f$f94M9rcUm%} zx?m6^%YBpr&_`02r63=*_$?x|$Cme)ZM#yW{ny-jDh+BoX~k0h3`#J|A_Pt6o&sq=J@&qVf*D{LZBY#7 z-DjrE1KmSGn)~to$m{BY$3qLP7A<3GQ-KE8W0!h|v_)N))-}OnXRRDv-l>n#$Y0me zj7J1ZrLsW+fv*CXbKesP{}`BenxU&`{cakwzbA5`i@xU}D=>~Z(IIh}3vS&L_qv-b zXumA{*tV~y@7C_q#Orl=4Y1M2=o-SJfG|oF&$ieLnBzOVSrBvtEZ%NP!{3hRw_g-Z zd+Z9Y-Aq*oT~$2B}8%~DT&Pj#P zlv)X|J?LH=+(|EV-l2O#Z+bn@Fu?>fnb3f-4ePz&K6ry^yde`=pa;CM8@&-5bPHm9FQ0sR2UpF5FBL|3~CIH-VKgL2#E;}iAxOecq4v_<$QbNokie- zvFn{f8=4m!idqeM2yo$OadaN%_0&f{TFxrmj)u1cOzC2BG+gmHvo~FW|7~6 zBX`UqX9ptZcO#DwqE2X|&HzytiG<(IL)y&32OFb$3Zr@vfM8l+e_{9&0QeXj4mTJD z=?X+?0z%&cQ4v8%G9W~A5UeW*Ap}IM5=CqtMS>VjN*Db~CYoZ9Z7(=_KQWr2D4KCF znt3mp6)}dLE`~EHk}4#II_cRoj1e4+5#EbDijE>G0!i)xab;qqlR&abvDi(qii@#W zba9w6aRBpJW!E@0^Emk={y2@>SnVbz5xRIGnfMRp@x~$Xrb%=hgYjH@@z#h5AL$b8 zWD*?A6Py;~Et2BhixNBs6TJ2k1YThLx+ee&0|5>38Ucb9f&psy86v?D@CYvfm6@G> z2-x(x1C?3bK^PRWser2N-Y^1oi&L?D<>fFH?TD4-`!Rox>1eOm&sWLVB zqbWQN`zwPr1>+eaen`Z!wS|*8fEaqcq1vM90_7apGz(Rz*^)Ok7OQvml=Bq^-J!&C z^;W}dQfiV;BfGDw58!>?Ta5WsbXv6+2%kDgZ@}+)5Xq2j$DS~uf13`mTO~e zEjK6Y-CQHx(@<% z;kqvh*Y3I>h7|3FKaQr^MgW0H;YQ#~=iQAUvOwBz!Ibf4-$H2f3%`ZFuHXF@#?nW- z8O||hwi&^*UAP%3aJ{=3B?3pc1(d)u-vR-si?*WWx%ReVl%?pt$Es_Ze~)`(QuIAu z*Lm-Iff+t(aIXE`9H12aUT&=BP>dkFp#?A>)=m~!0PRB$EQAJHSmYPlBwG}epvBHh z7i5ER7)pxgWDm+R>IsX>bI!GkD{{4$wwd8EErC_AujGK$(5wu=8fXy)>#7+N9qa0O zrWEU%WucU*+PT26vc{$8;j*T$*+kY22gT1DyHDeZDk?AEb1_JC&XrVr=m=gqsd|D# zIsG#DlY$Qurm}R6(yy>|kMlhzJSJszS$n}GrDt74!YgMzr1~%I`(7p-Rt=KnysjPs zN5-DCv-H2d7(s8BzZm7&S;?p=LlFrTv3__BoDfBqsGSgkj<}qZVpzR|kVHSKol#~M zbehr-Cgz;eVOMaP*K!}Nn|yH@;nn@ZRxPNKWT)nXgP&h6>mN1L^kp`?5{a~QCnTI z$bT`2t}l2pI-dS`xuhS}dbR%HMDS|EOLz(paQ~J6Zh0E-(PpK8?divAf>QgB>-i|~ z)7piX7Z@UU@IF=g3l!n0H-da76#l>$IKERKjPOht8bBwK_NgzyNG2TjKqs2psUI0i z7J@XO3oH55AK3>FsUlh^nBb!~L+cQ;!5c=xK3fLHmk9a*r*{3-Q`+Mn`clR`PUt!) zU+{PzHgqS>IjH!~LX^X^aS8yv^x9{klrrRaO<1Km3!9|LY}x3z*f%!$qZ4SDv)-4&maN4Bo`8F><(WSe{S=YAniiYnG(jbTHk zo@F)4BpviqRho_l(`w77i~ZH%U&sTEO!EID&;J_au_#J+#*N*}OLgAgE8uvnDH6#h zR4>lY>5JPhf~n#ImgJV7(U%m}WIrQM{q~YYS#^>S20h z%bE@;ozmJtRb=bRdhcS!#3Gx6qqx=249AUIR(f0jd4JVpI#h6~pFYEIYX=xY9XtKjv5QG)gLqFF(k@{C1;r*6Fy9L(RU02zV} zA{MgqKU4u>Z1z9tzv7`UfA(J=u;Rbje}Aij=l(lXSMo>yEnTcJn=by^$cti0Ya%1m@rAT`3bc~aLLIC-)<+A`l0-UWti#mV~e z<|i44CYb=8om}&i6{26zBs+B7=BBz#B^9LEl<%3QL9b5JNct(N?`C}>FD}UTpbn); zvEvQV&O(zR#LNSl@NF_DJ11+$rw7vS7v{#hX)qwv`C5n;6VA|=lwh@A7ME6`ag>zR zAvuYb7HOZy4u9l*lw(1tjUL%K|~!ge4+QdJP$k@+rB-2 z`TPm!{e&M=AfeJn0pipOjMX3HiUG zl#kgR$A6)e)+O@Klv3ASG7sg)ar^&ED5b?-UZP3yUj8p&&;0F4TkIDV<`?f5m)7s^ zmsIvWpQtLWowGP7YuqkAC~v*qKdATu$8h*;xmq4p4N#XHR*!HU9M()oF+6iNP0ORY z1(TAa`W5GcqlWdspTHh(dEB&{{|xMh^#{i-r+o}3e|Mtl*OOjZv4z67s#Jp^eSXrm zou_MC{me5eDR$a|q^s58w#gq%Lrje!SFS zlz(mI`A!x5QO$%1y0zmZpyr`wN`l?9c3P&TwRT29?Xh-NrCY#hK(=k<${)ikVsrQ) zL_uw#tj$A7>N4r*dfB$0@n*$w-uhD*!8quDujM?WqkhwJC1d0I7x5DAh^yUe z_Ngd8wcP$?m^Y&4cXWMYj>ZW;UP#(kAMf=Rrl}F%7G_y*dC*T5g}) z8%nh{F(#DFSxf1smdlaicy~D*DYD&X0F-c^|L|8WR}Ogpo0iij4*8|!jFq%M|9e`_ zEJc{)S<5*F@}}m5|EA@dql4m2=+(0E42$;)G6SD)T7-zv|5pJK3cV(R8sW#7y3b|;3@tINS#WUs` zTVF4+MUDPhc#lPzz(woyWw)E)BbP}JFynt+c(>cBF2}b!nL$i~Oy*a)=`2x@Ep`eEHQ6Nti!T=)(7uMF}efdkHVK3;y z$JTd-Qtpq}p3Y^UtCgU&txFh?FzBWq{x3ui^Z9n87i9l`Q=E@Xe;6&ly5g3!*WZeh z<_YT)^Y2DWkt&oJo51fzi<=awtjsT?1>s2ace(R7qK9-zRsT%%#PYKL7Z5%3k(+_^ z-wros$_Tc@{yf}BJc||^@rThu66?}U*%NaCllk{XOXt(@{}YUsrX(8}5HBbRD(eL( z*+Q(xMCYS6j;W-Bs(L}9-KY^L9rjEHlmQJ%56XnbK*G!l6!JII2|IRG&PLQK@DAnZfu68~nEo#{VsB@ZU5T)6YB3cc<0r3chlB zLmC5?T4vkZJ+n_vOd0e3G#FLsMAubzh@TBcbjZ%X7>o{2y8q`Ij9iZ6;)t5nsRz^pF$NL;G#HC^m_Pq>gYo|^Z17)bN~O&1Btft3CA@vL>_us!eit}q9o`S; zBd;<{Y5tJ;hYl@e2s2~j&_nY7SyQ^2ePdeopUC{O>m{p(zp+8o!zAaO)#6FFZslzQ zaiq(?Yf91-osCxBOKcOaj(l5+qKC5=JSN;1))?;GO6kf&DMZ`15(No1Uq!*{k;=Q! zdF6M9pJWw*TlJ)|_j7+`ewfe94;A{~WPZ7WptAo-7a?9C=MNV_XBzUqaS_(6$R^^} z|LWpnQ@;Mc#Kreq(udz@$xzZSYP302I1vwBE`uxUY9}#GZbz zO@;}VOBwxQezMvxDYuk}ncmI|s{VBG$pp#iT&slREa8#ZSp4 zH`jRnm#e`4;3B9VGd;Tq!ypx9VGJ58lV{2GvNDno*+cGM^V0qs=Jzia*`Jat2dwqF z>7uDSM&+MRI+bK`l{ll#J0*=ao#DkL6WJk)Gj|$PmW4+sv)OYbu8;3&Uu}ud)Fh z;C2du1gp_Q?gHRBbz3A_q-XdgI)rgN_Ih%bc-MPrz*Zqe6d4#7u%b$!OK6pG_wu>> z$hM1;kKpE;DnH@2AL7woo)>EcLKDIz^e0dE1a|1)hs*ho;Kv_3O4_n;XZj#84CJ~5 z3@rwfRF5~DKLQkUwMZDpsTaJ=x;O~{6A6vQ7o{ijdFw`2Bfegc&B5W{-dF z&?BDd^ok(vGH2AUWw|V4$N*6*VzjlRjU^fr_ z<2>@NCQYV5{?DnvGfghG-vQ`AYui1~Bmcny3g|{}s23=Q zkW>FYkIWc)YjGm2DtsTUZVN<~9R~fHM_!7my%kKL>}Rv<(tM9;^h17R*1U@)%M zB>UMsqWhq!O4lhHX8qF-jjqF#3n$q_${}HN$rVqo1LKsa)W7DoEc%;yM7z4L>hO+u z2eahMPnv8*KKvK+NX|sn@lW$e$08jsb84L90BxyjVH;k;Wl z6Lnv#nQak1BAjzsCiGS13DQLr{4sjV&`aefT2Cy;M8Y&IJMp)VQ_}>jk1SKVmi*Ck zED<2XX)QgYvm(Vuo{18ufKl88w86BQ2s30Dm)dvBU{^WOv7s%)Ov*<+Wuy!5k3x9=x5)fQJjX+-wL7L2LhQ}QLH!UwvD;j2S&J<(!9U%Cow+)3G)U|gbaWDtp$U{khB5D$J83uS9m*{fg* z9Y$I$ykHNo&9*z0CH_I~@Fh{*);GI3eJF8GI1*q>iQlS#P;wsiy{X5aU~3*htuP+5 z92me7o`qrx5Kqpm3`BQ(^%KcRvXOcCF0(MezmQBtOH|-DB%?+S=H>@rr7eKyRL??x zBAK~aFXK-n^FYDTo9box1IY&ZxSG!*>|W%+ZUFlEmd+v-nqQIJ4D<`#vC6wAQ>fHa z)Cv<;s~ZdCl9$Z#<#O1AfVB}9Kkx=+L$}nmvt`InOa~Ru<)Sn&y=kOhV4=3>`FX8S z(lxOS+6dam<*Gm5HVJBKq*wzo*?F-Hzwd8Y6iX0d!{u|~ttY^;R_o&Hhrn|`DT z_tauH_2>KM^Fx~D{&i)x5hc2YV&z8Vb;S;&2fAy;^X+$66}&K|27A655%&HSeuDGN z`N<1??~&p(9AA^1(E}snCM)CeN{uXC74mKHjDs0v%tYTuWzhSJc47|-6R=H>TY!vZ zT#ZF@3xF74AzSQJ!%|BxWB&WS`d1yC=&gxxw4hq&hP~!JQD5X35qf+kYS_U=AToQFai|K@>^{0(!)P2-_ThHxk=}@rK&$I{^OW2=n3?7k7mJ zq3i<=z)v}``?z-1O=aX8UdxYOd2QD4dD_j|u^)XrV^xtZBby}mKc3U4)xaQmqa*w3 z0f1t4bi&9MHUI6Pa%6REf&6!Ro!g-|W7Y8uBgReP^}_~eHHrQ5+iWSfBWBwJAuiuH zI9hJOqcWQVyt53Fe57ydoZt-8#qFbb4{pa`s**+@!c9f|{3kY7*;DaH&EmBFvv}?*Sl)fksOLZs6tqxI(4Hx#aw=93+|z8io2`tjD>YR(&|bcq zo1lz!UtI?2#q`WmK-L5NiLu`M^(-XtB2@7DT19cR%nv;|)sl({0Xp7HPWub?(1Ycn!Q2o?7*lU)kgtZ+iZW>>~aCVMheLc_K*hGMnge7ogNUl`wXh z&;PjBAjLDY+03_YHB$aMgAaMswbpNU#MPv^e2!?F#LLlkgW&dj;mlY$72tW)D7GuY zBOVrugLu5opeN09;oN$|U{)&9vUU&$b0#BF??Q@z|1f#e>B6uc;1TReJl-Y4b?O>> z^TxbQ5g19xbHQ%Z`#GK%Ybl=K5?hW@jBFgFQ%HO@*W542#mwsd39XvRQ}ED-Q^spS z+;5ECQoDxcdKDW~)m-4QX+CpSK?J_F{Th4;&*JIOzxawcsQtPw`0B_Ve7}wk#*ArU zemYM9KkT}&-cF-e{mznpPi;X!kV9Ym2bM&5`I9C2caX@ww2jKF2*Ca`we=4yiSnrP zIkjcL;8zN_UHT6!sjlgd)Rt_W#kiM%9&xF$Q|6o>f6LF*)=!p{alDnRc{p1C$JDs6 z9Dvw*%Xzfi@{=V!XD5b3;lXncC5fgVqC8Q5OKpA8BpGTw1Tl(ILRkhd-d?k+jTNeu zydz$y`JxIFf)d+wOW_@>Es-p>s94a$h5qrQp~A1!mT4CrLQj@uL<{V;(QKne5{Rf3 z%|mFNYZ?MAhvv7`Rxei42-Ci&2vp+NW%R=|)#y$HSZU;!LZFe`pQ)`(8B~ng5ZNc* z+%+X#pMFd)A{kNOJ48tC^OLY#xOM9?vb32P{?HGz@5T9#;Fd(NY-%?lhUxsjK%kA$KBumt(P>Ko*UHXVA=JwHj`eguQ(Lmi(Fkp3 z6CgB6t}iixKb`)VHggOYIaglgSS+7gn=` zu_%3JNtPO+A&*70wW0ll-(IzPU5T@M{PE46$~WSO+QY&es$DR;oX2 z%Mt=!8ZgjMZ+(z{(Q;WUBFnE{2heI5R-Ox(MZua>;9Lb(bcG6f&x0}bkQZQAv9?64 zN-iD5bW!|w+|VUgqw~33z((~$u)U8JU&RImzTm)sMzM;BSf65+p=WZG9k3XAaWi&C ztqJHpKq+EvnIW=3%rm*dUG#FiNXG~O;?3Miq>@lI?JyQ8-s$@1I6bd%fDUlfKqTDO zJ1l97G`7z{z$uJv!oF!yZzyn#nt+-W#JUniRK(B;owiAs{3=JdQzo31jn6$W#R_nY4Hm%Eu7=rf+oiLiZbh<~|-K~{zw zYInjQ^!?F88qMc%mEn1RvLyd+Bo2eaxrH_fZ79?Vs)=HTgfaBj{P}EN)!9dt zWPu04o(a;FFDI z`c_ea62Uhxy2sK*21Hpl=OFupH{oR_fqPtzQ+?K`$2@z8YF4ybv0@F5-W7d&DSR8G0Vm@J z;DBPUtXN89K)4u)R0q3W!=Gc8W-E9F5G)%VG3!*`*o>N^?mHGOP~@Vy_tF4=c%hFE zkN3`_)QCoIaY%cPiKMNRoV{dm%$=K_GAmQL zgX+gX_H-|M)gZ4X}PEyKdTeaDI@pmTo+u<2isKl7U1y*6!PbP{r$tPm9E2WE| zpmxt1EaZI?UO$XPRpPX?n~@!%sOaI(XtkN}3cF%NcN4*iwb}TiyHfmjlfY+|M5C}L zt8@21czX-Js`hpLn{JTqmQF#W6oE;1gLFtE9V#f&4Nf|xJEcnykS^&`Qo0*N;y)(f zQrF&VpZJ{Tc@yIvzbn4iP+WgSwr9kWoFE!Ai3~t2l3Q0!bk%a$Cs{Io{$ zhW(4l-It_)Y8eHJ&{CAoerCJib96{e?7W)f$fV}UZW4}&Z}H+NZ?n~f_X?ZZqV8MG z^wyTI+-9q3W!VTg%qj}89|-4VJ?%-B`>~6kC`H*)d~JOYTusVB5g5ZXlUh43!d+W_ zck4qS+3Kv8`}tvkuS`$k^sDv%C0p(5cjL#ym4Ex+W~=?D?|THn<#kdA-Day-CxW@h zOcidj)$8*$3t)mRq)c59xm2XPG`G~CwS0t2u#VK(p;5FFXB=6i#rIElV>KSPnn<-= zVB^GK5m^kx(WdcbywJpeqSd{uc^P4aL)%4{Xs^|w<>8Wmw<>Ju5S6H=#{@l?h9t#- z^Kh!vM^rNOs4FJ6`yzHtHFBA2RrM8y!RKu8@5)MPF{Y|(LUyKvOyapVSEiOAJ$KiU zDB+?EFr4@lU@g8-Ub1p4EtXEuCbMo*g@Wx1#D@BquG$WjsTT!TJYZOlQ)U%!0j|D7 z^xaZi@3AVIur=2gYT>zL)h!8ZB-QO2mO+xO26&4!rGnR>Q6&LW2j+o7zR4c_LWFp& zyk=M^Kg<>mxO6N{9r(W{o-&$!}j86!mQ-t z`0MkXi<7y;X}8nGSli3*t2rf?XPec4D!bdk4pC(l)YtBe8VP=h#2FC;VI=mMqsIl?J<#Kaxb& z|9Pd;FrL4txU;`2Iy@f=bM@wwTRbZZR}@$4sUL4FWmKyswx*g(NL=g12Nup(N`ZF@ zRx_0DVKJYtcRdF!5U@q81k=aQ15>Nw_v_?Bala4aJ5nQuQ0`GfN5zWFEVV;F7@&Fz zCq?)}vJ-@F&BGu(v2=P>Oeeo2|Rgv#tg;ySG(|mp*otezwm?JPBf2H7#0hMw!VkS5)HSm(y zDFt3^RTy!q&yNl(6(cm4{)&Sxs5md3upw9cbG%ZR4VNGp{F=l!BISrMToYQcHL0t3 z<(T4;bn?(VNfS%ug#3|gwl+ptv+m)9%P`9JkSdb5M?G>h>za~$Q2r0U+LpgaOm}w-r#tq<5aX680Cs-VR>9WjD~M6 z;U?z*KCbvu!EC94+6R&fsg!40hpK@8GR1j@{iZ4!>n={&m#@dNyvavJfnLlyZ_ezg z5v&O8gL`z)m~yl}lL^6^1Y>FoJ*#U&NBR{Jh5;mTjDL~DvCqwRV_W`RMd$Z3@^30S z2ZjYcg6IfaQomPpyhKud2Ib2w8;G3$iU@CttDF9e2-DT0G)y?>>eSo><#+m6ks=92 zAI=re-k5tYc7;BLUdOuj$K(j1DQGrJW0tPZNYQ&;2^wn*@p&YVijDF2PyJ(36?Z>z zltE%$iTkTabOq5GxyAR;+c_uJXUukYi*8`GxXjQhk zF3lEnW=MSx%?umf92|)MS4Bs|@RUMW}4}Soe+^tSD8cbkZd{~D;tI* z|4C-JJW6aH%yb4`0c+ls7K22lG)-<{B{^Jy-Y3r}=BNw2);x7=$%p~>Nh)n{fhKxq zxIfDhv2JS8CBGunH^T~Y^)fxK%|gOSi!Jr~Vyy@g0c#mds8l9gQ6(i!X~o*N;_HQy zG)z4abuU2=!^>x-7g6K2cqg+OIb!C!`bsLjowMQER{Ak|cfkET zKXV5P_9{=Y>jBkVi5SvTRRhVBZ6XH{x%MclD?YvCf_Ve+hyw_-fXGRV>i#pVbP}sB?PSPI#n+5Z5fG>iFd8Q{%%y<=0sHma_l1zpR$n(j);6cd! zfMl}01*Pk~RBPjQz_q!mkw$KAW2?Vi7gwa6eYSC(rv%Q(b*!u2Med62Kb#Rdr6iTL ziR&}s&wdG0pVK1qO~uSt(BU3!DtODUts4FzYp>pi8}SA#2okLG3P0e$n>gLZg-Es59rH@^8` z2R!zGGXhBBrfoj|_}E)O`#~?ZDuqcO(yfnI9f!->2(QGrNImJn(9Ss)7GkP8j5plb zKJKaX#QFmnvBrW}xlcId^Nkp3A?B-^QL4$sw<(3xV%w*Z zR0Oqj*vk76oM}dK16g2xBhCQF!+>;_RRX2g`z|x3G`=V<(gfJ8cDSXaDwmxp>iYwc z0?k>h(>(W7_;#7ozGmI?=VR90Ui52yl+F=(D~VSiC&v)|IwLQ!T$Lgd=g@L^JEZy@ zxbGXFz3L>^j*@V!J9xJuoZ#EY2j$x07`yes>=9MOl|nomj>GeojK?XA3W6LyR9B>{ zK{V=Et-iF{_=Y2sxMx{XT1x`*&9b7ZU0A`&QNkO8#&QwdTv`}HG50l}F4L`J$sQeK z^n|0DxmMi|a6(zFGS-Fd)vK|$X#cSSNq)ry>`c6vB`9}Cq-R03 zgoZ1>ch5i~C?PUs-k7w6FhGDJ{a#_6IT>tIi26tB668%|n2>Lh43U;&aG^Fj^I^saW$b0dnfKnMr7BL zIOh-f5FpY-6ecFm84>$|pOz=S>(2eMsCT3$OsKUyq!{)w9K9xYtR|baj~!x#A1&XD z{N8OY?`V9MZ+ZgH+G`D)Ympc~&Z=4Uyx-Un&vXxX?5VUBKpuNJ5!1pO#RGoDWT`ms z>c{ejDKfDMGJbpP@${|9yPXZsZ|za;paGA)vyoi+%6yH!^&3gt`2dr3gGFpey|Vv7 z23e66cQjgm1468n_f}mambSc;0QaPM(WdDvKB%8Axio`}zF0ke%2t}YiZOy%d8fUX zXfiJUMZ=cEPTi)H0fRtcVb?!V>T2 zI}y^s{VzH|#S_~G-`f7m4zBYmOA$qVvK%BDTGQ7}XU_PugZrwipm{Usrh_|Xj2IO} zdQp1>9Qdo4h!@qGl-&(HSNMV+A6|AW4W`iZ>NU6>ug#ZGOz2&@o$c*?CU~NM_4@KV zbdA0%>@oe^8#ron1Fz!;t0~@yAYgJ4SNzGm558%@ydSCyA*DZs>l1?jnlSTpFWPio zBe6nJaX+Cs3;OF0ZiXe)*V_)R?xAEtaQ~j(fpmbn6{TF#EFp!7pm)O2L|1Uk#`z$c!9q9qE}f$6OV02TOz4gLun)y* zg?9Sr1@l}1qRt)RTz_M^l z%aL{St4gHU{O#?6t~yk?ubB^37MG-<&}lh{dJ@}^uzKO>tCMqAnf?3DswXccBlGCOkK>r#TW;eaML#Gp($T$lt1>6JM-c_?ZJ}C zXpz`7cwS(95ht`2YY#R_w_?_mQEl&9Ko8xIK?o7aPt^t-QGyMoX=@H8~lPa)bpiZ z>fhHf|H61nm`^*S z^r~Au&R+ogsV!=L&I7AzBu(qLm*HwN`K9^oTbA|>yqExprFI~+*eOS5dY#U)Homgh zrTX^3w_&>^63px;oP1c7D{&p)5LqcZY1j=dd9@;=ud{zo?WnKBJqPuPNa%R<548Xt zSlKxkk_mQe;!RJ2-Z_N32xdA@vb~R(3$JXtTM*lKeN^g1J8K-Fjz!Y_cpia!k3w2g z8`6zC+|X%Y2(!1HdT z2WR~BydCOda<0`}gR0`dPn$!Z;TfHb0X28!MG08;VL;6tKkKYH4*5&X4P9K20@U1vwuD7Z_6+~ zrvGSuH_GFUS5;-T?og-LCWSS5lTqz-7fHfZoF^XrT)kCZdmn)m74>9+JAH4 zfBcw*y2GorttOVQr8L(AGSp0%zGr>+kvyF4a;fRLowU6(TT^k(bYY(T!!YWvWD*(H z%q<@S@4)p@S#=mOSj9U$o37AYwt1QR7^MA8s`WKSY;6J*4-^LGq8q+cVLzW*L|G^t z@}x>%Nd&A(xQfrw})JLfMnprSqMy`*dV@0C~(Rseg-<`GWhXuNhT< zezRm`NLgi-kv!|n6OD&3X}RCt5;k&s;68+pZGvJ#5xpx+LsvlqR)`LdcuS=uWn!x_ zCTeIZWg0~rB`c?-7%OCrOedz$Pa`a=!^MRlFK0O#9IOG4iT_YHJ|5e*x)9G7WXzA( z1;v-(v?%0hbGYOkN+vyE;)X(yqW~87X=V7j_I)J%N2MpGAtxi)S0mvVZ(cN!CQ}OJ zGIkINX1Tc1R7}7d?8Yx#VoX)URK{Wihnj)ZETtk%7jq?=5WZj+3vvd7N!abD)Y2*J z9U_Xb<(iCDX0t3QU)DJ+S_m66pibc5E9Laa!R>ZcO@T#2O~i%|9mcJCG+!{Cvfo~j zTO#XVziNWmCpkoTq3pCNHgx=AFu@0;lTe4Ebgo!hsf3F4VL8lq&kxVy(GnD?#Ij7s z`!(jsPSG}v_-?A#AFz7rUrXE>7TMrzWLo`KVbiM81t@G@{bONM zUS$XtO#nM!)n%!0G0E!4MLK4d#$+YaOl(Ke1tHpXtBWZ)Ys|ZlB>(}lO2FUgGM>kofG#N`A-IjvGgjnq;M+XdoQz3QKsDf%@_#266k|o zh$OK-fgSCm{s3m61**}L~`{oq|;Hn+gbK5N&5zXXPagQQj29RBgH zeiuMs*bOmbsAv4_I(3kI`XMObH16uN``JNE=lP0m2oI)S8GR~DQ4bbQ_kdp&qUs=v zBpaD)<1-+0N0=oSi1PMA6!Q)VIC~B7*-h_ts8sC#WHS%6UARHTWp+G-dDsQiy6)+ zBwS7I)zjj!K}A6{q74%W6%nvO^)j!Me3p;Vaa3i>i?Gsxif`S?`rG7|c&G`!L&5Wo z`u_ASXW3QVVoNNNn-17@s2d)5;1d1zz?~!b?ScDmAX9%oFy2+z?V`Lm*}aKe_EWuG zjyVcm4?Nd#ry^HBdkTkRsA)y5DS1kzu|-cstq(&hmCBE5MQ@B28dUpj@gEmVlp7Bw z$o04sX=m8!|IZ;8W}lTF|Ab6Qfu#HDDj^E?-ww=d(|u{=8zR6}mGli{3a>2qcgU16 z&kO`ImGb(#5#{2)K&J4%%>Nfg=*fl1zky5)(8npfLZLbI zdo0f+8MvB-+VZ(9Mc(qOTY<|L&XfdUA8la1o2WXpG-)JtGOs{}7Y>hcGS!}_kd!CN ztzW*mE z$r6xlK$QtY0WMDwYToO~p{D>5AlTaMYMe*^&5ppp7h701fC%t|^aVf!z@Qu>XT40H z4g-h)E)n_=Bea_P`OjiW#RH_b-bw!SLwQ*qD|dQ%Rfk!SR%R8{~Rl*yvL=VI)kEy}+KrgJZSt~D%sgu4n>duMN}7uD&YzSqvL+|4H86h&sW zQr!6(PSq`mYLq*o-8&WIsYVhK6lH9_`ug4GnhqBkX3*uCCy?(#X`z zPI{63x0rswf!U;?`EkEn^`{YvT&6w*gt}$3Sb?~bUa~`MBM|D|=%g{gxHdvxsOR;X zM);fd192tbz?dpSj8Idt*6cp~Q7hWWkpA{MK*9cbU;xe@en-@1NY10KgQl04n1&0@ zIRYnLR|=QUN`VKi`F057fEOgLM5|bU5jWuXx46>Z9=ODEZcid1ai!PkM*`8;2PRL} zjkhs=>M)zPFHin}fSB&c_U6DykE8=esH9xKR3u=8>Y3(24or^pX#TAcdbNKi*9I^` z(Kq627yu)5lwD6?V`eT-y>;ywrJ%LddJP|xdG}HAi;IAVclH}U%-Ep0A0<47{Zb<{ z{q}uc0i%(jM1>sNn7!P=3?fA^^O0OPr9~D?1XBLr<4U=5MV1;pQ)9oym7HRBG?HkM zw5=2AW)?b)8qp*BX!ggT8LFu4(b&Aty1{H{KCs>B!^R{F?W^Jzp<}FAgJs$o(+)rc z&v(YYnS@gAkx#fkt!>B$pP8Cm4bf*R1R(Lz(eM{14X0|$dWaD@m&+#~*JRlo-iR4^ z5{fpJ-&(2Hxmh^i5Rv{mM1Rr_|593i(GLH9i2kGjzCo z;r95?~3L!qG@IaJXGtxA*eLjC8-WC<=7U-Im$$5`vDcD{UcM4T1)z_a_UB^*b? z=27jz(&t2x6t)J}&5id&%!P$NX@@)J8wM}ES5UL*YupXoJa-UVQ*0X_yZ%_;D<9uU z7JPNJ4=p+S8g5x*&K>bMcJ2)-!o-{hf_Olx4~lYUsxO8S(!39;`oz31g(=~JA9)N? zdLVVWETI)k29`mYqzP9b zCZdf{Vd`3pmN!Dqicxlu%8FGt)g%>0$5mZc^g*YTauT?v9cH)cCW#cSF1&MDW}HjD zv!9oiau+5)J(YERawY8zHF0jbH>Vau+6$1Sd3qF^mPJPF;~=o86NEYT{}Gx-%Sxe^ zdyg<(Xg%QtTit>K%Fc)U#)pHo`|FFJg?mCZpy77-121U$3@FXX{EV%0)X54rA2qB6kU7gsS?eJeyt z84WKI^pvDkxKx|VttO0pBt{kLUL*DlZdT(y)CHl>c`)+>cJOfWC)Hrt0Fj=j8&c85 zk*lO~yXQj2FML|*(2i`v&qm)?m+Yew>0_R!s{3(X5YO)@j>gbOT}a&X_5yjBqORMw zlAnADIA?-s^v;!e!#hXB#%{0Kwxma-S^qQ09&mkL7gR^-s2%~ycMOiyc=3@b4F(<=o2);yb^1%5% zCq#(IOW-Pj{22s;i&&P8>H_Z%3;k`rCH<3^k6o~{JvGS1Kb&(p*Bh2WS73wzn}%O3 z1peiO@Bk8a_a29drtnnlB_W6JKse=#ia3eW)A~$nn&;VPDFjdHq%_qWB3|$I|r-X|4;LTk_QuQ1|}P3@^IW#l~m?se7e zv;~ZmYED1d@50Ve!c0X94Ll@PFL0-GN@jZ0$%HT@8QzJ*T3Np;!lQ-F9TpUa{E}Wm zV*O!)DlQ8aZJx9ojJ!{UDh-xFfQW|laQ^8o)y8`yNs2O+u=nq?g^GeCb%#`f(H`8q zbZBLQ8Dt~4NSl-#t43}Pk)%@jZ6XJ~;7Nz{bt1URpgqJ8BSes#Jx&o-Za*6bRgiV2BCF93d7MAb2T z6X-b%O;@@yqChlIg1$1c62T+;=7)MKNsLy5>F|_S{EIHhV!b3tM(kbvG0*%2Bp>o% zKdJ-oRxkG^TM!*+`M-y)9hmNNBm#kE#baY0M(ZR-bz~swjR)sF2*gE%(OMq$4TK@e zr$c}Vgho55&-<`BHzzZDmS2%aK$I!8xIwoub@CC)-L&0{WDZ7Us0m5_z1PbA4E*zu zCVt)M5BM8%kld`q;9WnS-g$MHEK!}wp2=|fg#!7Xl-1zjM zpQG5I@F^BW1<)?y^z%IaW)!W_IZ+-Y6uvn(f26D{VY>gq(hQSS=4IKj9j6l8@*p#i zn+5(~%5B!~c|B3=6{_M)DD`cFK7D@G7r$itB1#g>^XYs4i~jOtNN)DW_s<^xHaFX_ zK$WTTU|tGmtUm_G&C&<1$w91C<@>oM-3>|#Rl`LQ6?twIU)8EB%Zh<^5q%XoRlinI zv(;|VZ~~lir^|Q~26ve#>!uOOkBLtCsvNhr`iEj@~Heb;dl4_O?bVx`Q!5=6r$hb4@!>|6Z8e`8UctwVe|3`w@xfiwtiR zYP&W1_hahMm+nchjj@nBmc6WBM*LR#(cZns@qjdzULc_8ja~!mX;PY~gxQ)+vXk}q zUNbGLItD5Rl&}hs^?9RNmQowpk7)@T4Vj!1rD7jF*sV7|==2!7gdN);M^NgCbh5|I z9M@U7Hetwq6`HU)X(Xw8LGY#E8PeW2{~ZUxTLQEGv`DJ!N7CFm!^^(sir%Q=H6%XRw*+QG8C)h40~LxO zv(J7s{i9UcDnicbPoSe#)BPf7X!HZv+pE$wk6FbsM0pykzbX7UVo))L`+h*~EH z_EuWFH6A3}cuXS<#T8{7`RKbuy9$Dyg`PJ^U2RDo*|iN>O0O6%%PAwb9mBy&+8Ol; zegC9h9IKe;QZg$o*vINJDt;giW)w#$!DYT{CA}4yC{E&SzG}No$X*mBwhxuvXh4wB zIDtxl3(cyKv>ihPyLkI|oV0|;BSyj*oL5ZDPZ(`7h2#=g7u$uZ&hzkXgzP;B401R| zK1;e_XXZ;Z_2;vIO8MPJ3gEwY>lafn8st`d?Z!7Lo%UlcHtxYNHmIElJ;n2R2Q#r< zBkJj97?0`KJypNETwv?|>au*qK^ zN|=GHk3NlL)9jDx^f=o|$3<5-i&#JUax_`|fP~H+=lzIHxy!|)2QLLPj>I!ix1M6_8r!fz!BR&|_vJ zVz-q>vvc%}GEu%$W3ExYOrDsSLYA&y-!W+zh^aZzBdkJDa|Kt@LhphmFlz^o|51DY6$IUrmjyCE>6QVXK6p?ly!2+R`+l&p%cC`S5T zqj7>zigUf-gbk52Rw=O`ullluq`{lSfe3*f(k{^U z+=%ou5*}^LXKFEy2(o&Z_6Nn8p;*u~qHy0aK|_O#EvPcoTiEFg(QTgovP8ad6=M77 zoQ_;&#-QUkY)NX-=ixL74@JH5(mb%42+?TURy(keDaB9`iG0K5^SZTATJ3z#gXp4L z>hIVO#YD(p`$j~isuwZ3@t01^c?e;u!<3t*l`aNkD)N9XPw?4;!K+KONN-uV==aK{qBpd}bv9At zv_H1IMYqKLq-XZ>4EQH$H*$yF`~;12+JwYyq0z$u zG@ci!0rz*5ESf(2gD}-Yna7IcR8ej8CYUp3-Ae78(Uq@Em~AI}blV-G%h8rO-e~sf za685o6)tnTu)=r{2${3$`b#M^jRWg$-Ck|xl2uIaBVety&CX~L*_?=Sb)KS`_{ z8Ko$ckDUp3r+YTrn<$Mbqxwh}icE`VZaSEneot^(Pn7L^_p5e}PllPlLp1D~lx0XL<6a+Z!OFrfU7U~7} zK478BT=iijemFhw5A_Z+xEG<5)zv2w^|tYHeCK^hkE*^-s=Lp5C@z%h$4Rq^H!ZYH znz&eUo&(NMm=7p*62PJ<3Rsu^DY~6}y!c)S@;u^_(3e~&njF5TxY#5?8U~`-aB7A| zl-X);HL`MFM0xX!#U-&L>gEoH%2uv|p?s&yl?9y`SCd%z!$zgVw|+EiP?kYBl??GuC5~ z4ZQ7l8b6D7V>X;4Knl4X#|n9OEIieU&6+iVBTh2%41{x6bx)W;Ms}|q-!TLrr$1-e z@4zZqrjs-)UfdPd&^k;>r|n20;*)7x)okZn`5Gx0lb=Zu&RG=4>DC~<|>TeQQPc)t< zt15g(#j6_>m0Y`e*p%dmI1@Rmf%RB5&zwZGV(vHQZHLAHGP}vkwb;1RAM(Tu0GKy(8%IozWZdUiWyKa71nfbBZhf>naem)R6gVpOsML>74q+Y^fk@Kzd z^7J{IdQ_f`L6?+xs!z03=v$9%S3EfS8X`DXI(uBMSa`nuraq^8-n5@6K%IUOg`VIy z2h37Km}Q(jHLz5h4-I>jRq@i&#C$k2NgMB#w~%tO`;twj-MR8#jpqLj!$+8jg9QOF zX(0rlc&6jr&M5pdfa%lS)^thxP&=AQwW%k#y={A8K!i(THCMu(w)Cy)BV004 zaBzSQ3M@__E9qk&99ks5qQ1P;(xwNZnYdy*ZChy1oGxYI(vbia7`lCDoI-A{9vhNf^&n(T{F~67|CD z=?nu9;Tqw4_2D|gwUkx2{2s?To< z_s^=&KM4yuE7Ie2Q%A)tv|)66Cs#@?n>l_~V?!*52?*A?*i}*hk7x?>p&adx2e??ZAi3}XB zR3-Ilch;ZtIRdJcAo7M*v(!Bsv$SOIJEil zx$*7Cf~d=caKu!x5tD2okj_0-1I0ab(H;+ZvKlpS^fkn^Cz1x-DnvM%N2*=~6QmYH8J>X?F>&<@$-*nL~t)#=an|mjMGIjn_3k^&GLA^h10yO!3{DM z5;7txY3r5^Ika2LbRrLI)#TzmNUB`S{xQfti{Y^?;w%qm zE{xrfHCw;F%shbKxttl;2sKV;EH<&-%C50T>|@)6CS#)b7LFEes0CdEEfE{{!hEki z75d&_G|Jt@?)UJ4W^}4Yo1J^zq0Z)TJln4rGrfU%7|g(k*N9w!$av#v5|Jx=7?Z-9%@SkcW$~ zqVSO~dA<^&ijqb8^E8GJKK3?o67zd#^IgJ?Lhbv~nGNvWf9{EPwmOP&NU@fy5q-A) zp)!DHC|Gf72$- zjt7I1M=hF28Ny8aOIgDd-6WG{ZjSffh8rDfObnPfgLixi@6HQ3;m4h%0nR2`Xe%#v zA>lQM;ij8&`*=J3--7obxT-;WoL3p7E0Pl2?Mkno7hXqqf#}RzkH3NUZb1x?=nN3u z)!P5JAcmjOncpj(|A4FdT~NkhBXZ4-3()|-dDY`P^i^Hhyo%E8y%p4iQ@}H>xITw= zMZr~?fSum1{zEJq+OD7+p{9d=z2CP?kf1Q25Mh^o{sjO2F$A{6;9&y(wk7uKV;JL< z^)Fju-`}Gv_#-30e3!b%@cWk7U5wCQ?%H2J!Q7_U+9qOkOwQmfsTdgTtpDDY317)a z?<=O?`tH+{Gs44}zbRQZagzpHlQn-SStjXhypR4WDt@0>fK9t|N;?hdF?@>Xh9It2 zVQo;aNcE=YmUe(GvDq^#$d;IO%-gq>0@qt&9sD0H-o&qLaeuYG!gBiTjx=VX??v7f zJ?^Ch-wAXSiSbjtk!#bNbTQdR)AXtzE%gXh_tK|<=+${ug78Ww!e5})=B9$o(eH%^ z@nWkRs3GS2Qwd``9i`a_a{74CJyWE88isxpKp29Ct~n5qv1P7^sbpPE{!o?<&qyRg zM|4R>-9<_>UO$v~AkMTd6JAqA$2dv~$phCzgQSWPhuPJ}WC;dow0t5IUdk{>Sl?81 zRYCcfXfS;@ZA~!_URWw30p4Wrv#=MPYKF3m0~KZ>6!i$XPFPSoMqXZ(D5Gd4+LbY) zT6&|?iijlCOXYM*LuuuVB7~k;I#@}|z7y=kPC;9cF4@pR|#As2{^`ehs*r?~%fj7`vmIol5&p_YZ zt@72>00Ocu*I+A^9C%QQV#{e*k-doPh0xOzHZhzIEtXNGVD80nL{Dq*1bnz0coH^^ z6+AWUyLCLF_Rw+_R7gpBGCj@s@VTtOohzrxSsmw~lexFZ_f%#@rL4Y)u;FZ+A-8^ zykceM;Z7Co=fmv+eY2N)o!V9>64=HLib)t)51Wc~SyRrBD6Eyjv8kPo z+(oqOc{eagPWg~$npRAF%=>yvOkJ)}d=yJla!f3XL+ze7Lv6?CKveDU>we!f@A*|( z36YV}U0&{$$rwnm9swvfvkBRPyVe;A0En<)C!S#f2DX^E}EgjLP_5 z?Ako-1}XJfBngo@#o1kyC{0Aa5g~%bxr<9f?SPMAGp_{4Sa`^DuBXDMOQJ2g#lXjK zQQpt2d6sGr?5k=-jU3o1&NLJr@+y<&E~Bt8@G(^Tare%ffZwPz()5-?RCu`W#O1p% zWdiM>7+A7c=v5mvr-o?5pCL2LIbXYLp;AjFyzyA?iq_&Xyt>#tyJUk|9ND6sjPEPp z_xQ&Z#E2BoNu<_%8qr;hA3mHYc!ASr=OCMS47DO=xkmkX1N+?>NPW|@z62my3o9XeX+(=4RP1-?y2tQ zi;b*@KM$;=vlS?S`~)ZVwdP}R80nq>eRuLU(;c`#+zV+)-<{7N(s%zs>_R4)7F{(SSHbXs z_4YtrQ%7UZBM*!0>&y#2m!UKQeo~Q=8-Ro4dv) z!-g~68pAoo*RGQU@P|016^N^%+Yhs9qb=lZwJ5`@Dsm|RDh+)Wy0qT2e7Qc$(0ACM z-`hAQ|0p!$8P|#^0+cLk>`C1pQyyCv5AJ*aa@S(}HcbI{Z6FMA*QVpLZ6c;7T)NZC z-{H||bbk4YQC-tvy{;CiO*{9vx=xdB5vPI=G_~R(eZQ}WwqJ&E@p92Yo#KpRoc<|VrGK0b^ z8p_|A3MfE+XBp;q?wzpL2?E`tT<|SXhruqbNgrWL=|6d8$YrBKiCllIl{%T#-);up ztd+8^2BjC}QP~^)wQzIv!s(}1=3=cDP>5izrd?2UvzAt0Rw(sRc6R@UsPn7@MRgO? zQ=%PK8XYPXw{xKukt4$=qy|FN+0ioXw4pSJ$svm%!aQMbuFgWYD7a^!&!;%!p7u2 z*K4IDRGnZ0L|P80msnH`$pNG<5g}`(HPK%5CIQ%i1mqROB3$^!siv8#C*iET9PRNT zkhN0vPptoOtyEmf=zqUf`e#$p>req`N?uP(F^%Nr-%d-R5EsA>XfaD2O>|?4!=B#V zC?VDIQ3t~#lcW|m(FJFgGJWp`3-&WHTjwe>+ykbi`YY!3I!!mWq^8MZzEv+$cWv0T z#-Li&tYgf{$o3K&Th}{s)(q7iE|X+6$c8!;G~TYIZDQ6V90U#u?z#KEPdlY!fvlx% zW{aU~L#Cz7676p|=NqqOuQvlZ^(uxe_q(q*19ci?e~oDT=Y^XXDD{6G6G*~(dZaLA z1{o7j$iBD-nU>=5;YJlWnFg8)ua{=rAw(UwCAsTqshD{#*kWK>3bymbU(-^2DPguZ z3paK0?+BQc*D?tD*w$%ElYwa|l3th1iu-uhTW={W1{P~NzCPWFd0Q|R-}H3bb}yqI z5+v1T6b6Vo`ad>@{zlZfK_UDi>af!tsW9$b-f+(6z65+6-4|*7aS4T%3PB;j5QEKG zh$XKu0(ciVFrPTCjj@uOKcJyB@xtvLgSii^l@?3AA^){j`nMn{RdqAbU(YR(XQS`^ zzn@Y4#l5p^p~U`^bB?T5dY`zfQ@HF2CL4BZFf4S2P%AGKXM%mOIgpI3j|2WN_JXZH zqyx{b4*vWS?H7+E$9aNBX&uE08p5RXeQZpQxf3b{qu7xuZt{vKS~If z`i7{(>6HKKmV2kHTK%td;NPEH2k{9Tvn{E7be!&@8Wm-95AtwjgvlKe)q<9)nuus| z1>k&e)6@hyi89VkjrBIqhnW$)N}St=W!6AaJUf%xsdJ>ZPzk4!7IvHz?(0&C2ulOG z$F&7M3whktj;m2~64*h~PEr}tUqJly;=y`OLTF!*3eNZ54q3F4JBqAIG`EUH7at0E z;!4WuORJO{E@mU{F|gq<_IUi(Oh*NFB^Lj2QB3=`nf~9+Oa7KkSOsY?(T=HF{^E>6 zHd=3*VV!XB@vgV>7Ec*5L)F4m5Vm+D-UK(zaGk~VM(d8`hZlTR(MI;$Eln6$%&ME! zkY-pl0%21>9h6Tjx*qqr9j8YxL9;lyTwR4lo+JbIm=xW{`YQi8Ai0txQFNg24Hhpa;r;wU3ruS3hj>Hq(<4vm~7U=(9PCwY~0y$;Ps z5zi5{ybM`~rhjwE07tG~{dH}{?ql5HoMvyA=3p`+{OL-%$#ItwQ3xBKSc0dxrG>Aj zxB)ngQ_a;vA?p1h6YH#-x~Ebv@h|0izN zBWo3$b8Cep_3QB#bgp4NH=V-ghOu(RlgrDD1I^~utdaOglSW{B8!KdIV9IaHF3WP` zpPONjDZgRH1L0VbsF%WtI3q91{e4 z^oP8RQ^%8Ckq!Ud(M4}p1GB`-uzp6OYRi$qt~2b5aR*`zJ*iKsWoI*!bq?sE}f7K?wRr8 zfNd(c9Z$D3lr6sl>I0Gl8Zwk1tmbE^fhQ7ZOM$Wt_G%Ooi@C!1lEK7z=|cO5;v)QI z1_6(zL5s(o(lDEr2;bq!;6Zs9$Bbdp2w@rHhWlOT(^5pV{d$2?d~RJ1CY-oKmpMa$5H zo^X{Ooxx{>(GEumss3xRp5DWS@hU;i4lMgE-1L)a;|*2ur8rq!>bnM-m^(IQOST49 zi3UY==(lZE1=%JSk0@3JM3M@LY~6y`Xea&6qMIQ#{ip~797E5lOt6u~+a53qEb;Eu zv-`2{4zCyM6~H6Q`dKt~M(;DBaeNY4>s-y91zXQyN4*B{)v#y`L?j6-C>(pxN4lSl zm(oKP>pR0)3+A~9>2aRzeP+}pZIyny{6N)DX!BXB8We*TWU;-eXz&`mY23E#tUV&9EfPg>^K@3w&ogTXtLHsT@ zTv{Y#vEHcQLWELI4h^uP^o?;BB`zO0%|W42N12InZXKF{7>g``#riR|uYw-vxb%1? z99U*%wB*rRkc9{fBgJ&u0ro@|p*HrSd%NGnTJXkJgh@LOS3u(1SDJHBCN>bs9ls4( z#oMqGp5W^1Co#N|Mab3-U2v2McZ5;2T~VQHVnjD&UeqbP44FuM&{!sa;(A_`u60b` z78}u~7MK^csce}(-3C;qU}mD{Qw6|61RJCEe_G7_^PBWPTRB7@Vn@928W!RTb?On4 zB)M5RJPKCAfcrA4^Bnzwn5QeyR>i*v9*8&2x!7i?QpyHa4!zYBfPX+aMH*4I!;0xw z%vTl9XE7e2pVoMN8=aa9n8iP8l%d~#q3g@@_4HemerRNPwAoLpBEAB~^~xdtlkk+^ zze($PpZ}pu^eSoA0I-||u!p(X#-)=jCE z#CiJl){Qutk11s91|qq0aB#nxCxQF}PGK2K*FbPs_o}ShtY0~OEr9ud%zbw})%_dy zaco&x*&$>`l2XYbWM-2+vS$O4%9a(!o@H;!o*9+QtWZ`WA}c9bh3E4nf%1Uq_Zm_ zVs8%!c_05|)oL~L_6d85dI+ReHGQU(c_BHv@SX|{^O=bisUw|0t%_Q;YC~#OASTK{ zU`ua`iGcU<0iag>wU|hi!cDX}pEtzr-qkai(sY#dpUcA-Mzu3#Y0UP;8l`cem$AP< zO60oiF1SC~6K%r!`&K`P1GD)%L>mM}Clrzpe#8WPw5~^!8-f_V!}_}-%A-jdVg4KI zXzzRXk3EbfnOz%mR33hKpFfo22X4y|ErQ;acHOo(7)A(FUzU}ImPwbPj*POUROyb5 ztz$NPdG$-=1-Hv0B^K%Sm;2CWiHY!O!^3Me(HYx|jYF;uwLta&&&!XQJkYJWO(3&q zWl#jS7NlqBE8JFZ3g|MFcuuuVMixmHqPrfW=&cu!Zh1^Zcw$q%nf!3jsVJKphMR|u zpL{29>#!ikc9|?iW3SsZuX6iyapj z^Sg@9oiQ3^6k(nw5{5QR11pz0`cg#e5qp}xv7A&exm2~`vjgb(%W9$mie4~ToqDoM zq8dy^Z=(YQrr11137N(H-RSw>UBouAJ4p3)?V2IF+ThzZa=90F@6Jg&8Yw5CUpcHm zhV^(OMgfjXeyWxYm!N?|B=a_NHbxbF9d1$(#BC|4qM~G1f^{^=s@KR?NTm^) zi$^=c_s@HsF1>i=t!!`en1u-YgRzShM07Eo5kv+pewFW-Ea$40EhM}Z^s3Hd6)}!P zjws0DUv5627Wawd5pQ^8XZghv6NM_`@?y-gP+^kb;%fq`!?+X zqGrF!v|w1zw-3H1$g^#tRJ}74N7SR__Y^+Tj5!SQoCS5w53Ci7iLXoWE1tkDUV&m| zZ%7#xeI^?53nj51Bz|{Znp1fGPFTK%^rKa<<2)ELBd8c05#EJ zE11E4pK9RL|7jDrTfMpMKL`pgJv*lJhBp)O2ENgu%4@#+-2k_R;J9 zV~3=~8c9+?xEL$up`uSol=6~w&aZPAg86VB)Hl|{S4R~~PfF6JMg*TI0o)cbNufBV zx-+Xs9fk5Q-FO1*0oIAEu=b}gR7Q%Q6U7M*?AB$LI@v(moF!{MrkBdfPU0UH3`8@j zY>al#JlL*o+SpE3F$*XO(P^Z7)op4%dJD3#WvRZ9d2qAfnh@%2iDtwS#qkQB8?And zfYh5TlF!Y*+t}{mw)|)haQYVZe$D33_ZK}_&w@yvv(6xr2iOxGPh{IJxJSOQ$10sQ zyNGu;W1Nhk)2~`ALLkXUn5azAAF?N6X5y!cp>npuNbaX)msD?7A`J;U#%2w1Ta<@= zyN|hBjh{TKO6>j;a9gS_o%evaEywkEZe?oQHMb?w0~^~^MtR8tJL=7QBwe{E8(UrV zr_wK@t@3lsssdc%VqTWKwS!%<&(=Qo=~0-O)dNQ$nu$Lo<8vb=#QAvEB|a*YjqUJh zOS=8QY(6PG_qqXx5uJ=ikm_PVRBMh&WgqFC>M=G_H_JC!8pJP1>WUJN<5=)qMfNCt zDayT@YhkRV*}q`}{0FTAP3ba}JQhkAYFH#MWAkYz)25W6BOY80Y8eb*J6^hNPo%k2 z(c8LdPc%ePGz9zy8)S3|D;6J>$XQ#PwhVo#I8ZX{HRs&J`DQh(^wDxF&+ywD;eouW zH88?F-ow+x@O=a|;!}jf$47A;jA~oNl++4&H!i0l^ZH)R)Z=Jhk6FbODOIGoUVBFct732f)s~YJ7Sdflg;bg`>$EYWh;tM;qr@(#m8Tz2ssl{R#iYIh1aH8E&JhIZ5 zrAK)4GT6C?b@6ELlvE@bWt(v1kL!-HH942b^8sHSE_TPt=Ht(Zgyqi4|KFKAwqH;zlE zr$Z5=g&h^9?ZREu6HMnfQr{U~7+gItTRKcw@O=ywf> ziSK`{yzZENXiWZjZaRR1>^aF!E0uOVsI1m|RlUo@;o`g26@|jO(A$9NM1*u+FjGdE z+1pl)^nV@#X7-yoWamdV`FS&jF>w(Je5u?8!yNI`-pg_sn6p%~>K<|ba9?;lD zUN3}nz3g$A7K~j!d1M8UhXZ4e^z#0?CRF51j}?fV0bRg6bwBQg6Amh3l>87A3VLtD zXFZ~nB%+*_m=B5=#cTJ|#UD+}04~Jqo&l(_i!%6?px8d*@;i;|iu{xL^MMp1 zIuZy|;)#*@AZ)i}kurT^8b2mReT)<)y0;R_%qg1w0V(oHVd*!BF|ML3#xkFf+Q0Or z)j19_v!5hAA>nxqON2#~|GYHLkf==V_sE%7O}=DTwxzS1!F<0SyXD7>o3*;DE%oUQkMo9h0f;I~+r^MYm&(LA_2Oldnq)8`OY_bO zfqbGfi*BIU;?52!ti(Ka7Lt`H*A_zm7Ih%( zz}i*+Fl`54;s{;oXissx-goj*W=F1LYt#&z_TCI}^c0J+1DWvJrZ+H6?%jN#PGX|G z!2aI5n!w_{EE;WdaJZim8%$&(SdvbonBQX3$VeO98}OselSmgopH!ZB)XLV6fe94OR#{4B5r0zeJTi7l7`Ke;QRLd4CANb%^rjxxc`5)9-Dc5})U?ttNp; zVK2`HfR*iOy9sR@hnv~;Or`r$U0Dv~;GR=V89b7Sj)9-aj9fM-_^-k8Q4OFNC`Z=7}6zm>(}!a#BbjPQ+iG z%($**GF4mf^i)31BXDo*aj)NXZ|sDiJjx^!-W7s!>nXo2m>#$8jqfYl?;$8Zn9KbP zuG_vhG@+=n&3og{H6xEW1Ns)*}$@nr2*pNaAc1LXpC;GguFgn7piPa@D3nI%_DgT{EAndsI@mTgU* z$DZ5^@0+!&rL5=5a)`s(wNe5~_;!;>)f1Jmi&oBu1R&V8^p&iaig(PgkMyL>N(NgP z+qNieM;nej^&#lDJapMYrr7t89s%cOpV<(QrM?}SM9uu}1r%-AT46uZ_292wVPNIB z=@qs|NwvkO2WFI&OLN0dwKfP8I(iVjxFQsHDgXVx8I~rPb>$gPLKPboFwuNfj8S*sLy=sTc~rf zLxn>E3kpr@z30pa)eDC;4^S@_|8ClaMmP_;o1m+(@YKm#VUrtR<#;l!$s`<^uht$* zT`o0oFZznl#QmEu#$~*30Y<%r5upWu_gS;vCj|&_B;T{^jOrIUAY!3#Ti9UgeHyl6 zGq7m6jj1ngsAg)Ok)bp(Y2Zb8Kq@Pbeq;HtSxmjy1rTjWO-fd=c;gLsLThxF2R7sI zbUsxso-sRIMH2~clsJ7L;l(L_i{i(O2(FSVaty?IgFp@~0%J;4%^jt_k#%?4CM8F4 zHjUHPV;-(H_h@+>)Qg5^E5SA2uxPug;0LTeKE`o5fB6ai2@quu>IFpc_}lP);Zw!I zA6Jfc3Nf^~cDCAFvkSnClKac^xeHKe61s-{OKntW5@bdR&?aC;nGWg&zilgk_ZzsQ z2ChQ&A_6S{RWInGHYpyS2SAj4<_h{rk%e1gC*C5@+mzl90bXJ6h>KTGj(Z-?4Ni%> zbEKlzKWL~hKaHr`Y1=F8@6?MeMtwn$h|oZ;E(lEuxaxKa)QfhucW>w9bXT|^2JTL~ z*ow0MeVKD9YaZrz=OYKPstSU99!WpTAqGtOy_841h+N zVVChOew+^qId_1;LyX%^L7KakgHFVgg;<18NkpJCSo3CZ)p^ZN4uOwSSYHW*ULYJ3 z$3A(cu?+9kc}b9-z-g|2VQH-8bPu_bW zTcykf#fE@JVA2x97zQ_Gb_Mj$br#1tFYWmBKd^3NMR2CRdlzUwS#RyNREQdZbzeua z_cN26JZxgEn5omh$!|Z=)>={e}449022`VtVqAgPkt&fLz|R4h4RT=V~lno zNwM09(6=>d8+nbgFSNt%Whe<2 zi40|}88O*E&SQ^w1NNDL>l>Z(-UuZtw-soPZA3Cm&vq^?#VqevM0kx94vuCm5! zu4N*x22k&?&yHlMq!POM8DDhA!-y9Pa>xQc{SwTRx-OuVxtP7(%4DCbSuPBIn1(iu z@$;WR5m@S%9A50Gx;MicEm+P&S^7DhWrkZX<{*CMGGAY6UGG@w^ls#9pr6` z(k_ympZy}DVcSzIUMLuqrOxG2m0uvINA~Rgxj+KNJ|WELqJGC~;)Mvi(hX^QY2gX( zGIbM5yP_=lEP)ThG#^@fUf+Dyv@Cu{{=sFLha`4cB3HFO2#$vH3@l9m#-r-QWYTTo zvXs&ffPK~gO4FMc(B|==irt4tOCP@Gx^3JKo_d1Hb9*Iy^H+IpLJLS2R1nW*D^sl= z`*7}T_v0F#8a>{^l5gLZ2Pj>(eR4NjnPyHi%*=SS1C6y-KxFm%KB^$ze zlkn{y8NBRnB#wSJe@ls0h8EkkUO2Gb&RaHR)2IJau(3HjfHw7Yab?D%-UrX2ogyf+WfxYz()2`hP9*+~t$| zcSm63DRBUV7f5*dnE>~wNvXhMk{Lpq<56%drN%NK@`OfUa=cczK~Xnn9d%AC?~oEU z@p!i?wZ@z;Aw4Uc`E8{@JnvK!J*6;Pg)~jRp`zxF6~i;bfB`2@z<0wS zvm1Mcz8%1x&jwO2%ip~D@$1*+&kfd}dECPERxx{rZo(-pb~?b8u@l_D_^R(_v=Hg( zA}R!pubOxC;fUoWBKBrus2$C!*MpN@Sl06eT>gE82RgAK_e z^&!VV5=HjMtZ+d=gx6&#d=1m!%RwJ4NfG9FPl|rl@REdAeq>tTF3CiIq;2-F*@bT9 zgiw<#_8=cZqse=*-W(SGUq%F{GS6QvXK*_>Ng0xvu{FN>QKtX~9H&Fx2Qa>tuJN(u z)lsxiX9ETt&@^q1ua#=-FVrlp4I6bq&6gi~GFz(4)Ph$whGM`ujLUH$JP+sEsh{DQEwWZT1F=m! z1VliFXYTPl4BOc+uk^Rt(e5WEP&;Y`F^)ky`n&Pf$kc!NEk1i2U>u)^7;sQK3YMQ+ z8J-Duj-c2kV0@LCar|vNdeb4B=+7CRKQiF{@%Vb+;-f#bqfw9W3NC9cQA*a@`z#YusiH&DVmCCz9Wxo1ZFg`uSFfU#Nx3sN2p z2NBOfNVV02qQ>I{7(VPeeBu`x%R|z3y%xVP8qu^;RZQKJDeP_4ptNfZ6UU|1cWMVt z%R0&~p9L{;PklM?>fymqR?IDgf z>e9#L0S;Tc6~x2k(djpHG^@(p-!L=cdC>QtbQKP7J?teEET|gm0+(P*G$cpMe|C-3 zBqLG&i(}frOiP&{H2ayIGH7Np3Cfsz(qb7d0MlYApZJc#L1bik``~O95dUzRtz38ceP7u0!&0 z?k@!AKN*kzPCfED{9t(#PWwYW+GVBv560skGlln{ z#1no}Oa50l4GM$YV!u&A^(Z8ljGLcH-zd3`_0+s?pED`hwJmQ!)Wn(q>?y9pcWjA% zP-GvH-b$7mFxaJ+y85;zgzabD%MTN)FV42V(%B@FTHU#t_{=R&};spnR)`~Am4Ob0L+!sO= zO%IfL^%wZB>RGgvd+d9)lC7%U2cKQTTRZ*v(?~~hjdrVp{nT_;s^uHq)i>O2N?05q zf!z6+{fGBmq}5+|M3#qoUEy*%0~7*3&|6bE^eH+|{D?slmW zwYQbN6-sgDET3y8`?4H52*c%jKXS)%t?;1d-M*wjq3XD(VKRmipP`#3X!`PSe)!0c zuwu~@U-*}0HE#r78QU0ACpe_fLsB|~ib`sxUYuA=g8iLp$+ts~eblA*GqU6MzLg=? zmSs1wd6-ii>qDgLYvdWy`vMP^62LwYC)szkJzS$1JBGWm6I2T!7UUq0l;lyoP@~?b zSnOIDiZVj3pnJKXDxKhKOCr`Q9WQhN_#N}EF?sRCUSJYA%?fhNGjd8amBMZMH{31A zwD1!Wv&+W)g01qR%LXWvW?n||Q~>Ih*eybR8KEci0DQ-_FNw{`wesr_>HyWkq{(7> zws4Vn-(VU1@$zgrYH15itlLXlh`ROrYT=A2wmq@lREJ?iX9NEJKjX?;FLeG3)#B6l zWS44kEARhxwP=5MWfxcWhic((tF@g#{%?TqJ?Ci8<#|16>K<3)h9*|Zs-@06)-9JB zRMP+lWq|SLE;YcIVY>|cRmMZ+lBm6tAkCgfzH0}E@W7*s>0sS$%#i#&L3%fEwJn?c zbHJqT^Rj=wgVS0+{PB%&IF8da;BG9-JJ&;)x>A{_GlvV~!H+HR2)&n>nl&d}PlFxY zQ@xFEra{1+?0pyK!Y#{Hp1EqQkBgYE-*6|xdczstYgcV-3?Mbm^Rc-C8K$kKkN4S{{b=p*0NOVMsG+r@&ddBqkladtI{hU|3Aa6o(Ft&4!^F zyhzEsOE}Qj} zq3PLDEs+)Z^syuyjuI~{vdAW+86U$MEYf*I`s{N)HFHYIB*|$p zU&%zd)JQ)n23<_9WL^`n7`+uzRHJPbN{01<3p5Q{%n$OJ&k4CE$*Eg^ImiFmO6Iis z_1R)E7MDGk`k$Hx|JPC@dzyywE7J12hM00$dNtr9mJ)d%ls%|vaJ+LNq&^1%t}K-0 zAQ{g($JAk4jLHwS*gW5wOa7Z7=Bu3a8kE1W7r3I%yYlFC0vrOa93DCn{(TwG&lsGB z<_zpI(L`TB(|{l+au=6PB8eqqoB+TTYKVCsc1YNo;F=-JmVEvsaiH&YMSVGY|nqo z-5|Y=C^JbrqDpKd;2F{XT<)$}3eN}EW1HL!D*jiv7?&t7H6HP&+GVy3hq1zJ;H|$L zpHK}ETFnuQT@6t|N>k|X8=~T6+a13y_GbYXwkshVO|o{&ugk`&7}vG8&u7ecTjah)_U<@CF1mp$}a+xdE&U1(u-nmNzjZb_n<>)g6_#uuDYcZl- zUJr!SMGC=E__TCesToxY;X=i{5InvI#%^KY~t0Tx@$dbo}4hleiJ{WQ;U zz8qY2PV;@KcN1(EhZU!!42Z7nbMn4_gE&pS`x-XHMmV+>>Pd#KKi=WgyT-!gKy=h+ z1h5gO`SR24;-4xZv|Zd&34aIY z{O`u6rx)f$KGUeUh%AwYZ6Lnx>)t3^O^%1no1`E)%!*PDj^u3cC!)i8A3Fk1sD3MKvC*2qWj(mpb{(?MDZsw7Froe2uAL-4R!$_zD;GA*ZJ5*r1 zXm>|aY(OygPvW5;;GCaU!p*4NEx)dh3t}~Dd7{XX%w9yJ2Z-7Qa88b7&f@13tSwp; zYBK8tg(w>B$3lenEgcfo{H7(_Q;5ui8GmTWDmuqu$zrI<%$(C*G8SsdIG$%nBx|Bt zvO5|E)& zOZLQ-r@zj5A-+}5Xg~Zi+q?XUcHvvN3nzH5i6_ru^|P2!7frtsi+3=oOS^B8;p!80;BS)z5~Hh2c}*c^i(PkD?FPJ|Yi-(YQJGybtzP3^9!Aj|{)0lKu02@g^yI_7+5CwIUq5h7wm2hp zS;o}D*kB5P4fo@!dA16Em{~>NWI!S6ZopLn5K*3L)CjA73FNxh|bm z5k!LQL4hWuwBy{c@EshiZ(p54jWUy{XUnY$l@neB<07fW`m)lxW33e|ilzAtUS;b) z)l})9Hxy(IKitqfSb=e+3AQUeBPg<1xWQy2VZiFeRf0STA|3gLD{cFofR)En=ALjh7kNlJpv<_o#+ULK zo-C7rE4TZB<9@O@h~~ynf>3-(Ly}Y(Ph5`bI4RyH3TJf9PBC^7V_8qe>xM<_3q}oY zV*Y+JX4CP?>C#6-`uKqYTPaubRzN>66XM>mk_sk%d0+hjk?mAY#xXX{JBwDup{HRp z19xiHN51uZh!2anPIqL1`uc~*g>F1p#o?;yB5`h*Shp-%X2ctV4_35l6VKN+#hu#@ zk=*4jxHqNv@8)EjI4EEJ2q52o36cEqi;NmD8F7jjHb8ew8`j!wTl)gW3;uh$_gP|p zJMG8=-9FehjO6)-kG&|4fi`%au|5z;Iv-`^k2HoJ)=I=!nIDz*DOq2m=KXB^%wZ#? ztO$2r56*tfWp+#>uSXb$Zbx#9@|YVUfj^SIZgOE#Arrk3Smvv+sJU;1kg2Sy>MMJM zSa8%)tLgWkku)0KWp_)c%2pb%p+{#7l~3y#-3gi zS*=;kweW&x_d5#kW-$pLu}Hm(j3nqspXKGXtVCDyxFz>Bv44xnQabl{pQXg#eU_Uq zMS@cSHzek8pJ=wpULhT^EnyC0RNH+_;h^5E|5$HGIkdNrDKuf!%Ap=@KBSiA48fJ! zGht9|JVx=IeR6H4AjnnLT^JipDL_bX3 zuKTvh4H{4MHlFA#F`l!ZpWt>m9L%8QcX_0vFnxim@+<6}Nvp&Ly}nxI%3ZDW>_}dO z-Wg^0HA`q+3XAvJx9L&*#i@*BPmAUEDPd|mB%xnN z%vJo4_|AWVT>rpde9j(?vP?l)RPndpR6EC|Re3;{#@!s*ejJ;dKZyl%SFnL9j2YD2 z_Pv#2`#58}5QO36|9sy_&@Tf)hru;!)y$HL3D0AWT^kR}1i=RPrAUy{urX7yWJ#e< zR*?y>VfTSe(Q7mRZXOuAW?xKmv8A{(C+QilDbT07bNYv@u`lLmd0D?{J|4TsUayuy zGIY-8+JiSa#?%W8P7R`N*~(&Tj}3Q1B(iSdv6}TK!$Ie-)~&hd>np63m1Wn89JPv{ zTKX5)Mb%JVidcJ8+3Lcl>k3Iu}tjwNb0H6io>RgY3~=!56>= zK|hWA#Jli|CYdbK>sCA0X9R!_A-9bfD^y}4*f&BBKoj>IA^yY7MX*6|{hJ2YKTk}w z`QIF8Ta_H23KCBJ@Cx-vJhYp0wIw#jsfxQVs}67k&wM|EY#$H)OhJM>OVHtyf9PBw z4K^jlWasEZG+ZpC6w@c8rbxIoTAnenNs}J9Kx95X3>S(N5L!q7*gjMfBf`1rSN{26 zYs&sL_HM~A=58M}oOO!|a*h`sGIUDZH;NC*-PdW+q|Khs?)Nd>u(sDyv#85rdZQFz z$@y>yxkTT5bM*vM^gWKykIc$ZHcyh#?E>wzDGe$Ga;=J~JC0btYft#q#V^_rW<3q9 zy#MxPCH>DXt8E2I|I1gF3_YX$>T2RxeHl)UU(>xR8=Z#VF4>*2nw(c3uX zS4VkOU(y*}I#9c*W2lB1U6KX%shy=ImOzWeOkIhk%^!CkYmxZWL8M-a)!OHk&{QEU zbdsA^()I~5F#_3VwTts~#lkjH(z;LOce!ek>ab=uh2=;h4PU=~)U5WQHIH$izjay0 z`gN75G!4wyXT&q9j)7XMS&aU=Z;LX#6YjR9 ze)`SBeL5a+I%5GCR)SoZE!C{rfBSGvz?hFRtYpwle|5Rr%jdp*`qoW_LR3g$hhT%S zj$fYRILRx+!v5q?Pn(~7{_cTe-n6`*l6OP9%IkjM9LwEZ#2OoPg3d9UDG9y?2?Xu# zAID(w3d4Y%3YESWqheNxF}uE2XrIs4^H5)-zfjx)rlM4G)mx_}B9*&PtMZ1mOzDTZ zI9NqUoF&+GdmbaLV_7N9Gw?W**gxuAcI8d&#_dUa**=~j7k^B?2hTM)j2?KN_9ygL zpBV4VaA|wasd07cl_ZZTAwi{sTsAKMTyg7ZR$bg!k}=hRN=F$!&DmnjZ$bE(YPkV2 z@=_ExvJ2p*@^3!O&pymw)Vv0E-G6UB*y?Fb;h2mHcJM1AibBqJH6wlIJL5 zB$q8bL{wmsS)3*O;#jE4*(M_uRd7>DVBITu7m2Iu!~)rrY~NH&?~P;6R^k53H8Gd_cBa@MDH4QMtV}K;s`!v>iAE7FC`$p! zmJZy$M+=-1gS5#sQ@@d<8q^ufx7=Uj{Q^_Exa5#lrA#{ahWPlkK!QhQ^QoNNAH$nxj@Pmo!DCLpMCxLnaO6f*|)27fG2uBOh>DaWWeT@(_u0-K>aoZGeD=W;dKK`4Cjta6%ED}1m|Zl-}8amgAV>Z z4-6BB_ODDE97SIWzpY#Jyx+!IKL9hOG~L~OhT>s|VN)=0H{*1{uz&V5!03oj`aU}T z)M#m&YrM_YDR{)P#WkiIw%v3$2AJ@U+vapz8uy0NZi|JVvUN6Z;vHwZf3T*n>ZYH) zU!#D%Yo;KDF~DZf&i~?F*|$plu{|DKibr2omUS8m2U3C08GWTzJe1;eMA6Cow+I(3 z7x5n?!3Ym}W^w6Iie$||j^h^mp%m%C{8V=rRQC0x$c7v0#DrPCe5g|>fypV=lA$L0 zol~9lMcl6krgi=E+t=BpJa1}lqodPvT}%)Hv_v}HfL=YFa^xWthw)uW%1rdlCJhGJ z_IoEh=(#HvOuG{0NzdfosLg1BTt($71r%Ij^qT{mE?*aUgRwzCb_D4tGWytjy)gY< zVGCNVwG3n>VPCAp&xw&xXs;O+@_8?07-)TV_MU3r+2t_sSD*vLs2|0>ct zC{ovdZi!Y!U#@%-u#zlS8uabUdP=FUS4*)O7=2>210%A-`w^#af)^D|qhpxe6Ru%4 z>k!rsTONTV!E`p$R4EuFM*<^95S_t{qmU$6-6xgG=&d~mUMBOM&)h2%HlJCLqxPpy z0S@EEaWQ6*X)>d?t|=N=LpNzmz`G*-;w14+i4gTvgkvK6VQaazzOD$|E7+_Sc`W7= z@!hv54kw%xDJQ<(NN`;t>Dhh^v1HC8c%8AeJ(rZCJprfMUhKAsMC`HICWU*1kH;nu zq*hrLMph4`Lt|zzH%@iLK6qI{kydgxOea`Zg8!hbz2AxW)Z~>e?FWslTCs_EnEIs2 zPUI7DDf^sC2lLT;%4mw39j0^T9Ys%d1PeT7Hq=bN4Rkbb?!MiZDf)OIHVN5(%=^*I zcs7sNmpsvCSPUlq$6ELS*^iI0zTSCRvyl|e`vjXtV7d;yNEEO7t4Yokk#$+4e02s7 zmaC1-K~`6rbc5&TERNEZ&A0H@6m>pd@36Yodh$)qwYD>JGuPS?wq&0>#11jX2@U#D zQ;YO7P877@(7i7zLzld#-MP7hi=24Pqp;7&pnIQ?^>7~+9ZuY}_>ulE1D+L-B)CRZ zzt^BW?0S#cfjdP@Z|or#=l>M@hUf@?lm!1GH0N5I_43Og`D(e{!&W?aH!s0xz`Lmr zYS6;r-D$*bM8BpA?b%CxuR)}v!g@kG(|~-x%&AWYyVAwxL}n>>b;-0~88(WxAN)T=dT>*zW-9Fbt5|r`{@WWRp+m^OJwn5;qztn+1$$S2hdh;(HMyO%ouI_-*o5V^`?)iO&4P5UsP#wYFM)~+BZBaDrQ?z|b zTdoGU1tuc#XPtJ2CW3duHB9K~6xNh%L5UN?V95z5f0!NVVb)^}!I_HBZtFHJdg6tW@``OYijcWtym{oAl~jFq1ZwI&Eya;WS>tJ5hGV zX%rBg7*{Yr%Z>W{46rqr5cvG#Kl{e$zfI)D|1dOefBx@`vc2Ef*3c;FC-Dbj>0(k< z0mP%oRwNzxZo=v)w0g*&AAEj=ubaeDFL$E9H#FWlc68GdP^jpkB><2uAA!$rJ5UX& zv~QlAb8GO&Ccr^`baWW#6reXm9(E9X^bOD{EST~jgxzpR@p85|w^qxX2CSY34ud&E zF}cPY|1`Mi`Iw&sF)L@qMO{g#iR4v$5GPo0Kf*Ic;@zO2A8Bhmhqx~(d0<8dA0qVX zwMXrV#b~uY%V%nHT8e8I&6zB+>6M<^h~L8C%DPwc2-(0yIDA|?_lChSb-h4EKu#(J(^T8cWZQ0;E%J8Bw4W-@^AdN4KdaERkdqFZ`VG_gfjoSZtR zd|yQ2$y|wZJ@?OkHdo20Dfbr*qe8Gc%`;(ho(Z}=)^j6AqWEF+?P}>y)nvM=x_JgJ zUK@Sq^=?n&7U`LwG1=*h?&DZi@PJF4RC0$aQo4FA?j)$99_vxCr^5%2RRU_jwi~FO zg}7DYWdJmyb5eAhb?8b2Fpyq-bdnFn%sHa6(?Fw66wChcN9ISjdoyrYAHW!4QZNbd zqn%;Lz!1K>rv2?*`wxfp#5&&JML41t0|||Hm%Bvp_gp~zJ$F$r4>BRm9cLR;{lo5` zU4eFwh6Ah!NXKjLleoa`&1^Ho6D1BZ(S791>g|FIgK;InSU{E+ zF?eDuFf{OGC@@4qe<9hjCD;!URwAJCCJx&GG%1|gS9Lpu0sPAp@OGR=y&VInf4TLn z$==&0p7V&ImnLH~-^PnUO%G(izRhn&glIz23E!t>|483_hYME#<72xn9A*?U$iJdA z+URo7t(STwJH6cng75Sns-8}!ar=a!RLIs4#XfsW)|H&2-laxbNyq$Xta=j6M)OOI zA`6V+OdnHRw1TB(xng?#J;|l4Cob#VZ`ZPx#-2QIA`rl^cxdGA?Tx*$M%DeYwix$Z zQ|isounTn|1X*FLD*9s`IK?Fvn6(s{JsF_4o6Q?XL>676S<9rEnjFI1t;d1ZJvp%B z;7K+9tPn~+XWqicpR-x)Hb=!*-9@e4Ia?Zq2gTjLIifBCMX!-Sj$2NfJ$v9c_N|^> zXW24aJ?KldU+a5YL|;BAggwi)pl7#@o8GAKzX5I z+x>GBJ@}d^dz&|0I>=&+Jp&2k{MriF0UvJTrynlP@uQyjKf9OzJ!o*liluDNhudn@ zx13+My*Rc!-~Qs=^BeRE)u=;pE8o$p@jZ}=^COBkDEog@pc~5m-(!B${(pOSuG04u z@_aj~=Sl+Y&U+PoHiueOPjkSwLV0nh`1-sxn9V8c6xx^h{_Sq>p1%&YfGzjixD^zn za+Q75)H8L`L{9tB%4?ph5cn^ODVgZu2!a2nA3Me*xKdCDb9+mlH*oc2oqC^)l;D_5 z3G-u4zMqn-k!iiV56l4Pnic-+Ctv-Ds}|uu?gKv`O27a6uik6bHv3P?kt#D8i_;mm zmhd)}BjmG;y4s%)faHfm4`()zxwHW>Bg#{9SAD76c**=vAlvQD z&iB>BcXWKm>t{D;<`^psynd4H_=g~I^?z7j{)fv&r+?{?Z5nF)Ql6C2K>&IE45$IG zALZi9Pxq|4bHHt91b@5xG^FuHUf&a{@?k}g2*?SR! zaCz6^@4{5nAXv%-vUh=`{+mp(?+b+QtL`T~M)ydiegBnJchvu#)A&!MwPW{KP02Sq zbkqR8AN1K*;hn!YtW>N1phMqYEbb|tJQmbtN(rpo?3bGVf}w65R_a;C9aH|+-mBYK zvFcdFgH2_p)pG^(rYOi(Q7d3$2!1yf`CzaT@}-DU!G4l+sD_f>*g>7TC;(78XaPwH6tbQ zW|e-yO(liqnS|t92;vM@!wZ2&m^3T0$2i~x#|7Nr;1G`j$xN9UTfyVMw^fWah_A0^ z&k)&nB-Sdd@$5dcq8AYpR>fXQr^8+PN$j{wI%mrjU>8|LI=JIpzcR2}u^^CSc)r;- zk)Caw2AsC`hPIAt-_lj8Y#1q~s^2wfA>%L(TLp7tQRRGe3ev2T$|O2Ol`o>_i+TB( zT8uOCGur=7*;%YcBTx6X^e0Jpn>J}c$l%a>v4*>}^NYjjrPploMtM&ipZ2QPi#$T( zMUccU&@ntk@AW7fK~GvaF-r1@V8tnjh`$Xn#(GxJYu4(4uD0juTfrO3{3>7GuZ;Lt zxVrDFKIP_6bHuqI|FJ?Vri-l z{x(jZgpwshxz7b>LSLCLS?Z5l#fTZnW*E$eCyKX*YE+*@0$%o>?+ln901Se4!(N{6 zFT1!LI-e72xfIH_MZ${YC0O-G4VgHmZ^2^duoUtv0A+9Rl0CkB$&N&)S%s}5O(D5o z7D5{%V#0J^H}|~Fa#N}FqtjBbe4K97l|{!O9hZxi{QSW^&f>Qk<#wMn39?J)Uic;B zSgcNzepI+&i(7yEdD%n-n(b_owXD;GdUg1*H*q=T$E2RX#mTj2%8ObQ;^eXyGe{Sv zUa{&t1q&00)*B_)F2zmG9n^gdV%SP?G{H^N7`jip{3h($yN;jqNkA;{4_4c4rrPfK z{Smb=7(aN~Nm!367?M3<_CnB@oUB!+_dcnvj}y#fC{rCrsmu)z&iJc`>gLU4-tUep zXA~P;vc?(*R@<5TL-0ieW5XI1`=UaY@E5eLRbq-+thhKzYb_`UJL=EjVKf-onA01j z+K4@%fQf2ku`Bo$KbuTJ1eu@M?|rXa5_!R$gMZ>adTw-VlGiOkHw^XG}6I&%r6lq8?)%u?nHV*iXw; z7gJ%9pJ}b>Y5JhdCLr00l9RtndX6H+6tRnPPYjOhwO@+tXclQs9{qk?_rm$z8Rq&e z;k-L{llXeeE}uNMrh5{h7CGrVmcQTkm_N>rm3%at;IRKOvR$qNd%*F4`H7;DkHVFL%1N{ohH&`8;(p*grL(O-z;e}R_e5ALSTgs#o~UVY7j@36r?I(Jsp9 zHR`n(L^8eGel1KNMhF7|!wt*aEoa-}?Hr}e1cjaXA}GKSXipm<6+U<^hJxZZUyF&( zhyO2Li$+DWQ&1Im6*NXFi^74Gm}K)if5aJq56r|&@VOBU zIos}_X}@QNYc9MKxuCeAGKeTFxnbylKH`_1%NHU@9QDW$CkIi9b$V2&zB;Nlv1uv_ zQ8eFGCO)m;x1g! zW}$a~%K1>Hb0M_8S5uoKc!is}1VfEmBTvYW%VvhA$;S#`!J5S_%1}ra3*wM#4og># zluJB&SI}}&D0^B%E@SJ!8pnBRLO zDktmSs<5BzOw;qfpWAOo;+g)MThnc_U=G@OsV4s8*2pnZ2z@^r(hZ$~ z4Fw_Ti-zD6Gm7lLusrNV`FjW{?RvY&vHBf*`R_w}f$AlZ^Ax}j3k6Y+t{p>$!4+}0 zhjt2+cah2tzrrbXBjx_ePd}9s?!9Rjtx22|h=Qnp|59xwg8%^?tD*k|xk1&p_x#pW)Gt;Pp;jrxZGlphwqkrv9I?>`W9d;avL`lCPJ zzaZ$oWzXfpQ=K3Mm}LT2hy_6L-(mW zouz`6MuB>#iE3rIwR)*ud$Zi>>(;MJuD=<-D^vPVr^XR&n*4cW7BHm$p~5t|M4;ji zx0hhlX;pi!ZF(Q4@7K0%Z@SCANV;!^^Suo~slB_K-Ma+)f7;EmZdVwE&1?H_!h-*% z0_G0^7NkvQq=l>ZT}7P9I~AX zGtnzC;v+K|p1QNm`NbQA0sF=O08CjJ*A%D`m>^;vhO-Zl1u#C&y+OeK)t{(8_v*j> ziAi9XC4fO%+# zcKBl8lO}+lLJXq=KScs|3k^_EhHGzQp&3b=bsXUICO#wz_5R}SBY1uljroV_Tol=5fYXLG8lfW_5{{KQpl%Bv|Yv5YPw0U5`3v0D;gjDU{>v0E0PLYrWoK;e#l zoQ`%|a2odBc5~W}TZRPg6sNCZNEI;GbF(UEk@X<`B|(IZHx1Gp78!N&Sb<&dJL9%^ zDqA?6Unfgv@>wl4G(4+(S2lo=xRG#`fKQwy*PKQwA_$3Grw za5C9KSu>ZN|3kxVqI1V-E!9(XtI)+0XJS7aYd+bpaXd%TzSf|Q_?F0hStq8Rz!2=- zF75KqV=i~+oapHs3K3ld;-R~z?eF#J7xJivwTmU~uG_E!>KQYFXG{+sgbnmfu_=%~ zcE{eP)nJ@MBgRA+K9wbOQI)0i+gBHqMY&4Tcw|(>pWy2)ZFU8g77t@GZ!LCd?I%aD z=LBiXiH)CoQev7EzMnVF_Sk?i3uVl|Ye=Pz4IG=~A9BL8f^&ld#nJy*FR9~woKc)#~RYe z;zjT7P?Nwjj0ew88AadG2EX*%9{T4lsua0NGZ4}2g>L@*OU?Ub@PZk-ymy`$xLxmq zU#J4uSz8p7kCq8Pi2Eq>hhZ*cK(%x7TX@k2DGoi@9vLj$`1}rYm}jTp#DUQ8X!%uxKY?Jk_1?5beaZ_5R5qi=MP4O%_R* zm`s(6ZVmOCxZiVEKD+`uRp)N{mnj>~4AC-6882N*LaasxUYTCVho!{HX_cj_UAGPs zV;qc1>-ayceRWt=Tif>rW{5!nX^`$N1rZEDkq{6@q$QMYkPhia7`nT=Tco8!N;(t; zK@^Y%nQw#2IiB~N=X=ikeg8Ta``WI(*1hidMPiM6DQa^CpM)C&_UiUtFEL;pe3RO= zM!Y9lwn&}7QX&vk5WwHfRx(2I=>?f)+WRrh7P-*mEyFAV zmB=HVb^;VU0+k+|Jl0#@Vo_xz3^}tEY)T0YEnj$axZgD2JNRSh_G6B5F3<3vdPNvh zW2xd8=LD($TeJlcc4^Z zF>iLPR~&{{nB_e9^tc#QBWU{L7$2PQIpQ@BWTJ*+&d_ZzuwnuDruY*h1}!Y8&!fb6 zdWcyena^!^)HbL|@^mr`^9~5pOTwEZ84dT=s8mrzCWsjhzQ#mC;DnO#SPO*NpK`)7{_+n@P z_ssDN)4HEiP!zc?9z4j~jPF&(=a;iy6m_e=bFT#Z&1SRGr3cCM+nO(rCBJD(O$8N4 z+;ECv)bn-4`Q~bM&?)+^W{}!d7;zpg&en|%Wci(9Z>0b?EIbkOAD>i4#o{;BB+A3y zzX?y_bOq5o;&VY{aGL(GT}arY5mZ*xFD=1RAs?d|bR{WwYPP9f`$$3NP(`FuN1ZS^*l0=Jvu`4bfzc6i?WhOQ z_*8RO(AwuG)nQkCZmtYyM|$YEMTyCCFBJh9b2#m+L!gUx%?zN*4t&jRG zdv_!J)zf8kmuCG=kuMJ`l+YVCn$SQhbr$ zFvD0xX9(E8ov;6!;K7dUh*abGk;|PW#C2e}LOqMBn81A$Qp^QSk)N1*a3SjfPVlGG zY#H-3CjFKYqT^H5`P9%}w^`TyaEvq$}7i2h5u{^x-EpCk2u`@}yN0RMlU z`2XP@|L*1g!^?pePc4X^z6OYaA1d;6V+$_)5-iwAZ2^;g>22nXG>{yD3$KhVd*9(k zaWl|V(kfHRm-azEMQQ$0PYjwy>s2zEk1|pG59hX7o*CQ&h+Oq&mgHADoH1?5qjGJG z?jX)ZCjSMHXe`?e>(5omzx=O(o8~`kfq&dP|6#HI?KV7n)L-7=&zt5S-{Gt!#Rp&j z1Ar0uUH%80`Hp8X)lW6_-;@siOVY}}ltETRwt%Fa|2cs99pF{aND^JXbUJ|HVzEE# zZ5#M$Eohe6WF8Tm`L{w6iKRLOkte6|ojYUsV{oJJJ-0b*Yf5Rn6PleZ zC^WSsU$^nyw=WpE+)cCEP5TfNAKV|Y`z%CX0}HAJRIR^Tv42)6Wa!fRuWOLMq);Hu z=@0YPA0w;(O?Umb-q#;1_Q%M|ER)6J-vPj<{|Y?loeFx;^b=+D@3ZqW0Qea|bFjbj zU65~`3f@hgag{g*fsgw!w_&sCXH3nX=B<+do8A|5>>i=waw4eyl5^kw%ends*XyTg ztmvtV!u}s)rxij4jGu`7Dxty1#SgY)zM>lc{r5(bn)Li9RN3jR$G6xNz`Opm^1<$$cO%3xac3BMg5c@QlTNI!)meb;AmmDPwLa`Z>AZ zqjPt|BD?@hXP5lwb;@j~pfaL`n;uBq(-wXWo)FOO=t@hIC?SnMwp|a);F1A?41XT!noD z^3`SJ-3{&l!bz#m2S@gy--$O*A&_okWrTd043ab6O|q(o06JKWU4=#^a#~*$muAnZ z_ z2Oa1appuu*0jg52MHHd2FzZ*0+pVq3q)}xS=A(JD$@>!s zdv(n?=yrtbA%vHkcjC#_1R-%Lu3aK8+-Pkq7UF5cQ|~nqB?wKhY$q*PD-jXlOR#uN z)6l?Kf$L|=S4HmzDu*-I%w!kyV1L;9rAnzmi;&UpVfoy%xG_3_KK^AZO!_l*hIDb+au^(WO}hw+*m}IFY~0z zgn!{}8`y9BAtdlOC}bw7u!B8|-e_4go2et^OF6%e;Log>ExZp%7saqNt-8Vv%9#9N z*x0$C(_trgFo6XfKwR}qNW$SE8BA)?mk$Wdac;)r zjq6##BdA|LDzE&wBQF~i+{%|eaTsNN)&vm%O(v_S@Iuh^kmvYdcdSRtZ9Oa9h2^g}xO5}?GCGlvJf-It2GlFxkM2*=D zK47=pA3pJH57}S%=0X|g`0XOBFMEs4Xb1LP#T%P1_Lth?DX(dIH^|ESN7~Qj zzdPaZhKMD)$qs#BG2*IQE?hh8eUpnF*?gz$!Dqzcg-g%n@r(8b^54;=#S)HPU#>s= z^olv<)9ud=MRg)CNfeLn%Ty#eitYkK6F=$Q{j}EzC@yQsg=$dx?TvUKG^9*hn6FX z1Q}?Fu)0JA;D|XL-Bfh>ipn={LSow=R0`Bl$~l!sq#kFo+>z>0i06xplVNt}$BnBp2Q-ZTo+1GC9l2?#0I8E8Y`(my#Gg zqG!~bG>m)NG+*%&{;NE-F3(DakXOWP*e66=(cdjT9`0hm;$ zQ;B^O8o=$3Ndn~w$Q5|k>WTB`Kgk6MAix4v*hXLz6mbt*bPK$MJ-P+?85QDT-8TE7yf?D|biI zAw7tC?c6y7t5vKj^+HFZm2B6)vp>o&(h3&po}rAzTbXYoFo~jL6%D`X)`VUt9vnN? z3_$}Vjk2U@?f{W@2$mR7{E0nK7=r%QbnAam#Dci~T7iHW>EBc!Yp#TkbsfcpF8F(^~eim`@DtD&)q^H>4{!Hpi3WC+u>xQo%GU;U$fk}OT!ya5&t>j~&_{6DY zUkF)-dA`V9g@-KKz|33i? zvj6W8DK39_a*$#D>h8}5F$4?;9NFL@wL+yk+hM2U31z$BodUk)x>aNl?N7eWHyKTP zotBMBEq7q8C(MiX)>HGKH22qSp`E?FN$`*&vkg{1Y-Si}o(}Oy>ij5O7E!<*281Xl z6G}#NhEH}UP5nknO`Qj@t;ksI`>5boKQ(^BLHU)o|@@abng&|YkH zVF$YbsvDZGQZV+{Wk5~4@>uo9O0M-__lF0`PrM&H+SFGH29BGN7OQSeJl{@5Zu$mY z%dBF1tQhV@;(4G%XzAT1g?oZM|P2BcyZP{fTf6&4;&wEDtZq; zlcAHuTl^j?qascSOAAxE)W*EwL$DhFX9<(&0n{aVKgJklt44YtC(6~r>GMJD-y7dY z2I6*2!yu71ApPIUEM#IV6)Z(q?&C1kD|?|SI)bH0pl)hL*dN%+*Mzztjvwp>WJdpm zW2VYxk{wBYXe7FKl^mX4kJD@*dV*&Ybf=1Hn_aYnYFfVRI&ZH+DfS!27Ey$(4ZCJ0 zLnBn8}UZols~FLblh zanNtGy}u12{|t}+TM?*JMq?RU-~YDPXf>*&P6_U|NuvTKq-j|GY2ll^j;>vOt#oV| zblMKOnk2v7#F;5orgW+}5L_hr{XU(?_UCDk*QU>2X1v-PTvndMHzvSUu>p zowPp5hoddx$vFXDQ(C4o$(tTh&De_jC5QWa8$0GPJUpU@pd-rr?|O6Ehu=;eQPieT zROVgLm~ypMnj#G}P>02L2X8lVfMOF$M1mstXs2FBVXS_j*aTb0{B5{t*dzc?tcmhq ze9iLy0kn1e)Tl&9&F9MQ3jG6|L;d^0__-@{p^{A3M_#CZVuIRA-(%IgfBYSPDpEzi zZs{4Qpr|LobFQFhn0TwqA+OjgVmCydxdJ52va;k9;Cr*@$w?WH z71yC3jd0%nIlDNU0yKlIXe#zbOfSBW-Z8EPZ)7H>H*1u|Xp1bi1v*0H*^{Q* z9XJ{ZncI4!*l|p;X5`IA6KEsV=A2pP;$!@qOaNa)rP)jv%4fOe1Xi-80u)I}zN9)x zKf1-y*kjkaNMAjj_i9PE9!tNgoO)j_R~jIL&$mm{ii>+WFOsu5%g{U~`qjQxW7W4_ zCVb4;IlF|ar$L@lrdBk@E0flwfcp0Cg57RvOq%x)rMSEc%+5jCoI!IU&5bS_b6Wen zEd_!@nn9e-)w3D!{<%C8#0)C$e|kDGk*7NFPujFF+`hMw(nz7g@xvuY4a;=zz>6fI z`+FsiJnfL5;}QclV)_79WB`M>@5jCbRK{{be_l}_W$anzVCrPsTk`CJQ;u&3Mr?~ z1~|~e#z?=tRdzQ2$`sNSRnQwHcTqZ7V{A^X;mP%$@5EPYOP~&bXE$_kHKfs^ca4^O5%XV*CIt z{nDy}xcyp;_0z?8C!$V_HFZ?AnbHcPm%ssE{-f>)`iDYGUBjB}QFKUt(5-=~F9F@G zr;ikWxh3hA*XjjO9O+HMozVP9qpvBE0Jk$+(f;6g69ldzM>$Cdj03b;#M?Dht78mW zjDd`jcI*>wBKTddfkP{!@k#`#;t96zMH=j}PVUp`lz8Wu%)&C`>`Ue#*ivsEaX4t> zvwCwA;A~ioX!Vew-C*JfW0D=h#Im4^@K$V4Qt!f)c}bMvElYvx^#Rk4LodL_%`9v< zkk;6X)U1mBJ-jCxs6I}|!4{}%AKjgRiduL!5#aqB!9@L zA|-T0@LU%MiTop@{^=?6dq%DApX%~qQd$0I-T`8-Pxl%PAb180a6Q{=@(U$kU43%D z3$fUGIzK%Z*8`Dn3r&8MzgnOW(YZT6ZUWx?V5x|umUxgT1={-jYen)3Pr~|YonO=S zvo~S^gAExNY+BBDKc@N_R6)!cMe;iMMhhhX{%6)g5Q|6XkAt-R9J~1h2t!v0S*nGC z6J3le$%=XS*`hJ11Pr7T!`Xu#)ZM02TNUZvfUs>f1HGPhe>ye+L)cU~kz6iz#MSRR zC2J20F(WWv7zQa8*i|?4$qWxGg#)|8`DXhHGztY*micA~Q==lYAteLfm81KlSS2vn zW^(s*h5e02PK@79EQr_PO(ziH3HOUTY#HS4*0b>8KLm`JU4Cfrf1 zx5-7|jOfNV=AL;c0~VJvm+Zzf&$nS|DD&xq|vHD_8TDuR!wI+UYoOp~gv-sf* zUpX)5Sua+LTXRVZ)e(LmmumZ-rEtK+C)G7^-{g_9@I&W|S?%UIw?u^1Kb9G5P-{nc z+o8PcEjfPmxPU=DHHK1ivc)glX@-?a>&^yIO}r_p(X~0yA4w(c0ZgBW)|-M{ana|z zKLnOVr~6n0;67X5KWPHr-TwovlzIk0i`+MP-{N};aADn|`z0u%CyHR!sRzgZphzU= zCCqI<0{ZYX4JB9^lY-y9P&y(JX`^-}Ia&c(a$D^JrOaX_J;SdlQu)%tuu_BG%!wjY zVW*wI@rB#0O&&6FKa$Xw(@^!z2+j7RnI{2{=|@>Ta_0q;_P z744FREW+DrvDU8Uxhr9l`ygxwn@Gvi>1&D6Gs|_<=#u+5Uz%+R(xvme(->bvkRVmGvlJ`lr9@yo?NDdW7&};UiGW6*s?9)!y#a|1P66?`qhYRvcpD^n@gtOX@q!UUi z_l&ryXSNSW5?TmH3)V=EuW!@<>Mv^;76mWW7ZvOlzkkV9^|(N3=*l>ztkKOZ4Zrh? z_iS-^z{Q~fH&OjhsGukc@`UoQX)(rJ?|vx}SX)DnVNzR*+|E!U-%6kI%w|wbbE<;q zAw!o^kz@zO^`WP)BTxZC(}2yC#&|R{9R{^4qLQ&(5hoD~Thxj<>m2_G4IC{#~m*AC7iajNEO#)JYDFJ=I7L@^PV#_L1EDLij ze^l6tLDxBw9s4fpo<)J(tqif^^Hu>EbLIg7fEJ9U0Osy_%z><*XZg1jSwIr3Kk_+N zrUMw;J*b80Dv97rEpEH=Fb>tSs1_w8!-R?WGwsU(Frt&AeJgB<2zDu0B!c&;L^28- z6%*0SJd{f9ae<%Q{llGP792Ol47Y8dh2?GB}FlB%SyO@mvAx8Z44;g6@8Jr1~W2yPCyW`Us=ukRxqf z!Gpo9>gf1Ephl<2G}b6-^M{9l_GWJ)zgI38q=rW9Qaum8pDgj&AX>U8*!n&g%xo!Zw-B z$^%ac3?`yl8Pj z@#&;bINj8cdwrtb5oAaumM(HP;V$EA_NmZod+1ZAJYsqKb*2iPQ6i+5%zC*y^_nvk ziH2{$ZT!h{R*&y zEJLGE_Oz|%L3UC9Ox<3U($3N zi9CT~F1Vkxyq+`y%^amw8Z9g1O$;xlQsTikIw-w!_4ZSJi>yG2JsLaGcYc^j5)_7e zmUh^psCOgN4Y&hYGHzBMM*x7ji~yY>R`SIA&=RN=IpPkiJ0q;+lB$a6D;6w>nBYyD z)X*9-B_;gP4=f+-HPj%n0g+hk9l)^EH4zn9>F|3ksE2KKFsZcRQ&cR5F#1HQk9F^p z9k!(2r8ttSWNM)?DzF$<^DyYCc+M@Wy2b4He8{xlWu(yla#M|5Kg2FRFXyX~&~$bt zDB%*BF_n`i8jMevA(F&`OnncO;Onxc(oT)UKq9uBn2TM}u|JnO!PGg*EZyAZ zYE{p4(m8YRcG0J3Y_+rc$!ztqwSC@dWqCT0?;!Zrm^kBoh!TAXXr+tt!%BA{zF@md zW^ZP@jy|7^dhpqcz20*CCzQ0gm;7GqhrwOgeIUpQvG;|KC3bhljdQAZt*sh4Yo=|S zAKOpcEx*{CyGJ!^Qz7CuG6jDzk5ej+uWgs-AQ8r?J~?I+^>X8NHRH?j4^el`6a1ZcM)gH?;@bfLE=jv+AxDC{ zvw8n=(>`}50?gkMEM94fN?caFxf6hGYCaEsm;^YLKcs_kPX{sS9RS>P z@@U86T}cqlohOMb<+_rr)MyCMB!bpGjPt43T~^DiyK%H05J`X_XV43NVs?D+P&z!B zKOlOk`=MAk1P;koR2wz~oGE>#GMzR*G4Y{vfgv;6WQ>y_3u4weR45sbA^kv&!HV%bPQa#OmRLrk62Be>tV zx@h=?Ho*n?wdybKMPdcSGJJL-4}Bi2AGQkuP}<%#+JTrTKetNTY740rYP+QPB>a<>zwTH#uMkjb;^r<4f_(o zhBXr=dKUNbJzr<|RUX$wMRuU_-=C){8@ugUBzcoJ>Pg8(n=dQ$&j;m7lh(F3F5MCr zrhfTlf1g@_F}cZ2H2Va~qV2SI!7x=ci-JYvyw?hDje2mBIB}-C{v#KcPi;J#B{~c( zwEosYFWfiL?tJkR_95kogbCdEQS&fnSH|$235xq3Gk4IoLmr0Y1XZF^7 zZP#LrfB^WrW*Q*uV{J!`=d(%&f*x0~!5;J?wO}++GPSXQt81WHGB(szYBZyEn}&<@ z5QEM%rmFn1M{LTk)lVkz3!FbJPBkY?nc4D46)bdBoUBnaD+w>-3)sraJ!X;5ZkpQs ztlB92W*k*L?3&|TqN2N9X=8y~UiEvMi6Y68l=K#rjX$Xnz@a{nAFOVuy!noc-of;s2oLxiK%Aa^u`QAVR1z=PKi=PE~8LV8x5mO>8_X6rLwq0&T%36y9J}j?sl? zQ>@(OajUr} z+*S4U%epJegUQ0!5ZS3MPUl34Ae^FlYm?p*#?DtS>nqKsY7FM*D5rK*e5%!;)N>)V zoA0{Jh)7;()LDHTOu|m#auwWO8%r<=m1}ggUz=%ribTq}x@@mcG^UWGxVk#+t^06S zi5o|r^+l)++=$$ckO%hjZkc$7sjg7E{dpD?DnV&aTp`RfcVM?B)tgjJFcow&%w6!K z3K66Aq6jCY^JWpKP4g%5jHUCZ&nKlNTfaIgeL2oBEg(c~Y2|6?jW4xNnc^>WKV=X{ zt)mYYmTt|6kiEtFA^gS(W)`us{`IVIwY%^SVd}gDRZ@U4%}z|@3k19mq`#2qG7Ac)i? zzuJmHT^}eYPEcesEW^ECIRxwdI5Gffl(z1`pYB^LZ?S%C_O|Z%P4?SsBA-nrUfKok zP8yXI*-cwkaPCb%YcR8)u~}ZPF1=2Tj8smITVdZPjrV`zAmA6MP|Fe+L>EGu9{j{% z(Rbjm^3^0}WgyeB!1}?56h9oHbl7xP;3Q+oNa*d8(TBK0afNLlkPuBa^mai5PQy3_ z^R#m(iT&q6V5iiY|7}agi`uQOZ^gXdhGIS+eQV&-a{V^K?B=@NA_dGKVRs-Iv|N?1@4Jne|~_geMfj97k}j{ zI#a&~ggr99YpBNSCG5#a!|Xdnk9hgQr$8ppOwp=Bkj5CMf_=gCxHta|8pAZIf?Ab^ zZQmNgVR;|HmuWa=U2Wut8&AK|QHvp$_}!arxhOt8OMHL)250{uL(GT3&zgZW&}ubo=kclZB+P9f5^ zza~Em1TWuMw|(G5<*W=rM*v>AUyWJYCcYwi6jKFk^W(#3C5h=;nOZbubn7~M8p#&wdnO8ed#Cz!#5P|klB>%f_<`L*MoWKq5+dL8{L z2T5RSnJfWBhNBZNXksC)BB|Lq27*rKBYS}crsnTS%ClHy?=+s2>SKE2j<8yl?G8KY z!Su~*J@PVRY;f(y#C(@@s0tExmr#L_RTA7RbK#>k^cT4--0o}WzPUuF>psz*9M50a zJye!-RgY<2{G|e(E~Ubl@uMp2$6xdd8>TOEJ9Hk+ZaM9}e8+F$RMnvIExFo7wabL! zGRs@ia!*RMA@AGXb#G64-Zphzh~mQ-iWPod{v>IAtTeSs8=7&Y1<$bIx>ah1H*&KF8S*6=x;=N=n0kg@H`$d zy_V583?n1ZmAeu@()UpybQ0NT>iaDIgN8nT=yh!Wj>4qQ;E%TqS_c!M+bMTwS45Bp zL%!%&(=Ody5#v^S6B2SYgW$!AgtFQ&BDpgANM=PmXrdsK#$Vq>CsZNE3CI+v%2#k* zRg9@0%MIDd)stOQopz#qMLMUoD&)R6IsUfsBY!Cr^|Kbn^hDb&yV8InQ+?)!iB`?( z@-R*_L*a(0{?`H(*kYni=+T}CEPME^7iv|to`g(qEBC9N4 zLcV&>d}z4VKndTp4$`0@LQ2SVKS(x7InG#$53BC<5u?vzTngC*f(M=rd`midxh#UL z8}gFdPP^Q=B6+)hIAUNsOStiqyj%Tf29*s0H|&<{Wbfn8X|~mw(QC|$hrq69e8j%j z=M%gmPBtz(cme~rs)6*x`vIOZ``ItrEk`2T#nH82XTQ2qJI|pE61RS9-0(y?ze97g zZxepL>2Gmk3Abd=P4}fv;nv|ezm`L`=cLI z{A|E|G&ORvTRr%F9s0!9Tl@Pr-N9Z?LU(tk<9DBT7sLRyO-FbHE!L+7C<*A20RW<~ zb?qc}RPFDp^zM{3sba`IlvJO0U6fz;+=VyZmYnQXAisYJy?wmQjXWGdo`93ulf4qR zJ$vE4bbFGlR6qpJSo0bblqe`wGzJHog$uZQ%}_~8i9#AER;ffW0!Wa@ZY`6jX-1J6 zg3-l7uu89>bU8A|dOFv5+Q0E+>GI@W@nmE1;t}-Xb?_31_2RGf;#@Ifk-TMwVW*Ia zrH+79)7TN<0hsa>2Axn4zK1Ia!116vBF5Etz*BA9k_Gp+r?@72*bhZ~9IY@=cwmoJ z> z_dN!XfUxTke6GIWqlkx+`vylHfb<#QC*?d(x)#zx>as=>^1&hGt6#`RmXNjmkT0Df z$t0m0xgpyQp}T^ihms-u7#6Q`uVf;Kkqa<19-I?PY;ypzqmA7p?_R@$q9BirB9D%n zhvlx|T{VQGlIelA;h%tasb|xgf(ICl0p@bOuEvJv=7zJ>g>y}Y^K^T0vqrFd^3oH1 zVv95&&3p|VQ+5@hd67vBtVDaD0ni=o;0}ji=dgg?4RpN;Twf~}?S0oGZ4c~cB+m@| zT>Tv!R{Ydi?H+eWIj=8yeR2$}3(b>odU@TcXgOgC zGclJru|+bmku0%CHL*7?vF{*pATM-3mZVTD4!BOtT?2jb$+nFoOr#lhT|#>o3EYoh za0NEJu~H#@*ANd>T*a%P)U`<|wMht8qFc)5w_@$1C+(4?B-zXk?kM)(C3X}_pW9pVruB z`lia|JIe<;!^yK0g|d{?vQz?{zGGTpSV{0o+j1`x7+td!lgQXHN;0J-qrgbLIF-%5 zN&uN65zkL$U(K)~&$%~cd%uU|`ACk-VGiSBjt49kQkH#1I`=Yju1|h$05UMwPbe3` zhG!mtR|LcyM&kw61vwiKTj*pbOJ7cn4#Zk?s`n3SUiOTS&*#a_&#lidp2{!naV%sj zD3LBGo638sQcznTK1QaWa#+CYk?r&bPqijTL^Q{vhsQEMRc|x5nT^O-2rptPE4l|? z;IPm}$5t^zdSw^S_b|=W-g-hhW4AQx;Yb#WRJL|~@#<9Z=fmPJ?ygJK!kkDbIAlRfd*wc4x-Luhv|?kQVP9fg&ttGY&v z!YHoe6$6lOeC2AJr8*uZl{&$gG+1ULF!fTb>IGbUJkND`^mb+XVt0T#FRVi+ewEde zd@^jt;IZZeY+j=B?q&(bHM?kobPs<#jZ`3$rW`J)ieZE;Qi@gMUUOYN7fvGr4fBw4 zuLz1myz#D9(W%_tb^a0qC~VlFsl~!UfP*^_zk$tvAEvb8v&(}bC1RW-D%qprfu-#d zSs8a6Q~y1uzObRbc)GsysJ{Ft?s0FH2N5FIuO=?X2~L9|^9D9M0lSI~j4HdnW$~F= zPF4x>KS4m$EU`t^v5ULHuc|hVIyYVkXynan92btLh_&BE3O!L__9CyfGg3wuU658^ zhyW0f>)4H$JTN*3Z&O~VbTdrjzVS4MY&8N5zt#IYX{g5zWaQ}-Ld_Va&CtZ=3on}= zJHiFj@>*ev;lzFtJ;x)lja;axarv#3e|D zyw7tyn#MIPLy`8ckGbyF#+p=i`E@z_Yuy{K^MUKajX%6Vad~*1~lVP^ulC%FPipN1gF)S z_ICO>-a76mj!$p>l#$g*TpIa&#<{IV?Ll8+LGS0jYV!UDp@NaZg78A}*!b*bQYWF9 z=e;l&JL8;hhB;x*nKv*(N~$xqm_r}W418J{_=q|9l5Fs+#^AQg;J3uVt(Sv4DMp$&<>-)3mZNO?!r(lo#UCk4WsgB>RRSsWDPR;#p5!qwjOnhUXHo zB#{m2pIi_*0*OmALt(wy&Sj~W<9oRqd+TqE@FHbLD0`|c)C%KsN}&pQ>dQlzjlR(S ze$K<8JCISx>=4Gq4FCK1cbAep>FgRdWzIw7VyrXn^^8-Ei=bBB@Jt zyvcFA*(K4iXxzvw(R?;he|Fqh*3QV~nTgD(Uf|H}oVOwp!+};qTC3KgZ%0{CCgdCO z7^-tom{VW8P3=;a&~VMU&|~t{&*kVN(e)Sh&!p26DT(I~CzFcO)B1hW*C#W+`(`Cg zWj0Q|V4G?@u6E;_xN&6^*K9)OJCO)y@?PF(o$LgkXxz-9{ThqIh*3_vt6L6pnx@Ol zXVaho*Q}wWtYOO8(f+nPgJL_%30dW7__ZgFNXlfV_35i&Z(P|*N#2&&tYx+nKQoZf zZi{$++%t#1N%%%>K6tgTsAwWAe*XBy{7GZZ(f9e?^<1EM9$l_M0ABR2aUp_ijQJ=P zll+;r0Wncd8EKI5YdhRRuhf-Jq0F4{(V0FS+IO@#{bR>{^ycpv%=_5}%x>Sn(+tFW zQ;)~KJX_wsAQhJ4>{of=4tht78hMCyjl0iDs>kJ9z=|-p)BsF)I-)-pnB9v=Xtwg( zG#5<9zarPrNA9odftbIJr%nScU4o%%`-%>g=Y8lA@59Pk!}h%44j+OQ%45&6E?b9W zD<=~yVjFMec+`zI-H#=aFvWd-;wbSM*AL0%0xN}fU3005BJoyz9sc}v#cs-L~++r@c}r z77bZc2UHqiB1MD6^d|ZCq`O$q3JMQ56Yo;Id&g6Z4>u=2esV3Xo-V9T#=jwpcdMVo zIHZOmHz0ce_9+J7>-DHE#bR8+O>AB*E(YQ(`(QLs3Kq}F5W?D%AY#8%J3K(Q6id+o zTe=hqx}a!(Tt>56@uOP9N`($R$Ns2kYI5z8ht*d)g|`VIc({`d`VQE7?!eUb8y5pU zqAI{hy1rx`eK{mrgYm3Inr+?*`)Z1`lJMrekqH344goMc;0d1WUaAL1;8HKBo^`Z= zBCpPS?W^`Qj34#B@ntLMW{H==hi|ew3KlzuzB?ufJCEjfl)vt1Aa|Zn@4_~xU}43g z*Iue2o?QrVcW$@kz|LTu|5B9vEJHB6&94W*gKkgl?X2#(BlkS#ZTN1JHIuq^Qre5b z?7qa9_upALREf*SCk#F;>{7eCRXne}S((RLvp$DWEqV^ZNb4m`2kSBSA zhnu*_FHPYNAtfDJX_i8hP29%-Z}S}Bx%-@mfn_7L*&F>5v4$YtyE{IFlzfT)pu$%W z{xzr16FljXLG)KVuO5Ukbb9GdeLswm*O&1uQtNJyd$3+9 z+%ubNa6LGgy{z(8yU7!qU|=nr?LiXnbl4Wlm2!pdn=fEh`w#i_UL-t|%U&U4UKvOf zPZ3BGs$3l|cwFNvt7bRQA&D#sm!9MWNo^-C7hk@O$~I6}dryUN-QC>0jN?123)R+= zbR=U@#Y;`fBfIt4Jhv1o%@07#eKToJ!K;n(DOmgj$BZQ3T@H8F=R2D!ci&8#k&WxI z2)_S(P?R(Gj-Y^JAN_c}wBf{=ha2;gr=>$i_H^Hbyxe2`%(8ozEf^%llMdUYI(%3tnp0MAoN%&HDe>XgX)jYW$Dl00j)w5kfdZAC%FmrhH$giaFEslKZV;<4H!puK!`mj&1J8?ut;4$oBKZ;sQ zk1T5@A}aX-Aj3#gyvmS~`Xw}ZI{8(>TA*VpFLIPEU(VE^}X_b{8fK2cruo+el z^a5E@&7fGa&)JFH6~b-wR6k5%E(|FNNYMnS9WT-W>iSVnBD`xwQj^sQfz)AD0#fno zAtw!{TJP}=W9FAotMRnmaH&WapA+ai==h;11=EmPJyFQHjdsy}$R^A`H3`L>6%CW~ znsy}-lp$`62%0YGPUL28g@&ngOHLaWr>L(ee^(VM5}+uxyG#TP7onL~e~yC6e$!sB z-YCzBa$PxYsX-9=$Z}A&I+`V$63{fvLAVn_id~1Plu@V!A zpglLo1PfKrUXxRkSQ{G-Y)m9W1Of()I!OFr53Vw~qPp>Vgw>*-gmh=X!wXc* zI(n!v#BM#9p82}d6HAjQ*^)Fc2u;G6dCX%e_h6;y#*Q^_%{iOIwG>YJ0Cnkrz12|Y zkl0-JT1$+>_dRAz@m#%kBXaro5b)G~>O?&EwOWKbCy+*6vj77B(tO(bjp4%VXh0VL z8H@8kdhwyCu9?3VA0&%OxzpxAmsRQysxY#NZv=@tdf4QJohVmG@=*DD6oR*~>h5jgMupMC+1_hgqRVp? zB4{ z(V_qV4c1cxDOq}F#4_T(=J1m~&TMygyF@en;7gY)Fo$tyr^=tVNfC1yiB&pj1b93~ zZix#AR%Z#=5h!1J+9!v)LU{87ub`vMSg1K|j%t=MGiLl0_mC7j?+4jObM4E)8gYcq z!4Ithdb@Ah4$D2dq{xigZy>ge)|r_oktVM?b%zla<;o;(+!_)7YKCmc%g!d9`mtdk zRm=@U^l0Wmo}t{-5HsO-dd^#pdG~z?9>x!hX7e=W$yf!BIIoQ6@XvmF@C>FHJ5!k} zd^2Az;&3?2*C+P@KbvA0+oLShN4cU^#!3dOf+v`nM0EHnDlI}vWzkWE2K**!Z|aq* zs-uc5Y)v#4g~r`7BW0Co(O9?Yl^b`XO5Ao#v{8grT8N`d{rF9vTxwA15Qr`dwKeV5 zr4?4~hDBd}RW2=Tnx;BnK3U4}s{F!ZX80&UZQQuJvUumSi5ac>)a&u; z(vEdgi-PHy@#>m}9Zn0M%Np;h$7>7LIZW*!90M$T3I%F-&pPNY)mqwQ9F_aqlr_vQ z>Ar2488f$UIeNSqeeLD)ck`h5Uh;3xl^;=&;fS?4!VkyazS`^HR^$qbuoKE^I)GZb zLvLuKl1wyX+_Ur~dZ~?mZK4I&*V3Euh7L@5qLt*er7!1$1w71X|QEM5Oeih@Q3*umNc?jDsN$h#q!3zgk~ne@TDFOlaqt}lL=4m?G)-uh#j{|~A4AN~b-9z_gBDH6MQ zLVtCkxf`Dh)6c(p4%-B$y{RB%^Ba)jFb>JzQ1(eGJjj;c{RwxKt?D;49 zGtMYOwdn%|eb58^h=}vl=0(g_*!|3c42LM^hX*>Eo&n+uTZ_LRlN3cY<@?Gs$nKh; zab{+x+y@;{Eap^B2^w+n4~x+FXMzfgYHj@t4PTo;5AZW_AdBH$j;TZ0m-{7QZL@^) zYQ3}tpevCU1y|#W)dxxs#ld=%?%mp!rl7CXO+!Qn-&RJNZWiA%YB}@E`x|QRza6uK zywc>|K{K>cKfGYh@!zEPLmOF!xEINm2Awfx-w$zeAMnlJPB66^f~*fYAPCVW?%b16 zm(*d5KBmQDxJ$ti+5Ci@jSN4GBnl-x_UWH&UOwrt7Xf55DSSOfSs|lVOR#so?FRC>)Iz7AffdF4uzu zs!vh+CheU0DHRcpo=sS5Ez&E4Mt{+pRsLgl!k;}&D4nh(uz20W2!!#|h7#LI zBUXWIr84QFdRy)BTu2q&I@?BpYWdxf{71D_MZ;B=?|V1{#%UjV*)RWOe*Veor`IRW z43Jd_ro8<^2C>zb9gZRL`go#TWH9`){l^<*&-6xO#AB3-$gUc8JYO3Zk0tpL6O@9q zGpBPbpdTr3mF|9d?-GH?R7E&Wc)bq0?}z>HV0&%i<{?2W4Hy$nxy5^I@~!*dp6O91 zzBrR_J?9or77zXqh{7kP)M~mQpDF@nBBimL=KPHbK{tB^;S1wm8S+2{fsFnPQ*R%O z?NN~46%~mzOyk6;vPPhC4d>hy+eI+Yi3*QP&U0dvW#BM%h@3Qkk-&zoU*rC?1X9>L4#n?Rs4#RNHeeR75f{Zz#Yh(2pt53M6frlMi$c z-KHUqd=Ho$IxeSrpQ@Go785{+U?pQCcMr{}IS9ly&&VOpZu^rJ6-<#$^a)O-heYFx z)&E1wtBv!DHY-amj3%sSV)&g+ch*owulSSnG?q`NrXdbT=Ol2AqfU%F8aNh>MU zD;I1grlO1BE7QYLYu>4?sOaa68rEvHD!A(NT&%;!v@JK7d&&8wX*B_Wqi+p3J4Hn*QpF<*>1 zf1v#?c{n1+TK-eNa5$za%cV_C25%#7U(P>eGMl z#_9uZgDni3XFmsw`0j9`_CTFM7{71SCkElhPeTj*6Pavj_ezZ|{WAqD>;D3htM6~% zesP0&H!90+DjdFYsb5J?;@kL4*5ZNc7|iW$BUBftKyvz3Ij{t$8jl^;*XP%vXQ>Xl zR=44tU9~nY2^)O5i^2B%$$~X!f;#5-lgyh(eR~)qV?&%TKz@PmcN-I)fCFVvzF=rk zmNNF;Ln6N;F2VRGH{^j;#lJ~MOtlFjt$+a|H)&&}42GqFCW)IpePhm?@m4F5 zMI$|auD*FWVpJ8V> zb=`>yk3yl!m(SgZ;6fF^Vyw&GR~3CQIX3<|>hJZ;6s4g4T#WtcV_Se*7lGl%#KgY1 zRO6Bkm|M(BmCQ^W#S&&Ho9*(ZwZAcXKGjQ>J+J+6ADaHxxTyq&{KP@e|2b|HDQ*6j z6<5R=^)OGqLO>2?7c=G4HQ;+jxb~|5+v*2DF|VI02`NQPNrnf%PE68S1$XYPL2qnr z+Vck>PKgTIHn#}2NgL_A5dSoMo;|HMY?%6i;l@q_KE)8(3BD7&uQK$w`8*fvTJ+P= z2Akw-8x+~hfqGcej5;^-ABA{f9f{yfGsO66ijlgq+~a-Yrlrk6iQREW!U#f0H>tzF zY&V5V?cekMPXM7id<-iZOJ(oC?ageDH+Q5V3BRA81*Rb_TcVKo8?8Z4ZOywe6Vl@g z@3o*UFUw#Xc97Be)6+@O49jM{hFvGoJ;&w${cA~FFUufX{=jNU)#_rc=NDcL z!09mtP?P^vkb3=&0`-)C{;duAP>V$fOgh>CN~fG|KazWDUG5`GJ-$>AwZR_e}`Zl=ZZvNV(1-Os1+&&PHN27{4oUh z_vQ7!iGiLBs$%WW{$djRI+?N!D}!;MuTv?uO?{*AfOX>J#exA7B3oL@nT~59A6Qa)So6iVFs$O-jm?v0$ZDFZG^Tm(@)|<;$Ct*R3jEX%)aLJ1{xR z;_ndpY*qC^OLuDC0osmQ#YN)jd-8d^UR(_pKe@f`|i*rBq z=zmTA>#JP^gqzO49tpSmY~ngJ(P_v7*i@H&5F}i8fn=CToC|WF;N5-tL0B|895?(v ziUpoP`#U+2g8<1$X#;EU6Y*ZSE&sHzBV8nvjCdIdC8v4ajoIqo4U)%e!opa_tZ6~fw2p00x$_8$6hU!EU_i9k;HP}xpUnm#=Fct&Bs0;G^=WidG zoXwngFdh@_J7(Z!=9_{k$03I>=?%k{^!=5e(APTM&LYVdkG}huJb=Bn;JyF-$D{8& zp5~P}Lf-E0zz-RvUvBe;lAKhpkLKLuyQpoHS1-y|t>rjp&8IDm(y2dMWtZn5VLy`5 z#o&m|m=5HTL>wl9LJ~YnQ(n&x9?}u}T9qPO297Nh{1_!i2zWsq^RFPCdWYKX+2hRU zBPBOk>Uc-&c&XKD(%Uf#nQV5WK!{yt>p{^>UXd9r~_@C5@4 z+kK>%ldL7~JIs3=UET^rHv5S%Ttw0X`x|vBF(uuKIrlFhydCW0>5w}X_Ea{uU|(Pg zQK}VnXSg|g7#D-br(D1NE&)fnFme7PKM#|)=5}g(?aa@xJYOgze}3$T!~bIUwdv}ux1v5TK2#RkSWgUpy};|>-4lBWLO0E z!gPq6qepH=><;1HpcoIiR8Dw%^qXsHZzzgP;=g(PWUwT&YlI~Ki;%SxyZ?!#@t5?J zb}KjLfijtN4kiNw8yGbk_xRV**FNL_`{VzKxxRk)VLX!^8@L6M?pZ^@(5gmqP}%kv1*d~4WLh21w~xs7Ws)EnW6#7*Aa zHf{?coeD^WAq^0s`;2!=nrc2Hsm;$MW9Wgv3dVWarkG+OR-iz|O0}4jmXy8Jgi9mW zTxXxM{Uk{02L%l5o5AqyGbid~cO~@GnL?Fb)(Qe;&XiekgITNnGDeD$?G2yR%6Mn& zmDVFiq?lUpzFGy>>x%`nluMRqUey5y_NxF2^slem)ssMkphPfSjt7Q*bpB1n0OA8p z_9jMRj2V5imyjXJtICx&whAR*3f6gpo=BE@t{#ORY0oHchf$8T9432#{z>e_p0|Ts zt!h+07-A-QGaR;suFaKeR;|pbW@n<}LWH@QhnTLe!O#P`Z(U+m=0~duvY`?x&^tA1 zDqOoE;9J0gaj}K`6BFPIlP$$N0M&!ljHFJM7h5W{pYZvJc+c{pfb)nECDMM*hsyEd zZ;1hDDw`X5?BX`Wxe035nUA0A5bWrrW+Mv>pWOu1@HQF+5Eh{=P(?}Ke>#f(%zXZr zqv*+ue9KM)0P)=e?&PLrA8fz2ovZ;6-}9sG|BGi-8N;VW$*1C#^B{zNsRjnB%0(5i zOi7}O`4rHUZFZ?Ajb0F0xeZuKu-K`$%3JE zi$25|W?_=M(sHUGatj> zZkZ-&KS6l)LI43yaI{Ym4oKNo#Ulyx3iC5Ne!1*+1T z1{*sma9FFcSKVWV`Z)8#p-BK9x6t+3B|Dq0N)+MK z_n-Np%hm0X5=yjT>X|J^iZ7Z5~>}!+tw!SX(M?N#n)eU3=i_U z!ps*WhlN?bg!kEGLkTGI93i3iP-69{ylydtNj`aKim~ZUD7rNgm6I9dNnDhRv>`4o zOc8oqTvjlRb=@YUP$Mu@@o*SGiruZY_y85GBwF%hq}LG7!aPCbOrcJ_O3p@9zi zm=j;cdBEm#P~FhSm`<{K6Z31UaTAx`0t+DD%Ob4I0BStbB3p8bLnvx$cz$))V*9K)Q;P<#2&7Co3q~ zyAKy}xyinXi4>-utfqa`+!>_7u)VjDo=D3gOo?W4CSw3%=>~aKzPvGlHPIOjs<|@z zA>FWcskY67VM6?c!k+f@T?Ia~?GEqAmX|o0_BfGr@u?wU)YuT|q4}{|1Omkz zs-9NcC`EyFDgNQHREq?5S>|vH#}%*RYepyTc9pMRjb2@W@Uwue=nn9$Js)hvEHFi1 z2d2=TFEPF`6=R49F2A%lMYG{&@Kk7cS0(*S?VrLVj(2HMrD?TMt)uIpLC#M$0Q0zy9A#>artSR zxO)dLzI?V(Uo!Lt-hBHT4o}crz8NJvtiWo!hq)eM4EuGd>&>>PhCM1YGsIqv1{h^UBIxhAqN`ibQ zJ$i)!o)I(9&7w+z17kM_k3=u)#on@j$H`qup#sq1awbD!kI%jhJ?gS9UQPx2`B&S53l>gEK>>nF62h%9+f`N3S-o=Sa*jqR86o4gd^Uo%0~5ak_J( zK;fZ{0%vAJOc(jlT<2!7sMAImEM@X>n8+9VE3{2edlGW1T=XFaifh*$xm`(XJzyho zG`FnG*+z)BQ$us1hN=ZW8Ypud#%0+l@ipzrmiTyCy9=6sDZJaXx(u~LsFNKUG!HuO z-5}ZN(I*ziIOX$cn;S?quRl8qD^@u%%qwj#3)C9!pj662DPl}W>~-Q`l&OkP?c?ot zQ(oCP^#oT-a>~&nS( zl*epR@Llyrm9Jm@Flpz>GWh%NQ^vu6m{z^HoZ74#FG>qIEw|O@oLcP#v<>FUv!x+b z`EOO{pJ6SMDtH>j-9^|^h{i1vXo`S97&BY^D-Q$HqC1h)Qcj3F>3HsISw8}H)p8Y3 z!zH=F6+)WW-XBI9UNgV;l&mmf{;`v@Qt{)i@6$ld_ zlAI5fFk?e6(#7T;8eTKDbRZtX!7;8n!nYTh*mbLfsO_57s$8~FH(y=q`lO0oU0|Ty z6}vnid*v&L zcqSZi9;gEGR4${f@aCr$Ln(Lsg~IbxM?pCfH*Mtq+6tCL;8))rFF|dKS7N>)Bop>2 zn<=v@FNqkax1Vl&yp#~X&0jI!{A_!9zO?b{>@_L$Ix90NwM>PIzN2(3>OnCHyf5Gx z0}aIR+18bLbgc9~6Aq*08aa48hN%KLNK;JM2A2*RGTMY<**;)8jV+`6xqjq3SVwi9QnSb#>@7kfBtKnFWr{g9rarx*6Vn+u-0ldB75j2`uN@6> z>Dw4FdwTW*i3O&j@1}6w-dbWcR=;8fNrBb+C^DWv`1|5K#?7Cm`;$eks(>NJNiecc zf!a&KG$KK|V7S#Z9eWN6V;M;j=+_Url0yZ6ar)TA{S>N;a;0A5FAl-J12u_oDJYM$ zgfJA22#5Ev1&Ulroo2*n@Wu_tDa8Qy7_&M_T=w#D^i1I{Ib)Ex`~@213hCf1B|6j%B5awI3*?j9`JXVh9H{b;%wBLlDhG%QV&(8W3z z3^lV%-<>{XFSM979pbvWek%iM@3R!&dHt+^xTtFKUmGG_8T<#P3miYFZ3=00Ev zS+;!E7GalvSx;*4%=}RSc=keOmf55gHb;|)cVbr>U+xA5ggH|*P3zxHsdDKI5?euD zUzV`aL>lFwFwWf~tTc&+KU>mG;kgIA=7bo(b@lBp%S2#s5}r@*n>MMkc8V)fM(4?*%}510>()RAQaLmy z=h$HdY>FjPqG@umg)paE(t%^64mU@WIl^wygtDtMdw-WPxg|6K0FR99FJg^{5|A!6? zjAq8VVo%vrVA2I#S3 zZ3IpZ+gnZZvFjQE9nfh&^jlS7@c83F?{c|&x1Ase{!h=Z_&=}z_nC4nKQI00?9?(Z|M+h^%zUdwCM~#X8gdi5~1$PhKdwC+V~e8lz5A&**~KG zr>`&@$eq3d&Bbe$9}x9|D13H*Y$6WDKF93NAYwZCa5<-(ZX_kQ&AUEeI4hD~47f-E z$jw+bl@i5%=lsD09;1P9IKY}q5p>vk*Z;I|C)cz6z zp}o_@vy{esg)`iGWTepxXGndn_|W-te?qDJlXu^FE#If}StYLGMelLn^H?eHEkOMu%qs1+5VqNky%LT@ zOwW)y&!$ zKFpWztU1#g*GfhmAu|uegBYL;K4Og^0HR&a=BkpdJWt|7ev0^P)&YTr3t2R_N3hHvh@?3B^1W~p5TFJ#T;Dk`tU|}`+7@}Mp*wxjyIneYul2UdV0<5a)NS(qg^a+1=d6uo zHG>SDb_av^dkwz5V^FtZNCX6^xWr{B92fQqdRv7Q{kYKqauSd#ZVFFxQ_Q%XjQw{7 zjYjte<2nu^^;4S9xcH~cyhR#j%!AWOiXNYi?ezeKwE(WX5Vo8^rKl#Hxvhn(F{4l3 zUfa*QzhQhhSo9%{Y+4NBZai6vpr~+PjS^Nq{TyqVak3U}yYO&5t7o-wR+r9B=xt#q zn`#7->y_Rj#*_NO=W&;$_AeW_1Alyp-ZwP*+5zlyeChn5e7@hqO848rAg9suZ^L5T zA^>$kh2hEPctfGBxx$4u2RmwtWbbIP3C2?$!{V1`JC$Ew{@4q?Y&$+20`}jto;1|- zo(E4{=^BWWy|fY#9obvw#kx-qrYP#bd>!da$s&Lsg}gN%NC16sHSl^7;bU>iW95JgdWu&vPg{<$CU=REK2?=2DGO z%J3scBCHH@Z+{f*6_~si>GCd@=6gu5$XRuiF@EC4>95)twdk2FRVr|?v_ivZSOuB%9ZQ@+z1If`HFf!SB%^!m z0vJiNiDkLG`Ue$|If=dZp}b?1k!E@^$sZIg_!5iX8A!yYjMZ5@$ZS@!mid-4`wlA5 zy{TmPvNm<`_WHvYI3G^%k-e$3Smq#Mt4bEAaid35py|`=Oa}tuQ1RX z53S9=BVw(nE~FmorjfHtCJUqD7*;__6hh`Vx!IFdd@Ppf)b^xBd`nb4dcOTaFK|qF zON{fEj+?_D&q%v6)`q`&w<6VyJD7dRgoeN_zO_{JzT&k@lId!J{tSn9(}xEY4lh_9 zeVf&4J=3gopD#6D@zlW0M-?5O^g=27kuS?6NQKP<#b`N^9zJAw_4M83vLi&j(;w(o zh`WVEx1-+C#%2cI^dZ||N0hWQlvGA=*;$75mtM_cRorZCiSoo2j15%k2#smcm`%}XU=yuI+EOD7f+T6CUVIU9){WAu z>ZH>nlNDngB;3+_)|8WPDe|K_5^+B^Ol&fT?QCSFGUzQG4v;>fh|$>3CG&jWvlv^S zYT7&N4jKk+C-&Z1<8_#MXChh)pcgE7X34L(InE1R8H9;#)g4FlPjIf4Jv??c{& ztT6bU?&zds;WyPSN*VD*O&-21S&`_x=q^3uf|F6s5BCe;&D|lBuKhg(-5fC=-`&zq zq|GgIf}V{K(y=}pDmw}G%^W0D3-`O3lXX|@+@#gpfFf#6(%vLiqSL%_3q-Sq5Npj3#5I1An=^!5?cuPg#rcetx4gF^l*BA zPz`aY;E&c%R$^XuXfHoDFbafm?_!C_%p)VGJem?N>>{|%4GfJMXea8i*r!j9T3#C9 zf}>$%m*O(!+Fr9Gk-x37UY!i6Q_miDZ@yT1^~u*FCh_<_R7I9sWjI$0R5#EFWz1sg zD-qeP^1e`?A+#));R`n_*p$+jSKykpB-5jp<~00lV&KeoY$qz365npI#(H%$^tI+& zA<>I11-i2*PYUw|X4GfCek7n6`76({!QG3 zE{y_NU!@6E`V(KqBwuDW4F(-QaaTX6pdV+5A6QePIFAJ!tld;7WA5V5Z{=m2uf{Xw z&zES9rr-Jq(FnFK*Q-k zwm6pry4S$CDsu%3v44U^ks$_h0CRrr?*;!9FL!ev}~r zf+3z()b;elxH2T)d?_NXLMVaefF=&IDQBhs-%amLwrF*untxLemDa89S^3n?ufox*Zh$x-aCdV0e#vc&1Kx z*G9;I9PyjJ@ZqNL(T(u;)0`7Y;UjVpGgc8~F(G9k;hiTmEUd)K*pYo3cxy?KTTPKW z(~)0JBKIhx4g{kPb)t^kqfV?M%zP=j)FNM>gyXJ7brwAhlSBENQHKde;wGc;9}*K3 zhY(Ul6F-c`V~@TGk0$bnzLgw(+d7&iG@2GCYA7j+SvLmi5yKW59_$xc6vN}rfbxot z6l(Oi?}6e=ju9+Pjupa*)Q1rp@DStBgRptR#hYVgJmTa+qwcU1r({uN>O`7aQtud3 zm%)f-O`_)nBXo-+^g<&ZorZnfh&Oncps$-?3h)3=n=#HpkNyZ%J?=0uOpL{F*&Ki#C>5cgUgCiM~CJqM}+4%b)wYq`p);d`W_U z>_>f>Ho`!ffH=OKUc1(@EeMyIzv5AOvQ(giaMkX7yYvJhb}xV2v?CaUh#s%$o?;JV zBIi+JBgZP*OB!1XU57b?Zhz_T)cH8ObMK2x&ca@~+e5v-YiT}dn>1bsUF>QeTySglgiX|?oTH792s^BOc8IlYpH?>J?_2W2ySn|lcISvdO!wotHxJCivt7M_3r7Ngyss0Rg2|GRxt;H}7jZ-sV_b4hH+lFoh=E zjLSjiAY2?2yE^%%B6d$`-7HY7q;5_*Jd}|z5{{}4Mb8^1fs>2NJT!$K;lwSIA5G_& zia|tViH%Ha%xODn#?K*1V1GSN8zDyw3Yb})79^X>qY8?EsT1Z8r;LH&Hj}%IoITQp=?p2;(>qMDIO` zD*Fpczl66)tP-`nXP7B(_#`U)75357tFrCvNa5@2$;s9)9Y!qE6)-Gn7os=#0>3f& zfbQ<_M4Vo3bH4^_hu`bC_04v_m)dBjI*>%g?x6oBL)gK8Q~UheAocfg4ekH6?cvzV zbv)-XWq&;HzFvN9UZuTmdtlu?`B(Gm0#I*3`}xZJyz-WUR6v>_-rujhKVKQli$74( zf71l~&QJcekMuXpqeZ7GKbM7V5<6?JW6s;9`)oGG2wz$Iqd7RSWkas8R}km)nB^P2 zTqNO59!Ap24KY^`ARzU%*(|Qw_y#v)7e5|=S97R9Ynsfg&Y`M~E zsN4%{QX+-S5}1V`k=qwg_JMYVVl>>sjkh%h+zrH+EyR3EfwF~!_$=Dlp#Doaj1RvJ zXMiR`0(U@j)Jm=7MT&8E=rl)d$(en-v`r|T`pxI<3NFzT=vLfsgtN_-?(3!jnc zf6wI(&^Qq>awwN{8=c)U239#ndN{h*)%oUE?T1e8zQPX^L&dhPXBx_YnFcaFYz@t) z$=085njx^YqR?Y;C>FH}cH{dk1ME#x$#$yL$d%pM*U8Nq!U2g)xmbN zlMfeo+!ToOjiMYBaTacB8mam~iVA5%9%9RLs%&Tb4L8 z38_^HsZ0MnlwO7|G+CmBeK`5?Yim|H*8vYpaXs>8R&m$MG8wZ0{d+SF>htQ)8Pe7tXz9{I-NELaL@ss!d`z%Us4q?=cA6Fl+?Y0cje zbz_Z%Yxr=vqzR{@M3E=19bFEcKKsI>$j~WB`iisYa~-16EDW!yeAXxq9S5C$$WqkN zb?+b-3o2J*80PcI=Y1jV4{nJVY%nwPOnd%UErlEmgfg-rkau>y(ObCzuJa?L3u4E}0^SjK1mX&7j%{=ifi z2vZdi0bFAh6nIVz^T`;FOD<3h_RA$B!Cq7mhgYznB*4>t`7yX7R_2n5TTRQ{e1v9E zv3i87pA(E4*opn0$Y`jf-8el^jmKVsv&Lg>Cae2pCJ z`yWNCKX{>7Ckp>JBErQZwLD>?r;Nff6l5^75Al zeQpH{{x77>Nk41biF-wPD}Sits5Th{KXBa@9{9vD@`8G$OumXo6_Ij2v0X;#f~d`X zZ?n(Zy}+gvH-fYuaDl144SfuW=KaX`$k)i8Xs6W+6tmDC7{)c{xwt)zO#-?yR`x2j zNp0%fRYnE0C7`uG!t1I_vK;+Ubycs@@lv5(6CLL$!v$;|-R}vh>RkXGg)`vzV)d`7 z2%o`ue1H)qp8)bBnB1_~)j4km_c3s4pzoR|EnheCQDTe|CqtmC>D){*I6ewJ~gul)0*W{Hsx+U+b@Do7}C#L|(t@%e!tg zL~+SCFn0TxUc}@}LT5)K(;;#U;$fz)YzR)qmOiMJHZNHb452ln%=zqt#~MtV_SU9y z`^m$Rw5NJ!Yypp9XQ*6=F9)h9b#1jr96PQAa2=P_sg_o$k!lo(2l76&E^AujK$L^` zIn@3rZUV_s704K*4tx!+i<^JM2`R^Kz^7W$mq=0sXbk_H39;a~o@o2!#CA4e^PR!Y zxbq8+OyCv{zfO*DwM)AC`7{L6fAhZ;$5yv7oVgUv@tzF1p`6eELjD3L-V%zKk$O}< zOIlpyl*8d1=%Hx}^)@j9X!=^kDu|`JlW(#m*(%xW_J(aGn?_`HH`PDf##0*uDe3X{ z)6jQMv2g|AG?uMLIk$R)NTg1+D~;ZH%ZOjq0CZWvSb{EpYB@9on&cP%#{9wq<_E&f z!>?jZX0bIYK(NAj35zGKnGpY=Q{%t&80$bLAO!Ha0AVluH3$rf zct|^cCuB?e<`7!E0@h96MnGVGhjKM}oj>8ir;e+z#5=!F*mIf${T3Qq(D&1(B44*5 zoBNCEywV21g@M7KJ&Fnc*LU^WY(|VUybSC)1p7Gbddn?J3)0%5V z7RYesKoWn%J?am^@W0s?l8wR=`yXBKf7`Bar zX(%~N9tT9>$v_2@t5*h5_Y{EUSMBF_SpwX&N_y5!qeV~2l>x8j_LQ;7;7h9Jqn(em zoOt6Af9?xi54))!D8HQJf4UYiFPbSzuOYZSUKlpo_FL;tPj*+x6)DSI4Yr1fR=?p2)+CLVzi%)M7)o7*HgJ6_19wt(~vAK$PG4Q2M|7ew-~Ny$VcvD z=KI+|MqLNMHV)sF$Ym(YAD9_v|^fZWlnE-1YKrv^HXB~hUwbCxPZG_`CP|4a8zDI&Lon{ zQwup8PRlEp3%KB0Vxn^XB49+47gzKU>zS9;C17lW8t)!jmvjGB@0$%Yk#&cIxk$5gfG>L`~su)%X z$&%-i|86yrr=4hV^PjzmqiHtvTw0BKOZ@X^aZfZ_?LKX34*puh##>9>G&b=M#)Cqe z+>IamMqx>1*fsH*4kGXIP5#ydOhihs8_}jGA6kq>K9tnrO0M4+tr8#1P@=Xg@^2(q zyW5m%{MEM|1Cx&DmEf0^mgsL4ZO)BP7vJSV`0vhFwrx#cTRPkRv4Z;t?cDO^i?$zs z>U}q*mm2AmHI^J9AU2fGkBLTklL&Kl`WJfmJV8)A8J#Gx8_VlaToAdvAuh-%aA2xx zS{ZVJm7G*U7;~l;U}%baL_xF#Y(^jmh$m2lOpT4{h1x533Z$^#`UenTlJNmU>`aJ) zs4;L1!?Em_m}HfE3Yp_HBd2I%AUBh{$bqgti^nb;n4h_Qk-H`)6iKxp0%p%br^>^J zA-VEU;yJ0GUo@MMKHTwIn;!ngj||5m+})|8CzM9a6CZw%(-+HfuVB0>CbvI<-Y7+Crn-O(IJ+8bScVrs z%xZE3=x<~572{Rr9A!@ZIJnIXl&_rWTNZcKe9XUpAXLZMe zmMT^DSQQaJ63X?f9KU{;NY#Gwsl{b~_Pa18&!@M3kgqIdCl1S<5jVK`-%;{@s&l^w zI9-1(?MsFMpOkOhm5*^Q4+Iu7I>wKc)!%LC(Qg;mX0G*=w+ejy^ynGZvB>SFy_K$L zYLzcPvK7|zY2NPKYHRtv4MYpK`!nN@)%Fgbt|A`o9d^uq1XR7h*5XzMd!H<8LD@1)#H1pivdN~F+H-%6AyCeHPY6?`>X1{%5=BR{*5 z{_IMXGCy2hbbL}wQ#mw0PTOLJB~in#nMGgElM0$_l;cqlZ=1kgko>rYsxZ~&Lvlfy zR*GP6sijcm~{kX@#)Ju-UuY)?RfTRjQfP|lW~&~9XT+Of}=-b`+%bdTpv>dA^q2RbSK4{oiGPZfmqiKW@Q zyY%gz@AoBAZbeqG86R;y0U?O=Z-451GjX)Q`)2K!-hNOy*kR!uT3=_XAS|#>>$8{D zNZ0ZslZc>H#B4R=2ec&iK!FoYF&ceRy-z~yiAnuSRV!TVqFzq)EaFF}raIVW!JK(j zcOO11vv>3VILAZTh(8eVCuiUG3Y zGJb5_tE~6tZfW&4?e`k0h?w4sGVWb zvgG`{cR!%?EB=s)!#n8h`hF#{{_3PId{)6;0LN7)uR!=QKG16BZo~ap2}|3L6(wXt zUmXw9tZ&7N?t5GnyjY9Pyxd`hVVw>6;f`mW?L@+Aq(5Z2a{jg)ZYB9*{Km)AT)Im^ zW*MS>M40Kg+pYH-($X!6=%Bh>)(6G1T%K|tP3rO*YO!pkED*`FE_vMD#mY|y#?sH~ z3Sk$;s{Zoh*|+M8a5YP0>Pyt>IW!B;#!E#Xlp4*KXtfGy zm1)%%Ym1~X-*>uSl@ed-z{P1$DWqK;Gg0mmUuyWZB(P<9qQdEOsnL&?sSc7O_GDsN zHVFo#V*umrh!=KdwKsJ8geGeu((TLzymUXvH`FEpz#$6i8O4*ww{!XeEV+dBCR^O< zt8VVvnp1zAyqa`tXvi;r@^nytuEwo8xk-*)Lt$?P1$k4?`^xYO#SK{PNq5+HzD&sbjn$xK zI(bSMSfXHlEy!<}-LTI2=KRKn^I2yq=GVez>Mb=dz40Rc`T~`<&EF`P@$M?ux;Pc#~&X&8ncQRli!u=-e3d#gu&f7lXbDN5h<`2S3BM4!mA647v7396KjnDmYcKUTg zL+$%r$kUUqyIQ+KXTAu}VgKrtmz#d-rN}f3ZL)3R;@u4fT&KgwG)rxDLTA;;+y45m zSzfw;!C5|NQuHL39rr@ut*b%8$^CL}?p<_uokH|)_u&KR?MLsH?%F2MQa$Px(s>iv zGnzxocx8kkaw(4NJbNnC95x}w_zv@MVLw4JSviA>sY{@7)`0(*}!^SZ@3+PDcPC@ z66O?rweRhJHgbdV3?NnqykU9XlW5^G|KpCkT4vL*KkL1D0+o|)ri^{0*z+YimD7Iz z#Mz^p*!44aBH1T}KQ&fJi||rMCI(B~zHB;U>w#@MhFnhR4B3fcb`ToH>CzNxe)CuV z5tV*w2o?@I63kIPF9dX7^UAx858pqSm~3gXwk#8biTc~W9M)*1?j9(e6sT1c7})r;PpA`UlBB0DKwQ;hvDATEYiYY*gF6eu zyV&zMSH&}j5?-k~6Y4lPo_I7tacc`*4}B1;SzZ)9UNWq>^;tNOVZyRuV~(qn5H`wC z6r1ZH#iN&$0ozr$C?2g5CQ zl=!~rDxKg|*%Wp>6?WPi)?Q@#`Mc>4ZDO?`-BT9AT9EUqj05^KQHi7OcjDlp-WQiJ z2VX%oif*3=6uLix^lY_4BF*)7K(;BvM0zOcNVd=&!O&eclRH-7iIxVBdff&lTrF5} zzlVfbV0qbDMx9{?3HMlAH5xq7!DC?!TEXxLokHQCqT<)x6Ii3k*gbB}xRWPG_s3h# zBm5L7A_GpM!vcdCHeFIbhZNWQoP3Y`G97aVC(69YBS^q7??DV-v!mRV4C*cAleTG7 zv`vR^=H71v<0N$BI;`SehnQj@@E+=zw`!Z01_rgcTDle3YdnlsO^(-Tj(_bM|EM^= z@@8zA567*oS^I+?w<|B`K@?>1u^ByN~7;gXJVS2J^`Uu>9GBkahJ$>dh?Nf95Lg!5SELFxDJYz95 zV_7$2g9`Xd;)-F?#>E>$Z*4Jk@VuesnF~E#E-9i;L{r? zGFhT+3tJyblk}(EO|D%ZOBKuIFBbxC!Sx&Y1p-+{yB`~#u6+1SO{vLMyUwl zPcrlD#xwL==sDs?=S+mpv+Jfao6^`CZLXpzs=*Q|wDqh&Q-^TT z91M{n#);me>C4J+P(OYHV z$Sn^EKBpCm_q^h{C7sKD_AN?G$_8FsqO2tU0Rgu@Th@)ekM3L#8 zk42Ip&U5>n0HScI%G?_PyT}GR5;V>-o*z4^)-_YcY**8~Nb^7)TY+d=`513TtBc|kdw<8r{~QNg=Y3vr{_5wX@Sn(H z|Cu-Aug`ysQdAFq8+gU1Sl+JZvCeTF3x>?4-QZ&FjrY$Qc7{?ghGUS}FMf<9<4Y5A zaWL&pen6#=WT9{2m5-jsk?LACsE8v`Z;I{)lf@EN-WhqGoMGh!^VXvrAmi({qYfd$ z*qL@7Ug-A9#w7Vx|Ei)?l_&kC;^H`FG?G#2>&>;fNC>1do=?W6N#+}MzxK1IUz;R% z`94ppPg=IzCemv}dVG%$)WQjz^Tzn@EJWE!q>H15nqfd_T1Tlz^ipF$g<9t z#9H8&E|`x@Iee#XFE0e9GBvxG>6iQ^4|Pu!+@l~m4zQ7$t~ z?x~p#Kd5ZWH34Ui#86W!gQwnr5~)}t2jNnqgC}_1m+}A@g^GZSF`-Oy1R9fii5?@b zh`!q8UN3{4@K`L0{aR`>EeWxP{q4ZzzRKtWv_yFX$O1-(T(q0} zULUp6VuU#mv`QNr9vrrGBWP4dXB4Kd2K1a)5t!eM@OTm@ozeQ?A154xogeSVN(-9> zRVWA_4;;*jFRI2^b~`O9|jFDh`@ZvT&LncoTlvp9Hr z5h7Fl%iM{zUGaGvCMsi`6@NMWJv97S`53VZjb8t|A-vO`idj5C@Wrn)rt|Gkg7N5W zcD`1qZRZiJ*+ORQ+)$XBWi&!W-ezMY#}>q`Ey3MnozWJn+s?tIW@{->caAYB*)OZ9 z7JsG!BW6*oUMFums?-)E$+XF79O@O{;L_Ely1lk-mVb&u^eM^Npy8RtrEHcCT-1gS zQd)}N2BEY4&KjQ7LBM{|2^}u@v6l!aIOc5*38jdoCj15J$(2K*$aP@!H&8V_O(!92 zYXq`tJ$YL8W>-kE6yhjcj?>{i3K7No zHKc}RK9>XRV2*h-u!5BWcHxM>b2SjQah{>h5&bpZ^e>hq|E^%6iLj8^?tA#RNCxE{ z*w_(PFc^3vLy%ukbejzMV@RE?D{OhcWHPj*?=Nm#e+6%LkH-~%$o6%&#%V;`320QV zKAvSP`u}2^zf0RlHs#-3HU72RDT=RQ;+;$;??l9zP-#VN z>6b$2@Dv)XOA5XZQ7&XzR5C=uK${Xm!4T7dVtj2caxHt)5Bbb(h7>)6o1i?=!l>t) zdkj;tEfarSFyvW?ouBH1e&Xq{RW5+7G7o?Pw#wFk7qC^{qxy%oxRv42M|FSVHmD1S z$?!1f5AJ@BB7Dk&{~(fH#`{>8N9er5KqPR}c;mf>L%xi!$m?5wxiyJb824T|THLNO zN-PUS!F{Ih`I{8xFE(2}f6&;zpF;&O<^FvDCG0P-{kckY-_M~su3=9_APo7WM(7!8W}gUR#Z zEYD@`F%SE0r^)o5zxdUd#bbyVzxxyyz|i7*uv!67lYUhS73roS9`Xw{TlhftFPJ0t z*)2X$%w||Tx}In<^2?$xkB9Z^U_jvzhUx*MXxjbHsG|izYohruC77=z&Twx~H6m#* z|8Pcw*K;am;lP-cF>j;z8o6Yy60I1;2TcSTPszLAIUL3r7uS}H^CItGP=p?gPybx9 z?|a#;t@6SDD6N+1|5;k?zcH%&YioShPR@4(;{9PJNeeTotADrLlW_0%iF`xV`f$O2 zkyblHnJ%0D(^eThqU6#@LjA-+mVSq@@r-cxXE|_rYcR&OcMl7luRTDHP zsE>=3@DHTZk!|+NiIx;gT#CBOE1etlRJSlUR>ySGBu3knnIS<>L31V2OwA&Py@K8N zDJv5uetwW+ocU_X>+V9cROgd=vo!acb+Zg#c+0hn0AP`MW*~3Fnvr$v8dG-2%;%hx zc!AGmc``N|g}LcjpVqZ9;$XqG30Xyjg@x}LHVQLppf7b`ww?laMQc~q7t4fBx;M+4 zkN|wg)#4iPl`7>ZU zcp|!$&_x0w%a|b2Fv?bYpU5eb{43TH7!`;eK!70Iz@+3s*-|lboi5TxA>~>?@ z?^-e{;RXal7lJ!$rD!?<<@dvD`goHy0k0)n;Yhj6I0dNzIK-9kJYeBTZMC8gqcr{> z`ixo*QNHcW1L;P*osY->Z6A&!I^;_&j|ZrUgfyz1%(+}j>Yf}(832*4!d#6jW=^n& znmVQI0L`1krcjSTVCOeOptN}aSq?0+f@jBH;vHE`3Q;ZG*K7-mw1vRKa{-*H4A76sQbb^ZpS+$JhHw+`tXhMZ zYE=kEXc{IiQ(i&flTy5lsy_g&AYDms@T)lR$WawkEYz<)y*FAKJX)+H z|3Yv|5m*H*C^7PTq1At(RvR^1W?#zsd=~~e9E_H{4P(_snO1LyA1e=hP@<2{nsHdw zLHMj<5hSKH+U?={E~ui!RFH>!!r)b9#;akoeKhW998LsOh&gLjR_1`}j>nh951I~OT0&pv`M-)%yIIV2v2Xi{@T1%~*< zE#9w}dM4TvnHWmPxVovk-|#N(L6QlFk&A9E>9(|i(<09}-#sNchr~fEQ?~h9Xctg! z4grbZ425H_&%Vn6VbPrhsCG{ss&Wvs7MHWg-}718hA{St?;4BdWRLdFyPOts3mNgG zo{tMeDRieH2g}60sk(=!;G=aK%bqUFyTes!xf^P-eWN8F)g?yqo6q{E#;PT&%jk)+ z^6nDQNaW!$ryv8E!LVO9Ul5Us1Y8i1DRfsL;dL+|eUbs8&s&^yO*pIp)Gwyv)9%-G zQrO7K7SWWPk8gR-LDcLFZ8eVkL?CP3#}l~sN>RNLC6(?6+yS92HST}xYQUWVww9z|qOnRfiRd*Inu z1^fZ%llCblLW?s?L|-F+HK|m|c&fCu!kS_|rq* zpd4dMKTk7v;PFtGdrLSD%dDk}E2npB)Bf6Sp*;Z11tBMM0bZ_RIhgTKcGx7hp}~O> z4XV*f?a*4Z${(s!&arVGpwZ{NGBlVg;gvj=QkQl0^8JZxIT!u zAX#Y$H@Y}*DMtYSK?5SoAxpdwWRw>>V-$Cme(dZknc$n4=PNwo3(~-W+P$>FRkd0) zP(!`1@rhK!99wN)lZpvnSL$)z%2Nj)qN^jUgR!TJhPW#8PvJ)WllT24A3Q!F;x~2< za7qYptP42%5C98Vb)5+CJ`3=HX{Ve6{SyK`>jM2g1qMRb0;>-MS|!D1m4ZGEzML}% zN=gVysS8S*2+BAM>aXy1A0)f42D@7ZH8UrIYM6pylBqF`unFg|kwB+AUPR#K zr)0R{bLRf%_rn*Q!&lb)ujsbwBWsA9!mNym1WvA)Lb1jNC>FyQ36XHW9pC7h1RYw6q}7^DvlVGNim9 zlBqD5IWeG&DU`7gmRTFcdLG3?5`Et#ngf~`&A=S`C_3y>VVDR>4CrBu*k=mPt_Z2g z2l%KoYB7($10q_Ju_+0WffG@J593}1M#ExjO{7B>CIVi# z#N8{5wpfqjMT}DqRNEOLIG=f zDudC4sLu)3V3P3%i3y2`N%e^-lZk2TiM_`%bSZz@O&rpatE?XVam2x>@MMv;pR{Wsn8_MT;l?@jE%xn-~Ch!(o9@|Ok`3O3KPMu z#N ztcPI`JQws}2QBlPOWHVEnplG=CMlw?SE`(4&hUATyjG4fFjwJ6Y;98R+1*Sg<1F)d3IAqIR$KdC+I_JKJ>)=wP33eHFSvs?zfeC z^Nh9{&$!XBkxD$-hvEPrC@f`KA8WZ1Nrua#us{SM1AttCW=x!)GF3S9?(NfR3v&Zl z1Sldb>eIT_M=u%>u617-^0E*2!IGVEpEB@nt(Bq5eIo!s3qsC11q4vTJ%8XWHD@dq zjkxOb01q3^AuSjuzmz|zbi}pvYf)+XaCSDb>pq>ynh$_B;3*z9 zq7FXyTO+zT6c6)3zJ0t@oM@zLP=I#;p$azQTE2%0LwP={A6J_-HqZyk>`)?yFczm6%VQ$ZL|sax<)IRFFXfSPuk{!jp}c z?gOjP99y{1qLV7&MS)eHDL)OCPH&Xvgp}qcHxx8B$Q27u3gk14>d_2YJVpd$V{^Cr zm@ZZEd3IOdAb3;?B1tJ?sS(|kBvMHbMF!0ATO{+z?3K5zayuGWR0YQ*%tRjRSqJy}Ar_}GkMMSU|T18O> zzQ-ydmkNxHQZ>Q%ofiZ>i=Q@Uz%F!!H1NCu0stTr_T{1Pic{O7f7^T)p)-8rXC$My z0!TR!HDyJK_#}X_9c8%;CiMw292fHT9Pk{+cK#!9OA%Sc6UOnbkskuWWgr^20*%1( z42M|b4s<%$fWc|sxpyxt7CsdFzfi{Lgz$D6D0kv%KgqlxE^CDgBP|JzA*tb#>SaLM z;=)$Ka|Y>Sg$UYCAp^AST*%cJowT`8AxI29yqGD3{OEPj5(KKW@}zP$zCxe;t=eP? z2#uf&EYm%TuDG<9v3558#s%*rIdbi=`Cj72e@>AzbM2zTKaU5PSV=a z42Mf#`$&HNwVzGhIf{JX@xE^G77f%m-hrgdE1QU(#DrWPKj3AoI$F$NcRyk35Cw(5 z3lv9lWrAkzEaSylxWKpJY35-T>)2K0r_+OZL==>yse_>B_>|Vl*@fCKf`;e$8&$&I zPY3BN2EJcIB`QGD)|J=R3)40z)i$~wHu*NHpE_n(I%eEEW_pL%)i4B8G;+CKs5b=yRRgQMF-pnUC64^7sqPcgVAi3`>)<=Jy?7^dGrTV^vlZziRqpz~txJ7d-!$ED zhfV5}xCkNp6SWD8sEMvOU&Y4A2z zgJ7xGbNnDg=ani!Z#YC9NWZK#zI6C2v&WC|umM_%SX&=4tEu(q4VPy(UlEVKGJu+` zIeV<><*ykAtQnoI_2{ffn@E(kK6#*v3j!~`^1wH&Q67m8L3iRpm@8p*NY9ToKF z+2lups~21S^W57HD264!t&@6v^Hz3sRSFDAT2Z3rsLen;?BF`n@|<9;^$2Vtv~1ey z8_hetn|A%F!G8DUyX6wO-K$5tH_f}yvR(LD6ZXC#7+tS#F#c8a;6Pv2U>XR2Ox(IvY_WdUgdZ$*qy7#x6 zqhm+;smRutNZ;y-E=X~xo@aPOi~?MSm7&<5a!(xwXD<3?JV{DpIL|+%9boI7UkVX~ zaN;QG9lIyublpEn7(2(W7?Oe#nAlzl<484n(S51swhP~ITU^F(s^mK zeCddE)joUq0eaa?9~ADYAF5c<6CtVd7_{QWxL|*FleOm^zQXH z=ykIC-Fdy6uWxVWB5oFJZ`NmTHp_3epf@{I(5+cA1onwfsnClS=&YC@fEzT|>IKD^ zx_5>(-{y->!0Y=-aiJp!lU*_=Vc$?9l_VnBRkaqF4$My`n!YD-i z$u$p*yJOkQt(T9sO!`uV-y&0J9hnb#q{d06Y8_jSl|FCrr_esJnyS8QJ=>M4eQGn) z^akp2ISvt-Zw+fyb=NsR7wPRzX-V3$FCFyoOcF?BkyZ~BM{-3jlv)AXc$L4xk)evv;HPYV@?ug z)07?*)@l#LiAOlETmm0YPAn&y=N10)*k4acoc++fZNsWPgooDu3+rf*QIi^j`u9mQpTh^+n%H2J^5U%-=Xl3JEE)_p)5 zR-_C;^BuTc#3MpdeSRh7|1T;Ta_s~5MNu*b`ym-ff&CF)@_PnQD=-=Q(dud#`ZL-j z7zSYP;NK16N+PBWzE`9{8^Y&Nmlgi7nQ1ZNKKx{s%yW`wOJJ#*lc$2PL}7y;;==N3 zvE`U2x)!=|IyfJe0WcEDj2dlZ;omBmn7Hyglmh_>!CXiKV8GvBWTHPRiA^hc#mG$~ z;X}mwuOZq$6oUK)reFR&2}adhu>22@xg(f3P2Q7%!J2RIBoJ-tc%LK( zs2p|53-E&0!#7Igobeh!YkrMm}WtOdBQ3vQ8WQRKUVWHc{Tf z){< zB{M|4n&@84T;b8K)}}mq+f>5kxmE>K2%xuam>c$1epZ=E_rvA?d$j28Y^x9YZ{c14 za(9*ZXyg3;Hd^#gmD0b*L|v;p=6uqGzgJR2UlAjY?+>EbceJ?()*~DLm{av@W#!In z|3|x>d|-IM2iVZyUExFuq!CyJo0Tz!|6(rst{=N|bJZ5BUf z`~z(cjpu=dw!-vZu)%z*cFwG;!nf))jWN~9wm3m2-jOK;`pJJ5i}o*9R_ebvx3UZU zeiFr&ud}Fq?DR>8vg=NnD$S(MYqvSSt=bs%VOHJP;%Af54 z*zD}THlY8Ggi2V&`12_7W3nsN4r!VB!4ZkG-rb-e{*eobPRUlw3HxkYR^;7lzIbYd z(#n>}u!xE>gBkzVP`*&f{K`KKrx5+?;#NUtdeWbAJ-QAv-rY=}wfWA%W190sEE|#W zLRE;-^WI`79`we<#h(Y^g`euU{LZ{71V{l^0d9ZW)+x9CPVEI=)Si8ADm-z8g-h`p9!NPekVu_ zU#ntQm{y!Tf=L!{2@-32$?!VFK5Gu^GInk^Obm+O}-?QbYVi(`<5sR@^J1 zwle(aE4HBM+v3he$I@mKbKlYF9!{&~ImDpdw)}LecY^Ias1+SlvT)B3TLDOz1%GfG z|FW(7lRN#5AW;Cz8Lr{i^5E!VqLoPLmBMx5UE!w<75L>kt5q$!6v;jsU>w2EV65wm zKr^-!sA3AUucA3egzefe5=9>D!(RtD{Ix_lGprh%zbH39b`>F1{XYyEaA_NVeE9GF zFQdV&y8UjWpaqYKrfa#OcVf_g-G<{iX5V{2fn^gmkohniOx8zhwy={IOe?NN?NS=o z?eonr?yD(GgM7QI{22v(D^&kWi6%9ur@poNU{&$y@T>QBy}da}1v}ekB&Uhr0V#Te zR)<^~Scv)E6c>7$LL#Z2>N42-u2P(Ev_$bcohTJzQL7Bdx9jd1gm?GP?q3E&j~QVf z{%tfkD#Kq(l%Ch_rNiko5PU5WaqTP_WpstM`B{#{4ecR{&qi-xRCwBr9HOJ?k72GqY_4S z`Oi1qem9T$IG|kJo_sm{Hi_={`_b>&IlpOt|H?E{oz^n%9|L@-aL{9yF!e<2EJa2f zXUFAgL)6B_Q%`){?y1)!?TW+$03CP*XS;n6rv7}qI`z;LN;M%QeY&|AOD0G4h~@}R z7AfiUCgqJ=uq7dzag?@>kvwzAEucPMz zkR*TCZdVP3v!6UCj&!+IfIBK#OO%<$^J24SK(E8Y{@+=Pnw^L6+8H&UJ^`i{&QjZdl}J z*c376{FzZ$Qu95dknFosykSV>YO-i8yWwPGv%J-YH@gUrCPf7LAc*pws(M^Zoil47T7IJ#&NF6yB66A=1IpqtoHq7^gq3Y zDQ_!{gw)zf6?h<#>@nrH8zr)Al4xQ!&HdcxpY1DgLC)TB}ZU5g5iQQg_9FxZ0OZWc7%` z_0@VuMMs~<^I8dIgbfnt2+vDLv+8Yt_=&30`wp$uT5r=7$g_58>5YAwJFda!OavCUApN<@Wus1EpLp z`4xZqmzr9Wxv#V>&vX3@2@#3o^_|pb9Kg&V8PkyS_@xxtF$=oX*HeYYY3@5D4E9h@ z(=^c59YlJV9hvcymtHr+6Fy)`CX1XH1_pOL1D|iROzy2~4{@<8;jXlJ*F5t628Rgd-c`x>@xW?|SkI*(wJFrr8ob zTzLmFvO8T$#ZN(TNi|>M@L5ZjrnGkI+~JG0vpX>NWV4Hq1Pb3nU9`z9Gd`2qzMnY> z;cS7nHPU5LZJWZ9tSST&)NqDO?{=1mEvwCS6BKp8t z+CLe8N~G?I9?1dIeskn8f`J~+QV?@18i_R6;3@0+e(swUu_)%P*AJ&mPM_50fi}AGi+C?~*o^>+N z!Swkc>^C@$pHMiBaGKb{x0EcUgj<-Gv@TBhadfZNR;z{wo z%DIb{<%55s$^r;p9~W-mLkz{ery%wKFDS?VTKbbh15=e3geRPJ zDNvLY4@twDABo4nKF%Ao+ws12~46# z0f3|g?|2$PBL>7M&zE#d&hRg>D6tHIxH2^G9CXY1u1_`>ku<;h5Tlxm40MX}a!_n21M zacIzsVlA`Rz1|S#IcV_PJ8jgYHrV;nVCYTuj(1S3?0HM*Xyek>eZYiK zqeO)k@GFTssd)E8)Y%qE#e?2if3wvVT$`m_9RDbAQvvpoTdL)VZI+T`d2{_*0?wo4 z6KH1_oQtu{{6zD!_-AXcm$>&6T+gZX`lJ%jc~+Xd&c7ftAA&|OSnfwp`t+JA+)Ei3 zTIIDp?{n^}OgsIu`snh!U$~7v14Z6Ej;qH=bKzZ8mPDz9V8b9-Z8!laOe85QVA_2# zoXy<3uHbetoPk+g@I-z?Ir(CwK%u%wy>|m<{5=W@KQ^{w+AKwF7^~|$P9-SW)P1ot z){I#L36S41B%2=25Oz|)f9Ux;W4s<92^jzR%tW~&1O4=h{q=_br_aoszdwi^erX*U z!LR_YZTy)ecVZr~eiTtM{O92NqQeM^#R_#7_cq7Ni~{_HwRt~vp*&~) z&`ZL$JEKTI{k6o7doS{q)ulygCt-~kD^mqMqoqyU~xmzU27ctNIUdmnWz016KVM26_WzCJfi@pDQi zOX>qYNDQKSukZwp`$bx~&LVv1EY15lah-^t!R$5oLAba88c}%M1oQM@+029_cG^d4 z**-_#0*#csaq$Xs=;8e0;#I8AXKVC!cBUN4-oJi z)9-E!)XE@7SX)X-Guq;=sH4W@#y|% z^B}0n$(mxQX*W|={7}w%P6n>8X}%!4#(V%llx03BDy=@F2>HB91y3K5or%?`rA;fE zuy#zqA~0)%MMAP8>q9}AKv?jWQawkb3jFp}mTx6hte7%pol{1S08-wU{fo)5kGQS)6JtqjH(Ab;Uf z@WQ+=mHh)fF=c)x2@{wztDy$g%}_UIvXo->OFq}*EOyEoLs?vH#BOl zW5epM53DAHv_yGY%{txE-5%M0YCE7HfYo|EkG9=i(@>e6X zqe6y@3?N#LXO#EAv|P&!WGGsb(!BYwngy0*S{LA>lOXoktm;Lpj^S_+i{UZdVcBMX`C)!|txbdy0cDLP$ z5buoQJr3u5u|HM^LB=g`P)iw6{ffK7xHy#}qNMW5SpJGT?am%bfeWN433@DFm{ zXs*tQqDdZQh~mv4&HLdSnj83&+pN)u5_lJ622wk-we|@%-*Kd!%PFRNB&gM0Mp& zIO(478@VH_>BjFP|EOxrsQP}Yx}_UH!|}9dGr?M_7YdH^oHyEC4X{tJD6zgp%bpsI z7!hR*jVRfH$$S9uZ4Jny)(irf!kGr%;?=AzgmC?=!D1NyO2J~d&>vI2@F)z6CAnpa z!lfwTNCriHAQ#Nzle1THIab5;A#RA46LX~K?>*BD^QIgI*!-#&M8ECr_pr`CRd#>Y z>xmcYKl7%fBR-ge1u_4ab+;$ofAi1kRdhh52v#rr3AS-qXIjOA*(NIg1=u#8)zthW z^3QI%#s5zr;s1$jZMEdB=BR1m5g~#3m+`8lmk&BXE6rvvF*ilRE|HP&d{yOrC9+&QE^dq+& ze9K+4&aB5__RmQ1*A(-mGI`#(I$DktNmt5@%IxX2NAdqU>w0e3>Ud$_w_#KJPlJly zIK<@I^4UKk68{2e$)=?!mwnTt;U*iAt9MZEL4bON*Vi0@hT)a46nii9r-#doY~y<4 zc-zJctvk|s8=ZEi8yuiB+l^MwrU@6mL5vNzikF{{8<=yQs+LIp|Jhk8NR17terpM`aZwIH5J4)qiQHa-%Pw1<|zCz zDwzKyVLX)am3nZ*06VXigSp7NDf}~QEC;e1J##hb<+43FC0+45iFe)1RcahlLzN>Z305_VX~9E~ zuW4tjsq?rbE7i*^_0|n}!CL8MTOLg8(luRzBz1k5b`ec{Hq&e^$gXa<%>Xifn>Mbr z#=GrYWj%WV@SMKe9mx5POr6+^ag1FD7oT5#6!Zw4Z@c?M%1#t7o;s>+egiz*3f!AFnDhQ`vNqX4ZSRJ*1+Crc&XfC7){L3MFLd(J zpPg?gA7HpW&&?KUe4Z60)&;Wu>hW;Z<5D4Etv#euN4AuR6K}tJc0}f&oUi5m%usf$ z`@v}K2ltbE?4&po2on8GCnFIeW5+A`x*ivO;{DD0n=N{H7YDOBuGd^Hv*)vC<5h2< zv-W5w01faZ4n*EoaPFmXJ_wEh;zeK?v_pM{OBu%Qj&GbHvyt06g=6e_=e|C2MNLas z*dB;fXg|78p{CM8z@{Ny~G zo3j{6mSrG14h?=}L4o%du(vXK)@4Qlm~9LkywHJ{n--wYgYIdU3;SgBV2BD)Zu654a`(=R3Tm zX@18A=2Tm4r`uJho>40l7zzfQun{=wB&REdJff&Ro*IHYuk>JdtF|6u;S~9{QNj0N zmcWbXh~oX3-8^Ct6<-?pIcT{zQG}0VYy+?fUx8KSk$8EsIoIR{Eth*_(WsWAbw`m6 ze0|}yLlEyeOWAyVakjo0@fP-Ta}Kwr=Lsc{n)5XenAjAn{JjQw0)}*k>|{xlC%xlgqLCHY6(vhH=s>iKcl$D@m3$ zpI4G?#1cRI8so%BGiCYW$?&`EtmmhB-Y}bI_+na`X9iLhnP-J^Y?x<*AF=$H^X4Sd zS)j|TSp=CSq$`tb#AZLzEQ-z#j@l^Fe&=cylj#m61(v)Unp!HU9ZT9Qt!Zv3E`Pm2 z%2wX8AixHxz;!FB_BYW1uf#!O>kA1OC z-B$Q!S^aJqnQi0V7;Aac(M+*z^HtxbZEa%NGlLX6!W7eZRHMS>b{&?lTpeiQTXr9? z)aCX&@yuYtPr?^pxjzy=Nko(3SJl|fWy&tL?`A9CvhU%7y(gok^F}N>GFPlN`U(z8 ziuwgk*^c_fQRI&XB^mD=4N2S!s~VQ!V?Q2Nc_M#2Dy<$eB%W&NX3t+TvKS$9451Ac zxCzA#7J!}&JFzbXE*!HQ9q~8`7x^yA3cH*@nH8puu;%(%++DBPn*!q8Y`=u|d_7xa z8GesTV(c&eROGm%11MPS`z~B0$N12NH5)S2C$d@4pdfM$X$L+$4y2V4u68a87O9ER zZD7*1InV7-zuB?a%~jC68tg!c5bFEDSAMlWAQ)kC)a}E@_<8SJJqN2#4~Jm7RdLt} z)0<(H2!`yD;fSfN9rgnL8_2u5#UpW>x7TMMGzZeNCEj$ta zv>Nd;G|NmSD|O(RLBy2O9WBw0xzeg?Hcc07OX?CW)Cyj);zWqA;HBPRm0I)*)lYV= z-c+-|PG04bZK`Zy(E61q)=P-to7qdeNoeZ>USF`a(jne6USw=O#x}0!*X`piCl5NA zl$C-t-e(b(N|kvQ8tWU7dLkX;vs$@_<0nwhiCoM_csMHHr$s-^(h6zyJoGwbpqe2G zEJ_<2hZnMBV2dn=ec-#7hQk((t!s+7lq{e-v^hVwe{W z^($HWc9;|YK6K|O|Ir=GrvcqU8Mvx`V(ga6xj{`Q=A4Qu8)M@fqqQ25ta0)@fkG}% z27_Fyi^JLxNv0~8f!}bme0?*D#P&txh(ml^#nM=Ok^4+=5YZ4aR;a6`t4xm{_;@}r z(_a^uXaSx;d?iW@B#G2fb4m6&J}Hig8dvG)8)O&uXRQfg~d zQ=w$IQk+DJgXY)(++%%eTuSxWiY`*i(f8e!$MI%9H|#a- zh@M;&cTSDJKknSE*h!wf*->xVKDPDDUFlwqLX6NJ@Fm3mGKVBs*M{u@@uiiUN7Jrr zCys;QAFzPA9~)qlfW`20sQu8B`8&Q#V81L7G}d);m66CywFSqKD%mm9C*wG<@se-W zeH0n1hzMX?x_jvSQS^ixtoabY4i4)WhdYSOCpTu%uJ6`peiv8yWtrWrzDK{W!i!Ov zr-}M;G1|j>qV8=iZ@~o6UO9gUxnVi8hg3Oz4mGgxue+J>$A|rlk^9n9-0269`lw~@ zF9{^=F=}WDwHj?)aut7%TzcneU^83|$-Zq;o;H5F4tafYWufy$A%~q*qW~AOo zy@~ZcY@9<#D6NwyJ#wX`pm`)3*r>{3S%AJoD8uRe*sy8K$w+wps_gX;tsy~41pAhe zw(Af={>cvbji7D6!q>u`gZf&Eovb*wnf0BMrrGDauVDYhB8Pc&Ro0ya5VF(>y zZa-r71Ard~0HB`RM>F?Zrhz)6C0tQz1H{-%#Dft*y6_P;?#p;!U-p8JEXGpa>$w>T zZgudeB~n-H44~c*m%1x0SdaDsIIkA)pl4msGa}VTd(3pAo69i4t=7vlwX;SHxCtHB zn%OUEbu<7ieH7?%W{ZtBA^7mkKA158oOh^;*5!Z_}%4SAhAj_E~f zS(5>{UV1&tjf98oeUo96k^x{d!Kwu#lC5~DuOfq5F;5kd0bn7@ca~l@}RyZQnBK42kjEj2CE7?t~+G2S* z@-P7u7#wb}olZOf*>>nM5TtD+l={Z|tCYz*>n2y9qva7bhz_&Wsh`v%j%3Qoc z{H|Wm)4(?P7HE@ZU974vuK&>v)b9gbeE~s;qzyh=z z@GYce?1{*(fef-EFah}7%mHhpfHiyQQu+Zc13)}a#A~o`8Ixt>laO5So10cN)&#&^ zek3k)60}S*bt&wLI={(@u&-xf%=uyC{NczIVe@NYjf0f)gp~6u?#8v@QTpij1~E;U zuvbMRPVAhlnCzCi+#TzXPz}%lAk5}DEE6t33Lo+y3Lq8*AUy!&LG`$X*vfjoeT@w; z*2h8v0Uh~~kGbALTW!AZMJ-E4ZE8d@xkRy85U^TAv7JY8kVG@1Mc-qNUh8tdhMHrg z^W%~dQO2EMk(m?3t$3a6MQ=v}xYwdf&w@oXW5x|#BZvSXYNUlOBvEr%a3)|Y!yXNS zR5kzvWgs2zVbK$#mGfiQLI9@qZc2c-8as3yY@})cVy3yDQ;^^5LO)n)pzCD3W?(pD z8;%5;#mStzCDYp|Mnb5*zvx`xlv<1}F#zz;CgL2O+W<>n>P^`I=EOJ(`- zmz1{wDGvG8P;497eQe)aT!XH48amMkPrfF z3k$(WSFv@xl+|?7hnZ;~eas7N;9sLh71~zPN9D98@A4x_1-;20=QYL#U`u<(J@i-h zbj&?e&JM!YZ=+jJuALrei@Qv~hJB98!#?d5zwZbDW3Zk?M zV_XZT_zM#)3zKCEAKcTzz{!2VogleRVkc8H@-UYN6_7U$2Iza`kY<`*IQZ0C+jLu- zFuX<$h{n=L+&xL#h9r)x+G?4-T931(3yN+KaEF~PLW~Z=rzL#q4t=DhW5Ci0fl>!j z_op&AYmr6INXt}7ix;|caYf5?H*%|hMYS@N)NN(jD&Y=;R?;8M(Ymour<8jt$_LxZ zhgQnr;V7U}<%oh1WHLyf7X)#z6rVeF`vMZQLaE3UexOy6{mM>*$)4av7@2GZ`DFzq z*}FCKaJuQdyXfKcjTKs-Ab2>AVqRr?zzQBW2%cf_8MFvHmKV~yPO|C@dGXS;@Fm{q z6mPW`S=Gy`%E+qP%mj&^Dyhb*yoxHMMu?CbZdMTicOx#ZV5K;mBfPj59<56CZ>`Oe%k^SQ6<>35X|^4qSs$K@n_4d#RmF5ep5=o^Vo z9M5{{y;>;+`N#@DRHnx%L*hoqh7I}Rb~V@N6^1~}Ep}$yO<1EPgGICftq=3=1REze z3Ut+iQPu3O&6q}2lCI6Pan&i`$bHoffi*aZc-UXoQ?cMc{7#+cw}4=D<&lGP1qH;1 zlH^F^s0AcuJoNr-Lsvr;Uk?D#>+2u0U?7SCo@ntY08mH+(CH)zH6pw-P_`H0q#NLG z`jGVA1-V^CPF|t3BxXK{o`+S3#i!9M>M+OIh{exp(O=JwaP7`LESLqB86lc9vL_9! z59lBy>u5Y-s4xIlK+_9maGM(av{}M1bG^xgffdy_-?)Q5@_`zJF}SaJ13Pc5sei=(p$SK%g#qEtSaq2wAOVyFER16#0kFhx15_tg zOOqeN!_UkJ$C3;0m0&mB>BStyC6NS~-PW(!t5YhkGa{2PZOWqy2bV&Kr%zFgS6=&M<)zXXEomHv{JRbR~uD2Up zv_zjnaSaEMOAQ36Hd*;_q>(TNbcAGS(&w>pW#;#REQZ0H>w|g5gPD(7a)FtvMHcag;U~E5OKZR}>D-F%Aj^QBmo4#(kRSqKAh{hW7mafT3r@{9LRLf4 z?^M1(@9ER{gVKNCon!2G_a$AZ7+=b{3I3Q;$ z)Jdfi-Ghw4t@j(!NW|*uvxx{SgvYq3M$J-TSMp*Q&9ozId}t*B9D_x&qtRG}VQ+e) zfuI~HoOB|sLVRkJzM^7mYjj*{Ocsx+B;%Fqaflk!Z|}NK?c8gQGS9^f`IZaEHhowR z{CH@>(IbY}#?so!Ac zr<#M)_?ZyK5?#pcEsYPLlL=C3jslMOPIdKyS;VjN6A*ODG*)A%v0%izBn^Z;%9@|a zIh)CIdh|q+8l>hNdKx-P?_UrwjcULE)+b^WmCJDQ%2W!HI&XKUufsja}?=Y#WX(pSf8Hdd) zOok>Z#vsP~G@1B(@zLfY83~F!9Sr{F88hptMePDHD4O(2y%p}R_R!-%^_c?oob!}B zEtB)jVh=u9KrEe$$byd1*@U5HhB(utgmZ?Z$#OeUHP;Z+npfqLPf;FG3zu{RxB9~{ z_1eJH6&}J>8R=CBVJ$n~>aF$_HsgdVn@g$^NQ-ar$cTg;eMEvpZqgLV2R_fT!B|b@ zY{%iXMb>y@ttJnx1Oe}L@rd(Q zSXtv~33Xmg6x_U>waMtan*Mk*zz!8;$9(_5pW81CK@5 zrR#!|*POTO+n0@Zms`#s24#UdNGdn!D%El;Ss(2Pq(4(=+39q02_tM$H!K((-r<4l zPHOGSm+j1&>`p%}m}=jh8Qxv|xGP4xgX21Oce-%Rhx}FS&c{m7-um-i6nU{$vBaKp zrU{q|)-)^LRPe2N_UIF)5F?Oq1>pa=L)**t(MJeuaI0nGQ|!(fPYw7nZ7`i{sa8o; zR1BRoim79Z*>sQXCW@VTpCkL>nign7mTXtHN}g%&+5l@|#wR?l&^UPt@c>;8U6?-{%ky3>xvS`#O7B-}th`wW&p1 zyRWxGP)5xxf>bZnvvFXXdX<|=?MJ6ss~HPNE*CM756n2Qh0k$*+uGjAVLo711pU!% zH~|1`HXRw}{k@p!X(G1Y{eC){lQC;wK+cKgQ)-4iTio0ZEc3kVX2}aYe`2x@04R;_ zS=tg_a019~xY5rt2YWyUkSoz;1@%@F7Jqpb+5p1IH(Sd9wW?%QC6bZ@Z-SpvRXQ3Y z3qSYoo<_zfCuU^;uySTzzwHUsMRNE^`8;|Hg%99g*o6tukP|FM4rHs-2!ylRWg{F1 zw?2K|{_tD>>mc8KP$VlQ7;uVZhKm6uJnTFLh?oT+IWUQt7^(|dAlQfJrw=Ft5<7j3 z1E=YP6(fZFG0AKPr(HVRj4+E?N^ST$dHfrT6ky$Dg_r`2(rmq{y6ak5GJfaSbb1>% zMde)^*a~$ckwJyn)nED`P#OPtWc1<$?~lFx&EpF1!=v24gqdmp!8zyN=ta= zjWDKpv(X+Ww{t_O#pKQ=Sacq1>i?e|On^cz7UEMV7MBNzQ_rjt8_PHvo6N63F`Tj0n;W^>2Z2OWt zjRz{S!nx=I2m!O+wuGGD)mb8aV%5#aqi4GZa~Q~NZ3+Ym0`AK_k#iSTqs#)ZSI1W@f zf~YM_G>J=PmpN9<(Jla=Aw+LXel_@D#0cE^Y0zDYY4s>h&*^)K z6JleQnRlsXtz$Be?%0PUQoVPGi}5tFrgQ?=Wd_K^&tXu=iz*n5QT8*+5nD{L029gI z<@#dV59cu6_@>bu_g!Y6C7xmbQxZLf(zS(Pl+`t}FzUy*%_HbTo0cNji%u+}NF&8Y za#fo3q~(pQJ&JyE$f2cgkP30JvFT%&Gc#2SL2xLH99HU_>g{MSyC+J+k)0qCmtfh=H;Gv zoyZImbL*#pi6i4L!^(J>?!D^DXYLa>O#K3i{UT>`#J?Y<9hEO1Nk5!>SY`Nd-eG;- z{=I)k+wtNP30ZH{Q=!M+t8ouyeKv~y1tB@iHgw-KYm(Efv+u1v)E&5W#PmJ8ULt$N zx60>GYx=lht?zpj3$D`Cuil`$7e-PuYx;*9sq2$LYZ6Nh&sfW&eU zi@HQ&QuCt`^PqknQl3ABcKd>9e1D=6Fm>%sg^*jcZ^kMvPs{i%L`cQ5F`?;3H%+(j z1JP%!#P@A`cH!I#%bTh@*FzIjC~M%#VipC+gkDnCJp*-xC9=|EZeIP-$dMYRi*B3l zls2MA2KgUU1g~B>rBr*|GHd*`saQ$8D9+#b5d*_}8d<4I?I_P@%M5!>$}&fLv3>{H z36Jx7NkrrB>2Of6O6vF535Yrx1Y2@&Mj+Y=^{a$w1xqIirE%5B zdA`h*j~-9GGk1`c3atEH*8#Ss4F*0B*Ms18f+5%d>$5Z{ zhYuSS%lJ5p4jgd7hhW2D*_faLumoAwBLX_&du5GMo~5bC6%Jtc-2jF^RlMb!66(h7 zbdJ!zeqo-g{aP18dofjLD=r{r$CF&xVKd51Ka|DH7I+jFY-wWAdaGN5)lwzE%1r!8 z%p5jGhaayb(Nen4oE(r1=4g-0@}$37j{rdPQe}=Mt_3>MMjTv)y-E)YQc{8FT%%FH zZ^U{y*9+G%4-x7wVASCO5Nw|HQE)*iAsSC83CvWzUCI+#KC5DuW(EfKVh3x^EkXIy zC_pTj*=uzcoV3k1Z#!>KqkqO*9^&eLy(sR2nBy9i&YOF(btb8{{Y*O3*wn~?I0hMO zpbiTO;>Crud2q}Ml`%A8J1+yY$4d#=!6yXNIXo3d3@~pyh1lMv3lK2o0@Q8b+0Vk~ zfW)+>A|@3gA)-7PmSO7T0JutxC4%aC!L^DeM=vnImL--~3Vl zSV2`3i{$rJ1o$*SDP>?A`u-k@mqVfWZ>aDy{v<^C@r+*Lp3?_uFta)c2JDV+^yH0ps0BVZ{QaSp6t$0P)6! zHV1%r27}0%U0@c2|4`g3cAkO)R1nExPUutf(y9*-JelX4c0rQ|Zz|=v3kfE!Ouz() zp$Lih8+b}E;;SEF1#2*B6Mc!7||hIllDEgLyI5w>PxCQ}65BEh?q(>ew0Rj|} zLhNjtj5EH^)IO-Zd%9u=l7F;Wa>!%d<*&?W>HoajKdtDP0Dvs;FA=%8(utGX0pJJ; zvFNmR>%-3f-J~-CUO4-0s~x z!QBvK_gg?$Ca9}$w0nP4Zhx~|=ozh$W10wdk0?ja6|o*MjZ|!+&WrVk90|*G%D|qJ zv>vL0p5xk{>(AtIYZ==jx)7?FH#ey}VK+?Ui>X)WtIKm-_vv)iaz@~s!=((yI)y6Z zg|4*>8ogcgE39-Y3e*-o2k9gmv^la0_)C&dAle%ivvXy<5y>KN&+p+X9L-e zD@rJu$Vo#e%DaR;H;vGe!+I;(T1r{T=j9!D#fOf{hR8k%$NG*qDznpq^>+nT36Qi? zkn2~D)HLoyI;v7tio~+qM|3Kka%D!+tX^#CsSpYvjQveb#>KE*MywfU-$-GLEkp1@ zFJew1P9dWhbt5wX!OjLAR>9YY7PQirvMgfKxH1AjDz<}h{W(#{W5E*9|q@4-?gai6UVplPHU$F=d zO;ZHA40V;__=bnKIcWI0s7t^xIn3}HU*xBD#aIoAI6H*3@{0P}4mA=rW?*4LSVCIU z>NRpHhM>FzO%1VT;q=jJ=s#(UgtPh7)yN$VVazh4Tv8Li__HI(d;;Fi}-{ z91+*B+-?LFty;hRGnF{uRZBLVl*qN)gcS1t+H-V?z|@ zL|{yVcnleM7+K93ju|(a%Zr zeNXTy=wZoFfNxU}02K1rg#ZE#jHQ#BhW6fNQ{`k-t-%=1%(>z=t|~=_f88ODZ*a73i-y#Ph?$4P!=G_%fi0A=B6NcpF^(fBO=Vt^CAT||_0L>pE_ z6jpPbDTuI3xTcQgMfEf$i*4Bc$h*C!kX9a26`rUXL|_NL-paR|-?s8b0_t0?Mfg;M zh7c5YCACTHLVTbA&*~6Zk2YctFK`i`^*Ij2OX`?F`&6>B%QeJvB#{g@0j|kdwdd}b z3B+%TV^$aJUm;>KBNkXp&X9Y`VHV=O1ka%$r*4iLDi3?EA}Ux;5%ZlpgrUR*hsPCX z%2lAG$2JVfFzlHx(YA<*fgoUy2bMqwwast<5YnQYW>l{bCNh9sT~{HJqICL7{WbDn z5aFIe_(ioIWqwRd8mPeW>G6rcMG%hIw`xtE)`--u=fbMwm?EI7rzB-A9qM-_stHo)VsA;oK8$wCW&)L7 z$h~x#GS(oVLs-}8P?KTY^dfdTL!z1NTO9?#ZgeeTI;Ay?m<3;xhk(Vxs8))v zaaR`o$2K1FCWrwW)BrlRA)5WAnhpdKfIyzb;MV*Z#u^+++Ch~EF&!t-JNRUTA}@5Y zn-igt`YHJRWAAmUjXPQJl*^k!Z(+*ql7`TT9KFC1ZH^;)&T(ZTw$LX*2SHAd161I9 zW;-;qB76t%CjEh30c57+LQ`0M7dqUH8OTstXbO-h+DH~KyP`@9?$*VWQiVy5reX6) zSrIl;V#HC)h^yxndiEQwvd5qw>5gwXeUts88osRLyqjC?<|9-73Rrklodl#Vf+c*KarFna&0!^v*nwmuUzs z#0Qd)2lZFYd5{3c&9oU}YSkEmwJE&gh`!69GC{-vt?dPvW>3gW4btEDm~}koSj^Z! z;S$6R>4*dH%WN@$-)KrXipEr=R4-cPf;;h-%S*akUzhsP&LwApM|yqvLQHA-s{XRL^|FNiGWRg=wrV`%5y8`)2ynx)p!LFcj$-dxUi;FoktK88 zGZr)><2FZjzpbs@2bCygK4Xijug8n#LHeW2qV|`&ZCA2vmzp%=O_O*`ajn;F-*2X` z1m)bzCiD3DjJlP-WFwAbx^O5poG!wF3FtN|5(%|Jv17ISB2==t%oif| zY)L$lR&rC8=da>3()ZQ|w3mxEQXDPptyl(!n;VNaY9HaLcHzq%L`3jHGoj!hS^9#* z_2YLk@GQFZ*o`*Q!PUrFtL_b}p2f0+gN+;7HV>87EyeMl?#*YXg|A~lie@pVE%77i z3DRu|lK1iSX5xG$Ycp?G#rPy7^;eea;18FmJrQ02H3JK~)hbG-AMQP^yiSuP^;C=C zd9@1qju@b`NL+AUS~{t|fF($kT`_g2u+0sRA{R-M_fY;s*l(%6OPDBfQayaWZ!-uJ8}S;=pN^yKeKPY#d81B zOVt*6%xlko^2w|(hWv&&#Q`w+>>Hf_mB;-$K8TK5d7<9w;vd7s1 z9*!URL+SKWO!HeW6^Y)a&QH>eLn7bIZ!zXcvvPfBRKstvT=_Rk=;;5yjphCy*f;)b zX3)i-G3MWW*#AnJVX?h?%VRtMqxRsP&^eL&BCLa-XGEqQzs~Fl*0cr6OR9?l96Ir& z$y^#6-S93z3>??u zlxATRGv3ApIB{EKii~bsIVJk9bpFWHNI z9cTm=3S?0IrNcx$l+E-%5LR76#(rtp8%r_ik#+h(hS9t73w9?8J`QVjM@K9PDLw%@ z9-pEkmMPX1-4Em`8N!-sdOR?DSh0;pvX_VOHVGIGg)>?(Duf*p`CHs!w?G2->TC=J zODF#V$oSD=^3UB3ABKN+nEaS#4+hsRfkq~LUynX7qscHGvd1h(zDbc@UY*8r_2aGxqp$DW5ssIGK$aHF&(v zf+(mEQ&BQNNSDNYD7MaodI!+1FUILWEzrsb>m*rOuE9LLvQs=jOp9!w;^G6<6EI5W zJ$qLex$#HK-pAI@ulPQ_IGA+!)ONB~{;B=@5j}n5M*Qlh&TmO4{OFcFV>9Fe*F<&q zVIZNao1-W}VlTNaw#zH;&9cw0Af;=28Z3?CFQcXJx{LZ@uCL_Ba=Pl|yu4aroUOv% zlY9joS1TxSA$_OtTyCX_p7Rx6(lfy^RNTkThHOkh$$IjbF;{UP_f|pNuhy|;i(Cq07mt!qT{PuNp?rr*ne)0xd09HAlCiE zAd<0_{+|ruAFI}_rH;xUz?i+?H^;vZ;$h3>=19;(K!oFEUxW-M{Gp~AacP4CJ^zn3 z$G3J4Ew4={?YKnnS)^a<>%QnKe!<=T6T|l5HimD~^oJo+I{)^wZ+{G8^bFRbyfsRH zG2m}lA0ozU0XHD#C)$1#Y&N;dD*^|(@^rJ4N@4#zh`(WdsO(mL$NH#_Qfci!R7Wz# zs$BMD4d{FP2Gk3Mtfg2c*{wlY1*w18ajMXv{uMyYKa8DrPTT)}?C8#}ex6b+y)^Dc z*3QGKjQ{92`Wp=KZXW8R#cFY570mT97U^q_%TPZdj5UaCpZTVaE(9+GwxUPZ;7)Y8G#@iE4ZB##|66*J~u`LS;NJ;$Qpe z@}VcJpYMfIko-Azn=9zTrgk!hpKQ~#*>Yzz`D)-)p$~Iq*k007>esq_4e_n4BGJU(S*cR~#=M}SX z$2s)d{-^D?Z?n(Q7BdvyVgM%9Np`?4XSmLTak7aV`3sd|v)ej6E5pH3r$MMtan*iv z9i}{rB~^?^=;c-r!a|10^P_vR78xwZ{&6J|y4<@FABtwAv4>tgZ_-DjdeEb7K^CzR zui<>v6g}FK?_@~T>{b&A_Gm^Q4VrIqB8g=odWoh$shzzQE zHeDGP=em~$UUaI~y7u;|HYyS%_JxkVbY(wAdm|qqK4bMqC-r7ghUeC1vB|AX(#)Ks zS+>%mqOz@IwaPL?j?%4*jV(FP;lTs}u~3TO3Y^4#2e@(P@wO5HzFzq=pws?HK}@{J zGp*Oo2kTXC;`rNI^|Ix=+7-^*yN!#Yyhe?vq$s`gwIX$jW>QT;aO>9oma`V=F#V@C zva|S-HiErv2n0)GG@c9Jc4>rWb$GoTipkwe(hjPcP;*o%-X=NzSq)!e z+y)!bPy>1e>5_&vMCM77cVgGy*@10PtyD$mAG!;;u?Xy}zLA)C1`irlnuCuDmpLAc zX-MoIyn`zX9Ln$T$|Q~G^6_v@_PJ(yM5zQ>U5z)9KHGDJ`nSzYgIR~PE2JHawtLm{ z`4RNEhmrwraXFoRs$LRN`W%c&vQr*wI&mJD%vd&89Kjw7A&)Gr#0JD~xvx@t7DSP{ zH!DTo5d6APK!4!9SyEi-qcE0B|5c8raNg&UVOC|?Zeojbd|Mbh2kXc3s#71ObiB8v z%Zwe3+W$apB&*oM1q73|4di2>~Z1JEi?9ZVMSLwnv;?L z)=4{=AqglP`%Q6rXnv_U<$7IkHSb24L2D$Zn*ENFwsl`9Wy@uQC;9vCLSE|P4*v&< zO8rqaOdmSf{V^`PsLY=>k~q}iy-Ql^gZg!~;WfLx7C=`#l^JGe?0i=KECHH0#(lN$7@MHa^x=gj`V%~Q5^fQ|Tj^yMCD@L)9K{$xldp0*KTRi1j*+V!ilva7 zZ^XDD7IGVmT?o*$g5$6wZc(15a4@j;jmAq@geJ-e043oGTr>FbN$s!_ZO}c{J0GHN zz*0wrI7uMu8SayI>zQ6zH0$>q*9PKUDZkofrh~}T#@%=^*4+a(tqX+byX z&|QnwlX`c^h5voyb;{06b&34xgfpswDR-bzoKw?6O_lFUKY~Blw$LbdNFuXo_r?e zAqQa68qfu%QJ%y}(hP^N&cR_TAtth%)u1^2eG%~-G;{M*_`GctZ+cdK3w?}q~;7%oem%NoX`6L$+x~nFi5MOdg!e?^*oj%_yW`ANNKVly+ z1i64I*%MZEL>}RWCY5?Wx692;j^zq(UaayhPA!V{d!XJkQK!2A?g!@X&dIrAF+1yc z$(drtP@i2dG_!aD#NOxBx?5wlg2!yY+-x*_xo|v_;X2)4ewbww)9xp?_Yr*o zadOA(?8kZR=8^2BAf9JY`CL0VQ)`fNBk9Ix;@e}+Sgdi{K_ny~fKgg+W0o?75)KOX zc4FK}&KTR11wiBxj>NtnVu033u~MZ_G&`MGDAa3sB-9d@ZwVdmE?d1T8~UipgJ3)*e@>X3&+<%MbyY^nD!Y4a2#*XXowSY`rI zRjMdMR0xD~G{Fr>BR*34Tv9smmb2=&kxFV-X=pX|6W{S%`nZv2)gR)DcNBbp6vZ;) zbksbaDe=A(Md7%7ckE9{sw?G}^7t-MD~_MLZkCmCc6+_y)$JfmuovpNDXGD%(s9^~ zP-I-7thNK`z8>jo<5GA9cpz2qQg1i%Iw(r1FsW9VGeHcdBKb9ajEka6W4;4)N4hhI z4+TjW1zS13eZ#vtx1NUQst)ICt>p56LCF;k6o9%mH9l87{6>Vxm+Nw;*)$_ROyDH% z?x#9;2prFynkx&=y02$y_jg;<`svw+eLWMAGu>{ZkW_cNYx0VJ@AVb=U-$ANz-_<= zpyVG8Pc;_h|D(ebB9#R9O!YSy2^GavL@BfwD~C5z?GQB*Xi)wqN&bfu0CB-n>D%I& zTlL(%72K`MD6+9)b@T&d=w56FT8Du!Fl zUq-uUnq8U0vYrdz{lHs=N0aKVj_R9-P0~pMox9eJ2w; z|HQoS+ne7pE--JkjT|X=_>lGG>tRSgf!sydg48$Y7p#s4#eNQLW6k(NqT?B$wr_}W z0{d>B#S{5c%+ZJ09`tsua9`3x>nu!Ch{U3Xl?pOgc}s?8^kKtJ$f(dMrDe7PBMB%Z zgrjJUL0yeQ1rdac^APUE8H*DP#RpDQzQ^^yz|&L-+;7LKH$s5K!1P5)ca7;MB{Kjd>Pm5_fD| zh6utZ>NGP%Q4S!`T3(Q1K?c(W1)EA@k=RS@8aiyK+=tVN)dIZ4F}unz3_gdn0>|E| zEL;NmMZjmWsF7#*0$XvekJZ$*ODAgww%tf-@&r7rEPdgPk@gN0Et_TAA1#*K{&HQX zBr^1=gE4peQ@S5n0k50~CIflvqsluv`L$Axhz{UAOMV!bqW5!KJ<&>}JheR1u9E(q z-hP`i{`gY`Be7mZ1p-n9#h3IrdpvK<#ogVMst33El`xJ-&VUml7EvO>F9&&DgY0*B&vS?lrm3UV2qSeV_j}i?oOd= z2NLgiLA>JP&GCl-Ji(L2U~1-MfJwHI*Sn$6u>$y%C%XGLtBMF~gWhcF& zxL16`?2HnP#N0o6sP#B5W(o9dxG+vKg zy3UVHWmiI=<^@&+=6Ef8 zWR_1l`Vlco>|I3XsvI;L`h4F-V`K3NBpK=0T){44X@DFF01e&wT%TAp_7hgDUgFmF zg#Lh4wWqRo-eY{@&V=dg$AebLxFlvk>Tdf9R^R$LjNJ14SMXrc*qk)^?oXALg5|MB zviWu;26xB7oUgSDky<4wPvfxks!KTonwErbzT#j3{CSI42+%{rxu5;hVzvbE{qt_% z|NkoX@)i#!PduJRfPUhFwg%Rh-7=fOu<1iG}Hq@As6j| z=BHO(;X+^?R`RXelfpNsMTf_-+VN;Or-5oq-s z^=x?XQ>Gxjdn)R6fAL0J9i=C3ECm#{4oP4S9=^_PtI9N_r(6m^RiqjbFJ~WG_xe+~(c1ADv`u2v#o2{|K7e#SY|#p+WvQ-2ENBb& z=~C?{3t==r8S$d>yq4{aRk4l==TPf4m*YZkvnQkJgnJM;J$7z$W)2A}JT8=VqL@4CafLT|9u7{9q8v=^ASydn zDYz&X%R5z@18kQJDYS~UFSA8tm2H*%#6DmAc;XsN$ZS|Mj7Jh;ymBZdJuBl=Pa}Fi z#+6@WNR~@9zrG1D2I;B6p0Oz4#7vxvh139JYAusVWm>sXNv*7J*5PYzfkKzsTQ)Rz z--K^N2gNz~cMqq`!UT?{i(E5DUAI-+w99Tg zXf}lCqZ`d-8t^m8MrbjPCeuCB>x(QE#LJuGOTe40rcba5Y{v(1Mj@b{md(^F3W3ji ztrQUQ92myd1_h>CFR2cce}200 z9=VYBQY5>53ej>Qd)tfsNKk42?FDjsfYkkafX-=_-Xm@@3?(a>e)|!=Q1CC9{StIp zvigr@iT3}jEV&u_OIdRHSiLz?q>+vL2KSHq`17kh&%(PYxg}fk=pD>uUGB!KHI#_@bwq5};>sa6CMNeKV z?Je1oL3P$=zUJDFeHpV7*%iht90VTtEg2sorn=0;|_9s|DO+$C5M{M-Wj_Bjzd zKuHC@ayvj`k6PQ~m>962yvaIEX3T$g9Dxa>gl6z z`EFa6t|l4l49vT!J5yMP-%TQ5PPtK8SMYe0n8Gr#idbO@pvo1@sxGS2znUW1j2cO| z7DPgG7>H@Wj|21%a*`fO=`qq`&45F+B~1uAqp-}>$g+c-(XH7To<2Gyd9e!jwB8XT z>`R5?2Di$qUtQ3}dDZ?n3$B%ISH4(4+E#VCT`hR}MMQzO<}CHZp<1Nbut=y_iNZ-< zXVTC{$x-y%C{MqvURDs{t?~+30vFN=_9>=(#1T6)YNU?4f)}2#1?ITlMi4<*sS{;A zu--^Ptj4FRyC@B(I@O=rg?^@c0e+D!^%~wqc9vh&E4WEe?s9TVjZ1FWC;E5rXYsTB zOYrCZkZ>QvXt(Ipj&6@QcdyAXn#H}RrbZMk#3zwnx(7>#qTu=0f)1`ElUKhVX(Jz{ zzk)|1>C5*LPdk&G8bD;o_4v`)qp^2Yk*^s@R`nN1buJww2C4 zeL9;Z;P5cXBzycI)JKU(rvq0$GHyncHDGiY=qhre6!yWeVv!_94i3hhlJjUG7%j<7 z$5G4^eer+_+d_VU@}p>|n7;k8RffUgm%4))k&&|g%G+0F?~BH!bKuC7NT>`cuVgOa z#f-j}@%yGH18X*|JhPR%|LN>_F-)lamZ8Lr+Ead;*t3%zLZpmhfO_=#?AE7>k6hTN z&2G@Y?7sTw-M8%jZuh+zN8|sOgSXw=oZle&Tm5jn8pBKB&Qv(OE=cDJt+_Dak}Y^y>DMifYdv_7am_@5WE{_X!8jHH|r1m-x4>^kNev z-H`2`O8zDAd$O?it3y}u3{n4NGu$i z>%i1|4@MCHC3xI7>IwlPJ7IuFws2qlX7go(#+?o7$Jf4==tKi$QsRQK7Q+e<(lK3@ zhPE(c*B1}RdMe+jY&sS1xfdpJ~aI)03bn!~s`Ba=jm13Ak zOEdf__SwC4D0uck@l)e8d~Qv8s2;l?3*~Ga6;?stMlP-99->fS6M~5AM>Vo4I>bwk zB`WHaS;*tMA#+PPDmHXVo=IIa!NbTU%i#1TN8z1v1(9O5&&X!>H&vm4R&X&@mp%W@ zYPFhYN=FB?admI?TeEG(4a)^w2|QcTH}j!t z7`tVQFhX{}sD^1X^%l#u$uu3b7)7~z$Z>*$7257D^wi1?gDI%Sv6@6Xd5A-tz6e32 zN}ZZTGT&^uW6@t=Z&yP${k|*;6KIVJHGnHmmZF6myq3viNKRLf1|-ERNkPHhYZ(u- z-j!vA34Zl3U53E>u~g*9-xEpt309DG-6h*D3n>p6_NVOK+rY+P0)He*)GEDUFa`cx zt@>%;8+4j$=vuAEeqA$igjwutKaS2r<|u<(_G91Nah>1g?kj7eN5!x6XhC9JRz9}< z?d-|A(dx~&hwC4}#oSAuB+qo^b*GHMH3*j_`MA#mA34CnzC4ZqxqM=PxlV1Q#)vB} zD#62eoeZfRMsZQPsCC^IM6z|C{oJ=-CfJ64WWLvkpT8fAG@g@j)DdvTn!XkJyfc{t z$aazn#dc)}2he}TzmXEJ^+L@HLCTPQ&%9M7*ilZ9zY4&l>oLpl4U~J!}fsoEj;RUXP}$s=k+_xosvBemzEs-3-v3(Ek89vO_KcM#-Aq1&YBo%#^^h9Ht@UA1!mB z^%0_mp)7$-XkBHJEt|;^19B;XUkeQn$8DQlx+L6Q(p5L8esL%%{CLS1ePt4VWv~D8 zH5g4-{jG9vt2an8{_6e~V9HgOp0F&UV6DMN=f0MN8`3-*51hxcQF?&Rn#-$>)J4cS zQq|$eHIC4{1Uvz+aKZe~>z3l}LcKOrWi>?tgk&aFSFzPV!JW|bmesZVM!yM8bwG(i zshkb39&d~eTyLX9(BtCkcn(&<*8*&YJHT?e;axhteB4bs&g%BR#N2|fheCFq!)Dc- z44}s9VB>f8m+ymY6HZMlN#Ayw1SIV$ns=z^p{<0?n19V5ZGY+j;Juz|;bUcWLHOw> z3b!X*SFcvjBMJW4WzbHiU0159fkwR9z256%_9a4}0lwjEnX~nzyAAMPxQpK3l;Rj2 zByY`zt>;u9mA9}#${{cx)`Lre?^p{W0=eFr)Zb~S-2 zdy?Aj9==o@Vie$q(-K+njkJp2$%IdR?s6hGmP&9sp7&a>I9_;k6Z`b$&+Ylg!+8nX zT$Kzc`2EAU2F2_O!YAkbOaAkJXa6jH<%xx+w{HoWPn2qBqGJ+Qbd{>`yWFgJJ$DA+ zSffBa>41tm+0O5Zq8*Z)-v@hsS@Qdl|CHK2x^-Mt(Gq$<1Ek_15$^9M=_7l#+ElyR zrZ8j@+tieA-FHss`S`^9!7CR@EUzW>j*CQ!*&fV9PNXu&Ngm1g}QU1kBE9J02)D-yIT!CYLcq5U`@iL;Y26XKDgm ztjra-cnb$$YCF`>Sp2Kk02K0VN%5FGEn@fLj}#sB@)Zmo1Z>(SAr6X{hLRKtixH8hzWHwSPD0o{Ri8W2n5Cr~#W|t8TP1sU&YmUQw9v*_K>5;i>;9L4xX|MEa`-SiBGIdnG zu-*-I$Rxdp9%i&Y#7F}@mYAON@t%2&*KmVY=G(Vthq#WU-j6QMvQcN;i#B&kkndqD z#56h<0&gTnd@x}pi#NAbuU#4zRjBRG6-!WIETNalx7fod*hR)|cmU^5kTtuK@#`N; z?XMtfghD$7^!L!zkKhe@sV%SJK}6!1m%h7&HGgl_%24NY!SG0=2&!hT)JqU+$F`y- zci)X7Lz8Mgfi4-C2wBs#>Mtl(@U(840Q3}M_hvDkox*PrFh`1%udwAkZ@GH;uzh)U;~H?(yX9zB=UF?h zw2n@<8i!(yo=D`+M6pc`@V7*9{j_!YZo{1CzoBNvFzSQ_S zl#WzinQ zRaYDT@imSsLX409a9q#82_5ycsW_Z8{&Mj93i=~KUxK!Ttpd=59dy#u@9+NPKc$!C zvqSyA>luGUkHGhHFJBhbpLPJ9DL#))4E+uQ|4~|Sp4|Tx+@??rdy z3lW`Xh^*vsWEymQoyy}1S`K}9!3^^C)t#qNPnK<3xPEJkEvhy9<_C`NUu}av+;3(^ zKTy}Pa+oTeX;QQNB_!BH>4OfMnfp>%m!STQo^gW>?%wtTo=-C_gY_~cKjyk<5q*dZ zZUhqQDiC~EUW6>dT*U=-k{c_Rx1#O~;K5!2JZBYCl-GfkCeVYG$n+A~1Wp&@4Wz7| zQfL>sTY#~hFvb$?)bx~;@WoO9x1iNiT**uW-lJLg4e@Y#DV#k}E*5NWU0&Hxp+L@U zO%f7pl2#X>Tz7p-w;(Ij9#kSNDG7)zQc^I_%=^tM_uKWNeR)ahLYV`6yQZaF!Sb9A zT-r_b{$1fKE<$#>X5Q@`#ZgLl(t2z;y4u>tKUZ#z=#5!$Xmwr+L>wnPThFlY{qWqA6(wBJDbC= z*$PS^kKSzA`%T8n`ZFu-_R9NCG!9?Bm7v18&vW{*CMud5@84M1TD<?Hk5H+x=Kj}KTOh==And4^DwbbAgbVAQ0Lf zU&89rsKKfmdg9b|mzE`0CHn^ZzsL^Q9ofz|;-ciJO7#&+UsWvQr@H!AtfggA=Yw&z zOOaeUQfroS?UvrGUg|!l4Dl8w%GT&mhh%bypcYM0T4S5tNUBR^ot1ebKZi|bk17i_ zBoxxAX7cOfaS6JgU=`5%M*#p|>|SoDcp*vl-ifzaWLy zCcY{_-}n?ZQJ~s>ByTToeEtK?=C7pxQ){}WYeq|G8R}0nLLxo4dvx=2o4kx0=*QzL zb#`MVy5%Ns{zZoRA4T7P_ImXF)8Jlsa{m^!2w-i7Ek40K#mk`}VB1&>IgH~BLoV`Su6&-$%3 z*PLrgg`m)=Oho_P$pZYV*K+T9HbxvN&vRPr{e&+1Az5RZ8wN)+e32p$=NaL!8_nK` zxvH7vzZg3>_%xChtsVLqt~_OX0LUy+PM+NdIq*AJnoO;~qIp$Nmy*4IpDkY>**~=l za8D+GUfe%r4H8fC|EAF_PzGlG;d(KXL;MTP(;x>I{%%ZeGpzqRn)io=>i^_y@kwlr zcNIha(npgy^HJDfYM4SzD?|I#izUFBc@l~o;xvnxX` zfk+0GHDJ?>LNBhTmCElH^CMde^Pz-2ykUMa9_4v2VO?ZZ7%2Zi)?m&bxgT#<)0`63 zw$+>hesJmEhZc8hKqUFr(Q!ue-LAZ0RIa^>2_nL-zarZYCM%j@2?7-R^CfJ?y_Zc-}h>lelLNx zWf7Q2B+sD&gqH*K0mKjqEo3L6khdh%kbjL)ejTFmzj{9F?*|*K0;Q)r%IcjAS&ctqp2k(qR-%=zJ&gGe-TjB1NZtxVC2w85lQyKl1g6)D(Qz)op zZ)DAvPjLf@lgMcLHUE#6)x1G>kw5{DQ&kr;q{_EY;^od@%zsN6`ag^kybm;mMmP=L z`7aT-aIs@y=OPOuaQyhjx-XiI+&rwpV|t7#A+IuuBIdL_sGfAWWvZ5Q7Sw^0 zg}BB4u7H5jcAnMa%?W)%Y`o2H=47Yg`cH5t;+z!g79}ii1rjSf67|w5Ul+)O%MiKC zP!2`q8c!HCt3RiHdfS7}b}A~`xN0ZXHcxyi-9#pcof6NeK#+}a(W%ZtC8v zgc1L5v1<%9)5`rVcANgWzWld2(@4T!)pscwC?*s3O#fMZXV!}TyQ4=;k0dhZ@3D)w z<_^tpa1z*y(Jf3G8G2P(SMtz7@&C@8>Hnsx*~tL|04r3|yC;MP_3ZR(6%L+x$NNsX z`wvvh->=In4?^q-;pG!~xcR|(k!j@pg#eo22ow^GW`!SrN;yo8%ovqr!>B51yb6HN z1Hns-TxjnE)5Y_$*5!R|%k36B=Q!z+pIMKg)2HwO(I)x9{Asb z;$KeRsx@*|CV%Ay*FvqScA?sZziBm*+W-Gk%>To1;BOT3B;8uusZ5(c3f64)MX@G> zvC6lZ4!^pQn9?|f^!&A76!VtI>z&PRXa{e3>s4~ph zqUGP><+2>0~zwxYhP7>NoKasDTe0%LW|| zM4~_9%!M#MiSNg4ob?eooHE)1rqRj%K)%~mcP%$b$-O+`j>REXjA zMBX#uTdbn<;n9y`&ZrtTg%F}>28}G+RJu|{#Bh4K*4Jm7K8XG{j1mO`O9d9yi!Ux2 zoazQ>tRl-jh;u>VkMp*5PsN$ZI9!hc$E7ZDZ{{jrhzVrXBC;#wHh=!BN}(3|u-pZV z{5^#J4x>~2Usj6#k9!{dCi3en8>oXKc!GzAkKc7c1&&=G%1m+F8qaHpN3CgcX$>ip zt1=WO=eBFeH|lj)@(r|HYyXpD_CL|L-~IT{DusV3MSm};U@fu4T0x`RLGX7tYkekQ6{n!lj!*tWT=DU8#*d6-eoB0 zIr!)XPJk{EFMKIfh*T^piC?je$c$OMDoLh>G$dXWP|O zk#WRfVi|~Glv#E2C4mJt^Fyds-O|O9N^VDGV|LF(QbQ}@Qq%|mQ?8olMvC~&%&%%G z%}uSYsbfGjuwe>X#n=@aDP8@4(YMFob>54o8yo$#+3td(k86N`)$;#PrMVb0MV_N~ zj+cYYhJSz3sqOX#w;}d0{JSB8*7D#d|23);+dWnWUZ}1?@7qBj03i|Q7bR*!8x$u1 zMN-bhD`3B1Tw4E+1Mg2H<@aWrdr@q{O-glpa*gH)TFcWtJ=1CuT_{wq>JcJe5L>A- z^IeM7_bUJmb|tL_MaRex>BejVb{ zA8^RA zy7BnG!YltLkQV-bI-rrq8v*ivv#o#stNu(#lH|XS|1iCa{_cy4(CTx-TJ-nQ`!&ip z!+s;?U!^y0F;l3c?VoL<6=l#WJB4DT3>__ZJ6HMN77G1KIx=q02(JFCFDhv(MVPbW z<}WinZfjPPkH3nk&$elWYXg5ph<bu8qxj(Li7*l-+vtc{e`3X z2e?4%5gBJgYi^OJn+Ho$n4v;c_pgKm05CJaK>#q&Hvk#x1@y1sF7$)101E&RfCl}5 z1^|QnEW;tcKll&VTL}R2b9r+@Rg?B8LQX~yLBrla;GaA|=r_Lu%mJ7H=&~7P%3t4< zRWUCA4HYi`nlBa(9h3R-HBgF2zz<>!Ww8AoPQURJ0MHjB9Q3FBK3y|@wNn=i_eAmF z;Y8jaghaX?!slW<9El%*F-t$U0|*F6y5an|?0; zZE?`uk5>%}J;!aSA7Q>E_|`HJ-WyI`C$gr`KzhE-Ur~5&+Mi{nJb&|-6&%Dovq7-; z#~MLF&_VLQrfY>h=JuKjW^ThW1+EAjberm+QkgX4WfS_{$UnoWNX@bzuUOfV^aCL^ zT;jZj;3hi*VX}fDA0R~yZ}|g2?}Rre4jyxKBjFFMN>>MrC!i6NglWM6q)wDg)G&GR z=0mA5N-Reo2u@0M9H6SGlg<<(04fTym!BhJxO_|}&c1VKC@Fx0Vefkf*S%6Mk5oS61tt(B~kP01+Wl}M1!~6@2 zH{D2e66Vx_8vda?N3WUMTN`2QJ}=>Xq?Op}ItC<(TPftuVPxr;v}@V@BJbN*R?@mW z6w=nxSD?rRwH7ivsvru^)`{^AMZ?0NbA70n(-jCLnPcBbJd`xTtO~8n(AiZ(r^#Ly1vKz)*#qG)A49&rzA-)M4}G+m|vY416}BPl4$c5lK8 zrk&N5ojR-YzEFnQu}n%eh!~_};c=dJ`OX1GJs9L#_FgG(pr_|)^%g8%ut&Us8@H=_FKvk~KT=Ln0a@MLMH07@}1Z^)cC<@z)o11TnZpw5olphxxaIJ>Qv!|cF2Wk5!7EN5M5oD765Kh1a z8E|Dj*B529@~)mJu=koP6}YNUI<-!aJyt5$yQlBNl*C+a|>$J9en~Nqbh0Q(Un|2DEu@^SlsjVp&9qMa`FCW-b@Gd zVg05TfLR}iq__iH7q5wzS?6_&mTKg_@?Oz|O^xhf=g72;d6v6AoOf~;)Ax3e{3tqr zfO@wsg>Q&nxglD6au2_YkcsFrLbNnH7oG}1$&yGdUas*qf(#A4Nb6T=Kfjc7M4KVm z5BW(9hnolp{0ygIXqxBA=E=81<3h{G@lH9r1inNc5TN^v@iZ)w>!U{%c;qsDnA4DW z45tl7_@<75lGX;mn1<4Cmg z9T{2s5Ysl6W9blLu|cv%FN>I4V56YF>e+Cm<=>E2(*9;;OSNA2U<%J)rfX*3FuDll z$;k`C_wiMnYe1R!7nJmok6Qf(eN_g|U41|2%=}S1m6RMRgjUx-zPQaQz;)CZl$;8L zq@f14k$g^ix4Ean->5F${o38AZ6mn$veIz+ha|zno+;6{k(O4MAZ;NrAOxk%N*Ozq zd244f6{R!Akc>;==gzZ{TkWJ;yQoik%eVM3X$eZ6Nt-_hOd*|Ksd&_pZ5DebGQJy$ zN$nkMGmEGJH%k(rV)2{IxzO$CAC3DrrdZF;Y8SE+cDF&5F=0v^oBSTO@t!5!z87EhMo)T$_m;-z`h3& zbiCiaUyN*jJ9oc%ev{vliZy>=1A$eq<9W=5U{eui6Ljw)d;utDh{t%tcVdP|Lfm~` z`(BD8-O(k~4Y_qFTD6M(n}#lyg19(NQIEWvB+CSG8dn{@LJ zH1)5l^KDMUR*FO(41_#*?$_pl`?9LM_R8Pnop8xy7i=y;zK6pG7J~#cp@F(c_+pDL zjz26fc~SXRyfK3Dp(ZIB?AVkr+zY8@yx&x@cAvSr8fXrO5J!NDc3kPW07xgmtq9N- zou)wn$180i+Qd-IM0f}we0~MA#Ve(q0m7I=U8fFF+~vY6kkOfspv4w+S-xC8(XfD{KjVz8t=;dqt9zL?mYJu2Ag86a3Nf;+`4xnK}~26+V^_SzBF zajL4EHZYYQxaHwyf$R7z(f(TsNUJ!iqLfq=$>Y*WgjGzm56Q@q*L?RF=m6%gb(YTz z7GG<10jGJ*lwhmWWAd3XNzHTm2E`TAI|7fareJ9<%UEIi5g1Z@1j<2~bg|a}^Ia=^ zV_7^8T)>YckQo@Hw92Sk5cz%qBoM^qQiP2vn!wFRN^>luOckWR8<)uASDpfNZTEsR ziCs?(FckB+y+T`&43*f$x>lj2UqeMTp{ilSX3~H{;lO|a+9yc8>y#RHOcAcVWPmhp z2zw+!6Bkf4iu@|jsFoaHV~r(q%DnYWH7Loi$`n6rh#-?7T16CJb6NIY$^dyxLPUaQ z-~<%yjg?+(FW*n#B@9W*?4#5eu?PGUlE&hq;z zgcM}^vwk}+PJ=5z1`PtIIfLGMzDEGzRbQmi98h46PZyB* zb~*CA4?AYT0J3kN-IT%G97=7H>ztl|S-?uT8!eeg{S7jld&CELdkTCM#c}G-At8FT z(}Cwz25PMroVkV;vcVrl`EfF$4NY=nxdG?=Km`6EOmQpG3S8`b8_aL`Tt7q|tPL@~ zG1m4;Q_i8@h>ALw$PK!pfd<|w!=%t1z1!XmL2k@ScMW`If@X7ykGew(7nrohj_T@z zrEh`rxd=d|E_Xp*DBqupwGJ|t4Tk&1NGn#T$&M`wU?p--X^>@*YY@~|QCUm{_^al< zz=l`K!edw0ap7IGhz(DR-ybHtQbBam zkwpRKlZxks>o8&V$6g0=Hai<)>;^uYORzl-hl6N%W*qns-h!4-L2s_jaaU|6(?F;E zz)NeiDYeYS#0tzZ5Jd_fsx3~Yc7#QmSk<~O{G2mdC%oRQL4Y-Tsbbo zfj6xS+Ot4cYjK&vLB^nRuqkSc4>AE6v4L(uId`TTWYN#1|4ayBoTB@0! zIzewN?VgUL?PPHdbyKuc*c4$%ZyIH9ObdYpdIH$Yu)91K06+_{?sWsoxPTFLxz%L` zO|O-Ytg3H0CyMZR-Rl$wZA%MsRoQ2%t`A3b5w5dwL;ABN{Al_3YU+ zNV}+F&Xo1h9$F?$?enrU#jK(#ydQ0o<10ve$a57`u~UbnKbc|?c8ZwCfb{yxN=mV} z8M4V?_*9*X%5;hGVDh%o`D1WJEh<1BMbz$+4sZe~-0ceeu9P^0J|j1zwPk9-(yuIK zLxjS)+!_P}i&(2RNW(@!>lRs95aQgF0~u7d)CQLZwMM)b?Z=bdg{kU`0swfAx+9k>3GAXK3xK2*8eW-j zC6%(V!@-xn0pc+e`(@P0Hz=+L^~+P3O(olg@B-C~>92QCUBzR9@$IIPidEUU;J$I9 z4(2|rhcKpq2AP~2v?7i^y#Bg@*BKp!B^FGHjqP#b^Anm4C@YnodCA!`3AtEvU*pPe z24$?*3f_ViJq!f;ZKO>yEgo=tPMW$`ocYod*q3wkOw8({y=huIC&F?b)?L|0NO5Rm zeJm{#SEjKIwaP@h?6Y8_66TS&r88e1K<8134=vqhL5&|N=8%Qwi|*6eZt!-mXUBA= z^+w*{8w6fwCi#BwXMvDXGmtLCcg|N@E)aPxnA(pk^^Xu>eAszEEq-LxzUflBqUmKy zjnquYmCdB$@LoF3+gkj2CoBmA$5J{wyW!MQZV+hexur&1i@dz)?nv6^SDs|@q{D`eKUqaaUK)j(7 zG#Mqd!LFKJtF+PX;F&4Vp;4nS&%HTdu&E`z3Cx}RIPC0_zK(XWIZL`VFT8cwKl7Z! z!^U#0NXd~PlDzNCj#uhp%aL*{F;|&O~{dd{6LChk(?agcG!s~@u`-kECf@B}w z*6eS+-50?;5TD*L!r3QVw!xVg;}o0FNW^DV!e2y~ElVT)Lh3Z7G$mDj7%+9H+jD5V zeQ5G@Xli)W9eOZlfC{4`w?K^l;%<(NlngKa$X$6?hGl`?57-87{T6IXN6Fx$ut?el z9Iggs)mOklzKv~!s`ZuOjxRX;%>LjgHfbD$9}JT--xYEZNn0!-(6cWw&1mhXidM^H zY@>V3?0Kqdh=uhbEdD*yXOepVPleJH%Z=$9>kSSy^)Gby$&$AlH-`Ih36(CTd_>~U zn9>sP9yle6;9CnjFHrIoU078bo2juS7iqfXfytA_iVKs{pYTCY@8`CNJlc_5ENVs8 zyiH&J8v5x0UN?J`Wdmd&!hJApv-Qyt%gU_a)aa8%t~|j?io%u@)NC9eUwD+14Eh!& z*0#g*4pqCn&Fxe0;9*vZ+VLuoMI{z_TuUEx92J}ZjdL_W*q9rK*0r3IV4eHYVmdIo~d< zV%Ex$O+iPbv9xlyz0oPY5Bxr=C_q79bdnkrg1$!wcCY0-mM&FN$ z2PvrTfjlm8xcDg6$o1#l%oZbba8}P^wyU#~$QZu)7CU$X%yO2F;{-ePqcWcYWmT{M zyLNq|!8gcck{K!{0|Dq*jkZ!yvR^oo5r(-;ecnJUA>R5=?%5sjBpRhW$xO9F`7{>I zb#V}h*PR|0+r!z~UkrQTj9-MFChUGR;*h}v%juYm8U>*|UHP&V zegwlwzX|jE%5e}4S=IAbRIA_VfGEn~N8PTB8a)Y7z1N;Imhgo@9=Jtx?#L&7tFYCT zZ+%L?j&%McGdks_bv>H;<;`et?|!yaV>FUy@YD12Rs%t;;u{C?eaJvM^E==CJD3^< zWx_~v(XIgyLhzFT*u^Ru-h-sKy8B9T?@JZfo$kIC|&B8(*ipD2l~Ao)!a9VKg0kiaOEUHS`$U;GE4#pRgvGp~aNndbrUu4R)i zLeJ|5X&)vCz5$vP$AZO4kU3h-IWS8npZJrgnZ6X!H__FECe>0(>^rbM3@Ea+bB35V z_40fSiC+%sY@Dy9^6_wR#GQRdKTTOT4T;znk$-b zNk^9r-AGRuUM5KKtmWZrw(45F3**tVDZ3a`W^rh|rn9`#Yu-3~21`KUG?;s-?=r=b z{+f42)2q+(xnjD3?Quz)q3@SrUZb}+amj1q7O;FOsT@-YJK{(p)^Y`?2Mh}`$r4^$ z-gIg0re237P=)huONLpTAQ^#~zYJ}MxdmJg;USWyrO#HHx+lM7hLxf2QI?JWon@}u z(b`d-%jZ?|f`}Ju>&!*5@$9X{X2jHG+2Qv#6`77s5ZkJv5BIh;O-FC+>bekr+BFQ) z`r0>*(F!=UthCm)YT5IrN_B+fLcJNkv+T)-nTa&BVPL79hdd`|NJuYGT=_1zt;}}As{?fqs%Bu93uCu zoR`tz4P0D`4EW)j_e9MnhN?9iOfZyhqbK$Z;5iEkdA>LgXJ?j${p9#I?{53zwb^^z zJm)ZaE<+TH3~`)!U^s7%35G|c1j!LNLh#ZA=*uTbj`J--24sqzx(a>@nvMDin{bBM zNWDOMAOdNeJEjcH3)rL+b#zVW@^0e_-b7NzKu`2`<-xt?s(afXvwgjZEW_)G}FB8XYi5XJ3A{MLmd zPy_B3-0{?ubJ$-`71LO>|x82m7Sfj-}z!dk(>P`^b0!|Fa6&TObd{Uw(6C@wTn z0RXlUl2o*bg$m8q(oCJIv96be&zDYc6nvDD5G$g{Dy8Ix_VYthU~J$5XY^%(c$PN04XV& zTFpfmY5)K~>V7miwK1rMJPiNr8ybRjP;wh`AK|JAno1m-ZzPww;kV8e@$cM;0ZVp9 z2xvMB%#Fnnxhsmi;y~)JoRqTcXb`zZhK4aR_#8!BH0F(O32KUA^!hr?x>>kB)hLrkN)Y;INh9{^9 zv8G{plex4Ggj=VU^PTMPKYuCik~lM6=~|z1^y>d<@Xhmvpjg!Ija>ixM9SrE|6mj% z@$|w9a4BAM)rOdNR$J)hK6$GUF4OBb;3`aNw5LbVrbY*)*jO6*lgEfy(#HH2e3evm zg{6EfzYu~XOs8&5*vm#+Gz)nO)Lwc7z^ci6{pPD07~?PwJllR``GpU>(uPdM^0S~d(k=szqmtrpxcDDfi0Rg(5JZY~1Z?!e#6aCRy zd=%y~Sc|f{<&k*R-Ya|K<5N-mUAoMm>H4O37K6Ctw+8CAA%)J4YVG-4Alr{2bU5T1 zUKChe_Feoimg}!59@zlMLYg?Bx_lV4$q}gE4ugEfcPaiQ=(Whl_>O6sMe*mtl9okm zdtk%nA}P%8ap^gQJGg}^z_RU9#!VbgNRd%B#YVC)Fm^3SVyRtS8|~g7oZ}i$ z?U;MFuuJ#(!hJVyM#R!q9+iI3%BEuN*(7sqQ8QqWZf}TJ22D0U_sOHykv9d8Q-&T1 zsB)qP#Q>B-qtUZ>>;Zd1$9#4ODEg68!pVR{E$c#jmUwt!%I`c!j)nM6W)WgC+Y$&+ zoeC}8-MP#2@0%e|cU$Q4ysfa_^yIWV@jx{;Is3uX2&DmO9dVT2AA;bPf$ytwGLf{% zI2v!TikUGjS#VTvfqZF16FMTl}h1&+b&X^NP3)N(Rb9y_XW_1 zi~Rm_a-mg}IH~PNtAlzUtfD9)d>brt+itSxGZTixpHZ;UDTjR=cpZt(?3n%f`E|x+ z3CVm3P3U3K7%Sy0px5+xLj9|eafo95S3o|gpY7|qF`z68oCC3hAN^$T1J6MNP;W*G zt^rC(angf=NVFal_kj!gf=Fs(9@1Bj>fRWL^(*)1q)!31XyxstoKWcW=VWjEw%NloNQ+8}%O;tsyyCs-}AzDpLuWs%OBO0?AlK5I4w_(iF`g)?hxvJBBf_-3OJAZ<` zbE0)fVgdObOk~+Rc~}l(y30bW-js=M4aKg9i4O-8BRLbJuP1wQ6i0_9Cl(byY${He z57xj>`HD@PW;~<4k9)f)GekeNq^R_~7z_hu$pDvpB`D(|MCEn_dC(kJh1Y1884=IQs)Kh`DcBsM*nSos}z^2!(; z!bga1f@M}s{6nZ`AFjxq=+%-+B)&<{FnO$a#VhoVnM-@DpIomV&R;!V<~*QJ10H8! z4rd-OU%?~H!qKQ8NTIj8Oh6Z+)>JEhw#VEDQx`X=XspkoT&dWbkhB$5X;94JaL?gN z&4D!M@GR!=HRYRa;nc|Ch`Qx*Yg7q_=bkOiksi*GEveq?jA7x;@4~%9=bj2=pMsH_ zU#QMp1H@5XV9}?l(dMcJev4&_%A^TXqp2Zcu~2&ZNaMV+k#8Pa(+ zOF`OmA~d6*OQ5w6l#okN>ylbw$mOa)w#3b^J0DKHownejUAj%*yqjNWFN!rQq|(%2 zoGMzVPPi~xywU-S$P-CfWXLqkD_$+8t}UuOE-E7|sg@wCvMg!TL}IuuXl+G_vBW($ zDT8sD2MH}H3B-ZkQ!MC+8ImrLWMRaq(<^Qk>pzl7dn`(KlQLQ?Gde6=c`RFpE!(6n z+m)uWs0-_93TqapQmT2ZmuRjRztyVY(}EIcE4M#ev~PGhWuKBI7EdpQ6&b(JLVm6V9J~Ky2OF^(dc^UC@tP=i{DUd z__*CQ*OF&f9CM>E^tH4jD*?#CEWp?R@}{7qV4ws#)jo9%XNV~kJw#czV0(-&FsTfF z6&{Bv7DXi(xSz|g!>~Ig8*Z?Cim-mBsdd_7c;0PzwzYkJXn29}@k_3uujZzfX3UGK zuvtcwo)DUJZtk|C8j4%0=@*STKgCenkd35tulZ~xuZSA9d&!XCUX;( ze3hTv76AYbbXX6C2Lz902H#i4>1PDW-Zn)rbi^L60ugtyw{>tnujVs+lzOIAchXpt z8Cek-*yjB)Y!&{JFzR5iC&>6?Xx}dCM%;~1pgqEzqWc3OURQv=@)w$biKXB$Ifg zDl9Q9MbN1n-Y>0L7oOf1T;3Ov)~q9+BYryt6WIq^ULKYgG0SXZJ%BBeja>Pezz}#a zT8^x&g4|02ke5d3&j85DRxFmhp2*nD&Bp4R5DlJ%?aOA6{(#b)+lX1kCtB1V8Do0P zxU;weKlLNRw~{k_A3&Y4bv9HP_Gu_Ur57(57Dcp?IGh2~af3ScXebU>?Q4Ubr$v_d z!6#5GsiA;y4KY#^zAM`(DkrjBJ*98PrvGR~D6o?rT^T^H$oi>7jRct{UnxTtc3QX7 z*cEHJUN%4ggE~9fQ>B&%ytm92XY>P!{Rl*RzX#~sf`qHI#(gCvP3zrxM2fgZ(i5zM zpT(v5%4QW@v=F;5wPl!`HZP-enwDmmTB?@jZ)Nod%4`R;WG-6Z#4SNTCyXm7LxU=Jj1t}XL zKdO-NGiz~$$i8^q)e9;Fkslb(aKSB3=Z;*LV+zLv?!kTH4M$6X`da{ zNFMIaLl|!ahFWA(GY7x=gpC^gHm`hZ~eS>uiCgur!VZ6F|)D$+p2&TzR#4-s@U|0$?G%*Q<6 z;)RetVL2izgY9QW6!X}0iOAv3=yVBAnjM_1s!}HdCi7fg>P;(g6dRObVvYr^=B@4JtR;3XQWVAbJH$}o3W{jfc z(K1Hj$bbbz!me`(EGRY%*oO^C1LW3WA=q^Jn8<+MCQ^F~E$*-%yy-t!a(}SaxUmlZ z;EZz*8&Gj8^BQ0cX(wO4~HYpW*74D#u<0DcSU%X?zZyqspa}3E$6A2U%WQ@ox5CTsuHE zoMa*;c&=S%qK=DjA9%b#hBuy0C@AI3x=mKAtBK-=*S@c?yj;p*6gwF;K&I#t&L0Vb zSSNh3yh5IPyVT)jd)$O0DRawtLEgs1wE2*%+aRfaXtwt9HhYa;X(#>ec{Rzg|)0HNx0 zsW-S=F8K#@C9m$wBJRu6?<;s!$+ zg(jjz=J&q11s@_YA}Y_Q!r6War+4W)m-pRHX|>w%)$pL$2=BF1&%)C;Ju-f&K;KWZ zzK~hsap$h`podXHlD_;b*WoPsF~0}qY%Y7^@iu}Z#fQ0(pa%2R_$o1T{ znvKFL9WOjRG*+BU%KU#Vh}%@xUsE{$$@_I@AOiQDO*@}!A9R@mxBP7R%L#-c8Kcj2 zuCwR!xiJp@;GfzdJ0*^_mAPkk-<=oijEvIX`dofF?y7U@VR<^Zzxnay3*==W4Dqq5 z6c#%Tu_vCKHhBn!z%6+w(znvYKs-Hfif|&^_FYA}7TPq`R|W+5W?EvYsS$N0tC||r zS)&=+)Zr1D2JT~;RPnrL-rDg(pRM-|MqK!)6QziKsFMO%!u35%bW7LNNet+WRF=Z5 z^gOuJc!=Cy@vLp9Le7F(i7XVeh_W56mU%WDtQ#{+vu)D|Nu0!KedzLh&N}EKM7rG* zSk$NiqOfZA(4A&cv;y)>A&gnpI9fI4bh0Vm`EyFrZ95sthE-P?0@L5}WTmHU6^g>f zCUJZy(5qjN7ks}puS^mr4_n2u7Svi*+Z}ycRo)k`S6M%-=V@O*ikZ#aG$CMT-!v;S zu^5`K=gZQ%W~;v}&EQF0Y*Jf1uIhe6pO4Z(`UpEjOL}+t!bfy`WB>ijdEdJ3yZd&h z?uX@!(^eR?NxDAD7WR7ooQe-*_HFRwVZu+6UMKjt3iivwDE8ko?VnY7rCAmh9-I3j z_4qXAG*5L{jzb(8pV3XSP6*LCA#eC`PV>_pmnpQh!@$F;EjG?o0La1gIJns#YNzG! zH@Oy76@)$HGAI-*$HrPY!~lAWoPn^l>#lPi>NXEd>&BJ_wDme=7p?0~ZNfK8?yOe4 z8y=tD-fa6AX|XH?p^4n?2tn>9glho(;}uyt)i1gPpkuIwWPN`h({7V#ZS(LD{Zr{A zEMqj-tei@zw9k2ub5XXZQX6fGWHl!?gIbT{eb3)FE&cr55BJKB>cpjCAgxTK~R0CZrGfPs_CH4JDb6fa!_lsoL*WT=zi@Upm-k$r580!Q5%c4 zbND(4&(UFWs}R|_XXKciUQ&A3B6RwNLM7EXtr+cxt{U$%v?3*yIi*O;mB>G7?Wvr# zbiPR-AueZx$QjvpK+7lSny9|rm~$kw{bPO&)uYiZ_p?2n&_{j=9}y?O<$EguB;d^3 zy{2~$4`namP-lZsoAcp?tzYT~CGzGq6<{vmvya(iZCfiR;!nv+F;v#ln{pKr#F-

7IL$0L1}r$H8^T09I7W-=kIz_J zuh`?=gQE1*yl8zF200fZ_@#cTW7SDc&WVpU(VFw{^MwY)yF<(<(ygPxE}Hzjr+gpY zvU+KPe`^GV(*;FH1x86_d~VB#t_ZyNnem4v^8`0Dr6MEsCgV$HW`bWv7EfkITjsAp zPS-R};tEb%I(M7B2w?C%ei`n5IUk`lx z-a^{IQPqMZwuJYPNWJu+8`=pd{q$S9n1Y=5*mOUn_8>iI?(8Z}Z9N3mVSED5VQ%{R`-`3K-i9n3oDzZVTAx3&GNboW_OR{)N0* zh5YS>f=h+Mw}qngMPga`61`+$?b_R+X3B&$3kraTt2Ul#9Qp5Ry> z##<3;ToI#Hkv>+Qaa*1;_W9Xug*ZJTUm8(pj41X;lx88y+YyK*MAa>#hQ6{+y0Ss5 zkRl|tH7m8Py|R6&vh%jGo4%??x~k8(YQVp0D649uy=rW!YT~wPioSYAx_ZvIdfvbK zM^-hey?SY>dgZoyjlO0>x@OC`X2-v#SF3X0xbk4B=J2-Wn7;Nzy7tt#_T0brGOPBQ zUQn;S;sH@1sZQaW8y4qpC<|_~bu{vIbXavDO*(cwIy$mDI!y$-89I@79krn<+a8^_WkCa# z9X&FgeX$)=3|%uaU0r-#3xr*fcf8{rUDE+wYs;PU7{cy#lg>uV&Rssiq3q74%I+1X zuC2T7rRA=Z@y>q--4_hqS2BG1+xabHP4iinCb3m}$sIeOo`--Q6Q`bz_98j=7Oe4} zZTb#uG>KtqCAn-bZB8$JXD{PQFLO@IQ^r0v**>soANTt{?wmd*M!tseK3;U6Fk}DI z72=+y#`=H`NuqA4kKbfu`|kLg%868`#|9lw%x}mL1eK z9cjX3qdhpB-M^nbXj(OB$v9+9G-TU3xa34=Cp+Y1I%JO?f~^exBJ3O+FW%H2 zcFq}gI~;Of8UAQ0cxRG-zuyorUaqFihdk(G!A$hV@bg8R^6@i{`YjU#j<G;YxmM=SYdoYsA$d{^J=E62wIx$w(Ia0eaR(CjtlpSy8A8$pECgzMc zO^mlNj`ysL_oB!97)KqoCPog&$7CnQO((u-3noLA z91PWwG=UW`ug>DXo1$AnHS{-=Z5C5)k^nhHkvq$d^kf5{Dv?`tIof;=ER(ECJrhqB za5jI$Yxgg8;E-niSSBiaa3c(^C%wdMkT8U#ev>0>VNr-e5x1PY(t1O(tU^j!Pb%e4 zGA>81&w{T_&(|qO=0XZI0mT?M!WgV#u_tTy?1y!_iVCeJK6{8QkQondHvhxU+$7{!^vG z-`avTELfM-U5-|!gOvcs18?dFR3ua1Mxo`KKf+q{BP2?$z$@3N5dsS7`M%<9o1RFr zEfRf2f+w5#r{9U+=q~1}!e3(g-yFW$YZ1oE0y^rB2nZ}l zk}C^B#aD!sL@|o_I3a?|4fp$aG0W(fCe6zRdj8MeZ>;9gQARk|C&E}$K%wei`qk*3*a;zwV9<%Sx@NJP#)+Lq0Yr z>4>|2m6GiE@vLrBJ{b=F$t4TvGePlI1h#R{%3SBVboct-`Ntk9*aw2^?YzkPWwH`d zY}1~Pj}`uY&Fxr0({f?TzEOW%VbR`{5E_+SUy;U)$+(_1oSrHFJyTsjGa%i`jI@I&pkdmj;JOdgY&;#`y*; zShz}u<~D@I_QIGa##Zb&U%tw|9v}sN4UqZ&#MJ3ATZtFaUtBHxz~)P` zUmHY`dfk9a6~b9wz0{;fTC!Hn^J-7(eh{aJ`?(2#yer|r>J2hDm}?@uSpQ}iaBzEH zq8R(l{GrgTx`PMnJxAEp8gE2C^L(O<3EAVE#oArN*H``zcWq~@({Ep3m0w8)Q+qpW zH(H9bY6=9HVp4tYB{`z2y`PrALU}pxGYzX6)CDN=zbI5ia6s^h!?k5ZvAo;yg=5}% z@F?K?yn|3x@*PN3+ui%b5`ny}DYVrUE_~OguSf@~_-M~|r_pzJxXz7$_%;dB9C9Os zoRRJy&+R^E6HvzEg4Kx;a#WG_6Y{JGs}PH0lOcF&PVHh>ZM9qp>gBCxRcK_wMFwbW z;_3&dmnz)V860-pHJ<)MMAuav*GHt{gGh_=OvdiwQt;rfSULjNxJfEGd~OG+0F;z4 zzyYZreo7gHe>%)KeW<4){+uyh8Nr>bj1_9S35xPgcu`Bla@ZC@2)O4{*O^;*tER!Sr_-)nI`};f^Qczq-fmaWni+!KQMD1V} zwZl$a9r-g)jA*aF z=P+@Te&vhkW9*MU&u+`vvY(Zf>?@0kMmJoG2$BQAzrVuHesKjf!?)P0a_@d2y$4=P zxBc4LzEYeoFZAF#wLe(?JwzPp*m*kgtVZe$DQ#o}Yo<48-T2~-_TYzp&Mq&#<<~Qc zkAJD~Is80}5%O-Z3Hs`dvK#KYTyg!`b+vpnTP;lCOeV^~pRP;qSDJ$9@>@(ZzxDg= z9?5LGYZLjx|EMDG!T-4BN*?{IESa~vD9|CIi$kDvOk&H`@8f;ozL`hd=-h8|xzlEj zAoSih-2CeYF2#eJ+F;B$^Y4w~V8eMf{DFoD?Btmk!{QyTK#zqN5+WjNsBMf{%+|CV zr*Ko|Nem}#=OCzbs6qnRv^1$pGncfHPIoB&j5nJi=eQ;EMhANa?f~72{4C-qK-W&cY_))3dqAsyE z!zNxuGj1rMAw_M?;tf{ggRo)&jFkyq*x)|OOAY164Xni|W#)0=5aBgt5X1t9Czv+) zi7gQqS$HwnwLZiZI-`5ZqQbMcL!m-FmrCrfb!h*eEM8;pPvk7ST6+Rvg3UsN69 z@YUi08Qjmoo=eHv!ONzH%sVtV+DhU^Y@{e)M=ZgGQZa@%nRywmAzOVcNTOdN1SROO zXvbISF?G;-OK*@dMagUOO4%lg`Z*7Bs#FxmQ77zHzp#D2{0X_EJ_mMsAzM?0z=wUk z0%>U0SUHt`unEXNE6v*)njFKrgB3@S*Hr053 z+CLcjqAyu-!L??orVO7Ucw^$D>z?9doZ7J(W1 z1~&9(jIjMIm>muhqySFvF|&zcC?${bP!JJehgK9T z!@`UHuyC*I>+^dguVZKc^${iT8J6d13)j zOVyLoLN~%!oFTS#6NebFDx^M@J)sFe)CkJ2p03&v`gD*k<@7jMrrF)QdSq9g2Aqfe z6yp4`?~BTaWd)!;^K__+A#-HLs2q}C-;7c=9L4muQw>it>q{Ef))8Ri=h(T2vqo57 z8uI9z=yTq`79k~thl{`j8&5VFKS?~}2UIOY4W%5}!r#yC;+TykI_;(|GN*$s zJ@c{T?3M1)XCei~3aP%@t9v%hCYpH_vohI(k{|nHdgDR}pE+pyWPK0O&HpUqLGt=5 zwlcNISdb>DZ+5bHfoze`A#5P;RlM#L$?P_R&e1@5cAN%xm%N@HBcC73$4r^uSe$8i$%7$H*Z<%M)p={Th*)ywuWp}vkX2R3V zGv~_mxBTy$=?G@8!oMqfiVC+gDgRaA`MW<1%tv!2$6lohtNYO5+xc4E%@MtK2XC+Z zQMC^rV0<4EdL?N6ofK#ScD(eZmKn#~w2x%% zBtiqdNtNe2B((M~J`%mn@zihZ<=Sc5F#4Bxp5K(~+Sym!``>C${pS+R&MCD^`rco< zXOOA$9(qe0EHXKWU#(sSyk*K$VX}Aa!#sTdcv<>6ZL)1srS+Oj!KBD3C}1}QG1KO1 zd{(0HY5&do?a$%B%Vpw|3lHQ^X4IA+S~?^ycvTq=GZ5B9E=A zaM+*H->;-9rNTd;2p*8J9#EiERg+bPXb)%<52$^ld2y&>A2Xn}qN<%bpgvLF70PqU zu6F%wQ2!&|ttTzgYEZv1%J8Gw8*Q}&BY7I+pvl0X>HOfkok6qnj_hLx zhMo`(S-u{!LW}MGV_FUwT8$pEOC54tX*50`gv}2*?+m$|4>?mR+$atjfQQ}1hCNg@ zj8}SGt%tq6hJC_^eLwalWc1NjsXNB?7KrBWZw? z2A)T#Qasa4iF{2_fKbuRQN_GOLSCU&H3mi!4hIrDA@KQ;xc`(Z|0rB_H0gXKRaP@i zOjFfM^9$pEgge3$IqEeqnmwpMr$WV>#)b`C-5-KV~wig$k#7SkrFW$JfU8af}P5% zA>(ETecalTpHurHQq?0;$CozaS<$^o^xEtzN`2NU1KKKsvfBM%m0?Qd5$lOz{)sVd z?a=}4{{X{8r}iXFdy-KARWb4ftdqe%880?DuR6H^)?9$;{4gEONS*xtadIh6XQ@-? z=Y$SQRZ1_8v;kWeBefOZ1lIjdR~=I~w)J}Im-W=HwSq;l*2@4noik><*r@|kdPeuD zqjSQ4FLaNwr%xzf<{xU6<4v8Z(%!uONanpCE8t6mC+xeGI z4tqYP)c&KK!QzA4KUet#A2&R{)=Lk&Q^b3!Hn-d6mD9P#!mX^ zW`ccE~gdSCd-eaElU&}hnA2rufHJQHZtWM}LuIjNI z=`jyZKJA)i7oP(^(LWcFsrSKbe=rs4lJCwQSxBl~JWMQojL zMD480nkb!r5rh%Ddn$H;q%athl9@fen=`SVldb$NyYOAkx#N^lNSQ4HFDkqH6%nwP z{#%i@lPo$v|H;nBZ?W7R@jcCVSv2HcFJF9`e&0W@BiHld==C-FweH2d9u8EWYC&IZ z!GNmt^R=%0hlMw*1_Gbx7T;HLJ__atQ_pOTFa&_Z{kRd@2t!&z9@;Se)acy|js~7| z9!csOx2WBXg+oo@mN^l>Z4S{oVIT_R5ggZF-zdz}YEsTo^S&agu+C~hgG48`;E#yF z%+wEKk*0#wI_WR%(X-TDKWWltKMlSKT=*G?g9;jyo28s%d#BIAG#7d?8)kzFSDX7R zZWO78iYh^2BGQax&vo!LGh&LW4eM%RX9&RrLg796P(3w9f}-;4rUZZ>T2qapkK)IE zk?dS}!3njuB54TI+U(Zwo)XQPAuV27zD_ExIgA=Y$5u#&*dkg;=30c%b&K z{7xN^`-gI_Fya92M}&_;t=^~U?cwTJJ(v1g&F$88TTuq=MTq<(9)^%L(WOK;p<+1Z zRu@z-FqOWBw#FotS&R4Zibpf4 zqC(}`B8WH4So>#}?i)J`mnBJh-=tk+q1MfKi* zX_J(5lR{#XGNI{vGN`kn0J=K2owiB$c>2-3xM*)ob9KagQ)KuYt&HBCR3& zxQCL=UPlb`wDMFHk@uqn0&g4aIZ}=g3>BF(9d3lqSd6{UT<_Keq%R3#kAgcmkta9- zg@DpogX6qg|IQ214 za?xx`J4$2sUBuC<=9e9y>1d(&?>^7^dar9 zG-vp=SrE%36FOS3*4y{7Hu`wM-~OZ}x#OhYN9w)`Ha@}0fQp--!W$YEO^(xEf6gvI zE#iL>Si7wTqC$P87X4-ywe)`J`(-bAC~!4cr1Gp*t4(`$^Md$H=xu*{n~e+WjP27h znn+ewp+MNc2LE<)i{_IGQl|3O2o4L=-kZFhuKEhnJ=D7dlWWFvrQk!>y>&<(hMuBq z>SD{h^|u8_gn(x3v`#FTmfTx8kNv$VqwZKm#xuzTkhdF7RVYcXyZGW9$-A~3J>i{f zYLxQSAC(_}a(7!!M&g{=%zQZa3%kd5j-q~DMBX}^8=0-=<5dY7;e~Gmzforoi7rd5 zz%x-_ue`)HIKejw-VeC8$+0Q)=iarI!#DP;qIR4QcUv`MjyXybNX^&}y-v@9FRG`} zJd_-GV1eEd*y?+yW!71^Y!=tZ|K^e_`5>`B{2Atxx)9?#&S;ph4FPoXg1Dz(Bv?`{R0-6M4Hw(VDAe;6kS;DJOfaJPNqFgo@dj&r=Q z7l7sryY-JRY$Cq|dj&m6k8|63HS>kHg6rFQi07+^uZ`NO+_sj6zU){;{7{rDgoC_i zim>4c;?X1LpGPj#T`#|kT>T(Tam>>FVZB=I8g*fP`(TakcGW(1)ouQJ|9K~_gz(qo zhB;p7DV0;l3jm^@*wJj}68+2M8b>EM8!sxl+&+wRIsUhB%-m-N8{0h-W@;`EoPTP; zN>X@b@eGKDY=oQnv8bq#CXCATJj%dMAUN5N6zoaO z5-GylvSkl=J!A$;b3YtuKINNMZ@PF^bJzDXsiiY&hTvDqwteejr6J}KMasKR_U0)| zIvwMzvuPeT&$6?plsuzOEV@eGu4ZIT9o&>;K(qM0UwvdeSN=Am@=ZhKrI#w#IpN^5 zAHAoLbgy@+`|e)Nv64snzQr`_wJ9GmzA-fOq@Q|KooYV6Fldoy;510debE^%*=|qV z%AXRY+)A8TUA12!m;2#)?M18c2P}U><13Dx=nuq6F{r_k~(w1%CCo;mEem0`P<2X z+sbwS%HOxO)3#s>JFD7y^k`nA3zlUH0%tV|wQ4{b3L+P{RO@JCclfDDl%ua_vfd zj!AlcQ~dS<`Vw=78+7U#bWVb~i43|`xB;~@AO3u}cl|wy8x?f<(A2PipyCN9pb$0P zt79FABxl#pv9D(vilu+%v9edsK9b0$lFaDP03J(fUc!e-)h&F>5Vf1Daya9h%8~Xt zJ^XXVHIuI#NiN`c&OKMGl`i_kv38-STo7~La24zL+C;Q=Xh-Y&fp(pVbIg&}C2X?c z^=zOG!;d2r(rt3Aq@&rzq|^0cX!5}4?|OGIE}hNMIna)8_Mtt45aY zpG|+JfX43lTMxUjY>mhvQ{%Hg)47^qE?v^%2S01n`fKDUIDb?^t+XbW&Yz!b^!&va zazXp*mm9dVyB?#Z&iCfZ3~Fm$`~Cg$?HIZcZ&H16vZaB{rda^<=27m8q$UPnH|GP{jH$w46%UQxnwDwpcM9FC0N6<>N7JO#X z9ohVkhtaY{vmZykdvQ3~!WJvge$5sqQjoFgvhsEz=8e>4Nzpr5-CcIL48h_yT!ESn zoTN!#v7-aI{RK|d(5kRbeXZLD{sOh7qe-}fmJ~W;8lp9qVWnx&OPPoysnSeX;h)kh z=NhT9oDbcazrT79Mbjr3eONFG}sS0JyUDXFP6}uwYX&G)D0t)Q5Kyo#$pwDVS0KX@ZvU%Fqt%WXRLbAtJ9(R2D)`&Cf*I_x5T z*ELgj9KfW!D{^CMr0@8Vv!%vQt*&s4?F&(&?bXezg8Rp0W%RZsKPzde2jUC-AwdJ$jaSJMiYjl#2Su8pH8YKpd^XH0>7(fEDL5UF_2wnnzk^BV*{6QkG6&A5a26W0FZwqo>V)@0uGj76{%4@ZxYvN zSq@%<%+ydhgf0GEe!69w66UQx{0mnOhoDpDxXFG)dMCO>AWTX*1OngzKq$7@sMO(q zQf^hR@VhsUwz)1v##|?-c)i0U%;S63c*7#0EB6#_^0UZoF*_;ejH!aJ24D9+mdR{O zRh9nPbx5G(kk_nuS@Vx8?_q^YvENP$N{-BbJUL3;VwKnXtF&NfyO56#U$1P@uJEF2 zPvse}Uc9AO5%Uo@r1ICRsAS3_>jT{l)iJ#^(S{Nl8wW@{?)Oaf*QFvQ+&b@KzGvy% zygiWOeii08qh@@NizTOh!@Jw>BS-;%Btq{c3Q!Cp`iZIQMC=R zP=5)pG8eBj8b|zSbitf`SpcmnZb&Q4Iy7c^SM!;5_`T`cZK^gun#=2Xt>RttEGL4g z>iwps(IBT`Zv49{E3y~V%(>zUHEz7NnTW*+5AVhelL?Pf-lf^xS_F6Xn5CJc!PlDR zrm9cXPF94=i(@}Zsk^HGwH7UZ4@_T`^>mwV~o!W;%Q( zXR+(|Yc1d2U(|lW@NEDTt=%ROPJ1hMRBddu)qq4@7%tIf)9IT&GQpDwuAKE@h+!oB z{=`aUWz##7;8neP3Ni8b<`!2u%0s0Q*z!a&v~2}Mzq69 z*fydn-;k6Nx5L4=*d#F}l3HZS^ar6aWLPTlrMBubAsHS3J&K<_&6+|EMvyg2#x8B5Qz00vS!0y*EOAI}qg} zX2rwzL%=|K{7a2kY1&U4VbAvOKMS(7-*~|FQf`xr4M!^UJ~hWtTe2;r{j0j7e=>yx5A*Lwn{nHEWVpUV9I-f4Nv z&3)TuO5Y0coaOi|R`j&mP2-vAES|!3A5*s*^_|eGl6}e{o)UL$=Ntp3b;=R7H1~uQ z({5^MKkYF?2@HI4hv)fCgtl38h7aNw>)+8yzvQ!mLsM=!p_>46kK+Q0RZbasf$Cz$ zs@(9$?h22HVS(fy^6=t0QStckOQkreottp0D6nw;8gRzWuC1|3*}D zP9vK;doe-^H`S2#0)<1auwvz_+2OC}OKimZPl`R7UPLJjXm;#vUfxy&uj#$5>U7YP+{UVzGMuQF%EQdY6O;gRy z2_!2LRC0%8X4yxGWb%Y82(8^51%2E46~Exf_3go8S2{4x@wP3!8{<|xbBHxU4el-H zPy*Fq^MC=KDpi5HFa@OYqa+ZWeex0{L`lqIIgXy|L-xVVQ_TH3?q`cg)Ytp8jd+~Z z*YlL?tY+x?e8P5fIJ%EgRmo~a8Hfv2uwMUt{qk}Fv{$|&#N9)U-q`e=;OyBT>@z2C z#%%O`r1+s^{>$0yTy2w5xq!-+nOfeQ`T=KfG3BQXJuPTf&P|EDSeGI#6qpZFs9I5= zCA<1KwY8k6FE#-ero+AC?mzA5O7Q7ar3VvM?92ak8;D=pLI+ z5rrnmz_3V>%EXTA?LaSWur5eBMG<>bq?+(*!2kqLfJ?Hm3bOICZSf+u4(hh}+S!aq z=U)CR5U8PfxF=;kwp^H4lXC+A768Cjb6O0?n&v zpXV!hO+0qTy2?zzz5y}Ov8J^a;Z+wYC0i*MZY#5aA4?VI0beF9a;Xh>w)I%m%?i}? zchnq<3qF`l?roLCTZ7|S$*=q6RzRfoy^3C;ApUJ{?LmQ7EYdm#&r;SRmvhu^4Tc zy1omj8qe-5gvW+~ReP(vgr)x1+sDcOd8~~ClhRF@2(UQJm|qLhQ%PLf%&&lObF3Fv z`mkA)6jDPk@weOSlzAXP8xTxc*Qb!7E8IZ%B+yd)w!~H|{^f3o9X*DefO$eqYSZin zYM#dFm|N<2x{x!P8Ij59)K>~CwS~>?!nVjAJW%Rd@6}ycH6A!!{lRXA1+KfAG+So& zr^OyFoSuSQcFgN`>UL~5o3G3$b4wQ8Y`AiMEqYtp`P^pu)MR?c{Psz(%g!wOTEgX% z%oUK!m2)xw37+jW#kGF;i$>bcbC)adn2TVH>(fJ7&qsEjSA_YqnNF6dkjG0-Ym1@O z_M!CLVQlu{yyfB2d*RCE5w_gH_m4t!t=*`(+>dReyuneIrBPYj(cOoA{;YZO1Zxh zbHyxGxCQP-@BWDrU2)gq$=9#QPbf~atSD&4`yiTGD6v>5!CNGcC{pJw)j67!ZlMwIa`l-MH5bBCYXE(BNaI{)BAEOA!WASw~ORi%ikX2+@q#P+5`^y#0k z`wm}Ed25axYILc?<+Qjm)9aII8kj2^IQbd{D;p*Fd~~)Y5_p?xNXqL|4PQGY=$QyO zR<<;ZloF^mA3tsLw`fZk8NnY}EXWzg`a1Gyr6aczFAKxhH5T4lGSaeJ`O*H*r)n1R zhe~n~KZU&JHxZ&u9R5Dysy<><)yY4#myUV2hyiu}!DGk4eZ>3wiotk-;p2hnCccrt zs*xe5ktOWO(SfD<_;^|MJximNI<8Y!peuAEzx=R$2zyBYvRuI5;a&Y>s&c`w8Wm$< zCoixhtx@5>-bZjq-hH(Hn&==z*Myt6TYLmsRglsuu+GW9(wwJix!O;BJYZb4X<0Q# zUNa-V9&<}-zH7FpR&%5yxTAmkm+I-iKg_!>HM@=&7hvosHk^WMR@4BDbefjCoZIsl#rg^wlzD3g8$51eiPUJW2-%JuQ}c4 z?=BTM*V0IMT)lqjylg1Mu52~twPgtgxF)dayeFu+dzDf{C>dGaW?8;z?UN-Y2key@ z;2@fL+`ERbrFVnZy8{=;f7fd!&>x)69}9b^9{v0jwaYv5&-nP1)9s&N-6?_4uZB$l zeqfn2k}N4y2*Bc*Sfj2xR?zP497z|j7vAGe!mhODTj_tCS^(AIB$!^ojXc4UsROCF zJz91<{ULm|e}a`)4PZ`qOBgaUUty^0FQ_s9gt)Po?^PJE0ltyhyzsvYun@}Eg90!R zP-Vj7jk6d2Lm_M6mwi{9`}%asndOM*D2k(i7_`6PHBhqGMi_SJgVoU!TI2? z$1kzP)xyS&TgaX6!M}E7jd*dZ1~jFXXcOfNq5BDb_8GW=KohgnT)OxB>T+-;P`<0o z%IU~Qb8>D)<+ZJIq_om(S$R29_QRR!{9$?t4~iQ7G2rDBpx(bBC-g zsZc`tytPBf4>uGbSTZUiG^~J>o0^rI5-CbqAoX8fzPn2Ew*2pBkf3w)##!}{2&2$3 z)A#zV?s~0kWDN1a_RzDZwK^{*a>+Qb_~3omt)41;0N*@_CvNhkQkP?k@~!9p%eVmW%DoppqC$VWh3zW_Yc>T@2oSDs92{hNGugSly=Y;mii4^~3W zRvHr4FC{*T(ioacyn20BHiX#|I2@YyZGLh6aw)tSdi0oKiW%yZ3AMVkIdd{fvdtRe z`P}d)`-en?EnIQTdvd2aZz5fB>`j>20<8a!+p@R&L33bRJyY$uM~9b|!gJ3&u@~bI z=HYYOvda&4Eh|+LPF5cZ8=Ug`M?)#%DtbHI!SmBw|EEf`gA;( z%l-kq7cm57GPb2P_M2qfaBJMOWc<(TBr`tOf|i8J z=ZSw?6R#xUm{vHhR1(QiTM~^_^3%3tF27`x`R2)%j~Y^`FWXZ8kGZ!Dt8&}IhLFy4L6s0>C9n#(1NU3ypNJzKRE$e$0Slbl}bZA;Xp<(<{l9$0n|&DsJZ}>vL81fqiyKbyht`Y|D$R4vzSO7dg`$ zxjohSBh@(r9NA09kxtcxUK~YNYKrhVi?0Ods&SO)z9@NAQzFD!Dpgae$XTXYQ^vSj zWa&_B%UR)6Q$gjxeeM89L;%5oZae_~S%SNB?f^$bAr>x7Y;;4p%AnR-nDovIi%K+B zxG1^FkKm5UL~Bt>OAtAqFR@5*YO@WhOpIDvaau>@E#3B5k&^VT*KE&MC)!FfdJ?$Z z&`3l}Gy776LmAZDOS1+tq*FxWM9Z>=a+FF;Cfmz$Mhdjv)tOP2=Z=*a4PCsvU^S!1`eI@wWCFkSBqf0rqj~d~^WYP zAt2?WTPO9U8FyR-qZ!ptgry$J2f~T&AZVh^jQ5hrEr>UmA!U(NyN)yzLR z2VWAgujioNQT|_^!!J(!e{c>djBVYuH3y$RW}UTM=Y06)X!f8xN3-YNrIUkLC)85p zKRt)ckFMyf%OBma1nDl$!GpjcbH>tB8ysOY>qD2GIqQ3)e0kRIRx{n4 z|J~v9bI6R3ida>#{K@h#{SXSvdz9^Zl+WC`nw~*YDxfv3e=R=KdY(Kce1~)DR|Z2)YLM6 zoZuhzHVGeGZI3*ycNf3ASABQ(MNRPyy#3nSXveoBFM69$IOE^yZGXF_IH_}g?QLG| zFE4)g)$hFxO0Qr0qqhZ3e*WIu*j^*R0liK5h$J)7d4uV^rU=yBu!AXQJOZh`|ED!| zOUC6N)znggGZMpcqC1|+a*{Vq_Hwd6>*{g}M37-6HB7-|B`wMzdqr>G?1k>v<3Dey zlmK*l3YYc|kH5`FUh>zL%EnaJ{`1o&1HlaZi>K}X_p%#vYX0rh#-TUwTcip+ZLs5~ zGJ)dTU70`JT$V{dR(V)^GCw|Y1#rA*y>dIa+-}LVQVR{j!L{meqA}#VQ{pb!f~#MNtv@EUnIaDe3;C; zVtk-C1nPlI3qp_}_)GK<$PPO-8NPkd9cNegRk|4jNey{j9yoG6?Jy++b{uvU8+%oH z6g`9F$cvWBVXe!113=4REtOWnyc=k#XV}IB!7s;`XdRtay$qGs0@#<6jER6;6P4k% z^W!&;2t;DPIDV^ei`A8kL{Em*%+v^z)vV0)>{VcIUR}*8Y=$zd<(3YctmRcMX0PSH z*ulapI?$7Y^_XM+xRv3O7ciN9>Lf4(E^mcCK&O##;Ejmr6m z>l#cHO@^PU*UQ&F)oeC1S}OQTzMqZR8|M66ce?KvlM;8#xY>Xpm2Sz8W)fM*i;Ta% z`3{RQ{p0%xL9?wU0>j*`W@6j*trl{x8{4hmNVDxWx{TcI_8S%J+a0%BZtQg49WmSK zVq41H>3(pqzSF~v%(UCfk8i%)Crq2S+b@29V|PGWh-q(7PSJdCNXam7Z&=NCV{b&u zi)nvUFVcK}%qSyof84BMWB!psZ<1d>MuppPF2H32%t^ckItw^ z$(kaY*D@hosFZ_fE?9z5p>Q|~t;%lkPqir=Qqi5YwYb&xK1$-48R_tj#VscZ9nj$> z`rZTBSZOwtc%QAe*&~ijSU*pMat={ZzG_p7W!qKEK%= zHvL?CxR?Vgsi;*Z(to)6 z-&UnNP!c%{2>bT0s}gYaN#m|UaUVh6aPPqP=4fgV*78Vvoa?Z4ka|$#^7?Kd;bD%h z>k(+1)mL_Q?|y^RC7MhvfvYbO8(gur=cU}u3591oGPw>Ta0qOcwWULi=BK>C5yIhc zH0ha?5(jFy4ZgRs>6*lIiNW0dY>VGUbp0y0U@q<-BYNFko&RD)|KqFwl=5T$D+p|y zNH41ld4^|mcg8;I=l8_KFed-}J+c1ltDm!;EyeubUVY>no39fv%{CiRXmeFd(CYE9 zek_X|AY{-yT=74FYw;KQRO_a1wyja?QZNk7!e5Is!v9#+STl{8e*FF>d z%ccEq-bC2aK4r7T?SSOOgTLGpslL>Cu~2lZz(eh!$QX`q?4w6f)5$6|v`#L4o+EpC zvwxcVWNBxO`AW<~E$A^KY-yiDB5@kTAfM7inblW!!7}hj5Z$i2Kkd<{tt9Pnz3#5I zJ9+Yc5EC*r)~pbYa7e%VJ|wf(jkbAo+&zZasz(}B{I*X=RXR1&2b_un8B`2x8*WJM1i~M&V)( z!6npzt|C(L`f10QcwT}v;WUy7$UAhQ8(Z%)!e4yk)zd+~-9&t~>}d;miQd+8v{%I6 zCma8qHuR^<+y6%=o6^5O*(@b`F&{6dMp_)NWMGpmXZRzX(^rFDMmh)GlvmD* zM}su;4i}#zPo-SOHj$29u|!Kh8SZg+JZ%|rdsGJh`7;0;p(lcng&W|AHl0zxWb1Hn zKMENH{Go!c{a(n@9}8U1(YGfvwJui>1&MDJC0(Fzc3WgTLGavY2=pxTtwFTNA^br8 zVtW|1Vzn7+sD5W8lVyLWamkW+9QUi?Q~EI4z7)PtB6)^T`tEeG6yCVw(pAZ9#XKYd z26Vh_2a2b=IWehTZAtYt4(1~idv)}yqRolHJZ?kBA=e)tl%Vkve#RM zh{pGSx1wYwE8P-gp1ZcAey8LguP8O1`6+}pO#7xcgMbx<$6@#0ILNbWU(2)}wxTeS z*!J7rS+$vbc>p~xu45s>h@%?6@@Iqj<=3rztYU~GuJ3j;?aOz&l!uJ{XmQo zxX}b;=Z|ggh&nNz_WDGPtpi(+mCP)LR-r}}2iwMBO>wD9086^Vw-+I8Y8Ijy%D8K< zQKI?2kh^P#xmL47s`A7nTel@yAWG_Ut)QkRba@|NK1gXhG1^k*m0i{GmlMPQzI?Cf zq=XMQJ4STtx%Y5)IZn}iVt1?WJ40vq)v&HdAMd+zfcgXA17uwVw%sBTCA}P@jS~eB zJ~j;Vpx9B5PjgGY^Kk)Ry1m{on2e<5i&+h^Sa(Q5zr@ci91fZdogXjiOB?u9w@v?p2UH>#ry)BLLFfa|8j^x zsfUc;=+h5yS>Da8)ms5i{O7bs=~_6(w*u`t=L83%u!F;7f}GJ)$&str9^!06yv0)~ z$M){=F>eP${8PbD!4{G8{6%nguK;(joNQC2gJj@iPw76WtR>kdwq2zso6zNQ3tI(eRAWE?xv-DHYnYDUBmt~$u(ZMZ%< zK_L|q*$GLx_}iMEpG5j2T+{ve!-O9?1@pON>!sWJEO76vL^-*4WN4jcNxO;4v0x5m z3Vdmm36GHrM;S;{bzqRo$j+`;>P{!w5@WFx#)_BS%P9|LP-;0QD|pru<6P9j(^(x! zx*C%EWGF!CDgH>cLU4XUbdLIgC}HjPUV$@4t`@S`=*UD@fdh}3Hh#xwGsk`rBp_Fh zR&12o@&1_o(oBgw6UC14;p+Xe9ezeLL$MFz(DD89 z%C3!my_^qI$NLox82Qe)jB3qoC6%pZew-m46N?-NRlNcERvBWGt11W8qh0wn6&;hG zUK|t{@=p-dcf9vf>Z3xe6|-9@)(9+(d_(Z+=3#S(#_`*Oy2GvlM>hkFH>~azC;F;z z_xJ8$tu|?2Vl`*Pp6x{#38=)wnb9U8RzZ|Ld`s|J66n63z0$%hL!J-~Y$5Xo zWL-YA%l$~MW~1+K1s3@miq8=-%GSLq{Ve#zY>xEgu!S457~&;9PkH^QRamk(B(ig! zhV!URIyh*JaLLW`6Fh_QEtJ+8|EKsCks&Ud#VlI6eVJXq$XB1} zjnub}W*;Z&4-JGp(l6GgNkRKUn96k7gKof)DS!=|*3D)W0>{lZ7^@>nOuYh{i9^cD z&|?ryb?T%nz2#JzD?P<8VdqL`WUz=eS06t3WrGJz>T$sajMLSEau8GC-(ZG z9;w74pjB0`m2bt3FVLV^7eSadq($X&A67NyIcn$o1}BMeT*fU0x8Efct;qeLSBIy3 zf?v!>pYyo^;n7_avA0YM7LDl0S$SHEXZ)7$WF*yMn;xQxZ8f_ZcYb|&Y3;?nj?kPs zo#)`-b7#_?KX`dBt33Y|9K6A2T9&JH)2eJ(nX$BNM4fiGY*g+!y5$8pD8qDPsL!lL zJ*9*AEz|wJv*YENN$!VGPwaBkjW5z*IP)ZF->ZAb!EG<^f4VjYKhG8ZMhQnRckTf% zbCqap3_pQFm@e}%uPgEbtH7L6Oy3G&kR#QkgU9Oex;n{(-1~g4H`s-x2c*I4a2C6> zOa|U}8^uqX85-Ggg;LjeeIMynejY5z=^Hx@K{)cdPV#Dxr%UnXnQdW^<(bT@ajyPH z`}R4vQx+0#LQi*XtFyU22;n+?In_;d1hUX&58+@V^b^Gs&O|u;R&M4z6M3j& zBkiQ6(zVV+r2DOnm@hWn$kCHfgoNMX#B93Li6@~cw!X!y-t@TTpM-8G{EldR)03?; z3DdUq9qI9=7dLt`)`6GsdrG1$Z(;Fd9P^L{>eWIkN&jTr4B;jQl`UT&vgoY1wTbz~ zmY)`S3PFo-GX%ZR-$*=#Xr#57)y9Wh0{r^AGRhm{d+sXFW3`sZU0WVVLaYsSyTF8{#eP$HB?51CF#q+K@V;^kFr zYgee=4lndiyJ0BOp)$T5QQ4WsY}*F(^6kh5^z>U^BAq%!CDefr(w8aIJ2Uo*qG|l8 z?k3Q58RzH545wKA|pK*G12c=64zZ~|Ju z7=)fL138H(j03U?%26UQFwZVy94U~h^+dcbZ>C)QxGP;iRo+~+Tye75qsBUSvcz^| z@l}nj#dNhD{Mxn7$U@C`&d7|+Zw{Z#z4xc$jL0qhmID7n1Mn-H&}AfSZvp_ejC6b` z>dFQ{jDa>YKDU~^N%RQ%?1BUEcvvY#R9nxv=d3>5yS3gS!Ms1X=d*dKf5$xoz}Bau z9$rMm-|%D@Uk=E=@?`OM^#M46VcrbU^`wR<9LiEslwk9RC)ifToHznC1qL2Uunh&o4Kn zQF4AAwD&S6tPCDw87mlxT1%R9Q9*Q>2hQJB+H3vE^}fQiy;d14hG6W1Sir|^kuqW@#BTTXCwJ_VI@w3e*qFab9s|xwx3XMbs^p_1; z_zxz~NNV6O#cp>~2qbDY6B=t1_I5~gKF`X~$RHL$v}eR&-!XUCO(9Q--W^m5HIW)3 ze;W6dC^7C9KPO7clQ#4Jh$y+(LcS9v4y#rdL`kU#+IOPlAy#{g?ZfF*zmoYqP_n0F z-w;XCr=!(~=!e*D)LGrf>t4)p!DFRMfrD=uRlz<&ObX2&pWf@TzOZk>FE}->6`KFN z-MhAk#D}6cY_&T|6}2Yx#v1RlEGgz}i1hB+T! zk=P8TF_?PzKoP{!P8N*?xizQHUWaS!xS z-1Z(mBjMM|_D?#~`SV`56V)o7&Jx+yX~3})-RqxzH$$Y$MCGx2an0g(d`1@@Z}IDo z=u2*O^xfS7#j(rc862OZ+O1izP>_$BaKje5XJ_)`4?8m+9<*ikI3DjLfUe=$A`#KM zvgj$G+*{_sQR($0l}jRXTdpOpmiEDPPP&q2#D9;Y&;LbfGI4FDz-_etAdA6N5~eIs zsp|f)Vps}%mN1{FY*hDP>b#!TRpr#scvig(?mc=w*W<@Yr0$t~_p*5)FXYlN-Lu53 z8KnF~hf)>FvJ?YM6cQNZGoM-KJTA*tD&kPci`dIC#9&k&F;OT_9s=Gx5sAx@1DZ$( zKQJWNBufcj{~beuB-USGNZ%D)PiG6<@v#kVR0eCcxR4=w65lEYH-{3*Jd;}qrWTH* z)D8(VW=ZP`zpuLZvg(dOPxK?xS>o(aI;oV0!Eo{nrI`aMQlWzC9A)%_IkH8vLnilf zM)EWn(af3{w3Ukh1=k-dhcxT+&d^97u-)Q)=l+v|OVG~_=-yaj0TN1t-xXXxckdL& z1ds0uuDp?JpQo>IT0ZQoV%wTS^tdA3Jz@833E?$W5az4I-KBv%MY6zJ&b{@Cdf*!# zn2tv_I|~JVno^E05BJxnJA^*RJH9;G-04v)AcLOmoPLQUbzZus*Zc~x3u)q;a;SCK z1&6m>fUkW>@vF)q`Dii9z>eY;woaMzxpL@G*-#DrBZy!3E?$!+h@8J&l^wG|Qs5H$ zE)~B>r4dXyk?&w3`8FZa_JdOMj?BkAsEl&TB3lK@kZkhtmBpN{w{% zFVn(k z?vb3EA(twKpS(Y(xx2DEZr9^G0W^1?r}%bTjAX1{6CI4^PK!q0=_ELjHC5DF@Zaga z+r|&0x$~&=`wYN4nxrY|#k?Yy^-6enNA4NF4X)c08z85=RmLwS~8}R`W8Lz-Z(NUWZDu2qXKyQg-RkgxA{rs|z ziS~wPT*+mmW3So)jp}9JsbuNT7?CF@rry&ERhvvgy@6rc$1xR}3kHKd+>LWXr#f@E zdJhC*$V(sWqBs>S1SnLb*`G`Yu5la-vykSeEDaPu&(PyeuGC4n5kZl@g26!djxKLN z;(#y@^ZD;h^dt47rfRS9Nt}_kHk#=d0+Z~F+am47Bs(Yzx>U~ld~d-m`A8G(e3C76 z1HZYLWSLPs9|Du?x9w$1B@5?05yXd++Y?!^Qi1qc^>6`rL&b zWSc8Ws!u4E_XJ1NMb3K;ub->jJx@@ieV)i`Oi(9ACNz>i{gz)_r)u)1JqE=Dw@NF6 zH$e!~h*df(RWj&0lio`N?Mc>_Biad!hA<0u#ha)sWgQa96cl{(s>RU-%FmkOHSMXH zw8x;r&v4dtK3aLRk3I97Oj;1NR?c{YFG^%m+>~S?)60}EmtOiLIEetUn+^-7rYej_ z7J=tF)(tv*56XF2LWz|Jlf}1QEK)~0x@3tOiVnm)6i>%;S=M5Ws`ne;&EUq!Zhff& z!9d%~6qd-Ajcf-#>#>(59gr=TAv%<;vX`yYm90?GK9v7rFGmX_N2x`0xHx7n*GM8q zWu$$$ym~M1NkER;lITeF_+GwUSB}O(`$*k!cs>vpt~KV$*d?G<=q-_}W9v511Yk&9 zV3Uw1NXp2f<;CIFSz%zGUooWeBacowKLA6*E32ehF}?j^bPPIPP9a#Er&CZRIw`nb z>=Tw}31y#{9UiDO=fa=sR#crA%&jtpBN3$zQC-qm*NIV=vA*07_9*0K3mwn5ZZzrN zqA9Ofl*o~CiJq$7Z?%S3_qO}sP_X_mE5#$VK#83k`((93vv)yOuvZl#pGjQ^oiuqz zM-Gt$A2wnI7P?X;=_EvHRrp+}uYQ@E(g9oTnLAoN|bG*4pU7?#*S9Ceqe=*Mk!E&-2v zmm_9rVrc0S&-LS8Rk*v!_5>GH>N%;80KA^W@P*%B&%e??>+-5@oKcIA>pOF)!k^jy zqPsoUvpmkIMF2ivM$C<--}77j^9x8=D*{#8Y4TV7GYkh>7nh|k$_`I14j=oWe^wA$ zrLHRLngsOE_na(OfCJQ9=UfpA{G7YZOhF2QrQ0 zb(9#(#8UEgfe&9*me)E}T6RozeMqM7wV<80VuXl^QP+m9l`>E_(y++3mQwAgRc^11 zKE)Br6VYO{K~CX^>J5!M?C;#`W0>0RiO0<|%1cQI8XdCnP<^Pt-#heKf;zinKzBRRz^M01lpq_}Cc917=1c8db|mpU`STFm^NlPkI&$QJOeF&!Ul4nvsQL6$yE? zK5SYbbil@clLu`A(6eYO+w~-Y@XcGPzn|b5mmvmhiA%ktgkL>VFX2 z$FGa<6cCB2_cBRFu04b4S;_=hHP1z2OrHid&P8HE7&d<;68mNM`5_YHyv98rW=Leb z5Cx5TvKZ?iVp$KTKY6sQrh;;BC9^}=@GF)2E{s(-8o`R3_n z?WO6^&+lmqPPbW(d9Q7E3PB-Ty6Vhd_9SV2zwA%ge*SXs(QBH0cQ(@U>}WY7A!l#3 z;`7&-(6eDD>JG!Vw7edP1l~UyNMBH^QR5z3GDG58yz{!EG{| zt_1%c2devN_lf+@1p{bu(`)vB8n1{j!Nr{|sC%V@lXTvIY;2Rt&o z;LVo$q5_E8V{*zGBxjF9UAUy@dVHA`!Zt&06rrZ6{5R+z4-|?`T-CfOF`l(bO?8H* zmyUyE2-{rPZc>7XKrSdD?s9nI5Ad%C@er}otFnlP;!$|6YAgYx%!hj z1hx>6{LPj|^-go&@e4e=*1WSO>2Kub&y#av&Rg1Z-JAq&#Itpg-Zmcw&cn+*PB z>Ci7H>TSo9F3~mj_-P?19~w-sZ3#?+Svp*D5vFiYD}a`!?ZSX5iucXZVXrgQ;m>F~ zg^mwWqlbrkPAU&5TVh zjcW&XC6y|^9aJHNN;&DS5&7e&rQz4B6lJ07V^GQk`OmY7eYH8z*L4PPK4k%cDumqR zHDMJaPG4vnNtHU~%QB{&!|gp~Y%fbZowUI;rwB%n3Pv74K+r)X1*sa*CMmoaq8^m$ zkq4{I62 zB!Gys(#r&)eo+d$&cU-XFLnbn+8y_dFg5P6CMI|yTyK9tOOzcCVMZ|5-DsR|NFXf+ z3~!#PVyVB4KpL!Kzy=CY+R(@Ix9`3d7miBuA~+eZN|`W`Bw8u+1!K99F^-@lun@%B z_(nlwE2H=kqDaTIW85?oNN>{T{YN0QB0}IoEaNTm7@P)KgiI$DfM2r&R8dZbOtH>#UajZ>La zkA+C>2Z~`5J*1PM;M~y?M5Dd=bKPsUI+sB-byGCrePAKDmaXq+H~xyV;XM{i_nKNZ zm+*e=8BF(D@1ejM7y;A0dg=SMF#Waewd8Uvj~M>oT^^|`xMkdrBdw%|!Y#yEZ!m*@-S$YFrI6G^bJyPt!yq%;a!7js9$HRT(BNpz! z_LgBbz1#v;f_-e`1h&~>sxX6-O?S0iI?3zEGaE7c`CsY5Qw-rLa-c?dx{-=&M@we{(DoCq z8!!J1+P+u_ZmV8?kc3~`3mPu zT);UPncT>ty{<&Ni6|18y!h?Co*cVLSOJ;*w4!~!D!a)9U73RS+xr4v0H7g8mavd$ ze@M)3DxE}@sA7A6MD=dkt$-|X*g`N4AnILNlD6#w@yF*2fwY(CU^0<>*oOzeLhyoF zP$M+!{$Pqwa6$UB zeK>sRuk|GVrg%1YK07MnthEmci?BK(OPt$;JbB_%+$Y1kBWQI(1@J{)hgg@f>F*7D ztJRt%{j4HF1{yvA{BPxeP^9teQPLmZx?vGAge~7X_wWhs>h~rz2O(W|g?aeCY|^&_Ez{m93U$oy_YqYGHnYR z2YfC~)P-i6*I3vO6+9k$nUDY;K2wj#t9o-qVDeWYNAoeM6_>6~YKtr4M!yL6RvlgP7zqmrgbn@NZ zxltiLN=$5UiA{XGn1!>FdEWA3@pDp}yFG++aup-sLSLs`$pC zx1t4akI;tVi}6g&WC}@h!ZJi&5-}9x|5%l<&^rQk&9I`$Gn(WSS#ZRo4 zHyhwjlM5vc&US*D;LRp(r(?p54t!s5Cg00~wGCPXNIIVdf?*AxeeA71jvj>a5<0MkuE$+}B<~E(Dulm-L>6ycDJI;AXUi869f$ zN|-hZzXaiKQ^)KBMu$m?59H%8qXRw^A+`1uGBevqYU%At4`s4^HW~eQBZsqJjSiR} z=k!zoqXVsa>?9W=Q<&X&{PPPr;0rYbA=cwnm8s{K-=&4_a;z5$`J6Z`r7@H75M)bI z2_}B-mfvW8{a$9V?cmM{Xcyc=P~We67jeDpdFBEgVgOgk0X&9gF9R}HLiMMJP|H4& zAz+3zibf}YnA4hKYF8C9$t*p4nm`x=MO>MNx)#4VAcQdXB%vN)8dZJNPJIAB8W`M* zOumDi>Wtn=F7VK`(X~{>O>XQOijdN6oNae>ge)?tV!gM6D+M0Z^rSE@b6vX7GpdpJ z2bW1H0kxugPx&dpTd|J;4QbzskJD15qwB+#!JCP8^WmX3p zrM;fLX!y6)jow_~_c{wY&jv-vzX-ST5^Y2H3H2lswSuoxZU-N>QR!4VCkgOuhp4T! zfRg70#9y#*4pNEIqRd_qaNG_XZ6i9=fkTjkahbU~aDM$9iNY-BTqee7jruW*+vPzK z1V<*jns!Eq-qJ zp+<`@Gadj9f0A$~8Yu^c-$VbP;a^S3>h&~ewZ#0|@b|mKrc2KoezR3!3i&l(cmS!7 zohVMF%WJ#$_-{4*|0x3WT}AYkXut6Jp0|#&C!iu?HAqxl5he3$3RQVu97dAjT=)3u z2>D0KoX&L$Wj1FO-*W#(D<4E2hw=N}&p-(qXq&|HS;NAs!6ig}{wT=YDjz&=i^`7i zTLP*E7p49RGjUf%6`u)3$zk#i2aD%>D2;x%Y^&qJhwk={BHD(oW za?nuD>4kHE1c*Nak;DJF;fLSO@(&E+u*U`OH0^f=ai8KLP{IQ@G_KLW<=$@q$>VT= zgr5xJXjbP2aTq{iChK7EXY>MK5T6rd$^>5+#Opo`CAv2K{E2XlSiN(4!D|Y9{)zCb zp+uuf&(;QkPlU&F9zM%aC^Li^#1Fbh^2{bNVG`BSpvR)d)oRH(E~2`!V}hVXhK&c2g&tvz5soDDXSv>$tEg-jtf2|%$UrOPKJZJDJ1P& ziQ%Q`dv|zL+T&T-VyJ70F$%Ze0IHQL)0(p3T(GdtJzZ%r$>H{!B4(q>OhfX7y3X)- zqvv79Urf~an61da7lvaDd+bi9-2s-aUf%tc2|ALE{agL0Q7 z23{CSw3eGW{DLH11Dj#mLl#_!N+=82N|3rCK(q`>9nS^;5z2B3b!e z1`b5|<8`HE-mir}4kWnv`kGZNr>oLO)uS7V;Y=N^WXG%yo8Al<2cr=Z*{-&Y2YbS1EKu`#wJoS41;=530e~02v0203RqI;_b94b~R#IS9`@phoi zU9w)ICaedG*p7~;Ddfn})!bhts`xN+7$#BG6GW%~`iby)GWx7G$rsx&i7GZb{a2w3 zHIm51Hc{xW4^pNFgfcj{<4kpVtVFOhFyBXV)DSg!(s$N?LW63-i_GECojS||(OqUJ zOqMWmcqaz-xKsc_nHM_%ISf25BHcoyJF%Uo`W$XYoi>6yajQ2jb0iT;*$!WgUw==_ z^0^JE=cURW@}G1wh(KloCmh3n!j2Kg+keW=(5i9eMk-{u$j;!2Cmvi8ybFI;ynmu*3ClTez^`svU@%M{btLkCd8BQLw)D(@T zA}9zk+^t_SfXs$s@1!nGMAXk8xzpcm;7%N9V$n_iv|ZcmbIW z$=X{Yg+AOkW{T=hC#Vl+fy@TsA(0^Kau3|Nq>SVsAhQ81#?fr(XO<^ig!p)L%U~u1 zU|y*Op`|-v(tIq|vyW9_nGHx36*5}zhzk0iMu5TCj{`GIEAIVX_($L8`zwYKD_`h; z_LsYD0S4plBY41H?pY>q?l1odI~JP?k&aUf2Ig+6Ms^S=xB135L)hhEpFc7f!?0sc z$T_AYi0tLgp`r`|PWXki$;VUBE>nP8PM!Ufvk37kA;$;JntE)Ld`Gd9+ z+ILY8zlE=$ieP}MWiIvmi6^+;pe|c|tCDAi>TmMR$8{2x(;BB&Uk>lfdLcrkUN*51 zOuHo(Q+7Q}{=I@THRePI45@>KuiO|S6K^mjJYU@O1FUa4Q1A7`54+yJVwrXi2;BE6|T4_~=y;iGl=?Z`fdE#9FNfYbp#t|j9&O;<1u(&)DMsp6*7u+ufN z%_|PppFTvM3$Na6MRDVRH(%YVJeis3f`zY~EiCpVh|xz)YB;UI*BVU2!dDVi;KAfP zI6XzQSWn*8(tdP-g|B!}&a`~=tTW!5wuV3Snt_FW=S`sPsoy_ptp6n>@dFU+(s>K^9f`Uhs(=jpE}U=H;WMzik@bt{)O(*N3_ zF8$y7xX$0!`m^U7$TR^psz2LyFM+T?;cyARDKf+|ay8*X3?ShMgTwzk;Rv3l_}x!k z`a3#8%`1y=wK8@LyP<{Y?oa6}zezZH>?@1(QLn9CD=$NdUZbnM_!=zX=tAioq0s}= z$1sVgT1ce_)Rcx#R$0Lkj%?{P(w(6DOk>@joNe4L^f9`@`$(fF2bDmVzViiRFn4E! zy9bHK0XM)t)v%JxY3yXLXQzHR4H#f0YHWo138N3ORA(dZu`p`I6+o~(D1B5@$C4ndqRiapH&s8z;( z9!SbJPj5D3K?&9VozJzVHeTNx>$YIc zZ$&2l_zfBi4*#XdZX^v;{ZC>b${zQr|5*&gheMMOPYRlz{3ZtC4;Vhjo-SAn#MwYY z2rLGIi9PTl1_CfkY6QoS`2pyN@8dwgEJ>Sh|80OJy}MEl46tL_pT7;TXDTC{zyLeF z<6XcA46rQMuY4O|ub%B2BAW+k9*nJxzdXFdA_a`ahA&?pdnBx$@qE6H`{>Q)$j$mM zyVFv=hwE;Y4+UpX$q&Z`8eCBdoe|g*FCkYpoHcGZVZs=`O7@+-4hP)Mk2^3p`~{XG zacS%6zSkq1)tgRqceT-wS$Odxux>D|_g?<;{B7X-O}7iBH{W$U1T`)|ALAInPk4p_ zD7|x~P(lH8#K6!8ru5d;eNPW4y(3%zbmXhLF;!yat+3!jrv&L4e)5MS_)7+BAp!Ml<=<17!ik*o1aSYI{iE@F7>XQ3T z-Ct}L2T?=Np#?Falr|exH91l%tN7MiWqG{o4ng-n%^!@cL5+GM8;4+{m?+XW4wk-vR4Nd~VVZUEe=1Y^t_h33$FV}Jd)3`@6!i^0yyThY}IfLPj zW`p?T!*4eb-0q4}_j$mJFat_E)zQYm0n5BbczjAFV2?61q9~sacAnPT+cTo(%N;C9 zhT~&Mj8uajrbP426W<*RH)7b;rH5iwq0);$c-rw&D=A6%jxb7zc&O6H=KSgN=^AO^ zM979e7Yo$M-I=jSA|nR zN0%9M!=N@jxH7G!t9g{czOz=u7}6b}tXYO!;f+$Ate5X-RI%+@0;oO{3eU=M_EMPq8j)8H(7+=JX!c>Vjbm6b)iU%MPS&PQQn+kC*L9`Eondf5ISr!dAQ#z@2)FbW-W#Tu&z9@$1u@Jj<8L zZ++NVvUFY?th|24uy@6IjcGp>1W9g7n44(5GHyP=A>s;7RyD^_5-Zr6A4QHhMx3ug zAa8IggUa4&IK%^&mFU_IoZ7oyQaziTMR1C?)z7Z0tZEO{8C5diBFiStY!v z@YXVx=ujdTp9%3W3@xdMJR{?D*E`CG20EO0a^w2Xzh>ZN$XaK!Lo~eFj$q^PALn(Y z$7)!sWT;KT{ec$8``bSCCxK0WLyPktvt|C%IBd!YLcWk$!!%+yra=!tmw>+@6a)|y z$jDLLI29)4>f#Y+l4cyu1iAZ8S`^8`)H#zH>mW03o9y{ZLL z;c?e_%A5nU!GayPD;VCS1`g{Y5$Q41Dvg_M3t>6q)VE*s4J>62>Ud4nDrD_2ZItMV z7|cnCgc1u{!~pg;G%&dfF8n&}d2*w+T%pWC&np7bC}%MI6PEMjMjf$(Q`sORWK4)V zf-weU(EB{O5li1a9QR@hMDInT&num~ta=v@NNyw_*X?*DYxXo47rne>`lc`}xp8xH z?y}SURU|g6%0KB$s)z# zoo8zv=$027GJ-(y@cxZtPUzIwWKZFgTSy$wb5p&?N+OI%n&yKQfi}kf5}6+Hy!w(K zU;m<`VsUo(7TX#MhPeBwZbp&|QJv?eX3HfBRc#$gaYEljf&2&U!vT5%z~FfH!{{_a z9~hL%7&9vvlUw)cSDn)n9|N_X&CBE9yb(6QQMH5RrXr0HX{5Iuq*|wiuO!DA8L(@< z269s~bZ+%2Q3#2~DH~Wg!K%+Aj%GZiuPh4T>-$yOhxYU`3oMU}2Bd1WePtzv znLx;2w%9N>R8GZT)SSXYwj67J6$YV%$Zm`l8#BtL8mATjA%E+9X=6CK+_J)n3xL>3 z)tvEh`$%B^u+3UtL0HHZ5b{^vJ_nkJ_?AaDV~zG_5Xu`P@Yg)D-*0!smSgnvBr=k(|2E_=Qcrd2r7FWc0W5&~KKyt;T>&!V4%2To zQ9Oin`NKl~?Aa|KHerSuS6gE^iGPwm;{c}~59jnt`TS-4v(Fa(&yUydlxhE*auid>gxU{(6jqvmY@k_HG71(k!ip@WH+FTRZKG@4HU@xS6Cb{2)lVV z!5M^xpy9$z5Ty=KWq^4Iu?z{@9r^}8#eG-VC<#G!bo(`TY9Y+}$*`;K4DVvA4ae$x zAIojR= zqwJ|H5w@sRf$||7hrq!dsD8!IOZ!EWpTWS9BoTTn(`WtkJQ45&Y_zFBoZncK&Re8- zyLxj9fuQ*GY!hAI^4nO1P=2Ujv!$$AW10+SK9G?~Qni>9kuwITY;m|{vR-5#4PMuM z%jyTj`K34M+iWb;nU#(j)C?Dn1Lfn?z;XnX4-K`&PjP!uJ^SwFJI`Z}6R<^Mg0OAQwI)q5(!J5&8G?5j(`AaY z-dVa|Kx?-a7qK92iOOG zkD!&I+>Fp%Lp6u9dzB$Jn7pZo68j+XHV_XwgdZ2%W|=|&%+uP3aBGrJ7Vbb8%g39n zyfT=E83(M%Bif1pVy_2n2H|r1c#`5anLoUsW3u8#jMSqaVqH$8@FzyXb)@N^cgnCNV=x@51W%v?NpPs}O z(R^0dRxF7yCdq-O`a=YY3(`_7yt5#!L(`tSx~(ijHvN-&wS$bHBo`!iD?WXW#q`Y8 z#pOqdXYW)(g41E4wRmlWanZSp)nuSx78ClM=c^o8Nu_uW*NrwtL)N(Sz}z?D$4IQQ zi~c|AzB``EKK}c1>=81fviE3_s9TPik(p$ay=TLU%#4hztYq&!$}XcpsL(Q!5i%>3 z(BM4Za~(vX?(zFQ&-1$fyiX3-^&Owj`|}4TRD$DRJT*)pUutJ$l@=4 zE?qVK;3j?WzT07H`6Y3kgLy^B^ugORO>wz9C(GHg;<@UvBdszkcpm0whE^kv6g?KM zJ9gp8`;m8_{5wlrKeb6+9-U~H=3LwvNyz(t)^+A6+O+ml$2m#aQw3#4ivDj$I`oTh z2Tp4F+mvf$#23u@tA46NLj$5SROgpXYn_axKcLr`C5wcpW7Spi3P)pz8al3s}C+tfBtlfS$ZvWv+ zaf$PF-1mLA?oloKQXIVONvFZDFBI8*p(z~prAU)xASYecBj{N$QGE|{V6|pkR#qTnI$VPSY)$U^+wI8ndD0m)Qg3aFr{AN9m!5p zy|(x<6h~-DAPvd=0SJCYaVrACP^AJYzOpjh>`HZE5lH7xia_wYzgPHrFiQR5+gRh= z;k3QSy){9}YpQM#D^U&vzdN5iOy{4=mIF}%-p1{hKF@%$Grn5~k@H}cp!8{on_#awuxt2ZUuz*j>5`^CA|%@VF+Y&(DDQj2r%F~f zrtB_kxe6}2lLf9^?9=ZnRYhZ^#q_wv(Sl!Mn(PmaysLNi?Zl+7um$hGZ#d)kWeEML zueDQ$%@1Ge>X#wQzSa*PVeA?To|Ug05olj))~y=OtAoeCD6bs^9)*}76GYh0`)1d) z-BwX2f4FaWg^sTUYSu-a1oDsB!BHocHBKLsdh|%Tb7AZ12nB~FR&1X)^?q|7K&>mB ze>&tMZnUDavoSBEv&6mw$SQYHWK#xGc7MIecWMxI!uGa7L(9vTc851Q zVngcU!Sp`Q21RtOOQD|P_F1$GOxq=#-<(S{&;XWCh7WJ}&qXIeJ56Z@K={osW%@eLrT8T>6i=L#yt!m`BK|Kje^xG#fUi3%HS~M1?4ECy`BP&@c}sNFKA5kY0quPT zE|AUrety)LJqMesP%g0F&$(2B9VqSbJpI>0tC>IcF*{!fc181E%f!(K8)1pd)60>l zgQv~ix~}=NN}r{2o%@TEb6_LT=`UygXtiyFGk;d|NGxY{e5llDPh+xX-kt$@+*@bO zaP(eY$(nKDkPefwY*d1?W-jCIS;?9a+I=zHQ99w++vt5y9;&b}M%HK#_YE+U4TBM^_tUOy zgbN17<`)H2*W!L;5I4kt@Z53@OMB1l`4x3PypEQvc%9B}s}brC%}Yzvo4P`n)e$}1 z=~YJml^4!Sl5C^LfqppWP93juUqRhha;wtcvy5DNOf`*sgxF8k{`iZ&+2tf+zs&4z zoAE{)SykO9m_Dg3o+P~d9h_UWI3tM8tLLha<`A+`m9z4eyN=GD}~C98W2G;+%hoD`7&FJz$5=BY540Sf)vb ziULiY`oEo*gg(rPUYU9WTC%gAxHFvXlC9P*$}@B^0+a3XmBT%5O%4HO4X=iKuy4JF zU8y-+IH=Y@UZeo>!of1xYUK<*(4+Y&@ocpWP`Co5Ro6uHM;@UQ&w|HzO&=$K#IqVL zQ}i^%Q?{E8tG*p1o;g|z=pR2qi2D9=XS-4^-~;V$w5CS3h-IZ)19|M+WHuJcox5p} ztiDdi=F^1RS35*R^}%@}hD)D1Be|9+NK_OmON_3~b4bw-yvQ6%3Kei7*~c*h1zS-I z*r!$5OS2P|YxF&8Eu9RE#V@~~9XkV9o7AnRYiR91^poy?#xOu!In#d|n^8}feyGlo z@Lhwc(xO$~<^36CVf8O8K2N#oludmB)dTPN^SgN{%Ql)Ejp^s^y2^~XHG1=(hO)Ha z#IplF*X_n}*Pni%41g2Qz{-(r7j3W@W0tIS<6=Ruz)4${=2|k8>0E|hd+3FI5hT** zRA~1joZFCgTBRpL{@bLj)iPkk?To6hX)Nu92+??Yl>r`W20t@?ipD!4! zy#Wb9Daeel+iDG@N?)max2@F7s=g>_IrVOJ4g92-t5Qi5M~fPkIbpnrGu8W7QtznW z)LmxWW?Hc9`VeQ#L!RA*PQ5!bIcwz2W*osb-Bb=6=xfX#n(p(=J8FY9CS0H2hbCU) zxqeQr(ZC*wIB*Be35&fTU-G%=!f2f@K17fJ6E77x=mw?)%qy@7vS8TLtB@j?sJFYQ z@oA(TxB+)f@w01>31uE}vYG)=4*tG4E??}PJp%^%A7&@ccipUliI*ID^(kI4=+i?^ ztp)#{TMt=hQ+%h^74wAWVovyRo2t_-8iih`l+k<>Yh5n# z;yh}23_Y_0t`9>Q0qaY_l{K&~8H(E|2EGC1M~P$-mZKbUbGQ<7Cp@sdhdXnN%WvaL z=akw0d%J{oANncbhJnEbsKDtI~%JK1_U8t7dv$%R{|AOGb3nLzI@ zK})>`5+DHUnI7x%mg~8}4~4h%h->pm&UpT5LVVV1=|L(Pi-=#ZQdsAD|PzQTj zta!_x-5Tw!oQZk(IDXLrb!gX3LFd>evI;t~Th;Xw>7Dig zV?rE$f55i_< z4i7jGQo)EwBMD0tCm05;4NqfMm{=`2aD!5y2uQiA^pDd6e>v0Et!GTsRc1WVVM9#R z75+<^TtzV=oVPjomiW>j>WUw}4e3u^E8jTk3an>c6U$q~76k8+Ynx*<$ASJA(+K+S zoM9>V{E4Q-MZ43Fgw06v%j{--?G2xZ0#5nT?L`3O;v^Zc&WjYkODApx*HZ-= z3|}vEd+{9cIzf`_4&%;;#upzy*-j|Yc8C%}vt%z^O_%yGSCwOA9~iMe!WGVSl96^o z@kJ$9i!%`xU54wa7PUS=Mc12*@KU_j@rjFjc=j^tCCGKc`7kVn_5fX)F0)Q50bnpx1X^CsF7GfzPNqzLz+dK+8m zyQ9fR7e7Adw|F9R9eHazoR#-A6+tvI{!%!?RGTvOV|UteSQ?^34(oxTl(qxAFmkNc5M=a<2`PL>zt z{|5I)(&9rZ;c`!~|1{;l&UMNHDJ&o?O|U_E^p5@dT&F(_OLN-_R9YXFw#gu=Gn%lm=M%WS0ecBcE1l8xiNG=*`g5gN42%j2Evr-vM5qB(8KVm1{WL)vb0$x2V$ zF0Acv0M!U$_^~6$fGh7GB=aus$d4&`(d&|V18#1h>i;pCUA1uuD!AnSBN3MP+HOoT zuj@XFZbiCqa%u%&;{u$iPT=St2$ZN`|3U;O^A=I>sD5((tuDId_oQp?o+EzM7=zLs;Q?1cO6v!gR1wX^jiAHn zt0sVxdE2zZY;vw5cYH-L5cqtV14(O?WlpYv;y8{kw@T*yX-EFs4yW&d?s6jR*9zlE z^@-Ua_tuj+89^;34sWCNzs{418$?@}`s8<=2QY67m6TM(r3~Z^xJEgutkjbPpIyLtf2kkA&lhPgLdhRH(mg57?}szh{J6q!UaQ>2!onsY z2oY2CRc-WcHU8JMvS7elmvZnwT>PdWgzJ3a=-TkC_511$`+CQ>onHgHrWv-p=@4h` z{*rjzY8?XtqgDjX>-QD4MXA}TD7}gm^y|5jNyZ9aZ!+?XOj`OFoOrF5vJLM}Tu-je zn>rXdh&9yA%uqXOOOOsb|64VR(52+vSGTc2PgpIoB>TC-ohh*viq) z|E{Hz{t1#Hlvk2r(bc#7GS!jD@B_>ds<7KNafUF?wriAgAdQz1MfP}h-=~CdRd6=c z*0?6p;0lRc)qn8~Bwn9bG}{?~uKj-`UjN7YilQkAslc&%F!aXIIAQ?L29s z7j41eX%nB5sW!hb6soKp{Ml5Th)r-b4wJO(xS)VZg_V^zq=9@ma=BzKf>`Y|(gJ); zDy)u^F4$M^Oc52A9;kv}L2cWy zCPw~^xE}tZh&|WYRocRj82Od*@oj@1wry4X^>FH+V&o@oQY)uPt&3Vd$^0x#Xj{kE z*fKPzvMjQK8){5^IkhA8#e>T+^28Ok>io=Czw(RV?(2t@jPJ_TTkg_&Nk!FT%E!rc z>xeV0LfFh!@TO{%<})?q*3RI4NIObzTvlc<`5d;8Kf(n?Q^Jt4@Jl>V=AF?LYU0fr zI>-=uuI@_oWo4BA@%bn1riwDSp}ustKc6l_y!pG4{f%-w94;EbWtBj&O?af#$^<{C)(L|Fpbgm@4aj?-Y(+4p3F@)1pf-6+0XMZ-8uRP&ek@=WQ2 zh3n(X3%O6AcsHZNe5Vbk^>> zn+sl z(-IA{%|uokX6*+3xU7DcwYy3A2)hL6niQ3{DcA#-0NsufO@Y$eQ>i1Cs`d{!du}=5 zG9%lkn|Xu2alMvFDopM$E2_~hu+_7oqH)k8pY1cs9Y;3Cp!AmaCmivx9mMt?$5PlB zAVBnNqBI8k^O%wxMykHb^AnSQ4AYAKlEYdjf?R*;^)3TmtC!v;CgJE}k{IUsOOWpC)Nszk#_0sFr_fBfa{;ZExetBS7yF~xPCHt6=$yVrVM#w-hn3&dO~0?^@aM^nTSoo5y@_*EukV|o zI6ps1-1}*)jWeY0ujy>8IlO2ZVMhDA3wR2h{d?=g+)#6ioXKuqKbw*9z8`-Zgq$Zx zmv$o*&1x6>Bqw}LERJm zW8J;xOCa6Nu6u|^Dlc_Iu0$Bhq|8HklmOwjl@l2Red zMH5T;!tR2ktuoC;36^Yv>w!ba#&XxN+bXTHwx=!bnJeESa?l*`_(nuH5GGDf_2G^Y z|BYsFDtf?$xf&H`Nd*9nXR}tes_zXws zPV_xu{-DpuM8~}BP%6a2d!$ak+2?N8ZF$+Rq<9I_LPv-mSiZ)7EE?8(zQ4e!?^35~ zO+~-k(ABvCA4&}&i7I*#^+Df5AB6RJcT!yxzecGpa(u7Yau)Vh`xAEYAf*|qTGoib zyNnvZaDQR#2fM5f!YA0Z<`!JXFxa{DXhmu))nxe}4pwzNQh?N0|9Ux0-kTq&sdh$7 zjVp@uV&+!ZwB}l0P6So%SM>;CT{dF-X3QTKIwiJ+!;_Jp-1? zfR>gtS_E!sm3v0?oi6ti`z43US>FBvhlj&MI}kL3mSQi0(i_b-78563f^%zW(4!ZY zQH7PLf*+$7Gy?+!&HQHY{3Aj6&qgmMT8$PKXJXdk5V#NvbO+(J(MtpRc~<#fOe!e8 zb8hY~cs-2mS9ig`b#=UUb;K;{A6LiPm)5g*u)QDI!m?ih%@*i`hVf!q#u|ak39yr; z$QD5}Qo9GQ0=9rnd;zUxqcz#Bwx0US#1&Q-(UVsERwaN8ehREhQeb4LvE#k`65n`l zwcEE@&@aKI9h^}LCap_v?WT_1u1Hc&;`;t|O=)M|;efZDYm?G$Nx~Nu0InKJFuGg?#v9YV z+<}OJvo{ohsc_z}>p<3>y<49x7oYY+H#V_(P-kt;RQU!7|lM(MJ#po|f;?g3p$*UOzH$)&_9F%d|XO&3{j0(-~1kaps|` z;A}CHROK5ElquLnJscwCH>w>j>yDeI$^p0a^qOZdAy!O_hTSp>hU05UEx=0!Ed(lG z-+?TPM}Le!%)PXBp~a)G*pX>`Ycp?f!OLzz$Zvfn`7hy_3RcdfKKxZcAF~!4{cFJv zsq8(Ehu8a)#r5jTW?g#RQpVd_pkK36&N?i8$4B1d;D+$J6wtDjTmxKEYL|+=y&iR! z$`#sM&45xE_VhTX;88AHvUsee<8@UCU@-BWp&J30g86HKSNuzG6_{!UAsvT|=6AUxh5`GdD|EE}-QfjxcnfpLt!ANNSCF|ll;De=MxI4`-J@

hB(buMO^y>@vYd!j^Q4-{$*;YBMwF(? z?de4Rj%b$l?9!2m(HQJ=5n-N6QMr@Fj<(2mC6CVpzPoAvN}jy%vCI(*U0|F898Vc& zU)Va>Jg_Q;)yC+cT{6%qG{GI%;4iE*$N_UPgeP~jfz_Hy8|_(|cgD^v_phW_yJ6PLpo7R1-cH3VE{RsoP|T-IPwJnnQqCel>^ zWRLSBBcu@b+ejKUiwrkTTbu@Y+j{#qQSgcsm2N%-8E1;bI6mJNRWGS*8kG@ekD!rO zNNu>jor3zh7UuZTbi~^CGy$P_Q~k(gA$eL}MuV7Zi6I)fo$=Jv=Hr=fqwbDpiFDwH zXUc~YVK{ZNEHoBTNqLPpE-Gu0F+2zd#B=5Syf8K(Tdwp37<1y72*^)?M2z@U->o(ItFAU*hz5d~>@Vx}6CJISQGiLa5eHktzOxoP|um{I5Q-Tg|YZN zm3nvhar9Busx@jPenP_Ht+RwK`ly1DvB8J&$JIz9O=97r>gkL**^RS}fUR$}cwt1r zj@~}Y1^>MqdSSdWNyOdGGq#1P0lIu*pD{lZk&I^RhtLP2$2ecPata&Kf}S%=5@4`8 zGI68ec*2~DaW!6#8lB#D?sp|dGvKJY`lb2ZElLsM_oXj1dbsjCOfeo`f9&;vM#hR2 zpOIRhl}Vk;DNZDw>e?qxD8N^8pHlMDbkg<{`6Uh1H@*}<+)W(0|KZNdmu8xOftye3 z-u+{?{)Wid`@OA}74OU4YirRF@5_Q7G+SR{Gi2;rgX6G)l9EVjm#$LQO#nB4(Wbc6 zI!1+WvZp$(gZmt?ABr(?nbcnEy09I%dWm5r{@7OfcQtUac5J?_Y>nCBuH*>IaR6vF zN9_TCmc@1s#gIbVKjeR|Sm!B}!({&70$LlKx8iB~D;#FB4whFYbxrf~dAe@1jA)&l zf9a`dK_d_BGmrXqhf|^XpBN5vKy3)GUMt<9Pw=+FWS0KeR`;8f_!(|x!~9RN0orf# zSKW$En(q_2R4=qMq&g}3FR6L#r;Yud3F9&wlzSU(E3_>wrrcZER^Yrfa(e$ddxgUc zbaE>d03h?j+e&3~z5-nuzv*(hXDZcNlN0WFUTB!i(*a%XNxyvvwpFH7meJbFlnNq* z$g#IHg4uAIa9Sz%U!Iww%Sw&hGkK0gjZD_KGFM<#vbDmSlbXC~1vM~Q8Ebj_-U_+* z;i~6w^cjPdmm9Pqf`muk8;Ky7U+xOI7nFCa1a+9)yIjk!oS87WcX8I^!_XrS5|34! z;MZFI8u#6vy(BW(u^c$uOn}@QG0b#!&Uh6kc&4ENUT*AbQJ!*V>YzQ1T&#AVw?RX} zYjFY*ovRXXc}L-7^xK!aQr=12ybqI6M&s?}@eIUwcYv3BsntTbAEYQ3saJ0&rg54t5ytW&Rgg8)n7iA`E~Y?%FsO^K!Up#$#70K+Z#;h zZoVYb^>3~DW-#8jilq3XQZStL>7j~J&Sm(^tjK+3S;ss*_HWKCxJ6xiX5BV1qz{+9 zM}UktZtHA(O+}`=XD_ZQ_uD8Y(Ev~in3|fz=|4ECwz7z<&?zPNW zM>9I&4w+^pzoM327VZfNw}_{k`yz9Tt5H!2;<67c(WO8xuYHp3=eJPgT=hD;&tI0c zO=2DCivnanDfx#={BWzVs*}L0qH5B1^26=vHNw43mNnjq7T`q4Ie9jj@))qvre8GF zuiWAEt|WcH4Hnz4EbEKiEGiA&=O2H3j8`H5cWl21E-VZ8j@)+WGKK|6Sp{=w0n%Jg z!qZOD*Y+2L9DA#qgXayLrUZL4``kVFtzm8Nz2RNy&j$SSnw^JEAxNv@-INoDBcja; zzi5Wq?Ro0}n0Xm{Q?u66UAF@P(>CnWKQ8}Ys8Q`5^%~gxL=U)BhM*Aazr3lghZ{DB za7t$GvQSHX7{e`>`nvMw$m39kxnS{(Zth& z=TEnYF`w#-rxP%2O*(Q}ZezG~ckWHEYbY7*lIxeD z&Y?qg9!qXtQMhCMo?kwn(sv~I7_*+N_{W$3FB@sO{a=6i_w9&9o^sSw2BCc$VLc)y z(OO4$WMQaLXh`yU-8(q6j|Uhpv)H$Z`%^@61uhAW1qE7A^H_*qP--#E!0AqF$BA}y zVdg~Kp&m_54B63@k{+Eq5lWE%DkifF3uQo&zteDHqCmiQkVyPQyag|qHoF>-?^wzW zlV+mJ8w+b8dSskyfY3J&!Xn`CMP`)pwC^Ugn0!~!e()Q4fpnnGAg_BIF;KvAyvP=R zSr|O_f^9@NyEPqRoQkAHiAacy-#lhFs*{Lyhl*Kcyd! zVTv!wO@VCds8&ubSXOOj0UC#`$EpAh{ zjrjtNnto$WQmXknb{tz!Yqe>84w}~QrlaknsmH!q>AQXcU@AVZLG5DQ_>&$TcUU6> zI8u_I-9D4qPK6&(5nb3eHgI_a3xa&83Zp%}ao(R&aR(NCo?5#!xKhu>bE&k`$e#9n zV?ZClCM{7e+aN7L5NytRjvzQfz<%;D^8L<3;mHLoz2bkdjEC)1lDYUw z^p1_H3XYoG0myGkZrsE~(Zz%;s>)X`B9s_+`fXgn#Zp7dgE!$!X`qiF8AnTHwL1(k zn7;^CwxwP&+W#G^s;z_aYX11Dff^dF;E zf20J3y^%3p)Y?Lu617vfcR;kJv*J|{3{K!56hTpup}`52TSF&9SHKCzy06f;ckf5C zfZGV#yN*lWbi#(V%N-lT`p(wDAw6(Pe_0DNMo|$PkZSUDb~(^(CHX zhNqBpAn>kBL+<_hau8i;cXJ({8#4+%NXmBi2v^Km9-2E99i zZ|qz)G7US7NA!xi;q!Ftn0uGBBXdp$o(eE!=Q_#TQN&8Af&0k8O8wTcrxNV0(Kgx@ zRy8gB#1*`~v5o?{zOje0*8;WDuM~bagXT#}T@j9=?Z9Ereb}yX6*ySCyGS*W2nm<{Ik0+#^4-gmwXltMLc5!vUv0gE|s& z1I2v7<=Vjjihl9NFYxV)6z^bW2n`&>(ghH>Wdl5J!agX7W|5Ui_E2Lst4iUe2ZJGr zQ3wDW2sx4ImtArWlG339c-)SI0nb9OD~gjtDyBIZQe+cS>~?jRE|N#+}y#9wp?EL01!i>{Y#hc0450fjdo1hYw3rQ zdd~}%-))G03Q+&=-2oeIh`oO}I2|!*^Qa?PCAI)_SWfJ^RdZM@oE39e`0X%36c96b zJC^XVHr`DG)B8=|BX;5EcQ>^i)3*T88G(60uGGQf!Ei2RaQ!Kx*J0RzT|+!2fCh zw(2Cfxx31*bB;e+M!|wuVE#^x-}JcZlkO>EY{asqFHCAmf%3pT0TJkew??J^i}Z$T zhIUJd0D8PkN7-EO4Y&mHO(t0zQC_6at^ ze92iUE@e*xLMO&_7<~K|`1m%61bmzU{c+)TM)>1Y^_D4;zI6=pm&VYy82RcSg$41I zLfOBp(Jfvnc-LF31vKA#!?ge(DFn~~h-I0Ju>}tf!^Jq}Ge_ztD11|2&YKfIldAGO z@=*-qD%*6k$c?{689Eby`T%n=8t?pM&ahv#{vYw+ezXrD*9HT0{pimDI8VCk00>69 zA7t}~N6Lm=j6dwp`-XdwhdL@(pho!B{PgPdr#e@+@z$@75b*g*A+(?FmtQH28AN@q zTT%4Rr`CJm8{GU^9m7rTax|IDvM{-F)L zVU)D3Kr{i*dusJy;EoVhi}&3HQ1oOPqXn!SW$j_rncWAzYC*%t>59LB-i6H{Hy%<_ z3fV5Q272GQe`gu(%H;|UH81cqjzaq2X}p8vw(Ss}#%!~nr%dehyT+6a9tN-a1mGVc zT@XgHx5Vt*S!(9apd(NoMr`G70-nig_~G)Dsb@My zGSOQ3-Wiur{a!DJZMG*T=H8r6Dj+~G$FfbzoYL4vQ`qvU@Hsy&K28Y{Q=u9^@jS~( ziG59xSYG^V2N7`-{pk|#%a4vbm-pvKaguWI_!^ksFE^<5%e^VoQhSn`O_1S|Va~O+ zlbB>k4q||0zyr7eFNZMwNbhxalw8vroP=^=b4u=|*}#s{hwo6|&S^V+d9Ooz8+Yxy z#s-CzAIN-HMVYqOTa@@~Q0%~{EH^g$c0QtTb%d8VvZF^ca3DKojjqGHAg7#PCYSJ9 zHG7`)z%!o&`WA;uUpvXl9X(Ip%E~Yw@msx~zzd^*bfE%B8vMR@e_g)hWPL$fE#FP; zGyfUGlzL^_-uvj3b#JX_NeI#L9o9wn_8ws#k+b|2V#oN|hJ16ffAB1mcP-rsy$r=6 z1MpYXLkj3+h`AhoUWNiJg2K~D5~1{~j(^nWcR}atTO#)vNnDZ(%Y1x8c;_qo>wrVx zbHr)s=ViEBMW8q3`ei7+B+q++A0q|Dxb*&@U{2bIv?mSJ`^CJv5WA4Wn`KO@K-GTs z+({*@2OWX0Vv}jSZI39FH|0*7M+mLnN8nW<0b}MVbQ1hgs105f;FSs&_lpNntq}Hz z4q5~VB2S3RVISDWM7Zu%AyE9Y{%B&vJ_q{mxTV=o)5zarkvE+fgItxvrtg|rCiUq=rleOdSnGOS+IB0E zKWehBgCq}eQ(DYW!O>Mb1u&)~R-<>W zyWab(RD0)Q0sd&>ym?!v#Qfw?(J2p&+6UuAsHYWeN#EVQP@nx(JP|aSofdd3FI&Wk zIRM6lwqsMx+ot};2WHG1th$%tL~Hq=m7j5mI#p_0^uj6o6JA-M5n~aQKQ7DlAOv}E zf@bJATSiA~2vR~2xKM2-8NzV5HUx232z%0sOyoiK=n1ZVA{Qu3*0vK;P!XgDUhC{n zua#NCmGmdNu(S@wosvyXjpM|c*{#SxpX?Ph5A%R0i5x^7KDJ91eJrGz?lv*_F zG24kGyn0IY-$F{4cJPd%`7S@rZV6F$|DeBq)DZAm;FBljLBM2pBqRkHLj2%C#J~^Y zY<-Ovis;wIOujU$Wa!>y2HXhw9XHeEuGKMQ?y8?j2V{3vd2qs;Ho6P#j%aEAlwOxe z+>Di=X_qavM`kzCL6;!;XIb=*kZT;O)^FM^oqUDpnV6Q#Nw62i;k{_I`CjBIVO%MA zhot!brKKqDqCxM(0m{xImiJ!hkYAO8)ybrS8=)~S;8Wfvd^(60F02JbFd1n>55qc_ z4lmdl`uJB=l1Cn?XEdt`Kd7X8k#|=c@qzcQJG$+JOkV^)0imOE)~Aa8Kl{3*(o z7&f?W>MXTJ-T<7X{xf-lRTwMFcso?8|oM zN{ZZS9kNNQfeqRjK2j`ZND`t4&s+s!$KA1+nGc6j&KNk%%g0$J5X{|iX@R|LWE7YTJi(N6Iim_l1|^~Fw4WqCr_p>*7|rX4bKKw|8v);1`V}x>sJxgCnXYZ zXg4dRCNm(SGnrFOYkVUmuARwX!wQp9sL}JiAZE>O5j2?B z*o~K1>U-vuYQIl<9esF1&n_XVPH&>yBl3&8{;==N+sS?+ZKlCRNc)%;;Fj-5wj%=g z5~g7V?+Jk=01-i;_aGpHutCGR59{t_tR?1Mt0)S1%s5zFK&FUpYB4=91T8yWOfzx& z;8Dv+jqNp9^H#91ctK#)Ht_M?Ft$Rz^6};94|{X6!8-rdRRmXuT+lbj6@HJK^reG$ z*I2)a^byPb3UvvvHO6haK~E%UC$5gQ=4KCt<%zp$|5*OM!LqsfZk&y*zL@Wt4U#w0bm z6*o<-}D;{+lu!a6H!||WZ zU^fO)R&EpOHMfawRm~iuz&$d$HC;M7#Dom%Hz6jM>xfM6tWvDC_9Mh0Hq0HM5HLrQ zdI`h5r;9i&EC9oG=V#4=21LC?eL=}7$VH*H--xA`LcroVaLT#KN3V~(j-&lu>!m#4 zf?f&#UdGaeCtH(vtPNlmPWsoqD&8?O9V!QLil?fqOFt76vPiNak8Y|alL>H}R9z+( zi`5@(e$#Z>?zO1CQ)63m+PBZA!qf}8uvOK}_SAec{D3XwvPSx&=bonSTidlxR=D-O z`-gDT5AOXOS`G5|xS%U^!QV=M;3=lL_yB)Pb{fgri-Z)552A#zSuXTNB3nFAueW*^ zqvePMPy3`iK->6uOo6GbxwGZ4$7=7zvHxUxJ#dwF4 zG6W|V8{BmyMJ=+f6~m&BA5t)lfe4r(kLBZsfRcXpSbO5VwNgoq*;SAUT#ehX_`$y- z0{@C0;>7u>guwwUDct>rm}_rYM9T>gVO`qlTo{!6_f;kj4pUj~$)L2twO~NUK+#RK zcjbzp;E#aztwpr|f*dQj=3Lmi%1oBrv0JlUi-={_2zKk648H09$1kj3e}}a=?bZwS zKm6r>!iv|9d^UX!TmN!D{lv9@)z&|e4s0MiFffA%z;-0~&RLu+3M~;)@DU6!-Pa?* z;=>7(POaBKOiBARogG9%yLQ?J%c`VFg|aZp*soTSo0Jq=fAdej@*h2fzx5OU=pk(V z6aUsbhkw)-f7KRm5U!LVNC+!!i$i96N&!~gyEFN#SLz0p@^V}CcU#$acQwqOfJ5dy z>&A#9#xGp^wiI~|#o(CsAunqDOci#s6Po*BJ$HuPS z=5>w<>KpqmXUpDVgPtCn@0C+}wfmQBm%e=VT57<(%jKnwCxPlr?2huDntv50 zCTi+=11kHz_)6H#?X4Qo;m!(=s^gH}$M+8zO)_wj`#rBS@2}^_3S(jPj*dFe&c6$~ z8|d@2>;b)x$rqM(F&&)ndJcw0He7$h62~@M)GS_)=w8ArEE?_XhfdoF936Qjwp3iX z%evz&Fckea;2dl|hcU@Q`}ugTTEuT2#k#5JyOHPjEQ!{aH*O9cTqPyI%ZD7I!M?V| z@+sL+z=81Cw&1@G+ufkiVl0>6a2R~bkFRb;pZg!(QC_IUZzfZnmacqSsN18&j*}hO z#yxqvcRGIPC_?o*7Th>^uBY*GQES2Jj0+$mMj`3w3ynOD^kS>FR=3;p9|r1zP-M#P zcP@S?d!-7P?rz7U%3p~lCEY%{_-*dfP=Ar02k%ReiJHtmSBX|bx|C9h8x#yPDUctn zRJlw=s-A+RJX zSXQb93*vFJSuznlFqGlxm?h(u1iUf}A;Sko;&d80tbV7yW|IdiI|3i4WAssM;ymZR zyuEI&Mw1~)xKP@RoP(|de`OY$5eZ`^!4UC7E`p}qmkwx+Ci@VTXG*cz(p|gmD>T8S z>vUL9Ueb+4E+;z}MU&G)YF`t@xe~hdtTU$Z>8IH-K0<6(Nl{ zcFDgG#1U0@-9aiNvR9;`6r{rNAb_4Y~aBXAjWNG_ko-6^0y=(d72WdAozT@u+sd+s90- z#+J>(qt@Gl>5jd)b?iRw`}q5ZX>IJq3%UkBLJH4Mzj?ODKjWs)iBpQ7Uy`u9&33Te zif_MyC`;>g=nhEO-Q9WhNlUj)yr^T3#jW?{ug~e>A9_{rdQqrH4uyLBxnH=4JqCEJ9V_|k#xXhx z;;BgzCGH~=rEn&yWa-5*$&?%4rt0zcexH6oi_S#-lN2kvr7vSyMN41bRe%($>4$qk zidCl_YH?w-XeGspBpJe&tw+%RtrROCuHz|0r<(53ET>qR$=;`bHSH(-IEB=y2~M#> zlBANmFQ-_^9#5r+X?nnMcqTw4IF%|(wt+``CQ$QnDosUG!ycEJAbpaw9S>z255&y` zn;%c3?`&!ms-C%eHaKn9sO-bTuVzA=AEz(1zfwWyw{EERIF)NXvap%di*t)(_xYnc;8MfKZE+==R~yO=d63^o^rMb4v^T^^=G@Vgfd-Vbt?K%ynY#Qc^K8 zz@jOtZFrk`vf)QJrvY!3<&F;qdq07h%}KZhHGpA7^ee+&1dc|liNffG zLhG^n#g!7+%JA^=a}+&KReS)QjM?ii)ZzJG_U@i@Er@@HI~DccdWFR+z)){Ks?j0 zVCFw8(f*&phnP0$1Fz0~VEvxqVX&@w=7RA!B0ACvUW>)Jn!KH7xvzR{qIeC450F4887epx;$;kCF?p8>ZEGti#ZwTN1~ zNU;DxfeZ#^4uHOG*8)tKTf{PFZD&9O9|*2kmDC15S^*8J?65Q$h*Zoy-MN?*y2c_Y zL9*ru+m1yB&4U&YBKWwv_13XX*048TiigsO(@@EU4m5z;e9 z^q<#Z89)BP!NQfB=&Y->5whtXjtOq7S(QKI`jZyR`@LxJuw$28kw5$A-!VC08X70P zJf_fqNn0@HD7y zJqRcf63TFy zusk18xLewO!#Lgt`4Ohu@het*z+z$#v(dPp20V0tG{Xp|&=%{8+C)qwKSIu8 z=^l9E@fR0#3Jb?P!cZAWk$;5j5Jq)|pp-((LwnOyzb?ySddf*n-Y36?C_ER$+-c4hRZl`rdO^Mo<548IN&m!A4uh4(|8bP zoNiw!7g%0;3T>6Lpc{y?E@^gQV3G0*I)KLUOG-@JLX62v<^2Cb09j|k;<2!6EaKg9 za%yTj-pcJ0Qh)AgL?8rnlgv%uOgNVJ|%o!Cm}`*WpmBeYe@vGAv@Vt-KtuqB{P zgyr7bXd3aRTc`LY-&@Q97G9S2sh5qvQ;zRN)OU|%#P0cO;BMhyZjlMrJty~Q_s39v zMxykDY>+|0#$9fWd=r#c+VSd)KVR9$oPs-lcgYy#~X#=Y;tOD(-z-FFI{@CqywLc+Qh@LXFTtU+l z=|6no@)}>iYSG9kpwuy0y;FL-%Eq4+$ak(Rsw3rJ&GI--6<%C+zKzLu?`0h-??pcJ z$CSlq)LbjNtfVb7HRG}EwK04ot}}9MpZ5m%JTVkYgZW6^H*wwjZa|)kl z=R3=dWVTw|xXkR#S3_pG<0Fiw`EvPB^`!I*xCfGRM{@Hny?SaHl!V6EdN+7We2pvc}0Os?`}9~aZOrFlXnyNuMmClS*-iR(c?qgo#VHV5TUl(7Qt+B9;GQk= z_I=n4<)RTcu4wzFp2Lw=&bKbA^Nc2hiVQd-Yx6NT2!-;7LyP zQa%+Ue0->W?;ODkj`&M+Uvx#WA(gBoADW3iHA1%i*(t$7mamNn*{ZYCA~mYx`0aUe zvlE<6EkIsDYl9j^ag?Q5c6O!-PKHZ6>H5b3c++4 z3vmE*L4k+)-#|ovkFvhA49@upv0+DZFQv!P+{?YP8aQXft>4N|A<O~9ne`N->C0lHI$XtXWx&g_;ilvJ!yuMg zNBnl?nYdYtfu?JFdwZ+VxJ_tBqV19D&yyn8KRJeg3+np4#cq_P;=a$N_@o^qs9i^rnt#*0=H*7w_VvgLSW=3pFEZp_~B~i zP*{Hrr#J->6#F2YmtuU_MIm#6!Q%6mkHb;zbRrPl4cYzjybumDOjk2{yodk8cUI|3 z<+99PqDIAPe%I}n=5#N`*o6D&FOdt%CwLCZ$WxV>A4meiK@Dc$*Zmx@9JO7~AFK}*5hn^J<<7bg4ndaIK)0?K@0ZvpCEL%eInREw)S_7R-p zVfz~N=K5->fp*y_^&+cSB8d5W(qKz@+t&)+A2YB{zC7Z&cMMGB_TKRq-fP%^vzU{p z_^ouTC*5kYZ?UV>vz#dXPRIATB!j-DYgsn@CP8AIRZ$8_x*Fv*t^rs*w@vKo&jFK3 zBa}mdR7)NIToZ{b6Ns+KDMHDSC;EWOXQF?yKUDB$1UHHcs;9wa-$&{}z|nQ$v>E{| z5+QrsKvR@R!<<>M@NNb~F2`2VAW9j09$W>rvkDZ1$*~V`=1QOSO4eOEH5e?&BPB1c z262faxOu`LmxF-lB0~`wErs(rC)?K=r$%`An#uv=pi9R%n58KwoOb{NAr@l=3$^sv z4F0zFWtuVOM}g&uu{DeDmGshQEio1yBEw=&z8D2jQGEZzp5Tagcqmevq`d_?&2}z3 zIXK#!*mth$fZ35x2QA01oG3Scgxp3tFr1P6f%bV4wl$G?c6O~(X8QTe2_A2IcXHr~ z_a;GZvS8r4-(;cXT3oOg&|^Me9fB7L&@BBEM(m#~l2wx9O1-d_vQCM{RsG)t9N)sh!%bOS9h=6!HCkoW7 z940u7*}_lrrgy2a7Ctyioq%&=$Mx}OJetXOCv2s=S|Zhse|uM^ByFZ}Fx1Sr?mJJPNe;nBvdHd@evAX9H-X+zw-4+Fe13iI~ zFelWn2?&R+**7Ux52~SU8GlQGr+@Ym!byvj@71zG(y?L7izNJjuIADT{vA2VtOW=P z>8Gb|DRXBAE!~W9;j(&G;NYiQbGWqLqsXYU)NCp#vNOYB=$$CiyXMxtbFW-#*qzSD zmEzMMTl$N`Rwu)YM7I6Ak2KO{@|44T+&^jX_Ga-V zNJ-4Fsj-##B3s7~MK~|A??+N}Ee<7naW4+)fYoyV;w}&K?l;G#B1kz_xyU*oRt^c* zpWo%Ksb+^g64Q?y%30WcuDnzLd4$5+d#CvR7W3$<>2hA${zv1C+svEFZk-P2IOn{} zy&%2GSXPa}X*iPaqAXkVZj0s>LyX8uQpA~N_B8Hs8{Yn?YJz+j~fa@=ff$j58S z>(>RWV(-LLUKl4_47_6^&W>;+oE^Oh1}nQ2*z1AwhH{9S8`4jF zv$vdNRBMgE%1eCmQSY{g+Hs@ICp~O*Icn}@RxfiE^SmDV&+F9U{_-wi0yYLkm;hojF6w!aM(UKuS@}#`RQHHh`1k`>_`zUAE@v}lBE*R z`Ekt2M7ck-VaDZFZ5Y$DDknJIDhg^ltrg^==RI%cbrRxAK|f*y?FeR zp|deqfbj)in7z@{Z01nigt%mj=f-8{7frqhm^O!Auyb5!yJgmxqDHu7=>ApC zV@j8*K8+O9%1nK6$+LS^%8T#xMBBmY?dv*L6xmeGorZCFl+8?UPx*8Y{Zld=Z&mjP zdWrb5#m9CYZN5(%B_764j)niq3r|Ky2La`G_SxNLzcS!Mp&|Rmm&WwU8{dZiL)u$7 zMAfx@+d~X8Lk-GLzop{(r6zl96P4wNx z(hME%xYI|mc*;9;5)Yzp&_y?WM;*37Otpp*ZxE+>aT*V;%@bL45y+=vGTY1&R@MkY zzw1h?ViNmv^4Bc1^xOad`Xv*T6LeXa471rI%ZxH$UMR%m6k$(@6&fjhk{3=_ZWSZD z=&4JB+4@)|uBd0g(j_s@nkDj<13gj?%OiZR)F+-QuPh%$dMndLzro}!E^+O~S`f+t z+O3iY>{~}6rWPymx^6Gh5nOJK63|3wo3HtckLcfP5@U)lbnKJp zDh=$DO(MB0B}FPX$gbz(4*-~ppON-pOU1N70xhcNFY!EYxeVXT8FLM?Vzk`0YXHRbMB? zWyjqm>xoD_rdh4c6**tfu!NA;9LoUP*ZYCg9XFsP#^7u?;O8|QL8xqN!$Iu*c_m~Y>BFA)uA zs-_C|Ok5oP93;UtLA1NIpWcrveA3ReS8@aIL8vE#)cpr~ao6Xx z`f2+$XnKd2Bl^v*kD+Q(3AdFN8m1aRfZ!`xpXavadK1N+Twh%eF<}<6F?JbuduAUH zGsy#dpq87;Nt`JV{rc{=lW~hgEgkKjms9KSI5d8Jq(B7PnRX;xJvQ=r=X}@5@{Y!B z?_)DT`FXQQjS9`B*PbNo?*dpuFsybeb9x@-SO4dHeTji@Yeb-t?Y~n$n(Gug~o3P)LOL+hxR0903F7_XXdi=AJ ze+(u3wRirvUxK=3Y^d*GI=}zx4*AKIUjLIT&^vFZQkBqq2(T0tf7w*PwI7f+_Y3<> zu5uNABEw_Wm*qG~3TO&~l{#rJuwxo`lFFykK>#Lgy;&Rd0R8t13}<8(s9+2Fbe00Y zJo?Mf)+Sp?WTG-i9(p4gDs8;j8^*`l1aAE@lP9`#$=88UBH}&Kjk9_4!9`i`x=@1- z`pxKGPW6rDpw_!5a7_$Bd4R*$RYP73JLZKA^|D8uKGr+q2I}RVJ9GA8S{!d&_B|FG z$w+bUbbar6zdcQE*Jar0d-`lOCHCg8FvuT2PhkLjv?u?$WBm4{q{FNJ9*g*2#%45j zYV!ZfVs*Y6{rd!p3WEfkO#J6~{PuY1KclSE3_rEWf3u^1#Aa~aIR9Jz7^QdpU*wM! zQRqTcJLPwFG}WJf_))r|pX2eX95Ifc*`6i+zObTEnY_n zVIi|K`;czj4Ttm&GzmH-j#Thl`yrHJmDaFyjwje z3MM?gWF6){Dmux&|K7HO)apPA_^9#C!!^h9lgg45#X#?!IbWRs8B#wC!9P;?e-HpI z{;A};a3j$C{Yl55p0w1@t5F-^#?1ehJ|FS(|K)tvKHNz2|L~;kC43!z_VI7)wfybT zGTFdWYH^zE3H_0=K4Y5w^Ira!pa``v?_J&d<23(sOezNTUkwA0k6JkVs9B9O)WU)3 z{mS8(ywv=e^H=Q_3ncv&yzTS<6&W`h@?}vEJ!buDMDFJi4*-|~bpKj`xJQ4jK(C{m z2Z0!L_)gfW4AKE)%rZ<~&YM!vP|k=xp{aslB$ImfErd(aNHRC&j}^GBq={}z*(VIM z6wkg7M1Px>P&%0-7t2B0onWn2qL`uZOhka=O@*R8s$by_Yp*tLM1j!AOcsJH@rt=x zG>w^$+8eFs|J|?Pewim9B=I;(n|(7M5qMlB8n^2fO$7@ zsoYLKAIzV-paFc~)WI-q&g(>OC|n$RtNCFI=SpyKr46OwN)x2^;K&GX0Z0Kk(1#0YPNsw?Xds!?_C_$PSxWVjTCTAvBCG>@@goiSqcZq76 z^6!!~El^Z!U60{+iMj#vH(d*(BxKSGqIkg67Rlbr0Gn#wk<7v<$$?CdV(abL$~EEt z95tu&vCyhQs)aJ?$<;|SJ(0@`AxkqXM-*kqL;RA!lCW3`oN+6sEgCF<9MQ?nk`MVEr}^EIUdxNZ-!CZeNBYx z#D+#t>C}V68g=vn_d#WCA0dW5PanQsCeHx6ddH_eDo>i{Y;=)hJj0ABQJ;r7_;8(B z3Z*!*l`8c!sye@J|5Q_seR*~N#xuvRnb|EcXIy+>T_3h3@koE3D2+gux}}=H&^7O~ zqgfr-&d+nYo?L?ShGEJl^A;rrCyQ3~&jjDVo|7}^3#J@!b>GFIz1;#kMPW=<{chlU zHA^|ZQy-&fe%m+=l%Cp8TJVmB$$P-HKq9rtbm z4ykO!l()ZcGh4$)gLan2>6m*T8VPQneeAkH(9wQ&pTku7)T^jr?%;Sj_Q6D?M-qJ|35|s|!ImQUeGKq}s%x?0+r3csF;jG6_dzBL-soXrbHRkPoXFyDBiaf6*nQzTYo^U$FR{H( z1!Uj97?Bit)^n^V)5Pm<2r3Uxs5kK$kQ5dxPY4M@BC3mq~)Wd@_`d#56q7QkeqO-u@|??t3XM^*K+3JIpa&$E@J%F`L+;Jb?*o zM2bm#do9^l-)U|GiOOk?p?A!vQAfbBAoPiK8i)jF_fg) zqV|NYVEKbo9zs>Av0OVVQGCvMm!Xy6f$YO0!zC9gn>pdR*(rf2U*APF9df$A< zlauBSyblgx2YTydDJ|X7)y@g+b&Z0-^!EMRFFe|&6V;kaImGtenR& zR9yMAlBnDgNr)wE!^>pgA>l5C_(=Ve&-%gsl00TAtH)z(b!7bgG z_iF?3#?~d)puv&Q~C!dP*um)d`naxH3cPdSImb@oC zJ@~TU9GZxHYkdX3s?Ysqw=FvD%|JSBay`*jsE16r|-M72S z-xj9hllc?)tRSk7L}p4J3M8mU?`zgyys0Lu6VQ3KDSzi{HJ>$*bIs0@mil6@%fhu5 zXM6_{)jBa4iYJV^a2BWA;zV}r5Nv~ z`pd%*IQ1N#GmzacPE@->WSYzHtnh{*M3wy6MES9B+s!O9ExzxQQvN+Zvvb2+)rE4rXc6C!>(ERz*?eK)T4!STCCwKH_Zu7O7oP+SU23GrVOh5ohY_-tpAanAJ@zX zVgj8Bh>@73&0@{9pjlb57u-PAZm+AOXES_0dxNf9CjqLH@FPAf7^|6-pd0tRSssg% zQVB%9*-bCZT_n~0{;pe1lZ~OQjG!vP?OE_7k3G6GK@$M;>lzr$4R$)lkyl~YU4w$V z1Jt|-NV=an6fr^@{5H8m(0Tmi)(G&iY0{7EY{SIuv@L8;^(nOA^G#-cvSB=0u5UHX z!Ksj0DM)0W6%a-8;s$DY;Xti|Pmq9gV;s;mH<=z1vpE-#zD5wP?UQu_kOB2}g!#Zw zkKQRHBo)9vi?0U&Sekf+kUimj?eKUz?Dni%qJ@**wl!|pQ&o@15znVmcAmywIuX9Z*!`!yl`PHSmFsJ0an z(`A#=Gd0GmB?e1~`0k+QoD|myfRJ-f(B5ISpxbH&8clTUI6>0&F_M zfpvrN+2YPyIFg0XEL(#0;Fy=!fDkn+$Yu(rl^2d2oN+F|)88WOwPx7iP>emf%d;U! zfE<{79n!1<#_q-!oCVWO;e%>#R@H)V%1vbF}_Ho{p zsouqNKKeQ+M7_@?A;K!v^zK3`H*Y%s>qIc2!Dnq>5*{6a4 zI=e-HA3#GU>@2fqUx-MRY9W0A4L1?b=t;}$GD$bGkizRB^s|b?a5fDVibc0{oz^kW z*KsQcnfahSsilm3dtFA_i%sFNm({D2?e&#xUq0KdEc2+0d<^9D37cZb8gi-=@Vqrq z^_0A8AqPN}bAvGcdl_VaJr^6y_~qPU+afhs*jo!LFQhC5KRpm`okvWS8oZD~Ba-TW zo<~ZRPa={}13zD})QepwA+fb7K=3YZE@1YXZj+^ zFlG5Iikr`hh%BuYnu!zfM-hO#fpoC1svshy5*%l z<>dL-s0f7Xn#Z<`^dM8PuI|QyCI48AY zbQZ-699s#2k>p4 z49>-lC=~*z!F%yg2*$kC7N!QH(<}CqkH-{U2gBBg-z=7wfh*LhD<1nc zDsgzy?37|S;fNHwY7|$c zz}PC{FW|+mBdV6$N@mNeJak)vs9OY!oovBT4FZo`PYIePgEL@>Y+eocy+Ena;2bZX zJS%aZ3BV3CugV9u5>+g@h7 z7WT}RnTXyMF#A-U<%>1^tu|n!O!Ade!&iW;z0&TzuKzJjxpqf?b7a9+_DU^TEO`|l5Fia&ff?T{r)C_jZS9lg zS*_09QKCiA1O?t2d9Fbjbu-OEzr;rTY;XZ*$d6_ySac|~BPhJ1J?z?!VB;RK;J2JM zg{S9~{n+{e?4hBuGV)|wPc>+|vz59rXht+`yZP1|@#E9o_uH>TAmJIcwu`RG+m%au zFW4$uZY_^+KJDe8X^G*?!u>?nsgvEcO#04SbTTFP<9et*XND23)qJE|&MZ7nYl!|< zFrL-8aEpaz*!bkw_)6u_YRCAR=){Kp#9O6_o#mlck9w8GLhbK4A1liTiRmyYb8~Ku zoZjlbs4OfLRmJnkhg?)J>*mGVm{Tm~9ct3Ve|y=moyQ@q0)9;roliuY&tW4| zMv>v7O<^7ffJToMw2qaQWm$MGEbEe}of}IdmgGfuN5_Z9Hc*awdvx70* ztS`cCh!tYC^_1!9)ArKHh_~}mm-7QR7W}vtS}7I=JWVL=J?U@?gxP9?EavC>hO_Z% z3&j?rb>}L!G;xQX^UHv-YdZ{l3C6(5Xxvy|yZ!RWear#gSCEvZ+@zPI-m|6EX)PfB zv$@pJo|X3Hw@b_Mvu|+f42eAn9*z>Pvw?=dmCre_GKXwV7Aq@Nehfq z!$}BV**?8r1YZ0U^(wdH)t9VSdXbAD6Dh83xJ7wQ10G;>bf}}M24kI|olD*vf;q6* z2&x5Ih#+*iy=#@`7n;`cbw{~6Mk)P9DPl%DqGtH=#J8Kx@Wb24f|yQ-!(YuJ$A)i(+8wtw^gq`~n{BiT!^?^^ft*eLbS&dIB+f31x?^4= zT7s#!w#eBYo^e!h?X-4@T*L9hLC*!I?!dvhK;z~0%IbBxuJyLD_3973X=0BUbs(?3 z8j`$l%vC~!(ssnVfiklo^huda$S$8DVt8d*Pb@tq#<`6%BX7qfQ^kiupXtfuYDT!( zjhIw`)4S*1I0}$;J;MQW@A%ne%WWE~tgH_^l^@c{J|5ow_*(SiiQ&gH{Ew31t2YRz z!6rC42NruAA)J(lqPzf2;gx$G!9gpH%Ay@|ONRyC=1f&4p2|dWSm7m_whbW}(lT$n z?SmXy#sWtNDZM|t%6?{Z{LKF1v-QYl?(5IE*K?zsR2$xdIhTW3M0ciNby>WQaqAgz zo&G*{TQH-tYD74^SZr{t*kJMD>M_^FHfa4L>)@eE$@yUyB{+SjL(UuV8rCkn+R zN@x!6g8Du4&U89lSn)DrR?pCM-$;)SDOHhb5S*pQlIuQ7kz0va8%Ey9IH59uBpx@r z`k#2dxbR-RDF1k2P4I1B_?zRaiyB8?=>1268|1*YbM(b?m)%TYxp)$;J73QsZot_M zv>6Vuu-HcxiH~$&-^`6<`U*mub;-JP>bzXMUcFqtzFfI^<-l^5^XMGE#qqc_r`{R@ z5ho@UuXLK3YZ$IPmG32I@t_UJ6zBTXc)ttq+NK*82*e}%?yj=l9gIUu)^R$y))|V$ zsnD0Ix+xPwdjt9W&8JnEUZJ2&)b7VsG5;&9+^51vWMgQIpf=H=_}rR+Q?J|l)(LAP zIT(Hyhu-|#5Ax`;?uY0imD-VXOKBQx(!D)QAiz_++Pwm;T6tZxBNT2C9iT?HvV>l! zDgMxq5D*vW4ku~^#M{xQ)@o=0h-w$nyGQacn^kEatYA-V4#i&|;?cG+4?oHT6*izN zyTj4|_S%g$tPuAMfbM)A9o*GiT+8a3`CQGrM#*jr_k$hcdn`GFn-5P((NpR9~-{4NFEHyv7s=4Z_upxVTEM~aa7OSrI_ z-}#Ox>H9ba1nDb9VWp?NT@|a5sY2s7GpR|&{JnQfoU^W<-1G4UzCM6gI(ce<@>wk zqbD?Lyj5p3yoj1Eg*9Ha3yIO|!cm_wM=0#uVLdL>VXO3%&+SbnxX<^xFkGk%B@u$_ zu&yKtge=`5{Vw$0byWQ_E|%0^C=GT$pjc(CP1Z9cQOn2|c%o$z#OyKWFLzv8XhiL&SB0Pj8<~#VesbD zm%#Js90rY@6X}MJWQCTY?hW)#VQ$BI76gXc>v)uY^Xp%jLQ~f)iLWd#T;J#@|a@)0yu^7vlw&*>MvT-uWk=NOn{FL)Im#G^1i|9i-n9;aqWu{kx zn^a5}J>+crZ%(CmNP{(;slSo?Yj2*C-v&T$D0xyPeof{gN<|+vS_I()csLcfJ{;%U zdFm>h^Y#0~lH>2m&?-4JJbs);q4)d%0s-N5G|hMQYrYQhfleC7A;L+c#f(~mE&S5&KV_S=jFHmNj( z>((FN4SX0h6vwjM+>IEdZ)O4p_*gt0=CYVAV=5fyHG`oylGGy7y5+#uobs4(B!Ia# zP$mVWO(gfGL=XVK#-(6d?QgK;4vVh!Wx6#FdTiB8Xi-T^Jc``{tMB|I#^H;TCuav% z;|bT_3KbeQk*?K(JUpK?y~oec;!z4=4s=A^u-?GS5|WP1s$twwP2QQp6zKt4%h+G! zBQ^Sn8oz?zC%l_6Sout$rFd}LO$|lZjY`^9%xL$_g7nWqJYpwtvHr`%&{GOI3H&Lf z0}-uEa4%1(&OqErtx^shrM#SGe0)N%nKB20BDoBxv4LR@mehVp6#x8b0WLGgBWs1n zHm@Rv8Gz~<$J{#j!z?&Yz<~N-hR-H-wADkJF`Dwdyw#9kil>|PV@*wW$kc;LgDlvK z*hj3?T+?4&S0V;7pNlG{zlu-$p3LaU_AuCLibeG}oG>r{Az>piZ_O5VGzoA>$oZ3r zJp;wf8nRo@$au}#_busCfGUBX>vOO9tt1HBCIdM5>8bp~a5B|q_j{V~1LrIkjJ$Q$H+vpAh#`mDZ|R)hSolv|DTb+s}tkKR12 zg7A_)hP-qkQiZJ4os}%4rh~<~g)Nw$s%R1zq_>+~p7I-*bC|TTwmWQb zP+EsOK0((bj81NcGgnGY)OS233Vvo4*Q<{OD>`T?Bq7q)BJy*?(V{4Wrq}g5VhOOR zkrY8i*ELCY`5>UD=7Aa5^6rb4smWt~WPFmNOzHgaG_OLAp0(Zp>5_Qb&! zHI=bJOL9#cx4(T=R2_mnfCz-BfzKe#_xT}v!G)xXUHHDQrlIfc=m7#Qhk#`m{dHZd zwA~gGu5D*ht*1S|7$a`)BV#X;{GMXCBDwo3HW5n#CV_incb(=g?@dHv{;ZNDdVn?y z(D1;53!oDDflcXipxdsbVv{s=yc2;M8+2#d;{8kE&*swcQg@zH!Yx!1oYhl${Mj5o z!T{VcxJz>}XYPoVR5RJ-`MzeLjOPZ{8l|yMaZkHR7-zbta22P8@#6{Vl|m$wLsHL> z1c9o1o#INR9rH`6rTB98ccG66x5!}7{)zy|fevvnapQ+u@({^Tiy*A~UC{R@W2diHJY|D#f-~ z0`W!xadfWIMAD!_kl77t>kxMB$V}@Svgt4t@dT!!q)rC$PTn3OsUBjDp4jfD=-u?Y zpC|=D1uZ7Y2A@F!7x|6eprxhqv9z8``2=p$aIse4I3l`sosfqY%)H*fa@@dLNUUNj z9tI$vq9psuUUAE;qRxhsONm(%{pB5!m%9v-J5-YL5uH&g$>#g{*EYQ@w&|Q-*?ZB> z1l>4ECd&vzoQtU>^6nnL%yE%~b+Cvx6ia-6d7ngzJUt4nR-)Wls^U`;bwZ!Tbh2zF z)$P8%`gqPeW2l>ngmP4cG3XAWHqD#2_m#KA?Zr&rz+O$aUM;tN?aGpe)AzzAZ%>_P z3t>tdvcKd$?B_d{=KJ1nLNcIA)gLk>QYpehJ5s145*z1KW^tTd8OUkM)Tb)ZXUAVG zJ|ja0?sNDqLmrqHg&M{`i*ndcD%#+bFK2Ml?GbZsW{e-)_7VF~&c&Z85jKeqpbXbG zm44h;68?!%f{O7mrkn;zVSs2MR7cKVVJOUPDBNxcp)nMpA9t-waz~8~!;L>Dh6EP# zU9Pm3E!K>AH+?XnLzc}nKS^Ua`IsH$n@q{9eu5eCT8NM*KAMM`j~)??SRYOrVb-Gx zPdbtx{G3dz%VNRAVh+C9*u(C)HDJ%*XIrS?6r~`i+Bc&Bk0z0KZ(u`;iaWZL`!J0{ z@`n4lLD|bRJQAR1Hj4a2@pAd$RYVfON(v>xgJP5vo%$7Ubk2a!C84IJ-Aqc|{9`W; z8Ka(tQ*(yIb+CDmz+9imwV z*5w{wWPA(d2niy3X)#`4QT(0_XlwzLNs&4X=J^=-;yTsz#VO;&EO=sEWP*TtFxo1F zw{*kB<W=eQuNA0~=rG&i5t`xZzC+DsMSiwWw{#G^Bhs)ArRRhn}#)2rgyMkn0 z?V?7t)8<~2jJAZZQ8YUgQKz$ry$)l0%mtGE>(gnoO-^;I4LUP2O7IJ4n(;5al~FhlrR87LXv50vZiCma5Unz z!efmf?WwO|fca=*DncNn7I;9DNc1HPe<4^G0y#}Y2U;~%x8NsYT(u?+ZdLhj4nSk8xkFH)QuYok!1#plucIP%cCb)Wfu}5l~sHE zVcJCopdR%F0&zODZ(;06I2cn9=K{z$8mT5k11b&kZ=u|ogv#ksLa~R79xsuYEj79? zHJOVC0jN>mq>z^8GxXGy`HX|Ls`r63MJhUKPUt8NakVGI^ z^>Dd1b+M`9XqQXHoL=8Xu8LHr&*QI!U{^#Kl#M7XiiNwp#bzWTX`mp%5MJ4Hk65UZ z$4+ZObaQPj8e)TrXVzr-#}OaiV~4!a-v3(aOv~{~diCTT??KhfVn6nmx7A@sHKRpF z8}BRE-mPwQ>Ys)PK@_>tFxJpLxXwau9WonyC<1-{8ov6@FnY-7lfW8aLKb1X3Z7ky zl|bS6{v^|&hLkc;Skg%Jx_?X+VlDg|3iYq~OQvC60==|YJKj~h6SwME@A@baLVZiZ0N>_TD?Jkxg*LU~H$De-~&HjO8 zxdf=Dfi0+oRy!}houNY5{}5#4YIxF?qO74)BoBYeYJQB#naF_*QDbss5xwhS(4T0E zA3#GCMPMW1R@3eeGzAK1$p3$hnATgFn!Iyj*9R2WakkzLJvH8ng~?~`u>?_fuvB0LZSeS4_S! zyjMbs4&E=t^SKyJFDx$KFR#QhXA{qEy8fA6hz! z#??%@KPUoGi!JEnc1Jzftf&z7H?C0>&`?$>{w0wX$~aD~ItJ;X@I2({qw>G?d1x_T z;qx%tgIkUx6e$anW;a^LK9BJ~;_Q*+oU8mYahTu7H*EU-Y4xy#WTxvsLfBki|Hlxv zV03)-`;#T7LA>k~7iwR{CHI^6ELNVLK7D^WM}N(AwiZn8aJC-KTK)eogl)Mo%=1x< z1MofW2>%5m>i}zwsARK}@ubx#&YtV>%olsbuk(zCSdsyj{yMN6dg{x`@=Iil!iFyucJjc#QX#eZTw3aT(!TK*_V@Y^Y5)O`KVg4Cq1 zKr5t)vH7LMDzbSU-~7=a*bjpMQy?@Wy4|uuM)mt0i*D<)QHrRk!3_8JfjXpDimBfk{&yN*ZqJ|}1^HchYgs&We58%?O{LT=t4>>rwiXCWJm0@I0Q#$YB;` zC`SQmS;NKfkGHaa0&4FJ%l`_R$=KcA-$iMB{}<-!@`XG8Z9fZAliaqdqK6ypO8bYa$Y`K^0`v!H4#v z2oaf%<5}B}Kd>GjyS|_3(Z*eI;5c<-{#B5;cMpFQSjcFpevOLxJA zF3XOO*u>w`b%mUUIKQW$-KF&l8ZuuabcvgcM=w)63vjpqUQC6?|J=QLm{4M(nIQ)h(hyrOfJR3JZ8(9AI$nNQ%`_vl5If#>m~Nh4Hq=ekz1BgH1$!VjiAqvIDg5~_FlK5Lp6no~|dFuON^WTC56J_I6 zvk9OkE&PvSDb;hXO){ObrUjlP1W{agr0M-W)t!mzglhmg|M6&V=>7B2{$b8?&P$F# z1vC1vjSEqaR$W0U_qlmb{Ou=T4Yqms~%a4NrYO4EhrOf9QUyLi~*Vx2868?hM^bMYIyNN-$1}so9c;kQ`)`5;p zr#gSn47vH8L|fwUZV-meW0I9wKH1h6GR+M|PoW=rJ94N8Mei|=mA&$|R5GN!{rSV% z%?BF9KUV;5A`}nWbOi zR+jwDc+4JQQWcE4=lL)bIw_hbCk?L+vo{(WEzCvCG1*KuY18M!9EhYA;jw}o>@vtE zO-O<5?;-mPloX->@cbXI9mC+izV=^`(0`;%%;nUGWm_}lr*qi?;{_GUep%!REpUEv zB*h)U8W9a;3dIi#ii0_Rk{B*QGZ8=JZd&~Tw0cK3#mmip#wP6Ll@;GM32-*w?s4|` zB7xhFtPy_!L?b2E^(SQ$<2$rl@PtGArUwGX|0rqf_O zRq(2qu7#3*(W#2>zo$&t;33zCq_Wn6-QpY=dU%EH-x*Q@^nq8pEu9x*Tx4aw*Rr5K z^yc9EtTsR`sjZ9i0v2z6B^-Hl|-H_r+4E(1;p3-^0cf(uxC zEv;lI1?6_4`A+1@6jL`WER@}z*=)wC#JG&?RRVe0IZ@kBTUnyB zd9YdhF4I4^A1=ve!;1Ij3xe8(QmYP2#^eCqCes#;+v#jtdHM4Xn+baEWfyU_62>91 z?4c0-jliOACZag!%BuEHRB;^y9^R(Ef7nw{!~3QGT83D*|HCp2WMcf20lN@aD657p zTlXV70pLm>nEwSgW9CEqKgDBlL)6AXe>n!H5{Fgtv}<*7LPdVKKms;cil5oKy@#pd zUkc!cO;#@k`GK(LgtU#<(ZYx^4DD2$p9~NXOlK)ARG0;&(r6j_P%;_@<=}*}2wi;W znL<}3P#M2yu$`=t9$ZmsZ<<$0<=$u-{|7L0D8aYmhFXnF_-z3Or|>P|0WSGUM;2e? zIc#S!?BW{y%2`3Oo}@mZCKbli9=J9anF;l`3BC|5Vf-FuWd8jMK(s?E@dB6I5RQGK zxdy=a)1moidWQ`uMsYcn8w#B;GYn^X*l7GeTuU^)aHMHYP?-LvV~Q=nC9W_;=@_>g z5s$*BzJp0WY=!t}q9WDe4;=QGV`Pbr*Hc74%WlV9XR$MRS)*uV8APGh8YvFxWm#E* zF$fiRh39ooAZl5=$(dA*>_mA^8)0n9k%nx{5+B_)%=5Rei;}4u_R3;{&MC0LD(&n zk8r?(QcUju&|VTIBT$KLWi=Y-jfUX_OO}{8EV+fL`hSN-*=)++q(83tfgj=QaW_Qa zNA&phr0Q{B$CKW(sQP)jmh9 zbd2AjrJ#b^c1Tz8SD51JD~Bz|0A~zUNnA^jy;rlp|@2LzoZ*SOi8-}Tz@GBW&a9G{K713qi50r~q$ zADw)$42w1Vw~PrY{^oJ>S`d>w+WH?$vTH^y6tC`|H)Z@uL)1-Ko5AnK0t3YDb`18D zXxyYJ22b`YHL$l3mJWnfg08R|ad_)E9l=M6+7MY!ELEPVXj;Du(=bGAJh*EEGEFv& z!DdnB3_Z_H#L1I?V%jX!|3r$~qPbX>P)MUV%}cX%(+?vmjWt9{TtiXD>T1VQ+413A zG0fm9ZOxs3;=BljE3+x{jyEjdE6)63j-Z&u*bmN+5n0D9{&7=Q7#`fOs2$Mxb4lK$ zjj+}BRM23PiH=Dv3xBb=lO^9TAzb++K!&8U7JXsr03g+R@w#Eaq@6f~H?+Y{^3?~0 zSrURCtxWM!wFWEe`S?OxnfDQ#j*`yh;l{sT1LINNBr^aC9QvC?7>gPDFIYFKFSC{V z$3E;t|nvWV0h*{2A96Vv80MqRcfl#gVW({OQ(T(7rV*vIq)UQ=XBk8~fAld+*Q!}f(!Kr( z$NTg6#iI-$SRf2OJfjEp7vL@ur=G7rsBZ*cxp<8l2L=`3EPiWj{S3H^mlSGV^gQce ziJ-(-iZ_@4LqLQ715q*LX*XVrIl=MUi@66zPu}}Yr0TX<9$;2HS-qXy{?j!7;~FU1 zv%B5HDgP_&$^LTnw*OD)Iir2m4{_Q*WmW@1IDK2q`@m*=v{MQ z4|IL=$-vMBtd-#MXM@9%U+FdJ1M!^0Ga^FR?{>Qp{MMHdf^!kowWt830_12Tus@Z~ zhG0NSHet7QnY!a|pancmu#gr)CP^pFulU%5KvM|YXdsIuokS~fQaT>Lg$L336DDz6 zFbS(7EdAFta3`A|yvz89rzBA0l^1rRr&XQ?>Chk7z#Hsg#de0FThv9t78hBLG5Fl9 ziUop9I%V2fax_|u&h#Z-?u&PV%)~3f{mfDB|15e;Ex?y*(rVfMQJi^9YYkO!r*?nFkBQfGXI@eKP3}C%HChD0Ma+ zjH2f8+oFhHmy2V*k;$Ki3Lr*Pk)i^Kd?uU$cW-QuA?iyW=G^zjUz0y(oy?bw#(x~) zhU)D-ED$8+n0!2r(#P4nRj7R{UW3&`MzZv^VxiV@u$XJKu}Y}|Yn?1n5%~eu{`l?w zZ}MA;gNK1((O_j75+0S3$eVnjhe90Y{Yi{^*<%WY}BHSxzCF(adXgwPbW@~po zB;_XA?JczcS?9|s^D2f>`na37RU#yo`Vu&01KU1#^JaiKR3CQwEIES>viuy7j|~pi zUbbJG3p_IheA=yuC2F~k0xa@1%9XcD=M@K>t{)JLIiS|i`6cU`|2pn(tpun~5e?Hw z(2w3;ATj>ds}LHOHwr8m=F{upI+qx6;*{|}dVA=_aa@?BY{)3C*;17V!EGT(491&+ zpGSD&Xo+oX(>OU6d4@OzUF;_bD)>;-L=j$808zV*Ts;}vXYd!7#LzxbXgkfSxNJM! z%3*lhPoqPAQ4AezGRL?X+blLym+mqfz0I3gCkb$B;?N11~{ zD&EGOO(H|LjXcl6e80>qE5^nq*)4lNrLrPGsfcw)4yfMdW0|$aRIvOJ{OSuLf0ytff1_SBy5oWW!rAT}dkmJ1|CK%)O~S z8?Fzq1meY}UXE!4uF|LeA}V`tBJLx%Et)@E9F*DOd^>FLEf*RrFdr4z=f8Y;58*fG z2RZP)q)YwO>$|T~&bo)=(F#1TBxTh|`o#4a9nG#&BKYA1^Cyg_hV$=0X|KtbQ4~#2 zqks?0UHPxnwQ?k;!fGrQc>}J~)*DRq&yOq>i6`3Jk@pC<48HRX73WWrA6^c5ofX_P zsU1XK9Lms_7a(f{fzMChFg*qxrYb$$f*B@36f#6iK5L#;oe5MKQJUpd`bc--=>{;(q1`4AHDy{rqLg%Ww~_n7^vl>`RY1qNbv3fzRJlGY#na{E*u}oh6aVfu9r_9RGze<0Dw@y@}u5SP06Au)MhrQO#N{-bU(f|-$wPhC@!W&_Nk zuyR=3C-sN{A}uWOX56gAJDk%EJdURg`jb-Zx0PNibKh$)^}qD-aGKS(9dezMK+oly zH*;ijUr>~RpDa>MRjP~_)ju z^gy6;q0VwN-=LzY9Ce5AZ;C)Q_vJk>hq09c<7f2S;Xjz&6wI7~ValZMeCumB3$d{p z=)>ojGE!psY+2-N>UVNCv7(5CsCG-I(C_&h8mQGsa)J5qqI%n!ejty3{%!lw+@Bj@ z`m1{WB|w-CDee68RCiNs3HD_R)!bjbB>&Oe|Epj5@kEPz>k;6B`Q55~Gp1asFLrcq zPJozv&sxx;yI`(LBW^a@mLmYdhpgRK2C4`KS zR>t0po_rm?8KY5V^$PHSfwb_BXjjn_)Q}{?lew%U| zz>D=5nkYCyqG4{-be_oNFz{F=6PP5=lm#j~LBdYFyeK3zH`sS`W9a2}^VEwFyZQb0 zCMvnXG3-5n1YVoHqM$u*vLAN{_D2y!ZaaWbKO2+)q3iLZh%#MW4%H`r{B5&2sCpnC zf%@C_*R?j2N`ynAhK`@mpV+&Uvu=_|cRN0gxuIO54j+P+sROjhKr_aZ6&DX`lg6QFm#7>H=@!G%+TFPcQ;6bz|ajtH`0xC8#G8L-5?++pr|w` zGVh3o2fSvF8y!Yt_@M)h) zGLX04lhXI_w+S?5>S!(tru{0=go@VbrC@n?U`^thKUaN$alzTA&iPHGTt+>${o^rX_`NcNK7%BQkGfXtLc)=KHD z=1t@B|IsZ-tGEqMRzSGbOea(q!-llO3%pRT*)NWe!LLd|#WrkI>}ac9DK8=5gs9&h zUFr74h^K^lgSny%SXJpS7Hafrq8eG}yRsZD`?cx95|k2X4uWfaFQ+LOL5Q7CQ6dDEgEnL z&Yxt1>4)UC;%Q@3-oieV`6fZ?3GLT;6xRnRAvL(+(kcq~6lOv(F0-c69(Y$Vr<%xW zzl9LdawKP%ms6U=QZ|YZL^}*&+bpZ@;;L7H2`bgMJO`N1m>ToPf@O2$JH z_u?YxMX2 zWT*1(QRZSCRj$@d%pIpx?;M&p#6atpEok|6YT2kd;(#rb zh0?D9tpx>yVkV~HZJOn&QDu^v7t(Q-6cfg8-XpW%rX2!ZRtZq(_L; z4(5Tl0iPtN@Oz#H1d!hgl%2yyb2(dZmq=c|x9LLs4T)DteMlIM+@=p@>G5P740*W& zGrhH|F)5fLwl8tIk7|czAaLqsM#l5ZF1=ISz;3DNXd_#?uar??n}>y!(?Wds$&-eR zPbttsntDT8ZmV1vF1b3fHLquL`3RR5;mK)t(Y)&&nl)^yxO< zuNn&+aoCc1!p6gDFdmF?X)NVpj_&v@)Qp_psCqyT5*Mgwfx<9%$!H;k%W%lZ!Auqr zzDscDtGbNzRZ)ydJCEq}M{=(5A{jI9VbKX*mEWslLf}Eu$Nd}4qn}{lf9q9kOivZ8zdn9x{p^+XXVSc4Gc)^1$2Wxt zXZF%}^Y$^oQou^>vt>uZjkae9FfgGVpjmG|am41ugciOj1IEx4>aLUG@&}(d$5=7;_ zYpzNX6rB>mymp5m1`|P`(Wj(zt8ty%aS}4)c;A zS*oR?Gz^VW1ZI6Z4UkA^BOM9h9L?GWG#OuNWz9Q3)D~NAwM*u~oJ}@o zPZNbv$PMS;^C0%a*VQRJ)~URYGWnc@B#Dkq@n_x62YD zMk`W_n*`oj+{+20A}g$OsD7W+K3~oCu=CUYhx*M^#XW%b^T^_co}de=s+WRe`RUB9 zVYP7%>+&Cxp!1dL#J5=?b$LQP zt;p#gxV;!$s*;}~f8W}bY#IG(_>7T1Z_W2A=Vf*IlZL9we#q|$W)5Osx&ZzTQlppr z1shV2IQ-@`6xt>p`*E>)ZX}gmh*jZb6U(Ru@4xrd_y>`=f83X1XS6F3?dV`XC30&h z5`3Qwp)R%&8F~E`NPBfi{sT62^sM=-YWt_r7)$7IEB(rcTEY6BsnUsJ)xQejxeUr7 z@ff;!P8W6~%ak7HxVTS+`__kkJkNgZOWO;+Pn&a=C=#=(R6S;&(R|dNd_T|>);uC^ zR9kIH`wW?3R|uiO4W>V;0aH9YuL|mt`Cu7x4)YUbAutSNT+@Z|;hknq+2P&s$_z$8 zK8V|pwcRw5+WW>~Yj-Y^kyX|#Mvx==hR$W7io+|t6~{d&|5gE0(AN^;%*}>mz=gF< ztMo0Vo!Fnfv&m8xu6WE2cPC;A(U>fsJNY8C@C&8le){@A1F@+0@dc*nQ5`!IE5S9JZ4tJv z%E)JxP!*kp{erQwjg`$27Ce>pFXS#iU)ayOylS}xOn-(J&de~=H=K{2%BZG1&ix~y z2_xZqA+B>EefVbXb2iO}!V`w%Id=|HavfWAG<8x%;DL0k%9Vxn2rW89e z=;0p<&Uo?-{6(Xgw-LuCTLybv9_3C<_J4Yp{hK-eODyn*mlCh0p|=2|URFDwGF}kZ zGLEwFZharAD}(s1Ya_y+FLybP`tbG+(mA>^?e2%B-{!pX#)_uZVGQ{jXq7sv9yJ`^Lw7Jn6S*G4+k0h_qB%K4*++Yv(ROG^s5cHlM z6~E%asO-NhZf;9O+)(k37!d+~mQ7A9cS^={g+-;jzlNFMnU3Rx4SWGVBOEhRlyYIi6i*8%;7gN?Ph z2B|g|gjf8?LYoKEqndj~pWaXfG@)Yu@me=Y6F&Z7Jo`TtH@p5-ar3X&`iD30FXV9e zEDhStC2yvTOzW$43rMwX6vo2>_@mj)6Vb}tv2Fw^=q%4Pdxe#s3;ex+n~duHaID9sbd> zm{7)ib>ya`h7k$0hFKx*Mnuk*eVh7E=u#!V?oVbVi;ZL@zu}LZjf%Rg<;HJn=pIL_ z!-W4|I+ezuDvIgVBVkg*Hv+1X&A2mNKMuJ{!e2U-zYNp*qY>rK4&fh%{HI~s?>d!# z1lC`N{9nmpe{u@kaSpQ-61mizT|0kY&Z76L2YlT=xf3tqG&8Zxp891cysp7ma{b{x z`TKJIjq3c*%t{g#=%(4Z)9xk|DQ{>tsEz&i2YCvB6me>zZ%&QUe`V8w)9G+S9K#!# z)kympOA&t5y-w6CxR}<>KTnMgg$triPOX5;j$jaJMV{So@~Y=*^!Sg)ZwRam`i$1V z2mA9)cGj^fKd2l3$jSR(IMLpQ7hPBRpQ;5vvBXd0?7qRclp^YGra6}tQ}yYEmElmT zX?o$$6eQ|7%bz;6G#1Z3AsFS7|LN5Hk7?e$SkJlV}UosEW&RL z#)!0F$^Z>6@-rCeHGjpa_`!%FyBmVQIX;4Q5C!2mPH)7tD*N^QObZ}8TOdWP&nC@F zc<6${9cJdCQ5dXb9lqeV!=X&X8BSSEeQhXL*K6aQcWuW}A^0RbuoJ*cC4RYJN0-@$ z$!g1h3@k6iv`U*MWgO%PIn6)!L7`jEz4#oSmHK!nLHn);%;<5F)6KL>AY7>tZc2!P zaL6)TOj!IWf{#c1Q0?)du3zYBkk7K`N7#&!h0GnCH}nV8r~e`^)qEMa)6~?+6dc zUj^acf%pH!3#N?#Bjj}UH8`qMP{D{|9>ER$ASXGyjkCq%3E{6za>IvBLMYb;Ae-E5 z635p6ixltw_w@h&aP}7P#&0b3{>&Z!-$L9UH`X8N|Np$PE`L9JfffPSn@nlJu;-9( zXotkJ63`d$aQFmyvIHrb9vu`DSh*2`y`E{Ne--2TS_WNo(JTnxV1!=&MaO#vRckky zji@e}ky$?Cn~Lv$)y<(9MLcC&7^C=uv{_zuF)4xh{Vrp=(e=Q#l&SYG(&o>K@Bd+w z@ST5=Tvbe@Xn<4UI^qH@m_4zly|vWVL^WjQ=cw z{qw^6kA_MAhu!eM^90X)#`a@37{D1!3p7N2zwny>04e(8%zo~MrWkzfq#MQX|K)}E zd&pRPEJ4x8wiQEjy_FKn?med(m-2g@PC}G;0+4P0B~AmcPF>CWk#J}f!!K?#4#tq( zeIR|&U?vwzhY?94{1E&y6+?qcyQ<;ecnSb%Vw>jxC9-IYAW=7a&2pu5NoP?VhuJE% ze9dQwxU5wr{ku!mt>Y@)P~A5!JQVHwMjfV~_tVD~T;6m+k3+4M{@_iI?KjkgCE?2Q z3TK<`gk+LC{^4=`>-qM#BWT>Q23|pkB~DI!Yx}(V!Uv<`r^j__{Y350>kl855lvXR z9d%9q=kx70DJGmeellID{ax=5nRd{_15^d9)oCJtG8V8Af5=f?;_|!psShj|70<2^ ziaG677>d>P9^ra7#0-FdcQe<)B{%?S2tAxQxVr2H)$)D^i26aneQ_LLdqWVJs)d!cQ=~A+OI~flU zs?V7wk%$7RMFt{H+my$=%W+^t#OazCHg%4(E3NnW-tS^;^G`3D-}9YaRJ|_@Aaby~ zG4?2q=iRp}fr)e4m-_bE@0FGCbiyQ{*T+eGKFFi$6=$CN_?6zp{`l2p8C?$fc^UAp zY8B0+iZzw3{;?nG+UE5?R6hSiGyX~dU@Vg%{?+nrF1aH zJG^={&b{#TXyWy9-tj2)`9}{GHFNHkL1}zv^;+LLMCPA-Shp07k)4d32j3G`vu zCY;V2_)MHG7~DnlZ=kVs$shyhVLfDZi%UR&TYo+{UjY>WMwWM)!kd;mhfkcpd7Hv> zF`X1+tSOp&!ahAJK1hPc`v*r)phui*VTU|w)7M5FMjmc2^LlENp?I zifaoKp@ zAB5Cu0*o_J|2B8IzB^<=bey%DY3$NX?-vH&vWV3e+U ze}s(8QGA6Y@p5IDsHY%4H8|478Wtc+!g{S2EraoJD$4()M7ohsUQTg(ZdJ>VMWsq{ zYI-WY>!d8Yv$8_^p-j$`QWhTPb$J`$OaX5>oj7i_`k)0}NDGAiLCY}s)1JC#BPugT z%)Uy+K4H~^^lJ5p7)|>l?Oc=78hx}H-5;vY-ceN+OAabsibORTt#x{>RR(Ki#A$e^ zPY8>-OwPZm7aX0|Lvd@(Fq9VisLmRqRcbBB#}f0%1K=DuPnjOUea|;*tuZ9R@T3swfEqD za`od{-J&}07*TohFmr5mtI504Y9yTXUJ=@!jU@K$GZ*HThBbLR$?nyiPd@!CYlq&t zPd9j6{il>n&I%T~KSa0&?0hphPFZ-qpU)Sx7VzfcQ|9yUbM?W!*z51nTggyHLfIt= z@zBLOdI^FW!kLseu?#!*eN0Fp%&4`N3i z#u;v4k zEyk3~kQ?723g{d&yKc(rSANH5%QOnIMvGgZe(TgC0w>|~_Q>1h28t|Xzw&;CUhsz6 zR(xUUwcq-2-naX^66B(j;mmkrCvXZ5vZFst)&<-c+ixbi(@4y<~QG-(fY*x*$1Ozgz9t9of;+o*PN#M zV+Qlh88ZApjc5pQF~M-C9Dl5Bm;uSFNWnJ!JZGmkZyX;l^PQ+ zTHOHyUbJV5bK`FXYAk5J?`nbed$+u{z28jZMQ}PO83xO*yy?j20m(8X2GvRpq1eh4 zFF3hTbT7@{wrR{?dg>mxaBG?x?mH~NdzA7yYnu&@(K)Q8YENZru+BLl-I>e-^uH*f ztM^l6n+K zuhCu9v5!uJ0@@;=`rhR2*Tcl5`wa|ltk`n{ONXvKgO1^PNN0eTwj?5H%Q?W zQ=oK0>iy^1eM!HY4X(%$0==%nsP&@0%=5gDvkCitZh0Jl%azy(l!a_9@AF zlW&-&w^LKb3_FX zEy1t9zFs^U#IPr`Q9YRy5+-SA2j;lRcAVm0Hvq9&@nkB1TRl*m2iQsr(CITz6sYqR z82hbT0C`)00t}F{fj?31)F%|$L+)VJ?r?doZZ~WhB5AoJ<=i|BJpF?2o~gmB>v0XX z9Lvz)X~R4H;#~*BN+7pPxeajWSD0(`O(SFml^H|#U*e4Wm&Fpavc5yAfajhM3OVH3TU-dga<|nre zTS)!4ZpY_G#RGQ@Pw4U777f2cT?jj@b%gM8GOek7W4(7n{1Eb27YQu8=FczUKD2}$ zMmd)hVmbLlYeo6&T_l!ZCf!DN7AsHW5lXs-p%TGRH4Bq`Dt(VJB2v%8RfSpAtN;S66bg|PM*S2bzZ8a;6y|IP z+j1DXb#yIz&^}u#nXN_hqHR2!Ev{DnVJSOWE*PC`7HB|#HYXFzpB*P36Q}qxPT^&m zQdL}our05G3LRm5$gazW@&Kw%EL;X8-wv#|-(eFC?9Id2;~ z7ykLERKILPo5*zgRNG32lo)42Tl{Sp+J{M?CYWyh%z~KRzgoc?cA3MEo?9o9TdSYj zWS`rZo!jD<`?M;zqtiFOO0^V*l?}xzGRqsWw-~O<8{!C`=*)Z7nfE$7Z{}s*09O96 zU;Z>HnnnehIt&e^5RDFQVLZB*x9pdnN5R@cEf-BTDn2C{S&-OV{3~;JC7&1 zlx!VwX;_Z;IhAZRO$_qvHL5i{;A*~K{ry7U>+;FHFbVWH`@ELxnw0b0zHZ}t0&&@% zs5fjAi$u}>`^8&RND)q2Ar!8kX2!mmb(TbO4P%sL#U5Iqmz%~V7=;#Hq=HG{>_UYQ zN|$I2VS>MVaCbDg@Kr}*i8X#&bV1q7Lh zxd==|B)yg716~)=fYC;xtn(pHEZL&wT-=R~lDuPADLLcZz9vD0Gg*Q9>FRA#C7fHY zO1A><)T|igxr2Dv%+Sd(o?7Np|L28C+>4k)T`^Q^nC{wAN@4NM0l{ ze~-3^V7R`j=>kW2I4h_D+ADxFOkAUk=qWS(oe!>Qf8dC{-Rnr%1rnndv=EZ1-h zIbzfMG`@HbaJJa@%4bEU(go7Z`UuvC&L97!k3c9d50XMSXptCeLA?Xm>iMwVf2P8H zI6|MP4C`l;Gdl8Mz>dI*=Ch>m2wh%#f9SYaU2_Z(yES{)OZ@nLqtiKK)JiY-y9IuU zGWmxV@N*mz0SKI6`!%4%glBS2AAg{=(!>(?Y~I2#!D|U28r!yP+x)$C>G~q&bk^O+ zSxxKgD)qdKh9BfV2@2BXnOw6vR!M$?#$ZCeiIwe~vVqBA!ruenQYCncs^XIV4#izu zog-4$x>E|KMe}v9vZ6q5&+B&xFd2Y@sB-B1{X`L_D31L9aH0_K`wau&LvO&3HZ`TT zTK(pKvWfe>>EjRl;g7!U$VFGELa7U{$01L1|!?hA2MH|rfa@bV5 zD4a==^^C>sF{t`>`+ekF$e2!$*P@%C=uO#g5yZf7g-60gL2TYF#;nCw z$7bwj%*oQI^70*nKFE|5Omev56y|aATehn(QhRyz(4q@s2$9CeMMfftP&QbqvTWK` zEF3c}993iS=(WW4#f(~nu}O=u;KxmN8H7PH(I9K9bdd~mvDvhZtPBy`Alca>5n7N1 zyD(X%OiZ77n!%z}B*>6?YE%>xuV?o$URjo%O|@AcP>iTWHW!9&yqI1rl7PXMaMl73 zjbYEZV2U6?Y<>=1>gNk-vDuSvO$Cc;wUoqKCWoqWyTAHSH?;5$(0W=oekFG65vZ(- z#lw?+Q?48GVKz)CQu34Eyei8Re+B0cPhi!&A6TLiUF>=D(EB=F^uE1AeUeHgy7<}u zkSuStw~EmS){BKLeamfhAN^1xh-#aS^^Kq>tuvw8YNHFC$9UezWU_MpOWLGb!;b}!~r0We)#8gyx_@yvB@+=7V;?xx(HvGHn z(aGY^A{7D})hq?Y^Pvq<-)?3d4-qu{L9+N&+T~QYm-qOy1YkW_?}Q9CCf7e{XNHMB_1Ue$J_bM!D9oILNT| z<9vhrf_LDz(@(3|T@JSOzPxt1UE!*+(zny+uZFhuY zNUR6=9BsYGRSOos?{~WUrk#&2_}Qbg#R^L*Jy#Bo)gma_hAm30=0*rIt9)T7`km;F zPy#`U&9EE$T|67%qDZob(VLN|wCzg}M9^Q4IV!5Oh~<8=YY}(*IlE>2y;pXYtXG8L zST6OXzBx%a*O(hH5K%T2j1Z{5ogzn7WtFNd&S4D$##T}qu~-);BnbS4(#6JZQUG(^{Mp%}o#!dp@_m*?Dhf(tC$evR$*mGZvrzD!uF59X+cE8%{osW%_7!aPV!v5jJQjMp!@vRyt zO0z-{1dsP%2k|BJDT1z}Egd92a(C^rXA^wjZWu-8$Y~{Qiacm*cULlO>-3Au=~(u5 zba7gGnp4gb(qyXyib-s;7H++Gi_bMZVadmp6MiQNl&dZjTbvU;{TfhVP{CJ%K6AIe znxL7}eSph9l90o(+5(@W|vVxDb>{0tG zRiN5Ox9GcYC9f|!+)WMrw$qe?F1L3aKKZ>X^idTtChOJljCm{LT>lK-LL4j1_TqU> zkK=DjuV! zW=aJhyHNUuiO%$2((w+R$$G>%^SM`-ocM@^82VG6#8qs_F zhp9gqzFsO)p8^+UlCmNtQbfSOD4q3x)u+&ToJ)u~jzjfBdv zXo;h_Yr|UIsp{5sH}7*i+x_<(ul)^(nTB&{n$D`=uY-<`A7A6JgE2VOLzesLu-Gd= zk06tgWV1yCftAusic>LX%?uxpWTXYZVkf$s(9s^S%Zq)*4u++bu;SV)su^fz_~?@F3F;AeH6R50LjB7F5`i-}GvW!LOv{YSN7qODcxfz{e2igQ&4 zt<~DCgAxuoP=Io;iQcn6z1i$QHCkxMst4STgEe*K3&swyxw)WYX|w&BLfy{Ke#e-55UwM^QQI6+1 z883u z-XXSBYF`gaekf5}9!bDcMt~Cx8F^pB89*;O5JbwYrP3rDnmuVr3mV zDD>>}#OFun-CQVkGTN^0*z``w)r>4&YR0{2^ez3g74P^7S|(@cyE}#s5Z+^`V4x{8 z1iP)n3sjJ|5Vc?cdW(0mmYo9!Q6U!xdm(9? zyd)9SD@kj{YPP|pnu`RmACQIwu<8+TWMR~bZZ9UYv+dk4t@ zAdC0z8UFRRaExZSvRRN(fExprm@1Uy;j&}R`K7TW?NNYxfd^m~Wv`C@3!gmy*FBf- zaD8$pKp4u)Vsgh^r{DTPZo6T81h;b8!%d7JB8rd)GNdTx0Vw5u?Q#Z}0tOiKA*qAL z39TWwA_H3G0>~mmS+hdBhC|sFL%ArznB@td%7q-Fg%D?j3GP08>l2c}>M5}k%%c+o z>Ch9Gfy%Q(6|=$(Y@x0dVd@=W8p08z{G>87nuLcTT~Q$l{Gs}bp-l7se8Q2udXabZ zLhn|F+GB<}%0~ju!!;?Qw1uO@E*`oR5nGy*_^}gn4@Ob%L@}d96EZ~mFGk%nk7kgG zj=j(#PL9S6n!4{p5tFh=s53=^%uhNs!0X;f7#T&V;2xuB?rY4?VYC@TsS%SoLR!)h zTa7^J24m}YW3`dunnwr?`C~e=;+V|+Z@H6obr3z5Cl*2??6)HulqcxTiuY!Z=hGmg zJBgd5NT4?-?Y$s%?I4_Lxj&6b#_t}ta*@zMLGT;zHvvEgum(u|k&@mxq1WPZ{!)Cv zWsQ;lH!TIAWu=!*2q*;jx%Y?*6s{xqZ4D$K@-6cs+L8gfGEk7?T1 zScO*Vp~>#}^XI^q8JU26exR`To3Z?@Q% zJ(y!GPAPas^j_2R9!h)SVBo`z1IHJ1;Hyl(Q!5;BB&aTJI##T`LufL{4=Ktxa9-ii zPz*~jjZPmK97CZ!{>|8`8z7)$RGH^f_XG_ zM+<)kz$yR~0C@oD=c)tfg$mc8VSmxO{)bIDFa%1i&`9z(TGu~uG^({oBug-o@zlTG zB~~w&ixC`W6|iL0*g_9itZb7&Jv@)~ z&{IvJS9sSO{cX9F3Sp!gjA_tLJF#EuT2RFP?N(1$2iZh~eQ5flTUhQ`@{G)sfx7OM z(*gnvv!y$9?t5JoE6>^6(nWGH$Rn{Ftx?}fSPYx{s!4m6eY1wbVABG3~&%y5@tjck;y4rDd|NlAiB!n9YUR@_hw8ZFPPv=?!hT z5+DZP1R$(rFl7K3nAA51852A5zd~Rr-DAPQG@px@Phn#KQ*PaBCCZ<#)*E_PCEzwd z2*8B+WwpP4nV6O2|A>}qSrcW#{fSmX@6z9po^Qq|LXe&{Zo*L2k1>S5koW$%A;Zz> z6!ZQHLxh$CNOWR<6M*|)AhMjzWPjjC=B)K9QeHGQr(8?TBHvlG4+}y z7}jDAH3ih1@V{s|>u=`12yh1=fe54kOz%Hu z2u%i8J-UImFN%OkF>S=9crff#)_8S<&~g~Tk_^IOLo`^!swJB^?OZpiQxQb|s}Z+% z$|-^#M72Lyk}>y#f&ZWz7W?H5GytVmbM5OSoi5Da1sSfA_r?q8Z}Gesu~@t}pJM#u zQ%3%kZY;fs_>>=dQPPX92yIFVT`Zg(H`|ndLIXK%4+t#4MZt z8VC}0b5*GqRYqcbfZXg6r03kzU3#~P5wnctk0av7tPp$bl;1+(fEWlJ)J7sq%&L@& zVwf}Va>jb1;7`$L!2=pxgkk9q(P%Q2FZce~naBX{1O%N874R4_st5oL(}|_wPyV)f zpEn*8;}zRq7o??3EUnbfof&qHkVK-qQw9k@{(Z83kmFDQ9f)7M4RHKta-4;9075zx z!3JllN+jbCon?Pm`ZE3u`R9z^Ohh7r?1g&Me5?b&z`6MGNl0yf-r2X>V%aBYf0i#W zrx*tVFd%nMMh+PjA{epDxnDL}52O<6;z9SC7$)L{^i^Ay?ywC93vhf*qijKNon;Sx zhjo99G>uT+xS{{zeEI9oe=(7a!epRLvx8Yc;*k0ACPxm7hNJ1&B5Q>;H~8Y&C=r0w zQDIFuAK{QER&%*>?mgH2@s~3j%8!LZK9MXpmrecIaF||)C!62^N%Zwri zmb4HQ^;4syMbsCC-b4}w`MFr4qt>H>sJcQurUb!v2;~5Q{Y9oEp=)+4nDkdYW|%B% z%yxeQj-$K{j5Nv>_2V(k;nxJ;Su+ z@|fp%pYQ%ofvq55-@fAUqwA&jg`s3ryG2ms>RGab4vpAIXD1|pm}CkOBV}oWUJ2@v z9|fJ5Gjnnes}*dyk_0n;Ydcx3ZFIk;W(YpYT-!XlUtQPVng(S)eS{J2YXq3GOnTz< zLtO&E@R;i`#5_Tja}%HUY^;YiR<{eewrgrtJ?K zB3TvLi|GPZ-A9;{obHUU#obTmk(EI!9XOolJg&Ptqj)?a_@4UiE3x+uX>IcgwLIfH zU6LH_WW<4=rj>;bPG-~>vUtZZH9)tbzI@_x?YE&ut#hCT7ns? z($xjHNZt!^5JLa zOD!mV&)F)Lvy1whG*>*KRg5WP^|j0jUh-Xe>rZVPtUTh-k4^Z1?t}RECh9xY=j;9( zijCJIE51oCU3=Y3pT8Z+W4)f12tF2X->&h8_DP ziFY4)ge9KuZ4Eyr_zG0`+@*j<^CaK^eJ$zR_Z}|e_vm`!$iN0D=KVrs+$|Aws>u+n z@D1e6bBR}!5kY}>3((_+#V`H7(4Sb!pKiB_96P%PIF1zn@hkc;c=4f)E5gbOmgdVR%RI>K5&Fw9&?OvYH{YOJP)Z)GcIn?2xZaZcprXMN52Apalc& zaJM{gaHC}SGE;W{iQH)q`}B)ILigTnJH?19O|v$V_!si58*TIvJWin{oPn(L2?*mq zH#g50ZV||W=GfjBB{)C|wBRcSv^(6ND&QN^2#7?zOW@S`s??AJ)l9o%O%ge0!;EY4 z1YegL8wniU$6DP5d3#9`kFfa!NN&gRDPm)(e%~TVY>gnHJ+2>Ot^nC7E~-2_ED1cp zySqo$8DOMcXrzuzhuekra=D*;|EZHD()na6;0X>6Zl2|Vc~TfFi95cR3;@+pgT;=a zu+xy8>#As(9}XSWQ>=`z6C3N8LdGkd?4Ko+LVYHPYKC(PIACWSMnjE9snTcPQ$kWQ ze( z_Rr!jo+jWR31^VB7{&tVL+Zahi!vevK>2$nYR8--kmWb=hZQNFhgrKC!Vl;BgWQP} z^;Srj>8A~q>47aO`x2j~(CI&($DLQYc%^olKVUth5ABvgbXQjQ=r|!mCV9w1CmF<3 z?BX7!g^FY3qH;BERlxzyQlwGBs_xoA9S00M+wMt?29%ciXA#IP>Pa!2ugH+hWI)>A ztb8&U;9~8Ij-a!cxg@+9S}aV*G!(N*LuT{NA#2tR0&wD9qGwsOH-{0v^R$!%aWdCl z6nLN(t8H4PuX!gN`K()T*G%VmTLT(E@ld;CFS8vEs|QJ|#I|C2QF93H^Neg*5bG}c z5|le5XLPq2b|7KaunTC5UCC&yw3oIo0tnjZ-+a%on3?;Q9$#@Vj{71ZPvK=FKz0g0 zaXl1!7zob!-W$PeM&^dFLrFg{-vK_;3w~^Ew~d3M|X z`#jKcV(vt|2O3}~L~E)qps6pVdSY4ZiSZKgG0LcpQkaGb`Zq`iza%@!XB(Dca<4sz*5 zqHmDAk6->(PrzLopj2362u8M#!X3w+V@JYT{G4s@{iFQF+m&|Xv2)U z&1D94R<0ViZ9kH!<@D&IpIa3~aev-1gA&_bp1XY|b|25+wt4^>x}%$;t~=R`h9rok zC=W$j)a)EKK9G)RZzl4#6n1-SsL$?H+6pO=xo?Q6<29s+bsIqHjqNz1o3A?sZ;2cct{U2`S3tMx6(nSwxC<=BDW&M;PmSJaA^(Lh-6kV z&zYBt1)In@*qS85k6b`qn=BG}F4|L2l5jz@+)lZ|E}#WNiyI+&u&C-N6#+ZD?=BzN zRw?3Wcb`*OSF=Y>(>BheGNNY$;z6P8xDeeJ9>p~ug+>t-x=55rnouxj2+k6l^G%r7 zvt1lfo2it*_rkVpaiDE=S;-P}xAY&+N;HzQ{cX%PC(@VPO5cJek ze&nk>T$wmh>gCBOJ)J67v7@o37rllOhr0lynR8=8O(r3YtshZtY*vjgfzgsCZ(bO# zBJ&ANqc?2vt|6z0NT$%~r}Q(XP;`>qij1R1P37wpr?Qed?|>}BNde}%_w~I}FBelU zDbmF4?@thm?f9lGMW-odr^Q(&E6^js`_mLVW0dsMHT}{bEWsvA1tpi#rLvRI+#^jz zGEDR{tQ16m<}l1o4JwZ0l8adCPMAw)a{ZzknI8cKWhPEG=sR;J{$*xRCyeP{7L80+ zsD74Pj3qZDBi=qEvc%X{_dvOEFjE|v3Hmoz9%Pb-xZEmd+T1v?mXq><3+ zD6O@q5CbJht4s7pML5|Q$r~+%yGo2i%lQ<`?flDc8>F>`CEh_Vb(Sv07L{YsDI9De zV7^z_YgOUFS>dl(*f&rSN>v%&RndQvsLfe)%fF-tZd+~_T~0Y#ln9hwj>t$bD9_3% zPpz)X78QD3NrZkWpX7m0WviZZj6Kn6`oJGMAL^QuYBEB^m{;M(oW*Uz%+UzsNoXr| zk5y=xsmvge3md2zh%J4_SxYQhJ7iD`@vn8cC;u$7@~*!qPn#oxe!46t#DjtQ5dbos z2DXBMDVo^lUx=)FfQI3wrkan`?eR$nOK^&WAGZ+E?$dnt6MY#Df>)plT8Bm-V+TZ_ z))9!nZ-;Leif9$0k_iCph_nH>)e^16&}tf5t?;Rc6x=!Gn9>{jmX$U38x?>}55G1t z-)dqJYmzjOR!VD}_X5egCl+Wa(Q6jGv-Ks0t80BZ6+$xOsXN0rEf#45JDONwJ7nHB zWfW2u0+hHZ@gUWoDaebJiDJlWiI<2x=9H`;*6J5U(}W5eb&CM$(NADBmHuj)Jy`Bx zHOz~;c!o7801$B@Dz!DXmfJ1Q(sH^Sg(3g)N8MF{D^(hC43o)JONjjpOiGz$R%l8&Y7PhLo}H8WZ4dvOE7cu`{Y9-AyWh6K7|(NR|7MlkM? zViUtJ!AK1)*eq!BJ<5|I4M0cD@p4wHZf|MiHTTH9%A1na(Kr^$nV`^!;V&> z)D@T9Ws}y*3$e48#&EAsnF!nnh+=&Jd^BxU zLZn^K!U>_u>!n^Tp`mW2GwRhLREiU!2ILm9RL~^4 z@g!#8Bu$gJ5`SUVY(+QFo|dbc)x6ZFv?39;jKo$$+SKGs zO5{_;QN<#^?lQO8QiD;Id+@+ALE{}qeJdf3Q=3wE2!H#o5xpUC&xr_gYwzrI{vfIMF7u|?R2uO%@i*$o@D1rjg zAl)K@fRrL2-QC?K-69Rr-Q7qx!h0`5F`j4decp3E`@tXUo@0(N$GFDzA8w=SOB4%t z*C5Gr6YeiR>NB>e@Cq!(PcQz8n`wwYz|+!iK|5f^Jz!Z`JovteI%{Avj3@qK?An8v z7x*y~vV#g=`{XMJ6{7~djq!Q#^D~>=2{|PN?1l=g^4kpaBeN>PzYj%K4n^Y+I~*m% zX2xzn^%-&BeXGsdnE&OT8x0iSJM_uk4^o39JA+d(b2Zt-#^wrs50=Ta?EOM%>K-7Y9~77P;kqJ)O&9Ryv78y3I<3U}mIVe7{unQ-TyAhJmJYBRI@|_Ouz7BC;e}Ldv63O^v)PU*tu_2UM-u5v8f^plmcIgvQJvSbpEuR|@LBfJzB-ajC+U3x z@x{E>FE{68$A$d7grdKg5THV%qlv$f%hKRfY~_E=_+~3KXmz8%@Ai z6^WK?T0~wE-i%Ej6RXH>>SpZ_Ee|F5EHO&czWY8Ue`_F z+AvS2L2ak~!1TE`E-y|E>Tvum{4;3av#u44C#W+Yxut2%F+ z3UAxMLhB2)Hf5hy-IzVg_C1}PJ+q0u7i!U6r}-%36>#FIFzyu}S}bWKByDr%^?42k z>+XKZ#*nXyU8C#we9UDa#qZUjXFz)xCS~haogwmQ_Myov|M;QMx0OyeiLZ(hn1&PE z2qM;l59QJ&pAY-k8w@(`?l%e^6wn`hpkG-xk-QN#nUr-b{QbBl#ygXzr5P%|gtkxb z&5^46;GMBdS(Ia5@#&{1$C4;9>CwxBIejHDypPVPCWB26am1H%&W>mv9nL%S2X*L; zJM8mR9j^JzMz5cW+3#c%oTlf*MJ6~XcAA#;qPE^}M!ri&!hBj6G9t9g$xvBGR z-A8mx84JDpGj$%A?3zZY_h&`?@L5syv~y+~-Jx(yAkZE(2U|k5Lc8HS`21P!CJ0)T zv0)q_PC3r@_EIg#P{KRhx4?NeS(AdU^60xfbB08g0*Zjtn`cG}`RZS7@NHRWhx3j4 ziYkYfLn_s1xCwSx`Q|EV#T36w`N#HwWDrFA473f+GN5G?{oZj+Mnh5-ikE7J$iJi} zQW70XPcvU{^2U-1NPbhsWYCxPyjm511km>to;^%f)*qPaQIm~7c%esLL*c+`JjeW| zC%U=}7SppigX1$KCzbW28R0*Eh`z%3c6mASAgeNz~}tM+C(K_#APBat-*qX@Cjoh>Sv zH=m@Fl-LvyKi+~{BnHW0WC%4tEE|yKN+Bmo-dAG$V)&V!Uhshw^MF=Bk^^I;S!(8D zI5C2yvLA87`zFw234|kOYV7+Gx6R=1AX2Y0VFU@qB@Xzz=7C(^#LV>fgz2L&dV(3} z3X%>e>~gCBf;|iZE$Y^d8a}+TdX!r?NPH7u@QgmmDVf&y-DRUbA*G+tI%)I*$>I2U zTAqrhdC{Iy34MfKW|u~^RMdA3veY^07Fjcz-D5I#y0fH2Sh>bBYFQ z$zUsneEr2@FoN%*>#ayM3O`I45)h!#NmhrGy#2~O{_cZU+9evUq@%C9*zb;sR{7fB zw1}HGACa2!Fn?e?Q+8+WfG(x?)4>aWx#&Rc079X)t^>NK`c?k?Hf*|4R{gZoaHQeX zI=wVlVvj2AzungLWZ|)q_%Ml&u$*G`$?Z%pM1w_aF|$~%tm|WN8}3vb2aO5ezSH0fK$wKn#e`v(45VmzqW-}fJ{e|lw{vJt_Xjn zrPYK39M8e1(uB-1+bi2Bi*9nr%D4ephv<7fPgwD7I-=C74j1KfUfY%nJQ|Xzg5y0| zn%^Qjd0laL8qcI6=SBC%Iw~C3x<^+EZ`=|89KqMv`e5ayY;rURo*Zi$%Gj-Ra@=`J zX>0Kn!tjdy()TBi#X=|G>9yPl>F>9$9t=#6ZuH z@IS0Y9D1zm&)z}#%$m-uur(;ld9I|tF#B7kze?UtJGFLNt1@EUYta+Y9AflDMICaH z`b@8Th4IbHz6*h?);E}ju%z}Sd%~s8Ds*g8OQizeZoJ`fZ>RaJ?`w9HN|Y~{qD6*~ zZBY~uwQixyHO2nex<4Q~OESWwVgJUYvW)-f+gaZGIO6ZHdSl^)DEL$$i{?cs=$~4A zWmmiP=!3ItJO;Cypgt7d>Yz>n;TnYqH?EAY_m0#p3u!MB4zz@+B(D6rPao<870DHqs4DU@b>AjpJ=c3#2E+&j!JOi87y&wc&@6=$n^F)|Ev+Bg#XV2qI--hKQ^YSJNtkAw5Y#mJzKf zgk`|bDS?E5xd#Jc`V1>)Hl^sI4R^*%+7lvPR-bS9nMRrE7^_{?@>BGhkxs`}w#%bb z3<#onkfZOgi;(~%Tv)9k=?jlOMqM)0(t27+3m+7c&xF>Lq9zZaM!>Gx38wxRB^Pe!>{FF#IaWfE_iwndqp@aBZyPY?YLFYEqR|0qGys7AQf;jL2|wCFc?06g&iN9ZAsN%0(1hBVvsgBkxJ30EdPq?uDg6|!sT`wo z0s2wL5}Mx4#^-de_b2ybIE=Z^Qk~i-nrD=2<8-+p#b;f=2;+%Yv$92wcbFY8r_=KY zZ!)}l>Hhk?9!B%P%LEyl?htR2Bw2fN$ezq6uw2voZx&18IC5PP-m=xbk~1n-V9<7Z za2HAJBj1f$=?~afsGizqVwq-o#s6KmV+59MfgpO}l*-pk)`Wqmt+ zv-(Xvo~qySL$TR~nXg}yq&4s?#$hDz9->)BF9{KHOt2l)CSaDVmuj+pkXB^u;S_a4 z--lnJXT%tcIh89UN0=*2uFfPhF*Y^2fg?1IT2L9*rC(WG`K3bt$bWKtwnxH#XK3~W zsl9Or2Fqq;DIs}9!arUnpA z>5_6u?>&N+<>ibdhDb8c>Bc88>3ihF*R5bzp1h-KNha6;eM{G;wUl;Z1#-aZk)ci1 z_rUopGA$^%F#4^-&D)m_R1Z;ZhrWe%$JB5}mea<0iwSnx{@sC!$5}&-gSr2SJAjH# zu-~PCt?>k$O|FQL-xOjrG5i6qZXPi!5^;$#X96vjyN5EGhf6}yn(d@P+E1#uEVNzk zJ`swLmfEV5_b|Ow51i{1d;wcn6;R60PeRb$Hxq% z`Di}pXi3Le2S{@fX1`MK0qQTAB*CFL9Z z>8wadOL8?*Okj>bweB%A(4i>_OG!QvuT^}!M65Muc3<0R_0&GPMSn86A{=KJvb-cN zCtV5NJ6vz*B|mggofL0eW6|v63Q|j&UFLUcS<(DSl=1bncxRF z96_9Hh7bxSpeXn`LP@*CN_|49gL!loRsZ}Q60KghGYq$A06jdFLVzM9gp;qh)$@{0 z6Zwy#Ptat;n$)2EPqZ|}IuS7HovGY0?`q6LFeeCISNr(_RIlqHbRl8Mm$&dhXx35zeznr@5RPb<1BB zxxa550fsqxOyGwF;jjK&4jta7JJ`D`gV!9H_yI>IuER0_?i_++UHOLPI)jrW#P%#py2itLxeHLzoLG z51_OHP_=;16$wAxxlbqKOfcZn*^@v8Sd zFmx3q^>LUV@l2au)yym1xliZ%=COwMyAY)O9`3Qb7Vku1pLVZPR31CO*F+VdXsVn( z_=YEPQ>&5z^!a6v_7`$IZ3l@tuo?H`2o!*G)llgQFzi_tiIib@D6V`uuU$-R&z*^J zq5lmQd5)@04uaY9Or5rd@3ZK{z#;A=jJ^~9d`8bjF?7-8x~>u|Z*hdo{c(w11P{SU zac&&H%ME-iXSOHA{O;JasC6Yz68O9cxluvvGI9S=DtncGFo(0%dy=7JIPgKQV|!Dd zrpRHw=`)baRQlwy*0P&1kf#HNrxeomC;bif{9hPL+PR=el@%=Yq#74-lyaQIp7AV6 z&y6LYn1&B=6ocU@=cI=V&-Lu*wJlxxVSpVgx2fp|K82)6^KQA_b^6M4GCJUZSQnRY zWsH1=^*Fch_2Gp{Z?!{Z0e~~RAfq1-y+8lVfU}nH-#+tC2Sm0(Zd$*mXdYA-NIZCK zPqrz&%ltz(mHNU18U6>U<)VGpA@+S!1mSzN_ssXGXQN>7>+ zwCe1K_d%{~z(j;HPX-5yEnGSV%8?4qco!%YZh&MxE6>DJy##MwNDi*PBfgjlHvVlwdMCiIw7LGeawd&{wvF%Da_{3<*pYqC?or%R-n>Hk-(EPPW=u*H5-PMd-ip z^vaul-yPJ=`Mx)5wQe_C=@6sQG(B?L{%}#&9&pympnH3~A%7+jy3%-KbahWw$>9_- zxTV_X_;}(?-77)}cM2Ig{bwMQgD4orPPXgUHn=Ex51DyAo-JYjUX)z(eh_Or2Ysb z!B4_CTl{1L*pK%_I_Yy`;QwY%crBiPnpH;SW-VV&hG&EwzO8(=P)uPJ%r!AW`;cd1 z0Hl%U@HqL_P9Vlj(CJx5-Zq-ejn4yq^w5Y;CHPkGYdp^=MBoXot6jIE1ve5F)comSc`O?EAxy|@|)u8bA1zaI~ zz4^$7hOsEHp0)@fQBjgwp#Uf`OA^(zxnN~WO2uGRm;Yc^8SH5D)6vvlL?aHs6H<6> z(JudRG))h*3BE9^947UPcEMFihz|zCkibCI%%Wv5Q1$Q%s9J&*bW6u^Gkhhd2G$Tb zs#pMOx``}fHUA4^d1g+#F!kECcm_)v#pqGdW{PKn4ZoGnIDIt9tjk^jqr_}AL0e@u zdX)$B8S7Oidn@bJAUK+h8fa{zjn6)J@CzV*x4=0qz@8M}Uq?c3gg zKQ4e88@zyZ8e(6MhLZb|pS^#&Q%k6(m;Mm=g0tI&1^qv|Q~z2T{>^M0415K$+w|I# z-49iE2Oy|36w#XQz<05cV=LISXR*9B{uG51jzf2A{5Z+S9!|asm(qB~i!3a9$Ib=9 z7Y!R-ha&6)+IMVqvBPIO6QE*erg#?$&13@gwZui@7cwV1tsYEeZ`8oPku%=4QB44> z)1X)F(t`dP8Vs;*eG1@(!T!GBXt=PTPgcH3RM!%E4(mL(ZWX6uL$fvO4^!|s2kUX5 zHvjbZ)qD29`{iQ1;mdR2>rqOKKcm=Poj|!Oyl|`w)p9C8y#6&Bj(b zbnY%Nk5&HqWCek2{;2k-PON<6_+4S{q6f11#`AeVF&G#%ZE9Qz-v6oEvlv=dfBc>o z36_-2Lj8%82poyZ@+V5^6oEMOAcMf=_Ddg=pHJ4GMSVaKY6CM{vAW7TE4X>g5-Yxm zYICR_OrsD6)h{+Tt5vRiOrj;h7z_Y3S(G05peH3Z!6llb%s@XeS~lieMd^99*BUK# zUhSzs5ww+?t$(S$1-FnfXu3I86#yk4U0%AqP#hp|@nr3S>#uD;_q)!4JcB=vheZID z2LOUO@@3zEGxHL=KW1@ zQNKh=6s~^<;Oe*;=nHgGPy6Xro1y*uqe-_>+WmwL!e(UWU$@t&34cYpvd z2=-AGWg%0Mz#;>1+tNCPT37LKI76>^84u^6$#cJJvJlw3wBP-%9Zb-BQ{+yOG4!O~ zqe?IGIebf7jQ3>uksabg7C|A?PZ#4Djj5!QgU;h2eMv%U55BBBjVehIoE^@n3_UZm z-F!1(`d)RCF&{Eg2t$t54)Yhb8?5@yBG;|twXxU+;L-4x2VuBy7#bUkRwTwty~r&v zR)|!k{^mB8UC^R1=biCQi$VbFo8o#lwW$(B!JY~4_PniXxd-K>9QqOL=xsY_X3B2+ z_uX*IQWN%txix4DtQvI~uKQ*gltE868=f^#qh&Lwv~4!+!ifFM4qL4X?#SD11N`6ydJI&1?hal6*UReL;X4xN$0iU-&XD(#;YaN00PG7rLsH_jCle!+ zx))paz63uFZtn|kzT|@!zJkM6_k=mI0P5x&l;+uh*X#)AsWr)+TO6=t22yL1nj)jc zl*n^?0FnG7wOXzrW9WV~{nI+%MFZ79&j5xX9ekCD`zv}2ABFLXU|D!10x@ze3d@|8@alwVA z?VUUr9L^^xEq@l8#gi`7=esk%rPdskR4}vlfDS{q>cjxrxEjRCG)cb;3obOP*?egc zz=b9vJJMzyhP=^c{Y9Z^wYvFlskI{VQ#Yp3b|%L<@Nj&(hip+2gnE9Jj1A+XN0AqF zJC462?(J1Qpzmuef~5VTK#j*YpzazKkFJ@cxWktecyX0n7Mj%~Y>6|pHe(p|K2^k&YB zU3*x>-WhMcbKVl8UbH|FM%t_lJk8SVlO67hVwcpM0eJdJ$pA15QOmcK$&#x^1|D&nmHH4(ZZ6NytXJPUJ;0;-q5xA$Y&cpAY_`qSCYG>C!?e8p|$ zglO~2t#N7al#A;%&~Qm655<_CZ`el>F?|Lh($oB>h|H;NHMfAQrrB=3f6L-=(S!3= z&djoTM;mFUGzhm4$-?j^Q{sRC?+uayK5PPfympyZIJ3T%F(v6r_}3qIjgsJ@YlLn( zR4RYfS;4yIJ?0NW0y#lu{4eP!Ef@1&`Tt2tV-_TyhkF7cw%l|bKvi3gj{i_Jh=#+%EARKtf)n7N*Re-wSz zPio9<)?bnZT-gfi6N8B2$mfFavmQ9wL3)Y$ktw*8%6dY*r2LVN*u%n}mHi)*TsUq= z0+5csy!7V&;qW{8ivj6~U{4|+eE89BtSuTjDoaKXhwZ{cFJSdst{6Xi@^(ane3~lN znSYfw(75!}kI|R6A-^>y1g-F{sRIW5?0DsW)%R#atHfO|G7{Rf%)~2(jSCSJjCHTT zgS;u0!T6HDVik`XNoo?Uk&znPyuBnzvJ+!r>&}?3z$;cUeqO|aS6%V6+-O}0YppxR zbT71KduziG(mNEueGhe4fDk~%N&D)0j{`hG{;lKpp9-<&+~2SLU&oMGQvQ;lznpxk zCONn~#fy&L?-OJtcY%rj%O@Z1Y-;>s4Eb^x=@PTY+Dq$Ox^)gzqqAZAb^LYN;t#udhk}5=QWO zk0Z;vX(2|r5MeQveoAZ+==ha|#v-9C5GA+^+n^=-%N+#<1nY3fhKE}&FQxpw$8qL< zFB!UvY9*^A+#rLmJYQHpy9O5TdCt#{UmMFxrge2P*4n4@4n7l(JJ92pPBp$P#K@S8 z|LAcLTblgnajaMOqa&Sn{1`;`34o5Dmz{*~7i1Bdm%0#=k+Y6a3RWKV)aJE$o;Tm# zNoqt0y1V5n8aa9o4azUm+{2upE}Gw{;^b}}6iEHo4*s<_9k9eK0=((CktCTd*yIaH zgI}md#q>pzuD+IhuFG9yq{BI@H2{woxHklJ{5rAB6N+Ds4N>x=L85+^5bHGKn8uGH zLwiQUX69*M{;~bm&84tGSHnQTk2E5H<{$R^(H?(?d$M>cxu z1J^cvv($`Obx;DGAz2(y)WirNFcB|XVa9rWC#sK3ST&@y|>b6ocrs_Ico86*Lx;F zS;cSQbNI`b2w`{J^cVJ=m?D~tmFir&aD3KfmrS2ds_(jzYIdJCS=fFuHg6* z#k8Pn5cQ)*5+lDTtGv0|XP^08lvU?FlWRRh{b*+yIqMi&q(_OGp6btm_&N}SAagUG zx+LaZsxyc{g@65Q7p-5e3xxf-6~&MF^*J%`zu`3X@1y|l(-?TvBlD)Glhr8-C}k}z zn2Eef=xeXJDYW&Teb9u9#BY_GRP@FiX^CoOUgIl=-0a5B0K6Rlb;fT6fomp#M6~3g z&O}S-148=@aO)T5mLrc%&fHvE3T6X7`)i8^MJ+f!O1HYgwYEspUQ zvUB`~tLo+Z)bchFCjq$C^(Wfxp7b8=?4;*(A8;*xf!LV*z@;ev#JcOU@px{4;|Cb* zH=M13|PnRt0>GZ$k#TV1zR8Hc?pZ1dpXG zQ$sYgz4*u;zs=0`(1{3v6FfYTieGm{OEu)F9!rb z(fTXr5V*rAHnIOZM|jMa$pxub&b+@jYsA+|wShZKMoHt>8o`aL15D{O?zRs>T=3HnFL`MwRRRfvr>4-*{bM09VQfY5wu{Xg zKJRJ8QJ30YZckA=cbdi0*q2*pg?iMsdy`yg9%_USIQASShgusEsw*se4;EHT)8r9P z&NkPuRm~rWZAx$&`*w?SX6g0C%E2R2+!X_nOiozAL?w?q-?0p=0bv>JcevfN)YBA+ zMUmEk#4=zT{m5Vw$cO%*=(e&an@Jt97Y*+0v z2uT=FiA}R|@(rPNpektX8>$b4!yGN@NSFF)si*qU0wa9=p>e(y#H(|vYU}GfyZ=(B zGXzRBS1br!`jFJ0FI->8p$&!T1IAY|9SZrzC+xoHP@*p6oKR>iGB!w?`VyRTg~US7 z=1^u+6J*6?e4~7(ov~GwjLwFZGvO+6Rjji%|f8A;^rS?&+ItCwr`Cka$XYZ>Nc z+PO*Rw+SnaipyhBtrZT2r|AN75L>MDVry`-h9fYRez)a1-3D z`NU~jo9WcbVAPy{v{8rgisa>g)2vxx2l~F#!=B(80r@5*5AU-UjiOxiKc|9!neuCe z*mc+Icodj{`@TT4#)@2jlypgQe@v8rgdFJmB6)>%*~iRwVBET-*q$c~bih<<4fOh7 z;-d@YkNB7sg1(^=_SZQf`Bw*?f1H|wbG!1&mi4H9|AAD z(#-|?b-X&dU;t#?ALQq0^Lu@M=f+wp2j%xQ!>bEAM@YtQ}FWJ88i(@D){b6#C%dg1#^@WeRj6{*iJdx{-h|`bQL&sDu=JoHV`3MJi=0)xpcC{g{%i4!oWd>;nUkz{-GNyGixKozJSNPU4hca@@ zAvnqMwP8wVJ~bYOO26-vGX&z}f1DHkcT@ArW~R9?xwm9QGxqgV8VH=#ik~j)7fyI! zg-0jmZ&-COaoH0@JbWYyxUv17O35S~Sgy^qf3*3o8t>v!Wjh4t^(a1{0bd4-3Q`eH zQ;T{zgf>bMt{KaVj6#@+^bZo!Cdy?{YyI`q(x$3asu0I(NVk(JJn6(YicTJ-t zOU(tFgC7{SzYUF_t&7FK@s_KM=|xZch@vYvd2rY+wy?DcyYQg^bksX1PA z1D2IdId5a8&JXW#`&(=C~oHX7T-aZ+m7Ur<(Wd>=XuGT`#3CCF&LA;r8Pfce7YJv0#`((VUUHEJr@% zY3OOV+%Z{#a5msg&uXn5qqL)b4Qq!(2dXle#R3>rMQ~1qKv*6AN5&bt#n_? zbh<-&@h5r!3*2|!M5E*)yh9ixj^i5@B7qQ|rAa36!Z*ix5yE0mIWG{yPvU64L7S#* z2h$)N>uBb`M;7tDkTNCW%{YRRi8kX7qCj6zNhk&srDI}qlN>EkI$(D!rU+ zg>}3N*GK334QjN?_FGMYeV+!G0cv>L&46zhS_q>pN9$F15nXvw>0+yLASS|4`IcK4 z6VDJxx=z|KtRCZ_A!w;p90qt{oF2>QVRIkLkluCrzPByvAotB7RSaclaDf5;$JgwT{F6b2l0VKAzu7rk_!|y;G=dnrow8|^PLg)g64LCW|!6y z^M{m57G&qsmI$U(dGuE=+{+eecqhRx4_TSlRKA7+4sf3>`^3TX0W^mtunFZzF?%H< zhOP9sI$N{t4uag$2MZn1 z58o5emN6~$B+DkKW`)Ntela`4Q9e1G3Uqct87Je)&0Qa_fjPw@cw1vOQ}09lxIMDu z)oh2u2s*q>f@yFrN{@Y$koxR9)isW@@6jbJ2W5*W!D=x;g}9eJr5h8oQ6A_dj&-cf z>WBn6aI3-?TCBfgyXVWWKS8q*ESzNwf1hk!Ezu6cIiwh)antrr5}zD?g{`q=ojg9w&j4 z;!k!u9c7Gig3`O|8yXe7G@g;&aHbfaiQhduomtW!zLHg@ikrZ#j_5j&TYI?ekykUm z?IGV{VzruI>$Q($?M~Z@mD`}v`rKz&)6iIcR27e|WXN5Ku5`l0HoI)eW@N2owW>V3 zd>YatDo2)fnaaH=UNkEa^nl7N5lU9ktmeR=p2kg`a^!BII_;g!LgoCDoX^m@o|_F2 zoZ>HY5U4$)-yqqE<~!cKwX4}8L)to*H&S-zK47q3Zv3Sa9ci^a{P_q@0T&#~PN(-x z{Ov9Q>@22kVe+p#-H$}Zc6x(Y+^D8&ygMi~CIN_HZavezECRvO zu)HkpPF}+^sH}0AsWX*;3A+*6o0HHtAMH5JR&Ml1a}g^m>mhuP?cNb_#AD#nl$o_v+9g#@5bsI z&S#t}0eH@Dr{HKEthTGqP&v_L7Nt(;Kb1#Su5=&;TJ4Y8-Z!7v%*5MQKDk4E>>ntszJ-4O?RaA8(l(so)S;{ueT7Oq|F+wji^oE$4Y_CoW z{5|9lmKOk8b)apYp;-UxNtaMC)JM-0#wJN4)K^|&MD=7O(thoJ0(4`ZDeQA$ErOPt z(W-SRJloA@9d<{zymmf~4A(J~e%}p<8GkShGP(;RM~e{+_dP}Mp1U+tuzB?DJ~Hmo zuqWQ*KA4_3AW=-41ZShCp$&&{4D|UQNVFQL$=CEGnTIRGY<7}azNSe&RPente`e_{w5qYv zBG=HqYa&=E^2At!tDXfb$D3J2^MT<|qvqbH2$(fZUfU1n)fyMU*5&{ABrQ<-DG z);e*r$693tfL}KyCcmQ&0{1fgJM7F!SVFeSr<5?xuQk&UdYWr*x97UBwoReh9(*A} z&2tlp1W1*2bt=s8?(%QZurf;O8SL{sk)}0q8wVTE`R{+UYMUY8Y;SDlqW0-RnkB|N zY!ZEx?;p}OOU8NFEbW~im?AkxrF7V$(4HS$+%`wI@Q6nh^;2l05}1FerQer}f*r_s^m=uK_qjyBCvNe`xY#X_7@zI_N==O&H6enQqsc() zI@v@R+h@>pVT#Dax302%Ddp0M!?6}7et!rt5{v=5DsG|ejQ}*>CHrr*$>`lF3!Wua z4n9kMz)MSOut%6WOMP$R-A&^}0{O$d#z|**F%1doY9nHPY79$wKkn+2S8=p!1;q7O zh&HLy{QN_jKD1CqckA7m=%5q$7-~h;ytohx!hH6K7Bzh?RCCulz!!t{-&CZRsyRb3 zxB2jM6{%Unf0!*&C>ziXKTYr!rdmqWg5;xA)KX4g@(+BOe>q{1)e&D#6Z%%7a(&+B z2f7JT2Sr^gqxgwnRS-Ni&D1ko&V^4e)yv(_DOX+Uv|cyhD46sz5}E^0=;N{zcPyG{!P-^Bcpwrjr9k*^wUJ5; zHIDfWdZqO=eNdUVO;6@RogmOofGGx2F%zplG~wwR$OH!G83tl{*y_6O?p9&8x_5>$FZ- zeugx@H3|(ie=F1U&F1CV5>dzbcar@?zqBi7VJ zfZ~ZgetN2Yf}5q>L!WTD7QO2OpdjFbE1z3rpIsSqzsvgJM}0m3(iBwsu?YvI>~x3n z{@sTGBtOIdkKXmQ=FqO5Pb|HIM8dZd@?5&7i+$TrQLfDLzRqyYBGdsUR~f(eK8GZvJS zj`5tXI5^QT6a~mthwP;-*xV1S{4*AIH{iXon?Tb|$5;yyv6DMBO7=a>wEXJm2x8eY zUQ!!&j-2zRibM+yK5Ux2Nf%4x%XTP!Q%eg)0{z^=xDdcXtcm7+)L#zT zz2R^sny19CYn>EMD>d}~rUN8|YY6T3vyuUq%$vJNPNd0AH(#~-&BudRbOC8W|D~=5 z7_cq^BJy)x&G`VR)D@5xQ1z<^#O4hS1Xy2}H3tA+h#M3Jgk;r^FO-CeWdyeHhgc&( z_oM)un4{xpUQHKl5-I-D5&?U(|I!k9B_XXO7(lg_vNKKZbebq?ApVTFC;j(L+@G@M zKQHJ%XFZMJrI#yN^SI|erEbfaGvuN2ZT%j{Ynuz`05PEI{7%d0$fbIN?48V5&(wCj^F*xUt)+zp6YNbTi3i_1t*pKqcb05*+?$0idc%i|=B-nqN z>R;{g&`CI0ZZ9W!SeZT}!7e?BvM~jrIVGaj-l+(_HPZ;S!aqK2l|OC|ba{YVW?NYe zihpHCvW%(O0jdBO!x+4Nnfu~Osr_oje$XX_FPh(qFpH+*jjnCOtMo_X1&rqNLLm=3 z4&NTNsnwxS<$8bO*bnOnG64LX#!~jT=r)fU6crGU_KoYm6n_klJ-*t@J39mYMbC1+ zmj|cAuOYag@|V5vQvmnVK_93Npp=||McF_5aeo}XEB!@yZ(oa|;3J`@o>_gpCo<)Z;0&Uo6T#gxg)nn5?c(5jrNVFO3rZ2q~KpEfrzt50Sm?o&Ggq zGZ-S*7U^t>?(@b>Q^4PpM;DrUKz8RtXIo*t1=SjJxj{(_`SC&syS*}y1|Dtw{8Dy> z*M+do!Z0GfA24+Eo;g67r2_hk)A~5qyP6imA4!V@HQfotoQXZivu@*g;sI%do3UGO z8YGh#oZyW;q<6!G&!%_AQ^icp3MiI z#1zqL%sRyccrg+g>NC;LvjFdw7%e6cYj%k*$`Y4Ku&AJ?B|Sxz$shxzo*Q8$^R|@u zia@M?`bt*C9#{wqOTC(VU3Ry!`l<6*AuMwh*7p8Y(16e4E^UemdYfyB_ z3qOkSAK`{hS`O@`3)7JPwfus}_WqxK9AJ`+9amj;KcGd(abvPhO%fA1w=qy%mgvnb zYRlW&8t;7Euw|Lr%vw7_{QvWUV{o7;Fv`5x_NOOPW+D2iwf6)5W>3&l;BQ_Bh!`6S z5Vwf z*wyvT9tAs1JTtVK9Iw_}gODpH&7O>caS(bInYY+k^>Heq=t4o#09Zr~_zjLg z4k)+TY6!1gv;Vkn@W2FU+Y*7>i0j-PwJ;5VuKS`%1Mac$4{+&AWW z$#a=?Jc?FKnZCI0OJ=BkYgAN)KL*YAk!bJgFYpJMOw{c)L7dz6dK#`^jW zGTrOHP$Y0*@&JPt5d6&fMRDP5@QXc*I=90f6_`bH^=kidQ2@?5f4N2f<(>AgMIlus zIam>_jsTX!(?6+1l{m!zxe5J`zYxKNv%z12MmJeP{=(TnZE&Qxy6M+$1ubYA^zP4- z@q<;q8CQMrKK+0FcmGWfn%SpX>)?EgI{9O0FYrD!1#-pZj^A(Z)4yF7+iZv*(@=fNCfO(1D%kG=P7Xxxc%o5wt`RaJ_7Jvo;j3x-+zj*@j*FQQz8}h^D>au=RZrN>5F*DHQ6GcCIpgc+bxax%`Xek_#N?u0VOe_6X0stA zi_;@Qr-<7jO5cdK8V(~pW+Va1 zdMW8srJTfC;XS#zw9L_V_vbhi;u@`SGIa;tw2-B^Iso+GII4IfI7B+B<{8IgCBl3w zW!3SrVNUhQ>BxEwB=((+&!A(xKC@z9^cu3Fl5!o>4~Qg~wa_n&OcOkYGSV7|$RqQb zU;{GqbVnL8%!|DcdJWPaWDOgn<{}0PW>PO?%4Q9+WMmZb?ju_mKid^+2@r>85U-Q* z?QRLkl&0Y$YePk0Du5I<`^49Cgtark;~J&dLbGC2B)KN)=*WkFrtez@*>*xTq?qIINtF#GJvpv999)n4&=UeVPQ*b>xKG zjiL>V;hUZ>B&Yd$-RhXZm?FtGurYf1*-dHHEa7{n+d~CehuDc-QiIMvv{G_jgfFd4hhsae(=(YVMeM7A z;&%8T;AdFe{ME!}J7N+!g{@Jn-8_6da#1pcW1zX+vTQqQgX<&tj97=w@OJb;TMEy9 zvwnyD(RK_7C6y0Oyz?FIPAt4sssMINrwhkU9GX|EAh~##yW&p#?XRiAtSw#MHaiJK zC~2Z1;@$q?ObOduOCqxA-N9u$Neo_TlDgtO;ln%0Y+utJS+(>;AMK>@p`=T@miel2 z+$Xx~!~nN1EYR(hgm`>@`#K=p{#j}L_m}+dud)BrI^u8n6sRLK!p~3v>FVvA%5z7R zAI+t!O6#BNh#wD*|FBk9zP~>C#RK)C(pp?6<0;|M;rsbMfdDfZp}<$^-!?ZHZVWN~3S1ISB%F`c;_ko>LxcAW0{|LiBa zTtWF;$?B^0C` zxYEs&B`qBITNH`yZx_Nfp^coL1&&|`dKD-&2xb>;1W^3V+HaP9HK9`vSYOx z8JS*j5@v~T&^KDv4c#fsseEc%RNew%E-I{;5GabtUt6#&&Dm+B zE6ciqQmG42?d;3?5L4_c27$Zw`AH<&TBTB2DYUV(dQI82bB-x{b<2*sOm*u4i+c?l zL1Cp0+oeVO;Bn^9)OqpWFdGA#O)M?F$GdE4NAz_$*$@Kz@)UL8GbnTh`l4;CYP8+$ z0%{u+b>kQnyY!H$FYOS((XzJ@oZSGA`(ZIcE7i%(zEp&rbrHD^lD67c4f4%~A9eQB zOzw|*7tu<94E_2KkUmtnA(>keg~;pv7hccRvw^1BGkDt+DK zU3@3F|6ugSGdu?!&_z(vO!NvweeY_N6?Qy@>!35aSZJtGr1koA#;SGmONTeB$K3L3 z<+Jmxt4=pS2I+&4frrWW5#O)9G<+hu^5&k%Y~ZPV9u*pkvl97*IQ|c(b$gjrB@r&{TY^e~6pgswa2?L<@r8J&P& zgOYOX*VLWr>4%<^LqY;y-<=IHG^}VtXkM(jMxw1Qh@|n4IS;GzE}G|v={Jl8ah_yg zMleD*s6r>Xlg!+%bTJ9p@kprI4+X}$sOx0r)8yFnD+wm{GQ8f{0JfwJAsbP{P*$P> z`)t1Vp$}aL)Vmap2w#x)O`6K!NhrG5!SWZXqEt?a)5R4iyW8^T6i(%%W*2DJFsu0t zOqV{zm*_{|745Rct_*roY|Uz?S9djC+jv?+%E6*BEjL>=<6i19%<}l0S@Zo_T$#Oq z3^JS@xSgl8JV4Q28hucw+ZMY5{Jhv4Wn!*RiJ&xbxY!b_Qa!-UgE9?Y#u|xzVdBYI zH6n+Dt*SoubnO{sI~Ve#xes{0kf5s;zI_km#)7@g)%%ai}Gqj%moH(csbH~3*6ieFp7DD&!-Up`JgZ{AWYdpbL~eAamW{xG8K z*=PBWR}1GY7sF*Q&IdoUzlyj1%MPCgRSf=3hyR6&^R00H_u`blEEW1k+t>G8OZ}wC&xP}UO7Q)|{Qhq!iQp8+Y`z^0N;E`iyk@|i4`Wnb{wf1=_sPrgO)y%bE0 zHr7sj+z`rrQDdo7iRp`>!hWbF$_Yn@_m&bn#GnoaaRF#On$T8)2t$ac06qkD`eIR2 zl-F0RRcQSdElVj>)X`cIsSZcF+kM;cBY;}sWTuMJ5uf^X3t3NETRhQ->x}W+!nyN{*+W7Ob*R zZxRgUfYJHxA8}WE^#sl7zr#v)w){4eEWRC3l4C_`g>2Sy<)7?i=OueE@8o3#K@}Xixu`pZ zPMM7PIp4TPEGofI3Ud7G2omkyAnyyLmkCiIe<^=Yz*1aMPhC`0*-Wu(Upe}K)S+sO z(|WTQs_!q6vcKDAP5&5#wqL&%FTdaLvG&Pc?U&l!2V%jGn7?trcJqVCTA)-sY!gjz z>y-txd;l&>ue=Z*%f`6_jW@i!Q-olfxfKd40kc4DEhOOgkWU7M_2HxZ@M{2nlHn=2MHqnoP%{X&1n;6})S=lp02Tm`?FXw~ztV$70RUG| zz%(BsPROya`%gZ^U91`6{&?SGq*+Nex!c-m5tX>4I$8pj{{yEeu(X;Q26(qLiHMy& z2Z``}2Ajgd*XS4R)k%yF00TmuXj??X4Wa7bakfJRDHL^DN`DNeL;!%;JQnAvU$U!e z4*}}^M;AM+oTu|kSRt5S`GQeII6tAqk2qglDwP;Ej{NW0l{D}$55l|G`5T(!n#DK8?nCFfl@{1($a320n1V#Yv z$~X!D1PhCaZA$-TYImtuOgyKT0tzaE6`%)eh19n&qM(_3**YDfEci$(T2I848?SGg>cI0SgnA(J$qXiuchhS6-3@xD)(4iQ(#1J z7ft0+ge~o2qaO4^dD}r=8Y~7Ya2Cc%>yMWd(*-by0%)O2ps4ADdo@lsN>w^4Iczup5ALlmOcD6@q~=#0N5WOuO#Lg(TdImMwCS{=6x)4zh}MDb zLlzk?GW|~H*rf?^iUc~wNCyRGvi6`UUM(ki zHcCCD?9bhs7{N9;Z(&jT+We>DU~GkO4N*9+5Qjg2#PDU>w8Q46YB^6!dO1nuKVMNz zF)5*x0>W9Np>a?dKXMLY$pLzh_yv1(e6agE8f+U(rwbS!gVjH>nujt+(E;|If`t(r zxH^*F7>=$oAD&Equ&Yuj$4!y-S@2E;7prS(L?eEAG@pDCr2VWG(=^T2bN5{pf)xEF z&YY~Go=R-ARuO{`H=47`Yy==H{L+KWxWK!V)8bRIhy3V<}UCF@J{%4fj337+<*Uvl9Nv-=yc!2bR%g?tT1#m^9Z%45%f))X&FMih9&vY) zEv>kt=94@bZs{CnmY1Pb*D+oGqNdnPaaVV-ai+edrqp$K*YLV=w(YK_{H5X-6VjB~ zJ--^#{qirCT-Wm>kv!FTtb4ZV*9$WvJhgQtdycNxi_4h2^}Ve7Phzey86Vd)&JH_< z8_e_VMbzmIYtj4j|N++45w_7sGjS~qYC%J;R+bVAwr}C6e3-xbzbVeIz>PAjW zeQtN%zwpoXDxFoP+-{qSG%X}i{8Vl606+jI`p=IXz#E3jY}q&Gf99k8q)BqidY>s1 z<7oe_{`?1e^j~5k(2D2(Iwtblk>fw-sedH#{}rtLw`rKL*1tPc!uw)eSSX7?{BMcz zj78yq8kBxlIEm^0Xw;0xFJZ}vs9wRHc;dapvdm8pB68d^c}*z*t+t@NB3$vkfTF8a zN{YAsh~@ZO0nbuY*I)9}6O8{Yh__EQ`18AWf7F>F1C#*|VX6Mnn11r}rTB9dyJ1Vn z&!`pXMPUQ^n5NHHCW1mS)U7~0Mx;GbE zC|3+E6D`2}e+(J=OR0~%W8M$u9myZZRCqZP>NJoyV%zdO@{gzPOn@375rzWVUCq!8 zEZM(_oLV2HwR@2Lxx4=EUiJTg$wYfA`nxP|s3B*4Bz^WNx}u)_AL5*PFcJVq02cIt zWdHSn!~^6ger6s@N5Ve(MU?l)eBbYJ&Y=sZypiA1d~ksKNB~X%DcqxfG`s$ou*TfW z_$N`+KV3tApu7LwHT0-(=sUXmAExwwx`x`7$Ugq>Q~E*nf|i~!CwWq|A#Mg-&;>`J?Il080}k5 z-F5Nqojj7_P1@=1bcMchsc@6W{>LVtnqJIz%@@bB<4z)@ch@KXFhY<^m1pn-TdPmY zjo=5qB0~}P1*54JRirhwCf&Py>X)*Ba%y+@ny*mU<&3p%D9<;Jw9hJ(Bh7t@ybgYd zBKvJB~Y~9Z!dFtDXDi*&9{gL6F9}*Hp%ks{ohjd&_#v- z9Z6C+*MB~em~ISX32i>q-^ARnL|{|ksjtIz#68PP8U|T|Va7HJ0`KA7yj?QL2Jcl#y6t1;Cd2@KK%h$Ht76ga&$c+z_ z*%6FIWl5$3&T0=N<-Qw`aaorLr-59C$*9uGhBL4Xkd>>^cSh2)jgTEG=Sn7UxWZ0* zADVUeo{RklMWX$*FB{6&?;sDG&rhBf!>bf=cv@B+6W`&N24dw1%UNfSvwFeSlq_0f!%)(ssNy0h|sWfHpMBbP)hBmw5Z46+;5`N$vdt zJa6yI+zqu_swhSiY>@7eFGEsE4LVu1#G8NUK3OpRjWsb{}Un~~} zG_6mkAe{`fx-x2SHR>?^NZpF@7%W+Hhy-+4i_v}7Uch^YDDKfQ^QpFyrGV2UIL)rrN?ybfMd(ps?yOTt)m((z3o_7xbh4Q zSOl!~oGC1CSybY;>k8Vi8eALp?ImOp$KUE|J=7ajPxi$R%-xjbsV+T=Ks54@8ny^j z8o@-;V}ex8d1A%lvbZM*Q2>Xmi=?Q0(#!qI^YV=v-T$KVsMB z23>L#9V}}CV5V1%@;$Ku6+ujxk9A~WHxqfWiB&PpHb~oA0HAiQYH=76yFgMP zs0_vr-3Cq-fUwaEg=&L^-R8U4mN^0R_FcF_{i}lyy6Md^XtkA|2A@HCs-x0jeuf9$NJfJMnSq4@mw2<5Bz&=AZeNp!?Ul`sCuTq{EpmN`9J{M0TD=<@q+Yg2B zOQ3Uj7MZSDm{xwiqew^E@mVmvkHxwZmJ7`(B6UN{LpsH5N(8~;-pCx6RlVygdFzgI zya5XrW_fYH^@Z`E8HX+mgTWaPb$=|^@KJ2O!iM?bX6(Ba$;Y=a+Ohj<4?n4}vdJ%y zn__=Pjj$;sFh!*}Ld+3FrL*^hlZCamd!pZ(Pc z_=8Zm%h+6n$|H%;LUU5LvrjEgL(3ga|%W>Lv(T3RcNngA5gzZ~2j4szjil z#gYUf2RysUJDlSi!_c+h`2fpEinTrRO`f5jgsG7YN_fE&lVlG+V#8S##qg->k=_(_ zP_;(tT|@vLtU$W$?@Vc$$5RBqNDl90)ECAxIw}HfplhObS|H^1-*CaK&>D)$xL>mAeD>^*c9lS zz25M-+tIV(`c2(i&BlS@D34kBj~Ag9EdoPj&ljskZ@*=~Hqlu0C)3aI_&UKk`TRDLIi2eL{pbxW8w0^}UCPAe zG24Qc%%xIRl09LVc`P?$ZgY;+?Pw^$b`$DCq?XTTHWr z1A##*nOp(Z;w%f}YW^IJD+&a%MLiSvh_0R^JJZaA^UOMt%31t3V3kp;@#IprEY*@7 z4Tio+4S)AU-C-Wxn4X#SN;hTp+ifcS%fR}_=w+fM`07R*qTKDrai8tJ6hB-X_lexk zHT$q@t9>$mzt$tWAoEk=#nax8XFT77OS|i|w*5|OWI%iJRpNmC=Tu6M{ZG z;%#{CFq30lL)SdQs~z;g@$f`@1>hSTmSFnkrCrw&R+_tyb+CgbvHqakc6kri$Pw6n z=@a>^RUg-rqo{<1b#@32f1h^gaeU0pddUknW#*RHw{1_Sih?|czBap}PZ|i02hk8S z3daXdCUdZIkS*pKOH$Yh_TcyiOF1doy?vRtLZvI~dmDw_h}=!JS%aiUdF+@MEAg38 zH`MzchHF_f;U^l7J`p0ZrXb$FsZ($Ot;X|}5|M@`tY}$fU_j!rW!JrUOd&12GTU=0 zsckzSG;sJ|m?8t5%3{8YM$P3QXyVrq|f`h`2T zcZwwDmY2xq*~_+L;q6N$%#kOJg@}P`SjIMZY4_h7-eJpgKWDki4+$@&+cNTcxadTx z`;u{c69%r3-V2Q!LJX~1qdi1VRal++db+nSGd=VE40LluL+Q~xy?)2VAyC6r>F>?d z^E_Od|D_9-zqWDT4E8NAcFegmLXRBFDt2+Thy{Ykd#sRpaa(I3>()^?)EqKf4kr{}O*}0}FwNOM{A$ z1YMc~jG)yX{1TFx2hX16b%uFYvEw4A=E1Iks@VVE^`VKFyIU>SA*3sNu7;^)Mc6`OGv`K(aR7hc0N{jP8k*I2f5B z3jPkEo@i*;`2L6l(ebz=*7gap8UfUXOySt6uFcDEGo9eWC>j&~ z((L_Mh>2~nhCfzs%%g1w5pPG)`52IHtk|~0L=Eu#(0e`pmCHpevUZFTaU3X@O58h6 zN;X!yAx>{T4xi6svc}Q+U)yjqn00ak%Yy?IX)D&HgE)EuoMNs2q`?>a zn1H+D;c7Koos4y;bdc&e@P-dnh#Q+m43~VCQp^jhUJ3`rm=!CEfvf6~(zrLyyt;;} zaRvtrHwO%ho7$d^4R$XNe8?L`|D;xG?p3@uyyAo*raGT9;jw@SITue(`>^9-JtDlk zRH$skWAWGhT(ph|ZoAAkt3AZ4l6)BuNGySo)RBo>luXt-t9^;2qEQs8+HL*M^eQ5v zARHtmdC7#9)YZ5^Pb=Q`xp%8I?@&L#3nnrXgGu9Q;KCC1!4qdz%6lAX?JlhC4vXr5 z!{L8k|2SL1yq=0pA4HLINKjFaZ+=NhBkuFH7Ow$?IHit}UKCZc66Z8ML{{{nTt#B? zqz?xQ{!TsKuowPS5)RPj-4o8VuAV2_qFKf+SQ#E#fCe6J7>+EeV7Q}aY9O<@^i0 zd-9g(v*K0@9mH@>38eMUu-%ZnculfYjzCF0PlB!Aj(QcB6*|*!h`&!Z3f*#<*sz+X zD@;lR3Or4qkJW&MdAv{nT$GFH(+iSGw0^aXcMWe;BvYh9g>A0OxmSpH5K6;jL$o31 z&~Sx!IzUwWln)LE0kxq_S2Y4X$!H|MblKz?qCV-i01l?K3BU@7+VA{!fP^%tu!_L{ zaWD>Hg9CG2OrDM5j)~1ZV1)o|xuX~kn+hjW*n=b_(hGNQSTy`fW-T0^LIlX5K3ACe zgG1~G&Tw!QRa7w5aFo?zDL5>G)pDxUTWY2&{kQ-<3;K3hQ|jVTlb1KqIPWBCOe%^< zj|?;FtWFE^jAtlSf=rg_3Xg0`uclRWfF#I+{JbyeQco00*z43d2|WY>Pe|*$Sm-HE zvNugDT`DUdkpcsoa9*e2gj{2X31UYG0^X1|$Wb)}2{y#*HzbDDCloa#71gKgHlz;L zr|sf}$XE8qmF@dCqJ)u4H#G`oHqPzfquMkM<>T|C5m&R+Mn*N2E;h9+8kaBH)m=B~ zMp;UGHcxHXn4KAnKQ-E)ukqt8{lwk;1*LvXfT1Mx$!cMWVpvw!E`AB*`aK*@iyM8* zrk(1lPYYH><;FEha})UiT8x(H`_dITjI%P21sk%kbXjnQr^% zQifCv_2+Jco#&F+U(|8n9`G>Adk*3`U~^xi5r6=U&l%Y$>|MYqlx&BHSQ!Ysl-1~f zMiwD#1{DRBRan6keiX`gaM6{`IL-56oPcEUuVY#!5xUt$R_G zOm-c_6;)Q{I82K$q*445#dxgjfd#r&7BGgGi)JCHWB(@wV>KPrqML?0;_GZ5z~WN7TdIl}7-atpwKMAmFw! zsWiWLKCVZ8(oaeSgY^n(uU5|n2B;Y$F=zH2j<+ax$Doikfr6Y0(cLi^<5XmaHFR62 z70j`Do9-<#KcB>{;FCb5qAwg+M%n)6? zKGzgmO&7Ni*mL1}A%n26T)?eVj3|>m9MAFHX%V2<812e%nwW`s4q&4_CDUSuf@*cV z8m!`Yh+{fHt-SK6PqU8f9^d`l+$j8SH{t$z3|1Eugl<33{QaS|}8i zw^W1>%D~uKPN+zo2gi}a(Zj@&;qNGnE#E05X5IN5f&(y1_o9^*A5rUpGhQMdS4K`x zij8?ES23|cE$_WL_H?sJ`nrBwzCY$medeGTJr$u?Js}Ei*?i$}A4b`&^s_8>Dpn3Z zn=3}rqZH*RNjEA&xAr%RE>+Q$1TxQrpT|5jx3QucFP(57R!kb6vtL`ZA3n&6iqz^8 ztel*WY6;oxf;0Za)Kn!HwkS`vbag{PPhKeNuK)u=9UQuHmr@c2{U;j=p^u)$MyDvNAm$Pll8 z_8`NpGJ^8t!vqiY(!tRuUO@MYM}RlvKn09O1PJWMQ2NaS+vm#Tu>53tP1v|qV^&X+^&pv;e@QQJ%`AyRiEgZ zFr~gwLgB{_PQw>2wM4Fg;@lZ>wu^R^#dh^c{%Udj zEJNfxXY?x1>FP=Av1LN>X&fG#Zt8>(+z!iKNnBLYfkK`WZH}aHsw=Yht z0(CfX#OxOz&TdY^iVr$mEV$b*6hiD6VudNs_ZPDq-XKsITsW_F^NRC?t2K0die+I_ z9wEDO-JZ@e%8MlT_Sj#1F9>;8Yhjx_9QKm8jPv%gv|+yW^*y7zXIH0tAA8e`TKlvf zd_ZfKFKZXOQho>nqkzmYE+b!_0YFj#XT!}l=5Yr?!7wFAB5Eq4h%9(c>AjYXcAf2a z?PKXPLQ7@cV0wd5Nn)$)3Mo=2vLX>O&-DuFd%p0TGS{Yfm3@@DUHwAmQ&(1%$CYLZ zoH$H&$AW{wUmRfoK%!5%zW8!Wa z*07n({bk!_rsl(w|#d56c>r`ov)NbB*B zy*_lGKYqS3obd7a=TqL5#F;%p`{1b$eUAd3wg5E%1`Q(VE7L z=P4yERrvX8E`HF$YCe@?BE&Wi?cLROcHL&9bamGTiB)GG`EW%NT&vjx+dsTvHpdW_ADwCc9mefH%H3k+aDgVFEm@!pO52Tusjmr~heSO8N! zSsQ`RWAWz}OI}tjmui~Q=k-v#uzgX449`bCd+Ocqw#Mk?r_L)HKejyk>a9IEJQR=! zYj*+U6M1p@dDI7Rff2gqHF!hSO4o8P#|VIMQ5LseYUw~4wa_Kr98@6r%C9*#zUT_WSu-fgrW>3))_sh^vL??8a({uBaGG)R?rZv+ro-+<$ix$OZn**6= zGv!PpIAccwEUHa)iEW0DS!>oc%)DYMBTs=m%{Lpzeg$+UjuVN!5|*6pUT-tFtEfhX zCb@Em6>SIXlV>2smT9F0!}cU{&I9nD52~g5UE*=0H)&UB$91_&SXm`MyQST;=y$L{9rfcHHMYNO(LX-r9!Yx$3^4ZuRSfKE)CMkuexuv3gwUUA( zy1%Y+WJQ8tBV!g9o#Sq9!+>uirx}_R`^wRmCD2B}yNfznh|wRO94x)TE$kH)tHB*k z1hODedVk`o&5Dmq2voy*!>&mQDo>Rb+lqRwHCuXu0*jQcsKBkSvI)A;6=gp)&W53AzD0D2S(a+o?ue|gw|pBGG^jF< zY4Gbi6OzuV>u&Lp1jItGlj1At5lXw^&GlWWYN(2ckXdvx5;@V+8{jTX-?>RN@0N7E zqM0(mRIWF~Y1vI_M{sgMat=dzs6|;+@l0{@Ebk&}9p6;;}p13!IIL z_Vw8k<|C(P2ZF{hg!L^~IZl39Lyt2#=i0G?4ja@+O;EMxI`r4AQJfMDF*2MeaB*oiqd1@I6+wIgzP3ynKqY=6 zCG{ja4$^E+&)XoyzQ7)m)w~9Ti>lT3coL7MY3^j<#b+>68Gb9kO8(Ve-b*$l23)Ak z9MW44k<6E29vBIkn9p?Yu}%!L-XI|9ZM0Y%@;nvVS^+75*y!9c$F)>yoI}itR2d;V zk_#v-dV>~0amg3~%X65Z5>-w^F+X;{4eHzo1)BbRqjekQ~RW z>9`$au6OXO@dnt*U%6bN_F3O2M5;gRX#}*G%PD6lD&&Y zfrKMxQ=p?~sE@K_j*O3e#A48k1p;mTC1B<##KP1Pc2Ii<)L6H;ag@i3XzZ>P=CPeB zSr;;>{J~ILn)p5K4bpL;tfkFOPD7xTAW`*%K4lA_PBfR9LR+R*>`jHjIDW_OtL3Hb zN7rd9eN*>d-S-6KUx)8uP95ZlB<_mfy$Qf`wl$2&#>*9NBaB+^S`U)igcm(HLUi8Y zv2vzlIJkPF2yeBWpEGU0?7fUqLSud{m!{!BXH8IS9M3p+bYocVe=p6rkMQv!F`U;( z%ZtnVXn3P%gnV-FL%>A;(S|Fjv^tzg_ zn{od(q)5nOMLp@F^ZfbYMu<lC4=F=*p=li%s*ORl4E}HH= z-|_Li-Xs*cQn&P8^n_2IdnLmA$@ko0qBX^}P~`5QEcfQCFXSMh6;R!JIVl2rA_52B z27}iIYtRN~-v)0ELWpfc&ITd91)&v#kh|J2rrI#=kr#YIro!Hf+SQzKwd0=fZpOSH z7H=nTYbRV{nR?kyoZU_$#EM@nnt<{LOIJ1kF5ojPRQK{v%Q%0LH^F582g%~EB&+`+ zQv}Mn{AVhcf;%)QF~g=ROBu=(X|&y$`6F}e?u*k;l10)MrIF^#?TwKv`H$$&8-H;U zQ>wlaJy_}ti}Cz&FatG^>nr#T2l(9i&M)5F|(5LAD-2PWZ<4-g) zkIjKGYX4DY^#6nU*Cz99>FT$~f|5|Wpmp%Sl28tQQ^rC+5C$;*_Q6kx6b87~-#&nW zhyNj|gMQ<$KKM>Mc>?V^GXM#+>vRD>SL3a=>;L4pR)2W!2W|JCYwapu<)4`SD(Qp{ zlneCNW&!u0zZUU_UjwdZ{#5(-owN88Er-GP|4ek5dgWB2|BCr{_r#~SKa9-azR_PY z08rmx02#D}PXMg-x&DuaZmX{15}E|2A>Q7%xJ~`Rxk=}ny)rb{gUBQN6Op z0ZG4x+|6GzbZ1EbAi&t6e0Ewne@JwGSG|jIUlfTty^2lcMp+8Le86BHmtM|?2DfiX zc4|{3mdK1bl{t`JA&QyV6y_b4e7@fqghLQim3;tCs9L0r7^y}g2`{?LFy$ET3A01;+ zeHd(#AEN_zQ)#vPQQ}oAwJjN=q;XFK4h#KOBDQ&#FF@+f4&msdSOOvry$mO37OM}b z3E~(NHUk(QB)Hb)4cu(a5|ke?V0JTA^^w7#j{4(d>D^S<@vA4An z1o8^wI5oF4Ut5k+oXTki%;o845jl@Gl?7QJz?eR+^3Pd|)o8 zk!MmvCVkb6yQf=%?@-e;FE>CCA|b*lB+$UU7OfxMJiV1vq|}S&TBOwI{Y5Fi4T3<( z*BI9kB=E`OkwU{~mu8oU2hC^+{I1LN7_iEyalBRwsTgUb!%FPl=Bw-a$%>=jOM!g` zzu9>{e{=fBa~U#pHp{^LGMoRdh@;&Xi{o+iU%vO{{YlX71c+jchZBBcD<@-TvA*UF z`KE5&?n?SaFl|z#1t)VGb6iGFT#T^@E`++q=*HLH(SfP4cjlom(#W^l1eVb?ux|(y zn7>^LP$ub#hCD!qZNa#`x90~5!aXW`81+60CGWFdFETF=%@?f0NKG#z_{}C4%Al-QHD0t$F z50=Vqsu4A58fX2120pF!HG!ZOjIl^zj0aELbE(VUPH~1bDe^|ZW=-RyM#r{*CDYdS zP2sy_)1snW$iPl9V}~tEN!c2+T?zM7ev^ne*zKM2hGSd%ioStHJD)Psdgh8ciYB|t zQMKK|w{A(fy0we8b|iHlpQe=Pf4W0)Z1@mO>e#p$+T>Wj^X|H|5p6yOAR34069%y9 z*)44bKv>FK*@-KSQv3{LY zl1{DcEyT>ODy&;yIGG}6Inl{dab-Q58Q>Y(pSR45C|&qkOJ3gUTt~{gU^lzB2cowV z1@|X^fB^lLH+smuI$shh)h{kE50$Ql-&?-;1UFccK4t#ekbfiI>ILn`9NMk{z-2^9 z!1LQ-3|FWeA{g2NUhC!xbWEVl7j z=E@oFBen#>_uEtAY`3S=_sX6fciZ`-n|$=C)4NbVV|sD96mc)10Z;A5QhDBp*Z7tvSr9x&uL=3F@+9 znfv0f-I@!>@%2MF4?Oz^A733Ow4vv+zm^>`CHb1zr;y8;(EnHPF;(Kc;NR{f(BhCd zfH0EooJfwA~YEHo)vJ{Mz2e?lblrLA%ri8p9J7pz&xMcy-$gO`oUl}sUW zv7JJ3%~MYJ1q5Q=1FhMFzUxjt`#n{J7KboDS!>OLb0oKqD^D!}LJZ<^yL!CTiINDfFu#YqyScDl;U~#!Q_xAH_ChyzjFHhU{Mq7AC zTOK{DCj6isOIvxcks?Ry76luldH&Xaf=cFtKRPE*q6@X?rlI3rbu_7%5k`8KrU(Aq zN&w1>{FPv8o@@gPcpEKUpdND92;f{Od!Bw71C%bRXTzWZNH(CA#e2C|tKw9IPn;b! zM_#ZFC^k3+>nQEu)9I=|>ZgiR60k9d)qOml6Q^rBm6K><3!f7glFF2uWUR$cpW+yQ zNtfi(xEsh;FCg6+tzFqz=A0sb~=fWP zt*QxiDoORQMQcW7a5nKGO?b-^g|lE5CJbTxQi%sCzL}1rpS5?@ykCS~3IAZ!=j&+W zj>IuYTzm>F+*YY(OT*1dT(*c~Ou@aFYZUG4P}Qi;>*rq$Wy@|=OlYL)Ts3GT$0YK_v?3<^3e(BBPrNjsigTa+Y?<^r}(y$mr-Si)Rs} zRe8Jao-W`{d&RHl^i*5imphR1`5A)WJuhWp##Hr2O>3%Gn5&;xf^Nu9rh+Nst=B@n z7jlh9C8nrDt0m23NJUtRu3IE_g3iv{N^SUBS`W1;t zDA}caR%|pTd8C2v_;Q&qN_P2MZ&ey_BC+Pgk}Nn&DiRKNDVB+yR{0$WatRNn6`hQE z0J9||hnugFC`&6uZXLTL7YTWMS9M-ip!-(!eJDDLmQ9bZUaD;z=;0?&xh-2Q23mUY zWUC@?#?WFOad+cT3ucnOF*)D)TUxiGnHLSO=~5h>{ZA zYMBX67gm`GNo-HNE6E>?8*O2EVY=1wyq^I5V~eTWT&ZuZlAe*E=cU#uZ!G;E~X*#6Gxa}4{9MX zk=_^0DEJPZ@`=Sj0ult{hE5H2*ofVgx%xGiKVB*bX@Is5H&{8I@8t_O??ZFgED`-m zjjN+Hg(5A4P=#o}BE@$aqIxw6n!9DbhIC#S^2fF_6_EM?Vbu7NUSD(NXw5<1kXLDX zdzR0_+^v^NgBu((nY`E^7kiJM#Zf=8Hj99a=uIok9ME&h_RZOe7vfL8ibu)a^m@wd z*K6Lpk8pFIQ8JilM3{SdVAZJz)SI`BAf+;>2UsrvF;xfR+qzjBhu>=Q`z`8cO0^>E zQ$BuK=foiSLFuS)f9Qcttu61{XP4U*+BAWVQPrZ?0>tr-lF26GffqPjXi4VwynVY~VlayXF_9GZLuW$Cwyz->!LRG=#6DP%?}%s7 zdD#+9x-Qsu&{|pY#UToK+R)}Rf!m?F+^k#g%w*sBx#w!oX}xS~F}_6@++yLs{t=ja zbyE5CXj)T~++?qMBGMB=B|&bquBr|8MFCC`8tw5DnK+(mTCE1I@yk%XB%{zydk**G z-1I$U8xLRuG(y9a-(Cnmhit$36Cf;y{XBos@csVM0)<}uFD!}S_fRfge`j5YF36G8 zFb^2P=IDF~otSBb*F#X)kUOIRlv{|_+FCd}=+`2A==o+zYzVa^-prAg1AHixZ8LSx z*EU|QmQG@}WTq5_rL>NdlTy&lFs+DyLyA9^x3P$LhZdA;>wE&5gjGdTDbb@;_X&@Y z0l)V?6`iRQA-(NAnQbjVu|`TL@2_-{Sz@#&`&ID0@R}}H3R{~duf>OXLUYu6C_DJxoVQ!!{8!kmfV{r;C8xLMqGzm)7y z5d0v8tu21h`;#L%XUf&;Ngl0!=xFxs zD6W}TsyvDvA9gM)kzG1BAmtoiaQS}Te7=4D^VaIvLe44dP)JVU{rZAjLYCx#cnI$8 z0p**f(kc}0(sfo*vK()-%Ab-3KMa3%D&=8C?}p*xY2QJ5r-~ju#x>jN z1;WbYg8a8r-B*h6ittk!wyGPhD0n7IVv6y1I4~52TINQKuV|<;K*(($N`4S#UZd%~ z>K;HR`{_x_?FmKAvL?een`FHU92w^z*((ky!4Rz|p=O9yhcHMlRR&}D@y>+Kb=tY- zaI2Erbu%f?p?4RO_FdzhB6u_|xh8554VXv0R%xmnRN-~19M#KpyHSmDxcAZiqVLzL z5hF&|k9HO@y&os+YKlsp+?S}~9bmdDQ1--qSn%e|t=!D~*Mr9RS89e$G`I#H+g1=t zO@v79*DPETy6-yAs(wX!G4_mS;ed~Lw#$q)chHcnx|a3*H>j7swL|AF-|QF8%Oz-- zC=7M-7^%4&_+`ERbMe-@I-LH7gB)@1{Zrb0kEC=-ubLMUUr6No?w)A)f&TF}8b zlf{EVCExq+lp1;8&vAq0t3YRg7HL7XjLA~={p1K0sTD;xd7*?DsCI;d{Xo@;jPeY>B2PY%!6n(Lt^kLm6a*+N;XJLyW z$I*`?a1}zB5v?{9B`3)kwvZyhg3)9i(OebC?t{8w6@|3O`tumQ>b;6r6qn9c;K=wi z%G`Jp&m~SqR5=<^;g?P9FlGO-uz)JVoE_`&Oq^#a(UvlVM8^2NW}wR%QZ6RRclM1* zL=j;mb&G8;=)Tvq4qGboK)31&i1%;&6}!S=FN1IJg?uO#`MyT2C@^UQ*NYHNsAmO? zb0D)+t`p1Az{qo9)Isgs?Fmu{Qpbe!bJ}2LZ&Kpj&0N8t6UfQy^p*KKnJO2jDiY1@ zd!n_Wm%@RJv?KX^o#LxxJ!?og;l&IsyLYT0utgb#)9A?3R197JJQE7@?qY~36#cbs z^xexaY+tnOGrGm|wH{cfSlLNutH4`k#)}R+MD`xSmTe!dl}|Ryg0Dj zNO^Ui<+0kpDGxzs{(+7aNlac0C5%wb6H zO?)M8R%1ig?WONctxw6;jqGadhW*m`2?30jDzpBjBy^Vk{r3`M^vO+w?g5N$QbRhz zV?l=Bk7V3~@;D2a3up}-G?MZTv~K(A4>Fs9^d=A)Bf}oGt|i)wFdBo5PPc6H`UIPT zSoT<=4T~ULQj-zDk7e@$qqj9I6uj9*jr|BkL2wMotu{?(aoheR7N-CMyA4*AG&%Yg zlt#`u%JZ#hS=k0qsvubug3hS zoF<8wj?eez2)XFp;eXG6zJMntfcfX@F$HH+5XLLp5xU*+KCQ`&3wyytO$^=Z#eP*{FF{-$ z5=Y<>y~sDj+wY@#+1_NO+)mYli_(@#?ZmQL@u$imrh-j2P_WgRWXCu$PBB zpXFTqy)U%CgqnwGlOCIj&nLVG0syaER}96)?$j<(ZV+J#7l^Jj8c3U9*ssYG5xMPV z@-fF$>_SJH?`1m*-b;4PEAk@r)0M>F%2sf0u{N_Yn&o5{IJ+ViC?KPAhi0bN8%dK z#LkY(OmMY8Lj3c}xVL$QqG@9c9%3r}RlG3_wJ7s<&s%)|qxl!2|BE3r@cd6^KkG0P zSO7$NI0%Rh4yCvzNBjd507Us`!S+X8L)1~%@E>|_xS)Ud;IPHS z4;BaUfTRE$(gsoD(j8@B-}>-YWb{4p zh7xS^>Y$r_@yJ=W5-@XZ0dQ8KRHLhzD*pHgmem@atd5}lJKO?l<)aS-lXdK)vbl2} z#3N8wEOzvwAH*KFs`u;CBYKuB!fDr)t+K3~ygB5Mjifx=b8@q)S`bzJa3YFIN*yid>kbtgK{;Q2(d_xPk2!4IV(#%BN>;Z{ z_1O{+jw%8ksYJ24o8li7 z5OQ}AvK`EJ>96{FzSg<9#0pN!x6f8v zfo)!|zg}-@GJOj@vE$Hm(&OgmwiqIJ0iBK8?*MY~>8mc`mrQu4sHxJ?kIE#@U*C$8 zoVG{8tH*talU3P}8y8=9+Z*4DpEIA0%4S7Iiw0$=aXHl(TQODJ!tX%n)r=r*P@{SD zeL_sCx$#H^10>l(%JS0J0Y3S_7dtAcp-IrO@z^^^=?Mn`npn%oRU5<5n>rNnT+ShK zm#uxD(7R0rL&G^1qiE(olevG|(jPY|EWJK{-|b`9Qko|oj4vHRa%?%{CbhazCL|2P ziEOSEd!iA$Z*7;8Xj)+RAoa?MU9PY+?EY!$xD`x3HN9VfMRs-l3P2-|g1s#$coJfi z%B4p*5ldQT`>NPiWjS3w{sKKuYUicxG^;S0>@o8mQruUkbxswURzwV*(Q|O&dAn9K zdpozNcrN~}sf=HSOk%xDnMQO2w6*X8;_bZsdXv|YbpZYTcR;`20=QTF4G%(Pezv8_ z8;XC_fIiaoV|(21)1LtB%jzRs8*%sfQ+TBNQ`^Fj-00sLo?OdA^j^X}J_Uiq}v^zDpbW||~ zc8zBwsa&hi{|Gq%8KdryAtyY0cKANF7}MAqAQ#hNHq~PLQ}PNn;}j% z=ba`iT)zZpd7Les1A8~DP}kDgShmZOY20V3df#G(1NjEjI`ln!V0IvMI>6`XAGNok zRceX{zQ=o?Mg2J4wagChheGy_M%RGgiA;u+31?&BfDQZ9YVHBA7B056vh(_PA~ya~ z>i#saGK5*3>U9_B=c0%_m<`zVgMAl0tTO4OH~SEP9qH9zEzN##PS_p3vP>24WFh;? z+Ths|A1cWZraDnBq#qCBXD-EPK;VzQmsWl|@05T707oV7_w#O~(?07=q;cgPK;T>o zAv}lsX`>J%WbwrHpa9^5)p<=-JG@wuBJZ2LCpl~8!(|=K#TKHMH=IjoQ~zw|U78?U zbqMJ;VO8PzWM$~?m+^wQ<{TU3m7VVDB85z8FYt1HRN-_3sW|im15JrpJXOkAHq37w z;8J94ySS_246tE&>D_xvSN^I!^o!|>u*6b}zI57^s-z2Vt$H&WG9xr5uOP?stq{Zx zk?%kudZ%AM;nS07yY9R(L4AkhDi8!Z0yin34YrtK7F2*#YgUVDm#TUE#34P zh_hFN?-YCnR~zL}3+wI)ejUGE%3&(LS_qhN9|HX8)9RBP7!Kh0~r_p+Vp74+#{onD3jQiXl?!WF&R|@@Qa2>!^J5wzqB~!gN zjr()fKny4(H|SuT;o$cwhk_T*8vQ{nNkI_8K@z)In%Qw1B4SzDDVhQDgOK~I+I|>s z#zl5=A=z5EkfAW>1jM}OB&8AbQl^J+gZ7gq|dA5|7jmwduw=EJBb%t=h}VE zPP2g2No6!-G()iv8{)>DIJ`KNZ$;wild8mJkIRMv%3+4ggLk{BhjsJOw||5}tb;MCl=L>$>@ZFPa)4S-!O}-JSURK-1g!x>*vy zXu}%=*{RKPV={qQ3oH-{`mMX%0BR^u)`jUETCpoK!%~4OZz70M4>ECy7^pG~u8rZ?D|8NHnr)g5{Ts^P`{pgS%MR{4f zgCGdu0i$9-^9^LFov+sXcF!P^AzZ!c*pKA*u=HR7gp&9mB0vUoARIMA+?20X4byD!MTj;(=M2(m^Al?1_R67%meD<9`l;yoc`K$6HO951j0!Ivx^1;t# zK8&E?@(tg%TxYg5K$roDWy$50{f?YJurt31Ncl)W2ZWYQ0R;3ETSo!{zW%@vp@-W@ z3w-@IL&Sdv=JPL2Zwnx0KlyX+OM@cn>%@cb+{OE;4cYC z4){?rAn+c}4|M_pf*-WZ*DMmRbko2*!VreD+ zp7i#uu!oiWPeLmPu>;LfAz=5a|JXh6=-c+B~_C6F9 zTKX%m{v{}I_+K0;NDTJi>Y5(MkD%Z|`)#_l$>&|eb4@;{p$}G(m3dDxz6S-0_m0N; zLM~X$Obr1Q!J`4u2d3Ndy(so~0iNSgUjMf!S>Q;!2$9+r27+V$%M1^Lf!j-wCyA!M zAS;(U(wp&kPIOoDD~c(B_ZmKz*lXR_uCQlj8!Z?wGEdrld$I*FR%&ZC#V|3tI#lUw zcBSm|S^JK1!-W<9$xrs9O=x}XV6jiarjK#fp{APUYjYK0oW84H;?i-u5{0i&sO{Ll z?q~8nMngbf`6ft#@R3~a?%cEFn?2oEv>Fzcr)u%rd5lg1SLYrC1~ih~5jC8vN4{j~ zZme|)sPQ=cGIVcy>n-HG)%O4|Tpfq@DCz+0vIbBwd!RcEBKX6lDGB~d|DFEp-(9cC zf6sd0An^S8VsrX470*fR`B!EQJvd~B9L;PhU`?aAQ$SsK{{9(!zpns#c(Otdm2t!j z`D)po4P8h2j>I7Jyu}PaQ@*)~sC}=(9YB5L(t!9L43sy{0=o$!usP~wvz26b~ zYpDLm^&`77>fTuF6(57VVT-=_)4F(Tw+2}bht@;uzw_>iv=Qdua?JMiQ2-lCB)|eXVEw_elfx)DG6lyav|UCd<(X zLXcJ8LAtP`lOWD3OhFYq-H8yd53z43b4t7rSpJL26?TKkdKjU51zY)}Dd)ZlGV`Mm z=L@;Odzl3Wd`4+TRboz)o2y7RtFG!B9u(eFsrqk*{0d|8O%n)W3wpnN=6%uVLgYa# z8@r~{!FU7T$ZY=EqLquraXWTh!k@2X|^;53is#JSn=fKNV8BzkYSt+Zk9 z&~N27%sM2Ss?>AcZP>o#(-c1Js1ki^`6!SCqJe*u*x!BdFBSEF{3<{n>Hu8B`NIN| z!w(sMD+ubKeGbXD-JM|v`asc`E8=}ne*9zRKjl8k_Q0|QrC}rdXx_7_|4RSr6PtO$ z@|$P*GiLqQkPKL?9dQ3B{V+E&{dKY5A`%8y?%$5VeWE{(!Dj%dv^RxVWA0nbit7N> z<|^}aF^Z7~V0}BCTpiKx_Hq~mfxyy0Tn7ep5C-HIbZT(QIG-G z@UX$uH{yZt4#;AYo%0lfA*+++aq?7s;q)X|kd|)|?Ow)6Ij5Y#`yCRjl5xy-*Q~S) zaruuuOFaMX$uG4x8s|z2tDx`R?obe5usqO0J4lb=hv_l=ARqn8&a`|KzyntK^Fs$o z^5H{RcBbv0AHoN|>4yd$J|tgwq=7(aKn6YzNa!H-VESIKZt?o*Dw?_g(Ee`!{tt&D zB?CkX2hjol5DSR(F!cuE;nQgHf!H5=5HqUovXn=u0%r< zi0y~KL34%B&pgT&(u3*Iae`1b@=_fTEp&}bESnFl?~|@54x7kC&$PtLfCu~Z3$2&sn! z4Vs^cWPRtv)G2Bq=R+kU2$sxz_WiwEo2c|3Rnz#R7j@&wo?Cf7sXG*x=#o|4vi>QH2hT zfDSN%Z*2qagF^*mKHK7hN62H42+vRm#HUq!_!O?t9zY@f!XuG9>*>+?1;li8U^d_| zk^qjQLvXFsz>AjKP%;V=KAli5a5AoJ7$1h?aVQ}PLwoH&8YmKbigc^TwVfb5<40D7k{ZH^}r8p5LGaI>FdLC`GX_?wnZqrku*i^t27R7bY zcj0_diz%Cb`pA}nXXmQeT!THU!|RCvs>c$<`9j$%M&g6L#2S)GnsqhvkjxOiPhO{OU$Ml7+dkR-_PM5 zJ^g8K*v#v_N@AK4+gE&Zm1M%LP+ulRcMC`5-j3NInu2U*)sMtf?TYfVs#I_a*N^=H zq`OPNPNtGvfF&Y^i4+5c%^Vx(evve-TsngJtE2|UZ zX8TdmxX&ia#q)C|T~6kIkZdK9s0=}>U7NIFcB{RV>~35GkF+7R9Rne4Z3n1`UJ(r4 zYGxxhyKnpAjcpdDd@@TAE1M(_(T$j3%Zk3fOKy!*cDw}_=kB=~ZHQAVgYMNw((lJMuC zBRXkhi&~$$Dd*!NMTl)1l~1UxwG;5V@~IJUwU3zW=P_JFu#mmaNr3R{TJaN5IoP%d z=-(;LC6i=Ye#m6#=yE@owB;>Gaxm7928XXDqK|pT+MxiaSz|yD#~cCNscTe;4UEt| zrb1yo!EoNB2$aOrYQAvnlYG&Ltxd07rk2a2t)yPJd;587Y122VotB>4kB3Xn+#KIX zDtTd`Ue$Q`zB}ofu5Ypp26L*ax%wK)6?2}G0BtuWpAk!r* zrvzW#S-l64!qjIYnmy0HZKj*555M$c-3?v;IpV>)yJ8dFk!xzD!OG?HrtI%~uq}-Nj~B?DMV1!q~4L z_3Q3w>|t%QzV19`1>xr#-|!jE56w@k>6*NFJq+W7{$DHXWggp3kF&40w2Nn z5D!bM_Z?Sjqe%8MuwZf%)WQW)XT>WcV>?in{zn_3|N*0aAZ3ugG7o`Q?Ppaekv`m!GNKDFbS9^#8Z(keJzJ2ra$x$*4 zM!CYvduk4!@(vPHhJ<8KD5@jY2;3x8Sx!hCsY)>EHN((smhKV>420koO?`P9kI*TDR8%vg zsMaRD9C{&D-0~q!X198xM|&zbK>QHU!bRDHQmwK(lw1nLMk3Pvj=a*k#=CzzG13deWk-h-e&da9r0k?mk`gV@gA7Z8jqTtG*}R0Qhi;I zVpdJ%b|sUv2&JO!N7WzBw&BD$s*;;)$nKQ6Eo?Y$3QN#?pt39No;Jmeq-jl0+EY+tA-PBm#9Z)ZhfKe824QqeEL%FORGPX5qKRpPWMRhfnX2@mIqM-%^VQH z_F=veELaGy^yY{2 z8u27K#3pq^3tgaU2p47}^!4c!1}8CGG1u3p?@L{zAWmlM8psqt9n-QMEr`uE_u$E% z`dFZw4LNHJWm8xlk9EGh&V@SRJ)J2LRS;)>0%S&LmczrfN#;CSecP)_uU0BJR?9jX zQ$8MIfJlZpQNJ*tdasX4v}q$A5JGGFp|VZfq;H$+_Et|-MGM-5swP{CBL;t_CF2XuN>E3 zR!pL``$U|K;qUWOzIOZhh0XI?$!x*){vp>c562i5ntsfO+kqYP$1muYi+i$3vTkt|s z@JSHtyu3V|L%*Q~;!=P#i{)!Xi7W3lE>g+!GsujpKdQo=spZB25yUEz<(sm*P5-FiM_)>VlJHDS|BV5 zRa5MK(O!U~t3I*OZ~C;HgUobqbR`p4&k&kfIa(Zdp5I!x&+*J?d=qf#mgnooe&Hz$ zJ}-l6s<@z40pth-_78=Ue~kS9C0794Svt@cDLKTG1s~?czX4fT{-JsL_iVC%y0eSj zRP!a@dLvaoA2#N3yF?yw^NP3W9q5m1R2QMb^l_DMF;assW*vD1V08yo&3A_|&jb)u z8U8oT?SoP>-dl^GkHSAded6;65%J2=>PYOb0uk}SEQFIAJPKZ#e-UK@Y_#X>Qi?BR z_%Lf2u9TG99vy{I_rrna;7lcWeFe(zb}$Sw=>?4GINM?8A60 zg1*zUZp=3wLW1~9seUxhmwFSvLxKj=&K%5b0HSxWe46?_^#e(=O)2k#(|2p3o|$n2$v=@@SA?<}N3$SB(% zO-^9dSRgv$07(K?t97($DE5EZ8vE(|z0`1@iCXcfv;(}M5|D`#Nd7Pl`{{%~Y~y=> z{=1I!-(DpB7Jq${3)eJ8jF0NO(tSe)WvS=bzB3=qKah+4hP^_G$v4bRrx_Ec_D9&5 zfRcwTwB?3|Zg;DfE9Ddgre*zk?Ja7^vP`Mdthdq*&l`tA=K06?lw3vvP+@ETP=2E4 z9(CpvU?i8V+w&ds*SOK31Ux|nwC$kYYB9}3a&?ne?FZxa)PozL5Vb0fO^@ogTG&-& zo@38`Xzbb;YPG6dORVa7WvYzF-8|jm3m)F*^~H$4MAo&uv^;lGAZ@^-$M2$ro8Y_2 zto9Ad8n3-$m?qCKVIGn7NRCxtTK-trW=5Wq-eHd^n)Ip0?z zT4IuutDv$16nSiE@H3FuTBqZbm`=4lKWcw6hU1l4Lu~<3fzxM)7(c^s!nQ|_Z?`{i zHL}KBawwr*@Jic(>85%nmdHK4`=ws{6liV2t^BUbzQ!@nyL#J`WK>_?jh`;tZwkP; zMQD9|=~cqqndV6tk;`_ASRLQOk81rqaMM|fk1c@7Es@-tMK32KfZ{uJ^3b0@1m^H0 z9iBaIM~>#NOBn3?zuhOt<@Na=-N0WxSK$zrddE_3o__(uwkg^{h z>$qSepl)~2rXo7P(ABDRw|E~Z1P~8Ezz#C1O6Z!1YkgPW#zT*-~Hn=}=Ow z+m&yI^3E1&_uj60JC-UJ&7oAFncwT`;NY2>QhjwM>&ak5YAtcTXqG1;t@lpd=Ienp zjYw@^p7Y8?i9>%x)AEz4Px~|2FVv43-8Zn$3bB{po|p6bJk&#WdjIS0m(9(EmnF@o zvDkem!7Lg=)5&_3vF!1Rz~35Ey^oF?EbVTmotJGqUkIH zxij54g0Od_GD8HD={UoL9&}oUBObYDg-KPbF`kJi(_^`fOJg_tt*E6g(PiyTU_V0Y z#B)+=F3xb@(jp#Z`Nk&REP(KJ;^FAFOAmryC)-zd@!UFXx~R^NWA}RT-r4#5%lGfB z2QOVZuR8*Z!)`}g#ho;jUdWV_=w8S=u2^rC9jk4hACWkf_$DK@uhTr0?p&M^!t;}z zeSY5kf|ax~n-LgeHU>K}8%Vjk5bC!dB>lp@^3j{uC6DlkR!iGxre8;zSZrw^+QTK$ zf+#LPV+b8H^bo^(8b$I*wGRhu~W;u=&(*zkGF%QVMA zK#0w1pAtDjHBn)DBuG9&7{``>z;`iPL$#ctS7tz%QiI)J{_}H4JKyJ6uzWowzUVk; z0U0HK?(^}7VpeQsi|Z8xyW;3)IGP#lMO>WeNK1kdPK;nRDW-)7w~oAp4=<$`JADpmPBgSD}^-UQ9-bThDs{$X!Lr;QgmU|+a zkAXF}>RoxU=_+mNF(wj5S~&E}!g_oI>VoQg?@gb|YsNZLaPqEp4_NEVN*P_YvhL}z zXSLp}tLB;=LxHwsy_%sXp6I(AY9Q(!B5YlE9Hf)o}E&dc#PeD zyV(#a^Y!zz7xq@6WNm##C}cK3fJ#1uy3}i#+#I6cocR0bcX8^yq8;`xqCnlU}t|V*UgV zL~mNavEF$i92)~HHKBC(L?)u%6J)dN7$i_-sdexhmxUNLX3|s`-4|59c7x^FZ2Oo> z2u)e!CEkau#7Mf+du6)ePL(eiH*20y_m$mU7h?-hQ@!thqFvFG>bcS`ff_wb48za3 z$lA=;q5P;P>MT`u_^^F*vI~RDd%~(=+|~^@ zjm^q@pT{SEOfUM%@hsjoTXm)Sq3F!5EMaClO)Z#y+*oXmvC4Kh{?3V<_4zxSA7&F#@*1kXcNX?cP*qdNuj{qxFxuccH6hI2yn##IcefYDY^VhjC|) zDvnRKzLFguM!HR7i<~UhH>RQP7I#*6pyHyaJ8p%=sK)P3`==(t^6wV>8`+1CB}(Z_owcQ->{ ze%(Fa%y~lSOtj48yAU6ieY%cw7Y4};9owq3Z2V6fDNNoVXlMPJ2bDRVL2_;@OGRw+ zsg$y4BqOlaQe6Hxgq_G9o1v(X;sr4n|U)uA z)c0{&2%du#70IRIbDTxyd6%{arAVv7&j_yQ#q5qe2smaRnSu!#Ky=O-*hv{g(dlkm zG1J+cky{=li;yrHggrPT*O+8YE`GjU>q$jv3R8%u!RzL)Q0L0r-k0`DsL}|V8;Ts%u1mBL3TxVT`gfce^afLk3nF)M{$aEQ3rauecjlXc5m%U zq|Ec2dV4lL0&FU(PF98GEeDH?A|NM`kmpl%R#(%=ZN0O8Y7Zl>^9WqAA52-J;~nmBU$qpl%@nG3=dM)~XtWh*FjCT4WDD@)e#{qkS2^sdZCI-mdq-zj*K$~oyG&;` zT*p`I9fekyb$C=|_@sOI44uk^ZTM`S%G|clf|1Ir#E8Y(h~>@*!|aH)Agyd%FT67K zJ1%Ovi)x?D`4%nsR^}t;Y`NdL6B)RMy>nN=yA`1yi+Ncay51Q+wHyJHjw0cYptg(9 z+ae>pd=pNnMR62=XZ9H{mLiQOx-mwaIXeTd|ruu>dQvs&t$dGEPT266b+taJIC# zD^XuGf_NA%c$q9%Rcum;gYI$UTQMc`BvEU6q?kUUmM+2KLW1k91ec_Q>vaik`3ZNs z65I(BJ?Rs@E+qQhN`P09ce|==v_gAhK(Ul8gVBPh0aC0pQ8fsc00c^TBO62siWU{r zeNR>-a(r_RhND9S4OSrzjv?wwE)B*k*<#L)Bv;d?6!NFkC#8^i$I*X)3neL$TuahR z7q3yki$R~#$KX1)z-)93+J(C1aXG^apwrhY3noS?K9LSS>bO|Xe}Zm$m8!=lOfp%m#tJQ zEX8XSSx$G~OW7XM>(|IkDzUmNc0JN{7y|L(}V$(s#&; z*+AK|L`XJh%`8k_hs@hIgJn0DoKT7=D}#9@H{f>oMn=Y@awH*^Jhj#6WC|P0{2WYO zhgu(WDsd2A%%#JDkg0M)DFIq#^TPAx zP<8Xd&*pr^pb~L_@(%>UwgDFu;6$ht_+)AAcIkAU6C9N>VNgbgD4R?yV`M}coy?=j zkPf9+CtM)yt$^mt!t~|oaav^FeUOoVPnVQWA0a9ngv|o&>A{{2r4!1--hU8)4HV%g zQ6-FI;93N$uY{j@3)e)!ISR;IkqPJ9pimrKuocng*-Q!!DAJs00)jhR0sZ8hKO1ur zr=fTusz7y)`@~Kdgr3K#A?zvw6Tc-euv{&5AoV%9`~)pOjpW1sMYX*H{q1WeaTIdDSllbbhgl#8QGx2TL1p05EG)I_Dg-;+tLbDiji?8vV%58rZLGwAq&;0p3-<4?A3yx zPJ1gI*_vW9k10&4X|0W`4GFD1S<|D|)W6&`gLP<{Effkn`Dotb(aX?Bb19GBXrPfN zYEv8Px>G7&b=Q5Ewm%!(_&l$9Yr0u?r?K-D-TiWYoG?DTRQ4)MzRAatxT}0|LoKqF zM5@Nl8`UgSamu1X==n}Cb>Njf#w%+R zQ;;ddmFp{%?((VB`~VkoBu`0CV>EceWc_5rLi2Ltll>^VR~~T0L$w=kN=53*P{^k( z(lP6t@pqLI0v1aJ>B_u`!}DZ1Tk;x$o;5UJ5uE`JonFs6gP(QAxCV+POY%)7r^i0x ztLx(L>bn2DD_t`Jq)ARinTk?`$tj7NUWk7~32@m;23$wjz(GM0Jrn|hlaT6*p*@pg zFyWP$mS-_-Owa5no=|7pQ!U7KyGCZhMp(y@wQrYeiQfkAWN^9UC zlsV!}7RY#jtV?ZRxTZ6=uruoUK*5)R8pI$&&j96GgLasSp+#4XYc7cb42H%Wnk%q{Y(-f;eE%kMSX8f`c8yrtUiRxHHL~HtCl&TDe@xAF`#I3 zzM<=-_%ec3d;RceQHb+^@pYmhNVQ=@B%Gt_dBf;f#C(d*NrmLy}>P-Az#)L2_S zOF19@!UzU4*L*mmLN(o&ZqOrPa$%_-xP7@M$Czf`f zoC{;KenYlQIbbaU(;XnINykN@y9)~>1vC5e-;nJ;Ox70!STPWlM}AR8m2p7vk*eST;c`cz?=3WV%+5D>+C$OUR)20hiLKp0ng$d38-) zN(u7i9O`9b@XOt%M|)0>R;OPs6^;=pJTA5-a+p#Xj4rxy_c=s?SM^%&8k_jw+PKg? z!IWEdBVQ>n4l_j$B(6z|7ceUyi&o-~5pCcI^X7^tM?JNyn<@&Q7WSMLGaaO2UN{~x zc!5Dwr?K)advUO_0{tT@roP7-3{7~*0aycfcmsmByTEX3ZfCnokEPq-)GIFOmj+z3 zu(CvWD;M#H1%*@8O6!$!T5xM$PES`(JzREK+4f;AcrW9Uyyl|3>5{AGlJlvhTUVAm zB9*=(78%6Fi6jyRJtI9NgCVG6Lw>jZ{We0A+ z*@ee}+HJw4OV)ny>wQbM$3>N76%p1ew;z$`z928_Bd^$BqTXtd=V;8(p2<3O+TKNx zoc_%;T_?YvIL%;NF_lJxkdkpR-1^y*fruxAr`GPyKf!t37ww^eGbdCya*Ertw$On5 z!n0HSl$ML@;XKv~^BJeuw9n*6)cIyjLu(ggzmlu(t$d8At0H|zr`+*~bfwF5eO@>I zB@6320V%=DuZxu>3aO+fT`U&&#a?+RVWdoiWw~Sp~bThm37>7_UtXthm*o)U}aDW5g1_$#WUu)7#Gn; zXk1Rtj6N4KYqlbi4@4;g6;IS#Pc;ieu1QaZAeH**{2)9gL_CBdgaJOM%EMkPB3a(9 zWtARdCy<9(aE>x7^$?KAAkibqIuG4&CMYcV%KD)S&WK{?Ts^iPpyR@I>e;~AXKkGy z@LR_gjEaI#BB;l78dxpCL840WUZf)$_l-WDnhqId8zETdMBHiE7lNG?Js4$a?hvy| zlh$*7L5oxoDE|x$^uZy-?=}wc6eC*4LNS1dnZdF1y?J{eHMgE0KT7>f_=>8}79R7oxJ| zAp(iVMG218cp{6K&E9k35E$0mJHhzpU3fv-a1i3u?jli%GR4{BqAFD94a!t#E*LmA zc-3;|GwbDLX~PKBfa&p*mF78dY#tmo6-!jx4>M!0AbrAuO%#S$wJGwRrg=CjC=xxs zB)-fdgcf;A%f0I0A1er&XiG;u2eEk<5HpGsz9w)9)0W99rb2g8O)S#vQeZfW zQEKd3h*wwm1;EnOZFa35Id>V_*(-IaBmDP{pQub$=!?>vacr2>sFm zwb=!irL@3Px0j?P?>O8p>NDnFJJa#?~rV8D-Cd5$n^fyp1Y&Gq#NHd$$MJy>*ya8O54T6!I5@1-DtT(sX=0vA=dHSk8JDTY66F znRKD(jO8;(Yptq8brcsom8l6*amqC3s`)Cv(Qc(mv?;w`=#q~b>z5$-c$u*Ivi*x* zwv7`$(2dBq*UvYMNp?A&yB?wDJECnMAZ!?N)GRbSo@Wuumufg< zw!ri--eNVi{{D)YSvJ*e)M>`O{DaBU` z*{J#MP@irMsHV61(xhLDX9mC9UM5j_YQJuDQVM)0lLe;ZBWwgl7rgM*LW26KqSIMC z_(zMJ{NJKJFSK>Vy}5@=-YtyA6nHSa(m*q{2s(oO42cb3?8rCjj4niCrMQM`od|3~ z{3IUHOlHZ&WDvz(t3PfjPH?hahxr+WSZ}EjwrHDt95Z_AJcX5XzY3GlFjF;B$5Upclu{jy||q1`P57)Qc=Nj_e@ex(@OgOiT$2 z4bP&;8?lt=ivc+jw?n#89nL`dhcKC$+l~IXiw4nLsn(^k1^x^-zL!fkMl3&}*+9y?sNk7tZM4*pQv<#pwMJ61XrpGp<@w<=)-ccL#~at zQ_rh2;&S!l_kU z%#TLQWWzs`SS-0etd7MBsYn5XaL@R05eDA71~FckL^;b7Qkd(+D>0pT3>9TJ@hhT` z*F)uEAcZ)IAW)@zh=i^BlLoG*l`I|-6bFrDj^^sDBUFuD!dP%_lnzV6|PpCu=4gFJ_imi>4Ut1h&qrch;%IQu&Qj5eSY9XjzMjy<3V&A3x_^W#D$%k^v z<5xGZ=e#uZ*jwf}2ER`3GTuqhdiJEDKfYxtSM0}%hk$S(T8gZ=s>XU6muucgi%D&K z^TxA?Zvqx){PK;7I%-YfmCfY2&s}c2qmZcPw_C5SZQa-2>)Sk-schbSek*Re47;w$ zG2&AkVtd9oW_{;7dH=g}QaeoU@#K;dKko1Ghm9fND!vu>v9cKJd4R$Z`yzC=b&mLx z$^A$g=#RV5XjogM#6>XiWWtCUCdx69B9qSoO$&x^-J62MQ1R68X{@gWPCj~iTgi&l?brBQvt0$1r62!cSpjRaLmh~cj{1sJa(m)n%kqMnmPiZX)#*^dR zNV80~q==?oF8x9-&CVLl(AQe?A{J{R)ZbhBZ2azcb_%Tp4sNrl^+4DM1rujTVx387 z^*NB{e9IERX)utK0*8;W-)#g>CLU%V>&gzAVhQpb$?s4X-4x(K%RDCR3a>zTg|4FG zcPGIcff#w9Bhhsm9{~Ln(erNW1aKLL$t2)Z<3)9?-Ye(9udchJ;*5UiME@w#TV@&m z>?SDk^|J?IF->o>9z>Ww2%r{@$`6SBdZ&Z03q*}~<90ApcS$DoZDeZX$%$*K*4J5a z(Uy}!qc|#Eowyh!sMN~E)fAXATzW)5usy@4w==+0Txn2iEK$KFx?6V-?2J8D#~#O% z895E6cZv-q_f+jh$DQ#m8up&P6PQX0La(Hilfb!;22xl?m5cPYH3)gR%#~wK-CCI( zZB9%Nt>RbmG|0yDK%?fD%A!6(>*J{;xqmam*bh|qCV#$5$Rt2B!SfiB4Ji*oKMMPt zAQ948%Q_@Qsn^?mI}lGOvnLS4XY6LFCjebzB0+)%w{P8qU-!UaDF}qH-wyQd3qGUM z@oQ5APmNv6WRh~3#>N@sh!*!mfLExxWDLz`NJm9VRz^BP-Y(;T+6|C9Z@klo+|z}4 z9#{6r7$d*05VukG91yHwu_>QRj$j@r4zp!q7LR_V=f{r5v1*X@A%;l$0rAebH}z2& zI~07>T`q&sZ%vC_X@bfPdfV2E-oYg05Ez0k@10ZD^UYe;hnzRO0be`c&s?%5XUy~K zfbRx~&Gg&r$9u1dUyG3V4U$w3`s?Ps_2Quw@{Z=YjxZF;l2I2w;|)TrYpIY3iwZM1 z3Gm|J?o|xePGG8L@~h}98j}Z?9MyUdUvnT+3_<*Gi{JwXy^^n5$qrLc7gPC22RcIu zNYa%S>%lD6-ZX6{^&MF>M!$wyYU`-4fus-p!kim&ZW~v>%qT5IE2iu27TD>hB$e3g ze$P3SA?Ka>$N=*-X=V(RR@y?D15YSjQ^^wcigceae?CsHf_4})TlpI1*Yc2Cv}v*< z8O&95c$`^Fuo|jQvg!*XeaFMO((hz#DO0C|&eTGmh>Z52rz-9A8Q7~Ro{Vs|cdj^> zI7TL|OlGrrKf3-&X?3#Bx)c}UM_Ym%<3}U%?~++q=$_fD`lyXI;Eg)ws8R@i zL_kCP+kPbia9VQ)T;Z-NU9ik^{&Hfv@I7F?V;+C88Gy=x`M2-Ejvf*-qBwyxwIa1A zf+dPL&Buy75o)9?I$;iK&;G3IQjsKpvH2@|h*+4AWOY`v_I@E{bB{v$!xEj_cP8n| zl*a%)C1v$%$&ybYvZz{aQXi+g8=MF}+aIxRjW@d^o_*sR_~^-uGL9_ZYV}pq^$hd# zuA!Aql=llu-h*+XnOg}cRt*vq<=xKrDw(^UOYl*bXDSkts4>?pqlWuSC=qz&=`{(8HIp9R`l zPR~FnOzFbDUWQ4!U>Y8fH!{|;j<+8_6Adgyr0a<(4sI;Sc+5f}%4L8icUp{BA}>)$ z)0!s(%2~n#^}(8&pAF?4HU1g7Y4VsW%a668YYu*f?wrLh`u>O_QkrXJK3e`fxm;Pr zWFc0~s9+&Z%VA|9UdNw#F~K0tWHHe=w_q{Jyk=$bg>@J6QnKBs$x@2bV!=}C^I6pS zC^r;7YIrKTDU+w~4w|uh5asH!Z-@ZPN;dc&iw^Ws(s*I27y)b*CxX-e_~?I2ul`d; zMcz~P=#2-N2d*&h08tOHv-h``?j*_Av|g`Mr{5%vCquEK(Z4B_3F&e!`2= z*?ab1eDrV4jORNGW0ilKDxUo>tjy6E@~6Eqxt6DWa73AAeDPI`fz%u$AeoZfVR9D9z%{JHQ4SUPeMP!#5QxG(^9g)6zq4y!A9>HaLM`Pp%%s|ESFg{y_dHLI&dWnJ4W zYsFQgrfVg2i-kan}i;) zIpUOXKo}P7CGbOeW_b17W=OprL*BK2Qdr4P?uu@rMs!MWj?0t}AxOUG=QO;t2 zL@h$iepJh`d0_NOfXw!Q`V4E0#esk4-Z(~ZAJ?L?paGS)o<7WXkb~6WKxgBV~CfB+5 z?w*h);Ku&T_$*+Ltr76vb^0{@*U4uk?ppVCuDhT{>U~rFF0i;GmG;Z{?80~|ND>Ep zwtd*#avpqlg*1q(&UU3%v-!;MJl2iys7t`EtC*OmA2^;>$lkZ-$ z6P`0-5c*=GWUSxMlW#u~eJPozo}Mzrsa-h&247ftDs6kpyqxYEY-p4b7-bNGk2p4` z>2jcU5Rw(7vN~uRXH>`>i*CMZA`<2PTN9Wntdv|d!5NFGO~v0$K)NKy+{_THais~? z)++}@SvRVNRm?W3$Bc?LY9<}d-PrwEH|yr(%r@(nbBi_`)@#-_8@Ibyx0?0{krP44 z3N8Z-;7BhV!~Mb|41I)$#LMC*QBech$o4GogcCxxS$1>^>7q`=Cl54Xl6w-Goj_K$ zUJ=+t+7`wblAP88ibvvbj)Ogy??kLFu5ibiGuVB%>sGAX`v8@lQ=AjqVsG%7$>j9` z=nbF=a0#yM4=bylH^I}AeV_?8_CM+bupf*W#9P$Vg{GDqOaObP2cN9pupds^eY7~7 za#||kmPOsd**N^-iTd8~i!5(p)wJ_pR;+*!HXLY@B(VD*O#-R|#{*RQ&>p^pFQ zLUvR0noc0#&i0r0X%x$aEfUZq@>zr<%)d5mBsrM@o5J(80z$TtpSvs@;-96fKj6& z@W9=VXY$g#;?eEWz0nsxPJ3fv`KJ3~DiY7Q5$HM1fUcXO%>-ck8_ztav-H;nvI2=! zT#!=&a6%B-8Ri0SQ6gnQxv}7L;amsCI1vv|>eApy2)qVx7KR|z`(Dhzc%V0aDDPbI zLog?hQm;qXU(<3-H=bI9*eFiV^mrjrD|5v#NlWlzJV;FDzqx9h2hFB&o=+9QBgsnR z0lP4!d904-W%%KdGG&Ia@Z~4NMS=04^7dW?zsl)sMC_Tbe?eY~5u`A$HI#)VFFWak zxiD|y`f6b*kYUVH{4$QOsHD6`qo}ZM(}neA+bN5AX;rHDO1UKR;%Y@aSKoT&dr=G^ z2u($5qk7aRWTR%np>L!1vp)uV#XKGXF)Ku`&@wl{vSG7vy$fTjX=hYwtNCCtWUJ-m zpl_@76s6d*9tp#bgn62QZL=N1{dT(pOAOPd8d>#wG}-agTu9Mo%Sk_fL$9RyOWJRI zwq=aiW;?y~wd6Z}uiK?7-ZE{OetpMNeVaWG@9;r+KlF^vZeVWKyh^%g1Y>9DM-*iH z16T}b5=B*+{b8}E*OW+vu{Z2L>Ugko)oH{}4c($HG7D*_rGpFeKX`@%Wq)z=od~FE z?->RW8t4ol9~7%9YgiG!Tkza>MVxlT^E#W`e0y6A>v;ZNBb)OAXOTH?kCCJM(EHN3 z3=mEh$9)ly!qMC+e=QPD8{g?A0VX3_553N{Vc3~K#RC1aDPv_xm&U?z51aI)z z47Mtr4ybT0W<3h0-IWP?y-+h1^5RXqIl{Idfr-q}DU6?Q{DwPDDAh@EjHgT;4XFKw z5Z;+(28g}W5)yoOlHvJGgev}~6?6ccn~Q^BZ-D>;lw^w>j=b*-ZyM?tj1#?f;w4V{ zN;_;S0v5-;&kf2TOaOyPHg9_|5ySCo6QFc@Z@lP++Z|q@wK4FG-TzdbNqHtd`DN0f z8^2~dk~MUmgmD~4b2@|xoV;m$va=I^mYL0QT`{b;4G%NjD?$_l*9P=khsEG zp^EvdD88l{e7v@B6}TV105g}p>g-1n}1>B3%WOg2^KG|1)@Qh89 zp0(q$H1AWZKc7QLOHe5FN&DXh>G|@l4V7 z-jC&g)v8*}jg`^brXM8_eWfO+Nr~#ZDK>3lUrf$&Io7{7EVav$dc3T0SU;AsX`iEs zy>`%16T>FLz?p&0E-rXIYCw>VGZLLWw6=N6{+8d*Cvit4)V*4TvFu+33^JbFX)-q)8g5nTbF7hkm0Ix6z{ zJpKLp9(fhpm_)V(7Nz4}xfRiIk9#wS@9eRCNRke`an?Z> zz8n6S?J4O8=lAw4l_|S#pFa5J-0v}3nf?uPSrGfAUr^;PW{B3jIn(%HsH|-^Bm0V^ z(#cTVd(K?$k`>u!Cm&L=?&XV7n2LwA4@b*ZW~O~iVxv}nV~u6wul`_7=p)}~Rm*OP zA;sL|ZyF!l;&xy9QLH~9y8p4f#XeK@N0S34^^mgvLHxT18+TQ|P3U)VRad^-uyFk} z5fffhm{?LhI>vaN{j`i}lpP}DD@aa2=)*M69?b2dkC|o6-8f!?EK~OB%l4DQ7x%Pu zpO7UD1PB}@%UxT3%=&!>J;Eua61I6}<3drtkIKL7We~bnL%HwC%`l9hHPue$Fm*P< z&M!(6?q2LOl_4*}uQs?WFHbrm(dC?Vx8#}sm!@_u?j08Csa^5I@5>M5PWm0+?@2z@ zA18RIk%|=MNBc5?@-+Vq%P0)PB{|8mi1-alnQXY@w=4=>>~9UbaSk?^kMVyTiQQji zheSowjyH7yaSZPdoAc_ZimV;Kpl&&~leKI+aoY~3F>cUygi~Y<2v3VC7+{q)b|2)6 zF({WO&}u)yUtfN+#Glr#ApeBmH2pZB@!F=92k&xX_X*1#TsyJa(}RgFw*-?`rz{ya z#{QOPqe8IfP65Q>c0{kYU(*~an78lcz5hh~{jqf&wx`drk^4AyzgwrHcE>CS?HSUI zFWXzLXWzf5KHusag=CSbFYX5(6bQY7(S>+Z9vDAdqKLQmP!{lGP_;Vcz{(nUoKXfj zNOu{Rca4a9cCGH2xTqa=w>9pvCjqeu6TXPXM*}=3FZ|_aRAXM$#;!Mbyy%#`Lb)v0 z;_oe^Je{?6pp3gVUkRCoVl>$^Bg*UE3UpY5`jClYXe>E&J$1`Uhx~wI%yD>j8@Wpd zx{Jnu#5vr(1KgFze5X+DS)J~_A9czsdqisFaSF1^;D#K}W2Y@)SL2uv`P*mJTK<4~ zqN-t&XS;O1ajAC>nLyL zBj?jaD=oCB4MJx+bptB(C_O?*64cpiEUJM!jENJ33lGNgMAF~@*_}BB_#8zUs05O# zb8HcZsi?W51(=mN#eA;S6~#vYM3Ezlyr?EgP8N52eQebj zlw4D9S!I%36=blmfUU@hvR{U*sB^!&C%LB}rO!EeQX=_XLGtujeaZ<#VktWF*6Sy0 z`Kepg;hTx6Tf9#a%2GFbQnyG@zSf89!PCCIesZ#q_TyL^B&iM3NZ&Fvn7;?QON3rL z08vawKC@2W?sMaRSHa(_L^fGzzl|^WF%exOtHjH_#{OVwAvh^7)FuG)3$zIH{{R zqImd^Djp?x7expbt>s;p(Ib9GTim^h#|y^qODcYUQanIfGQ?LhtWh%RQZklQGSN^n zIZ^WYq-2`3be6AlUZZr;rF1!|bhV*$eWG;pq;#9~#AU%1iHGeBiHQf|X1C=`<{8G7aZ1y924|JVFBO}Leq0huy8pulxuZ4>*A&N zKf(l`{0}g}e}Y3a(+NNSD;zRvW>sqaS@ZEv7#b0D0WRPG;6ln@C1-k>XG(6}KmGE; zmFOS0Y|qUnjJ`jG=bT%|{RTt#TsL@?`uDQ(rI*96mGCPz9+#d4f5OmzA#nd*a_b}X z?Ex`BE)x0J9iZfd4u3HJDmj@ks^6{S{wo;zzb!e}h=ecyiNFyjKL!6@a?}#n`2Q1z zUKc^TfT8t7X@Pj@U^aJgoeKocxAdaqE@0?`Bh4^@-(YCowh+mG;vT|L4FK*zf-+j~ zFYci+vgbd!hyQcQu?T7wUm$S0CyzkCA#nc)L;q*VWy*p;wP+LIo8B#<|A4@anr$^7 zEjGr#I8pg4dHws5UUfCgvmvP&DCf9u{$vo>Wz{XuML45tVgR0N+AUHfZFD_F|@D(y2CDlvhT>;3C z+IeyGH)LCq^P&dHCs=(2aBtn50yvHW1DZkLR(U`ZpXaaWZi)y#%5!#7}&YhxoP2LWB!wqxVVJjfFnW+sOYZ~ z5imCL#zTr@NtjQ+ns!E)paUdCo?GUlmt%@3B8o=-%}JPir8>9c2_DWqhg%6hA^h|j zc^ZXleD?xw{dEava1k7twGsLVqJp|5YnD_(pY|1w9KB=}twsD%l0tTueX5b)XL{;> z)n_R6b3`9sAoSs#CblLCP@CodLCpPCo0pgHW|MMu+=v=tTNev=cD{RM9*cD#9k*gC z)f)3Ih`FOdvsFXIM^*ztciTJ& zPhw;gGjL+$1DW))bstsx#p{Vu*l_Eqzgu7khEd`nO@g>dhxK6(@$l!NLJ;L_;Vu!o z`6$%eEBev-Kb#D#`u6n=@ob3Pu`0RBfA+#(UJKQ*5A;~4U`Zr zF2j={ovB6napNZJb5IhQ>#Fy#asgNU$jv%HzBaPy+kjdRbnLbW>4h^{m;~t|Yy;U*Aw~<=AvHg-hSb)lGR&)Zf!5Bnu6BOar^f)EShI9FfAa`Ty^4QD&t0UMRIe&=sZ_2STr$qs z6Btr8^Q{%e_fks$8-GAQHn&R7%FQ==1le^GxbE!a{U#aT@Wt&C)rlm`@VUF$t$A)@odCkyYXmu z_y_Oj_c(6G`C`3`1zatx`GojKL!@ZGji^F{oVaxK? zh#XA1e&|MZ>HgOQ4Ygr4BemitmpMp+#g+*cd)JRmx;&t)9&_kX*O`#y#J&c@j!&P}NtFQW6G4Ezuy2b&QDMiN?%Ap3_a#69Y8AU97&(i~OtsvFy7;EEICdOiO%DrXF&$Jc@XG!-Lw&%Lh zPi5WhdH;dueP7&q_pG0jLvz}CHg@r5J~Mx(bta0hE%yEwmlNDU?fKv|L)W@R6GCl| zSb7+o5Xpg4+xs?i+q94VF<4g=148Eq#loWQ@g>LNPM0T;6i$WRAXKJ>F=EB&1rwL^ zc!qFL;@=38t>=P=fnUYVLHSy`<|6K+tYpE<2uvdRMOOo}BP1D^2ckr=KnrjsuAX@~ zw9qKRdVK17WITmGbCfSiq&hqiDFb-ZAWv~ezObgm&x1V+{!8KVTj~AF!{$Z(F-5$b zY-fRA!mQ&E6pHC9EaJgTlw!;;$hiv5Vz9Etd68iom?c)mtNMr7!5pSTc_DVVoH8x4 z3uMgLtxKL1u|FNRT-z`r5lkx1oZEb~S-UKoZPoy;w^b-a9_M0iLNrdA%6n>Bb+a+0 z`h$h=(GJE$J(7exZb`_`3~=7_1|e!{TSck^BSyJ5CYu< zUOFpq%|UbA1i6CcXunt2mYuuf{%Z|h&YXJ+bimB1;$)@6AEcqO)f77zYo4!Y zX=RvypJ^k&)0OcD`*YT}xvvY_r3I?*?Ji}aV}D1z5ZurolGQ!dIYjtU8FCgtzN&Nl zb@@Y)w$=V~*x~w|4*|W0Tkha2WbtKM*;9Rq*C?fl~ z!V3j?n<{q+lQ7^<5+fhI<`IsJY?i;y2#IXiTP)fN(inFg zZ2GnuY}JND1k9Y4UaMwgXx!`D=QHQmPJC7Kudj)p7MI)C4;ER!q_Q$M1;3(Y1Ozv0 zYg=g)9x;AU);uEH-qIA}-B(eRzM%W)Q*WuP2>Ra^^jrRMrlNtmK(&9>GY;sgch{wW z3{mr^#U){n*Kamsiu5=k<{H3tepk03;1(4vF;05!Pgy`rW;1Z6j_&0EXR6QH-(ZnZ z*rh*~+bKkf&?KtDSSCEB=U$0sgcy3Mh}u@ke!3&_-;&Aq>@=ZiVDAHP81H(5Z1pViuD8QWW1jiqdhr!tfKOS9e4Vh_Tt z%WVs4kZKH1oA`FxJ4(#H2vC0$+nS_OJj0f2X>v}t*mYNa=-K>j7vl}%Fj8yobH7Zy zMWVVh9gpuP_x8U)5k~_iwNdn9dtl>q!_|S_u8XuAu zlX7tNf@+8d58t>lPwvdvK;X#;Pn&j$4RLDFbs6T!M4TYH*k>sSJx_$SM3D?-#4Nic zL&!%&vL)1L4I)wzi#y0C3sreNRBOMJ1#t>&mrO^VHQqe;LL)i z;0Z57vrrP{3-|>Ln1u6dTvm(F>d!P7MPCFT$(KMzNLN9P2d1p~tthT=Iz$l!g_3TD z7&gJa1FiurgV}2NDrVUIHa9he5EF%oB!h^Wu_XM>8hwW065*w&B1^Fj8P%b>nOBXa zV$;kqn@!kLdpHKD%>_8=NAEdB+b|`d+tTKe*=;rTE3Vd(^*!Ipq*J7u1_=q5UVN4C znQFvQLY;ah)l3$@9^b>1SG?29R=a*7AbZw_*AEEDZUlMlzQ-4Nvn!18O_TH)b=L5Q z{#}>nxK4)RbarneXxaCN*_dVa`|fG~($1hpV{#3lg8f3yjZFoH^iWGm`)%}ogQR$i`#Ap5JNg1kIf@&i>c+< ztNL&th%YRd7*D7*ZSz=QVCe@#r-)z>Yo3cpURF;e86v2uq#tYit{-&ko?S>kdev?j zh^Rbsc^Q%C{XknQ>#%dyA)C9xiqnk|mB!Fr2fmf5ywD%EHu1L}A64+m>HUtZozFa7 zf8IC9HUBpAfU`V*>(4U$b1*lKE;b5NCh?~Qt>~R!wywzs;g`0q!4em?uB#vNuSM%s z_wE}vmg*>gyO&vu$CIm3%=!CN^u}wfwMRpw;upq3)y_uF^H7ysTfQGtu$8?9sUT|M z0`JJL-P(U+92be>&jh=F3Or3B98s%yFGD@$TEi|ej)3>?&sDu$W*)$}J-OOEt71i~ z{n-_`Z_0dxsQ5qX?606!mko2m8=+fcA6(8b?com&c7gk5%d|zu)qAU;i-^ag+082p z)Bie?5%kpmo0lUMYl3hUmH0S0Jp`5*lbh_05@bvL{P3P|I27X!U8=||CS1o4ONME{ z{#r9?Di@}q6Qv%Cdlgn7_6VcG^Fm=J$V2>g@j)gkmEmbn6-TV6F%RipRygUtQe?0= z7y76N;_a1eg*&n)^p77sSyAv26OEylt5F;M9FI2gQ9t~)ePCpg{fOgyya5(IqbzL+ z>I4)%#VntS{8a*;=H!t5G~E@CuPr5zG|4z4l+x7LYGe6co2oT?%#aOO!gL@VQKvUX zN8@C1MJ(Chltnfj@UJUusqb7BCu{k{vZg%r?p)v*Wu#V$#orB#+gyt#C70v&rNHwq zWNnC0xVpxVS)sT<@BR=zK^%*GEiwI9IG#|FWNGc0@j^7-=g+m4Vx3(@3z|uzW-lvG zHl<2(0qx28eS>M_WL8gQp13Q!*9ke0-q+@O`Mg{aPG*nfJD;x}rIk>hKC6q(7%n=O zsgaeZbe2BpDYQt0rjJ)!yS1>_-7S5b3f%-|{CKNIO*cfVNj&KJeDxA6YRw7kL4bEf zg})tbzU&3GoG22`zvCvNx3Yd|IWI6hi?KrBKAQTmJGCmM_ijg*&2F9%7 zE3)Vx8H=dpp99r2a+Z(Rp>8=GrTQ{74AFsg^M8^T5%i8YnKAz)XjU;&^6S$zWzpv@O)tPLifCXl zN%G7I&Q3v8Hz|U(u9Bt|w*$}1z(QQtb4>4|-WwI1hLR*KGL^{hBV>=O09wvrb;uuD z&X`-+SSNXnFOkU#no;U$a9)mgvBCo=nAcKUPq8%0gr(S+wxw%hVEXu9-16vzo1UEH z=I)-V+!jtIR~`c~&!V>6u(IhUBoCH+xyg0a$` zhuCIG(Wk&RUa9(nLOG;{eHe71t#r&l@~K^2m07WWshwnf21)I9DANr!LTA89I4qkB zYC#zr96Kyu@KL&HcA>5O2}J+JxY@r;DZNZyzF^#BucdEq*6h1CUORmR2#~S+sI}iG z(@6V7zEIj{Z*JJ^MJ&_&QhNWkKo?h8D|3gx7}{ylX8 z=FeAm)^b)^jfNi%`yr!D4MRN@Q(!{Z8&3B|HHinL_)!M<-iQj_R9`zV7GdRaJ(j(X*$ZjlHX@RVX8cY=t&cJ{vU}_gobWYXAoa`4(qad7ZgjGo?C2=9r>}ZCS&< zN{rhiFJYpQ&RZ?+=xw+3aGLLLD$R3LjkOXChHSS>?B{S?c@#8_caS=+my45ouAKzXkr8kQ=(HDe8^a`Hza+_ z!s3Ix7%)WDJTkg@DL|f;K)BbSb?e8IHxksopkaOe(5j&ce>Zy}x$%yhFLa9@JNjA4 z&98lS3~_97_|m#??Won;XFjCO=Y#)|^een7r&*hOSjQ?nOAJ)vCLyk6P_ zOD1-(*W(hAOjTuwg`Y<@s2bH~8|U3Si6?`svb@>k)F(gqGKYj4eNg=S*g|YB2 zAN=2R&i*Br1Jl1#k>*mG;H|{ReQ_HP{aPn_Q$FppYXBQDMqy^~m!Dfb<3}MsmjQl0 z(9LjL7I=P>+*GU14fdU;sCTs0+`jE^8CGHdPJi_cLam=) z6=`qT)vr~9aQ&iH?PJJ_w%W^(Z)9E|+V2=_!d5KH$wMF^bsLIKxl3uR#9(7da$o}rvA#`>Y$?-R0w@69e} zg+Dw%n}-YP(Mt-7fnVzdlaW@@1B+f%s6~`6hG)fH&3C*{YZz4WdKO5v)Yu=YN3A6o7E!0f-}A+8rORG;3Z`@ea%WM zb883K(SKAF72K)rU==Z-v->F2((?La*&9)*p*-YcmW^tZA6%Z&RImL~p#vIAtHND+ zeUD2P`Hb_uETelezVh*)M zPt|a^UU#+A5+t}=JYJ54k!?{hP7i$#rE*lhlhZ?JCs!w-PN&p2YGGq0d56{fE)0x= z`mv=AFPr>TxP{;#A!8$8Gbbh&V_;G{kt6+YoG3QTr2}% zy2%`j8R?hlK@4B@og5;A{VMY7 z9||LGeirvtUtA}!DG1aiYMSZH${pHVq1FDb-;2@oeRtsFrzY{{5AUDD6xEbV<3?}M zO^OOWGpM$oisn3o;&q1b;1OA{Sqwdm5cpB9MaStS*i5!40IQw1!u?(n_;~NV*e$UC zO~+9Eo?c4Bn&Xk1F5h;jkjjzEOJvHP;0;Ut?Czhm8Z*cP6#lEbIerQaF2WH4{?RrZ zcn%q~t3b}fsqWAuo90apz`7gZ(kE z#lWM>-w}vQd2?Oi1N04;1{=<%u9Mw^dh2d3i7E7{Ps&4V{A&%gEAR4^UOXsi*w-9Q zz25G>(eS6X<+Hr9V3E{aT&u^&nYLd2@qo}ErF?u9*mrxl9P;g8>rR+Au>gR8Y=`2 z_**_Ej(kW9F~D~3pqZWtUN|=E%L5M~Lr#YiTFx*j1aNtY4-wKJ9LGf5 zZGO`WL%>`7;&k%Pa2_T;)IA&u9V$;I?1sD^#z#5 z13{ChX!zZK)EB8R^?zumoChe+Zx5^^M>*j30P1URO!33p^YF7tW;`^xD2RN`3HnZ2 zpF3V8jvMdrOi7NskZ3-!VcW}mwaP`#)uHTBU`vK&&!sG9tdjU;rk}(?#zeLCTyL2A zE#0YlylS*i1Nkjb3yK9T{sYgl886?j0+_Mz+oEp}sijn;>uu+|;_jL)qMbiKB4FpM zWS5g1VGgMgLt@6J!2E>9T-^lY%FN{|87;l|Ta*VmH2@s;^Z9YUN_MKrvmavg(u{H3 zq4DrsJGFB~JLURSwDIXj0gr}OghS(}>+YnWb`bcu3Ww-RwO2Ablf@9+9UHltQ1Ld5 z2k!IvD{7KDq>HmlM1oqG%92oJI7SWMbU{*(riJK30Ltw^#UPaO{IOei3KJB=z%$0c zKIP9~M&}O0pMMZ?1u4%l0shT5U{5Y^+A29hES% zpdnq9ndJ(DAw%`?Vsgx}2(UyO>}Zs_)Kj10p*}J@M7Stp8yStbZh{l~TyYWN^*n0) zlM*_vII|jf(brfA-W%Jdc-@JS*(s~*XExJMJrgGI1Fx|62o^w6$bYj@_&<*&x@4Mu zvG5f3{ObVR{ z4j3KYH+ugS$C+6q)Z21ct7_@GUQr}gr!Hn7gV03Lhu7DjP@cPF@w8LVzq zEKQbW8*E&M&}|c%#_y_?{Jnm^A)M9Bs?JGg-{;HAkTas^w~jou z)3PFfjl#Kg@2!$9MluO0Q}6w)>s1e_hfar2R~V?p`n`{lRUE&xxixo<4uC2>`LdV~z9PS-9uO7?fv~V1E!1z%8+28eg z7R0TWEQghl^`=Nl0fwdURt3>5AEqd|d(D$-+dB#XvYm{wiI*xvg%w&IqFrJQ{kb(n?Xkf6ydqL^1L zG@^YlPn0Tlj5|yv4?fxZ=)Hp+t0O7DfkY#C9V>=Lf=qOI%!e}9PB)OzkDE4#3Clqz zn9YSyIE3aN@gM`ox&HxHN#G3;zRfyC55^NFU=_ZL(BR4{{J9#8a$hButlFF2LUX^4 z{;3!^R>M!*(pNnZO+8>SiO;zw*V_v4Kaf83<30C37{^US{Gp$h>b!%V@9cqPx-4VR z5Hyn!s;9iH`?#cv!1+*`Mw$5|Gs}RxLPI+oPY%~^L==pf4S$v(*l8lH;hxPLtVg3= z2G0o#7giOm-K!pswZ0R>B1$2s>@V?@fq_XQ!kvIk@(mP}xG}qwJ^n zs);)%*tJuD>^1#3D0ZU`*aE&8UA20=+CZHG0k(ig`-bZeRD!mmu8s?LfNUB6D>a8A z_6P9emwEHbQZ3yZO$Ou>sf*2XWVdmjUuj^z`G!9qn=Cs-KNX1ERR8|i{Iz+0o|Q^> z_tjLL?ZxJKTuITT?lmulwXRGzKU0w6i8&Y9T$wKrnT)CQb;KHxTuIi{`Ps;O@C_nP zQ)L~Ky4E9=l$Cm2*1{IdG)n-Tml>^8kA7U_*| ztq6a22XEt(Mr96pSX8ZuwA$U2Om%zj@1I?+^lz^QBbJEn;o!Tt@m(Wc3tzOu-!xFY8Fpk>~3;*03$>h$0Cv zWypeLjWdLBpZx8ik?`0bJ8}$u3rxdEYw!_$c-DWBBwr6l^L1UkEwYWxAl(T9=mP^` zB9lDW5}h}iY;tPu35c9o2Paq-GB0VI1sx7{rLmux!p9CXyy3V(*SR3{s3yi&UsTk0 zA)pwilRo_Pho0Qy$5TqWg4#*hMD`}7W7=u%f9T~Q5aVBQP#5pVNDvjM8I*M8TO;LM zy(C2ZHLo`8@3B)?h3bE+*Z$s(xNO+q7%3r50yhP>V1i7~5`bQqIx;I(j{&_GpwFw> z=z1wW+54#A{98Ni0`x-dt#=jfwP38D=n(2VJ9xPsyMz!$jCs@!s1NBj>*q<;N@#zw zPzV;f3ozdkuoqFPxfq%ar)y^&u&N)J`x`VCVvdi;q z7+v;0)vDUcUh`gZunQ%p^8UMw(ycR0ZqEn8yA*?2j)`HkhCAD+g%5ePb)Neq2wZ>b zk?0|DcKU9QLeTyioXRsC!70icjLa0N0*3K;`qC+MPx(p1mLvQS&6(g2U9XA40~sTk z;6W}Kf$(6&^6u*aXycXe(5Ll*Ghs-t0_Vb8kHNGN+z1HS(rCj<0}(fv=7*k}i92t_w&Qbh)y+;vo58cogeNcMD=Ms!h?2Lfjh~pPwmR-zGwawn2ONe&V zo~Ba2>UpZ{e!8-l>P>iJ0P^QD$d1!vXuyvS_eNTQK6D^3N%F1P!w4f!>e0%LCtb)3 z&p7u>d59bg_@!iy=f`l<6pS;eJ5>*{2vu?+ttCGFtc3Rx*~?|^S$41Tx`l(pCB{6ify8RU?7t#)r)rhPw^4zxmd%7mf0_d zFIZXJ@}hbfzUN0xx5hDOx1XaQ?_O|gpSF)HF!V{OK4*Wkv^8(`|>^qW+m|2 zd5e)X_iAM3*cL$$^=xecd9X*}lHZgX0c+B&nqNc-u+wi6(SG6)~RAdJH}b zRH;%nG2Xg-|bBzYvv>t$TuKv}yKY4eg$1rm=1KL-9 z8*IPb?1}JeJ<;G;98AwUbOpbFrVAJusUDu*jBx0n@tt{3Uk*vc+iY0=*%OJEzR*6{;HIF&lOTpF4V+RT6_hi3gAm14PfabP)23=&2Ia=v zR6a47$1DAPht*lN6pg!|W+E?vsX0UO& zcCE=-D03swOk}gVWOog%0Hd^!0)R{I`#=!SNG?;_FGh-U^*;SN8DS7MYaBm+e3GUv~+{0NXHC0fTVPHhXMiyDcwW2bayu> zUD6!_(jlM-iURKf-Fvg$`<(Cj)%E_*HO#E_19!L~;6MH~FkHYZUvVFr% z38aIJI}M2cR<8ajt0an9Tktlw41(267n=jP?R2 z4ONQ>+SH5DYd>&Qpd&!<&M~g~R>C(?u`|1-CkH%TQ73FtqtyyQ#lE228eZ>9{(`Qd zdXK=as~zQgg>6oqv4Qs`a=iEK!KY4U41#KkP}K@(WiHBBAGzmDb5q2^8voiOWWID2 z&^r)jH3FsGoTBN#1JDNv0}o*R>Hz@PV#tf%^I;vHNO;;n!73dDL?s@q+nYNHil%$? z95eH0lN5e2(|@+LPJXl5@hWU(Hm>eh%j+&RG?F6GtXZb_XAYagF94fPy-*rp#WbvW z*o%f^rC!aZRJxFA_w+2JmtoD&&l`oJ_1mq?>?|AMCHP{q)wm$7r(^6n)$DKk=(Zbt z2cA^)mTAb~sJ7reotZAbk(>S#j&)n1Ig{~ydhE?}eLCnRuz(8!zr5+{m-B(~|5@7j z)&OBo>t?C$|KO~rx+WTQflS5GAG17`tCT3xr6rqAm_EI&--mQ z>H$oz3BUaf2ZF5;L-GUWhCpjQbxJSrvPQJYto`8k!!jU<_g|LkM(m4de3biT_`Y6L zGC?nZHz@}Eo_XN+G&B9?O8*yS>Wxyco9%AbvFWQSgU}NX^mC@eX(uryvke*)T}UzK)mzMDg&p|;;R4$hE_+KykO1VT&fOB zbJ+Yn<0Z{sg7E9JdL76ZbPGfT{9eeMgLgXKd7mXx&Knv+Z zXX;BwB*3Id#DnyE{o$_$zEL=c0E7r~0RG=S5W)=lm5$zL|7KJ=|L}HK@U8pSp_a;- zEn%ddziM^K4~TvV#t}f*A43a#%vGR_4}^eP{kL)C+XncX-5gfm1QMKUEifz7{cKGG zK%p`rh>BO6wpnk?pUVs2)D8ze5fM}me3%sA@wH_rH!Sf%MPd9Ib;HtwJ%{3Ec7>2! zt*-zrH1v}AVh8GI0u4CDpJThRzOM8E?La#V&+bwG1vCY+e4w#^s(T5){;uxL-m=b; z_NBz~XXlGD?DJ+q%B3i;T!+Nd8uSCXytRkP4@7qcXFeJ#z7lo4W?PEsNV&f4?3-AV z&*N7Xi6v88S1nT0(w|IvP;gBwJFj=NeVe0{tfCeY%b`(cIh~uzR%fr%=sLtm4;bx% zd%0itkla@e{SFtrTU5pMcR%##T!y3nz1;&z%bQ9*DLuJrUmMFd=Q%ie3Q?7Li( zHgh&IBFE5o$08mCshU-l#~4N0$@HD24CS#!Q-c`rMryL(ywqz{ZQ9QXKX;cZr}Ruyw3qc$2?S{6QLznFh@UO{IEFfn3J&O*o+ps;WO2fssbi zx){PtZ9^ahB=Je~^E3P?)VGZMDSf`K_|y4AGXt5^@{I$jV#m-yrkE&RUc-|r=%gT} z>0mIOdz=obFi?Z4Zkdw-C7Q|P|m zf?9QQz$mi3aXpLneEH}qtzGHZCg_!zV4H!gZl`5qIDh#cPFiHaY5+blzW{hlsW=3-ipir4OB~kbh}`&Ewup ztDVsk59e8XMQ7h29csW`zlwmm)UfpWpyeAl1t+o&5^GQ@AeLtn^9&Nv!`ZNg;Ma1t zPt@WuDjIz2LQ&l9^Sc^Rze_!yBX~T~T2WKFOTpQCX~mJ*QfX87z0`4$$dedXj`Pz- zo7Cqk8Mh+pwtb@8o~>^WxSyVm)}<+bjaKCReqPm4=6OOD%Za;aY!dkCBBR*=^}zKR zIrZn0fY!N|;m26M)SFYA?Wisvy>CevyrmGs9p-rVLVunL;qEH^?L=I4W}yu9N4;-} z8q58-Ueeg;yOpJll+j+uEkRW3aH$I45jSb+uw8mcchchH1%67_$AR#@4QtP(QNlDL z%wz6iRXGY)AEYI|4WEpAPa?RsJ_FJ#-B>ZZPwhQ|VteM9t= zR&_>XkD}Cz*T9%&GHT}cXuRnR-)@)-G`%SytPukX+Q0GBmNW$6M|MJ{_`Gx$I&Qzl z%;NxQL>eq~V8P{g!Jpsd(dZ>$F{Nnd4|2W40bx^zy;g872XWZa8e#S2NJB^EVwjgR_YS2=MUv<}xB8sXS0v!)j{2g-%BXX2!B8|u z3^dDC>Jli}UKb`$En!3erx(a24n;?skww4oGG_4tdC^b62aC#r@Vk{Bno>na4aB@9 zu5Lv0sa{P)4I*C@LF3z)eT69tMpvngobo(FU}*(2P<$y!cbmep+oK3v9O;V!4JwBX zKJp>{YMlfse|x(WwVed9CJ2$4MqraWklE^+;JpMcMMQRS++HOd&d$#zG9(CWLV}uF zN$PP<*&}H4kWSr=M@~9mF?g@^B$msWeo^=%b`Z!5F&f#hPUcV=-;xfOf}yyF>}Z^5aQ_fiG`8!G4LD{~Yed15*Mt zGB5o4kw^fUhwl7f9Wgypwdm|LSWhDGzF-n=J(3{?!aYhG&AUizfW;kN+rrZ;kdP(N zDN`m8k4;6xe|T))0fZk&=;f7_b}|R1PDE#LcWNCo0{qOA z5EgpFhJ2gw+xwOghzri3+wQ%DnUSgj=u<5?W|p@p1=b)Uc)o?%X_99&k;DjUwEV*C zOoX5{xWho_jv7A>%Mjf4dl8o}J1D(4K+7x|%!U+!YG9}X1eto`12Msfgwits^iGeu z0ejF}RwY(dws-t+4{PTM2}cOPbeU~fD?Vv=&)+K)Rni(TJQlOh&=j1@6anW?8Z|^t zRVqNx>%cmJa^7Cge{hDq+ASB_Bzp%JnK^apmS^<6aaRSjJnW-q4>^Y$?wFgQ2ayCY z$n@d%Q^5$)QA`eAO;n3iA*`Bb6N1Zf8>=#iMZfu@pOX8!(9Db2U031iKMzOj@0w zGmlXh-+xRU=W|CwJh*LkhRW{i9*1Sv-W#z9dmgF1@-J2)^b&7EeV^t*kdsD=$6=~y zSx*%wgxCEWTlS0km^JDe{lu(es53uS!b=>P-<~E{ly@k;b-K^<$^p(nWrU^pEh>NP z8I)T;#D{o~M)!NQF?#C>3Xk~nhS{SXE?R_f#PYRWzvzguhI&*q+w&EBdTH=i~*E9!}KY zH!f@A`7VCsfm>E>ycD*Dxq(Q&l$Vt6PT+Cjq9KCdco#RTnl8>q@H>0Vx(o2?A`u;I zjP`@fOlyw??{C;G^=NO#c>%R1f-0`)>ozjg68c$kPfbJ?Kk!vY^O$|$iFCqQ9EX^X zQ=mO|3{}_vVCr+G%IA|~2swtgxdS)u3q?QV0-b%irj}wG_#)X4;LC^4|Opb4HXi9!05_8XY^kSA_4|v4C1zwl5 z^B5O7$O=r07V*6t7cn64#nUuI@eXWqqC`&!O5&4C=Ly0v;ywQ0|Cl-0;DbN)SH47V z`i|oOZjwOF8eFJKpj$kz#hR0wiI23VZ%bB)SZ|25r8Jb!w+R*M<*j&f$To71yMKlz zJSudsJ`{YPy9`e%IR-Z;P~aO~z=DZrHlKHPpm$|2)XwRpNvFsiKY^}s1xjbgM-xa^ zNBHY1(zRY5oRuIOz6d+I@GLx$vH;h&A0mqB@MKUU;S(Wik0OxFgkwe{jJ?e$5bqtYv& zW$__k-%!5GZMJtLVZ$@gLf@hVNn`kD*~AK>#b-mM(ZVEUVp@&mCTGOK)j=x!v8r0J z>d#_xyB_SfyM2Bngc=xYNE&C%A7?s?-BvHxP$eq~jkBGNv;P(+wdP3b4Q_`@Aa}~T zT1h<9l6YYiUosJox)$%vpU_N~;3t#tEHS~qAR(|JA$&F=@>xPuUqbY^gn&f3yR-aL z$nhz&iD@jcjs(*W<#xIBy7GVm69g6AtYC^BwsFj*CZxKW+hiQ zB)85cw_7E@=}UgAmD2evrOhg(?^#Ml5S~n6!c4bnh99r4p%>htF`|Sua=p&pAx3SN zY7+xe+a;F;g``9&F5)NEB$!O%o>k(0L)u5u*N6PCqx#}~p1GEaYstjA>44ZwA3v&V zhl7HcMNe>CYSHB10#ay1G;55`+rUUG$WCxdmiJvWgBncFBNK!q*=$f0KOrXE>d*As&dQg$U*Zcz z=!*=il9fTSgpHWmJi~#PRpiP8S({q8sVBqD=`=jUxG(0$USZW{lF`wSVk(epJ}2D! zEZ3?qrG3_`EPO*5y@s)Yv?L#AVc*!c4`r zICArvP0$6WGG#`vUA(9V?q|vSgXN@zT&yqzPXx`WLGDvoqGz(Ovp})u83UYlU+(}8Yw~(8wt9#lZZ#zAi&cW(e0}Kmdf(Z4sppX-PeN^yYI|o(zCKE(;uCVx zsY@RyazRx&Z44jHo;W6U>UXM!S7-3$a&arRol%sPke9A=1X>y!)rT?jh&5;(W(!-Bx@*J zYpT&{oj%2>pVz$g^v;{lO&@JqkAk!Fqv@L)n}Jc*H_+ge+!krlHf~c_o>&V%Sfsrz z+{9K_@Vx2GU<^TM3_%K+OH_|Bz#1$)+AVeei z786CgAug%gX?WC`?UWsxoOo~65oeU3m`I{!rC3x`x}BuE3MA&MIt4T#3v|#{OjwL4}gbOPFhP;=AWP1-_)%4+VUyy7efcH!jD;1*@YH zvReFKhMRKt!5((T>PCs%MtRucZCgf$@(3g>^hxjemE7-#hlt;e>CbQOFI?y^{?T7b zF;FfvP^mk>z4pReSHk{>kjRdcUZ7IrOF7dHm%8HtTVDTOcC)^hgP1wpMyRd>6lQ}$ zLt~-R6PEq76Mm(ZYP+>VOAEovKZaH*WH8^vlEH$6l1q1*-{lguslAl8nU#`E5N>FY z?kvm=wCx^>8UFDScJ^cVym|P7Vgw{Sg3K|ZAKikn;*=|{Phm;j|)&vfb~Z7vqzkD2jfTwOFQd!fWEC>+3nB?`H~6TMOkI{N%ho8rIJat zmPviA(IWv-2VLoEWws}B6}6Q*m7DICb{?PE$9rT(9NkAG^roGJ$6f8Fox^&&r$xp0 z6?(dmOAMKjW0*eROBFvML;j=|!#_ILJjxa7v&e^h?nXsh!3jU$MIjpE;WqX8aK{S8+{~^AY3vVX*ZjC{{CWrG@5c55qr7b zd2C7#Z-$%niGS~jmAe_q3 z3tDrfS25JQcwC`-4>yBMl|Y}2h!gLE0FQ3o6Ffo(ugtcD0>b0stK-sjClRx@>^9kt z1Tu~I6|iKXb+^H3b%k{Ws&yp~N<}T0`k)N22S5LkLhQJ*mv11FnUo6mlv~TR{nEzc z(&;B@)6N$gq-y<5pXZD&giTt7^+Y-~zw)Yf7~e^b+HvDvXiU7li#|YTDpVaEn(}1S52{7E3{jw zzgz9GTbs7a5<~yP>0M0gmUp<2vt)m!M1zj~9wy}i7Kc~?0UqYi27%EY-SMVWN@83% ztXO{^E_I85s&~SkFLRuCpAV8pw_o)&TuO7p!wF`_`LWlY@3MD4J8eHt;XoyPlQ=`T zoPd93yqWo2VCKWz8RwxzZ$!xuOkY>vokCs*dnnfaVM8GJ4FU}NJ?`85koMjX{I(;S ziu3w&eV;U_L56zuz6>~`u!86kFzLdaWi{kwiEhlm)lJ&V#vDzLTqAOmgU{L z#k~SwG(|I88^%Qz$AjO06-yn8Q2Y}0e)9xVPPyg1!sW5S(7P1TxQ{=AY7q9xilkm# zN^mUKNZ<@q5AG9V(8H_X6;!mk{YkLIO0vZP%St5cIdtTvvIpS zrzj%J4tGvdwS`$WPaRap5f%f?{l1SH^l%St+X;=)Tq=I1HTZNwbwQ6~PFyhH2(OEJ zB1p-zRb8MUOT434FdMH&KmQHMl*v_i6CH+2_i}dB>(rVtN1> zL5So-ZdhML(%6GVt*P~{bko}Qvy?cFWc6j~N7EmY3@yjsd%{5K+tR=b4=RX#J~!hN zsxGSxUr#t|l|!jMH+vxA*QouVx>9>RRPEB-J$CAyZETIYp2Ok;jWXJWQZZ~tf~`2T z$gRBSV_c;JMHPAwH5@405JeIRWT@W4EbDVu*`W=ou3NII$o6fWzYVHhF|^S}fMZlm zgT0o7%)Y87|5dzB3G^*Ho6{TX`^&5-E_H@1Xy#BJ(x)jEBad(U^R4c7PnIs0ldR$y zg_56XES0gRo$A*~$zrTU^%b6$M5+;!md5IFV$8(4IBUuUIqZEkPsPgl+C+u4I;{_5 zy$_`iACM$7i1RQ%V@nS)=i5#Xuz!AORamxhWS!sDJj0%hb#Z1`-a^$*>_0~;Fe9dA z+{9Y<)K<{GPCjYZuF1xR+@xuJ=K`UoYcD`eAtY{L}5JkguC&fOX54>)7ZJ1 zB-6reyXWuS{pti1o71WCUDvug8^7gv-f4A_2tyYB(stf$?L1+D z_k2l*hq=A9&-<;fE3O6}-?no+J)-G26z8HWm^V-m`M!evh4bDnW8xUnto;rVy z|JqB-iz@cmy(}wzkDibG&}!uJ1^SOEq^!?XtQ?BgPH(g!xu+tTHC!Ar-v=jZyPLL= zaIDgtRt{SUd8ndFY($Sqa4F+>NMW?h(%i=QuzCpwo>9h!zQzPue3C5cuwad9W8#W> zNe&lS$ir%+LJ3WB-bwL7TzNw{mL3Dp<3Zmx?1!CEaP zjZ%1WO}}o90B52y!k}JFhA3F(GgBIdAU0|BN?5!Q#hK+JX@u17`=~n+pM=nQ2C|=k zi@uGq&=^;;eZhE8{%nZNEJ#+fu{*AYF!1fgRwlhtW>!6?4_y%N~bVOy2Gpu^kWGq}$F1Z<~WUP9GUB;8&BUq*H7jv>|twbR2-#KY#jGu!7v2SSvS^0L2=!p{f{4%0vQz#DxxGkY$$|9~{Tm ziM8Akr9i^$@;qvvk^Fmwv!W$gAch1iCfsLeVs+`h2{90KG;pk`sv52ab-H#o$cu5N z9i211uxJk&B^UMhA%E>tI{W=zopmyeM#s+5$1S_MG;2M3KQajwkwCI?m1t;Ors#eg z!5m)T;9Ffi^mX-Jm#;roc+-E);$jZo^DlMOd}TEjAW1Yc{W;Ak4rkuqRW%>Uk8~<$ar`jxWuG`RFS6WS} zh)Q4PN-pRMFVk%~c1F<^sFx*9yzIo^6=pw=G-AxR4)B)iB0!^ejhxjjEyAr#6ec+Qe(17tV@=*DBxbs3%>|-zmZ3-luB0jE$Y~p>n&7cv4weNzJMSD?B%hBCJE5%EY?Y%p z!kry_z+6i|mlbIbF-a*ye;r<<@t|=l;m+z>m0_30yklC$3jys9vKUXG;-xtQ?^*U> z#|q5O*}Qu1?94wWXJBuRjjcaEWz%tK{>pd9BH96?Z2sS6{TJiz(f5c9Im zJfD}a`UpO;RfO20v~%|eZ=iJ3ljK{H)4}IFX~OMY4L2{^5vgM7^T>b_$}R%dlRD9u zokR^fXChX2PtbYNmSn{D)KRU&PU%*6H3RUBO~5OxV&%`#WmWZ$EH}q{TI*g?-KhMD z1k(Ib@D)I2`l^-hs_^Bi{Nwjx$?MGYwGZ>B6;39)_BSh>eB#9m;TnZ1q3Kpi@5BG(hIZxFj?HTp?HF90SiKeeutG*Ja%v4qxHl;7}`4wVhx2 zFqgezzX7y0#Gh)!{1{PeDP|gZw1<{D^A`GtIi5J-ES!2e@b>DSdz-j82DL^5f(t^Qfe0RXkH z*sclirN2#?%Ky{}0jv3K%KV+3pqFU+=aktV$}C24k&Ve^IB1KtL*ISXV+%l zk&0`D?6Mc%x%l7A0aU&3745m{Uwh-3CoHIC2VEB zBB3Ju5W?+$E6el2HBh@T*Z9A%iC(o({jV!z|KCg*M$2LMe}zr`i%3yp75Yo0cnN!J zA1~Sph!id4p$F0QOE#v0W?L`l;V+Qc4}Zc9QLkZB|9~4Fm2FV1Y4(tJ@R|TNQ6bz4 z#*WQ+Foyu5dcR~i=4U6J6vBhSK1rnVo=3~Yuk{fg!l@6igqxNPPiN>x4q|zSaz6$O zIde-X3#Tp&@ktp*HGI;-S{Oo*P<}eWbUs!!-HRuTdyCaO?BvO#w*Ay`#8HlGk>csn zOADmFpBfrX=Zf+)FwX&(d3Z4HD9MHq*PWasH8wtH( zPyDkX*t+D~b&t^hw&39JwMaKGiGM0a|9jLtMOoX%NLC&eHGuuh(Zh>tc-L~(7ykXz zB_@DL1bT$}!exhB-DQvfd*bGdIiMKjkQrL@X}jFoyW3!_B#f^d;N^+x@2cp7`R;VU z2kU?6+5JCJjQ&sL%KzsxWAvY!i5v_LXyw4pl>t1vyBhBO{WA(zicz~v8LZ>I>i?h^ zJvr5FCJ}>P2@Z-JT6Ol=UK8RRZ636*t4QMsVxTeOGGW3&4{gzL0AoASmynT)6A{cb zQ37Tfm;ydr@sVvCwZwAo+A|>~_^5PD{cd=9Fn$;2o4rp~3>ePK;1kW5Dv8fax=9_k z&7`YGpx1;S-hDc+5W{7Zgc|07u# zr0RhR(?1-c%)KeUvAwU$)}L4Z-!;el%_g06Tn5*Q=xF!5P+>TXgX^Ts^KJAE`T^hw zo#Q~*)q4LfHNVZfjA80>N1^qH(pn`_l#J4krf;W*Hnf3&NLL<&!!!eQ!eyUafRLdC zE?5kvAzrAAy(5h1JX?kmU-h`jB~1}WVDLER`848lPs&#U$QtWLd{I`UsRNl+T!%Rj z&oyv^Sh`85pWnMyh^tGR{7FCf7n}6|kL!OX*E{R{z}lNO>0&jmDFMJHy-K402Yl^c zk4*ND2UJu)0xh)UbKyI+yPSq)se*X82hS5Fu19$jad-v5&N(o%ZI^Qt1B42niHzQ2 z{&W4m2^*AVb?DOzhGqrUX96(L?KhYyFZReJQUm*CMBf*aH3>Zb7@k4=BjBIF`WaciGnwPnTKclhNY!P8@q00B3RD1Jb#EBhEjQbmOo zoro{CKrL1mwN`enJjUmmS!ff(c5T0Lw~8~Gta<#bR*;XkR4@7Ridp!31L-fPf7O^EDLqbW|Sxfs=FU$u0=QqK1$wJfbhRDD*7e z!)ktcJ~*4wT1#$Xh0sSP##+Q4x2}5wo_~LzsdfY>zl*dd3^e62g zUpu^si+gXnj##}T>^K*u+iTA#370`jVe~07m3RH$KYQ_p*US0>Z7oKzS&O%w1QR%zTkOpfoX6~Gajuo9Azg9>;^k~9F}(ndbM1N#o(At5*dkW>GV zuoq;;kjQ{Xf>g(jb>jjgA-GRTF90IZcvF8Fn-l$yk+(e+4o8~91O7;6^^ z9rdSIo5Pa^R7)9k?6dJyf1eorOb+?(EtwDz)@_5Q^3Mq}^itwDX;#kCL`;3WX<5h=Gyz&)XtXXGR#_on)Y?n*CFR6L9X zAs%#1>W=TIjcL7^QxjmNv-XwgMV9)CVKs3##c4Np@8nCrjspSLN$QBB&U`b00TcFc&Eua;4EN3~vk_;0q z<8@(;b&-?GLy{W-lqev8(g4c;bAVh2P_V3J{-rPeu5l62+!stCGe+ZeO||^1v_Bf- z#%=KaJT9Wx2+>Fu6sd7^h7&;DJA*Wzd8*-8W!{aVj=x~SwqVTQ1A~ljG@I}AMs+C^Hl<&JdvS~QBAvr zB=x$5WCfJvi~Xz&@#xRRJ&j8e{qt)Z?vzWL~p_XQNSK(BN|{Ky0g3K|7Qy zsZ+ByRSUqcQbWdw9;Lhb5ih=oaZqWKgZn-xr^%)7hl&WF4v=SlUjLh;DAxxP?%&ca z1|nv?aX7W#9yU5ZYy#W{9{pxO#EeBo#vP-{Wpb1`E3kIx`+bRtmRBaZlqvwLx>K%E z7U-#Xyg5QM9juVb-BC1H^cM&LfU8|!a;|z_TU-8m;gcsHci*?2zc)3Ag6ngfZ08PTK?mkErYfe?{R%z?ysx)Wv4z_l~ch>Wu_v5XI% zeSqAv-(HW$zG}EI4Gu8=gJuE1)gJ%$!o?WPU)MZEV^+<;o5&KAvF2x%@u^)K_6?y8 zo_!6Idaw@RS4UUF<@ypspYzhXZZHfyGBAKpCv#oJy-%qnHiR|W4h z9R?3LG@^ZPa;!jk-L%~O?a7v1$SLvjs!ARlyW>nr1hN~e*i|d;(2Z@b-0+S1@BNQm zKH2~0#D^QLxVuvZ@CW;ZyEOo!g}E;ipnEXSq*+harpncEiZ{4?-U<8WKpXFUf^3-- z=-RI1<9?g*q9LKEq~#F~4zup3r54X9n(>ERpp1>|Fu~_M-*~utJzfW~%GeR^5qHqZ zSGg2Wf9PkaGU`WSW2ifbtVN0Zp8Dy1iw?IpZUm_t0F>r68}L`q%V^t~(Yh0tc71d2 zAo#w{nYMZS2?zskKKHmWsK0;xyo=J}X|Zv!_yu{1QHcfxh-tY@QbDsG5Q2SJ;6O(5 zn;d*bVncQkq-OADZY#?3?j(2t*I{534nHM9mde0YKuu_w>G$(a^HUNRm>S>}B%Ky< zeK@li4P1+Q_?MaxzrZvW$g!`->AC=e`q#}JjVef0f15tZ&~YjkQd)1dkz%4RZ4m=q z=!;Bx{*Rk`KKLc)Pa9@|e%S16jw6;r;dbuw`8ac4y7}pLObxTDY;2YS(5WPR^VkCe zVw{7&?P?|e@s4|g4|_!bVYv%;V^{m%QdJhzF7>Cfjo-db3ox*;Fh`cRN}W~q98QU8 z*b>MVOOI?U1wyqiKKF*x#Ag;!*-SwloO%b-5;?Ezs8(4Zg`bg}R9}PtK9bY?Y}DW# zK=@N=d9Ky1TAW-hc$9W>KyLD?%eBBwNb_hkgH6>zWNqyPOi+1Go2vDEeCuG`R59`r zdw01C7j>OgvdYNNmH zYCu|m`}&Uib3AA+1X8r#g88wWnaqF+zG(KlNw-3?Bb220(@c2Y^%yg$m>2wgJXmcc zTEZil0tAqtsc1H2*earIJ^vD+0He{So9Q5`1q=Z&j{N1ljRbU%-Jl!Mi)AqNKW6&R zR>T`Iy5HXHA26nc8_|nDqt}0IU;ol{&kivl;cbwxskKu8A?$sTh&+6~5PY$)vuN|_ zb+7u%Q`v9muEs4{b>&MOFZjxV?d$GTaPd93tL^Kb{jtECC1WXo^FnJ4Ulgc*KUZ(U z$yhH~cksUb6#!!r+T8c<2`T&WpuNm#{eHB#Yu}IeZ3bg`W!0z67B1uXdq$TI7w(qN z`gQ6FgcKiCfHw>~?%$3OxTENcFvetY8Qb=VPPB zhPWYH*TE1GSQ7MgiF0GX_z3hg5d7^o0or~nHFP6^uZ*M()r&DzWyS6rtA0=@!=is< zm<&CfW7LThlM1Kwr@s{>-OZ4$%ScR$?`1brC5d0c?w=WrUqC`_SOUFE5=X0LF(6u- zKl4sh#TUg~h83Hd+7_X@fe`>hshYFxH}f+|SMUGky(L?S1Fv?aRN>x(Z7Sh+bqpVA&x?Tkm4acUGRatXuLA znXg(EK{qH_&y|}KzKUL`KF7YvhKvMZfkr@ue;tdL+d2N94zs7*7&&d;26ewIWR^x3 za-=Tc`Rd0X1Zp&*O55ukKkvAsr)QUy+Yl|0jmX|9@QE^wn|nd9@+O`f9oalIcC!C2 z!FTvnA=Rok&!J5!-Kfvg87tkS3D{e>(8Q5~)b0~Kcq}W%$wyS)9IxR6ZmL}2#1=WZ zb@btHh)^I%_60bW|9MLKaEW+*Z@S7W0;i-Gekmy3WzS}4zMX#k9Gxm;;5kqOxG|S(yj#5+?Q4ivA%u8d;noVsZ7P{E7dgS z>5x0DPjBO*IiszG@!;1_8kMkXDj8wJw3OU&DrCk*(dh92{7&^aGD}JIIC_#oxauaz z5ql&j3W1x?=rzMEd|pcEn9PWOpihi1Vzl~>jur=T3=1R~d!hjR`a()cBcq?5HU}RH z1L!zEdmC!4s3&Ju6!&f?YkXl77vv@&#{XCFml{kH~*Pe zoH^>dHs)OC6+aL0Z5DriC$#xMb{LE@1XTB*7vIN~V4_q8$-bUF{t0_m)v){W6ZWp_ zy8mSw08G0m&$J4h%pxUGR#{pOH23+*^Ul}yJ`mX_Sx~Y_JnlsLgvkdOb5J<>)KQpj zP7oNNtQr2z5Q(UVX8XG#Qr0y8w{_SNt=-z|ZOqjU%MbeiLAp|;@vF$bxrZ>1YT9$< zAIGbsCt)~b82fpR_?LC~CKT`L8XYal?UgNQX6ZxMlp3ZEJ@o@wcQ;SA5xgl)PPo=mrtD|1#YNspfgP2o74 z8XxrYdx3P0zGCwpk=I>BjiPEPbkp$D_LP-r18xrE=M`jUb?%Wkq&wR*}$@C$d zWR@8zye++VH3C&6Zw(?xMxVfONl)D+D!ju-8%h1-SPmcI;j99Ab~WvWn5GY+8T_ie z6;8ND9O;;-E;@I%aBZhsW-?hSngsmILM^5=DjF0EYqZDP1gSRgbIPgss4)`O`1yUg znMA^9vsnqmtPGa5N`)|Ce0sb>M4n7by0A1A)2#gDNEjmNN#OU{;J^YYiA_G@018o%wXjqJ{|jXxmJ}MmTL8`_(wWz}Lw`&IfLZ=1i=5%X)qF^wB79YXKDR3K z-xZ=<@df{xI}EyL+Hx>ltatmYT?23o4CQ?FYv4G-0<}!WD(rzer zO$%~VpG*ia8+J4j&x5x`YpY+GvZ>f+WE+O@IIn@k?O+lqLt-!J4W_XfY-{#spf*|+ zD>chCh(nTgHCtkcG*9<(=a*`wAh%{3KK_)W14aT$<*ftAB`4ZpJNzwOrFIm8l=3$} zc=pP*QQ7j!J27zxE4m0wbSuEOoKh-!$VK-i(otZcW_`@Bi!0+;s+#Y`b9DTu?By1( zA??N3d|2_0>~rYnci>Zs<6*H|^3FqlS7e3gK_p7fa@LT3QIgwSc@v^u{J+J<<@%LWL2l%0_O3^8~VF_4u9s0&huV z>UUV@sK6E_Jkc+M^pf%S+d+8qsJ3}ktn*Ee9B7LfmK+th>N$kzFJ z9@7LG`UgoSw1WuAP*w&OX}YH7QC ztciPaIQI9X(-ARiZ&}zO0A;@~JB54RzjUruVM=<@&kIfuI{BjiD3FJ>K(kEVdOPPo z6@AJ5El=OY(YIS>^X*Cre{CoJOP5wDOOZ8tUBR+JZ~IFLPh3RFv=V0nRIuoO*DSqR z2XZyO8Udi#Uqyuw?_z9LRj4(%hzAQpjAG`{s1uHe34PEFMkg6ScGstwkIPgh3SK@} zf*))q7sn~Ct_yW)ZvlcoXXNGg^B}L0yr(Fr2{+$l!o%=|`;RTg(-qNJQ^_XtCo*mT z@9bL=RrA#HxeMa-nqoLc>MT|oOZra=$D1ra&)E%Vl+LtyT~$cAWvKXpU8jV^JsL+~l*a%nB2Lir}-8H_cC!JTF`5cyirk*Yt%r!6`cVf(LH z{$wh3B#!l1ex0ClEG`pBb?k|$#>M*S>sZZCt~qg9>eu>LnP4S7%=U0GIrQu-2r9lQ zg@!n?Om>QMw^d%Gn|7~87(&gfDP{ya*a+xVl!gMN{i!+`DCi`{A~j-(KQB8{!J5bw z5ZO)m$Sta=u`lYNM`%!*Xr5 z8)IvA?3;u)=Hl*ja!wN1@$&b7Z2AF&UE9tX=QMTC^voB7QIm;xi+dPe*!m9g6x%pr z-``6ryU=a2?f4+}y}XCmb>OInHu{H6FH_#aVLxM4XypKF-Co6OkVBwB+xMxI&+jfj zr5p~6OHOn{;6qfaN0EjkBFAo14joHjGf+N&NF!Vy{!^38wSOM|^+-xezfGjgR%Ph9 zcvw&OpUnSw!r@}qbAI1z(P?wPMhSoB(j;WT38D1V5&&)}vaw@*OkNc|J!e}Al@2ct z_nSB2U5m14%_O{J|318)6hNg7pM-A8w~?90nUtG?64qrvD2dKd*EA7{U4v2m>}JZ_>smKENw`=KfZ9!rae0FFgb9SSD_GTCzh%9 zA)I}G=YaQd33SEy>=5NNf@6Q=GJ-H1gZt%=uJMO$9BLm7Ac*Nrb)a&hF9hlEr&aC9 z0*BtXq3MWB&^PGXhdv~O>BzjjZ?K;qzM{s=K$V8R#ZNl)Wqz1}uF?CJxbe`BD>MVs z0@^_~cj(VIn1Suu+d*}97y!nko#9YjC!%%f3Vb{liW}eC$tZ9Xq!gM-mZtvr`h+tIs;@@UXm z+R5Blj@KznR40juRm&4Z8MT#llAxjKa)!Ao$*Newd?Xlhuic3Hgo~u749qL3zS9Lh zWX|W~OXK0KeeD`??bJ-gkBfI$m9Z7m=)PV>v;Ur=`FWQ7ukKdpj;>U`gzEX!+GjAM z6`-hj%SegLgKyS%@=y3H@RU)3rwoPT{^wKv>%?x{Wq@+`ikX=8Cn4?sQY3M2_*ZJ& zZph$-yD?SnmQj&<_Rh{C8;EYsz>*D_lP|$=#XA6r@uI%|2-1U0L*Vg{-*LS!?*9Kr z+g}Dmy|w$}@Gx`;Ln{r^DX4&i42Y7_l9GaSBOxH&(kb03NOzYAND0#2DP1D-|ANKd z+kNi){GR8$o)@sztaZ)0u1`IiGL{CZI=T^}1u(;^f1eg20AB8O1(S-!>OPzrp>~v>64eb!7Nc;D1dCC6ff8PDE=Efs-Jp$; z@gI#3G{C&K6ss4;Koe(Pj;bFkJKzu!#)-+@9%nW-niXr+nKKfA3XKs4$Gv^@EWx$? zO@em5Cy@9O(L*d zU!aKT1b}M1KhFu|hY3Bx(H*&%BiZ|vo8^7tUi@ep_vmI+CXCB;h0n99Mn*6K<*pEMR{R#!b#%ajHy>!9i;3P% zus3k#J>Bc!+B=H}!7<~x=@2pGS@(*%(DoJ782QEa-jh(%_Kf? zAD;ANus~ujck{CW+sf)_VvY!vv4syo#e^jjXT{`;iiD#Hn-*9g;GhQIb2M!}O=>^u zNPPcz)_m&0?2Oq>R{I6pb@h{lsEUM>c`NfR4gI9DfglzQ+k$&b*@RmsYdLo3SRG$U zSsVvthNV`AP3RuiY+XCd;QZX6d3d{L>O|GSrrkK`%<4l!pz>bdZMJW_gXo0L2fgII zi2`{3hIN}IgjnZWd#1)rVw&@2n7quG|0LeipXdoEebx}xTgX>TFB=GS$ z=qZR8L;`$V4uU&_zwl=Scwj(r2FiweI$*3g(x=hnhQ`9$$_=^M7C?FzjgNjHCBlUO z=5Qvuo!$|N>jnzhWulSvM}1l>X}_D4AIc3!eLdHDSumEyg8(lG>tqomU8hVlhcHm<)OBG#c9ZE{Fm593DEb&=|w0f@Wig zo!%J3<2G1oFaOLn5*1~4P!u~uCW8}~>RO0`miuG2K!P)sC+>~ZIO!&js|Jigg@@-k z>gadGTp#O(g%l6_D=>K;cABx@ILu)2W>xz(PW7-*(VfY(40lAlQzOY9p7}nJtA)Jh z4H&_ok+^oBdas9-Gi>Cu@$yE-gy&R_0F{PrIaO?8!i}d*Tdf zVpyW4L>Un-ap>nprZ|mJgBgZ#6JWKntuQepYEh8q(U+)Nnx*?a?DkFL-4e8rL~6mX z@djm)FEPT+Yc8-2w}dZilesTA(s4qHhjN`wa$j6ywR<_4m_Kuf+&y)U{UQ$zX!87R z&ny>4UGhb-DdhHwhJu6}M0Zr(ZjR2Y@LrQ!=`;B{IxNMsxnZZ^O>`*;%FLegXD(m4 zK!X2<`~fsQC=$b8`7Emo-vvQ{x`9TVN&`UtoI^YG{LtkHu3-0XKpY@fkTdX&Enksv zU0$dMZgRkd`Xe9t`|t3L;%k>_YzhYEfZzQ;&6`DmT;0w~iWsZ}`r>`bE$CliTl4E;cYl7aYB|?Xyq!Df4Qk z@MLG%pQnbGQ*^WLV1T#q>$GylXcf+S+hZw7zOBs5Z)d&{P=wey5izs%@;Ds!mbR1N| z8{>bJ?E&k41ao^4tHnI<0-z;Mj+lSHrID((1(TIW-c!HUP4+v#RXJm-9gywSGui%g z-8N&vnW6Wkz6aj_i(fU6rThzCt5kaMJplZ6M$5II&;3h6{w+}LA4}GEA9>FaqyM{- z^;akbO_Jg&l=6Mt@ZDd3_#0tVkxqONxdbP%1F#t!H1tdsd2CSI>SJ=njAsT%7%@lGX1Ih>LX7i2wVqJL7|P{*dEk zj(COHh|ASGf93205oS^LLR;ar5)(V<+wHIYRTB(%DW9 z9Ub4fDSw5Q0|+m_?%}?&@RxOqwO@}aKQz6YJhOrR?u0{u@0Jbdg+VCU-#cNgCWhZI zJo4D>&9U)qI-Y6N+_zsKN2X5#LMiah;iVxHvY*rUVPAsV4 zhtNh7e2(fm8kX7h{fBKYUD8d!@t^-ZK?HYS=HndY8>bICSChlu;&!=`2HXXWmRt)r z5xYvA0i29LVsMuKa`3RjuKw8k^`bm7Y2(nzcPm%8jMe=Z2d{c@QGN-3{u}DdU+c`@ zAlqMcCgU7u?B)v7&g^@cb-~2$1M*=QR8Wi0bE9;l*Jo04X8U`p&qcadymjU_L^b^~6yGCYl7#eP_LiYyqk- znK#OuFIAN2oF6R#eF%R8^++l|YO`JcyW;LoP)(oWf$2}568>l`J0n9h*8g3PDqH^XRG#_UlieD&#B4YaG_f2++1CgT9f}0cR8qK4_Hr|b*PKDOmjkT6 z(knboZzK6|FTS+*5gTdgr^5-I04Dg5)MSw3%r<{po$625L{q_@A%3z}qUl&MRmt141bPcc z;l&b`5iie#5w!JU>o%JwU;MqAy1l&~5g=!K@PR}ADKUU<7NX`I={dWydT>i7Q3HL|Cm8lGO2p>6T}WW_emX}6 zii8*Lm8U&AP;F~K@<6qn{^t`HVl4RkiOXF?dO2QHFbKdGQA3su`kR>ee`;&eev66! z__UvCD7U~h^CKRj{ux5|x4^+4da;`liT^t>@pxX{RO7>Q%*0z)!W^yvzj$nL%76Za z!GJfw78Oq>_C-)*AZcN|*&ci;Ci(HK$Ge^}*m)7G4MdmGiU$HoQ5R3K4%Pd-rzF3h z^>`UF-rU#F0>?^!1G5(-2*xwIZKcPWI)88FBF~YQ@GI@0(_zlADbnB1`k&f@KdrfV zW*}QWPh&H>%s3$n*~;NDF--`28Su2ZR!#PUocW)BVHE!HlI=D$|fHvW1fQ?=S!CgfN ze$TG2v2GykW<_3K@fHc1-_o|13<pHIsBmeEhvAg`~r8FR5s z*S&&2BE^W=o^EkRXL@A9%|7q-BAPYoURBXzXDI$yi{Bed{rAai^DlTQ^dvrU$=5s$ zj6GN#&Q+_(WFRhIA1OB`{O0xKXmh&WWBCP>eLm1VMq-Y{->celIV|LG89j4&GQjas zb-KqnM|^WK5FHkQQ?x(2EidLmK>D)Iv3Gm?y}opVMGXr)4oKyk$*&Os{zYVx(q0|i zv|E%Z!6dYgUvb6*<<*iRZ}aSPN{cEzdu^`+q=nv(t8qAU zy9x}w@Y4;~A|PDSLT90eyt>A@m=X4@;KPE284Uv2OB?T_0De@-S@ehor%FGS1{4ak z2+g6Y2v>aqy{UL_stk<~q|eAH>DW?4hI(RIpAp(}_Myt6& zZ^UM7-pIii^Kz3}=oEr(FEP#+RPKsDW0FTmri%_k(39ZB*r7#A;^E9&f4H_YvR+EG zyAmxsQp}TAUTUV6$-#C*B|dj%j)MbZ$0%4+vFV5Zb&E_v6QbXmN}e2 zJ({v|gnc}kwmu5XFJ6Ci?Fx#=ju70zk84D-a=_8b=CqE>G{xHxLv_LQNd6y zqs9_S)|2IU;&X#x`igU_PV9FT)MJi5;}z>gErbdDC~U}IzaWP_-y0CbGUxl$c2kc*!)fM{Xn8xuzjAjfK}AO!>za%NJSdGY|7vsg1Wp>%1$XPR zhWrI%Elhdf2K&?0apSrrz}F*^z;UA7Zihy*T;vYPgCyf_TYj$na9h7O0bT{u>84CJ zG!^{1fG_(F{iiJY$DDzN=sMqpv1>w5B{%gJOuVl{d85U;?-QRe5p1Ydm<~tX<-W@> z=>B4FN?qLU-KTojol}--i>=Qs$T!c`n6-*@+JlH6B%W0k>vp}yCO^O17exHgSDh4( zCCui*Cj?n61(uL9&~TxMM`C`_kl=W!wPvenU(nWf9YO7JyXL0-#%Pg;$lelPyht<| zDbKd;QiH}T=hH7=)_Z%WUw!2-LspnekbG zbMcyXz_oVYb$^$0#OEW;<;Surrlo^Y z=mjCXJWM#bSSiL^j}G6i=_fff*DTlUw@a`&F+?fp2cGsAe`z>JnxHjbCySOX@gy+8 zwwmEQ+iaQh7T2(T!#cX=JkCS1(>_}-lG_|RdOM_=LTRC(s5SHTZf8gFTjN5;VdC3) zkg*kxZmw~Rw>^L_+p{W~VcLgakZ3=qe#6L3LONWFexV3;&2qDqtIv6AnjTc$qT3}919y2jN(!2Fw%MAj1;C> zrHh8fM_DG_(gATCF<+Bl1ch*pGElfgzyG2vibe1oZ5LB@cN#ni9TLcZqW$^}-Q=0; zuSzH%A%U`?Ef^pZb|m6wZ&Q*9ioO(p$!(ynt|(+=n$?ZzT;|n&2p;v@(0l}l){W0t z%4pz&J4_%#l>M9h5B=o2*@ssI&gPKH^gEHQpC?5_!I)IHyq$KiRN%qb6p&_;9zjV&g`S>LZ~fFPTRu zA<%?!NCgTF1^9O3B${m-JV9r&rVSK|q(%6Ej6w_HD^Ut6>|saA8`Mzb{`F+x4Z%_b zgf#-V5qE)CvS^^fc|)+lLkMfOu#fIXS1o3Wvb8L)y*^h=-WX!g3N(PH@D>7}vfKDt z6x?y$HB-u%rgNb}kG*FSNI`fVmNs=xK+PmKbhPNiX(OMoD2?6hj2WV{s| z6)NJg%!0wm8YtZfzrw>q9GdSK%=O= zXpxKiT+kLg9^BEvwzd`W$CN-r5f${*qVrH??1+YpG%-2T-6Vcx5bbnKI_AmH?;o}8 zi|cHN9l0pu72<{$q^8Q0X&A1J z1I>7!+`M^1=@wFM4>V9guZc+4wZehN2dVw*xcqRZv<0PH4$7!7Zg`=5uUN7{+I3Or z^b)6{6J`MxX(l`3S22(g2y7AFc+C`rbS4L6_kx$0O~qaWAv+lp8zktt0)+<^md1D@ z>KTNhj(FRfQ)cBGo{W7^%qkx$D|`}hUz2wn0Ty*wPIW?otxhBxP;OJv_$}YUS>oxN zU4l%&=FKcR06TM_ysRW}Gqjy%a=HHVJ#)PRTb2Q_{+EQM)1)T$574J}{VSx>CktMZ zhkabBCIkpY5fxL$>ZVBa+Up<9g(&J-+eyplimHyP_JB z`R?;;VRcls7=cmKLT}VL*1fQ!T8i^R-}e$a+nIJP#AYJoMzY8}`ze8}-a7$meDl{o zDYtXi7X_Ji&l7#+e$S7z8*In7K!K~$A$q?!EUH8J6!~9?DhIyy3zat(gWTCD*`jnYy)n9YT@jZhn@(?all2W%)9F_pHM2OWAQb)}V-gc}=TYy7=ppwEJQyBL}3e~1v! ztHwi%Sm{f?6-fKgsFeOwGCN|mDEE-okh>DLSwo%TliOVGU5mxQ#I#=HFYd;!Vy9r7Qn7U&Z{vA!$ zbwwe~`Kc=g8%qD^gD=xk(Li#bDDVXtEi#+cS>dKhj_GZ4e)^b}Sby zc3HtcoBB&1{5DqlQs--2cm!$q9{fu$KR@+x4F4|!hXz)8@eAmToYD8M-_J}-z_rVP zLvD3%o~Ak1m66QF4we6RJ9Np1U^!>v=J;s<^B)lAzxT?2i#SK$8GcZrdpVNXeB$yQ zZ36fZ7n6b-0#+bj^D4RyObVWP;vk)pLQaa*5D@j1r@9@U=k(a#^|&~}0GAmU$^1lG zIeAo)^G7exrjIohU*4BpfQy$SnE9Kb=D7glt{kABbP8Q@=6f)vG zL;`-25B}>x3hUEU+v%;2->y!_bMKn3#0TrQGQC;VaEnIY&Hj0Smc&nz^ZGBg=dEjU zlzWDf-8IUZ^2P% zPy}uUUtFa(Iq!ZcUIR$~G`n-**aK`qzh1@dQ-K|O1ttb|?C=j0-hZ4O(rMQ}kQl1A z5q}U@J}ovRLXoS{eos5Udn^5M!h6Vs<$2VZ3z$yik0;&+Oa}fUfdsCW2Y*1{XID-4 zKSobK4ZC&KdzfbIK?mzk?_tNaz8^dGQ;Pm`+9|caEbY<_;AtANXb0;9@ZjI7d_-U? z62avE{oz47qX7oL#I*m@H9~V$JjVVR)?wuQ|Ka=JwRnEOA zY4dTa<1bYQ>p^+XroU4dT*mR9k^DB5`SyTiYyRlhnL)T1U4lRq@HLkkh5B=Fi*-(A z@FfcBh(t(>XWvWM=7&xyHIZGI-0Dt%=uHw6+SuShchBmKyD#bIg#4d_TLa-VJ~eEM z7vcCK8KTdG?snQFf6BfhExFK@n>5=(`==D*BJ)Qt=xN{2jBFOpAaBS!C_pYnt7TMX z8&vfCddU1@o6#+=43qBM5mLC=DT6pa`Lo_!EypGKZjzeAgRfO6OygaVKaY(t-tM2s zzpyW;t+cFslBMy;SMg+O8DUbq?Xec#UXocR$@h)Q)tiT5Y}-?~2hO!&k(7;Veep;~ zF`2He{Y=A(bIdeV>r4z{$L^K@3fqfj+%{XIjtu69fgHOBWIi=wptyibqmpJ*HxMrZAS8!Vq%C!GAW^TR6v~gl zhPr?eA;N;9BzLl)WK;^;$q1q0OOj}Z$gU}jrh-dpA&(dtjO@wMQ3Z9W5%3uvHV;1c z13$Kq$)t}uoruS#ZS6EWRe!=D5Mf!GcBn73; zU*^VQjshAu7NgTZP#!x#CW)k|Dbo*yf5pJXdP*^*5R90z3GF=3-KyRwSBoo(n6%B2 zm5-tVR7#$reG%}Jx#N$LKkE>p04A#t^WqGV^|)@c0lz zA?m%SGST9KcM+exZ!cXFK9NE!^9J+B@A@Fj=%+X$ba>x_dkx3#F9#~L!jD4ZSyFZq ze~3d9@^IMnXi|feAFqmS6?P3*bzzY~hB$eR@e={s)I`}6#!&f`G;p9OeK#qgWC#;a zaIRvUz1`NyvQS1un24a5BxE_(43C@83%751M2f&>-21T_t4!PzDMOZB%rbolw|M(%!T4CGdwn8U6q;#AgS${V+v@m6@4ZYp>k-1Iyn0SWi%%u#+y(j% zCgaxXH#b|}T_4%EHg`E2pVu5cKUklJogKj^!@$S&XQ$20f_Unc&LbUM7h*fz3D)|M>fATN zrHfDPOmRo^xH6;uA=yBPetZYX(Qy-x;%-n>>rL`9ln$wv1H80nV)O!HopP~O^l5`) zjIzbp(b>8YIV7aah*T0vv7S-ocnQpg4#94|J>)nyQp6M;I(3NlVniuvIif#wKet7q z>Uo`cCrj+3k?LOTh;D|uiJ^q&Mp#rm1|9c%hb}*-+i@$BSv##F>BA{$&Xxr5I%Ot?f0iF`s2CoDb?5<5siQ`aHPvxZ}Th?7pwZzw3oBmai#P9}H0p_F;#Y^ zis;27v3H_qgX<*J_;CkY3ha7}((9TQ*7$3b$sJf_j3ANd^;T&j5%eX{%iW(IOk)ICG4YLY}AI<69!T zYD?fwii42m&$&kfuZYs)O3!En39N8@HXc#UcrA%MMV(44jRqAwWqN!pcYEe^4If;D z>8#a7)zO5YR;<@A7+LJ4n9Lv_FBH8631f5$l!4#3{E`f38rL+KiN4{}@BTMJZ0kCivDG3zJtd5doEi ziFusb-ToTveQx+#oJcF7XXFas>7uWtmp{avw3VFhMnY1?Q%U>P1s~>@)@*M?Ae7h? zX#7Ix41CmcD+RO$wc#*0hmvs9NRzqT@kAq?iDkBCQkdQU|?1VQ;d9{9Rw z<`|>tV8R$JTt}ot_9jo1?3>}?iF~&hcTbQg?-O(fc%hf*;oVbSIqbBcI@w&(KnN6! zE7xarFuAy7x|wto63Ao-w-ERZqu$JUHSb$WC5|lt9i1P9w}%w3(PnU}Q9Zv+q-TUB zpmqTT=H@GE&Ibv+Lo!#d6Df|myZcSW_+ek`JHe3$5U(buDX`^!JzGyECvGDK0wk<~ zlLPa0Nx!&{b0Ga0rCd-NuYV%zm}qICjt?kCxIukQRq!0&ikO-@O+Jc+-xl2v*CZ7| zphL9d>$~8mD}=7A&sCWQ47}(L%6c`{1bg-)Jv0*A^v6Ik08n$r|6~S~w>X;VaO0$_I#&6Rw?59Oes|3$%Hypc>8ozMP@Ahhr%T-w0 zgaq5g_q`qmwuFc_wn+Pv%>yi<=QxuOaqtbKe1;?#gh3vkv2lED-z`d~g;ddGH*2w!yiQWW3TQv_quyl8Nz3x-E9l#3jUTT%re2ws+-v!oP!$ThNMAcO<@T z!(s91sYMBm@FS3EAGw9R587umdtZl_20p^YK3|7?T-*pyvc0_ReecWq`d0e#uGnzF z*uC>pJay>_q&j?~?ERWkd}Av8bW)ziX5*CDx@|=}uxNX}ELagODTi0!>g<*I6;;B<^&N zq6{8CriuzZSL#3vgsX~+&jWc<6@U)8!%y%$4PPFjtx}*8>}&95bRnEAIq?1}cx)wc z&mjeAHdU@X2?{6Ocn7;)1s7|MUH%3GB-D7}9tF8}YIj76Oin7#J?tB?DYqCO$8kMH z?w8QCBZDiX+)IA|o=rKpjg}!3T`8LWkvffE1u{I6jzF1-EE{D|Erm^lpFt6~(TI0i z1c~jJaQ2FxUljik{Uk>e$JswCKil7JE$c0Pwzqh8K0P)d%-eD3_IiJ>hmgmZ>TM+^N361G3LL zEO!aXCE1awU_8k8FtY3MczzU;-v8q<%vh$(oP?%e7om|+sBiSESQg^osa02 ze=Z8C7`Z1pLs?d#f<1?$ArAVAnpp8Eubq+BfG1_^CFF|{WJf%A7ww(7c5d=);#lSD zNF%(UQ``7|VTyI$Nvu$JahJHYQf^0OvPm5(&RP8j9sMu&xB3zN*ZsL6hA15hCM4mg)1qAOW@)y;pL^~ zS1Y;ATPmbhD(G0MDO8%Gjjn-03p?eD78Z-eE8DwUrWhxt93ZA@{2)jeWLH?wFo*SU z#AW4)5DR{Ct9agP9&4={D&9tS^EfH2v2q<9Axkxgodm>z7vjhSah3qN5LY5oRw4;j z+VfWWs#W@-S5~f|v-V4TX|tn<3qv4$<=ckCh^)F#`!rrc$%cu*{A)SiHmM6QZkjP9 ztE=KxXf;ApHT-Nf7_J6^qNdalQcPS^(j~?7xjf~x>RHpftr$ohFVQB2&kiN2-ErLO z5<;i&*G$w5J-&)+w$W(Z6d7?uj(rt&jum{63cI+vTv$zo3vYEs4RYoVQOR1(aD+s@ zg1?IG;U2zx2@E0;6%-Oh+_NkNvyMSS!J!z-GArBs9#~4Ms zzND)QUJ%)CqYLCj6DHhTIMT`I)@@J8Gw97TAegq6-e&R|qFh^{YSR8@f^?u(vXf5- ztZ0GI#BMfDnri$WEQnk!3F4sWK?(&s${>R+JBS6lT6aq8IXs0$s-TNiJ*_H|*msQF zY?MY!-VJ=za%;-KuJCh$Jbwgog7$(b;nhg;B2@U3!7{~8-UvEuN}yg-AE}EV>lmB zioghP-Bke)%>*KnK#GD}j+CERJZOm028V=i^Yk%8?Np>c^9ph(r zkiR=Jw>+3bIi8O{j6{Vv^Ms0F7N^|vX?X%}eC>N^|0rT=>$SHyQnkK&x-=%(2n(_W zPf&=gsd!HJ$DhHC`{++H>)3w5eO~}G(Zstp{33iJi}I5(dT08#Al6XEnW22!qMZ1Y z$>utIB`1>9O_3}U>fMBHY9a!p?BQeK2?U)96xo^u=Qot799=b?_OoooMbrK8GkfZ| zp{86OQR26K8)gw^tB%{n=VxKyIhFZ#2?Aa!vpJf2V!DDk2B|snsX3;tIZDj=JLhwp z_vg9p&#~9f-wm3-Uog*K|JnH#L7yVoS=x!hX&c@scei>08=a97*%#JIiaz%L~HGc4o_9 zuVu%AWvBDyS7a*=_g9>yR$Qf4p2C>PM97GUa69uRr-R5=(=b-UgMwF_S94ibW29E& z%vRrMtY)08CXlVgv##ZuHh*&#->SPY`*^8a(n1(9a$x$u1Coz^X99|3u_#U`#Wl9GHL0E z#S;eb{Rvo<*e<*2klw8toLwpyR(Z&{6$wS4#BJ*HWW0zqj+giM`Uxq~r>0~FIlzT4bZ{O2Fv|N(FO_LD3^msy1Wra^E5lgdCScRwrd<3UAAf7+->S%new(leV?9rNcBXU}_ZxC{xc%B% zQosi6#zsew(bP5}<=_#_6eKu94(E=DNF*H7m(1^lfy*O|VyXSWAB*WxEqDLiBQH|^ zR|q%c7DU5tzAiW|!5PjF+uEq+Q;@qi7M({x0!xK-(HPPN4; zebK0Q{)RRrbVLpcd;1n=0!N9G4v{nmC&nsfW~f1cL8(1n1#s6%s5#yBacz|H5<_Fe z{(z~S=U(tKj4TjRuAd$aGn{TuP&+cKgQeo2KpUfVJPuGq+3mY1LLMWz;4Zidb0{j7 zXSwfxQ2T1THCY$jeXhO=-6J~?}J{_Wc`<`;n! zqT4|rITZigd-EYT8|xl}nd$F)PB4kyb9YbM=7Hl{D13k=aK?t_g*4Yp@oCM{D;&dd z*RRmyI!8XKJLGyB1(IMZy9lY>!Vc@g*v^NPB?x0*@~A6xg#bPO>q-?_k|&2aLskSs zEr>?En{eD+A)67!k-SY~$(}91KY8B=xiF+ys_2o$@kdYOkiR7(- z*0H5buQ8TAQPR{yd!k&#fm86+)+*r6sjdWmt=xLNsiL+|nV6zZ@Iy`&y=c9175yYH zPF2IKjB-_g#fh(GTCoTyK~^_7pIW|uh$~~&`;bfh#jsw5x}71%p}NCzMumnW@C1^v z-diLraRvQQo&j(e8;BZI1b6=zq7gFF@UIRofLIC@%l#_2qbC^3`Uha}pW>~b;Er8$ z_oXrysR{wd`7gTmKb>yFZewS2sMtUv4 zL3)M61@(vD%B3>@K8OL70(b9nN55UW{v)dMx9;%|Q0ouPuTX8){|<>ZdQ78OVpPVU z_djTz{{Mi*z-4v>QLt z)qc3z#LrK6B{kH2ZM=H^zV8+juv^<8*#By`{zo|WpWq^o0@^R!Udb2SZ~+wk8IHZ8 z4F8Kt^eV&uPv?)o!T2Y*_yd@}#O z8z2)efV&B7!Zhd`>OYPQX9Pvj6`4aY#my-+F}b;h-{B-=k&Pw{*1yrR7RUR4lz(2a z_5VLUGSY}IL&}95Q7pTDY{GIPA2;83!Uh5W4l<{LZUg2c7xp6vpv|j(Mf@OokUj_< z_<$D#`{!o-iK_57%{(eC>QC7@@Q2y}--Vxli00Qt1wKdtvH$wu+tvR-4){7eK#stF zF!)ch1e*Dz$N#Lf{tMgYM+DZN**3X*1i#MYA3aWgf|oy3C;#M<{HHVdi%aqy<&}n| zVEo(~;M`dO-@)fgTZX?Ga1~NEYhwNb*}tk|`k%NE|Ga#EICli}trx|AQdIA|yyoul zg^9@j(?aX?ztf7=hYSA;dxAeIWxvykfK=hVvf+C_PbsiNmLM_EAV?cH3S0kn7^#{V z2yPqw!944YCHjAV6#lS7|9>t|e>)04X+=Ni^H;RQ1xKtus6+4|U<>4d`%?>g32Xrj z6pr%u;)Ead?{ez@WrhC#VGGD%lv9T0Mf2r>OBI80GRDHeyJZ82)#8H{SJ zg+6LvvN&>bXDuue5hNA@b&VK6QEzBpQ7LP5%SSwGspHkfL4^;VX4M#|Xc|9!g{@y- zv}5VsVJe-a(Qhrd45l8*BbL(OUfG;rAe#mT;5oMWqGbaK_tWxSa5%pe(@|E|eO(z+ z>etIZyXl38h?bS?N@Pe2<;B!E#B#-Wz7We2X&Txpu>ZuM-x(}?lmyyypiS^02}IUr zqD&p>x5yOBQg&s%k}>fgoM!$ldRisI11d6d&;|8t3vfTe*zTHYbOTgm zfXiMo)B_X#>>1!9E69L|t2mL}rv+w!qmo)s?$-(nro<1Telwuai~y3kA0ZmP2n|P- z(y=*tw=5o44i*K4CDV&K!Z6Nt{r1v((i@yUGv65a+>nYBrW;8?V>pn5f0y&)o7WahAnkivN3!=~t?{(3l9Q%48of{FP)uft$qQ%I-A=WWs{3&-x zIgs;)Tsm4Z>5xl)z3thXBQ1G`aFuM-MOFZa%F9wfO48}s%_V-c}WZxKZHYIA);bNxZAC+y{QPvAPp>tLE{KLANSxgOH`S-<04yVG{&XfWu6RxBxMwzddsCW*k%tr%dMo;p?w&R=eEeU91iz z)ZCxD#aE#Xl7806``pMIWG1<7tMRT$kNkChsVz<^%$_dkenLJ1gD$5Sg47+6IGN6S&} zTGb+n?#rPJnXb>hRcK>Pf<|dy8YWg{#@RHV&Q8%WzBryCVQe?9 zqdvXW^z}ykHuN#4Sidn^_#IYDEpV0So4J0lY1vT(> zT~^hUdCVp4-Tg+^@3@u$*KVGp?!Dgo$k+D!XwVd}gsPE}+X{ua_)T+V8a7y?VaY~! zKMCt^+LUrR#_tZZdu+bwW~0pV1f`*XTJgY?S!pA;OPF4a*aVw$Iaw^L+fCTDz?@|e zAghx{Q|^1F_RhF4$L%@v+liG8AxBJA&B4;IWD|pQB&y~D?d})oK3ViXiAwh=SXr%1 zxL>`N8J$?YzEO0}vsToiak^ICrNO&dQPESgRo5Hj;0jl)Tf0Se-m|*a6*uLy*885U zZl#CGoPTdvDfrvrm>t%)FICT8anCMbnVlb>raZlWxIC0gBk`OxK! zO8vT77AM#s>{mYq6p2XC13=Et{FfpD*!~G0f6;p2frb8vn%h$Ap&KEh?!-#rP2phl zi=4zC(stlUs3#so{!AP}EHv|B+;vN%K~!tNJcaeL6C-Ws#+;m? zJPBgX2r4K}vnnz?M(L257EZV-U~pDtt3O_fJ)8TDA(}$3cu@a>(I_b7rG2ao^1%p+cwSS*T3$dH zY&GL;c&E62X35yvqISug;nKV6G1UnH)VGI*g_^YMOn@&l`dgq#jBl9vs3NbF70SNE zD}Nc58v_F2#VI?;bDYLki7O)IiJ5vT$<#2=ga{YGNS1VuY>i0Q zm@OK?*W+(BuQ&6UgXhSGw_EWvX}+|zU*ugp_=t|siu1O8r-M4rW~cV)=rfWunu@pV z24bS2o(Q*lCvv;Em-#{vz|e{>FQ1T#UH$wbYe4%d@-bg zuGPzCeQ0_tfjFA>gtz>ya{rW%NFv0^5W9e42C->5cOgC?J$Ww4E+}dR-oe%(Ix4)N zT1*v|RyhY2tbe%>_W&H$*&8GDyxYVr;z*O%O#X+EP2i zZ#{d3&}fwo_2kl9o45hhbEm$`rok*Kd$Tu<%#B)^5hv?omS`G}&B>Rnp(us~@yTjz zN||I-YTpI%!&w2p^4wQ-JXQvy6=0gFvuI(V$#*(QMqZA^*BHF>MMFdFx!meX8hXmn z`~2U{+uG2WP=$L+g5=UwS!}zbb9DoB80r_g31_t#V5(vf12LuZE()e)Mtbj_gt1tm z61{L9v@udssi5}j`kLSMmeGx=S0&zfX8BDT%v9t5WA82FqU^f%;h7<128E$Rr5qXr zQ3(+lx+GOnrBg};1QF>Py1R!4=@KcC5DX-w1PMVzQ52*E=6}u*>UHTA_j5n*@BQ%n z{Kz2Z>~rt6*E-fZjze>57-T-fmh)`j%*v;Brsr7`(8aGCPmn@5=1`^MC>0DRgY!}eei`0#hU4!jv-%1Z(Ac$& zZqP*QDx_{+|IF8hc_=u}azXM*U6#UyZ6OLCPOu*ORrRZjg58huDMmNU3&);mYG{Ak z)}cGCFn#&@fsYNZ(3btV`Q5J`i#dG_uWWs8Xl)v_xf;t!m8O|iD`Z{!mWZV}p2YHC9ygf+d9h9=B5l-vDLZux-(`hJ#G z{>%Y$%0p3s2w8$lsM8tknd)&T_HC1ZYorp8GqVJMP;Alo)2f#mwz}>h3x;stCaxdr z=H7`P5UuZoCC-s?%!FoKdLL#M~dlvJclnG)IWSwJoi7jQXxI@6KiFOM^VnVeejq$e-DLC-~SxJ{EW<_W{i7&+h~f5G29uEA?pLXR2lXq*_D2oQDOb zk8QO8sx{wHMnHtqaOAM?DS*6ia5Q{l@ZKT7%8Gd7%NlpVrBog$NeoNR%YhPcn=Peg zs-od&Ox|{3;w29)utF!SbhUbJxSk0^Wi#q%4XJ|^OdTyMn=i@qBHj)Qu^#O;BYo0Y)h2sZL6?;@R zvMN?;U6Lf9?yMuJ>aJh!dfn{ndL&U~=|l4~bpiI<_Vvh5H|uX2H%OnEKELsbdG4wg zq0!nEi9o8@F|QZvvg6hZSgC7P7AG}-yfTjPAc)b|!!DL5gra$iha|Pg^)3fo41<6; zk#I=mg$Qov7v^bhuiwoLc>B{ihJh4`)Tm{u;69HeN7ZXH;wC*6GOifkU^k05Ym^hV= zYcb^KxiuJ?9L8|lGBeGHW*%_H(ddCto1L0LLeVJBRH}!V4Xc!j_AWNlYnqzxljwT6 z-j{&e71g2%i*>_AN!ML^crU>w{6Lk+Y_#;(tyr~EHigU#)3O^Ta5h+0p&N)F+l3TZ+bh#gTZQS2(d+lvp*!ISJjq178+LQ;b^$pK3uAkNluT;-Jj8fUez=sck4#+n{ z=odYR&QB<^%Ugo~*8jq3Pt)s3v+~T8FaPttl?K{$SqoV;jcKY5ahJX^)HyTx@T)NkqPwH#0kFDOl zLY=o%3lKxGdR$-99NPv<0)y^FbbKkJbn{(#^H=W1@MRPT)^?92De;ySqW<5GVCk1R(B;@y>+t$#W8T;G+?s zS7x-a7DlS@5sFDikgPKx1O4pHXz)so zE;rqe%Suu?=FEJ4UQPkvdtW_|b-C8~$s!2wG<#ptOvwFbiy&Fx8}#EWg0L>v*FQHe z)J*tsf2@5Id+lE4cxoY*XY>AJ{lPE$Nfgi}egt9%e1bTDZT8}43ZPnggCCAQ8Zps? z0`y6FoK+1xLYSm%`%f)qc1Cd=V)?vUI^7!0FR{JxR&}B&h|PHZQ9Khg9|3iOwK?}u z!}Ub`xom_{12V3~y1Xg(7YAFJ@IGAG%=Rf5^r}{zjsAl5ohH!Fydt_tGg_iB)|jHC zl{<3ZbY|)(%HdOQCMcZkYtR>cRRQFIIo3O0X2o4k(scwYT7mNOyjkrkyXXLZc)C>3 zk94k`E}d+W3vvOxpM3-0vK_y_y1~ZX8x%l&_({Gtlqxz*?-!a`H9cG$28pG zGyl2q0Ei`j?;>LfbhpOggwJ@^Rd7s0S7Z4d`+DxMusw-6{|CnVzLOeNQpg_$8#;mP z(;Y+!yiC)dUnUmqgnZ9-_A^jf%3UDiOf)Xr!DgWEZYWB)V~sl>-$W*ORo~tpY#=wu z-({^*bw$7HPu|}~0NOnLLtl{!e}{yP3@RF8|q7 z@xR@0{C$@Rc-ibl9AkDe^8*z^GY{{F%;}A^UV|$$r5@MrE3$e_=s_(IMA1LhmFZ5qi*#CSY7GFB;X&`g}TI&B&XcEW0-Jz8J zpr!uD69LRsv<9?iZ1@oG%DUi$g}NhRLFA9L<5cozw1Ng&jMcO?`D(i+d1DR zJG``fo8mm1|2Fl`${!rD3+6I|e|E%PjqrJwV{X;;&U*J);rfs{K>6YVk_6s=%pXch z;6NAuO3Ca;Wb(&U=fC~_%bPyV?315?bIy*}w13XQy8!^Vg(Cp7tRRThKi|RtxLO9@ zyI}q|zrvqHD*k4$fPMRPc-8!``|WaWg-i*PfE@tl!)=kpSwIr~E!1E~5?!Ad5M#q` z;i3Ppw(zt5E1_psu&vbCYU6NeYRf-vVLvGnk$<^`nb?4f=I$5Hx%Bm6skw{*HtZG_ zFtx~HAl!@gK)DSEvjf);E%35yaQjtlq5+t!qu$K5XY%mcre}G@G7;AtKu)l|wEBrj z%9YLzDj)81J`$hmr0u%tb83(tL_$#-dGCpMw8@AmW%I|h26xaMSa^PEZj(L+vgyrv zA`+BR>_MX32{-J)S7Ihv=3tt7?k|0ETZ+DaN(Fq*6DC%_Z1ysRG24%-$I9S}mq~vl zb6fRHYXLr()JLHgp_y~Yeft{?Rk38yL7S>;r|YOp<9VpIUp-j)fNX*6>K@>-5er}< z<_bgtw{bCK|J7{73ljF%vDe9p+snLrM*`wIoqu;wL_bUcr#}O@VE-T=^52QQ4S2gg z7DE;6arYW_Hm=_Hjf-(1{I&G7AO^f6kCW(Nd{I*G6PChe32~Mlu7@)C#(anf(qLQC-oz`sJ6QQLIY5r*Dn~ z=Tn%gCJQMc1VM<%55!BLCq#gc~*l4Dncwaaumg6Y2XT@>z{ z=!_SKbUvxOY1j;zx8y9!PBVX&q*}Ogw(iT!fZ2t{ft`BWMhOsksSL(g7jyCM4M?&;T<9F+(9H^LJ)L&V)&I9$Fo z1i~l}t~YE=6+hK&e6H{45cV>`F^qa7LWqQpiE2pSIAF$~;bx&kt%3Px&x`c#eN-!q z*C%CWC*-~vR*(B^5(v|JGAWY{yCB9_Gm!79h9+F?3_Fsj8{-LH$$gcno|Joy%4><7 z;UP@J!m!xUDuH$t=auMO<@yuow`r~rE)J!elG6Ei&TBGP4*BZ6K;Luj3Qoa^+8eV-OeMPX;17hI1$T(SGb_U?Z^@DC@4y7E?d#ttA7Z%-_t0O2Kh1c)c+V3o|!bM}AKfwEkDjZA`EhxI4`fJl<~ zk2TyzBzs>jbPJI8InC1Qil?MG)6ZgPGk2qyjT`@n!g|BD zI4R!r;6$CzROEqj&*PMs=G!z6lqL4-h8Id`5blR_+%qtPw19>B2??$uQsV$xu|F^F zPnM8j+bRW5)~;oDqgL=AC9m_(Duo}!KzlgTvyo{+sw#mjAde@RGbZL zFQ!PF#Zwo^ho+$e2pWO~hwTdUpo{8Yw6z$(M)@%8zHJR9VnQC*i_$ufL)q!TG+58L z1ncJ%lDN{$Ho7i0LNj^w5&Z%kD^D}OS|>B(``}^PoAN19q5&qDRF_OjT;rOS~HE0_DpoU}-+OEA8+C^tqx<{UYxIwX&>+h0uBxhw45hB=QeR^xoIZ|gbt4cF-&sNI^=l8jyHG}0*Z3sBiA$$YaMbq7 z{MUlZ1z=lchlC2mSc8oVVIJ4ez3xhP8O0gVm*!Uv-GOokN7UU;W1Up#S1Z*pJJ z9scHDdR5;2t6JfBV&$cJP4xNtD)u!Ro0s4_`A43LvbVc(ZVfmEts^e`UTqjZT>Gka zNf4$7-5)3g`j<>#1hB2JgI4dcPJ0}SjNd(qyqh4>n~u*jnm~kn^cS^1Pqu`>@euNo zYzmOTLx;BY>d2>&t`Hk=DJz^!Du#!cWYe@HrW0f{BJw1V!sIC+?%G^gr^c$7CF(A_ zJV!bI0)5{9ekJM)Lb*VX^tepHvf-sTqGPGaR)Rc|@!Dd3Gm3rhTY`vA-=|U%yw+D| z!Mc$Z$mGH2Zf$qJ-*q|dNeO=)xryaKoO~o31`&48IU;ZS@n)(}V-=hx%EXX`aO+ zsWQX5Y)Y7apS}{uyxaaJ{fgQn=)bZ5@4b6Cm*~gWt zm=)ctHd*BbTq>rX5uGM3B1U+=uZM6kE+-5uBXihW%De6?@*DP|vpa3$-%U?PLN-sd z<&Q9%Jj}X6vpraFt7n$trs(Os`=)bq&BU0Pa-k!WT%!=i!j5G4w;Xo`#G^F67XFRE z#L73XRU@K3UVLFy8+DVo!lov+s89-}QwZ->;YL^9IO56VIS|i_;owknn;w>A@YNW* zltNjmOk^a7VTzeTc3d~@_Fk!EX`?Pn(T)j%SV!Qya;<-j4aA@1c;hdq`BjMNZB07M-XMeVbPgqRq^CWOBg0Tpa!xQjNfNdkp-6|$s3aqaw<-CTbJ@TG z1etf@PtCPtVs^^x0TpRZKANW0Pl@Nh@wV9K?`(?UR1JJCYnxY7xaZg^0iI)0|o0V@%J{yC{iP-JeS(oaZdh%y2Of z+mxm7Y{sSo60tZdkqgZAsRzGZe*}yt;GDl4*RJJX@RLr%@vok_t0d{N<~tT@g|9ZE zsMh$HzUNKY=a9iYhZ*)cEPi+n58lYV=h$-~3&lBY^cuc2C*0%oY)HW$ zWDIxfa9774tBHS2kU2WU0O&mu?;}&da**Q*0GkfWusVu!)qx}HcMhD|M2jCEJrHxq zkU)a^w+r;!?GK>!0>EB<_wV+qLb=If{l8YqJo=BQMSmvF2z?CMbME@H&TT32L5mhPf;DR~AX}DQ+tw z9L$FMuK-w32(X}Zc>n6~rq zZvAIJ2^>d90n(#m4jx#6W7+Qz-19~^iG`2Ag6=j12YpKZ+H=abEe%PdnP;fCyR<+| z_%&XSi{ZbD3phNK2;f9f<6-NZe;kQ%F9WLgAHIx+yc>TaY_3d&RPW21{vs~SG%EkW zm+Dun)qg+>JGPbm)5`!@(-`Y(03MpYuZ{a(iz>fe_uU2x0)&F>aI61(10LA^Jr|7{ zKmBKJwO#p>A1N#kQ*hJixTdZWOUND$ExEv6M zB7iW2`gd`Ceeu7agFO51<{*E11Aj7CeQkMT-_=+2>HK(W5MaCWiyY+KtwsFLqp!u! z?Bv#ev7LbQI z<9EOGT~_?lS+V_O7FTv504qpru7tvsU08o=JTMdGqFn~am+0_uA7?cdDKAQQg;N0b z)8vZzuyt*yClyHol`FXTE(8vl?f_~!nN*)r$CT&)gF{kcb$!7a8 zJpDSB|J&$~yDvz=-z(42{X7#`0wSQ2p#?DmOVEg20^uIU7Ow*oupYFG2emRD9n6R5 zdd5R+C39r$+H|u!?E<)#sCQc4msKd0(juHy(sPyk9_3=8iK3Sf0pVIlMJ_TNNg5l? z0z#^~i@DgIS6fbfie}7Wz*k!`e;x`gBR{qA+@Lp^)^o9F{Ss)%hsfiu*x@B6c(KXT z+dTJIa$f~E{|4=CVp3g6B8-z}?;DI(VF{y4KTY_(rf0gD9# za%((X7D@_GtKl5!xXPCWvA?GPJP`^^%p3p_0Siiv#S_<5Td>5O_LZ z)9xC(VZd3Dc=vpTKp1L;KYQ%I4P5jU0EIxff#?3md57iq3AKMdK)`BnW4BbsskH!S z?DU4wU-SjdhjI7cKQkWvgUiL=PKC8%B=)VX8F_XG2!3T=P;%c@;@k4lYmyy_ga0JA z12#4_9zTcxw~^a0P4S?Mj_=3w0eE8=g6Ik z0#eGsbnIaW4V72&T-kJU1im}-rj{LXIKF}|RGRMdYiiCSZ3QBuZboGkz8--A>qPFu zNE=B17ZJ6Y7s1<`tdmAP7Lx8;*0B2w;X1CswrYD!a~Z>>0;RO0=ilfeQs(Kq7YX z*P(zwZ=cPvKi{}V)I2(_^cOxR|DeF$TDSX)Q1A!grd^q#tj2&}c@Y2GQ1HufIH8?H z>~(jh{%(QIsLA)cakyC-MhRlJxrx2n`acO0z!n05nLrE>Yymif-9o~pJE!*YE^_w^ zks6ach4k16j^7!9s0MEn5^gE%!nXUy#HJz+$brHOKaJrSlQ(B63N^;h*|yWkP7aY6!S22p^hfN#zTVznek?zgypR1pZk z9JhK^%YO_2tXXgGHwb|^K?bZF9QX$!V*CN||KkuRWb?0TLDHo+(w+hpu>^lmmKCnkaZSMK3NZr~$p{uP8st#h?pbP7pU)D&fzZ^`2aqquIJJ z3DJo22gWs+@~?91Y4?4pqyl+dssGw*h0n!rrs-weL4LlQip4N!XZYxIvpxqwy3bku z^65tE{p1t)+B=KJ1bhV%&}mCDV9_MJ6R;W_dyD4W!?^3ORyN)0L~CP+@1lc&7dy%FT9iX#JZr_ z5Qg*d1ry(0q>hr3MsEu5m0|yvJXKu#|4H)nV}ga*>v~YI+}TaAep@pC_6NJr(0`B` zQ~mqq$S+dk+s1!!AO7#A#_s=FYK#LhBLEQd|B4ChH1a3@Br{@DNA%jABSOW-(se`=KgZhd>~kG-PqA4(uDf(rhQ z*pN6KZcA;>=nF-j8V!$H&qOv7g_Yfg%jN*DL84Y;RLm@ivf9iR)Eq9>SW;aTp#0 z+8ZM6uE1zKuCfh(xM$1fY3C962VBvyt#z-x@wdqCuP2PB0y%aK!(wh6Z{Kww_23`R z1Bi^c(Rf16AAHIqDQ4r3MX8~v_UhgLyE^~f)%n{{@!KEZ&dlG23gGzs_?drmb^b+K z_n*Gq|GPT>4~P3_SLa`BzTe&mf7t84xH|uIX8z52_=}VHf9K)fM!Ubgy|@12_EzkT z{-?Kh)A!pO(z%<$Y`ogPz2$eO?g>VmcDR{s+B+)ZO$*$(;e;e|6qHY`r}x$H!)_-6)TfU zN3FU$oFMgq7ckX*kL`zlGuq(?`Rw1`X`^ocvM>AF+gpWI55-eG2gne#b4;KFeytIT z_Bll!{U+jk>h8t;7keByT|Z`M-{qHq8vlDX`T&3`=>E5|(Y-|MCuHk4b0&K=KDj%X z;kkUGJo?AchLj~)ah$PW+Y_9{nB3Ibqy}Wvd)f=$+zoW&NJ|J8ho!Fe?lb0J2`7(XQx<(S<&G zT#=`q%C1^nF1G~8cksIt7Ryrs{Tvp|`UR`!n#x56twzx!1yr0Bl5GW7>iOUGyW3Bb zn<{DX>eSgEcv9TGI$u(}V!Qotw1$7E-sLO()q`L4dz+o71yV0lmR)X(KH1%Gb)m%M zX}WP{zw3oB<2?vDnu|{di>JEtj4O_~tyc~Rq7P2JOsSu+ecb@vre?ToQ12z#_vI={ z@_MsoD*>1Pob$xQ^YV(4NB0^;}i=zQn20njQm3_Uw#krg4o5}*@# zp5fgaSt5=%&%H3r(Le+1?`-PyRz~)7l~vANke?5*59TEc;)A%>FB;AQ)f&O%s}eG@qLi$8x041;*U3$UhV&%|{bR_Y3BvJAVBjN#RKT%nLteLNy%cy5l>^C4skbNli%Y4k8 z)xaj27Dj&BSBE=+1l|T>BKg`CcZr0u*yCpLJDa450%%@*R;=h0^)poA@krHsNwblm zf?Re5c-Jl92b^?;!i(}*-hV3dANlgU^x?BYp5{iDadLlnpiMT;C076yjQ8cumovYOGGxwvfUCK|?x30}S_s~9tq zTDGM#Z0p)kJ%UsgYi1*_oWAtRs%kBwowILCQjt@q6U~CeX`wyJkN(ij#4OJTueZBQ{Tn{7mmBBES zqAA>11-_yGrLg`(C&R_lgTi*j+%Gwk@-W+*tDi6!(7|-jo+Qty7ag?ZdleFJ#3jKh z0GogSILSwU#aE-JTq|MmKBdUIgbNYkR^; zxy)q|cs6AeuN)hzRf#Et6XPN4DAI3uAsU&wZFRrTv?~)#4st%@m?K*Vjzp+&n_lbA z7J=SSM#kBwMoY914sECwzs?2Mez{}8?csy)r;s9mom?2{2oUhnUsmgLJd1;a0dZF_BZ!QcVm|_A-D=bNlwyRQqAriMOZRNhqXTTW z#L5<5KJ+{^g38xma@boUTza<%tOOkn`5y=ARY8EesCj=f+#h}vhy3GUb8BJs=_Y;9 z8LLVyHH1tgK6_%(+NU(JI9AT>+nlDed@)oDW9OOLSf50bDL^JgDoi_L4(hXkAn9+F zqTxYo3dqtNl^A)ltIEw(Ak{Rr3i3N5R2i4Dj5@ZJ!lfl8pc!cu;yF94JvV+F!Au-msddAk%ZE+w+-664PPZ=)-sVQll1aBO zw5*(9jo@pQ2SXe$q~4GYv2ndq%h+DVLv8rpldjDpjg z58t}}y7QRO8xA+eA1>`*P3z#c1QBqX?;%U0`{F9V!eI%cRDeVTh^QHaA@~Or^{bm- zKWWLhQrK)oeR-}4@+8H8!;PN5QSw{4$R;n@$9mpR;6U#k`B{C47mr>9%Mi@4-dzD^ zo1d_ltM09*%eDFS6qjZ+FkZXK4mQ+`6C$qm((M^n_2uf0WRCHO=GCy#%{Y`~Qc#?? zl6d^0NL5S&ug1ZqLrFIcxH);~3LGrI#8EiSO9#5G)) zK+OP53nI$iJ;)=(=+8wkM2hqUk;%!e(za>oYquH zVX^aylCXQGVlVvmQ)AU(48E7M5&3f)BF9;|u+_h78kL|IKoNKW_=d~Q#-$t^RR0L`iArMd+dJ55SI58>$bp5|N$ z^I_2FWRzpeG=1*DJ1b-yT#@qirHgHucGg`!+c#quhD~b>{lzs_!#s&>FHT7;URowb z!AO_@*)7)mtKs;pYGk2iPxG>GND1bX#nTPUyjIZ(RX7?)XH#pIc!>EOoBUzwH}p|b z*C}VN5pF@X((#lz86^nEoy;8{%y3=}4fpe(MH(Hyo#48%uCP8BQ{)bkEjN+76hRt$ARz|F9p014A zb{txLbz@L@bLxZR}!Ds zu97T&YFtef9co{?v$-hF{rc?3=V6B)EH}zEJy`0~Cv{tS3Fr;3^uM=;FT5GNy1hP| z8@4@vJ4(exET_ZH+0vIibnV-h`ZUbDZ>#Q2n2m2~AUt{GHr;VYtI?EU%J_3*DK@w8 zJkmDUYR|!ROKoeUMyU}X5I(|?I4e;SbcV=>w=~nD7~}!dl83p<8~Sjce|VidJuuU) zm>}AGXYp4Vq!^cgvy4Vzw~=R!$Xx@ZSqLKnm8_>EsPpha@?HngLtd1P zg1(4SFDesx5M=0j5T&gom&Rl!O_V9AP_R9ve!UE5yLQW&tBawI#|Wrbp;As=EhSwe9l*t&tp9hdCCyQQW-H@Lt=ajh@{)uQG9C`L7_-V3L*>tBj9Ed z(K8fbJ*N)Sk&A!?N*A2))C{2S%f$4UG$4!D+NhIrC-aZC#k4T#a{#;3G4o|w;<+T8w@!fP9W&v_&=DO$f|}Bl^f%F$ zcl|2w@h*rNE9nhkMx3gvHVTHT!||!ukgzIy<`Ye91bWpFKkj}>nWs>E&>R;i4gWCb z;{CyEPBA3|ZYkq;m|G$rm1V_N_^Q(gjc0xdNs4#yhxA2`>lp|nRj)-qc_2DaXf@zb z4Z3t!$+)R_B(7jpEc=OB;21^LvR6Krq zNPnnh8L!NrX2Wn;mNhp2=&JzU4+hlr&Tah1uLtWrP=lDSwvQYof*S=+Gptf69wNT1 zt0;ML@Su4!9>N~lL0=|Qc}%&c5ht#4MN8%%jN`ba({`DpV)5KDGd{ib z$8}->UF3L52GnQ;p2LUble)cFylM{`4|vk1uAa@g!)&6$30sz1K9VfCwBBP&o|a3S zGbefCj9Kb>TLV4eoE-D{o$;(Q*qtsOTR~ww?6~|+^(S@5U3ZpUvanV!9~`+ zIUJ6jtCIdi%nZ>M;YJcchZwDbYp)x1pcwi5o^+OChuD;=0oLSSje@FYa_>{q63Xc( zxOPWD&p6C<6%e&BP+kkSmZ*Td&`{2+<{hmuoD7Z8i#_>?zCM+WVi&i4AhPuKS(a4V$9U7j-sti;=F?XF#u{lA z#2Cc%{j=)=$?_4$+~IdtzRpfZrSUc4+&rdVmo$lEFxvz~OzwD<)8x)8o5s)izH-b> zctK^?lzd3WAEt}1Ze9ozhi@BC`ce9=O$4yS%1;HdT6@!Q!qZ!j&^3vYD;;5!-YM|7_sf)Y~hM-=^IqR5Vs3BtbHS!&wR} zaB99;;pez4(a|bamf7)F3oLVzRbb{4z6=*F934qObNQZ`1y%(`_fQ4S(b<@OLQbuh ziFrwKPPORh^O6c?aW<*>Z1*0Pi&&R6GaUX<-X(bLLq%G(iFslFecgqsmu5=EcI>`f zaL&Y)PIS(+lhwzZo!j-E5~u5UX1`()p-lv^zYwJ|8iG@yv9^Q7FT%J_IlJ(}5SqP>t}_!7KokVM)y zvY_#!4ywH-H26yok5`?%3H&eo9^&`x!P49{%OChap<9xr5;YtcxI(|_fvY{e>@qw( zKBR}wfx;j*o&d9gqXi{?>E?&)8msm;^ABqf=`v!$q>ImoypFl8C}p!OcT>VjHG;@t z)}0m44{Uk)^!V2cuuo*iDGMuBJI|FGqiL3(<0~RFciIvPMAACZh=(?b+vlXvkO{0Q>Bg0j-*c=9CL=pK2uD-jW82(`e?_`NV5 zbmuj4#gh!)`;MUC)(k^URaN-r2k0hScsj)*d8AoLpqcU*2l7WsE+wp1*D{nnEDG3Q zp958bStxTk+PE~-12VmhWW9us(U(7R7kX!C&QmMQB-;~gdiIr9ueL11)kh(RJhSrO z)V4z#Uid4XVNue(ew4NM4NCJMf|@`<9(nGCz266xz9YwE(@#ZmE}+o$$4_^hkyH#j zU2b^M#DY?ax*VmqiDu8uOD81}kl2(8^dhgR)s$4d{=BPq@|atVriWq~#bXn3^C`BNh&LamdHPw~2RXdSNzbM+&WZIL`5XdE@vr5e{&ZeD$q%6gjNtb$1a zS;~^kstF*wpwlH)5S6-A`3@d2tl=hr0FxyS5DZ2a38cW|)$eDA$y;=2Zx<-iBDjvb z1}fRUv`sYDI7Uk5(mtn7kqF%?IMsT)-74`!5+N^CdM!Z3?*2_Qm*YFB^DwQbDNYu4 z`g~zW4)Ua_3%MR``37~`!fD45P>G@_UQ|Ff!wJR0S4T$0-JE-jMj|r9dM&i8Him># zHJIVq(Pr%V$2qUQ42+M~Iy|Dt+|gB4yh_Qg`W4pgjH$jT>s(cAtsE(T{NYmd*{AOe zJcBx-=rxNg=*K2EKdY0nPFmG)96JEAti9n(p9biOdCS@^v=#B1)T-}4|Dp`f4{yNO1U#C{kx3&z$w75pe4{6o<@N%+e z+BisyzSbR#D$nKr}wqca)1iF~ z{=MXzYu!g?$wOLrxwTUi7DOWlns_hC^H&6x$1bY-e3Wl~BY(&zYuMKOa)1|~?#&>m zyw^ho`!sIEiCof~#ncP-zMi%%1a}Sr;->K^E*HqO3eBAyHg&Yp2XOn;mAD6U1kL?u z^G}?#3)C6`lH!WSbWlYw^y?aZ%t-`1sHXLh2Bvo8UWk!SZz^4uXh^^+gA1IRL0W&o zH4PC7YO4Dx4>d6UNOwi3_{pFZ!rpV zyt|SuqPLoR?2#o;6A6c!NA#8z5eJ1 zc&iIMw(bEJU&^KacJWIE;q25EC=-sw%zKnXI+eYoES?c#q|Aet&NLlM^>|6-(@O51 z+ye>8@Ut;ox@(Qfli-8%YoJHlrIIFFZ_OuVA50z-JTfCcuAXiGY0c`0ktCF%&9`(I zp%C1#Y%1V7aN>@d?863b;!g-qX=Mqn=?08|_pn}WfJyc5%#Lr^kNI}LRfgQ(|R$jdGfD$3Cww(oFhFU?=5WM zecIXkOuYBmHE&T`pK}~OVjKqR#^jEX(1diTE*zSe4$WNjN$BypIOlVL7J4ZUs-^9# zTk5MF;Cofx*D%0Wz1i2q!cSMtPhZ~Gs?*n|*3Yif&w|$9yw=Zg&hKWtzf-*5?ErrR zd0(12w<KYHNe;4+T9~3u>ed&NK+B zat?YV9NZos+*TXh*%{oi7Th%y+)EVlj5efSIOJt~$UruguO0X?FK~eoMh4iK@NsF4P4O@#3JmC^57#J#yafv#U5Ovlvs-#mLpE?K~9{!vb)@Bh7&kt8{2~kRj zP!5b92?!bGh`IPUTHP|{LSW1#mzc{sL7X~wh{-|~I7s3wf~M?){D^!f(+T`IU|H$0 zW5O^?PMCSZAtNT3Q93lsK32^+)-NESS~xgqD9WcU%1gqz5K*t&XDr; z#6pE66_=#az@)N-qzY(~{xCUQomk2xmS2HXuom_nNxEzwP^Cs%$WKz}k&K4JrY1-i z(vx4f1XT8rzQ~77rNbsMAX7{;NvlQ5wpvPHU8?_Z>WB5z;I$}&$M7bmpcl0ycs)le zghMm=4gKPwh0XRE=`cpYAk1)DC}&7!GczWgq%x0WyBVf49HS?aL9LrXTM$D(5;JBI z+%il~ArMgxW{Px*DQ>HjBukBS1r95O zXK*A$6AWii1m;lX1H!*K8i`^g;X_)I z%^uRP{3P$yEIQ8^KB7%8X3E)CBYw+8k~5sP%>;{?kK6JnBINRtRzUH#<$}dcZ9uTd*`YkZN*=+09Z7Iu;g3>fQXx59oINQQF2iG7q zBHy-v8YfX0jbg~r`@!zqMc*vFxs@^wkJR`j)jpdm-ZUp=puUGuM4`FR!gK|u#DP^g z=5`8kn2pF(z*&U&KHs}YsH+dxWNGtU#nE@=b_IzZfx%;QMPj4T<$CqU?xz9s$atWX zu!Q>!-|8C=KWG+x5d2NXC!i_-T97FkAMae3$3eL50g`8e+bLAPBu1MPM}zCCM>}%| zX^TBEha)=j0!|UvRu)F1>cbP^4R!VPCkt~_0~^&un!e~YeRgfCQ)p5h4r$XPhe#*u zrq`HrmduU>+)c)p-HT zXIqZ(l&}W3umnFuyb54@@{sG!L(V&~1dro4+2JdJ&;*axGetgUU$vfl)hheARrpDW z*x5%CMLx2ZA4xuVB>&`*Tym@8+M_c^9tnEmD=@+37e%r>pc&0=m!E{_zsfb>X?LS< zmwwe|a<<*PsNKZ6-E_0v`bfKQQ6zeaU%gcnrcEwa+X21qQzNIt(b{pO41QrzewF>g zu@;I_Oeg$>mglo}_={}m*R+z#Q69!}@H1YI+xy%~A3aVz(wTneaptCA#`&&st*)84 zuDpX{=q!4I4E+8jl?MOwk%HY(gyed+x}`35*I9QX5C(Ztgp@-b29ttSZ`~cv2H-hS z=6s`=qyXdb6DGmIhEZ@5n(oH9r`P6kOPtv_2L=P1XikHY8VU z`c`Do#wTA2X~Jz@ymWeDRP|zu%Eok=ZN#UO#>rkc*GxyQH?{v6b4V}ySnox|8Bdh( zL^;!W%nf3+{b@1>((SX%DJKa_sNBvk*mXCJwPCYLOotCX~0;dk{7c;>h^}m4%qn_lvo1>_DHsBU`FMD-oJ;tRW$k@9rNcM(ppvTRUYe89vN{Pt3T2= zh&h0O#`kP5o?2ld$jHDCVkL-#3xuD%3i1$3YB(l*45XWGB7Bn%9mheqrA;;P`sz!L z12H4Uv#&R|UK3uOAUZd3ppj#?2yWFXeVB#4$bk54hvBE2=RQ;5UnnKdo`A^;8YaU< zLsnj?_X(*_oLh?>d(|+-H9j@8H8r|0g&uP}?Lb!VM4Vnsmy~W*la8;4gwakPgYrYQ z%7<4xhLalvQlAQ>7lXdK={h59$`6fJ@Xl0<&1m19(Y2kq%rJBHx zOyKu=LJ}1&xBNsQo-TwBq2Tmac*v=sKB0u3C!v=qPu(3=_BI7Az>}Mi$YLaDqK_GK zQY=pS3LgCRwLy`uHe4yk2yP1T5qg;go9bS0&`sEuPPXk$AyG>@H=lTQK2>Ete&Ag| z?*#Nkr_nKU4JPIl0YhT)Q-q!_kLafyY~MQG1Lfc1qilGa(*G7(BXY9!jeNQAq}Z8_ z584?^f)fpwK}Y2#uV|*p%nYT@XfjOeZO@dAEf{PsT(%trE6g4-)T_&uvgH17Ug87$ zbvG5txs4~X3@!zc4Qdsg z;AORWqf1zJtjpvv%(wen?wLpZpO0WZqiDX6&U|LEyTl~^g*|Mfr!}6`XEE3OW5-J8 z|D)|J+@f5&zCCnG42?9yFq9zDiVQuZbgOi?NQrdk(5<9&cStuXs5FR_N_T_IH|XB( z{XBa=@xJfz{Racb@w?Y`U2CoL3_xV;W>oEhtEK`j*T_3{79qo&1j}M0TN3n#Qa)2Y zpNI;U_j8#1_;!2*+HH65tA?E@a#;|G`V37Q9L>refnxSqUb;V`KL#U?W?7F7#g5G% zAG0hn^VDqPzOPhzaPWXzBB1eU4cU_+EGgUwuRD*CpE=(ZuS0kG1h)sLUfimo+^4|^ zA`+%u?AY-mnzOZgXK{~5PFfuWSXD**-!7zxr+E>h*3L{szP;y+XVT5982y%m;=Y3g zh%$CikQsW#`jxox_&fyIjqiDr{v_t*)S=)#Ht}~d&V(gCk`tU4Rgc|4C*qXct~RXD zYB7O5if7RdM5!YJeVm1;cOHF2Ftf%407wJIPJx>fn?iJ2MAlqRPzDS>RF_X*zTQyB zo#jRuH^KujIO4qbxPe`(A_4*I*>rSp$$8y4{o-JVDpy8RU&EiJ2oNaMLt@YujMD*n zJoPt)b|+uM(G0H5iplLhK$J>jZ5dpE8s5!%=6D9&u4ih#wv5s;^1e!K>nu}wyV^yd zBg}bR9vLIKV$HHgy=j^oTBWFiwIlS8(+Wqq2 z4A5AA0E0N-oZ2@5Kzfe=3iy^b1jQSMcD>N&DV60{M&0EQW4OG)2&>z)GD8Kedjxd> zo~gfo*{ZV_5|6V#WQmKBK|Rm~_u5pIKnY6VfuTil#tks~Y3%odx6W8=M=&e%!9f}= z)mbxL)gjptdPN2G2UEV-AQT5VLt#J@=_>h+#Hl6zG<0@mq-L3>yXe*qI=~O4w^o+x zDMJlyWXmeVLKNTLj5Us58Q2YB^eMlL9hMK+eE&i5_QQDf@q6R7A3d`*G{89ETiitJBad?1fTH^~27niI$EqA#g&VF3rnO#Hs4W3VIv$TfwWhgy* z;(%AHY7PLV%5SY)a!gi$&&FTmx}MoHV)%J(KJp5OY%(&3&OxyJ6K~Oe5k$_NzO@l& z;d3MDsA9#aypfH_CDoWzc>a7)MJ`eFSV2LQtn_U#Xm~3Q$sH|51eOdzm-sm}7*;|q zA2Ku!l^5GKj*@$OD*H5qd#qP+-+#8#g7tX&omz>r(lP3zotM6E+fQCZL_FIv_QrXQ zbuoX6d7A**-fjN?8xkmr@ZexPH+g9NrlI44U&W6Ae-w>{QXH4p(Vx7O0sS^+ ztlusxf&&^i18FKoxLHc*4VJd6C$?B zNaQ5MzUT2u9szw@pf>O#sbhx^YkHwJL=X-SVr|W( z#S&J~oA{9A!f9$@sU8oiFGxmB`(&ji)cZBI*n=^af%lX9n{~1g&m3cOJ_pvfX38Ja z#t}VWJ_YBrihJ=KWtQFSTSEPt`5)N5GU5asnv`8VUxj8&vtVw-!;;9@;<3Hd?mN{z zc)s+}{ridq6h%bEFMJqw>lvek%9^~>tLp3$d>oNkVbyT8!%Snw$4ceAtq|~bkkKK; zp?FCtF3FUgDL))b!T&>9VXeKTFxx)+On;mVspiY7G_A3sH?G?*uf)EuNeimCZP-2V z31rTaAnlUO(F_W?H#QG7)zc^$7%LT>#W~6eNtHGUfw()k)QGapu+pm7Oq9r&NJlZ+jg0{BjVy z+Ng;Te0C7fcNENIOnZ0HOszpBt&*HC>=1i67oATIzzdwT(+jG*ceD%>j=%fTINwb( zRsxk%BD`y6na-?|T->EAJnL|sTwxdn!RI!)p$u6O zxYOW>1^{*7Y=QweYRr<3MSOmF_<`JvaW-7p3By%(@c@GUC#(mi#J!4nR@D#JO7VN1gI(C9E^H%4HZN1rycz=?J%N=Iv|`6{Hr~ zisKSj^@92EbqZkF)v{z(97G+g7*rro;>Dc2Pjbc%CcqXADlerMt6#87WdeW?k)x`l z2h{f5h+g}k+bl(ZW9u)E4ULxld~YD#^J~4vAXgx)vyS1j1nOggL3bVTeB!zsa`Q*! zaa0M3YCLD;2B+0kg|8Uc0M;$ofR2D*0f5mS1eD(qDdv3FR{*p~m#5;(RlPYmQ|`&P z4#e{bEnf9EkU~{bg&6~bHv5$@0Lwf$#cqWx`CwZgPAhiv@8-7=FojOCpcY8 zhEb+hDFfvPA(YIL26bvW1R6u|hfhB9mZhVl$~bZO`87(Qe3*gPbtrTj#1sz5(m^Y+ zs!dPlxh8Le0#a$0%pVKc0j6Fl3~k)5dqw(ImnAGx4%kt3`?EiqJlq!~Vm~ZY^ECNX z0_Jd79QYP>f{%(WK@7r-@qv%vGjZ^e=;?F#P;5(y8wmjgjbL1WBO}23DW#=PRZy(1 zg$n0(sKkB_`h|qY5FK)*pQ&oPtJRdff-KC2gubWms7j3Z8XaP{hRc8R z%wF=DZLt0f2M(V^UZPUaWt?w~jOD)Sp%=-fxIekti}ZvVL^pYxWiRP@UXm-E=LA?*x<%ad0RcW-9^BkqWu!c`e|^rIY;*2{64WxZE?M$SlZ7z76` zZ1g>&=EcU_s6S3!9W@Y2JW-q=^4~DnprWv6On$Q0j!FYXBke#ByorI|f#K4D83+yF zr9k9zl&942TV*PT^E>iO1 zvkNXhN?gu%-CF75=FDFo#-&?trxAfN?q@Tobu$`wBlv73`2xH7UApi3OO*QNxEsd+ znt@lNZAq0?qLqo<9TLKD|y}uV$?@epj!~Sg+n2X`L~# za>KC43_-k>**eWV+Dxn>{)IYfY`Q>>N`IN${o=xNcB|4pD=!(Fygs`;$=jq6ybKs( zJwTFmmazpKj2Qy-Vgd*b^SC9`(I7`GOxD7>zvYZvbcLKSvPUYgM(`d%>bdvK{}DBQnb~FCp;q zC7|ji8fw0hv7DT(AlBs7o`XCA=i6v^b8apS%s9q60_A)Ye^rHvaEX}p_tE>7Dx@Uq#X)h4iPqWE52 zYiq5`@PPhsgB12;n$(D65bx@s4@?BogztKaWvfoag)JNE&j`@L1AZX0yjfA1;*aH5 z&o!FbWrb0N;tR5@NMRP9w#H!Q7!tfYw2A`X-+Ot21at{WM?+Hp3;`)A{wS0|>Rt>- zO+kJ5sMJnT@swz;mS{>GxX(h9wG1&3kejIz(;U^aLL=EUhww->6S1b;M6i?uGmXSr zr1END2hV0!Ss~VyWsn*q0u%tWMGMn4YKL?T-lN8DV!&X_ilA@~vXuA3G^6=a0mzE=c-xCpo4aKJOH=5YL(R48ojUMioXV&Tp6~4oBCS(?38e=^qc=b8hn&m>>Mh`@-z37|xl_CsVL~$M zo9fTq666%`U)LD)W*QaDF_u-_U0PX^RvA_Np~Ne!yHSa`eq-L2;L#Vad%R)sM8|gQq(oz+`G(*}6C@4O(+{ZD9 zfs&dFhWhk<#Yhnl2MPyK2K2(Q4Ii?9ZXET23~Of=KAwxrz*RF_N|R{97+b?%lA}w% zlTlhI9G|21g)OXzOfP&$r!s zc3n?1W3-YCr%ZnCo#w}pFFKuM58E>5o(|p94ruzI`6;@@falZHDNw)i;V13qa}G>% z)4iWwT7UBWxpM!5A`p!vTuTCwlLgn)wzdDiC<0cfY(nrM004#HeCW)^cN`@jbAMBw zr?d06fUK~F%I;@CH8_?NJx+6Y*1vtz4uxmovsPj~^$fMU!?15DT3o1-$Hrp2&%>Lt z3_?K+bMXyAQeo~fc#;hwTVzuBq%Ky&sz&zwc4?LynOQqrN7^cfs;Wg#Lh>GtY9i;2 zoHlM*JTI+uNUSeSzn8o&*QR+>u2cGo;D-?3lXz| z0sP%99fd!MnCDzK{tz*5H?6+-;rQc$`-#M!X9Kg`q5 zdGLmB()Qr3(6`cqclT^Abw{9BT!*7l6n2O2VXS3`9~1?*4nL~May@m(gYndPlrkJ0 zj6ZqkLBwX@MzIkFzD;v%8*^McIPLvuxlfr`5PfUH_Mo>|5%Z>$+o$KBB%+98JoHT~ zKYNKKyDoYY+s7@jrbW5ytMk576OF->Ihm*PgPcjEYj2;WiG@5O`pWk7>TIpBpj^Z$ z2XE|rz2q1B3%OVvja=MJL#_T9s~?onYdRvZH2-&S*1w1qM*ly9wr}Y!&iw&=Ce0uE z!;CBW^cQi;A3f`b-@H5gXz1y0R3E%*(w`vQn-lW``Yu1WQQ!JpUE*GYIzRXj5a0Yk zxhp9nVE6tPlsiV|-2Vc!{U_>qvwnr7`fO{PwY=~1{Cn#~9%3xlYg3`0YWghoZtFfXtY@i3U}Yl>--)z?(ZS8Nl> zkBk3<^wrWnwa|Gr$2d%K6cTwItJ=jNI3&Rw8LKL@?(10TO>^5NHRKc`{pQ6c#~FI- z#g)~F1k=*m3G0or#;?U2<%MlSfA2TX&&2(+-~4|XtKANC3ft>gmF{+t%yjK$)Hfbf zW=<&mk7ISRdGN1dbu`xV!kT&fRLQr_OVobrXwvYd1zr@o6|sO9ftdU841!k*fQmYu z%a0OQ`S69lYXIvPs4E+8?8#@6$2S`Fe(ezc7LO>@+JBBm?SF_z%!=|aj_uH2WpYTv z(?4=-e^edKpi;euzgfb4s&RjEY+uJw>$3m!Q#?F(__GuF`Sr5)|4a&Sq~UW-&H0HT zeDYh>!QMilSN5uzSQ?1GGm-NfhyF90`!5>zU*gez2k;L@kn5sfz=7Iu$hzQZhHtsx zjt$kA^urer8UTkk6GjOd&92C*V_x(n z$Tcl!x`qCVMN!b!PJ-=5SwIF2G@x^4nt~%C*rrvbL5Zy&0 zjc+->SDm$dN`85*91JIUcmbMU_*x-fofW(gJxhMQnBFRUG`F-5*=sK%e9yj7mh-*F zFuc*;(x##VlcQ93I!|P?Y5-iaS^Y*}W3y&dhGVOCXHR~sZpvIC))DOt0&keH=I9ll z3obE=*9aQOXwuay(SUFMQFWH|?0;3AKgR?Aq{X3|=z7KGKUAHI1k+)s`F)-@PR`;r z-cRO{Rp$lm+BWQI_VB^qRGp(S4Q;!laUF}YqX`4I>v)849Z#7i+Z|6^7L*;&*fwk( z&pP&Voy@sR+MRrI|5kP~?{%UgT7>S6b?bCtdK~6%BX;02jE)iY?9^76uyz}E`~JI` zjKq+Y2&jPmHnk-Br%>Wmw1;Qa->Rkkn%(0ckP4@kG?062F1=O0*t*FYePQxT4}lCB z99e@>Q0xCGWVkN>A!PAr)Bjw9{-b!By;BR-Pv^Ig{j;6D7%@MTsqn+RfviEZ6ZAip z@Cb%R7b-gc5Axetm)G+h0dD3j*JvuFwfUdS8%Vgtzp6pQ*z?y%yZg^U?OWF&6Fa^X zMqz-HUy(J^Vqk)G^o%fQzp9}gLy$FyRI5-c5c7;|krXVK4S!4?OsUUB&dB%!O_gJa zUcS2Yh?3d`4`uJQrHNgGBNPxS_%~=OMS-=I_|!V=-^Jtd`Ep4H^P2L>hQVxL&s0j# zP>N+5nev~+;}Ss&2{LaX5vjREVMVQpVVG)}kvI4y3F#e1*OAHKu+E zqyq>ot{l+HvlMDigZYLG$|$IUQz+Ae#Bk6VM#<4LJd0`<$XAA;_1LBls+xmKZb=+Z zIme))cPIdW=;STi&BvD?2ug85x8bi(if3%f%-j^yUpzx3eZk0lHCz*ghuP` zYczVrJ}}T$0>D-VSKIDgRQ4(-)xR`RAO#YsY!9G+dIEm~s#v%0Dx0d22I`D^Idmfo zE%CI{g;r~t>lGt4IS{bL?Dw+FcH0BEvd^2B|+Q%>`Tgl+#Q7(^X;>5Ss}_Q-*S@e z&##Ym=j){n+vgjV{kJYQYbWh5wi>^cUu?IYY+vkjU~ymW_E0!n?hUY3T<*US+_^j$ zmF50^IHv9J{b1hTZme_k0jfn*Xo=e{J0U8;s;XVU>fYp8hb5{4iacMa%pk*&q!g$a@?e z66|XQI94oq^p<)}OTP?RQSC?oTeCoqeq_Txy*>2P#Wmv|^jXi441n zOp`iTO-ooWUhBG|8n|9p)awIhjH=xAffIR;vn3#t|8bAYaG6L=P9rwX{=` z-uw`t;c8Lk6@oOH{0hVnB$mrZy-|MODo!1>Bxz`)Qsg~5ye!9DezTf8$X^Z;duei$ zsH1vlvkqhjgGLL_e9%FSTM6B2WczM1A|?)k`l8BB$#1tXeKCz`=tml?XWP_&H1lXzDT*&H;3zQSH)C;czs;^|a-c zAXV7IV?*FyK5k>(IVJRCQJ3aMDXaY$PO4ATVfY3r=4EevFjEsmN`yswC*Y>*Y0U=} zyo8T7s@h6KZ?yhr6}9na*xj9J34VnAzRuh5pJ6X|v6fRnhJ9Bv`s{0l+mEo{I$zEE zKZSiKk`QL8RoT*Nn6?f`u2FI z^ty8Qr2NI1HC6MOEB|$iTXtM~1cJWe@WpVe+5j@lyk~)agE*%q588$Ocllo9O8Hhk z{*C|yCqRACQ7z_`^gsz&&~viYEa&n8($4{;}}xJrIn@cCF?YH5y{E+nj&wGiFZqzH0U zijZIdqem94m#Ioq%NHP~Op5axF=rFX(9D>^#q@gERbF-p%xdK2nC=q-)u!$Y6}>aR zOIl(~hb+*8L&aN-GF#MJwdf$#Er_uiGR${XQwLiQFm|`dhr;DJS}*5KBcR85>?%OK zW1C&&`p`lsP@iU#M+xiL6OM|;(y`l3IcyrkRU{8b?_Cqf*c;&d4&)J+ySxkU05#kL z_OAge!_d<=rJ)?`Eu{ytK!vJavHHSv>n;Hjmj&^=tX!%c`cognMfE{dxgTu6XJew^ z6VDp1tUdQ3N=M^3juQTvs;`RW@CqC2yJCu4UPzn`)E=n{wA-)yI)Ec$(!CWc1 z_)uU`0OBl5c8-S#O~4dY9ukTz?oLar92%6Wo2}3$gGm`I6Uf^dDjFV4j5ot`M{ZqT ziVuFw?4P%8b6;bCJN&d8EO1Lwg$5gowoA%S<2|FCOAdL%K<_Pc_HaPFu}rzUG&d8N z;dh?xk7Zk0Ks6xq$A{z^_wP&gL(=gFzx|JAC{>g6pPa7WjS>HT+4hf9K>^Yj@!x>Y zMKAv0o_*~d`+3hM3zp|pCtXgNCNGiDo7`LqSd==tnID#AqB>2N{AQ(Mp4~4MGmxB% zS3_u0?_6%LfBMcwU^Ma9`;^vB)_$@4-zAxP`Cbi|I5@a`dKTG^E?zrz^GJWe>`Mn0 z`1Ab*-hGr*DJ#T276S^9>rmNE`xE@x@yX_5OUwhGHoeK5E-Q~0AaUSYolygg`_kD* zdZ22Cg&ug)s9`n$O&mgCiDpVZ5W1R`aUV5ZYx5@#hy$boVYj2f$t z6CdhF7L5xLfzfCv!o<*|d;@*%yPg_F7P2JZ#4a#;fFu;?#_}RzdS4VI+woN<6WXRs zhQ)C47ha;vLEt^)Xo_qMGEcv&KX|By5BMr-MbN?Qs)?)d4d6B}tnv`Ky!#+YUmht^ z%mYEgx$@xe!?}(#Jl-QOE+3U2A`?~!J+93u$OV471AVD?rEbM>Y|DsIgvK|toL@xH z!(Max-jYmVXsx9N|!=ok7 zqVY=Gkvm+tdi~_TW0uG*mp=Np$^W@H+ED ztpymp!wUMRu2VdcQ&sXuFn$_rF=iD0+V;S9Vno^?t^s!ce}aK^9Iv3gV9t+F0&902i3Yn1;r7n&Q7S$`%fJTbKHo zT&+@V8DJ*BmuU*;A6m^#5T<6!dl06@n(1L&%wU*dp40nS_4FeFn<^!H5b2dv7sN~Y z(Yem!@@ND(M`_fDX7*RA)62tvEBxAx^4F+$eJfv+Z@dz#uQiDfZC7OM6h#K3MEv8` zozhxV-4>3D=|{s`fEi=F@`mwf{;h`A8Iw6NFgp#TNwyRt0kC{754{8 zOX^fwHtRF0REX7As#FnDkvrVV$3vT9r(n{Wp8Fi8Wy7CPzZ1WM-K706Dz85FWK>DE z>|-msDw6TSo*8j8A*dV0`|lp0$~0?Tziq*h?Ucu5C!d{?TLb{U|MG79=L#$G4Lb&T zH-?=>c|NE!U6GfT5G$!>}5X>9PTJS=#bcOdM%8)vgyf~qNC&uQc<3G zavvPf^i39PU&x2Jh%Nz2`FJsqTwcQ4v?l{}?f%s6NRL^Tc5G>!IV(H3%5TqqGC(A5Xj9_5wB{v0$)4 zW5XafSQbYT(Rd1I67FD74Bg8%C6O1Z9nJlkYDn*$v?*c{XbHuyx77UiM9KaZENn@Bnz&sv3ezx=}$8 z8weMRy`eE$$6|C5Av!x#mm>Osj`UV7?UDI5Ac|^is(HoQr5svDP&?a%aT`3!ePTNs z-+TG z$E$UosVT5;(JZ5^Js_?oyYn4BXo*uy zmJj5Kg7Pt8MA(K|q5V;& zoacl`K@t@>oz#~N)x{G?)2!YmTYbq4(!lAuaz0Eq=ws+Wz^Rk`?X^Ez>(vr&T@kb< zG?!d!D8*{IH=0@Ug_n-gmtpLJp-*p`4rJo|2vz1C7-I$#0&_d%K>`P$N z2hY@-A-~M}ZuXxVpJ9C#r4e#i>W@Oa$jms~pM9Gx#=ULe?y~-&>_Pjx=XYQEVWUSQ z!nxSv3vIuQMBpaQ-}5~F`l-U9g3kN=swP|2rW`T^KO z83J(Vgbcm2N2T5Y(#FZJf1Mnh|k*CYEHNSvaoF#QO!g1 zOsnQ2ZKBrkvIlc8B6f9XLU?zh=mTNHRl;3m z$bqfCJy&jM9A}YWT+v$SPP8?5t3b3>@gr0tAfxBf%*P?`%~SOe$X=1!h}bfNVvOj= z>gr15lNFO)Pp%N>uKUrcYcyh*VJcH4XS1p{BST;9oF)Cv<7!9ZFGsS=E#yszWGa% zeheh7RJpt}@51?9sLVj0dx|TVDOjwnR@7pu=g!M-Q#hilw?@W_mkBvm$JG_Ufg85B zmz*E8$agxnyjAYWQAytx`+oW){*d>8Ld^T1pC-#A?UXra89ZBI_Qq)#V1>{ztlLmC;L}>6Ilqe;{3%NgHJgTbOtD8L8tyfBI)n(ia{{H>#ArrAz*p zLFyz3U|?XtMa$BeVZx#xa=QJbE6td++r0~As{09=5P7c@h`_?C*s8QKYxF)JA<$_w zV1*Kc!&e4RiSLF$sUa5IJAT4^KN#7iW$y=b%3Q@#9uyd?<7$Tgo{V0#`nkv;RHurb zfaQkW+IuN6jY;@vZ$VfPDEXZ!YxJ>Gggyyqj%`bvD^_kN=_L2T6#(uF00AQOX!HO^ za?1`5sn}#|W z9|ZSrfCZb1aP&l6GI)nT5>vYcu{Rub{EAWXHdASw-~JjGr~Kmlz!51F}Lk}(lWoLAhEePwI6rV`c;YBbFyUqxccPv zb`-bQx0|0`Ewx+pVg6nx3ZJj`Puj0oc8vV*0<>3G=$}q&`4cNX^5GQfBmi>w|zVhMeA{Z%yt0K}{%l1Wt2Cqi#o6_(N?8Dr7n6xG{Cu!!M zZF;;5O{&Rx@WzsbRiw)s?3k50w<@LW`98X@Hvi7^HRUHFjI~kR6rhe_kgZ>u(6x!)@~Sm>k?5xV|>4D z-?4MH`BkH=XFdbUzBvVUE}{~n^sddL$MB5T&j2N9x0H5YSG$GWUm8Ua?Qx(o%%YDmuYd1r4!N!9O5l^S zsX@N$!1!=YDE;9(`wE`9S!Flbe%hYER2xr+Ym^~s8#f|^qaF~5Qb>bcjp<81z!8K# zAcEX{Z3Vy^f~0ni+AR>CmM?S_9XX7TR+6{npRl z?YHKi0j`idoq-MqpU=xPIStjjWLIB46J%Y}bGiZ^Tz)2D_(?VQy1l83T{xRt?+*yau$xhfW;c1P2$V1eYK= zDA)!zu*VLoVYR1Wb+CwJMjkB8P>U14aBMg46vIwSqXc)qcFV}f(8$=r$ljDtmjXGf zo+k~K5lFU5W+QXZqCRCO_Y?j{^Dr{0Sdt}ouN9$ab8+HjOBuy%inW30mBQ#R5TflV zk^@LgN+VmZg5O1${is%Ax;#u ziYvu07Q2c>qBGXSDTdA}mR>j(Wjgl6lIW}S-=9`Qnm zBI0kMM9=++nIXhsjIrWpl%p^T;=OoSDv?}Mth}(lSZcfqRic`3qK0mwmPevaYNB3K zqQP|Hqq9Uqsw89KBvaiabB`p;)FkVsB-`mE`?DlRs$^&3WEb6JSC3@()MU@5WUuLD z@3UlIsuX|WltA5-V2_m0)Rge1l*s9nXpi{3-ISZeBym*0+(oKYt<>{IU|LgLp%alD zoLpc!6}Xp>7Z!hajrhf#w1T3T(&@DP*tAOF^jh8YdXMzR)b!@2^w#P0wzKpOs*En- zj2_*LK97un)Qq8~j5pI6@6IwtsWLwZXO8J+PIzQarDl>krOr%e&Yxv+4rVSGPN!7M z#Y+gj=s!!NReg~+_;eNdr;cV+jT8H-60e7)h^7*~v?6ka3g8f@E#pw*GGYwKVe)qp zFUJy@RAy`n6Ce3Te_j(7OMNMI_G0=h{=_Pqx;dL>h&VSjI~WN}{!LZ!W1I^W5Q|#! zvtL!q^xwHRK(hM(`+n8`&;(bxcs)e?o70#1NAnpuMEqy>#y?qQ|1!>n)Tq!a|C}`W z+-7n7So|A$HVM4E_0Qv6@;;e}MCB{t(}UGt&1XS%L>ikyr)rwSIClz5{42#hj6xb; z^rLQEKP*Pbg8#soI-xgaSl2>eHyg}XRBx;XSAtw^mC-(%W`&T5syrtQGDAeV6vDYp zZVW+ypiH7S$rIj&bA5H!2O~hS0HEG!z)J{l-4bMX{_u1;hN{|mCBEkMlnLs6F!IHY zC>ZTaQt={XZVZl;Zx1=O>%f=P+^{Z_L=816P@rWWl^$5`Di?bF)F7S$wT3}su~68* zW${d_YeB59a-?1mgN%m7uB6su*aNjZseBnxPanK6wPosr)JtVcgD_I9)`}vLqmAUp zf$VfTvFsFWyd@AQo|h6g9oW4mCQll?>)s|Do4Tf#*nMA zxG>1|S(ud2ToU>UJ%xI!(aTId2CN&%gn74aO!9&E;zB5M)8TghV@MTKaTqu~(wQqK zWrD-;F*g(SPTf*qj$`Wx!KUM*;$pVFx@p*^UFiJ%(kcVSaA0(QHV@4{vYOgD>yba= zyxoCY!D*Sr+Has$nr5kb@K#{Bw8r2_X!Xg+U97hg+{Z+AF7KuB%3So0g}&8hE6CoM z5JQB@){SdENai1ZFN*caOD%*;^P^IPUA@jynA`EpV?QJ@SxNjvVd7){mcX35`j_KR z9w&(BBv0N@p*Ma;PMWxzK29#+mv}~hJ!vvbb}Ak(dp&7_hQYs_iuV*P$V-7#L^{vK zdj=0DI~u-@Rb>y~!01$lZ=#PXCv1so+MoY-lP2`FGc(*f^723;K9!T-`c*#jU)Qll zp8vI9^^ZD;%a63E6ayVQtrdPmky+@huufdPU4Kd!B~spjPJ(lD7drfGY*|=W_*_mP zL@^szI|Ytay&J?6nT>A&>!zOB4HkNnP2e`rO?SQ<0>#fE5)Fa%Fj4P?!W46W$pbxL zk-adL$Q;rFSTDQYUbxPipZzM&y$D16T*`h}A8*=T{nkc)Q8i5 zjI;dcfKxi*YRD(7eMl#85(yH~wALuRQE>lxA=!pzIZ;da4F&R2-8{>ms`Gb#r3<*F z7>8w&EjRWE#?nccKBM@cUC>^tI2v`i5r4BA{-ru^x?W58^+kzUDqF9~l>A7j`ZBn% z*=WPB0;7+Pr$u06w#cdC-P>nwt4L4v1*c|})*On9+l*Rkvd8D{Q4-n5NJYrew+}Vy zllBiAk@M45@(7}Vcg7p-i`QS2t0%8RGZ?CQ@1F=g?>N1<^?9bP9jW&y)_kD`>*3S) z#ReBH_*2C069EWNP}E6%mEcm^_~wO+!2l*6=uPsvPI+{+#M`6f;_k>DH8scU4mhSZ zE){BQb+2Tu)R?>w0Fyb(OF&h{`I4ZcmHH)7 z&vo!ivSJ_PYYL<)b{Sw2DKP{wEfszTu`WLQDpVRNiJ7sC&ojiHo7eO;Gq)Az+x39x zYIZ2N___nWzM2bXm;aiVpq4jCu6F$ZscPwD^(rkiC#*mZwzLL`wagBBm23aLh}E zdYKbgv(+#kJj>NM8=k|}uo#!V-Mn5uyxp?hhqu$ZKcTSm`uOX`cH^8m(^floQjRa! zDbYU+k{ucs1xde^vD*m*TFMQxA^A&|V*|!lu&ztp#WGAdAnv>OPK_ zrMyE7HTX}4+2Uzxh6QRixjXK4r{FZN?{hdbNJK>Jygvs=9e$7(e0%s2|Ae#7Upbc7 zc~IwZM%^3Qkhr5)k6+RpPw6G!sGl~@MS|FE3qBpsAQ|j#Q_L2?p)q&XDcmTrWQ0xa zXYt%&hxfi{-)ldH(wDn0MONHBedi&2MbCjHYv49b-eBu7kgi`^^^MX8U!*su`<}=* z;q-FPwbFw5^KT_B_D{fY1^Z{7rK2g*T`~$Z)`d&qOfrQzDf+F2{m;IiEWHuj_Bt4y zy?L}XR$#$DvvIf_Bli7}nV@UhVdV8m&S>syv7=G-dz(*6wytJ(hG~5+b|<;pzaRG7 zxgA{w^bv`>tfennzmL%jH6c4Z#bT4lCh(~=A=}_FZ17Sg#Ae#1--PQN3Y@kQIIB3t zY`nx4J7`DIATZtBmEGgb#(g%$M6RBm^cON)Og`%>yQu98j_-2zZrOvkU1&~rD^Tyc3c z?X*WgEtpZeMF+Q2CdNO|nC|Md|F|!ulG;98KYJBRR3^4v;@uAXRC47zxz&JFeVM)6 zlUxwJdY7MRiDMnnOFHdE>8B7C|Ic_KTr;;Dy~nyDtQA?PwVOJLl=llDbqY zb7&C@#zJ3>Vm72pgULyl@5*EgPj_xV&AwyK8&jnCfuH2*o5-)c1#5~{u8~odZ@#K} z8^s{DZbdGpFugxDicm6*B?aQKoJ)WS^iNGlvrY5wY05q5Gg41Km6E3sltvKxxZ9E) zTlUhTd3N}R=g=Js8J<>RR6plci;eOsWM+|nANqkS?(7XjuUeYV<$VCX6iL6VCb8t6 zQw$lC=wq?qBCdHdd&l8`H3bv-k6ld)uZ|R17V#;x?T!=l|CD~O~ zwcor-+jLHSw*D3_q%rzbxtK4#SgU48vq+CDjS{0+$4w3HC*}0Q($0*^F70FOS3DAv zD2@k0K-u!O%Cu~i)Jf8M?H19}if3;z4G}Z^UA&x?0bgt;+fHDi%_HS-C4JKdbE!f) zt@4!2Fqxz$gSm??26*}}^eHHCec;{d3v(N7S~nXfM55~|o^Dz6J{@_3WU#a7ihj~| z!>dl?KW-30D|h%<|N4k)JbOS|-#O^+*doD+^V5Rm<5^=jgBH)$cC0UCWw(>yeq}gg zhB0|dN+*Z?Ubs=DF~vw@AJ?m@Xx2GHlnY8G5-RM6-g|`hz|?e4KIho2y%-ky)IsG( z&hd$nD-i9}A(g)Ugcde44vW-bO}Z~)alQby%Urtp%Kl@oY;zyWGX$MO^qrJc{BOdD z+;4`Od)MYME3L_iQD-BNyEO6{ zmiFh}9})@p3uU?1)gE|`7J7%qB3jqAYR<>YqxnlMxHj}Yo==o3AEc1LksV#XbSv|k zGM`0r9g3Fme)Ff*QLUTy0_js#-mW$3nd?4C*FoO9`l5!iEqlSVK^$xeRA3h1&a;cT zIc34-qPN>ztY^de?`o2lKbdijT+AQ8Yskzk-FS2{I~k^YztjI*LIP=qOw$`+Lpe5`@IpgG;~N%GQGJP!Y`$z-TW@Iq0P5DNhUa%fmas16k<2hjFB3jZN9A(Q5+5d#Z88a{K9Muu<<0tl#HXf52|!eGZ>^NboUlJ#6xXb z-l&o~9N<%r0qwx;m2pUE@JOFDZ6;T_J;l^f|J?M{%v{IASts}jcF0qh!#&tT+g;0> zLIhWigyjJAx=|&Vq2;CpUXVK;2^^=YA4LwKf>$@`m%cz)<{JpN#5>yc1NZ`5+!(Es z0(_3Wkg!S-o$#zxVh-LQ{B-IEJcaAVMWj zPKD53h0A0h2-ZPhp9R2CA=FLwO1Nlg`E;rkrZAZL=uw((1!-_VLR6w z;sK5E+OyD6DsgxlQNZA5;6BraN)!%ve{Rai8j5EP0CauJ@L2)CTiNgeAvj_n%2-qG z&=oJ=7qAI`j-tu6wZK?5g`1vbE=`GHIvKP%ikX*%0p-Emp#bQ2;EutfP9`JKv@ubj zxW2L>x2!_URtcxS5jML8Oqo!m}9BVfm4Q(tq0{*-c+d>T-FXR!dhG~%_=+N&<*yS2> zk1FK;nd4oL_~hw$Vc}Hg(_|A2&rmH3FI_8;VA^x5wA{5+6U`($E5fqVqDiD z#}+kbNfpOwRl3Rd8`53Q(p#INig7fuz@8ymY3d;vGa+dO(;3+U8Pq`}vy#qM1GWTg zw&flfDgyCy)8M&KP_&o$>-b06=q|JWblxt}|(IM3e|yRMaylAOG9 z8as5VO5Bn5c{A-mEBsTkJgzG$ES4#UUpUlYbV&*F-~_<{!N=}d$SGMsW*ig|ECgb# zu6!#f4I2^56z&lSZvQ@UN;XJYny}c4j5vpqKj;2Q<|R`SnM2O*6o|zthv_T_l{ohf ze{QE=_}Bi-^G(p#%@m*rh>1;Q=RqUp#{Oo7nD7dTAkKd~xs z1{Mev7r1#8Je4W%oX+>#D)65!aMv#MEzTdUfiPUbW@BY%h7%Wc_<_~7tSJTx@g2PG z_(9T`bLeDp(1(j+JTkSbDE2vu3kN6#v{?m*A&iT~LDQg0{t}Q#38qnroOVgGM@dUc zNoz{6;wZH=Y-zhleiv~*236^8ztXPh(zj=-qRd>k0a)+PKx12=iD}RjKWK&-G|LZ| zCoX@-U%sMUzUEQBky5_ZT>fzys;eyDBd++&UvZ#aapX~Pl2UQjT=8`ps*$V!Z0A)H zSHkO5A_@RNj+H=JB8=)vjPptmNfow06|PPdzGoF-Y87!y73oYB`FRy3Nj0@VHLXrH zy=OIJYBh69^{tue+vnBnBsF&gYM`@gz$w}_ys0((Ej9OMYJ|>fgd;LV1Zu@nwM;-* z!`ihE254l?OA-8X<*gxdBy~mnm1>@KnyGc#Ep@sxb^7OZh9vdI0`;ak_2!=S7OC}C zE%i1t^>*j=k4YLF1sa@m8eBXZ+)^7nS{k0tGwgG3p57mGzNP%hNd=#w=_PR zX^c8=1d}wGSl7kqG$nX8B~YOxy{7!L>kbQmfi3^mb+0A)-vuy*TXg?-ITcS)Yr7reE$0=p5m@j@NU9wft$C{!wOmxI1CZ@@WkYZ;}y5 zb%K?Ve~zOK{7~$yBrz~>GBoSCRDJw{ zFoJYeAZyyim)G~-(^;-+t6VF|;2s;JGL?d1m*PzmoFfF_ZTB(3SGC4VY-|Zk>lzJc zl|h1bcF}>Uci(P4(kL+seI!s{OXHV9G5zJ8pbvL*JZl;5z?A#5@QsZ;wGMaL9CG8W z&4=$hw9Hr_+Gm?ZGN-xAY{kKSn*e_DtFWz7DRH8uviy;txsJeBTXw#a}L{tma_c}Mo zZ%v@0h&%&#At~E{yAh1!z&&t}KUOJ}vj1-vJ<^Qz?{;7NmB&9_^#AB*toOXf9d|TU zfY5&AfYthkpV8>KhS5;NQ>0y|M*n{$C;LbDg@8TOzNgO8d`xbF+jflmZ9E?ow|s4m zfCYeI%f1zxK^Fg#Ska^X|6Z}#;X@9Po&mfG1%?QxKFCziD>w*-BBp+GIw`ibo?aK5 z?bD$%yVtLfN1vQ*zqmL*`EqS*gqDW9yLl*l;qfgN{BBA^Xxt}CPcbBJY>gI+L4@X^ zv1~>cu-UDpRDrU>+XAaG2>;8jSAq3O@_tyFw z?=bYN?bJoMhm{38*qu|0z|$`5T%R>NQQ@>3Vg(6;C|o_1SYhql0)BC@R>G!!vZMok zd5(DN5AX0lYMQ?jE2{e;`R+Hw3ddR|RNODGzY{CuCf@L0%g91t(45>#L7?rS%zYcB zW+@%~A3Gab^t>Kj)C*|*uHC{tfe!12LL;EVy8i|mvE1bXCk({htomDlB!~3UUy7bm zvCL2p-{zn?&J6DlwZ3s2fS9x;_N{ADNXMbuF^t>3zGvRcLXmc6k5NCEo0@?uM2 zY`^l0NbFpuO2*-q_%l{yK;z~MurY({7EAWFKm3k-CNq^tAf*bn)D_s@%Tv|h5X4-` zx;g>Sfvrn@#7uSh^89$5PN?>@)di=2$*L@c)tLy#_^x5zPQXfXR z?9_dJO;6QvEbEV=Zh`x>zE*|$sm_On^!vCfd9(Lbr2Nz);5H_dh_>CG7XjC^wVv^YAG%W7Fnqa(drDBcL8Wjh#NI z?MFsU$r*N-=!aqV=-T#EUSyWV8YJ~c(erP1wkb+KD8bC%YD>%|V{6F1cy2@KepwHc z#Ud;7_6Ibg^=Rw+&UPo3Db3HZgUrW29s|D5Vi0M`ti@2C0h!?wZG+-dXFn^!vT9i? z<5E}qs{qh9aj_ZR`!J(*2q&i%ww@;DB$x8!lf;s?7f4y7a{5L*c*igR;!mX@!UZ|=;? zJb|)UK5pFKtAB=7_hF7S`kiM+>!V&=lrpS3iR};S?}5sNtRsvfdWp}F++QoZ!;%C( z7L#EhJ`y$|5py<`@*$0#W|`ft&B3Io6;Cwl69C}Ba>*%(K57XStIYt`G#AXG?2<%} znG$v_7H(TLJGS9qm{x`cC)kY4gPL@XW&*SZn?f^uzIpigHT^T^n50s1BAT`yM?H(4 zP3%EGm#shoro6FpizAN?>ns4Xkkn-`LX{g-U@};(%OONfhLns&B(Fhm6J|WMQlFbb z%+L~Wunauz8yp4RS3-op>2bmXpobF-Km#}fs=gmi=zwGB;Y5N%`{4icaAIY5h7;bk z`Y;K`y>SfC5?cQ4;ryR&`tNh=pgm5F@XNLvPhOX&IkY2ju8boJZ^OVGDtpWTZg%^! z5oe1^cg&72*DhiZ2SAxzt@?wQvv@n(KcUY#Tm7I}$Bl^WJA@FIlQ$DwPj6 z4pefPr9v*So5j}Ub&L+;8_=cNaQdHKi3x$fw!_~Vd~Gukb1Jcy3%p$J8_06bY2ZZ^ zai3qAEkxZLotLOXYfp4T&TjZ1G9IrQ=K_bGlqrWp+yzqpk`5X2g`HA~_E2nUPzmNX zS_g;GJA@3gkx~cd*s}o{uAiO8ju6isq>rB~LTS|z9mAJ>8jFjC6*e05u;;);#$@*d?9uk2 z!2J2so5P97Jgpm1#iW&<=3bjb65U-igR75+JnW6Iv=`IDa&ke%^2qIT$={Sk1pEnXi{PuD+Q9(ZwTUoKAP^5uv&w}DMT#r^{5LS*)> z^{r0gw*Rg<>bKT+d7s%Ik-sX`cYPiC89WAm~zmg`D}`-7Z7ksU&p2uXsiQ4%pYj7meXBeKb{kXv*o zN&yO9p-W;c*eelXa0@(Yo;Z=Nvyr@OH@@por3kKmLTs?tup7=Zv*-;KNwz6ud;tlf ze$^0Whw33#yGkAF>xvKRWV6O`*fgWMJo5%z~OGZEaAFCc(DgEOOSjWsfP1=J)AdE9lZ3{k+O^vLXbQAC0ifSvQfRx9)Wt&A0e_Ze zh>aRUI7hNR%X9|7;?YPXjp%5q=uYlONDzs(xUnSs(IRl}(S6Z4cnSU(HFCSq_=YfH z4th1x7`VxeIk0h^Nm3k~FcXM{pQ}kJx<(pr*dORVg{6*OH%XMB$v>JeZcZ$gFPcW0 zkfV%AzartWjh^-XK@1^$yO<$tA-$n}vD1dI%I#usZV279N?4wB^KxF&);KLB*=39A z@w{FwbpgU@tgcy5bCOk_1O7>oWj3%07v5iKjY-9&7TKx55*w}3TJ+Y%^hhzD_};iL zVz)L3i79%EC=ZRPqfp#OG-cg`qxlX17MCwIu?)e|J+?YJy%6lwFRG>$n-Hv~+fq^Q zEE~zBoJ`crP{v>Q;9P$Ss}+8K+)8{3i=;vq;7LNKa_+Jqr_tI8Nb(Z<29&v<$x z&_dK=wHw*{%@8jBcAVwC)Tny& zdo?2l0A(Bl8h-9(r7ZvdWk0vXk`kdMiUsTbVbqC&x?!6C)_$%USoRNh+E13mj;b=; zA}~(Cw|utIZGEk*<+yzArCo@*3@@S4qJIbqJ;s~H{lRWnDon6ka^-To6N>p<3E!f5 zdpeeP8(MX>(dz~bE^GvrbuZ_O-tNY(jSPTVI33d5E(HoKc7me zqdmbWEqIc}y3Oe`brrxkx5&09L?{0>vTft^=w1O%DaOmTi*xQzB5}`s7_TmAE|3=f z$gnmR{<50^CN@y}`Cl?D!Oh;KpieItmu1r4KxP5Asgsta>OS1@#l?oQ~)?jO_xH-^p=NF@w;Cw@OLklK>I)cJ z_C?+7UNDHtR)~MX;+rivUm{6ufqOBr4LA-bs?@w9d^YBukHNkhD0~}Dw-XhH9T!Z< z({sB6`0yP3c%y2@L0m`bYc&3jINeAGa-M*p(>~n_4J?M=$LTH%@msO!{2^vltn5Aq z5w8&*hJhT=Wd>9VWz^h0r=!fa00g)K>VBSqO3Hsc0~}Pz*Uo9$zVO9Dzh%k{(*Ek)Bq>&tzafR=hMgeK;-v z>rN?TbxFs;KOITMlPe(4mN>e?RC=z8XU0}8ooQsg|9!ExFDFS*1E1%Wn_jr|0 zSvqu%b`yXie6S{lHJ7NSpL_dYCONwqYhW}WkO^q61V2}7ZCc>{XY_{*Z~@f(+9lAW z0AYseuhAccj8P%`b@ca}jTj=uyj&c_sxk14Q96q-B-#8o>dt=wb^N37k^3Q-BlJTH z?Dk;mu{v9a0VW?VB%)#O0S|6;T%CBdgLtATac+1SY~aH}=CZZ3@Cpj* z_|)tvwey|2qjs<>Yfd4!Cm?+emxX!|G^GD(anEm+LgVbBYaRe&g|BJ{Fyu6RDo@rZ z{on*051@n&jO&uj+Z&Z(C4Wd5Ll24+U6dghpv@86bB4)Q_r_DF6uFBrG!UVg9I_nM zT-LYzTo|#5#6SpmQ;Q->Wr3qBq*djxOEj`o2wqk6;J=-?8ryWLL7QlZfh(S*^{^=> z83X;8E}0yrKL5emY>n9y3*bS%oW3#Vx?BCQXygg%c>LjtIKiRuCDJ1|<3HZj|h0+;rQc8F)bT!SP zc{aZz(C=QoeM1&?vfp-(Zoea?lpmWlS?ySL{&&oa>hkLh;ecHmn%ctQc#i8)=qfPp z3k3QDZ4gxH$F$XqL}#aCbY)z0U%}FG-5F4*Gwd#N41#si1#Xi^XfVO+f!Oz?@ zJAFf7tL~OZI+W?81lJKy-_6=;gl&ln}K>dnN3Ln#Z0kh zA0@?!8(||RV27|vLc!EoO;OzVBeHNoCLe;@eI!ej1+kc%;Q35Cgtmm)b)r2u zv@pP$Y+^H90iR6ZD=b05xo^clK-(>{7M@OB9d!9I&5H%ey*_n&8U<>I^^bm`^ZN@71|UGA z&_4?<$T%1l{|jHpsQO1{z1G7Du-W=R6cf=!doKW(-e}ccm@O3)LzQG{3<*q$`J2po zmDuWM6#9)3dW|ofsCK!@so3zvGc*`AWHKI`^E#*w&8^Jtn5_v~E2tPgLau{d2weyp92l!5bnIfhCbh z3LA_I+L9@_i&>dQuPpy9`YIf#wxekK^LW>VUxhST_Q~Pia_>E#412HB2R=rLQS+r| zmvDOw?`^NTdqKXUb;l#tK3E%yIfYAK0xKdOBiIey z1K(I01-UC+*ba1{|CGf;jgkZoKnJ!U@^>|qKMdssS+Q?2tVDBOsP>2*AMz^MOL;KR zJVPHNG!tvnJ&ljo&OuVPJ#?5_g(7sNwZhHwnebAq>cisfZJL=FR2<$~K9a`bcVEwV zdW4dgQ+9lv9DrkLHk7$z-%ZrXx_z$rmK0|8i7pWH#rl18;2>le zN~Sgn;$|958dbjBs?F}nlZ_eIaNTj1(e;5cLc{mh-#2AB5dT(IiiW0OeSmKSuxoG+ z2C7s|wdg(X6>7S(x;P^Bpte)q+93i{0@$XkhW9$z||dNWimYasKrqCdW+!!nHUkYJTV=#n2YdI$)c4T|$qf}JbGvf~#u z)e9B`!izzhTzs*f67)Q zDmcrp2rFqtmmbUaG+SDQwQXO*JW{S%l0h;wzUoncHk!7Xn=d5sYc1jZMzG2zR14N$9WY^RES;#bO^mu8P}*fEle5pU()45&R#d)#nDL1 zX$y~(0U8xnSwxthb+hYgM~Tcu)iV6x!oDWh5WEd%B?$j`$ZYx!$o^1I>X@FiRX}$O-PA7O>Jalb;r2Z zlWp?rptYbDiPpdy3SX{hbEIc;vv0PWldoDA8)|*1w!@f9awP{IYF0^R*1}8sdXH-F zNO}I1Mxpm*=jh%b>H)ez>qYZ|2!6Ep72dA~Dy?on#XizvpkuZqm4W}@I*IEm>Flhh z1OwuR-y5jAhlb%OQGGeqFl~$`5+qt(i*lXryd&X!@?FZ<6hUKgK`d1~CVHyKD`Zlb z3M;wNE2aqg7V?XautQ;^dT1nwR36GaFo;E^8Ur;(Evjhk7UR39aADtAeK~a&{ zbUEz9HBnE;RpSiiXcP+ty)9F7nOKlGqNEJ3*kqP;m2@-<7x^KBWQfpccr-05a5IoY zrIyy#i=TE~(=w`?q$sm~YpbNP2lu9d8m>`Pf6XRuZA-8;|6T{W8O?EB+kOFn{E^)t zqt{FST|bhhTbcYiKE=*W@Ml1h5KY3)hWIDT{Fwv4N)ieH{$mcD4m_!wFPv-gs z=BSU9b=U>8IDNtBVo9jbukl8=gI+@HS_r{7ED{l>P^PFJjW85LcvICRsSN?Y5;jN) zfo<0^2lxkPJV;#89m<5pr}8D{TR<9Ie-!g~Hgyiq?8>uzGR;`itYZ8c!gW^5o>~$3 zOG|MbOOr0X3@8myoNv3B@Li~Cf?h)R7sxxdq1g?^!i%S$50PeGWnSqBc|lrt=Ed&& zzPvg`on?U5f&9DY-4V8M_5I;kEpPxMRouiLV;oXAEcnctLk>iUbmAdAr%MaM1%4Je zDl)a)BYq6^7PwDv9&Ri>6T6^Z7P}(iq>jAj(Ut5jh?xA)jb;n_0!z{JkwwE26JKPXSR$fRk+S#q!0P1UF43Fpgd= zr;|?IX*bld!@4$MY{k3l6GKfHq-FgZxdi(tn-DAnsZC)XeVHNp6na`FiDWARUFQX} zu9T;RcQ#fEh;~nsOJKX-^(={8nOZHDqIXPLiq#~zQ4o=iQDbEmbTFH_)nh{#B=4L_ zXH>Lc0G0tgh-Re;!`R%#3WP2Y>-xL9p(W23f`eIIlIR0%(opHGhZl|=%vNq0Q zte7|6J-v$%***uqA5CQNhOq?UV*B$O&i8$$(0-&GY`){bt z7PlXjd+A>!dY!t0#;OU=C=*fcN#<&^vU+%R`V;$s)uaq0h0D@A0H|{7NB`zpx%D%H zf1$$;&ER8Gus7Hmdxm?E;#4&6H9d(G$?*B=%HDjijZS1@pXBZ-u?64aSpa=#?}@Lh z{j@Ir!~ByR$p!UkGAToUVvfQr+qPlEIk8f-Kw;fBUc%8JRHFk*4V89WBk{pHu5b~Y zb_kUN0t~xS7-BLv!825*VVp<`|GFT#3pCSQW0n|PQypG>PO1pFXN+J!GA^E+Sh&!{ z4k3L-Xyf2&?uW67poHPzW?4N{6Y2oxrBUtuQEd2 z>vtL;$m1%Ed1JPr$bi@SeF=+Ylc=&~kb5f9UCOs?^GbPY>cuzFa%R zS5*)KoPOb|zHu0DBu|SX${2q+!aui_v|sXn9R%{15QD`}_=n^P!?qxP0y^GoO; zkdF^N4F>PD7Syw<*Te3hf8`l3(~EwLI`HDPtEqmV->jVW8(dk z9+_cjMth5JSY*l#^GzlMVyg2F8NtF3k_QPHZ4iaT_)W%y5SPdK1~IC@=Y*D2F;1Gn z)@6gS;o=LEBJ+HM$V8CISB)QtjMmdU=%6wjeU4};8UxQe+nErF4g-!3@y$bC1+aS` zkgBUGxP6f6qY6{{voJ#r{b#Aa_VLgBfvQvKAOG3^xORbL;VPZJ25`~XW|r31S3x4P zpiJ~&N0IXNRWQah4$-@&Q@d_0aLNn8Ym@4`sEc~0Y&N$4>mHR3GKy0_ml zU4nsc&d#HEuJlbI84rNB-QN44VDhs5 z5%l1T5e*)w8jfNr0h~e!7#J@Y;>ZyDC6yzP;~8V`>prFxejeG4U@9)_fxjrnFY$Xz zA{xLBumgnu_&dCNzhBhAJT!JjFm+eNwN8m~i2T=ydWNr9%xTGy*U8OdGN8NR0DTk* ze7;E${899NT-0~BNHy;=DP-fM%UmEk|I#V_5zv@_$f-)7PJcM>-|GB0{6mZJ_Ts-P zD$8L5ehvb-324lxcy_IVgpqH1$&(aROjiiHcKy1jZ&(at%?g(ZvnwiaAMa#(-vJzU zy-WetI}6&fwBG*YEaG!+@8bGp`TcX<^0pWDN4wB~#(sq2qQvR>5vnKKmHr9wR0H@v zj%Elx0WBRE3(4Z)s*Li+?6FQD_8g>3|M!-76m(VHf8E`Tdjx+xe;9iVzm3V03^jv> z8q(F-9WmdEk&uc6b`xeBx|%;i4MowfNYGM!?u|4PH(M!45lO;!+F=V&qUNmKodOkj zq>H|if!^KM&!3J;X$shSy1{aWL+ml$Zf_ly^^_Se70RnZ9OP+FY4(n}XQkX$e5I9< zi-BQCL#Dd8pE`8n9!|d|jm7H@RPe zZ@*}k*c$(Bmdcw7DW`9uW2hg!-YhEcwd9AdZ7=#doRRFtHLn)D&(-=TaEv7Ds>Pj5 z(ZsU6rC8l!;W@_OQUZ{bCx`tArebgaQimb9A^h?#nL&X30}2ONW2Yqmi^PGBIC&3l zE)-=oF|R$D&TSHQPl!kTy3wN+E^1zH5=~U+Mk~j4v_=r~h>Iwiz7nPbWDYWNSB)aj z>IVm+QALx4;l+Iq0pbq&-iZ)h9f>RwHZ5jF2g#opB9DsTS5dlmEv+o-&m4T({i_eT*Dl}SSE zx7>(cDjwcp`iCC*Y?KLHIP`7Pe~bD4rUFkUi%-|`>J%OtvO(kBIOw-K-hBJ+U%uT)lnL(g z=eLvB7X0z;bbo$({-8fI%3AAB4NUXn0^wY-8%5Vmy!+R07oPF^UVsg|l$qH}5Qo?- z*SD?@&5QXtt!~ZA#?kzTqU+Z@mEQpr{}HVH$_qIkcKQ*XG-pi`&=IM(CY)vjkt-#5pN%e*5=nv;e>ewC!{=jTUW>ZYWdO z?JG z9SVnF#4w3j!w(p{A#$1OfyGY64~sO@ts<>d*8mk9m>zWqs)keAW=Ls+mL3SUEqR&ss3Dls2Mv!;23R1B!^)?unYIM( z=a09fe43x|Gr~-WOsTh;A)YmaX9q|fw7EUT|b1Z&B zeaz&}%QAHv@x=iq|0{~C7p-nzaQZV1GRZHTj)RM^<%Od^h|MF-pn=%|erwAB#0^bH zoIC_Emb|zQ6aqX47iC<+Ncw4QoNz?qAh^JU#UOn3#_SMm^U&;Is+hjT5Neks>Tr60 zH{&pxoI4>jb17XveF)?MRdyvKSOJj7>{r39lkGErG3F8OtPB`nX4dL`JIP zZECFXL@@+9m~N}MwDPT$by;H@6rb8MH*H+JT+Gkiow z1c-xz^;N`D0&z9jS>FsR%+KX#qU{~^z>xaYP(-oR` zicn}PQHWR?mVrY9eB*hzWf8lMC)Lt<-a{RT|rdZv8><9s0rS{dK*DIg#V5$m2QB z23LLE3?mKRju3`R^QF()NcAje4LOaA5gH1ot1&tmd~31xyYA~**5v%qnOO>Fo0&f5 zIP*T|gJ;{mE##itwXf!Q6xeOs%14nUg=$*1f@e>rzt7B~aB(B1b7uKaHG=L{Q9h}E z{&D=#^NXYEmVu}8M_+L+PnHrDFHc^k*|(i+R#aS`@AhI|ef>P4cy)2K{`~6l>^L*_ z{^mIXU}rzV2Y$#GUToq1u0#6~bfON-Q%YE>r1m3uB|m~%L%3IoA{cgi6lCy=NDrhs zu~I7i$;GmfA8Lx?XYA2m@k(EH@&LZnJ@?^F%f@)p_loSSGDKK6Q{f6$s+}5pKU6}F z8auJDi~i1jn8Gt^+ycgKW|jSL^*2j+4ok0yquA)~qnUtu8GG);>_1!0?H9G06a|j& z1>))&kl@nfCt-;2MnY7DSBl>FkCP-JD~NE- zT~D^YWFggw3&3hdb7^-agS_$u=ct3u>T;frj4~i$4Gc$l9OP0S77E@DABx*$BQF~G)2diBhb!(h5sAA=GlD~%DzcJ}V6V{HKvg4KNiW;HDA!@@IKOJ%QSC0KHm z93^oxP6lq@aD}^1A;?AQ4FhB4mjMu>9SatVq*w!Xa2~vvHDFAp9f>%)%v_J<-Xc)A zZahAWF&$Yj0$IJ{?65+6r{p9jY)G9QmjO%OOrQ@i+(7Fm^ia=09n(t1Yc4l85uwx^ zQ)XnpN-md@)LO>&Gp2!CAm!!*DH+)gPWakod>un=_$?|Zcc7LwxS=uRKAIzVdb*PW zB+@7N0pzQ_H%>w75ackkq%=DoPsw3}Y|mOPk>L-H%sP-{Y$(xF^8eh-b+6C4BSP#<+ESMRB3**Kn@Kpp6!3LJ~5)4bU7KWujn??4%Y|9r* zG+G7O@FjLr5IpBT+1c%aI^obxdhA`N=PL9PUy z_0zL3i#5aB%JY^Z%Ju8RbtujC{+yWGOHuWdlXaE`-ZJ4)_o;x#A}F?&uko|)fqZJa z2@sXn0d6I$cW_<%8DPrAMw@0<;f3irZq;DdDw&6Y60h*C(VIPwi}RR_ID|lj#TFb&%}9 zV5>RB2M&n}E{TG4;C=B9!FT1}ctqT>DJ_0@6=VaJ2v3hDKWI6U@}-v{8VDePZ?$gY z8*FI#@~Jv{{r>T(#(R>3A>wNK*18~{f)+4EM=}nuQ2aq<9$0;*6JHn^N8H>N98{~# z26zl+!DWx)Wifo&KnVxha)>~&@P9=>E}j<63f5_aK`sGH<@jSmDnki->n&0mCEv6I z9xtvfu69nn8$59o5Sra&a^#;E1Zraf>hG8n%Qb=n=YjBj*jjE(03}QiqAP%VzFOEy z));hdj56F5WC`p1%iOn023ru}h&N}|bEMyN`g_kzeM&F;2TfG^qQoJZnz#=BS#>dSW>M5v&JWD{d1Z zeuDW}AJuVMm4)LbbYgu8q}vgXgb~wu6t8?)LA4Yyd#L3g7w%DYGZ6esGi_M0J8b|Q z2&FLfBg`%{-3BFKd5D9}IOtdyMBVH8_{dipgz(iB3nd!l6{KfA9?177NKDg@lR;mP z(P`r_Xf}YeD4IWg=Ho91S!-5 z%)E8+BVqNGFEW;DLW$x+G#x@5(SVP8whaJt_d+w29^v8;FprTJk2y%I$1SwLufff0 z{tI3!BYv9{PK6VeYpnwH6~zB`o+Q7PNR|`R_^@$Dx6T#V2Sw{atC>2;FAyo(P*szB zjV^eh`-ut^pUNAo?-sv|7h5qLKpLn?D=kwBFU_MS%!qJ+3a z$o;yvB=6p(;d%FfWl~wefF|wkgS0q&?w%&z*G|a^r&t@1BB)hWP`zpeDO1MFCD9$8~+*rSNpuBS?# z?$`@V8NI{VNFq5n;aHoSS#K14tryxU=jFwXyM^d?%xos)aR%>&6iRkWy zlL-;0i4sGE&vG9$%S*~YWQ!rv)43975bXkH3Hm5S4R0b`6qm;o~E_hEhoy{XX=8WuuIp`rT!jic=< zhbvGl7+(j|Qiu1tPH??0`>ak+px#)g-pI4wFtvWHOa8+dreI$|Xnc8MFHAv?>>VD! zZioUQ&y&R`s15D6mbhZqbHVpLGn!9K(nX(6^5dkYlp`9|`ZXDsRo0@j1V~tb#Nz<5 zkL#|&>MV7tYdlIQP@C(TtEgq0b3B`kt57DF@R~fFcto&|+YtclHrZ=<>@5QJRnYlx zLLz&WdRs#GSj2*?8^f%zB1$A+P8*dgnV%!b==bQ(o}m&Qm$4%Qaw&zdUMothDxTKn zTU`;iEeN!=X+PLQDAso`$K)b97H;SZa>fg2fK&2VdDY_80<+zlJS};@d*)^TOgbJ+ zL)HPRDim!STFI`AXw|`C;*5Gw#Z3N$5~!St-6)FxvQM{X#zFPayg2h-LXBo)m0tSFxi4aiu;?sl1dmmojKYvNQk7~GxCEla} za#Cj{)F7ctMITjUJjf*V6Fx4kIOXqFZ>@Ovteb}P!KOeVMv7fH1nUDzE(KaN(blVO z)GjuZtV@|>)M&HZ)$*y;ZWdyFfKH)XTCaX-Z)j7m_lI6zv`+eaodLR?OL-;Et!?C2 z_c|;-^o3{lFs9(TTIS3nwvTc5pqclRZ1vsO0bf|+;FzVP-5Us{;(MS|SOHO@{*v3} zpQ}Cqc@>scjmF(y1gVmHUGwyHvu;|`o7atBUpL&!lb^;o?2=>3YlEb{!A*{zjK7=yzOeYcR{wj$$@c#*{8bvsUs` z1|H6fmutTm(-kZac7B@^SV)5KWTLK1Sz0R#Pn|GGIiF?FF1`D)e7B=lcgWYF1)^Y9 zK{eJ3MXj>BV!Gm|=w-H%%>iW1L3+)(){|k8lQxi&6#hxm!!lHO2|VfeEOB)s1PL0F z2`9k``<e*`RX8i|KN~nM(PYYQ338uNlFR&QS3| z*(1!I1;!!dRybiRIXHl*dL)jj6*ef9<;A!G%Jj(W)ab?3SbAZuyq+6+Dr*lS?^O#5 z0zB=L_p+1OB-wY=wNt0ZWvau=nx75MeUhJyNN?WT>F;^gi!)|99VBEBGU&_$z%`G) zcWVJ>Fk?#oX%=xM2M>Z~y_tF59WAdXWLg}8hfmT=>e5peh{^LwFN?_ROh|SYsWFx) zc1LN2mJ}}P`&x&n_A&F?E1^&@)C1H}!dI^d7B)D?Us+EeU=ShArO%(w2tEpid2D=1 zIp+{yl9)QJMl`vqGan*9|9NLlWo}MMs5xqOhA=v&6oJfur&l%~a5=FY^>vxzLz6;! zpw?PDChDR=kzxZSz$UmJMQBXLYuzPdUDsxK&=RYDk8|R)!zBnlT@+vRiM#O?2DAy< zXntFt&?EjlI!c%lhT7!=w*shPXkJ*OBj8rw(~p}&t$o=FeVMnn{GN6aXuoB(BaF4} zi}22gEC*3y)#hvWLxg6>)3>u zsa@8CO+!0Rtq ze&XtVbv%%J&*Ag2|NWCd#W#LTUx*wM?dOUECzO?SRcu>Ip^W$U8d|sIPdOi*+FUsL z>y>2~lx96I&3;#!>yu(x;cqLTrXM<;f%?9RSj|JQn5|&?5&HRkgc;4#_syB-t%^=B zp1*HkHn{7M$Vrg0cvx1PIMrdL(rfUZpMHwpZbm!)?EUlg@yvBG^@EZt4ZN$bO*7MD z3lx`*)7_l?$%)!R=jr3qsZ(=!7d~5;=4In!rQ`dUv-%{n6SLcA6h%Gd{(yb^b~ZnR ztBZ5zPm~=#mxR>!kR5zG{ID3vTP>89e4k+oN_=eutw==^O5>*`#n4E^6KFU(O~vH3 z$8%ctwDRHPzfEDYu0J#TL@$>k9tM1oh@JNmMw*Y`7I>HGeKvd0*{$LsM%lcFp4fGo zqt>$VCWFLuEjT+Mv!tQA_AO76(Byt|&{Ui@5E?@J#x=nJN(4H=MLp-#{Z;BF?+ zmOW*V9)LiOd_{OFhyn3@eX?1ouX=cvVZ4w1ViRr ztH;6iY(t2Tcfp6MMkDO6Ty)|0{aj(6eMVx}DTG4SL)4qa{WuDV+5F`3v8`y{O1*zZ zootf>y8E7fgq;EHL4ZsSfyKe@MP~%VaO~U zhiJd3Y|GT5PX&IF=euhiE6TMD!FeaJ{^5Pj)W@Po>1?}2-#fI`q*+&}Fq(XC@yU>g zv(OhLh$uyvY%II+w|O0rL*>)pxzv;;>FUaTvP`kFJM*Rd$uuDBu{3aA{^6+b(=d*V zoD}dS`O}&#uUX2~aAh@38u;rqO%os1YgNX0C3K&C3{dXzv=b3UjpFTh=n2eO+Q8@W zHAIlA4Zd|})Kb>0LC=*>G``;;Y2=d}&*e4}JNL9@(7aRwV{W`kTs8sryvU?*#*sFP4>cEN2K0Dq!k}WScT5RL06Q-SIn>BlJx_Mi_ z>5_OZE3Hd=yK;gKZ%27-x5>8ITiwxy_O*31eUmDXuPi(YBaSudtnCbn+Pv_v@)K3y z-)kb6XmNP?D)^~I|9!h^o90OufiFE=6Qp)DRHf)!FCRLmyz0d0W$P@#p+Hs|dD#8w z!)sB*7hBT-oqf(99&*hdOa`od)zjg%LOLGUKHtq;iEWT~Ur(giDqb(>jXW(W2odu9 z*pRs`P?Cn}z3yUD^+9U>t>k^L!{O)FUdQtx_q|Wo3toDkf9j>U+}Ai=9ZA9i%> z(Tg=Qgs0BKb7IX6FV;lf`Mz$+IJhJba*+q|w2}ZvMUR`Sj2>S(hqUMga$DTXIf&%0 zAW275oan&WeS4c)H+##800&sVZ6|w{2_S03CNqxoWizHc4%}$}#Gx3PT9RFOD>Rh^ z7{%@DzqFO*_Nq#JUnnrv7{@lYn`v$>%-|z6VaZ7YdxEl^sw{PpMQkzY2qc7$$`~dh zw3UW@FEWTKi!3CxiE|13+>nY&!KPP)P?XVCcX7cCm+02ArBZY-EiJ7pk2Ka>g}a8a zq|4-q(!FDJU^(ibCt^f0Dp4bGd19-N6`Ew!sz>6>0#{kgh-9_jjwIA|t+Fakkpc3V zsb9jIvj_3X8RNfC>V-F#05{2*bH7i1M{DjnUf780{Z5|kN;>@iqwO!_qFmede|Q+W zyOHh`6+sahnxR2LK)PExrMtVkyQGy;8dN}}ltxmN4i)Bq0>aX@)^*?4{d+#o>v?m| z%()-2@7wm>g4iA21h@JN;o!e}-EvRPI`O&Q@`Iv#-6d~%>Tjoi{e*gQ_E>lX;XOn9 zOA`TuS1J66do=AoQEK*CBykDH%#ks1g%MkZ33v#^==Edbj^o}G-wY5UFc=nlBs>yc z=nrXMekXKifIHTyJfDfjOiD4drindF(nLsjD)~~5=5s*8_EIFo$LTp z!?lun!#JwDs97E(F+wBK8Q=8u%bF9#Wgd{3*xG++=?mwUBB2CRD&x!^zoL3%D#t%S z9e}`W3Bq_D%z@Jpxgc7InZGs&dg24JqjscyS@KB00G@os`~%NBtxEem^qCcQCd7dNMT!4C8REYv6+*#-p-SoszE; z?ca^C&9oeP=P)W#VnRH z{;8c9|KraZ`G+O)crR{iFd45398Jl2s(#Hvys-u`P=ju5BPzB0(CT3I?mdhMC5Y7x zqpj%{E`BGcyN7)a@H!bWB8q!J4CrAMhn9BYvq4UzLM zN8d&7CTbK_s}`m>hN+(^_50tlv(4CAHp#o8F>KsWnI(gl9V?v9ToJs7o;q*2VBfdqv=ZFC}lVPHE_}XOFVE-pyFm#xX$oIG9-=@8|FsPx&o;#9Av@ zGEH`M(Gu7Yj~ek7M6ufK13GEqqbEuo?A)5g$U*Pig*l^!O-U>lFbpR6$98xhZi;db zs9?!I4NdsW!tF3ytU?$)(q$Uj5G05)5uLVO;d*c!G(z?m=NpHDuV|DmLde%1_%r?x zIKd>5YSr-!`W7dhg_=y(DOE>S02X+Zy$JQ2&loBbP)2D*MfS zzlqoWCHbkVl-E4vX@&FKoo8$}EK|2MnEKnLE23i%PBxiN4mLa6QloW#ESJf;_Q$=l z36~u(dSZ9aLkmymxLe}kPC}N)3U*df@k6yuVz2JA1x3lnT}#9z?*unYyh1DBU(R{S zf8Xxpd?AslJF8U(IeNm$F{0V5#Evz6!aWG?8HTX`cU z5y68!v=?!=PHsb#O4`4q)-c|C+4elt(!B#?KfhERZ|Hpo_RkKKeZpz=R6L3dx)T;j zy>z_T8#F8soH0^MX$VPvCkBB~ds#MmdFKs`1hZW_N`zNler?{D0X-LLhDd;!`09#g zP)GK^^GW~z7I*#IDF43_h5g-WoOM{#Qa^-P`Mb*fFD1usYKFblE6LvGxh{s##CnKjcwDGV<+gqR;ENed z&^{MH0%EXuskfzC7Ndl04NnbPYWgA#$U~MEHx8hz2J!y)kI*O|K+r_1{qfV{@5j{i zGusgUuW?5aFzw$w16RMM+83Lqoh7L-I-R#aO@q3?E`~-0uL)C!1#s`5lphgh6zGIgdd< zMzXd?D^}+26@k+52J~}+gnGy&r!Pr2kYxpMrUINkQEtG$k6LMl=VcvPV)V;EwNi5K zOg-oHA+fGy`%5(&o`;h#JJkR;VUP=%DwF@ljh3}I2&66ml4v)DDqO#<76?hpp32VC zBSSDr_nBe9@pf4B;6-#z8vi?|ue=(`ETlB47i-Wkz@kUBG+A*h0jIp5^~GZ84M!>Z z3Y1PVlX_I2AGvaio-A6;+S98UDH{9E(aN(<{t$VIaq^f}oE!@dCD@w9aw}-{#W&;Q zK=SHNFjM&UD-^;{+Z{L}Lzcgb*CK%#+vrt!10aFn35XxUe*j1R?iMXaDx^@@%>UCZ zdM?zG&#G5#_zA5mmUBY?ND3%*3xc~SRpv+(Z*z-BU6Q&2Sh63M@>MipHEDSiVFcGYWbz3PvzXv z7Z_lcdD}_iNs8I5#%4rg=J(C&uF!EL5IdHxyr;WUW51ZE>g9M;7uC_pcNPTC=?3j?W;FUVL{Lr z8(EZq#5Pwn6o(tDJb7nPJc5kF?&lh}p+pR|KrVa9ZoYIZ5&55%!0Qb6VO97TtZJiw zmjphtVlhHH*TI56=4cH%u_+b6OVwvcPq4peahYgQ>J!WUe1C1 z>I6WXTXQN$Ae=6hzVLs`;Ma?hF_KTpP4@M6Av0pv2B15d7f$^Qv- zhSaAb0|wx`&k!hqTqcaWYma}knAbD91HQJNjdx>1~;XueVM z`vM zpU>aEWbh@F3H28+1qGkzr(<-EP!Kw~lm{O-ZFd;aZ9M;`8hwdyDjwFqoXfunQvXn4 z{||=LYZKD1jTZ%w_pl9M6`n2=iP))Ud>e!&(mFza!c!cKL6DH12*Z^pU^eR>6mGCfl;`iBwX zASUO|gNtJf=P=dz+b0kE%=`=etn(k=zJDHL{(;#8);S?rA^=R*$5{5|?{D9vaT$PF zce-@N1DJKUY2)U#!VC2C`8wAFpr7~0ExxrLuatcQfGL{*5@OTYx&wh20H&;C0vj*J z|Av0v?Po43zd%3l4&Ll#-y8acelFj8tIr6De)RyEV}JNngUJ4fB-;n^QPJrW;`a&? z9RCrsemG@XbYm*aMi5(I3L}SIgjW4Ey@t!jKw?g zQUiKB|m&X6A@h7v*y<=w&;gnmPBnYFRh~8h7stLGK^p)+>$sU!i(`925S9>vzBf zZYMt6l6`qR>vf2L#ryVU^PJA1C7iQd>wT?dz{H?N{se7*u06>HSiB#W5qv@DN&?EK z^eY+5U* z;gK5VdVNBNo7OP7gbvr(^nRcuxln4(CKGEcGQYG3mYP=h3UmLRKpq~5svNcdf-k+P zUWS0vK2s#03-9#-1lah^YS@a zNq7EwvYH)q$(R1VUR+f9eWSebD{!9b<#aa>e`oz;t4Vs$=_@O1hkHO0*M3@hJF(8s zuRUsO?z?ws2R#Dn1;6RpjY!Mq6e>QRntw`|0YlMsXKO9Hyn* zBVI{@kPv`XV2T4qj!1+!E+5Z7gI6r_3@qaa}EdK7f|kMe4V7`=%v+E<(^wlqxNZ zYQ2}tv4uh1oss_?)~{m=Pe5k=$Wtl?fiz9BCWHf!uA@aYdUl%@qA$8)`!!5zus`yA zcrro+oj+iITwK5d;m5Pw8O)z>;z<>#XkZn~TnOZui9D>HwrtV0o%mWk{tA8k#bM%S z%Qnr3eqet?{(H1RTq%H&Rc*z)C{XkR+$PeC0{wx$+ee>d`A31`iyK|;Z-F7&WAh5t`5Y=oy^e!p;+-eVcxD?Gfekw83sI|VetpM! zcK7ogovh%J;gx8psg8pgL1CEHL zdj%aS63Da+7fb+!AkGM>`VBEB)#v6sO$FJ$6}rx`c8^*0)8KSomu{iz>Z%3ZoEQ)z zJ<^+McCl?R*HoLIfh$Ll>I1+@3$L-YX#Tq>>S>zSz*YEHZ>IDc%}?HFUNLw0I}7_o zBUC$ZZI76oAFr6|6qR-VQ^|e@969hG`>-!z|MaYjdJqb_4 z4Ve%;W8Qxk2}w1HiZ<9WHjEQK)qlqYt6QYCQ+|8A99J=U%P2{Z#=jupPDAZzs^Kk$ zzE*ghX=IoYA=Q~<cpIqG{fF6Z{2+ahGq}u za#X$zu;jpchWO2B-8v2EyZZ)|iy(7$YqkYW*;}_Dv^z2ww*{zu)qqMus$a8G-s`Bw z$K;#pSi2uy*_n_tX>9V&->zt_&+A`DC(ttYNOgJJFv>*#k#*zVBe-VXj|3j>d&IK zPx-m6`MbkHYVGWC0F_BE-_s0H(V7iZ+_NQ!nE-h+X}?^&-eTZ}+|T_nHJj6eNt3G6 z!%xoNPLF=u;|$REm*Miio&9LYA!+X3p0I(P9#fRJzf zV^kTJ>uiNTon~~jq!89irx`-_1wLJ|B@`%H+3>UhjP!eufj3zYKQzmO=wgVHc))q^ z$-kQIbpLU$yLOskdM$i5wb7k}Yd`yXL&l|2*WC>ng>&fGT)!iNPTKlKayC~%5|hR3 zgPS#iUVt62>1PwoAlwr)Yd6=hytSE9v|bAfP$XTs-TJeS+WD93>7m@8aDm4zHV4au|AIQ%Qqd{(B`5ZYgz4V z-`E4hvq-^ctuq)1>Gyk`_X-EIs^3LdK}QIM28i?l8mcb!dJ1fmL}M8u3=zRPY;0No3Ab0GJ<4hj}iq8hKO_@fjzOj|qqk*c>0gc|+Ynne zmiwN#oS^Wqq#!~4&@{?j?7s46h`~ls0W>OwmqAmYzh#=;w>d9kcy>zQ6>dqx?$O83``58r7(ju*7N`)}?6A=j!&zXUJ0%wKL zlhv&o-@1ML*8Uz#H>@7@N!euQ6T7nNb~yfN^F)Ll1l;In_kS`MldzTA_E1>J6q%yZ z+g4O=I$7@aF#EMw+eQ~YW)`EkGx%)?9bTqFKqv6Yc761%C%4}`?ES7lP!k}DlZ!}0 z<})P7d*e>WYA8F;I~hUDx;MhSU0)za9h*^dg&7SRxh9O3hvg=M;dh1LrK9~nKK&tj zx67i;iuZ-H&QxKV%`R+)DeA|m*2aMM(J60LklGi<#V|HGm&J_P@9)MQ4Qkaa1@cn5 zu0&aA^Hq7WWiF1}V@GQ?tMW%2Y?L=-_!HP1C4B!<&gOw*>K$cn@wHG>=EsK)t_MYZ zX~2++^e}sJ=36N;?3R$`936ek4^N(I0y_gP4LcopOrdchYkIl|nBIN}a0?JoW*j`vVL!(75y5GpK)C1yD!e`wWXxD$g6Zf$O68D% z<=mv1pT3@8^hHfrtUXEiJ|ef6Xs!+celi0qE}x8yK7P(|m!HZAWdkIaV|oOQQ=2cpM!wMY0&9hu2F~t0a;T z>ypR?R4CSuWL!+Zbrl_+PtOGHm(tjcO&-c;oO80tCLn!l~2Oq{=nvg6UR)A7weXr zeUnQm$_!6beSBY%`}v8~7IP%6hZecNc=@!9|+Gnz?#by7Pbf5IcYq6e$ccW%>r zna4v#50CoU-g$oC%K~8*Ly)D0eaZH-QQjDHS==Lcn|dFE8c{6DBsCJMv7h^?P7Lzf zc<=nsGyE5@|JdS!$U#KVG@RWE_`ey_FNuCv7kgr@dNA}Neo#J=f+hNMrxVLBT4Xq< z`n1&AM&Wf=_JU5(eGi9GmRCAYD&xMwYG;fXSFCvj3gkP{vw~qJh+TdShtCDM3I86K+!aYdx;()GqcYY>CBv3KhVwXq*zKLrcjQ3{}-&7T*C*#=BP(ry~2(GvzFkJ|f) zHH`=y{oKpqLUxi=RE6{(W+zuXXnBw%xbYG?#1)#D<1FO{>J{QCTW@u+o?|C!=Vv9;Nc2`deFHr97e-r7*~|nB`D#>e#MP0pd(; zKBRvgb`O*dwpEM~@HmT|Eh{rd=#prUKQfOkwPKEQ+~hVjQNmVD#mOOJ2*pV-edvmv z(a5o%_q>b8B*Su?hnxzKN6_n3H(B*?*j7VdeAOCkyXcF#E51DZ9$<6P7km06b4W^-GcRdxtUi zj@=S(jAo}5K7$&631qD*SMhXUc>wBSXiZhD->&qS9jvSochD}Mnyk}c@$6m|?9Vvb zG$fziiyD_F_pg)KhC6*fK>}N>o8p5N?r4xdZaDa;L3QH^fXfKL$;z7AjY2p~hFLYd zHC%N>M@EGk7~sHv5}`g0167NC(%hslwSvWz-8CZL;J}${$>liFStlGj0ky~t>PYC{ zF6Y5P<>OS?XyJI1yaHusfm@gR##rfFU3K6DMjgxS@b_8zoMw|~a27S&$(z;XFE}T@ z?^jC>gp@-+Q9jsje&)OlLf|rf$_C@3dWrDv=&O29Uj3f@AyhI3VY=JBVfJ(fRn-&E z(2^F8rD0o+ZP%Xopc$F*9i7%sB;7D4lIq)EEEFxX7%=Ij70UIX5M?!M*1dN>Y>9 zgzbtLHe46FkmX|`!qJ^b7gRdRqrTpU-*=+CG4iRAp?$(+qxy^Y4Q0O+_tj`s#@y

4DTII`-MSW=Ot&!ct zrlA5(=l((M@4HDI7=<^3phNm(d&$I0^tTMA28{08GxvuS+T+!7-;7igm@t&Td!zQv zPrbdgX@sJWky8}M%+IwsmJ}R*=7`@i&rKO71rcvMWr^qyCf>+Vp{w~&&VTz%G655> zi1#&A!5VGfaYl4aD6dh$MJ}JoGFe5~sWyOH0H4P63j;f`A+ATNzqf}aB9<7@kkeOW z8pX6e0(4YzImKm#Cw9tUZaf6xGZEVI1p?4rbDU>#ada9ehJzGtBVohq#df*sO1SmP ze$*-@3P$G28Pj9Au|27nvdkjr_Z9r?RC07?O4WL&RmxgcN|a>TREngcOG|?*Y*Z{X z7tF_7>=2xOKLE#qP(g1&CBGej0lbW6J=wgJF5aJt0#ik_YiN%@oFU^~_KVIe`;_e` zgo|4%n|S{@Z6ec}FP4l1xF_aGVuJgNhv#4A{~zfizepQaFiZlBtF(zvvD={Da3DX( z-6p%WKlwIQK)K?3?*a0A20z6{l8h5kk;cgQkP5-EXL6bd9MLixaA*41;WyIi#HR@z zEj*aX7e)u+K^QJlIM6{B!X&hpDi17h%5yavrqX73g_pst&tVSQtt*bf8c4}^gR^N} zUQEqdHwXU|kWA4FNNOzeYKQICB<$*F`ABmf9YCemOW@*0RTMz5T2Iuaa)T1{H!#!0#F?V56zU%-Ajbp~ zVD&Jlu$|Q|>R9d?$%m@Vx)PW%6HOPXSywihhz5-wtY*=mr4pF6|2&DxjF8fZC4fCh zEh$V>EoCaq@*Rk=OLrqHDG`M3gb7!p!S2wN-DHRc;h^T<_fDy6i-+JftD1)iKo2)8 z@R&YNo0arv>~B7Ym#juLYq(>9Uppxk?N30dz8P!q4s2nTGyAG;i_wstn}Ad^U)fsv zgVfC|0lcU8JF34mIHX9RThVk1C+(ziiGP?Lm18@sqwV(S#`=kC_geLZSR+=F^3x97 zkB_ztlS2B5T#``7LpkVzp43RcLc@5R=vCse8_3!I61V%-gooYGGgnKX@zd+5=^_v` z_H>vUQ+9vErH!9$RE9jj{;D(EYx&`^NyWkV6X&giKd}Sjpi=Jx^XOy`|KKrQ{L2qoUoO6kh)LakZpbwl(EH z`#|RzM#XJ^CUU3-8YkBf4C zB=VG@Hlj}RG4uznln$>TkurHwH>$1w0|x82SqA{nzL<5KE1qWEk>QGdt~OTdmH47F za+-asUg}jO#*TjwTMZeEzHL!>Qf9pL#=X(oc>UcXM`|0A1LdhL&nu2flt}#<@of1D zg>F`o?G#5b)Tc8il#=FpLqXjfj0{umO(H`bUWravyN8|Y@M&RVastH`e#tMwU{&ki ze{{TG`j|-S@}PCn4H2%X$dr=#=)`t&=`tmjnQ(#<$S`6aeul(on(c|E-K~3>VFd3l zu@I1bU`!K8Vcnp2o~=MDx*O5=-htwdau|dug*o0rqp5gQzW}uw$LZDzGm#O)-GUaN(2L|T#wvB*2Mk5 zkm8&Gxl*G5F4X*0P}E_`x`-b*1_H*rgNDxnKYCE4smBP5@h-2$LRc@xdULO%9FKlv z6C`%;uvFcF^ZsT{?cGwgN{oQ1&F5OGeVW>@YY8pDz*R|9$)Z8uDM`uuVeGJYV@h_m zkIje!oDsLS#`<917?RQMVdg7Yx6j_55x918Bud-EY}S5$X{QIrG1WZuzSq5_--<06 z%irlXyVQ@p&+F~Ae5#hgn}q=Ncft{dLE}@@+Z`RreGH?|4|dVQ$sEMZv6MnWC8)LhnfM}*qV6tRVz?(S=5iIuEOXXEoQ4zq$~xxLxA$BA&WBgMZD3+PLk{~oFg=sL`w z2vR~7O3-(bRDJU*RkY(OYGAB5<<1AerJ80V(`3SN+-l}JEs>6F#0cwCI>IPl)YYmH z6KFxql)(Ee8Tds&|HYrSl5u!9xE=SlEbws`^RKmdZant z2zfhk3G-!qB9aX>u^cf$6DJOYW}y&><@XohI&Uzlukrc zJjE)0F+rW`QF)dFh1IRE>g9KveTL8yN@@7Pa5yI2N=Cvlxn#E;20>J_1$qPUvWd0o zs1VucKzvDtLP1GE_F*DoEsq2)!SCR55mQFdFA&?=a%Dr=+jW&9<@<%}J*pv_u8-$o~^ve8k z@HzeY6lq0#3Awc?l4F*{1E`Q45J<0bno&on{zYyVd`OFg$Xdrdl7||^$RqWLMW_fq z2QB{l^NYRZVMORI<)aGS*R}Z@?+YdY8H%S0P%KilVCfu76IE*OI8B6c$HAj7T=7B~ z4`n713r9Pi;L6{~POe#c9fi-Y{fUHoc_4;GKGHJfxyhR(Ugz0q*M0AHhHi{<27E{1 z2?Ratc#i19_235krCCfxXPen7ABj(<9}RtDm2GUb!W}I3K1*laj*^>kbzB>NZZPK= zTRs8TYt#b6U@fUSsgBJDWe)jJ$JT5Xi6mk_Yg_w%yuR7qKGz2O`O_+p!l7Y``=c`s zi}R>X3pd|KtIB&MH2&E4ACm_VYe+8mlSw^Zup;$sS_q;DU0VoX*5?EHa&6TUE5Qzs zb;IFCO_##?28sjI9n2(8jaD??ni3jW3#NiXL{2uqQrH!rgzb7Q^2D#m|0)j^#fDp7?ws! zb`)CaR{bZXj}`T^f#_eGK89*?HqT|2S+{&i{m9vp@zt3%-3E>POZ6eR%%21^QT6O*!2z6FC zq2-}udhNi?Frz4rDWz%KAwGkHD4~1`2ZgurlcQL}YAmdF-JJMV?+2x@^R)*#=(cKJ z%c^DIy)mF=JpfT^ZaK;b!QEUDREV27m@uvKcf^C2%sJp9p-Vsfgc^d`HCf0l%R6I1 z<)6fpsrik=MHEWG)H$O>FAzQJ=Pq#DB|sw6o8F6imTv|s8GW*n8x);&N4({iC#f0HyPnIuYiHIec&X^TizDh7^H5o08Ziv`;h>S-@_; z1cz0qOzydPJ!=wAYpNhrErxxPvq$UpbzuE?=|&9Wt?fe5gfBPGnm9Y?QD=q!uxT=CBa``-ki5fmnZ#Y)K`m~J%ApfGKxWA6PKlXXw>DbLV}j&rlQR`v zWDt~TmD(^32g)CM=5fL!K2`5m)F3eByu3u%ibaL#o@cl^>?J|m#3zJ@dT-U3;8Sz+ z{~lBFm=MXGPhXBF@ia`0c`S> z<}=HJl{EFTltW#cZm6lAKZ$Cxo)Ny2OHN?i$?78uvJ)np5cps|Z%=BwJkCnK!z7Q_U$zl|*{IDcip37`M45W{u zRuJ__BP8GE14GQL59-@)^<-U7REESM%yBeZ2RHRqI~Q=$YKB{n@h8yMO=m`tfrI|l zoK7uXZ%4c}J`$VYuV$I+_Aq5!m{)OUarR-HG3^d)2z1F>7>e`fkkVj0O zC2uuMI}L6%UKHk{8=I2Z={`aV1kC}Jym>p3oXg}8hgk^k*G4}&kY3u)_VlHt8^Y6i z6!;gGuh75U$LRpq2;;a{vRYcb&iHWOTi`8Lc6K+0&J)c(dOyosJ+w)yI9l*2$-Di; z_{ExRFiV>5bcdR7yZ)fI>5_L@4~aM43CEG`7i0if6u|+^H2uN8hX@YPhxG>1Y--Xz zy1ImP&-RCP*aRMHDOovJP8p@i5=~o_2{e2(E#lbvXx}^IG-LVx+1*dBA7K^FQw~uA zB%x;LZ;w7&&{-c(h01sH%|^t@68SVdex{oj%#X#loG$qFWW^obny>5T-p}2)1;iYw z?=zae)UH=cwAS?IdlB<*SY$d`Eaq=T$SK= z+p;%aXRwcRKML2o5@M$Sxg-_Z56X;j<8!Bs9=m0U`z#uMrSD3dXh#uz10H(a;Bt+NpeCK)-3Lwf^NERk z{AbeoPY2s|pb4}x1J7BQ)FlO%OXmPtC*I3sB&Uc_f0V6 zV;_BfQyM=I^F8Hg$aSX+1Y&1`ZwJ0C9PllHFO6^|+yFj+gHr;@gLHro3V@HRkEGAn zZd6)|$2av}0|E@r@TN=H?7t;mU9`X$w>tkMZ=TP9{|5kX_q4*wc-8+f1HKO8_(S`I zv9}=9D|F4U2c8@ZrwbwnVFORj1w8rjxoXP~9+y%1kC>d$Lr(B-8J){U#U>M90wP2K_zG*sIgcv~^V1C=@k?*~dHkoKq zuv`Tv3<{!NFzNF$E%M!B_8}kz8GflZ`@p)X5lL$mGvhF_Dc0(&C`2*5y zaU-EON0_{EeS%}yNFM_nx}}6GgK^~H11ihzsjsWSv>&e%4}f1r8P4wd&-VKD0Rk|q zVpjw{00Wp^5DE%t3yuV3UJddWgEbn+KI{2S4S)msgSCClV7+(~#GEc-hc2dBzX$&{ z*Ao27r`lU4^117dc4MH12xx}#G}tH9l{^ZP$vQ{xvW^y4XsFLf)!q1mVE)HllylMx zerNj9tVaJ0lYm`;Yd$9slS+FinSG%%f{xeY=i}WD9ijr9F81i>MwJH-!+4%F1Lgq@ zvFFS23L#S6rS^#_C}|(O)li__#^gK(-l5f>-JHza8~Z)cy^yP#ylEGP38ncPEvxL! zmneMb%PZ|E4y#|chkefCRQP@zWaOJU(L`bL<3Qrg>#V5gThE?ve3+Yi2g^A<10fYh zdw_{hsC|$ai*+^gIo3wqFVp~hG?F=TINHTDPe`rTXmlGqm;seHR&65qyEpo*{d!+2D_gN;)ojl z@)-PSuexxvFaohd7b@?I>@!VPCx(LL)C2k7FIF)?8$9r;4US>T@Km?c5B1M5o(tf# z`KP9v9iUs-sCF0n{(yX1DL!BgkoEx~6h0u?D|nNJSI_M52q(Xbna>Z6@Ub~)wEd`wu+0Pz;zl6FWG z^6~COQ;uXwLV!|(I^UioJtpt%{dIM^^{^soi7v~=71?g~f~WgGRQJU{A`U)I-%dau z)4{hbd)wy*(eo;r+b|xe;z!3ytjGTwELw4QP%dE zyb*lvE+HYp`Qr&;R*E)5Q?xLdlq?|Jy%*9;bU3nZgmxllW?H z0uI(OK+y(*f`NL4fsj!Mj)A?&_ixc9mw$}%q%}mshl=;g@%UFsl3}1KUABkPne~d^ z#npSBFV1VCaN_3&>oKFULUt{o42>9NmeR+BE&YE_0{f#RE49Lph*nw$dB4p1d!0;^ z>wZ(yX?MeBDu_Mt<~$_l6JI-;SPN6RNZbbfB?21@FuA^2HL+HFVOseZmQts zJW!I?0v)0vopamI9|p6wW$Y){D?jklMuCt)k)ZNlKka1*Fc5QUc@=ZYURr;~-OV0N-fE zP{nDrzuSt5aM`1p=&f5UvYjtW2fYzUaXUAXnXi5;+fn-P1*QYRw=@ASbf(~`vMQfm z)H8~=FLifn`m=Z?*q>c`TCgo#UO1O!w>vjm*+;*G>1e#r{c+$$r5YsfW$5C+ zw~6logsgc+&73mL%YIqro%cau4E~@c!t&=&d;ZQ}diMhRCZEw>zVm=6|5pfbvaX9J zaQqM7pYmOb9FMt(kiJ;$E+V8;;*6xO&7}V^fa-j;i#n@mEYwGiVFsEBWOtbU_&3vm zNU9c4)ZhNii#Rb6KN#hod)L(cYrW|^qWb?zr zzyTtuGK8zlXYSu*Q}g}u(i8FCTl4%HiUJaZTizRQSxlGQ2>3h71e-~{Fvp~a31{0e z*TIw?JCr(|{`hRar)4ws(|E*B29ZGLo zUmVR;wuc#0$!Ff2+5Y^$#fbs_IN;v|{BcEMV`zRGJBSPZ1ggLw??TB&;WT-}jWV!_ zESQ#6g4P}NC$d_|XiS`fs7y^Skr$`<^%?~Rv3CN*er1q5@YC0V5U_YjFq3WN7^j~`1)5j=35Awr%C+PG1Mxbv1v4i+Qp1{{g z1D4vW^?;S)*y6Vy#(91VJG0TXmv^}@@SktcZ-I1D`%KqKBmZYDPbNhxP;0V39m2*(yP$3aaQP7kjO>9=y0z7Yl zhU(TVU@F4r2qUf(e&vhLCfD4Qv(QtHHf!}OBoh11kotd0aMHd3q*?)KK%27}6PUk( z!Tuv!0DH^%(h+J#MfIHjWN+=ie&heXHC(S>8!5ce!5?X;bv4g&`gFi>ay?Wbh@FyD z`qbt{xwgN4{fmP%9$YnWW;(x4p@Cp)HBJ;Vo(t94%cV-staH*xFw zwUG!Kvn1CVb|rIJ97-Rk@%N?(*~rP<-`9b&oho%2bgSPSukK%bChJabo}g5}GCSbj zXj9(m17l3RlOq7f_HAmf-u>(Le2b5ln81yegVo8L+{!ls4M$&rVHQjjD)90o;Inkp z-8Y`C?jzeDdTqQK6A0iy2&N}!2#%g`X&nJnjvxC?sGlLUt z%WS}6Mp8WJG)5^Kq*OO5MNUa6Aw>!&$}Pv1WpsSQ6+z#0)~X?2RYi_>G2TF$A8*Vc zLg19yFj~}3g+5YZBbh$x_RMY~D1S09okMxFi9)8m$yY;AglwH5R)>|;IGP8K+1pRX z5p^Y1zqWrliMNm`FU)>)C4r!ROe6smC+Z*#(pZD8h8YjsV|G~|F(M7XzZ*KAhbMeL zD;uh~LIcu>UX0>sR5;QRIP)kh03F~o6z9dX@n(RalDftbvAM7TW?v#obBm1G1Rtu* z1MjtjVANA6Yo$f~>+F=+F{yHmJ3S|i(GMSPTGovTTWr-$NR?UDPddG@YWU>2Ss^?$ zv$(+6fFP71kU?oOSlp;sX4 zG4$0;ln8m}{UqMje~d%7c1bA_dRD)Zu7jBu^x3HG9yDk0r+sg6R%J^*wmGJi?iRbb zvr3Gjio#YIJm#ELaY$cjyT)Al_c!dQGbcNFbn+(r4yWHscMTManC<*^v;~&Oi6c)B zC!DKVkEVj&ogOWRVYf|Wys}z4UP*d)_G2dLB*lA+{9)_FkzWSP_QxX~7Z@o2EhJU~ zvPL@0Qz8`d4UGiv`@t6uoh^DkxSWz3cQeb_tm8reV04Lm|lT;;=^;H z-AaYP@;q8u$t1D!hS-oE6&(}`zU~A73sE}A6hsKz>p>`Vmz%S0=iSQ-gr0~yh854x zgqz;4!%(+`;)4}+FM9z9=L=XK$PDBHkez^ncq8|EI3d|J$bi^}EGF)$a>$HSpZw7th@RLi}mRkbU0G`j>gSIl-`8 zN5wBE-*S)6^)8NF&;cAqas^U&>^GhS+x!KwQyP%~Y;19Vk`Wq_Fia-> z_{WOpy9t$bKJ%^tG?M;C=@7|oE;NZlJu@9Ou5c)o&t^kZ9Y2S|9gHsbD+Ba$ymFoa z3N&U2H$a+TUhH@?}IBsRuF> z)v~?T9GZoY=_a*_w*qOj8m-2F%sBF~Ro5ac{D;w+lZ$eN`qo`%IVaHYI(>=7+*g7n z$*+c9S}@|{8y+fkiMPw5!c$Ja?|)r-{cY2H&>I2%3rw08$4g(*N1HO$xTQyEd zE!!JofOpdP#d?pXf2)e*LI8fD)35;i_5_-%4Rle8zrtfpJ_Ja@LF6A-PtNhbX$NRv z)>_x}!$~rUsO|Cf8lPxA5MN%379e8DkHN-uU583C;041-_zi)MLM6v+W8+RbB-3)z*G4sPqUfQB^nBr|90rE54bt6oawj zTZy$t|zqYviy^$KyUy1D0@R_*3cIao7g(D^V~uQDnUQ?e81t@_4HAy;c|A zD%jc2qi--62qPPWEZNZ{ge8D1Dh+;K3kkz5^?~=MK3h}kK+`ziO{iV({A0YrER%z# z*7u62Wjo+z_GJfqQM#3q0aebou`4~ddqPYY`lHIHtJO96oSL7daDP#UWk5}?N z^hX|$T=lJhK65pYU#9><0#>YB7j5A!m9 ze>Bnm>4W|IBe%uV{(599v#5>BYuVuTgkUZ3$j>ItD>NhOutsZv7`3XP!`Y1){suYW zb`&@&0?X*9La)KNA__ytRZAUF$P%0nPM&`5N+LF~#vs+>Xv-Gya&*oH!rQLHhOd3F z&(}j|-;i$zY9doM5oMHI?62XPm`(q&w=rKu4CB>p z(fYQx7IS7E^d05vFXEf0M~lh(&AB=Jrqf@RI?CZtwx0~e*|PbB7i}fUZ0jS4!h$b} zad4~`p3|D1+43`HT5~HiQ+?=(Uf-_ax4jJJnyH7M%?+GRsA3cgn-$oU z=s}_cE2zq$2q60E5WzFZd?*0~fjWT0b)!Bv1s4s+8x)MD2!X>Q!0E^dMpH=5i9s8N z;QC7)=clHVjiHfN)WwQ|U7Kk;fvmGwZ$=_HYB9EaW>~anw#|C7nNJW_2PhZejyVK` zhEeTZx%_#c1Jp;Puu^e&V{-jDYCT?u3DW5;F@iebZFDA-vFB>BLwLc=!AK}K{oxQ% zs{PG4A}vyLkl4vNBZkK{hq;twV$`(3Gq-){mF;}|1=R`*3X=DxnL5DBgo96;F}zKu zb2?*!OyOo2JPKRQ3Xj7CP{&ADxu%67NO%r0>zO?ovZ_V#Y<>`a zNwX%|yB%7&xl!jVNegY)*<5c%*F?Ck4~SD>2#fZMgo3Wb2_pJxB6RQnkGZc5sA}ul z-E7!M2?!gcL_j(P6p)ZcT0o?`8|hFaq)WQHySr5y=@g`-yF*mC3(VuubIyCd@4ff( zm;Ga{xyGDxjAxAJd3N4i`7lP%QlU<3zE+$ZT^+0&riC2KGxYBHlG2d2A4eIMKL|%!_9c)N&HgN%B+fG@Hp@pR5n_V z)F2#`vJ-%6!jkE&B9WH&5BoQzsNyHl=YH@v`~j8>mYOt~x- zJJVi}-Y&aKZFe`a0fqdg7u9PmjJ>EpoQ{924Md(J{^T7l;VtsTlK!G&?Au3t!FoGq4YxX<#(lNu z6ghP?xRv|+KH>Kf?+ZDb3?qiGs2*?;#e$!JARyqe5iSGI3P+@o^uiSl<(u0k@QYtH z#xJxxqkxnA7R>ovKs@N|GEf5ju9Wy$(clM2*~I>{4d)kt4aFShFB;=Nl|V$0l<%d) z+HT^wo9#+ZU2f%tYR~-zv7jQ2KpE_BuL2Zp7%+Aq2AC_r6MKL}fTB&xrO6EzjYL)< zh?v(4;diF)e`^r_^W7sFzij@emPSOj>-pXD?TH1AiGKJD4KPoEb_*DIG8B+A0G9L^c$C z4m*M4KZEW%__-Ssp34nWN&0OR;xdR90@4PhfXRS|I0NA$lwAxI{IYobi!XkTWVbq> za~Hlss_8yfU(Kff2mz~Cbbao&VPc@*?-O368=n-d0hzOlbYoPyzGz*w zfOAi(7;C{3pe2-~tUcZ1bT|p$hj#b=W=}s4?B4v~g0oFc)VaCr_YujY4Q7DVWA2b@Xm5OU%igKuW&P^-3xU1V6O~Gvmr&#jqHU1%`qwBDkl~SjWu*@SX!cumvKq|4(B`%Pz72Js! zQVuF?s&sfhP~Im>q}qtBf+hL(h*GQBeXG;dM7DUo%a!rQHO`7Z!q&_SCS}`Nt)8J3 zew@l0ro9D?i-#vCw}+;ZoN@^zzrog=*^hFcUla3^tlreBb5z7_P;=U{PWOYkcUFNa z|5$7DQRCxL&O1(fUlnnkvaQ7|jFeUzfJ)*^M^nQJo$=tU0kWsAnmn3}uG%y8HyE?7 zUm7)(51p~c9t3#{$JFFGSs;6=x}vTCO8jP^uiIM@v}{#a0|;2PL27b1Atz z=RCzG4~Va$bYJRyADOT$;b3M$u$Tn;l5}M^i$?(jl9VoeyG9xvBw|obAv5OIr7f~$ ziTtoubVDfwj%-rTG_dVLO3v#*3sd4v>4fx_5PF_WEbVX+WQcHhN!DZ*Ih-y5yWBX@ zMo2LVEK(nBYz(QU?j!FS$rcdV$G&C3y8?e9CAY4aCI)fs>k^LsAd4>ZrVENMnorx; z4z7<~FA*=NwHA4NR~3qTNP^BFBfUK_(hs?8bZ+!|t%6^ojwC$d{-`%~)hbpvPr);; zwp+41&quKvOiNUPBA}LMJkjL$qAN`sFn0a&>yOo_4&V8+O47b~sB%D2DDCuE7Q^?! zLm`onv4F4$0i-he1qrUU&S9{`BU$`3lQ`KJGO8j=nnhcc)NzO)W8hrf(PnKjX~h0a z_`cEPlyuXEuC>S<`|Ts?cL$LIiLuI$bi)g3Re}~=4t=%pow4DYayLa(rJQk(YNA%h z$v%Aeu-%51_<;MqeGTfxehG8VQiXLZ3Hqq-4H#j+>M~~7$ z(GOI1O18OlG0Q2%kI$APUz{VOD%l|qHIBnHJo>;ioyyWOr2MG@#gvzB5Uj|B2~xg8 zppuD8nmj&8Ve0Ji)sNG{E6)E{mf+C-lW zgm_M+gS<#}u3dW5cAg*kSnH4yD+&w9$pm}WrIFqi=@69M4UL1-z4q*CI31-0S9I}2 zum&vS-WZrmx(1o{j&`I3QFnNx8(E_pC4t(=f<4)+I9-hnp++%NRNn)2hX|1bb&{Rv zK7aCu?{)=Hlci$DUT3h(-V^P0=%eb;UNBy6W9XrMO}S_x$POum*7QC1CiT;|MIG^N z31W7L+ZlFCd38p3l!g%w+6d(Nge&ESIuw1zNy&|A)aOZ3mW1}uV1l4V%3Dr0<&!_9 zAVp4ppqh0m?x(DKcc=$KLiW>$1*!P&#SBCg?1xDs&dI1ja|fLIGM?s96}k)x&RSpL zY!4;Ht`w53_1Miy5HKPS?Ho#H9}bc5Sbe}qHJl@JkQ3`qEyr8Hba+Jd>)E8pYB6(8h33ZSv_9th6vJD_eP@>O;!3A>yEC*yKCPt^b2NDa0j89wI& z5h%@QEBj%wB^|8}h1i=;C0pXi?mRu#t~Wi7hown^zUm^d&=PC-;(NHJ2J&6wBQ=NR zMFAVSwNzNGXRYBC%_aFJc3l%wCx?~&VR;Hj%1X1?x`kXXO+`#(NEbbqDXRkLtsyDn z3wT$n#<~k^`C$j0UFQov@zHC-K33VKAFboKvt_R-1FcCwB!#1*cYKpOwOcUSaGYQG zbg)bPWOtNsk}JjXo`6Ow${5cjdeQAPj)*n-mi(N6M@AGTP(=Btmx9HQJQGti2i1;W z;lmeu@r%E^5_?=ovT1JraDAqON#VudZD1_*-3Z(>i8@XyIt3*a=2kbmTIv1`t;fdN z+1m=V2-QAf1SPx#UgZ#_ii$G9sgcZ%W`S*W96QK);oetgus^|)U~Q=~PQcBKf47p4-ao~RT}kTNt)7o6<{ zC5JJEGLVf5j&E}dH%I7Ps;N&$w0X#W)Mtc;{5BW0U&B(+SB~Lv@8JmTj5oM9vmKWj z7Q5eO>lV*EHOPAl{6?8HnR-^np@9_YP2Tju?}f|NDFwsZJ@)W;2?ss{I~9s?P-Lb( zE?rCPGX=Hw^4&+s^PMj?j6BLyH=aMipQj|!M2J}+Fnm3({k9>A#^(ud3LQFR+vXQ8-Iw_Q0^Lp*}6Ewp5q6{Z!2f>S!%*aY$$*dGq6bd1h3N z$q|cJ9N}gLTMSi8glL?CCh~B0AC)a*A`+|t3={OeHktIb3itdlUn??1EwfTxE3Uop zNdN6{TT#=oe8r&YI%*vT=CXMFoh7$+OY8VEd@*zI*!(~CeRl+L^CVZT;RnY!F2oI@AXA(FdGrs%OB5CZq+LnXiZ zec!Wu_EaMxcY52I6ONwf00SR}mQ`#QI~7}xQb`0N(kO-w_P4U=OdwZ*Xcs8EHT15P zoj43AbJw8(orfE69i@ z;BN1LWh%}{PvnMfr-6<&L{D_XDQ%wlw1|6>#UMmTTga82Ra+-Mi7cJ>mtqg zR8Je4N<=7*sV>&k{&z(0v6N&hWRR^f~Hr-3r{pkmL_r`+TZujdx_J?Kk#J*;fQ z&qhUFH-rMaO!v7C6C>h?L{Vx$xh+)L9!ix(57(xb_6oM~nrC2As z-An8}E%OBXW)S5enk@{51<8{)6^2hjT)3j3gt*v~0=jhav{fFMtxWh6!Uj*ygxshz zl=pFnSVfFPl9k+}LIvLV2Q!6A;SJu6aR~g=_}|(JxnH!Z8NQxrTWNV=2A4 zp(;WSSNsgN7=s}hgM3-8_XwZ+jlJa(R>c8wsIY3!f+>vxNlhds8*HSz4O*Wq+U)_N z%UKqa8JPAWs``8?#ohqs6Hai8Srn=PPZ9w?VDylZ=(GyU_>IOrcmv^1Ee@P#$xMZBgfv+jxt&zW?j(URZt zBD5_Vt8@o1hlJq9s|2Zi9zo(nsl7-0Z{iPeLz%SWahT%GgJQ`nVDDXtk5nXrFBDjv1daIM5cg0LtAU30em|7|I?nx?7jU@qInx=I0+heB`Uf)#Ls}0HV ze*O5wviHZ_V{fOzA&Za?;*v6qvw>@HxH{#SMbi{_@c74x6^)2`sWN1*#H#TczRt>c z#7=~RlgYcRwQZGjNhZTO#w@M;xn^?W<4$7DP6GWJHZpWlwi9s=A+O3ap&%^;&mh3! z)zM5s0kGuF?n@(k=BV42Ma;^s$XD$rjF;5`6O!hb6NBrJ6+@8phS+g6)!vu*lqmX< z9Q4MX_O_>`+EGp}dqxpO4zElW<9K?w67wfLBcWNU%1TV$=4bVL=^!ibI!B_HzB#eJ z1Z@b;BvCwV{OI9c=nLK<=JLL#nYN2DQA_Lvsd6|js`U$XDfYMoMJB#oju+ z5o@|RqRAi;8JsIKmLkX!cRsk_(Wo$c@yQ#(P)BQ8VVEfJUbQlYnL?<*1~CyJV~vew z+v?l+j6sn=Y{s<`9*#wj*{U7~Xpk{XsB(44<7y$sY7gIHvEpi2N5A`2hAkroJ`d4T zvaK?ZwP(l(w1reVE1z*y^5$i0ajcpXr$mBT4R0Q**+A3|`zk)Hpwk`I-r=od@*@^G ztnG}gW16UI>8k6+ukYcgZ$-|}f~jxw69-ERz7=zsGKNl`Ava7bLx~lzX2lxj#ITl> zG1l<;SJoQdA(K8%DfUxlUV=-VnkU{D%k*f8%(XWh3Xf=VjJd*FHwkOUUySMKq0ru{ zWBn$=&LM#WuL8>x(_rVypqIx@*V^RB0y6j)^GGiVRSK4sUe4haa!R37siZzG!eQ;g z;_resaS$-8G-{N>-gA8=l>AEY#VfMeR}h$HFmW?BPqUCe0kagk$XntMAD}2NLdz~; z-X~~zDwK=p=8FLno3c>Il&61(;uRcl98|_Kn!M7oYUYT0Wfa$H^7fVSdaHQxOF`l` zS>874k2l!XUyT^IKH>Cs^4Dy;=PeYYedVVgdKIw>~#UdrCO*c`r^(W3Xfyqa~vi#Ut@T3hK{L(?C z`B7XK_s7=Sx2^SgUA%Ff*J6_3R47AGlt09#U}d}xkEqw-6(!Gl@}yPAyt<7bL+uX7 z3vAL92I*I)yxwhj1dp58N}hCG8+d6*{JKY8{^c76G1?4?j~NY=y}17BX+G*3alOgn z?d$2ipXz#xGkVCW_?Bd7OE}4CZerU$>Ejwe&F?E%jU$jyA(uU5lI97O&wvq3=IMj> zcv>bA(vcE(6Xc|Ov5R#!_!CDH^t%}`A6*R-sDUYe;!<_CPE5(={`~fUh*%Na%f5Ne zw$_wEjRAuv8OnU!Nt+sl>W?Y!sS=@s$TvrZJl=J)tjqfvLuc)2=S-Mc=}0+v8b>&p zvvJMPll5p-F_1wlTjFV$P9tU;xOXL(mGhw%@nuxU$nT#K%Ut8OT4lQQek8jNr}PDS zX);KM=6W#SuuHv!suK~7s$MLj@fyV=#Fq+n#$|q&!|TV#z%Sq2i;>udXF}aEkDlbP zk)RcLGEN&$vd>QRUVc2acr*@cI1meji0FNqJXSz9k;yo^JvV{BJN)3qM0rPSMa!+t z^dTO^fLIf#6WGMP3qvyiYw((-@dihNDv@b@_x*lGk+WpbGrqU?H5ui|r#5rOTSLa{ zUUv+ILGSUU?^yUReiGliJQ0^p2M(?XkRO4u3{EtiR_#Z%kwS;1M~6sWf|$WvN|-^G zoB_Mepqjy;o6Vs0%wQ4DViwF?m7K*$n1KY(Uf-O>SHmE>`;Itp7JF)zvf&*;!tCX# zcT}72Zk)a&-JC7o#+Fo^B3UI;OBx^u@rvM; z6(P-)aLE-i*Ol0U708Q~#LX2j%xWtADt6OKSm0{<-IZK=^z4F_!k*Pkv(>b_Ymt&` zRZrJy5>{%bR!W|N3R(t_V9ePYv>&gc-`if{R>HBVejE01{Uas*nd!2I<|;&MW9%vP zjTv+#ka%L#tgk?~8~!D2@`QH3mDAmnp`H$+%E`t(A8w}QVzTv1mgJLniHhjgu!FYV z7HmyS5d(Iw1uaXi37te63{8aOi0aUeyUc#lt!q6>fo1~8joU{BP~_`7cxN0Q4LgKe zs)?NXf*ksoXn0u8L@>Qj3Uw%&#wuD78~F)V_t~e{T_{UW@xoq<@8L%5QNGwKP~PJ} z+h^zA=Q4kCw|8wlp;u*1s);t%5Gtk4Z$f6J;~sPZ~ovhIkd=dIn{CHHAV zJJg%nCNR-6Xy{i8nnQMu3$~KYV4i8O!f)?Fh(U&?P+u7+%-Q=>!jl5}6EOElhWbes z+DT^Ou4ki?I_paklb6>CUKAG=l%TP|a&3k=zeGYKZ=#2j>jw$!yx%W0}AG`OBsyd8$*NttWBL{6utjH^nfiQ%~3@Q@&y>|PiNuO-|{FIX=&_OeWc zi;R_Ia1dEyLwoMNgfIuczXg>9Lehq{E* zA=?>~GcHHC9pif!k11sfW&{ek74lwUaP(vMpk`jKzjRw`>t!Nd=S@nFwAG>{Sbr_w zW>=y8J}~q?XTJcJs)}?A_5=T7fy?HyB4r*=aE0$8W1s{O%@gevGZQ=)7@$QC1&m&i zTXK6u4mjUw5KBU(4BCB!f=k308r^9G0P6`cPNwT0{fO!5W^|J15U3eo_5ch>oPDdA z`99Z?fN8C36@m*C%pH@B;^C5)d6q%;UZ+f&z{3%gCtPkBCS5|U+nss>AF@YBG(Fb^ zrgO~8Zm+;;F3S^KDl;Qnk(00~xS^G9lYHaRN!yUpN=`_U#G8HQbVggU3WXN>+Z75N zH)L)p28a)?6Y?W#d0-(oGl%(ukc}Xt?ow{UrS2)vBWBs|Ye#S0+I8h8A%h-QCynFN zS(EqiaDB9ldD%o=}w-^VU21=SHvki7V9RNlA1#H3o9C zoJz}SK5FC3?s2DgjIuK`YR-&u3tQQZ^D7r?j0+p#IZTS%$ZJhXdq>9g%0~5SO)IB8 zIn1h;GHT6gw}ehsGLA-S&7UPjux;0!0lqqo5P87#?~1{oE_MdWR*f*tqJY%*+J)#MD$n?LmPMhL`J)QDk0(3g{_rtoGi!o~ka# zERml+=*4~7&1<<%+)W?K?ffZMPi=m8YPa9$Nm}kFEOe(&%41mwl$maC7gfzmc*;-) z$dPY8B6{VM1j%rz^C9Rxv+I0t4Z&xLcNVwLeS=ZG3o3`MZlH&09E}J^N5qdz`GUBM zSh$h^oU|3+=fy2P!Yz(LNk~O1Tds-l30^B-&2^rRR7C;Fm93@cy*9a75eT0aoz`s| z!EJbFiszU=(3LI7U^Yanen41|MM)>%&LA9b5tKS!K?4(erV9z6#3GZrdZN+HRp>nn znpiFl@Dk8T&||LYsUs(8EJ`uK2yut=HtMxJUHPu9Pypv9inO_8xb|{1<_I5_}#*^{N9yBh^NhTsIlxB z4ZpbFRlyUz7=_5ge74hXDm)tur-60ZTqbHjHsf}@p`=C4VCf z3#(S4b@6^y07Mly^Dicy;DGitEhjLeyAIa9Xp4Qdi22rfM0~^hlalN=HV2>s1$~o) z<*J0NTJST8=8h=JkFDDW?o1cl+t01rayIL4J@xe$S>G&TRAxKl0UapSz_U$90gk?i zb2bNZMQ3DEsOu5DpGjs_@myQbvs1ohh7!R>c*d(k;z3r^&k`V>Ee}RZo6Ai` zA1no2~q zUU042ZUwBWct-g5{$AgRet*$={38SNI~(oXVdHc za-6VK5R_#&bSWvK;|@H(i*Gq3$>GzD7IHXJIT^6K9JRWx+NT?ae6dQaE6yq`M>tFAhtD*>l_h4IIPu#~9l;8Uj#<3LC-G%0)b9 zcmyL&CnIayKU>5gv%LOd5ku=J{s#w&-^-?T=X40kf0+V=JrC*!07a%7tpAIko^6st z{a>6%5dFjW9+|2uFt-eh@8MlTsq?@lZoaTp5xcrR@wuP=d4d9&Q2eX9=I3GT|Je7a z7O+Qb`YeyU1K1<}6|MM}rghhMxxlJGb^W;D zcqkD?5oisFElzo|f;=hS&-Ho`kw>b3r4|1o+6xY;jE>(IXiHD0G?LFqS!!bOmv zfri27`V(iMKb?F(dhh%&bP8O>{4I~|NACHr zf`n4eiTwxFf%B8^rOo{i@xyfWa}P~j&HFjwgQ4=+VPw1y^@bP1zMH!K+S%}LRR=DD zgh9lW>N|-J`1At6`7rhCOOGF%XT&NS&+Kw-?$_H@_hJ}?7&yj?!W%@S*aoj z>&tV`sfJ4-N!%=YO4P9?Q8+2 z$^<|Rphy@};B1)yZJo22{$hl0j=@v$n_=`1BYfvs)eAZnP4bR0@(VUl!9IoTTw}^t zj{j%k%pWeG|5)4RUtBU#93Th(dQkRG=8p`DCWdzZ+RZOKl<$SxgF1 zX9fn?6wNbxBM+Y1;zub znvP@rwUqC3us|j0vro5810KY*!f?My8c{!eE*=5A2a_r`1r$6 z-hb;2znXXbdGPVC6E*68;4X}V{Q%4k{mOO$md^^I>djBya;Ff{B68F$&uFUr(n07qY?sLFk6sKI@bC8hRJ>Iz<5JJ?D9& z0`$5#;`2KbTnhch;RXmlBtV`32kUhaopj%Iwa$~xzhVmpsg-OX7E_?xbB7}ASq$*mm0(4kUj&8Bvyu^KySkE@1RrIX^{38; z-VY$pT0!06XOL(8oba<=+)kdmUhFPc zIvXR#TlIaazFQX_c@K_)@P4Svz(84x0DI1d9Qf~50QivavZj}DHNG{~{+WD0PyrG7 z-KsH-Ik)GCLWFGZix#?~n2m)fZT`qL%T?>Hx#07quG5|$jK<&OVg9rU-+tbN%-=U5 z@RLZe3{VT5%auVvs^@ZL05kMUdy!B6o30tKTM>YJ_bMy^_5exnKi{n#A&sbizgzz` zVpd*lc|m&pWy?l!&aV?#vZ>eK94&uU8h%!l`|WP!-=wMktcp2(uA_LK1pf+>y*}K{ z`vHFE>d^h5GoCXrjDf4mK9<3Z^`-B9NVoD=yqH43ZcUW-`lgEchr8s9D&{}itpFOo z5cd0)4WNn{V{)-uTmJ(M;D6Mzk^aqY%{3ARcB@`=NO8x-ZoS(sSQc2pyOC6>a-@!?@Ha}+-@DyEH3miIpD7uA(f7On zm8C#3AgK#h^zqMV(XTIXC2OmowD!ubye290g%w%ZtU?sm(X5Xp2(SY z{*r_zJ)A(4C6ZS}$(j*>FX_Q{> zEYlbTyrF!*L)f*CE`8zdU-Tr3Z6{-YK2jp0HO~iVeu>_g9$Y`iG?8!BJGvN-r&K z${e`32#vQU`q8u)dK;V`Otc1L#=h?gGO8$_4`I#9FBgJkGWi)I*+; zpWJu`u3&1ymML>1iSdNGlz-+X*^%`pFz`aI2yRY+=e`zBKbJ$I0h0U>;W{HXq}Ho50zhU$5X ztwck_jp9Wphb_|bg_Xi*!X8@ifYq8*%^cc1&=+pDvl z9_4(#UPK|g=#TOr8N7Q89m>>lrY6_%Zmp9 z80ZAkQSZOw76DPs1xXE*-*|TUeG~{JDU_|NDtuZ>!Y9V^MkfgFedR*5!H#fHI3npy z@|Z`5f=HoeBUCL68_n7Jibe$#L2x1W79S%C*BP{wgsO321r4OYXPGNYCRXhm3+4_y9hg|)(m z-J&bp)#rAtA|^2FCCXUUGyb_1j)bK{^kjKl3@irg{&**f8~F~r5OfH@eF}#Cj5Ggj(0%I`3CUlQ#*oKt~x;^4Sq=qXxA|ih=uNWOBv^sdunme0;7I1ISV-Pfh{Y?anCstE|EU(zKlEnoR9oXYKS0{&wPj! zxpl8o%j5uQu)tl1g$N~ET%9mAz4v61+MW(N(FVQ_b1~{Za*46m%n&l;ENs~_<85BP zCr_~6bjVD=J?)@Kc)ECpGRX;ENuO`(4Qyt340?`1a+su%VM>%}3{^^uZRbj+muJmv zmS4!r#cb8;Olrrxic#t(g#~A;tB!Cm8bN^KC*E2?>C5rlyasq=6H7P;uhruAO;Qiu z{L9wQ?K^~M^6$OcrOqoKKK0$G5Qw3cLRSvc*DanfGTtm-3VCc+u`Ib(@E{3^x-fZ9 zuEsFyKy8((VgJyWA+Z;4=y@sP6ow1-sVLI&OC;9U+pkdXq3kqc$cyhZPc`K3NUz(f znAH*%elTjneNco1;SuL`rO9ByPiVjS?4w0HQ=7?pE8CgCUJvt;$zIzbgn;lF!>Gxv zUTzAfTh@12O^3Rr_?63Q9x$8Q*vRTT+1M&+e+qiuNKkp*R@JKBW(Yo6wS3ehc9NwC zC3|E4EqCzZ@}zC;3Znyjv40oDL4Rl7 z9&L)v*$)4xD=h5NCZ)Z-{9T9n^riUf<;=na_UQurK!>%mUbEWOSi7ej>y1_7M_Vk! z^<@JuubvsbX~o>y+kXA(^2a^0EBcj7qY{PH`@{N$@dwop8tV_ooEe@T&p&=%&#(}A zkNwCycI)(D%MR`AD6-A_joy{D%$=9fR64S@kQNADPdSyZcPWM%MWgjxtYx+^+o z5*$7bFOsB`HCkNKI+QX()lc;B z$;bHsv#c8`Il`^6K0E$*W@lpkTX;Vf^|Kh0KEyxJ7V>%>Yz6Cf#PY!OD15aLP#1d?-wF#27h>M-G(R83;8(9ozR@eC<m8A?r-HWA6Vd70ooP93l;RX11oI!YrH$=TS%Q{pTi_foBStaI(>Gh*hPD2ohN=KJNt<(kzpX;4=9rMElk0Ekh2A z-tnYM^$E!BrxHn!vaT2kJ~VSf5g~##7R~Mrs@ac!WlhSMUIZZ*)l}TbniI1_dSH#m z9CvHn4NgfDIevFPYr71BIicw%Lr$zB9FW6jB|F40wI3+cZA52tBZg0A#!vlLj$GS` zFyCo6_J)C=Qb(uUQ^)fBN8wuH>2eiSr(fmIU;zk)_BxC`2nxahGW`i~J*& zOY%!EbhOhFikl=aoDZKqEMqIe$_^la{RoS@Gc6DV7Ewb9k|qNA-B8StWg8%DfrG`I zd14Tv#rGJ2(J1WZO&_>a8H~e^k#PEM84{u3dhh;`##99=vp8x?!$Aq1kRZgq91|dc z5fpvnCM`N(tJ2T(kzzqUS3Q=rtOUz0U069Efm}1!dXwj|9GURL_Pz+-HYa3~yC%7+ zZ<>f<%dAvx5`F1G0|_$%=n3H2NdAk0<;R2>$@$ZV+b%a+KO1#lbXXv#rI}3U{sG!0 zcx=powG5K-WrLQ|Ov$)&->*koNsYc%Z|<#N>X zJzHXilI|6$0TT5za;C}^IPU1%7SwAziak>XK^r9 zouT2=`$LgejZXK~>mPqOc*8nrt}w^Yw>LXFY6yoRJ0#O)K`af04ciS?O~+au7WG6V z^>D|@fNJWQeoASgG}ASZd4M;p+r^D2Y!M;6(62XXeG?F>^t%NwKW9GGVt+%f3o(tz z?lMW5i!0(a8v-i21BJ;zvGHZnK=!*U_#PjM;RJlaEVv3`QazOE5&a9xx{>0(h|0WC zbnf#YZOVCEFI`LAj5v)E!^H<5v23-#@@fWX_w=Wtr=3o8MV6DFksD>D5MTiA^{^Hs zJQA?ijt2QtZ~88$#9^;eCC58?YJou-*&|7?EIHIcxqNJLxrHTXfM783%Wtzkf(WPYLSh?U?n+s_*$Gwo=(t_qbNFDUdC)yXYXaVN zbSS-|F?`fU%}7OV_QP8&u`Z=GBp;|Am0pS1GCrvpF;Do=b6~CsE044N;&eB+s0o?l zC=4G~ik*i86SG;A!xW_~h0p7a!gkwbir3ri2(Yx49dNlLiCnMQC-M^QLui>QHs!?j zx>@k4N2=l|!(56i0&-P)*59ez%1j_5b{!CpRkD&l!TYp7BqJ|zYgk^{X@5k4;Y07h zb2AvCQL*v|c}4p7{8)-jj$$hE5bEjdCStlbSSDLhyQDB=OwRa(FoY}kI@9AA529w_ z`QgLgdEdJX;ELP{mhVEC?^e%wsS`RZM%bynUy6Gs>9Cyk+>CuO(>#HFKF@f{afw2- zs6!V+xHyb%J0g&M%6NL?@nl^tUENgESwiJx3x)HOZ7(E&9S?R>V#w^F8y>T{pL(PG zp?E+W*NZ8y=k>=Ep@pB`Pd+bv`hG1H?dgY=QijG4(t~GCpLQn9pPs5sXx*pTFz|p@ z@FaY|l@dS@PXa^SINpkwUr5wn;qzq~dxj#+htWkJRe%V1HX@sN(Ak3liF$Nb+O>AX zucE>zK2NlMDN#?j6_P=Wx8sGs8owJ>#W}~g<8xg=4KtFBlPZuD7<(gr4+puxIAQ>M zlv2=nzZ!6(D#PP>MD%BIbwT$t`X8+VWweDnC@?dch5M&@BguX#3O~-A+W(9y6hpN$ zEVZ^$)y4_lTWJl`s;c-l*zAa0Qt=IlZCV2U7^VGc&747I4Ox=f%@ z8-}#1&L(eV6rGt#GKlmADF1oAucxWf`Z5fULE)lA9r1MjOJns4eLw4+CB0DLtauH! z{df6F!F+19A6C^j;7zO=Q90`N_Xf#?iPhhZxa`ZAB;I=6Q09Ob+fGV6DET;d`yjd% z=P6t^;6%PzeRalo?J}tcG=IH9!w`|g;69Cv38RY}X2jur8Xa_aRh1qdj&0IF(nv8_N$h-V_@QhU}jd=8soCVs&hBU;*YYQ6^7~ zy08I|9)7|NB0jcN2xEG*%cW3RG?)Gi=xbkUdPeXwqQXEXhAW^dy{BPj-mG6^pG zU}V~rR&a^X#d{|m*9|?;9n%G<1Kp)7adBonNd+lhkcVAi>w8KNQFTQUf=c88#fw=c zx#uOQ?`H~_A-7-;)MshmTf7V!#}){#nhUz@ihWI2=umh*wi~aMOPk{CRlbSDy-;eNr3Gn_^Tjd-b{FA}n zH^7@^naCoKlXBLb@Du+xdny3%9#=F7@+SIhHntqZm0oNR4h>Jf;FL1!N^GNMgL7T?8~ zwj$zC5Zw)^o zT2zDGg_R{j8k7f3B<##8?vq?t$rcfwSi=~(3 z{X-Ksk;00b!(>c$+HMseuQ9|5_xa{exaI9i8jTP5(ruK5G-HERt9QFu4-^fOl}&v2 zdO6-O1@&>jnp(F*(ebP}JP0>#N%C>i9Sq6Jn;xjLj6ShZ`*u13v3?1Nby(QXgr0vK z>+}EL;2ZysWBpu3wWX8iyoKm|`r5kJgMbi-;p=!%E#4a#vhR2(kitkHG!+Q%{77C3 zr}&f8FKGF*^+ah0aHI&QKIh6gP7S)Iq~EK9kF?**BgQ_YBZw<%s}o!o%tsoo(8Edw zQN|cr;8D+sAcbfNmPu`H`FGR`Yc=^XT`d*`^8*SLt3SJ;edoL5w~E1YAVN^Ps-`M@&iL1~xVno=~f zpidti*hF)q@=ksAN>zfI(q`J?(;Ty!^^~=O^esYax-6)IgA^#4(0z$=z5t&g^YkUn zqYN0#x0_9%SmXlJ`h@Y^Ahb+8i&u9gX#vR%r96vP0*<$gtuK`3O?g4fu{T=Ko#RT{ zXrHa`b~32HWqN(9%ikivh#qAk>zz`}Qt#bMlY4zOV2QGRLFD-Te$i=UINoCtS$GHn zXBpz40z>}o0TtE_n-SG#pKJ!$ms(3ZQc_g=-WXQaSB$@Jl{kFMv&2D$0j)}L=Pg$_ z3nQ*DX#_?XYz8IFXT7f%*w45#s2!SV-D@}))4Wgbun_gwsjm*+0>h>k!RgLIyREXB z<6`840>{-nZo-LH)CtTF>sVcC92@8p2^^akYf~Isbtirz7?q;%c_!9_i>;pT2#wT9SI%ZT0X***;w74qCUi54C45rvOVutL@F=KHV zq3~MBNY)RcZhmYFZAE;oF|`}#T}%d1;zhEpDfM6Wr_imT@=){LOE?N!GL6VS>o!p< zO$2?)6qW)}Z4U-X^(y%e629~IzH>SA zK6L<;X;K`7o;E{i;medpOs6ZN>o8DhBAb4ILLtmsla|o4pXnuHh=CCV7tsJsd=Hl+ zbIB?#ncW7NSdZ zvc5sWo(VUo5^=4xV?{}lpcsdV#h9FMasuMze52X{31$C7;mm+_BYm+5Iie?7fE{VR zS?{}Xxp~_Zthf1(f(N=4P>-s_rD-g$WB$;-LjXz(VVFC=NolWE;IT3OF{QQqNb%=+ z&%LBZSJrD&xnHHX|GC)uuO)~mOQ1xR?bJxa8aMzy(Rq@V2f-z<9-eluj!cV^L+)iM>vo=^t(bjN{ z*bp(1d+n?uq3FaIunNByrgplf1Cn`k)H+7+!n zk_W6jHaGKRF1lGw6Vn%}`E*_vC&F3ev=4cP_d8$e3Sfqjz7=84 zpQ(bfPlAknUImO4zy?BxUDrVmghdyb3%*T~trGyI8zX*JEtoxFFGe4&X`--cmmYCs zx&lmz>Ag>n(zFy=jMmHOkOHSRw?g=KhGEJ1(h+2@@U9!MX2j@juIMMaq)?%IogtP% zT;GLL8YDf@8kYz*%GK*=+dNK=Q!6cTNY=^wnNGfX( z_>2wo{BjR#lW9g1jgpkdY(6D?kY6lGakdB2@z4t&E<%8nb5J2zvaX zunA^@jVEvC4bwuHs*!QgD|EkDb@My6xtq-s(s_n01m^3-twj1LdZp;5(&$AIBte;W zaPMozJy5i1_gZc}<|ysHt<1R$!XV{sCC3QTLZ-?uOD%fEMv>2)>P)|SEAc+-<%1y^ z{S#WVHW7>#9bx|`e#4idRc;UJ+*4&4hLz@Up%W2iR17nS{S^DwVw8(z(r%)AxfVzA zj3+2_1xqY1mHIlgIlt{BgLO)ODSy@uwoD5s6lHHsx%fTk&Mk1XOjye;u%vd(RTr%p zl;BJ8ALL8H(CHe@UoR7xN8Gs8!t>DytrJWub7?q^raGSOc2P+rTGAJ@u(#OIIlB21>GsAS zOn*9^SenK=`lLKD?mrR;BTUQ#0TZ1jwE?E!o37DTDs$xRRg2B=HZFWwBd10GjEj~|h74SA;k>WrP z(;yY0?7)`W4GDWaPfGDVPa?zT7WN(~xnQ=4ScGL*25CC=gN{!68cVYFwX`k0j#>pr z$%yha-CdLFTGdsI$cESHH?LrP9XSN(FIAv8kj(`+eD)JpaQ3A-?Aa%)&r~q{ip~qF z1DFUYjtv8#R^f^uNm2EwHHY6sED->xk$jIyG*3g=1~YmS=^&yOE0!epqqtnDA@93% zF%XGU32)bwQFq28f=q}F%#CDnHRx<5LS_uR;xYO?RsH(YT}l)yk(S48jKnMKF`GFJw3~$Rbz*1B;S)y+DC8av6f2v0U~ACKH#W7h+D+D2h=l~C zlhu%A{U7$eIxNbq>w6fw5eez;QV}F1MY@qj1f&}TL_tbvgaPRmknR?wlx{(~k#11w z_-;^9&(Wivc%Jt=@B5e6<;>j7?7jBhYp?YSQvP?jLh41V1wGO)LK`9woeg~Zd+Y7M zNhn0BcPebWikGH4STM@&x356abUWXjwo!9}!=xp;MtRyK1;!BqiUq}h@J`NyuS|tc zP{Xi?pD14b!ei9%Bk1KAtoRMUk)8u}5R+8Eg~@@6rngnB za84AYuG<`Z&MNg)ip(8qQF5rcs(9(M!Y<7r3?ih65c;-zvc4eY8{POJk(90=Iwj{e zN(V^DU^)9)QBm^q^HonTts_ad^k(tXDQ9&NwU$zeqMdeed-fkRA-m+BJa z#&io!EF@hff~G+S?qb=rG@?8(eEi~|G^OS6;!&mzD|vOXq-dN2ERaP5w|fa@E|nNV zhAY8YKFwFX8znF36vmvaW@Xfu55<`0#T1yg-s0SL-W*s6lYh5HX1#CP!Daq-{q5yw z7K}?r^SiJoWSn!D&M2otcv9f^1Q9?neL7MN0q^*4TOod*LP5?*dxA*f>}owdQq|t# zp4zm0bPfD9@-xe;7$-h_RLRn{PG=81H0djO@xeDYoerY>!tj|vLxd}z^NN}vCL&ypv#VWY4BM1*Ijq}iTeS7gL`22y6-m{iwJi@KiGCsB z_zES^z0CmK?L7S!K6%qu5ml+gt$p zXaW8eIJ_f(!)OZp3QhNkJALXg@~epsQ|)8(Z@Xpp&-lLh=j1M&MhIVO zar)^Xv3Dn%X5;KV=;q>2{4cze^s4!NkzS|522j(_Cw&311>?{q#(2=vC)fmuK_XMp zu;x-TKWH8teFtFs^Kkg`Ga56@hBAUjDxKzK;1{;?g5pQJeoj5Upn=$8 zJ)njnjF7E+DQj=NPmx9nqg~@N^;);GRK?ptbu7pC9qM63DhvwO?yvUAQ_9I#th}&g z#2B+?(J$a%lC{mL{+vkJ3<+9~2i7eI_n8d^3Dx3I60uIN4NzFtX7v|b!?ZafvTllR zFpvPMuH^1mTS~*b4&bW8GFW*RM$0javC+}8Wt&6frL6d&lC`%LqvGqWA}sgibkVO@ zEOc+3vhRSE2!=WjBKn1uctnJS`1>ozpG0h$Dg>QMZhb|<^<6{#%PIzc#7g`Y-}BGZ zWXB&sURgsP;>f8$+%ZlK)PKJc0mLBJooWHrdO&jPkBKQi2X&{Gs?vDa84_72cemI;z;P2VDh512(ZzB^NuO%ISxa{<5lltjmE=3BZ-6O3oJRXJq*vbn4AM1r zeG&yXm}U}2?UDvt4Dm@#OUbV2o#R7%jZ}-{5maWB`9KZwFg;y-y@REoo^GDsY9lf- z26KNm1Ge-q(Ilz4I5fQgY_=|w;a#bgmFdMkl$qK&!-er=jCnDmRIH!es3eG59rAqM zN#7T?Ehx_$CaPahoFQpg0yFcyn|=z`pxW{MI)8z_26kw#0|%!NY=)UNMQ>J{eug`p zY598VYW>TV<~+lPgNW93NWSS8ifA6|r|@L;4ohd`2oe?;CLt6ywddp8tX8;yQPucA z_2<3=PCh{`PXP1}y5G=0J{g03qJKai!c_LT5AjjB-W5uq( zglb+?D6PzoOkLh#udlG)u&A`b-XCEGCr?BIK|sP#h`HXW`M>U=s?;!S$-zS!*gqh=+B z&3^gCtl}A;#q6@p=EWQUUbmF{0!IS4+*A85SR-HDsB6_KgH{X}U3YSP|jPq4fr0Pn3;D@-RS2k2=NFx88Q7IV+3h z_TonC`EJJBZ5(5nw_C3a4c~6(TU~nF$$vJhAbS{Wn!&=7GPwL|6SO4ry1aMcUF$jA ztfEeJ_~oKkH;20XbG2`q*$o&Hv|YSGTavXgWZrGcpxl1cC{nsqdPC-0(iOJcqdlc zPckU9-l8}M8=BV z87RbUzUx=cDPq7x33kE4vXJX|T_PzUz*8A61Mtpd`F;2%!52ESvP*9+;(*CqU>G(5 zJ5h%BqLEm%Et1~%4c*ppOOUEz{O-;Q@ZA5rZzFWDxB9jx{S$;RWn=dY%= zap%KG55UHf1%vvveM9ONak4f zBqkR^y@aT{q`jqJMqV;2SBX+Gc_yk1P!lULye)!unl;fr$TvhLHJ#92DRpO(4SI7{|hVxw?x7%}2&2VXU4V1I{ViR<89H>3TmiMVY&o*YokBi@3rLg;1bdsh;p+ z+cozj`4OK*zCbe5dpXK!3zhJ#NFQf5EHU%bOHeq$^B`7|zYY%*BvE zEG>%NS}Isr$CYHZI=XqKP-$12fG5g5^h!o*9O3D8PYs!9g|RzDZ{%SESOB;Le z_^PVd;p9i5W*M+?57w*Ugev-JOo!_u%fpZ&CXEYjff{=(kL0Tzbq%#Kk{~ZF%U(F| z54qu}1YQM+#^dA~PsjzR7qkZA6ednD-KHWKX_Z$dLxqX4DPd5XyBAh=q_L!msouY_ z$qc22K`boxs)rKg74Z`o5IBh6L*1^26g(}Y>)yOK*!}!9CW~5r zvsS+U`x+gok!e#aUy$(fBT49f7RIHlkb_q*EMvM_{KShmdlzt)5r}58)%f8>`n^4= zMA2#%xNt9X*dejExSVL|? z-MmzMUTQ)9fqt7YFG9MzAw;oUttZ#qHWPWnSam3}w}4tS%j&+#joEunRnoROt~{pN zxV3W0(#82D@26hsQ*%H!X2Lf?^!ErvWI&Kg2!!W6{BR2oDyB3?l|^K+qLzy*V!nK4)g#$>D@E z*vW!X^f={-ANvBWioo#BToTE=*q5TD#$@TQ_~Jv2)9)w5rZ4cHh9nSqL7-$nzW@mc z2OLn#N4+AjF`0&aC(cV(G}u#3l9QTbI*18y69yrWf3EGKQ)6IIog!w*>p(cHXxI5q zfwsWMkb$5t0G$OsX8!qOUr3o;F*NzQwe_{iiv&bYvl-xfB;|Zi+ftx*i{*d7JWO8r zm3&-)lAk!+^y_q$0%N9owi(LaU;ao~pqhFFRG&ZyZlI&nk=Ji6TUK{EPx(vnx+!A|^hWaGttfX4Yrf8gDJEhLU_Z{G-sKPd@&QBQ)w zojQFk!H*q@kgk~HxI8-JW%x8)KYiY}#1v2q2`++OxSQaAPvx|h0R+OaGSq#r%P$1N z()Q}#UMJ5|_oW&8Qq<@(pVzYYvd2Fy3;kUoiobSDlV2?)3{JSlfb)7%(N+b6Lf`_x zw|c}rAWCtp9iFHPPlz=Y03as+-az;@?QpJXtP^cutwC7m49C*~50FI0gR+1M6&Q#N z1kf^|WpbXM|06^lI8tB$MlT##?dOgZ5s&Quk&NDNNL&88vV`@2aR2b#T%y%HUA-6} z#zc@Mhyx7#4{)-R{eW2g<|-GwfEt!6B&p$R&4_>UWVaNAhCf4~`6q;ze^K;F^iNC! zsqpeK-uXk4J!mK4L6~p~CI=RP9#EvU1EB$fD-AOGEavk?k@lzH|6is}B5*GUO#!r>y6N3{)@Oe-(NC^1S!{3zo4+f6$I`5xJ z7*2D&vn=2*`<`^QxYCK@U!|aZIbZ2BoTQ*%bz53K@8>_MiWV|Ycs(o7R-jK^aqF&> z7W+bAG4f1h+fb_OgQ_q%n2$RVpmFo#AH4dPfAHo1#1A$i`uKwvF(6X1>}IdYE&A%) zxaYt6!M_QG@5RiobtAqE^lx_~em&4pX)k>l=wJSczke;A{9GF7s?(we)aiW^7_e`@ z@Kd4l?^!E9xjFpH*2=f19*Btw(4*5}Y4{i{Fd*PWtpZL|LNE!ie~$j>L_I?u^MHiO zgOMXY@yA#Aud4`ua{nA+vxMZ1|HX?@?vWERF7X$KP#VY^sI~xILun9y=H#ycKQ4txLq>!d>4GP@K1tozPw$g|B1BZ zAFTZeZD}--)2J02%7mTYWtHXD%5M~ppbd3R{#?carcV#ZA<96~KtS|;Q=AYBxB>o3 z4ngz6_eh(Nf=nyo5%AB2UkH_8D{Sf^MuB=lOzQ$w)to_ODR;RG)C<0=2O zqwsfAuJeyi`R(sbIsWG`zVkzaqSUaw-42!~2ip{&O(?PYmxr{_fviv;TX-`+w8!{bx41|4UB3^fmeZo$UXT zlRtU?{H8GYv#%wae=hg_GaKFC9p1l5cm6Lq`LiY4#iXCfy-#+uDgc1=37NEdS~37; z_U9_$Kt~)N06L37(EyjzW9HvJ)%StU{l?#LVfiy)25hn#SHvTCB41fk)qME2u}P_I~J^#>+dfN30ok7X;OBP)Mv8ndF_A4SY*E ze>aZF;Vx4{{gpjyvw=tp?)EnB0`t5IBlr>?!jjd=@&E?h%4qxBZ(0+%!_e-Ryg;~h$H;s8ZtE;d3W-JR^S#ZrS5;voHxC^5d^>VFIu7Fw5085KNSxkb zi;lZOQ#Z!BAmgXTJ8wbF^;={q0?PSGJGUY{?v7AIdUUvNqkB;p3zK`$CWq_Xpf8>y z_knUNCV3dwwmtcXBfF8@a^fk;q@?^XQQL`R z7)hqjyg|z5M`RdaeuU~~K4NNtdL7L{un>c<6}c=}tk4==H|rsyiT8821=XkEMx^9| z%w^H#qWHrE7c6k8pbuDldr}5mWJTsunvc}!50WSCY-b5hpY;JP?F+(zBMZqo%ireT z9>5XTV!(fTSCu~3$SUvdOe8Wxbn;6SKGT_yErfW)?4w|v3>Glt#ROk|?=76V5}T!) zm{E*MdQBzfq#&=nkYOJWW$8S|T8_(^tTp_W+-B{V@D<5Xkve5YucFDb-o28P*v9tC zhN-SEosM1Xz>(jd>|ly2WrzjQUEN03o!Wolowk2pG0j;yhv;Uv7^{?JVTeBBR+q4d zan>D2lB0o`u>q*jEsKW~G}{vjPR~`EBDZe^Fo@I22JjKx+3ui5(olt@Y0ZWS-KZG6 zhb~Z?FPIOk8w~!mC1Zc93Gx?}F+p&FQTH^}rNgGi@)xC(LDkmmZ`RK2?vSpd^m@my zw=x{X-$OcwRaYJyYrtFvek~usV9+;m*FKw6Hph7r5-0>-MY<%;v{?Ky>rwmVfaec3 z)Wv!e-ZkVL?YA(6{8e0Wd)2{10eZ!QNn$z3 z!``D@>g=4XWe2sry64UH?CX|f2$iYspvD>!7w;AiwpQ|Jc|(Z3QJ}|#rPl$QZUh%s z>iwz(DDWCY%h~hSAL-fLBAl=nrjp7P!tQ(TOXkcZKG^d&>NXPSOCsyMnaV_F@~Ilvvp-FKe3wUQ}ZdSFYEV zNFk{@iNQ>R%Ch_3kE4bhhcx(`niUhe(&K8=@e9;?vNd}$G!D{LUW)f-MTVr`;#s6? z@lncG^Og@Y^%Z#K-MNYYx_FIeL1rtxuX5&nj;JlxO7(nSwa0AsW3fyf+?M`&>4(0^ zu9>=LFAhY>hmxIQ5P;1d2{t)(3&In{9fe&+W>M?0n+h9`Vb zH%geLNcoWkALxYio(+dF9ekpYbm=3w75W(58V?}qjDJOEOwh&_k|gjLRu1zzC**14 zzXws5_FpY<-yP)>XFo>NVbTf!_APW1SW5b7PakfgOvwn|G^d*hpK}*WhKNQFXq}=a zfT&6UVv6_#i^>Q@6&9`D31gewG$nVU#trag#R6&RT)l$>_yMM3Ae=-M);W;&r=l_N zfHdF%xF-*wIDWwP7nJX-9-GAC(T3*{kDZEnuY*2)4*D3)7k~PPFC2%nsO5P0u{{u0 zxYiRv2Q&)d>*RR}*SrxZ!KEq?A`#Cm4EcT0{3Mr~)VQY|@1MHu|0@bSCn)kFV4*4g zEY1j+D$ai`bk+aAy3ju36cKS4Yb$tkKZVXEYNbIQk$t&^R0L`Qr^moQ<~WHA;DiIeg;t=N%XAgoF2~4-W{Qrvj$~ z>dC2c4g?LH4zi>!pUmR`11Q`e>(f;Syg35^hNFUx`M$Ux-mDez`OPQ?oTpSA;J}Ci z+VKy;&L<)BbM1ISqlrF&$CO{|*nSCQ`{qLYAtnq??nR8m@4()YrMcR&}BQWRD{n4kxXh<>Qd)IPpySyF-S;(}wVR;@`+SD;__R^;>cD$T33`2K zjAfAIgBPys5z6&(7lhCLg}=h?@+1;H6?G_$VmjK_3E*enHB1tzB23d2<`?I8Ws(p! zlHox*GCNG;irZ?d|Zr@HXV+904)So0>tDZ;RWWOhRMr9bc0NL#RM=dsI91A zbp|<;qwL}6-FXCeBc>r&CnH>7ZZ3GIK9QqFG>p|W7f6kUh!4;vR$)aL1xo>CmQNaN zXJ=A`eRgCp!2>BlLeUw#&FKOBXoEgH>Xdm5F(vdn=wX0*j}MmBCLUw<(L*B%z&UDy zGPh-S8@*5ia|n{slh2XD^O84;9`?v`X!#K=8h0jSCf4^>SxhK_1!TEwPv_bAj5R+EosNmh%mnS`8QbzO*od1~d?*zN>*q_InLPkB=INY=`usU0M>M@Ha7o zIU&jXQP7qPeoftaGU2=rlHZjo%(cdeJn9uHyFM?KEE7Xr%UPJN_?YDY_4UHqXitt- zPFJQV+t+rb_X=rBR+{qd-Y(qV&bMfHC~ zuZ`E9p|PcP$a(9gDRz&jdfN2eEPzfTX;PkGflVy-J(@*}WHoB75{Xj^h^*LqxAv-~ zDpOUUuHk-d$HagsK{YZx(FPq>b~*gKcv-tB-CX{ zD0mI(>6Eo(Wv{NW%q0BN$JeEeo(88+8~S3w?YK?xzn65s86+2^N)>uNt8gkpUvq#u z6b02t7jmtOGbK8g$~I2mDJ3aHN%K7|1~-fqTc?dKg8OWOExF-rqJ1_(xBd}|l96^8 zT&R&w6jHB|bexj$d}?@5dRkg^!oBWf=yO~k2AHCwTNr=`?gdDs_zimFwCAydCh1l8 z27`ExEIHG%t9R2)fszY>skcvW(_9RoT(BG{ffxyiL#>z^D}*$2REr~?BUmX4U=E`! zT~c#cDPK+?V0qqyi7fO?ygg&pEI$+xJMyTK&axUtf-ScOHfLV{g`ATrMjj%_CFlBJ z5#>U5yyo-tdc0eXR>>sl`|I_@0mBy>sXZkxHWOwz<~K5>Fy3yx6sE!2!anQww*CB& zqXH&}v_^Mpyt#%=y~t{_bywM@-|c9W0=)Mx5R|jdS1avB6}?thh_SGIbNHAaj0rN! z?o}q)FY04em5dt7$cDSqb+yIp@~ztsG%k zOL_bvym^uLSSvY3LJjFvfE@R{*ttE@_14R)&-ttPnW5-(DFY1&k_rX;-VWcXDqBxR z#&TjPwzoLk849_%1j^daN8FohU^&v99unl;<3!8l*)1HqCwtVn7Y9NGS6iXxlEO-k zLm?*cgPA*>(fmlkB%)^44T%?5mm1GIxf7n&dxvNQ*(fuu3W{Nsbw2h(X03=#BnB2jeM+ z5IxQ-9}&j{oW#;PI=eg{lsu7lS3<8bN51kkfJs!u_j!+FsKaBjYbVPIH{5whAZWWv&gSuZbszrb~uINQPBQk}-MD zrn_UY`eEf=v^6T0d@Ib@Yu&eVmtwnzls{)Pv&?j)@~J95IuJ# zg{!-%-8M8Y3Kgmv`6?#}My1Qk!CI7iYyL>u$%EC)jZ6tXajwG&zc3!PCPeUZY3EsX zn}_I+Xs^;N$odGrPQc7cy=qwm`;Zn2lzRyQkKY(02$K@AxOMItTUl2qb1ERZNAk>}?G%r8L6$akmly`QJNoi9n@aVeFj zEuEG1_8GIC7wPJB2)Lrgw8|*!8Q^tTWlQf+ljiH^J@$wB+U{OU?0TPlyDfubaksr< zvM1+WQHCZJqRfLePZ2GAmpsvQZwffF5U_yY8o#kT8(eXY8*HXN>tdaY(uIQfx=h1~ zrh!UL+k^vkF=NHlLB#CMqU=Y@u-e?}14p|7#U&deCa{99A3aBR%}&qcFTDowLE#5O z%PtC95%AC8cRnj;8dSf9KQc4eTUOMzVwS_r{3anUHyM@1zQJT*1GD$}Wl(yIO+Jbre<1taInhR`0zf(4<@5s#-wJb@HXxIt1HSBd}Y#q7RQ<6_8=@L^WZ1 z6{TT>St|hz<>rVxNdo6!UqdRr=6OwHeAU=CNS^*%9q#$YPlt7>)OU)n`;UgiJ)fq% z8DY1z?apUDL36=lM`j04)PD|hcptUzr~z4E0n{j0Pf2^HDXYi&OiCv86@#6Q8#An- z&^M+92qIfNH#h7uOmr~0)oKEWFC@_%O!B#wyku5N%t#2k=B#zkHwewvi;l-wj;8cg zlD|!wa@K-U%5G1x2U~{T@`8#(X@|;idiI?di36*_CY>q$IA=h)V0ECsQrIr{{(Vz@ znxTOfIQG0KCNn*my@4K&&7#B`re^AUL!)SSir)Jzn;Yy6&q#0OH4&NGncN*-V=gWq zs#vkVOb~HRKQHht&(!@r^)b-uo$4GUUAMUY-U4BJ(TWU9HSXsV7&4``COqq&%2y^+ zriUCgC+{PdrvB1L&v>=33Pv*!zm}^wOFfiO1}v~=>vBEU;_U*}-HTA5GMIrC zBFXIq7fM8olsfg&yjvdPZPcQq0(q}mTuDquP1nLIoV~7gGntf--fB;M@09IWdQq!2 z?G`RC-mc{&Oq5p3sFbbNRrRAJ$~4C5q}8P7j|1MLsJ)=R2;JCkaxFbXYq~!R97Z}F z$CES4N&KusI@Y-FX4auuP-k;*=lb*;RyLE2`{hc|#g5EKH!F{#llHsO@RCGJ+_9>z z_aQmKUf3Rcz=m2B$F$sk(Z!)mAaz12_HHq$6VYbLgcr-*St5aRPQsHu7mcO{^z;Jj zC;h093gf)NuTtNL9~r)r2>|bGQV5W*7$#loVN)TZ6Jd|&3XsK_p9(&QDmERW@&k6P zQAn`$AWX30X~hJnx&{JR|2)vK16SZl)%B~{gkS!y3-qjId=wVz;$g!$?JXhMNMf zgZ-9a2I)D1Q$DCJ7;jK_r%*mQp}Z+(@SWwVIQK5SFGoV+bS!}j@l)VJtOx!eto~DF zIp$;c?tf!P=vRxK(#4FQe5oHDT-A0vrJewznhcDpE?5kh+MiRdxJv)OtIY5XKcDSa zd}l{kvE1M;7>+-1IC$&(07Gdzh)H_j)`W+Zm?)ViX~O#e9uf~ja-}NTcL7XPv2zK^ z6vf+nfRr^op&Ai)Uv^UK#IJ`%v;R16TNM#K(;6(g7R5f?_p3c?bFJPeT+ zC7TZAMct7BD=UdX1zeGjCkrzi#kvLfya~d=Cdqap(Pc$P%*0&EqphLVmnVgFJ2y#} zDtX~hteH<<6oW><4sC%}Bny(4z@JqpScCJ3H=Rxd;jmjee$#Y)HaW?zRwo{-UkBYI zHFRM?IHVY*YaydhzLqqjDEnjO3I?c50Xi05pm3lNdd$&nfccdzOdKZud(P6Bg{Q?a zpn6&YR8I}T_9rp;bJbI!e?TE&?t4-h`x~hLDXEOnKikIm#IgQDzqAyG2|my;&>Qv% z?W7N5@f@IE`WsKF&(+gr+iC$3oX;(&V^1k1qaP;&bSDM(*%E7@GI?okALfCp71wLIqjquX|vp zi+&>oQrS~2@J0+8{4wtY4hASd*qZob59DVK2Bv*(j*CFv`4{gMpXS$-sw4fz@1+(b zw*DDm>kc5ZdL}Rn`{ZmeFQjbaD-EThzhjrU1?XIR;<&0nya@kzmxu*)u0NR#ezUFi zOoQMJqGvyLvrgJvP*9P8)XlM8B0L~<16pJFupmxe zLxKwWb_)y&kibC%ivl0|ncURV{QoxzoXf^s@UH4unviYf@%ugsqATThjb>n7JNQsX35A>+6FWD=34w(_kv&Xo_4Nu;0K z8z9v`X1Lk@{Mp;t&Tlmzum2q*e{JB!geR#-V>AzWsNwZfpd63~B>{PmK3MT5Lmcof zzxe;*^=pff>UrrpK&Sqrfe!jR2Ksj){)0S-(zyx+5C>zz@tz8jJb^jlc<~F0%ggEo z!+%U&U_jWPn(-f8ZyA1|0(G(;)c(IqSFfdjfb{@OQ}QC&AFPLhzc5WRwleO36#Elf zDAV8UL_e6O@8df@9Yo$e)G%UJoqU?1M*6O}v4|8HaNcS9{<@U|H&2%vP{;}e8G+7# zt^&(V7N z=wASA9IK;Fi75XYospfl#)KTEK45^9-@#4b2FpMW`S-x<3Y{HCT1VT5un6NWWb+2G zf=AC%PUQNvjAjnVU%4X4ZI2(v$b?6tn5e5ev}@yp7bV;^ac|mWuVBv)r`72#7XE-D z!5?m21rh)Qg*WLhw5c)`AOaUL1rcTr9@nWF$9;NLLB5*Y|D>d?SG3XT4d;p%5e65i z3Wy*RotPOvp z$n{rcvbHhw-P(w*9Dbh96S&b@z`|R#(4L+ztXh!9Nx)S2T298ywnt^vv8b2MlQ7zy z$n#*mUnfjzb3i}k(Pq9T?pAsc5&`3#VVlcWN=9s1_BS&M506aHEBbwqwuiPWpOL`s z4W6|~66lLu9l3XPbfqac3ict0#J4$e@> zy|xIhldhr0>X(-7O7vZESbb&3tI>P?wwdF4qeaY>^=26+hKl0Sd;v@>2zfG-1`NMA z!%)Gb3>_4u_QCRDJQnQMaNi`-E=V+whmN0b?8@7BInnpHv67su7aBUooDb^G##*{; zm4i1|aKK`b1hnz)_bgq(MdL9%#G+7$qXHn*R%|e(Ky@x^(gQfhD3B{_y4wwNizzPc zBF2UnSjD;O^nMe_ A4t6T;Ti3zRbI=3}xq%06!QVSFUC+4);{rZ_^zdj3xRNOO zTl5SHqH1%ztX4eZe*JatAzVTg_9(nmye(il|FTM9D0^18l(~;p)CkJ#AwOKp246y*O>tbv@E|qun!{(LLc_ZC>Bu=N)5)G1?lci@ zz9vY_o~RZb7Z-1_8)C`6Nj4S0QJADZ6S%jwE? zleRg|?@ew};H$hq+q87Qwxm6c)L&6RZ}{Vf`KEYjN;OY2(vp;>V2Cy#Z@6@mPQ#v6QjkY zjqlB@UCW23Ba}$9wrOsMNQ}&@DVN^R8!$Gb7+gv2Ehm-~<>o>hRei>2KlBvUx7UGV zGohhE6I(QGasst=fQouMVQU`R@9Fr;%I z;4x~0hrrI-lZ*~qEfe57_AiOiE_n6r4ZkZEmh5_w?t`8`c`;(UE?t1u&ww$;yKB3i zqdm|6PU{=uz3m3@b4-Y*K}7bek28Euf3b%nPVCXZmwOOsG`k*>c>76Ih?4W2gb zoRJliHCs?B-|Z36X3G$`Xrf|5Lkjxbo(cgu1MNpHU=5W2rakpR&YW@E;*WI6e@|Gg zRX zh)M%EoiY{@CfO`#$`*3k;6oxa*$;glWy_7414vn2Bd-gKQdL8C1$-H_TgQdLcEJdV^#;`y)4F>o; zYe*AZo`x(PL&I=>E9^5#NE`G7BcvT?ZHcw*GIR`U(~F|pj4$BM4l8s?1|(gQm%6%a z^IAq(>V1!b0n__lC6f`hK9vW{wy$L^Zfy1$dd6(_oBA$q4q9X|-5IiUzOgwXcJ^S9 zMSSb1?amm?5o+nU6Etz@#1Tez;iM-4ApY#d$9#7xm|K%`>d~$2XXB66{kJFM4Mumy z!*EwP=To98@6KiTwsXzqG>n#xk~y32Etk$_@2x!FTG?BL8B-|Yt3J!(*j-D2zP|wg z>-OK4cE=8OMP9Wyc;Bynv^_iYmiOM~xF-wmYFB~M*05Fgqr;trlDNaY8$+zm_iT|_ ziuPgNWU@jX9 zpee0Az(siif33d;({0V=37&X&eZvbJHyP6n3gW(C_>9UJRJwz!J}5i0f^$8&p8P@+ zhDRK*wdD9`?p2My;0GwQ_s#)CySxS#H8Lnt1YNAd&d1m}hETNlln+GS5sj7M)-NKS zVOwH|$M0?w1{ce@TzT$^$<&DyjOUJpsO8S2rtNFDpNNg<-1=>lYD+RlhJKYZf{g!jAs;d}ZC82P@zCgfPwsA`c0o0l7`98qvBG&r zZI<`C}WB zDqlV=gozsD>_~vM(r7QFE-Gnzp6SgNDLuZ#AXaeLyCmuEJ~3NsEm9~^K?birMA*5& z0BNjP9@$WkAU#v6!7` zVbs;$M-VEen+>oquU~@8TXo<9#1!*)-)F)MB*=B`Di=~?WX9*wOFwJwuggaFl)jq6 ziE1Q!xAJjVpe?@MKwi7dBNJnL@(0R91pJaz)nGTCIYVqf8-biX6W=dQNR?)2;po+7 zaY0*_ne86W@XBV1y^kOt!i-0(yAQUoi3r0AeUn{d7x?|QJ2 zrD!McR(90EQAVvh4}d$>O((Ge!s}T=*B{;XdxQ6OyMY&N!>d3X12NaQflc~iP*~;^ zHS5k35@D1(3bQxfg8Q1MpKb)-QrBa;Inbgyvk_{-UA9IIQ+O8VZCHd(8t@q5ElATM4ZZC zZ8nlsa)8G?rNwSn zY2O&^tJ-Btag|zfKS+!SuJj{%+_t389hEHWR9u)MWmYLvKG@&R?lwi0ru?jKXoS7D zq>jj3=h4ux>ID1s?5t(G^1YEYV*fINi>ubILuBtYMJuuMS6RonM?vVN)$r15ZUp<| z2r{KFaNE~Bxc4V80!nLXq}P4a_b1PFl-6Hvx2nNV%^(Vs_*l$1ks(6>+U9uBABs{x z(;d0WwSVUeKn#Bvj#e|)-z-gzRG9M1Lew9V0h8`S_If9&@?x_=P}1;dTY1UqSoKMf z_J_5@A14DKxD#jTznBdC$o4aBOp+!J-Dgkz0S%q+p&8FT@%rE}A+GksUznaw{k#-ce`F}&Fp(T>2RKZ` zdmJYNp~s{nb{`{vbhNOLkz0S}D+AtZJ0E@APt?4EfRr%+{L?Ap*;QA^Ig20k(2x)J zu>TXK{M((*u~&VGPpE080*SvZ<^OETSW&*U3Q>IUABd77Z;?|T(YI2@yO?s)!e4_c zX7q0XHq8UK#K8CIPN-?gUI&>cDdT_^ShNv{5)3q3j0pSRx=4NjuK3EP`8QGWftq#_ zC1}S{l5CU=ThiP7xd{Pu^^ZdY^3lEM_ZIbEb@eYKR=6I)IbofX9~Xt9f{m7ZCQm6E zMyZ_;+_dquCYXq1^0UAC?`XsTN^zm)Cd?hREHBm?0a&DE?GR9{i2x}K^rc#3h?zhM z%mi9610)+%ZlAL-()@8F@i&&qsBt)282~KmPuPnFml*Hrh&RKdj!_u4=#I3-GJFh? zPq&I>-$k$DXkRzYtKHFk{81k`IP2JM*ts=+&+_S2g z*@ldp0S8H2fRWe(A>J6LjopTIg1(#4d{zM0jCTBf+r(v3d-xfV`1>gI{o_u^T(sI^ z;Y|h;?)iBs6CNi`h&F8ij8W=pI0;lPQ+2E;i|2HV8BQvff?I&#k5cc=hZwx2i2+CJ z+ixCT-4xY@@Watk28qx|=(-6Dt4;+=u3T0CDwjLTj{x=}m5-VSoxbADWA@_sqqJoI znkUC0LOwehX+sQ4CUz}hO4q%F=~+s!qWn%uye#H|!4p?%uG9oC<^{t<$i_Lfm|&!k z=-5VW<6%21y9J|&5D(*7+h`|XBVq7KUy#AdKbMefmT>IkO`L7aAk)xx`AO_k-g|R7 zGT-2=h;~oSf#Zyiqgvs{i zNDP*f#f#a|)AcQ~qOHQ`a4j0~%Q7n)R$2@zk9IRmt6=(C62v#Cqg9h5W23TPDo^gM z)GpJTS}8@0h_2UkN@Nv>8I~N34qD!xXP2|;Gus*=?8v&@a?|%Hi>=pb3w3)O41Y-5;XreUKk65i zy8Y%pJM)eQM0s>@Dm=%acshg&m1IJLfSGIVR)8kQ{N2L>&RLd~hpL@bddv>?nSJJi zOQnyE9YVwOGBK9$W|;R&%exWxD=4Cfxfa~wR`xeK!klid8+S#$S?jM7=UIKmp2;&d z;F+_ssiJ9ISxDiVbGR@S5RU1xn5@1$_Np8G;GnB-?8@O?@?oc)S?ivfIosTKX)KOM z<(gZ;XCJS-uDT3JX!&ZC&@I*!id4-gPGT~7?3sl!!HXSgg~74T1b%4?>tAf zYjDN3!M<~mmKV3oPy7BaY)Z+L1v+B{6=WIra5eq%cE1>f~H+sp!{d zQoL%(kOF*EF8N^J4X-j3bOE~8MuA_-ue<&?<3$Mps7>dl?&+-!PIRo4VE@^## zo5Dn5IyaF4>s8BBdF?5S8{PbxzVHV!A6P zbq|xw?t#l_+|c zJ?6pXQmoY29;g1I8TMT-><6hR;B6(fF% z6`)c31o&c@Ctr;AxTMR`NpdVpg|`3n6ll0UQRRaOtCe|9D^bKXllV)ZVGBS%Hae-F zl7ZAe+6sNL^6^AGBOHwIDqhGJi$%#4`-3>dA4|bD0_EjTk30IK$L*gYT!CnR0W3A^ z6Jag;<03A=aH@8LgC|F^wA8-(5dAE(ZYqY(HE%Q)Oute&iaKvXny<|=e_xdDi2Ist z0x+CXJ}3|8!2l<`Cuh;&M9Yi1~K&8p#MCOTJNCh(S!gUi<*wN5(Qo!NMHU8~C20ZFp zFZ}VeeCre6{XzftsMD?Wht56!3&skF?hSwq#ttF?V)y6-I}91G0>LAHpk}$kpXH4f z4NMU7#%47ZqFp1Y2XYnRDZ}%L6(E|cfVT-TbB|;WpO^PN)o~d1cuS6a& z5PEsk>#yji3VxG)>+VWhgsOPZ69JOqNTT?V>VaZ2Wy)(aaq~=3l#u))L=HUpTOtd3 z2k(?I>7YDb;LsJkdEF@peZ@@A!WV0$o0Xbpc&~RN#|~^(B+o)+x!^96b6C*hf5=CN znJ_!df>F`Bn^l_<LcCNf+JxaD5hVP!Vj5(84~&cmgAe1LX}e0393q9FHi< zTEKWUuxEcFyOH2TpF1(Rx`2aKdg1smp}^UHpK}W^+2FHdY`XBYB@CP9kV3VKvNehW zc`#!DGestx(WrfDry#W@M$`=d#yu;_nkQ85^m^jhPugOr^30>v-W#?CvblFH?Y<4G z@D;m*bVUM(W(Z_KP#k$If>X@W1_#mER2C{a0uj_k1!axF$dB{BTfCgk6Xb;W@(MCc zo~DN@XL5++V>2+w3%h}*e=E?RFDhXSOe++Tx<-Ng$oQKWvS8?%jwn>ebrvH zXX_Uh-(YH@TeK*Zyrpcq%aW45Wxu!>#VirG(!F{cF;V2U%+@nCFx^ElfbV%V9eZj0 zS`j1`SKLQ)os*v2?t0H&P$QsYKqOAr8H!m_viT>@8_Di^c~N8R)6otA=|Ovpt)ddLDO zLnXynF&uk_$Ait6{or0$ViStXt<@RqEMob=Kja9ioe-y7a=pHpqKle#! zXeVc+IUIhwJp5U~Y)3p$&1ri*-_xxq!>Yu@HgDXQC0F3YL;xsj@4>V8b4kapvIna#R~cB{j%Fn_9kpSLxR6^GHUNfHp5@ z()DUQvB}4>!gRO}aIVT!*OaY8rv=qDjh^1UVeL&7uIpqp6MoZUN?I(s_1*RGvv<8` zqSZphQo;>-BWPmpG^fpm)78;U$3MhD3if8F_L)nNq#vYBloDJpObSpEPvh66OS&bG zWPaU)KkEGJcBRLm^z&(4TiMLWsoE#TQ-217yH6RtsSFbio|VAaBl-0@ zB!kx6dbHcE(>zu|Y|WyXg&S%7B^a;8MM)Kw@@iSipRczPb)#6d;=J+8YlCts%&*~x zC(^DKS~a;;EpilPn9K<^uGn>rf~lxWPJt=AQ^g?b#!J6}^x!^4*ZU#;8qP#?1BP)~ zc4kHe6?T1~#|MT(iZ7QpN9<A>>uAxIf7(xj}8tDd6lrHH|;tb$ot>w|Z_St*wALm@>_gvR^ec$`e z^StkKKlgnrqi7{jhlHKceS~*WJ9~|4>_3`Kb4HiUB&)T1Oft zKX!fdGBYRHG)|}h@C|Xo8kjr%BY-_uGL2FimsBbp-yA4KFf`441>aCH8r6@>y(CZ^ zKZEEPFHnknag7xdBu)(XOJWdG=0@6SkV2fK$cxuP8EF6j=zQbc-Ssd7d}DB^#ar^# zx8!I_8N~4xVRWJEPaMLHOlbTm2+bOY)=0B2KgYgb!j4oc_E zP~?nn(Ms5mrF@um&G(Z){1!KBJ$~1;x1fRnxhgDU=Cc)Rpd~+nP@^Y1K6=3^y2KjYzx;B-sSL= za!tt!0APfPlMySyNJ$gXY1t*$%M|QV909j&AfgC*jF64Z49Xc3Dd(!j{-n($cqA(R zgZSR)ge`CsI7dvvDT{Ab0nYX$Pa#M{R@1Ea)^>SQE>NgHEIQR&H%cl_HG`L`nv9pf?-`}D~39d%|e zVQNOwx2Y!tBBv!Ij@d(X+M?5&{p+b+6-LXl??SW{t|Wm}XWpeUtQ?{-vNUvnMO6FH z+ew+)&;d@EJ(@T2R8sH0;GTdnOGGCjSTRd#?iXmr?WC~+7zfi@^wlljh|2G#)#~eR z&Wcbw+UR5%FX6IsFo34ssJKL9gg z-{>`xhg0oc|J-MW!^ZFe^oCU%u2sQZU3JqY`%;z-j)8nAx))+KK#yjx(#%U`d1W%% zgkK`vUsm6x_`xUL=~itJ&*)n>kNK2|7t!T|c2)q6-X@ia6urX%81<;N$&+%I!&Fub z3;C?ny@ zV!k^}_t@J;h}*0I$B!A<<5_N(4DoVaU9LoIa#cs{4irxCf9OT9h*Wa=u(^z4>`oTi zBJV9L?V(g|&)Z(s>{a_!bPy)Pw>^^vFm_UC{pwt`ch{#UwL2|kn^{#NH}E)$$~VFs zQ4nuomZe-RG!`+Vj1Y8`5mZC)jdj+@M_;B)H3N5SqNJ}*_ybiRwXd5;aIN$p1;dNg zlt%7T{_3B!GCe58g;9VEO+i9syPsV`J%E{!pxJU0y$K&Rrf6leh3Ftbs|6PMIK%y! z-~IFSZCJlg@)2_o zE_p4@eiG*L1@m@KITV0w@{k{W8MYfLw#5KCOdyvCH zB+ThY9h0xu12uVued@g2>2WsHDG2KwJZ8JvhO|7FiYoPek3#t9e4fY0e(=NrI?x9^ zK5U`)>?g~;?6s<_F%>X78V5#aie+c;z5Es9qw_?v41EZWMx2oWdBX4~^Xw;8I8>m> zUd5~Ma>mc$UW4va)_tH7kQXsxjydWM`PPJMV|DC=V+@Glj;WMn8%0>Ppj+ZYM7eR8 zXc4gV4xrB??~?~Zm)dx|xm^@`s2!>++!`x+^l~!oY#y5ge{}4GxEaDJJ1x9@ThFon z)|CYvT}7*fELc9TRyy{%I09L^%Om%`2j#?9;~0Q)fcBTcixq$*zW+ss@nKuah>h*a^DT4l?jq$iL^5LfqM9x#p$DE_ll+A664=SR{jKp z6|*h+r6dfC?%t#P-<@TC0bcz-6m|YT`b)&=f8AOk;{kyDJa)9I(|ABu;=q6A%5swR z$aF8<5BYUGoHfnOW95Dx4{^J7p|tXdADR;H1+9wTpH|}9(PU?pxJ?|*_jnk%eijcR zW!FyQVQAU?v=aBS;ZGw|=D=?WIptLZRA7$185J~K8AdkEXRk^a0Q~K!5spI%QU13)vzgGMOz zi!-C%?dGehH}DNOZgW*a;zt60{@4V$^uBmshw1$Yaa%uv2~@DtA;fCAQ;xk`V9mx%y!Ot5xq(SaQ&TFK+$#6}ga?Ez3X{XqBohlGR4LJ$J2Vm=@icECD#{gi zA?JZ7^_AS1*qVjh+ytw<{H&1ne0WLCvFBnzS+USk5n^`iN?z4!g4OfVjeP5pdIIf& z=jFIzoFy&9i8iGj)CGkvIu*y4b(IxC*_LonC=pbZnAsFDdD|o*dd}(!OJ#@3Rj%?? znXC4%w)Cu5YS+dRuh(_&Xs^@(zI`ih*j$u%s69CHDtV2|FH+Ko!R9^xmQ>y5rg}XM zv{d#I#ekz^2p@F5g@I(cTY^QuaHE~Ga(M&k&w8L7$31Mb`A%T2aI;G@yK}Q!9E)qK zN19@V?41l-(N>=V|H@Xs{k}+p7@aor_8>bQn0G+OZDo7dAc%Hz$SAIsdPrOD$+Iyt zF&RXUeWj1epwsX>iubOK1E#GubH~XQ8a~b(Rc&a=H009$Bw$w=$Ch_WpA-dGD-|N| z)e%j?tP86p;+^ZNTY{Zib!RS2JyDvY;v$Gz@Q*4U{Zw4Pl{^zb6};7kxh|^oFV8^FkE>y>!vrbx}bBPsw@bw`3yym?tqSVCeZW|_Cwd%;_EEp9k{3>O;}KX;=gu-usT%qh zMjb!G!JS(aRQY4qzWxqr@gzm7LSkS})A1l0O*YzflXiby#@4Ut^696Qo=HQ19 zIxwsISdx-Q!%AWVA=w{n-_oJ_yNDI+iaV#rR2fb3?8r4<_5~F&^Z30$WYbk0LE22>H zw;AZKbFG~~J+P1$ne-PdC134#ghUR|(~tq>?v&k&swqzq3tx~o_l%vJx@LNbXNE!0 zTy>_YD3O%+gJhRF(6VnU*T~XR5h@q+A^m<7h9-wf&LXsAg2@!?!ezJEy;o{=(pD;m z^HM{W&D|Hlg)A7!ScC0DFA^#WtzE2j@~*U)A*5Nh(px9z+lM>R?H~&9SwOxq(ZnID zB|a%|51m++udmSRvB_sQNrZI7VYzXo0E?k~Lc4#slS6&gf+)1QG*O7zL|okH>(}1K;*yP!y!h=#fjxREYv6p|6(X)u0Xokx-%S+ZkF}UjyL)LmvTKDQkBK+YyJ}5fD z&nPt`xst-ol-wC5SsPlll^7T+Xn|r!y;&tTPaeL&(Hx9z8K_NLqPG+&?jM=SLKz?z z#VNgGk4Zlgw6>EWxu{DvrFC)kzAQ_~$`?r?20%FQK^@U7Ob*LHqHUk^RsJn~DV&W_ zl<;&0gn*_IhEtV1E;E9FiZsMcEAm6(8ePl-hD#w{M2qb=-tb#rzkJc?6PWUOBRa=p zT|Dj%X&*I!ijXNMS=p_6e2rjqWrr}XH=o8r$yzj6L$1>#L@IY;q9kG%ktcRU&Q0;> z;$7GT4CE*rK^c#|byXa*@i#`%%%p=}gT%3f!}{Ns^LIG$+_@7w5hX}y0386|q)3sE z-nfuPLNM9@M!CBXaX+G?RxU#aPvz1F6%Qrw5Rh3zBnnGT4p$|=JYUMm^a>ex0EYpB zlcg}t6DNI(!H_vq{hf8L(EdA@l+ByHNps@6)s>;UhSg#mxO1;@!KU4waZvcPC?p7 zJ5epQE6&~D-hZ21ukB9wl)l(L`uP1?T$H_hmFcYkI{Xmhja6_aj#%ln8pj%6&jRSw&><_}xNB_~?p&^d_C9>j<;&;;Ajz#`B% zIMCERaH5%Zy#nk&8MF@9lXIsmrqI1E;KNlFk#}Og0-K{_Ku*M13QHD1Ngk#?c4`m8(f`zwOgad+H%0|c` zd*OW=WYNU>_5vhBRV1U>x)T}~$2EvP0Ewmqh(2rRzh{5C7V~rt_>@rjX}>$Ao~+9* zxgQ(F{qj8`fJVfToAie*-)ajA^u4FHj#4==a`+1o6(;Q~?v%akk;WGzh%ZKd14bOp zhm-94L!603XNYnJL^)nStY;%PnL|UABQZFl89~-G9uRh_dlxt;eVn7YMuFUIWO}AH zO2;yM6uU$LSrCnRKAwGw>va(-M76mDyVr3I zf=LQHE?JZDF8vb>?B9;)O%!Q=tWg0*)B;(QKk5noB#~w+a zG*dJJlV|tYJmXVzjU{hYg{+N+tnY_xE(D_ni=hIIfYSC zS{YCX_lf`>SsHe`)>25KzNQ9Y%_H6y`hIW4>jCJin;&m8h z|I7?=AzzZO_Jsz7VcU2i0iK$laig8AWwJB)V~>;+@S3trK%!K}A_i*qpHyJz{uzToIWV`Jy8bO%Q8OY@ z3zd#$kI)(((qT>2DoNHMQNr@D3eCJFbvW5;3)y%g6~EjxtGo^FY|WcuXdf>R$8e87 z28i#_-dT*rO@G8dZTfOLu^gJO*RK+oW79y*8-N{*=TX>B9ZaE|)|pV)jr+LuN>K-H z(U4qGlP8H`LXiw*h_+?wBz18bd&m|?>TEmFC#}?J+~Ut)i>iW%3fqe|a8uS3$Z9~u zy8_SeR2F^p3|{aoUd}IG6)K@$f9^S0jCrX9@Uj>`G4*iKfbdeOp5t?-sOQ9qEa!|B zWSu7hzy>U%X8gR)!x{ZY-nOKp`GbC1c)GxPrXl1#ibPj4-3wq zX?eu*>s+(`@3;q6#f@d$v(YZsURAE8P9|7jVUi2Di%&J0lU$O1rQs;i96?J07SSv- z=m6imG^DWa^tn4qLY;g?uzaC6M?O=psK&*t@40G=ndtbo*+`}7Tz2ia>)cp_7uGS? zD}nWosLA-#-zv|naQOGa((4zfL#*dIX?I<}ym#?Erl3pNb>E!v$)T&8bpN)w__~8l zjLzq9Z)tOZC{ z1-_-_7d#%wBAcE%lAxOOKVo{*#6=ZbbGy>|sxkk}>GwY`sE3cJ0jV76kUqbdLD-sec! zYx~nsbvtBxz`S^WHp%Uz;~I4B>pVOYhHM<1_j!=Pq>3bqz58h}O*NIz#uB?&olY2dQ{U5zO1VG;TB5<@{h0MH8Tr18{GBh$C{p4C}UGd<@WC* zwR*;`m?;#sanQzV(Vu=VOh#1bmgQiU;tR>aD=}9eJXd>d^j;2OJ^I|dF`L#J!KGDc zHC5&#&%fG!irAea*a~}0?Qa6+#&ip-O8Z*W8Ny;-#g^%GxX{W@io`pccE?GWH+RCy zXS;I6atLZY%NrYm{}F=ykG!^u|0gu!e{G`Dsd)aEnH>AbsEUBBNm!bae5eA zRj_>rT_ForMdOtxgWSW`>CQk`>+rea-e%XZhyYt7{oHZ%*oy{dWP5XM^y2`?s zx4vhGvC~$Vge%MZNAnA}|F7f^+y7wxcwUTH{(czC9TF(~mPAem%t`~U13XSe4E%sE zI6vB9``+wC{X=U`HcD-zn+B{{=J@jVk~E From e1e81b3a1a3c4c5e86f472538a40f1b7c57a8de8 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 17 May 2022 08:37:29 +0900 Subject: [PATCH 035/223] fix(accel_brake_map_calibrator): rviz panel type (#895) * fixed panel type Signed-off-by: Mamoru Sobue * modified instruction for rosbag replay case Signed-off-by: Mamoru Sobue * modified update_map_dir service name Signed-off-by: Mamoru Sobue --- .../src/accel_brake_map_calibrator_button_panel.cpp | 2 +- .../accel_brake_map_calibrator/README.md | 4 ++-- .../accel_brake_map_calibrator/rviz/occupancy.rviz | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp index 542ce6f7bdeda..545bdac7b630d 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( - "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); + "/accel_brake_map_calibrator/update_map_dir"); } void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md index d7de930308412..0d30686bbe5e2 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md @@ -17,7 +17,7 @@ ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rvi Or if you want to use rosbag files, run the following commands. ```sh -ros2 param set /use_sim_time true +ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rviz:=true use_sim_time:=true ros2 bag play --clock ``` @@ -110,7 +110,7 @@ ros2 run accel_brake_map_calibrator view_statistics.py You can save accel and brake map anytime with the following command. ```sh -ros2 service call /accel_brake_map_calibrator/update_map_dir "path: ''" +ros2 service call /accel_brake_map_calibrator/update_map_dir tier4_vehicle_msgs/srv/UpdateAccelBrakeMap "path: ''" ``` You can also save accel and brake map in the default directory where Autoware reads accel_map.csv/brake_map.csv using the RViz plugin (AccelBrakeMapCalibratorButtonPanel) as following. diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz index ca51dc4ee75fc..c430c21562f32 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz @@ -17,9 +17,9 @@ Panels: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel Preferences: PromptSaveOnExit: true From 55d807e4625f65fb857aa5f3b99b158667827870 Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Tue, 17 May 2022 14:35:38 +0900 Subject: [PATCH 036/223] fix(behavior velocity planner): skipping emplace back stop reason if it is empty (#898) * skipping emplace back stop reason if it is empty Signed-off-by: TakumiKozaka-T4 * add braces Signed-off-by: TakumiKozaka-T4 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .../include/scene_module/scene_module_interface.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp index 50261de15f5c9..398994b4cde2b 100644 --- a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp @@ -123,7 +123,10 @@ class SceneModuleManagerInterface tier4_planning_msgs::msg::StopReason stop_reason; scene_module->setPlannerData(planner_data_); scene_module->modifyPathVelocity(path, &stop_reason); - stop_reason_array.stop_reasons.emplace_back(stop_reason); + + if (stop_reason.reason != "") { + stop_reason_array.stop_reasons.emplace_back(stop_reason); + } if (const auto command = scene_module->getInfrastructureCommand()) { infrastructure_command_array.commands.push_back(*command); From f1d2b9ec7aab0b27d4e2b66e1cc6cf1d97b9a2d6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 17 May 2022 22:54:46 +0900 Subject: [PATCH 037/223] feat(behavior_path_planner): weakened noise filtering of drivable area (#838) * feat(behavior_path_planner): Weakened noise filtering of drivable area Signed-off-by: Takayuki Murooka * fix lanelet's longitudinal disconnection Signed-off-by: Takayuki Murooka * add comments of erode/dilate process Signed-off-by: Takayuki Murooka --- map/lanelet2_extension/lib/utilities.cpp | 34 +++++++++++++++++-- .../behavior_path_planner/src/utilities.cpp | 5 ++- 2 files changed, 36 insertions(+), 3 deletions(-) diff --git a/map/lanelet2_extension/lib/utilities.cpp b/map/lanelet2_extension/lib/utilities.cpp index 072f079028db6..8983d9d4f3678 100644 --- a/map/lanelet2_extension/lib/utilities.cpp +++ b/map/lanelet2_extension/lib/utilities.cpp @@ -315,8 +315,38 @@ lanelet::ConstLanelet getExpandedLanelet( // Note: The lanelet::geometry::offset throws exception when the undesired inversion is found. // Use offsetNoThrow until the logic is updated to handle the inversion. // TODO(Horibe) update - const auto & expanded_left_bound_2d = offsetNoThrow(orig_left_bound_2d, left_offset); - const auto & expanded_right_bound_2d = offsetNoThrow(orig_right_bound_2d, right_offset); + auto expanded_left_bound_2d = offsetNoThrow(orig_left_bound_2d, left_offset); + auto expanded_right_bound_2d = offsetNoThrow(orig_right_bound_2d, right_offset); + + // Note: modify front and back points so that the successive lanelets will not have any + // longitudinal space between them. + { // front + const double diff_x = orig_right_bound_2d.front().x() - orig_left_bound_2d.front().x(); + const double diff_y = orig_right_bound_2d.front().y() - orig_left_bound_2d.front().y(); + const double theta = std::atan2(diff_y, diff_x); + expanded_right_bound_2d.front().x() = + orig_right_bound_2d.front().x() - right_offset * std::cos(theta); + expanded_right_bound_2d.front().y() = + orig_right_bound_2d.front().y() - right_offset * std::sin(theta); + expanded_left_bound_2d.front().x() = + orig_left_bound_2d.front().x() - left_offset * std::cos(theta); + expanded_left_bound_2d.front().y() = + orig_left_bound_2d.front().y() - left_offset * std::sin(theta); + } + { // back + const double diff_x = orig_right_bound_2d.back().x() - orig_left_bound_2d.back().x(); + const double diff_y = orig_right_bound_2d.back().y() - orig_left_bound_2d.back().y(); + const double theta = std::atan2(diff_y, diff_x); + expanded_right_bound_2d.back().x() = + orig_right_bound_2d.back().x() - right_offset * std::cos(theta); + expanded_right_bound_2d.back().y() = + orig_right_bound_2d.back().y() - right_offset * std::sin(theta); + expanded_left_bound_2d.back().x() = + orig_left_bound_2d.back().x() - left_offset * std::cos(theta); + expanded_left_bound_2d.back().y() = + orig_left_bound_2d.back().y() - left_offset * std::sin(theta); + } + rclcpp::Clock clock{RCL_ROS_TIME}; try { checkForInversion(orig_left_bound_2d, expanded_left_bound_2d, left_offset); diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index a2c3545d65c7c..ca29304a65b22 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -1227,7 +1227,10 @@ OccupancyGrid generateDrivableArea( } // Closing - constexpr int num_iter = 10; // TODO(Horibe) Think later. + // NOTE: Because of the discretization error, there may be some discontinuity between two + // successive lanelets in the drivable area. This issue is dealt with by the erode/dilate + // process. + constexpr int num_iter = 1; cv::Mat cv_erode, cv_dilate; cv::erode(cv_image, cv_erode, cv::Mat(), cv::Point(-1, -1), num_iter); cv::dilate(cv_erode, cv_dilate, cv::Mat(), cv::Point(-1, -1), num_iter); From 3c02b13469ef982e5445b113d7106cb23173a7ae Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 17 Sep 2022 11:48:19 +0900 Subject: [PATCH 038/223] ci: add slack-send.yaml (#133) Signed-off-by: Kenji Miyake Signed-off-by: Kenji Miyake --- .github/workflows/slack-send.yaml | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 .github/workflows/slack-send.yaml diff --git a/.github/workflows/slack-send.yaml b/.github/workflows/slack-send.yaml new file mode 100644 index 0000000000000..973b08674f7e8 --- /dev/null +++ b/.github/workflows/slack-send.yaml @@ -0,0 +1,25 @@ +name: slack-send +on: + workflow_run: + workflows: + - build-and-test + types: + - completed + +jobs: + on-failure: + if: ${{ github.event.workflow_run.conclusion == 'failure' }} + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v3 + + - name: Send to Slack workflow + uses: slackapi/slack-github-action@v1 + with: + payload: | + { + "workflow-url": "${{ github.event.workflow_run.html_url }}" + } + env: + SLACK_WEBHOOK_URL: ${{ secrets.SLACK_WORKFLOW_WEBHOOK_URL }} From 02a740a86a01c10546741a36dadd85c4afd7dcf6 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 5 Mar 2023 01:29:54 +0000 Subject: [PATCH 039/223] chore: sync upstream (#302) chore(typo): fix typos in comment (#2999) Co-authored-by: Kotaro Yoshimoto --- .../src/pid_longitudinal_controller.cpp | 2 +- .../src/tracker/model/big_vehicle_tracker.cpp | 2 +- .../config/intersection.param.yaml | 2 +- .../scene_module/intersection/scene_intersection.hpp | 4 ++-- .../behavior_velocity_planner/include/utilization/util.hpp | 2 +- .../accel_brake_map_calibrator_node.hpp | 6 +++--- .../src/accel_brake_map_calibrator_node.cpp | 2 +- 7 files changed, 10 insertions(+), 10 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 16b477387a598..b435e5e4f589f 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -924,7 +924,7 @@ double PidLongitudinalController::applyVelocityFeedback( m_pid_vel.calculate(error_vel_filtered, dt, enable_integration, pid_contributions); // Feedforward scaling: - // This is for the coordinate convertion where feedforward is applied, from Time to Arclength. + // This is for the coordinate conversion where feedforward is applied, from Time to Arclength. // Details: For accurate control, the feedforward should be calculated in the arclength coordinate // system, not in the time coordinate system. Otherwise, even if FF is applied, the vehicle speed // deviation will be bigger. diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 12086daa23463..c147035345901 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -132,7 +132,7 @@ BigVehicleTracker::BigVehicleTracker( object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; last_input_bounding_box_ = bounding_box_; } else { - // past defalut value + // past default value // bounding_box_ = {7.0, 2.0, 2.0}; autoware_auto_perception_msgs::msg::DetectedObject bbox_object; utils::convertConvexHullToBoundingBox(object, bbox_object); diff --git a/planning/behavior_velocity_planner/config/intersection.param.yaml b/planning/behavior_velocity_planner/config/intersection.param.yaml index c46861d32a384..7d4cce642b2fb 100644 --- a/planning/behavior_velocity_planner/config/intersection.param.yaml +++ b/planning/behavior_velocity_planner/config/intersection.param.yaml @@ -21,7 +21,7 @@ use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning enable_front_car_decel_prediction: false # By default this feature is disabled - stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collsion detection + stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection merge_from_private_road: stop_duration_sec: 1.0 diff --git a/planning/behavior_velocity_planner/include/scene_module/intersection/scene_intersection.hpp b/planning/behavior_velocity_planner/include/scene_module/intersection/scene_intersection.hpp index cf1efca0e8673..a7ae4b496ef5d 100644 --- a/planning/behavior_velocity_planner/include/scene_module/intersection/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/intersection/scene_intersection.hpp @@ -86,14 +86,14 @@ class IntersectionModule : public SceneModuleInterface double min_predicted_path_confidence; //! minimum confidence value of predicted path to use for collision detection double external_input_timeout; //! used to disable external input - double minimum_ego_predicted_velocity; //! used to calclate ego's future velocity profile + double minimum_ego_predicted_velocity; //! used to calculate ego's future velocity profile double collision_start_margin_time; //! start margin time to check collision double collision_end_margin_time; //! end margin time to check collision bool use_stuck_stopline; //! stopline generate before the intersection lanelet when is_stuck. double assumed_front_car_decel; //! the expected deceleration of front car when front car as well bool enable_front_car_decel_prediction; //! flag for using above feature - double stop_overshoot_margin; //! overshoot margin for stuck, collsion detection + double stop_overshoot_margin; //! overshoot margin for stuck, collision detection }; IntersectionModule( diff --git a/planning/behavior_velocity_planner/include/utilization/util.hpp b/planning/behavior_velocity_planner/include/utilization/util.hpp index a7b3b0457544e..18dab98533616 100644 --- a/planning/behavior_velocity_planner/include/utilization/util.hpp +++ b/planning/behavior_velocity_planner/include/utilization/util.hpp @@ -295,7 +295,7 @@ boost::optional insertStopPoint( const geometry_msgs::msg::Point & stop_point, const size_t stop_seg_idx, PathWithLaneId & output); /* - @brief return 'associatvie' lanes in the intersection. 'associative' means that a lane shares same + @brief return 'associative' lanes in the intersection. 'associative' means that a lane shares same or lane-changeable parent lanes with `lane` and has same turn_direction value. */ std::set getAssociativeIntersectionLanelets( diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp index a00f780379d41..e7d6be502285f 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp @@ -296,13 +296,13 @@ class AccelBrakeMapCalibrator : public rclcpp::Node bool isTimeout(const DataStampedPtr & data_stamped, const double timeout_sec); /* for covariance calculation */ - // mean value on each cell (counting methoud depends on the update algorithm) + // mean value on each cell (counting method depends on the update algorithm) Eigen::MatrixXd accel_data_mean_mat_; Eigen::MatrixXd brake_data_mean_mat_; - // calculated vairiance on each cell + // calculated variance on each cell Eigen::MatrixXd accel_data_covariance_mat_; Eigen::MatrixXd brake_data_covariance_mat_; - // number of data on each cell (counting methoud depends on the update algorithm) + // number of data on each cell (counting method depends on the update algorithm) Eigen::MatrixXd accel_data_num_; Eigen::MatrixXd brake_data_num_; diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index 0b24f6c4d41c0..e2707a51160b3 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -155,7 +155,7 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod std::copy(accel_map_value_.begin(), accel_map_value_.end(), update_accel_map_value_.begin()); std::copy(brake_map_value_.begin(), brake_map_value_.end(), update_brake_map_value_.begin()); - // inialize matrix for covariance calculation + // initialize matrix for covariance calculation { const auto genConstMat = [](const Map & map, const auto val) { return Eigen::MatrixXd::Constant(map.size(), map.at(0).size(), val); From dc16a31c8c2bbeb7ca76fe8a46aa4737624c5801 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Fri, 10 Mar 2023 22:09:01 +0900 Subject: [PATCH 040/223] ci: dispatch release note repository (#313) Signed-off-by: Shumpei Wakabayashi --- .github/workflows/dispatch-release-note.yaml | 39 ++++++++++++++++++++ 1 file changed, 39 insertions(+) create mode 100644 .github/workflows/dispatch-release-note.yaml diff --git a/.github/workflows/dispatch-release-note.yaml b/.github/workflows/dispatch-release-note.yaml new file mode 100644 index 0000000000000..690b2fedbbff5 --- /dev/null +++ b/.github/workflows/dispatch-release-note.yaml @@ -0,0 +1,39 @@ +name: dispatch-release-note +on: + push: + branches: + - beta/v* + - tier4/main + tags: + - v* + workflow_dispatch: + inputs: + beta-branch-or-tag-name: + description: The name of the beta branch or tag to write release note + type: string + required: true +jobs: + dispatch-release-note: + runs-on: ubuntu-latest + name: release-repository-dispatch + steps: + - name: Set tag name + id: set-tag-name + run: | + if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then + REF_NAME="${{ github.event.inputs.beta-branch-or-tag-name }}" + else + REF_NAME="${{ github.ref_name }}" + fi + echo ::set-output name=ref-name::"$REF_NAME" + echo ::set-output name=tag-name::"${REF_NAME#beta/}" + + - name: Repository dispatch for release note + run: | + curl \ + -X POST \ + -H "Accept: application/vnd.github+json" \ + -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + -H "X-GitHub-Api-Version: 2022-11-28" \ + "https://api.github.com/repos/tier4/update-release-notes/dispatches" \ + -d '{"event_type":"${{ steps.set-tag-name.outputs.ref-name }}"}' From 057d0da1776c05363d136930c8ab48a8deb54042 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Tue, 14 Mar 2023 17:58:47 +0900 Subject: [PATCH 041/223] ci(dispatch-release-note): use Github Apps instead of GIHUB_TOKEN (#315) * ci(dispatch-release-note): use Github Apps instead of GIHUB_TOKEN Signed-off-by: Shumpei Wakabayashi * fix typo * chore: remove white space Signed-off-by: Shumpei Wakabayashi --------- Signed-off-by: Shumpei Wakabayashi Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/dispatch-release-note.yaml | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/.github/workflows/dispatch-release-note.yaml b/.github/workflows/dispatch-release-note.yaml index 690b2fedbbff5..0245e2b929cd8 100644 --- a/.github/workflows/dispatch-release-note.yaml +++ b/.github/workflows/dispatch-release-note.yaml @@ -28,12 +28,19 @@ jobs: echo ::set-output name=ref-name::"$REF_NAME" echo ::set-output name=tag-name::"${REF_NAME#beta/}" + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + - name: Repository dispatch for release note run: | curl \ -X POST \ -H "Accept: application/vnd.github+json" \ - -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + -H "Authorization: token ${{ steps.generate-token.outputs.token }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ "https://api.github.com/repos/tier4/update-release-notes/dispatches" \ -d '{"event_type":"${{ steps.set-tag-name.outputs.ref-name }}"}' From 38d3e7e7646aa9ab89a9fedb090ac801e9d25bab Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 26 Apr 2023 11:44:40 +0900 Subject: [PATCH 042/223] ci(sync-upstream): run weekdays except holidays (#379) --- .github/workflows/sync-upstream.yaml | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index 3e164c07dbec1..267fe2135a627 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -2,7 +2,7 @@ name: sync-upstream on: schedule: - - cron: 0 0 * * * + - cron: 0 1 * * 1-5 workflow_dispatch: jobs: @@ -16,8 +16,21 @@ jobs: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.PRIVATE_KEY }} + - uses: actions/setup-node@v3 + with: + node-version: 16 + + - run: npm install @holiday-jp/holiday_jp + + - uses: actions/github-script@v6 + id: is-holiday + with: + script: | + const holiday_jp = require(`${process.env.GITHUB_WORKSPACE}/node_modules/@holiday-jp/holiday_jp`) + core.setOutput('holiday', holiday_jp.isHoliday(new Date())); - name: Run sync-branches uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name == 'workflow_dispatch' }} with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main From 1a110178b53334103edf82ad12e132ee5e23f389 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Fri, 8 Sep 2023 11:36:37 +0900 Subject: [PATCH 043/223] ci: add dispatch-push-event workflow (#803) * ci: add dispatch-push-event workflow Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * fix: change APP KEY Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * chore: use strategy Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * chore: change trigger Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * pre-commit fixes Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * Update .github/workflows/dispatch-push-event.yaml * Update .github/workflows/dispatch-push-event.yaml * style(pre-commit): autofix * Update .github/workflows/dispatch-push-event.yaml --------- Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/workflows/dispatch-push-event.yaml | 45 ++++++++++++++++++++++ 1 file changed, 45 insertions(+) create mode 100644 .github/workflows/dispatch-push-event.yaml diff --git a/.github/workflows/dispatch-push-event.yaml b/.github/workflows/dispatch-push-event.yaml new file mode 100644 index 0000000000000..492083c8038f6 --- /dev/null +++ b/.github/workflows/dispatch-push-event.yaml @@ -0,0 +1,45 @@ +name: dispatch-push-event +on: + push: + +jobs: + search-dispatch-repo: + runs-on: ubuntu-latest + strategy: + matrix: + include: + - { version: beta/v0.3.**, dispatch-repo: pilot-auto.x1.eve } + outputs: + dispatch-repo: ${{ steps.search-dispatch-repo.outputs.value }} + steps: + - name: Search dispatch repo + id: search-dispatch-repo + run: | + if [[ ${{ github.ref_name }} =~ ${{ matrix.version }} ]]; then + echo ::set-output name=value::"${{ matrix.dispatch-repo }}" + echo "Detected beta branch: ${{ github.ref_name }}" + echo "Dispatch repository: ${{ matrix.dispatch-repo }}" + fi + + dispatch-push-event: + runs-on: ubuntu-latest + needs: search-dispatch-repo + if: ${{ needs.search-dispatch-repo.outputs.dispatch-repo != '' }} + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.INTERNAL_APP_ID }} + private_key: ${{ secrets.INTERNAL_PRIVATE_KEY }} + + # 注意: workflow_dispatchで指定するブランチはmain固定となっているため、dispatch-repoのmainブランチにupdate-beta-branch.yamlが存在することが前提条件。 + - name: Dispatch the update-beta-branch workflow + run: | + curl -L \ + -X POST \ + -H "Accept: application/vnd.github+json" \ + -H "Authorization: Bearer ${{ steps.generate-token.outputs.token }}" \ + -H "X-GitHub-Api-Version: 2022-11-28" \ + https://api.github.com/repos/tier4/${{ needs.search-dispatch-repo.outputs.dispatch-repo }}/actions/workflows/update-beta-branch.yaml/dispatches \ + -d '{"ref":"main"}' From 81a3c6d9f4147ef1413430e7002e66c54916f81b Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 12 Sep 2023 15:23:39 +0900 Subject: [PATCH 044/223] chore: update sync upstream script (#792) * chore: update sync upstream script Signed-off-by: tomoya.kimura * style(pre-commit): autofix --------- Signed-off-by: tomoya.kimura Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/workflows/sync-upstream.yaml | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index 267fe2135a627..90420ec404042 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -1,9 +1,12 @@ name: sync-upstream on: - schedule: - - cron: 0 1 * * 1-5 workflow_dispatch: + inputs: + target_branch: + description: Target branch + required: true + type: string jobs: sync-upstream: @@ -28,12 +31,17 @@ jobs: script: | const holiday_jp = require(`${process.env.GITHUB_WORKSPACE}/node_modules/@holiday-jp/holiday_jp`) core.setOutput('holiday', holiday_jp.isHoliday(new Date())); + - name: Print warning for invalid branch name + if: ${{ inputs.target_branch == 'tier4/main' }} + run: | + echo This action cannot be performed on 'tier4/main' branch + - name: Run sync-branches + if: ${{ inputs.target_branch != 'tier4/main' }} uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name == 'workflow_dispatch' }} with: token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/main + base-branch: ${{ inputs.target_branch }} sync-pr-branch: sync-upstream sync-target-repository: https://github.com/autowarefoundation/autoware.universe.git sync-target-branch: main From 18b27a241e73729308989aa18d6e5942dac21daf Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 12 Sep 2023 15:23:50 +0900 Subject: [PATCH 045/223] chore: add workflow to merge beta branch to tier4 main (#811) * chore: add workflow to merge beta branch to tier4 main Signed-off-by: tomoya.kimura * fix: fix variable name Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../workflows/beta-to-tier4-main-sync.yaml | 34 +++++++++++++++++++ 1 file changed, 34 insertions(+) create mode 100644 .github/workflows/beta-to-tier4-main-sync.yaml diff --git a/.github/workflows/beta-to-tier4-main-sync.yaml b/.github/workflows/beta-to-tier4-main-sync.yaml new file mode 100644 index 0000000000000..53f40f1e811ab --- /dev/null +++ b/.github/workflows/beta-to-tier4-main-sync.yaml @@ -0,0 +1,34 @@ +name: beta-to-tier4-main-sync + +on: + workflow_dispatch: + inputs: + source_branch: + description: Source branch + required: true + type: string + +jobs: + sync-beta-branch: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/main + sync-pr-branch: beta-to-tier4-main-sync + sync-target-repository: https://github.com/tier4/autoware.universe.git + sync-target-branch: ${{ inputs.source_branch }} + pr-title: "chore: sync beta branch ${{ inputs.source_branch }} with tier4/main" + pr-labels: | + bot + sync-beta-branch + auto-merge-method: merge From 3399a5333d14f9f109d8eddfc337afca758cd413 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura Date: Thu, 14 Sep 2023 02:18:08 +0900 Subject: [PATCH 046/223] fix: camera lidar fusion launch Signed-off-by: Shunsuke Miura --- .../camera_lidar_fusion_based_detection.launch.xml | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 5f92d25022a22..eab2a56607dee 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -339,22 +339,11 @@ - - - - - - - - - - - - + From 1648a2b1979bdbdf4bad1f0fc670a899731784e2 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 14 Sep 2023 19:44:29 +0900 Subject: [PATCH 047/223] fix(resample): remove duplicated poinnt before resampling (#4965) Signed-off-by: Takamasa Horibe --- common/motion_utils/src/resample/resample.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/common/motion_utils/src/resample/resample.cpp b/common/motion_utils/src/resample/resample.cpp index 091f3405e2815..1a800a38d1051 100644 --- a/common/motion_utils/src/resample/resample.cpp +++ b/common/motion_utils/src/resample/resample.cpp @@ -109,13 +109,16 @@ std::vector resamplePointVector( } std::vector resamplePoseVector( - const std::vector & points, + const std::vector & points_raw, const std::vector & resampled_arclength, const bool use_akima_spline_for_xy, const bool use_lerp_for_z) { + // Remove overlap points for resampling + const auto points = motion_utils::removeOverlapPoints(points_raw); + // validate arguments if (!resample_utils::validate_arguments(points, resampled_arclength)) { - return points; + return points_raw; } std::vector position(points.size()); From 18427ca0cf28e8a1ff0ff2f3b49ff2f5797078b1 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 14 Sep 2023 23:04:17 +0900 Subject: [PATCH 048/223] fix(start_planner): uninitialized hysteresis_factor_expand_rate (#838) Signed-off-by: Takamasa Horibe --- .../utils/start_planner/start_planner_parameters.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 771fbd93f7196..4c095a38e7f73 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -83,7 +83,7 @@ struct StartPlannerParameters double maximum_jerk_for_stop; // hysteresis parameter - double hysteresis_factor_expand_rate; + double hysteresis_factor_expand_rate = 0.0; // path safety checker utils::path_safety_checker::EgoPredictedPathParams ego_predicted_path_params; From 226611067153f4ba48731d74196eab046f05e290 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 28 Sep 2023 14:20:28 +0900 Subject: [PATCH 049/223] fix(autoware_auto_tf2): remove tf2 geometry function duplicated in tf2 geometry msgs (#5089) (#887) Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- common/autoware_auto_geometry/CMakeLists.txt | 6 --- common/autoware_auto_tf2/CMakeLists.txt | 5 -- .../tf2_autoware_auto_msgs.hpp | 51 ------------------- planning/behavior_path_planner/CMakeLists.txt | 6 --- .../surround_obstacle_checker/CMakeLists.txt | 6 --- 5 files changed, 74 deletions(-) diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt index bf48e8fcaca3f..454e0e7ef044f 100644 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ b/common/autoware_auto_geometry/CMakeLists.txt @@ -12,12 +12,6 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/bounding_box.cpp ) -if(tf2_geometry_msgs_VERSION VERSION_LESS 0.25.4) - target_compile_definitions(${PROJECT_NAME} PRIVATE - DEFINE_LEGACY_FUNCTION - ) -endif() - if(BUILD_TESTING) set(GEOMETRY_GTEST geometry_gtest) set(GEOMETRY_SRC test/src/test_geometry.cpp diff --git a/common/autoware_auto_tf2/CMakeLists.txt b/common/autoware_auto_tf2/CMakeLists.txt index fe4cec1c0fc89..a8ae9ec2d962e 100755 --- a/common/autoware_auto_tf2/CMakeLists.txt +++ b/common/autoware_auto_tf2/CMakeLists.txt @@ -17,11 +17,6 @@ if(BUILD_TESTING) "tf2_geometry_msgs" "tf2_ros" ) - if(tf2_geometry_msgs_VERSION VERSION_LESS 0.25.4) - target_compile_definitions(test_tf2_autoware_auto_msgs PRIVATE - DEFINE_LEGACY_FUNCTION - ) - endif() endif() ament_auto_package() diff --git a/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp b/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp index ee8d52fa402c0..b35eb6e93ce6e 100644 --- a/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp +++ b/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp @@ -45,57 +45,6 @@ using BoundingBox = autoware_auto_perception_msgs::msg::BoundingBox; namespace tf2 { -#ifdef DEFINE_LEGACY_FUNCTION -/*************/ -/** Point32 **/ -/*************/ - -/** \brief Apply a geometry_msgs TransformStamped to a geometry_msgs Point32 type. - * This function is a specialization of the doTransform template defined in tf2/convert.h. - * \param t_in The point to transform, as a Point32 message. - * \param t_out The transformed point, as a Point32 message. - * \param transform The timestamped transform to apply, as a TransformStamped message. - */ -template <> -inline void doTransform( - const geometry_msgs::msg::Point32 & t_in, geometry_msgs::msg::Point32 & t_out, - const geometry_msgs::msg::TransformStamped & transform) -{ - const KDL::Vector v_out = gmTransformToKDL(transform) * KDL::Vector(t_in.x, t_in.y, t_in.z); - t_out.x = static_cast(v_out[0]); - t_out.y = static_cast(v_out[1]); - t_out.z = static_cast(v_out[2]); -} - -/*************/ -/** Polygon **/ -/*************/ - -/** \brief Apply a geometry_msgs TransformStamped to a geometry_msgs Polygon type. - * This function is a specialization of the doTransform template defined in tf2/convert.h. - * \param t_in The polygon to transform. - * \param t_out The transformed polygon. - * \param transform The timestamped transform to apply, as a TransformStamped message. - */ -template <> -inline void doTransform( - const geometry_msgs::msg::Polygon & t_in, geometry_msgs::msg::Polygon & t_out, - const geometry_msgs::msg::TransformStamped & transform) -{ - // Don't call the Point32 doTransform to avoid doing this conversion every time - const auto kdl_frame = gmTransformToKDL(transform); - // We don't use std::back_inserter to allow aliasing between t_in and t_out - t_out.points.resize(t_in.points.size()); - for (size_t i = 0; i < t_in.points.size(); ++i) { - const KDL::Vector v_out = - kdl_frame * KDL::Vector(t_in.points[i].x, t_in.points[i].y, t_in.points[i].z); - t_out.points[i].x = static_cast(v_out[0]); - t_out.points[i].y = static_cast(v_out[1]); - t_out.points[i].z = static_cast(v_out[2]); - } -} -#endif - /******************/ /** Quaternion32 **/ /******************/ diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 542d4daa0c676..f62e418371401 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -58,12 +58,6 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/marker_utils/lane_change/debug.cpp ) -if(tf2_geometry_msgs_VERSION VERSION_LESS 0.25.4) - target_compile_definitions(behavior_path_planner_node PRIVATE - DEFINE_LEGACY_FUNCTION - ) -endif() - target_include_directories(behavior_path_planner_node SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIR} ) diff --git a/planning/surround_obstacle_checker/CMakeLists.txt b/planning/surround_obstacle_checker/CMakeLists.txt index 694bddf421486..0d7b636646783 100644 --- a/planning/surround_obstacle_checker/CMakeLists.txt +++ b/planning/surround_obstacle_checker/CMakeLists.txt @@ -18,12 +18,6 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/node.cpp ) -if(tf2_geometry_msgs_VERSION VERSION_LESS 0.25.4) - target_compile_definitions(${PROJECT_NAME} PRIVATE - DEFINE_LEGACY_FUNCTION - ) -endif() - target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} ) From 533127c66518905ea3f0948e2cf1def43d295e91 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 16:11:12 +0300 Subject: [PATCH 050/223] fix(lidar_centerpoint): add arg data_path, update model path (#5162) Signed-off-by: Alexey Panferov --- .../centerpoint_vs_centerpoint-tiny.launch.xml | 5 +++-- .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 3 ++- .../launch/single_inference_lidar_centerpoint.launch.xml | 3 ++- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/perception/lidar_centerpoint/launch/centerpoint_vs_centerpoint-tiny/centerpoint_vs_centerpoint-tiny.launch.xml b/perception/lidar_centerpoint/launch/centerpoint_vs_centerpoint-tiny/centerpoint_vs_centerpoint-tiny.launch.xml index 13fd386238eda..b9c056cfb5686 100644 --- a/perception/lidar_centerpoint/launch/centerpoint_vs_centerpoint-tiny/centerpoint_vs_centerpoint-tiny.launch.xml +++ b/perception/lidar_centerpoint/launch/centerpoint_vs_centerpoint-tiny/centerpoint_vs_centerpoint-tiny.launch.xml @@ -5,6 +5,7 @@ + @@ -21,7 +22,7 @@ - + @@ -35,7 +36,7 @@ - + diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index d552cb702b980..a7f181ab78ac6 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -2,8 +2,9 @@ + - + diff --git a/perception/lidar_centerpoint/launch/single_inference_lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/single_inference_lidar_centerpoint.launch.xml index 0f6923d5e6414..491abfbad7764 100644 --- a/perception/lidar_centerpoint/launch/single_inference_lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/single_inference_lidar_centerpoint.launch.xml @@ -1,7 +1,8 @@ + - + From 0810eb71f2dd6da8d77ffb2b6eb89211a349e7b6 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 16:30:47 +0300 Subject: [PATCH 051/223] feat(perception_launch): add data_path arg to perception launch (#5069) * feat(perception_launch): add var data_path to perception.launch Signed-off-by: Alexey Panferov * feat(perception_launch): update default center_point_model_path Signed-off-by: Alexey Panferov --------- Signed-off-by: Alexey Panferov --- .../detection/lidar_based_detection.launch.xml | 2 +- .../tier4_perception_launch/launch/perception.launch.xml | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 23e0297dc5e44..3b6b9ba652a24 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 36d43bab74894..b0219376e9625 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -25,11 +25,12 @@ - + + @@ -78,11 +79,11 @@ - + Date: Thu, 28 Sep 2023 15:11:27 +0300 Subject: [PATCH 052/223] fix(traffic_light_fine_detector): add data_path arg and update default model path (#5118) * fix(traffic_light_fine_detector): add data_path arg and update default model path Signed-off-by: Alexey Panferov * fix(traffic_light_fine_detector): update README with data path arg Signed-off-by: Alexey Panferov * style(pre-commit): autofix --------- Signed-off-by: Alexey Panferov Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/traffic_light_fine_detector/README.md | 13 +++++++------ .../launch/traffic_light_fine_detector.launch.xml | 5 +++-- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/perception/traffic_light_fine_detector/README.md b/perception/traffic_light_fine_detector/README.md index 1ed6debfeae91..dcc89c76387c6 100644 --- a/perception/traffic_light_fine_detector/README.md +++ b/perception/traffic_light_fine_detector/README.md @@ -50,12 +50,13 @@ Based on the camera image and the global ROI array detected by `map_based_detect ### Node Parameters -| Name | Type | Default Value | Description | -| -------------------------- | ------ | ------------- | ------------------------------------------------------------------ | -| `fine_detector_model_path` | string | "" | The onnx file name for yolo model | -| `fine_detector_label_path` | string | "" | The label file with label names for detected objects written on it | -| `fine_detector_precision` | string | "fp32" | The inference mode: "fp32", "fp16" | -| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | +| Name | Type | Default Value | Description | +| -------------------------- | ------ | --------------------------- | ------------------------------------------------------------------ | +| `data_path` | string | "$(env HOME)/autoware_data" | packages data and artifacts directory path | +| `fine_detector_model_path` | string | "" | The onnx file name for yolo model | +| `fine_detector_label_path` | string | "" | The label file with label names for detected objects written on it | +| `fine_detector_precision` | string | "fp32" | The inference mode: "fp32", "fp16" | +| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | ## Assumptions / Known limits diff --git a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml index 5ce7840c28fd6..6e32d3410c260 100644 --- a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml +++ b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml @@ -1,6 +1,7 @@ - - + + + From 5fffdbd5fa8fa5f64bfc10f3a99b70baffd9663c Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 15:52:00 +0300 Subject: [PATCH 053/223] fix(tensorrt_yolox): add data_path arg and update default model path (#5119) * fix(tensorrt_yolox): add data_path arg and update default model path Signed-off-by: Alexey Panferov * fix(tensorrt_yolox): update README Signed-off-by: Alexey Panferov --------- Signed-off-by: Alexey Panferov --- perception/tensorrt_yolox/README.md | 4 ++-- perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml | 3 ++- perception/tensorrt_yolox/launch/yolox_tiny.launch.xml | 3 ++- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/perception/tensorrt_yolox/README.md b/perception/tensorrt_yolox/README.md index 3c253a0b68489..ca407b1ff6811 100644 --- a/perception/tensorrt_yolox/README.md +++ b/perception/tensorrt_yolox/README.md @@ -71,7 +71,7 @@ those are labeled as `UNKNOWN`, while detected rectangles are drawn in the visua ## Onnx model -A sample model (named `yolox-tiny.onnx`) is downloaded automatically during the build process. +A sample model (named `yolox-tiny.onnx`) is downloaded by ansible script on env preparation stage, if not, please, follow [Manual downloading of artifacts](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts). To accelerate Non-maximum-suppression (NMS), which is one of the common post-process after object detection inference, `EfficientNMS_TRT` module is attached after the ordinal YOLOX (tiny) network. The `EfficientNMS_TRT` module contains fixed values for `score_threshold` and `nms_threshold` in it, @@ -146,7 +146,7 @@ Please refer [the official document](https://github.com/Megvii-BaseDetection/YOL ## Label file -A sample label file (named `label.txt`)is also downloaded automatically during the build process +A sample label file (named `label.txt`)is also downloaded automatically during env preparation process (**NOTE:** This file is incompatible with models that output labels for the COCO dataset (e.g., models from the official YOLOX repository)). This file represents the correspondence between class index (integer outputted from YOLOX network) and diff --git a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml index cb89f5829c65d..3f8d7897ab5d3 100644 --- a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml +++ b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -4,7 +4,8 @@ - + + diff --git a/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml index d8c67e39e0b8a..2f08031ea159f 100644 --- a/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml +++ b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml @@ -3,7 +3,8 @@ - + + From 7822596b1361a6c09a3e4ad2a367366ce0c2e275 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 15:13:18 +0300 Subject: [PATCH 054/223] fix(traffic_light_ssd_fine_detector): add arg data_path, update model file path (#5141) * fix(traffic_light_ssd_fine_detector): add arg data_path, update model file path Signed-off-by: Alexey Panferov * fix(traffic_light_ssd_fine_detector): update README with data_path arg Signed-off-by: Alexey Panferov * style(pre-commit): autofix --------- Signed-off-by: Alexey Panferov Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_ssd_fine_detector/README.md | 19 ++++++++++--------- ...traffic_light_ssd_fine_detector.launch.xml | 5 +++-- 2 files changed, 13 insertions(+), 11 deletions(-) diff --git a/perception/traffic_light_ssd_fine_detector/README.md b/perception/traffic_light_ssd_fine_detector/README.md index 1dd05665709f5..4dbda8421d85d 100644 --- a/perception/traffic_light_ssd_fine_detector/README.md +++ b/perception/traffic_light_ssd_fine_detector/README.md @@ -122,15 +122,16 @@ Based on the camera image and the global ROI array detected by `map_based_detect ### Node Parameters -| Name | Type | Default Value | Description | -| ------------------ | ------ | ------------------------------ | -------------------------------------------------------------------- | -| `onnx_file` | string | "./data/mb2-ssd-lite-tlr.onnx" | The onnx file name for yolo model | -| `label_file` | string | "./data/voc_labels_tl.txt" | The label file with label names for detected objects written on it | -| `dnn_header_type` | string | "pytorch" | Name of DNN trained toolbox: "pytorch" or "mmdetection" | -| `mode` | string | "FP32" | The inference mode: "FP32", "FP16", "INT8" | -| `max_batch_size` | int | 8 | The size of the batch processed at one time by inference by TensorRT | -| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | -| `build_only` | bool | false | shutdown node after TensorRT engine file is built | +| Name | Type | Default Value | Description | +| ------------------ | ------ | ------------------------------------------------------------------------ | -------------------------------------------------------------------- | +| `data_path` | string | "$(env HOME)/autoware_data" | packages data and artifacts directory path | +| `onnx_file` | string | "$(var data_path)/traffic_light_ssd_fine_detector/mb2-ssd-lite-tlr.onnx" | The onnx file name for yolo model | +| `label_file` | string | "$(var data_path)/traffic_light_ssd_fine_detector/voc_labels_tl.txt" | The label file with label names for detected objects written on it | +| `dnn_header_type` | string | "pytorch" | Name of DNN trained toolbox: "pytorch" or "mmdetection" | +| `mode` | string | "FP32" | The inference mode: "FP32", "FP16", "INT8" | +| `max_batch_size` | int | 8 | The size of the batch processed at one time by inference by TensorRT | +| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | +| `build_only` | bool | false | shutdown node after TensorRT engine file is built | ## Assumptions / Known limits diff --git a/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml b/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml index a4d61b774652a..714c4d288b603 100644 --- a/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml +++ b/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml @@ -1,6 +1,7 @@ - - + + + From 55de0b46a0989053a0278e0271867c7287142d64 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 15:15:11 +0300 Subject: [PATCH 055/223] fix(traffic_light_classifier): add arg data_path, update model path (#5144) * fix(traffic_light_classfier): add arg data_path, update model path Signed-off-by: Alexey Panferov * fix(traffic_light_classifier): add arg data_path, update model path Signed-off-by: Alexey Panferov * fix(traffic_light_classifier): add arg data_path to README Signed-off-by: Alexey Panferov --------- Signed-off-by: Alexey Panferov --- perception/traffic_light_classifier/README.md | 1 + .../launch/traffic_light_classifier.launch.xml | 5 +++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/perception/traffic_light_classifier/README.md b/perception/traffic_light_classifier/README.md index 3d15af0cf7805..7df0c5466695b 100644 --- a/perception/traffic_light_classifier/README.md +++ b/perception/traffic_light_classifier/README.md @@ -55,6 +55,7 @@ These colors and shapes are assigned to the message as follows: | Name | Type | Description | | ----------------- | ---- | ------------------------------------------- | | `classifier_type` | int | if the value is `1`, cnn_classifier is used | +| `data_path` | str | packages data and artifacts directory path | ### Core Parameters diff --git a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml index d4794443d95d9..10aa04cc585af 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -2,8 +2,9 @@ - - + + + From 3f48f10de2fa81f09e47e7e82e5f97f1cc0e2ae4 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 15:16:16 +0300 Subject: [PATCH 056/223] fix(tensorrt yolo): update model path (#5158) * fix(tensorrt_yolo): add arg data_path, update onnx_file Signed-off-by: Alexey Panferov * fix(tensorrt_yolo): update model downloading in README, add data_path Signed-off-by: Alexey Panferov --------- Signed-off-by: Alexey Panferov --- perception/tensorrt_yolo/README.md | 3 ++- perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml | 9 +++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/perception/tensorrt_yolo/README.md b/perception/tensorrt_yolo/README.md index afa9209c43bb2..58d4af0dfa83d 100644 --- a/perception/tensorrt_yolo/README.md +++ b/perception/tensorrt_yolo/README.md @@ -55,6 +55,7 @@ Jocher, G., et al. (2021). ultralytics/yolov5: v6.0 - YOLOv5n 'Nano' models, Rob | Name | Type | Default Value | Description | | ----------------------- | ------ | ------------- | ------------------------------------------------------------------ | +| `data_path` | string | "" | Packages data and artifacts directory path | | `onnx_file` | string | "" | The onnx file name for yolo model | | `engine_file` | string | "" | The tensorrt engine file name for yolo model | | `label_file` | string | "" | The label file with label names for detected objects written on it | @@ -71,7 +72,7 @@ This package includes multiple licenses. All YOLO ONNX models are converted from the officially trained model. If you need information about training datasets and conditions, please refer to the official repositories. -All models are downloaded automatically when building. When launching the node with a model for the first time, the model is automatically converted to TensorRT, although this may take some time. +All models are downloaded during env preparation by ansible (as mention in [installation](https://autowarefoundation.github.io/autoware-documentation/main/installation/autoware/source-installation/)). It is also possible to download them manually, see [Manual downloading of artifacts](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts) . When launching the node with a model for the first time, the model is automatically converted to TensorRT, although this may take some time. ### YOLOv3 diff --git a/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml b/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml index a548939f2cebe..b2656de0ab72e 100755 --- a/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml +++ b/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml @@ -3,7 +3,8 @@ - + + @@ -11,11 +12,11 @@ - + - + - + From b77a29f01df88d65fe5b14de74fc51f019a7e88a Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 28 Sep 2023 15:17:48 +0300 Subject: [PATCH 057/223] fix(image_projection_based_fusion): add arg data_path, update model_path (#5163) Signed-off-by: Alexey Panferov --- .../launch/pointpainting_fusion.launch.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index e6275a2ee83c7..8e79e21db40e3 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -18,8 +18,9 @@ + - + From d5af0afc255602e01990a59f12384eff49f4deb0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 11:06:01 +0900 Subject: [PATCH 058/223] refactor(motion_velocity_smoother): align processing time topic name (#5273) Signed-off-by: satoshi-ota --- .../src/motion_velocity_smoother_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 75c84d3c482f6..6b5da01b9cb09 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -79,7 +79,7 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions debug_closest_acc_ = create_publisher("~/closest_acceleration", 1); debug_closest_jerk_ = create_publisher("~/closest_jerk", 1); debug_closest_max_velocity_ = create_publisher("~/closest_max_velocity", 1); - debug_calculation_time_ = create_publisher("~/calculation_time", 1); + debug_calculation_time_ = create_publisher("~/debug/processing_time_ms", 1); pub_trajectory_raw_ = create_publisher("~/debug/trajectory_raw", 1); pub_trajectory_vel_lim_ = create_publisher("~/debug/trajectory_external_velocity_limited", 1); From 4ab73742a1d630218c749ecf4a18f0bce125f603 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 12:54:03 +0900 Subject: [PATCH 059/223] refactor(path_smoother, obstacle_avoidance_planner): output processing time topic (#5274) * refactor(path_smoother): output processing time topic Signed-off-by: satoshi-ota * refactor(obstacle_avoidance_planner): output processing time topic Signed-off-by: satoshi-ota * Update planning/path_smoother/src/elastic_band_smoother.cpp Co-authored-by: Takamasa Horibe * Update planning/path_smoother/src/elastic_band_smoother.cpp Co-authored-by: Takamasa Horibe * Update planning/obstacle_avoidance_planner/src/node.cpp Co-authored-by: Takamasa Horibe * Update planning/obstacle_avoidance_planner/src/node.cpp Co-authored-by: Takamasa Horibe --------- Signed-off-by: satoshi-ota Co-authored-by: Takamasa Horibe --- .../common_structs.hpp | 11 ++++++++++- .../include/obstacle_avoidance_planner/node.hpp | 3 ++- .../obstacle_avoidance_planner/type_alias.hpp | 2 ++ planning/obstacle_avoidance_planner/src/node.cpp | 16 ++++++++++++++-- .../include/path_smoother/common_structs.hpp | 11 ++++++++++- .../path_smoother/elastic_band_smoother.hpp | 3 ++- .../include/path_smoother/type_alias.hpp | 2 ++ .../path_smoother/src/elastic_band_smoother.cpp | 16 ++++++++++++++-- 8 files changed, 56 insertions(+), 8 deletions(-) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp index d0fc995da0ef4..4f4f01bf1ec9f 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp @@ -45,7 +45,11 @@ struct PlannerData struct TimeKeeper { - void init() { accumulated_msg = "\n"; } + void init() + { + accumulated_msg = "\n"; + accumulated_time = 0.0; + } template TimeKeeper & operator<<(const T & msg) @@ -71,6 +75,7 @@ struct TimeKeeper { const double elapsed_time = stop_watch_.toc(func_name); *this << white_spaces << func_name << ":= " << elapsed_time << " [ms]"; + accumulated_time = elapsed_time; endLine(); } @@ -80,6 +85,10 @@ struct TimeKeeper std::string accumulated_msg = "\n"; std::stringstream latest_stream; + double getAccumulatedTime() const { return accumulated_time; } + + double accumulated_time{0.0}; + tier4_autoware_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index d6f49afad4391..9207277d0bc98 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -90,7 +90,8 @@ class ObstacleAvoidancePlanner : public rclcpp::Node // debug publisher rclcpp::Publisher::SharedPtr debug_extended_traj_pub_; rclcpp::Publisher::SharedPtr debug_markers_pub_; - rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_str_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_float_pub_; // parameter callback rcl_interfaces::msg::SetParametersResult onParam( diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/type_alias.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/type_alias.hpp index 0f45e1223551f..b02d2232a4aa1 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/type_alias.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/type_alias.hpp @@ -24,6 +24,7 @@ #include "geometry_msgs/msg/twist.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" +#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_debug_msgs/msg/string_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" @@ -42,6 +43,7 @@ using nav_msgs::msg::Odometry; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; // debug +using tier4_debug_msgs::msg::Float64Stamped; using tier4_debug_msgs::msg::StringStamped; } // namespace obstacle_avoidance_planner diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 9cee933a1c9a7..da31c7f469555 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -45,6 +45,14 @@ StringStamped createStringStamped(const rclcpp::Time & now, const std::string & return msg; } +Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data) +{ + Float64Stamped msg; + msg.stamp = now; + msg.data = data; + return msg; +} + void setZeroVelocityAfterStopPoint(std::vector & traj_points) { const auto opt_zero_vel_idx = motion_utils::searchZeroVelocityIndex(traj_points); @@ -92,7 +100,9 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); debug_markers_pub_ = create_publisher("~/debug/marker", 1); - debug_calculation_time_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_calculation_time_str_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_calculation_time_float_pub_ = + create_publisher("~/debug/processing_time_ms", 1); { // parameters // parameter for option @@ -253,7 +263,9 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) // publish calculation_time // NOTE: This function must be called after measuring onPath calculation time const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog()); - debug_calculation_time_pub_->publish(calculation_time_msg); + debug_calculation_time_str_pub_->publish(calculation_time_msg); + debug_calculation_time_float_pub_->publish( + createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); diff --git a/planning/path_smoother/include/path_smoother/common_structs.hpp b/planning/path_smoother/include/path_smoother/common_structs.hpp index a14c42ed056af..d44c964cf634c 100644 --- a/planning/path_smoother/include/path_smoother/common_structs.hpp +++ b/planning/path_smoother/include/path_smoother/common_structs.hpp @@ -44,7 +44,11 @@ struct PlannerData struct TimeKeeper { - void init() { accumulated_msg = "\n"; } + void init() + { + accumulated_msg = "\n"; + accumulated_time = 0.0; + } template TimeKeeper & operator<<(const T & msg) @@ -66,6 +70,7 @@ struct TimeKeeper { const double elapsed_time = stop_watch_.toc(func_name); *this << white_spaces << func_name << ":= " << elapsed_time << " [ms]"; + accumulated_time = elapsed_time; endLine(); } @@ -74,6 +79,10 @@ struct TimeKeeper std::string accumulated_msg = "\n"; std::stringstream latest_stream; + double getAccumulatedTime() const { return accumulated_time; } + + double accumulated_time{0.0}; + tier4_autoware_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index a67983393681f..217a138084310 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -82,7 +82,8 @@ class ElasticBandSmoother : public rclcpp::Node // debug publisher rclcpp::Publisher::SharedPtr debug_extended_traj_pub_; - rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_str_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_float_pub_; // parameter callback rcl_interfaces::msg::SetParametersResult onParam( diff --git a/planning/path_smoother/include/path_smoother/type_alias.hpp b/planning/path_smoother/include/path_smoother/type_alias.hpp index 75bf1cff20857..c8f6d6da98dcd 100644 --- a/planning/path_smoother/include/path_smoother/type_alias.hpp +++ b/planning/path_smoother/include/path_smoother/type_alias.hpp @@ -22,6 +22,7 @@ #include "geometry_msgs/msg/point.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" +#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_debug_msgs/msg/string_stamped.hpp" namespace path_smoother @@ -36,6 +37,7 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint; // navigation using nav_msgs::msg::Odometry; // debug +using tier4_debug_msgs::msg::Float64Stamped; using tier4_debug_msgs::msg::StringStamped; } // namespace path_smoother diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp index cd314b7b141bf..923b753e83ac6 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -43,6 +43,14 @@ StringStamped createStringStamped(const rclcpp::Time & now, const std::string & return msg; } +Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data) +{ + Float64Stamped msg; + msg.stamp = now; + msg.data = data; + return msg; +} + void setZeroVelocityAfterStopPoint(std::vector & traj_points) { const auto opt_zero_vel_idx = motion_utils::searchZeroVelocityIndex(traj_points); @@ -75,7 +83,9 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); - debug_calculation_time_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_calculation_time_str_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_calculation_time_float_pub_ = + create_publisher("~/debug/processing_time_ms", 1); { // parameters // parameters for ego nearest search @@ -205,7 +215,9 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) // publish calculation_time // NOTE: This function must be called after measuring onPath calculation time const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog()); - debug_calculation_time_pub_->publish(calculation_time_msg); + debug_calculation_time_str_pub_->publish(calculation_time_msg); + debug_calculation_time_float_pub_->publish( + createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); From 0a48be46df3552456483e8b9eb6bbdc6f1164a97 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 12:41:28 +0900 Subject: [PATCH 060/223] feat(planning_validator): output processing time (#5276) Signed-off-by: satoshi-ota --- .../planning_validator/planning_validator.hpp | 8 ++++++++ .../planning_validator/src/planning_validator.cpp | 12 ++++++++++++ 2 files changed, 20 insertions(+) diff --git a/planning/planning_validator/include/planning_validator/planning_validator.hpp b/planning/planning_validator/include/planning_validator/planning_validator.hpp index 3b09ebe51ff6b..ef570b57773bb 100644 --- a/planning/planning_validator/include/planning_validator/planning_validator.hpp +++ b/planning/planning_validator/include/planning_validator/planning_validator.hpp @@ -18,6 +18,7 @@ #include "planning_validator/debug_marker.hpp" #include "planning_validator/msg/planning_validator_status.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -26,6 +27,7 @@ #include #include #include +#include #include #include @@ -38,6 +40,8 @@ using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using nav_msgs::msg::Odometry; using planning_validator::msg::PlanningValidatorStatus; +using tier4_autoware_utils::StopWatch; +using tier4_debug_msgs::msg::Float64Stamped; struct ValidationParams { @@ -81,6 +85,7 @@ class PlanningValidator : public rclcpp::Node void validate(const Trajectory & trajectory); + void publishProcessingTime(const double processing_time_ms); void publishTrajectory(); void publishDebugInfo(); void displayStatus(); @@ -91,6 +96,7 @@ class PlanningValidator : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_traj_; rclcpp::Publisher::SharedPtr pub_traj_; rclcpp::Publisher::SharedPtr pub_status_; + rclcpp::Publisher::SharedPtr pub_processing_time_ms_; rclcpp::Publisher::SharedPtr pub_markers_; // system parameters @@ -120,6 +126,8 @@ class PlanningValidator : public rclcpp::Node std::shared_ptr debug_pose_publisher_; std::unique_ptr logger_configure_; + + StopWatch stop_watch_; }; } // namespace planning_validator diff --git a/planning/planning_validator/src/planning_validator.cpp b/planning/planning_validator/src/planning_validator.cpp index 13a63a7e7d4ed..875781d47b25d 100644 --- a/planning/planning_validator/src/planning_validator.cpp +++ b/planning/planning_validator/src/planning_validator.cpp @@ -41,6 +41,7 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options) pub_traj_ = create_publisher("~/output/trajectory", 1); pub_status_ = create_publisher("~/output/validation_status", 1); pub_markers_ = create_publisher("~/output/markers", 1); + pub_processing_time_ms_ = create_publisher("~/debug/processing_time_ms", 1); debug_pose_publisher_ = std::make_shared(this); @@ -167,6 +168,8 @@ bool PlanningValidator::isDataReady() void PlanningValidator::onTrajectory(const Trajectory::ConstSharedPtr msg) { + stop_watch_.tic(__func__); + current_trajectory_ = msg; if (!isDataReady()) return; @@ -180,6 +183,7 @@ void PlanningValidator::onTrajectory(const Trajectory::ConstSharedPtr msg) publishTrajectory(); // for debug + publishProcessingTime(stop_watch_.toc(__func__)); publishDebugInfo(); displayStatus(); } @@ -222,6 +226,14 @@ void PlanningValidator::publishTrajectory() return; } +void PlanningValidator::publishProcessingTime(const double processing_time_ms) +{ + Float64Stamped msg{}; + msg.stamp = this->now(); + msg.data = processing_time_ms; + pub_processing_time_ms_->publish(msg); +} + void PlanningValidator::publishDebugInfo() { validation_status_.stamp = get_clock()->now(); From 47682f673a620e6924618128abedbbf4bcd2f449 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 12:52:29 +0900 Subject: [PATCH 061/223] feat(obstacle_stop_planner): output processing time (#5279) Signed-off-by: satoshi-ota --- .../include/obstacle_stop_planner/node.hpp | 8 ++++++++ planning/obstacle_stop_planner/src/node.cpp | 9 +++++++++ 2 files changed, 17 insertions(+) diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp index 93a9736bcdb36..368ad34b9c4e2 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp @@ -19,6 +19,7 @@ #include "obstacle_stop_planner/debug_marker.hpp" #include "obstacle_stop_planner/planner_data.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" #include #include @@ -37,6 +38,7 @@ #include #include #include +#include #include #include #include @@ -78,9 +80,11 @@ using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; +using tier4_autoware_utils::StopWatch; using tier4_debug_msgs::msg::BoolStamped; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Float32Stamped; +using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::ExpandStopRange; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; @@ -143,6 +147,8 @@ class ObstacleStopPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_collision_pointcloud_debug_; + rclcpp::Publisher::SharedPtr pub_processing_time_ms_; + std::unique_ptr acc_controller_; std::shared_ptr debug_ptr_; boost::optional latest_slow_down_section_{boost::none}; @@ -166,6 +172,8 @@ class ObstacleStopPlannerNode : public rclcpp::Node StopParam stop_param_; SlowDownParam slow_down_param_; + StopWatch stop_watch_; + // mutex for vehicle_info_, stop_param_, current_acc_, obstacle_ros_pointcloud_ptr_ // NOTE: shared_ptr itself is thread safe so we do not have to care if *ptr is not used // (current_velocity_ptr_) diff --git a/planning/obstacle_stop_planner/src/node.cpp b/planning/obstacle_stop_planner/src/node.cpp index 4e4b5d2f91ef3..9a9712c5a2503 100644 --- a/planning/obstacle_stop_planner/src/node.cpp +++ b/planning/obstacle_stop_planner/src/node.cpp @@ -209,6 +209,8 @@ ObstacleStopPlannerNode::ObstacleStopPlannerNode(const rclcpp::NodeOptions & nod pub_collision_pointcloud_debug_ = this->create_publisher("~/debug/collision_pointcloud", 1); + pub_processing_time_ms_ = this->create_publisher("~/debug/processing_time_ms", 1); + // Subscribers if (!node_param_.use_predicted_objects) { // No need to point cloud while using predicted objects @@ -274,6 +276,8 @@ void ObstacleStopPlannerNode::onPointCloud(const PointCloud2::ConstSharedPtr inp void ObstacleStopPlannerNode::onTrigger(const Trajectory::ConstSharedPtr input_msg) { + stop_watch_.tic(__func__); + mutex_.lock(); // NOTE: these variables must not be referenced for multithreading const auto vehicle_info = vehicle_info_; @@ -376,6 +380,11 @@ void ObstacleStopPlannerNode::onTrigger(const Trajectory::ConstSharedPtr input_m trajectory.header = input_msg->header; pub_trajectory_->publish(trajectory); + + Float64Stamped processing_time_ms; + processing_time_ms.stamp = now(); + processing_time_ms.data = stop_watch_.toc(__func__); + pub_processing_time_ms_->publish(processing_time_ms); } void ObstacleStopPlannerNode::searchObstacle( From 8de1b1371b1b20ee17d3c5c86ad770293f516c95 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 14:03:20 +0900 Subject: [PATCH 062/223] refactor(obstacle_cruise_planner): align processing time topic name (#5278) Signed-off-by: satoshi-ota --- planning/obstacle_cruise_planner/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index d50054da46237..c9fe9f2210423 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -374,7 +374,7 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & "~/output/clear_velocity_limit", rclcpp::QoS{1}.transient_local()); // debug publisher - debug_calculation_time_pub_ = create_publisher("~/debug/calculation_time", 1); + debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); debug_cruise_wall_marker_pub_ = create_publisher("~/debug/cruise/virtual_wall", 1); debug_stop_wall_marker_pub_ = create_publisher("~/virtual_wall", 1); debug_slow_down_wall_marker_pub_ = From 9a116bae63b78c2e618e8d15f83757ba5ad9d29a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Oct 2023 13:19:39 +0900 Subject: [PATCH 063/223] refactor(behavior_path_planner): align processing time topic name (#5281) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/planner_manager.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 24967608775f3..d0e55ffa574fd 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -35,7 +35,7 @@ PlannerManager::PlannerManager(rclcpp::Node & node, const bool verbose) verbose_{verbose} { processing_time_.emplace("total_time", 0.0); - debug_publisher_ptr_ = std::make_unique(&node, "behavior_planner_manager/debug"); + debug_publisher_ptr_ = std::make_unique(&node, "~/debug"); } BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & data) @@ -894,7 +894,7 @@ void PlannerManager::print() const void PlannerManager::publishProcessingTime() const { for (const auto & t : processing_time_) { - std::string name = std::string("processing_time/") + t.first; + std::string name = t.first + std::string("/processing_time_ms"); debug_publisher_ptr_->publish(name, t.second); } } From 5e32e8b48cbb3ec29f18224bb2fb36d664f89850 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 25 Oct 2023 11:39:02 +0900 Subject: [PATCH 064/223] fix(goal_planner): revert "refactor(goal_planner): rebuild state transition (#5371)" (#5399) This reverts commit 3d2a7f6038627ca52a4f0c2af6f5a8d56bc6962b. --- .../goal_planner/goal_planner_module.hpp | 19 +++--- .../goal_planner/goal_planner_module.cpp | 59 +++++++++++-------- 2 files changed, 46 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 21372ed6e2c2f..343302a022a69 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -217,28 +217,31 @@ class GoalPlannerModule : public SceneModuleInterface } } - CandidateOutput planCandidate() const override; - BehaviorModuleOutput plan() override; - BehaviorModuleOutput planWaitingApproval() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; + BehaviorModuleOutput plan() override; + BehaviorModuleOutput planWaitingApproval() override; + void processOnEntry() override; void processOnExit() override; - void updateData() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } + // not used, but need to override + CandidateOutput planCandidate() const override { return CandidateOutput{}; }; + private: - // The start_planner activates when it receives a new route, - // so there is no need to terminate the goal planner. - // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return true; } + bool canTransitIdleToRunningState() override { return false; } mutable StartGoalPlannerData goal_planner_data_; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 95ac47494d016..64504918efd0e 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -113,13 +113,6 @@ GoalPlannerModule::GoalPlannerModule( freespace_parking_timer_cb_group_); } - // Initialize safety checker - if (parameters_->safety_check_params.enable_safety_check) { - initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); - } - status_.reset(); } @@ -226,18 +219,16 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } -void GoalPlannerModule::updateData() +BehaviorModuleOutput GoalPlannerModule::run() { - // Initialize Occupancy Grid Map - // This operation requires waiting for `planner_data_`, hence it is executed here instead of in - // the constructor. Ideally, this operation should only need to be performed once. - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); + current_state_ = ModuleStatus::RUNNING; + updateOccupancyGrid(); + + if (!isActivated()) { + return planWaitingApproval(); } - updateOccupancyGrid(); + return plan(); } void GoalPlannerModule::initializeOccupancyGridMap() @@ -264,6 +255,22 @@ void GoalPlannerModule::initializeSafetyCheckParameters() objects_filtering_params_, parameters_); } +void GoalPlannerModule::processOnEntry() +{ + // Initialize occupancy grid map + if ( + parameters_->use_occupancy_grid_for_goal_search || + parameters_->use_occupancy_grid_for_path_collision_check) { + initializeOccupancyGridMap(); + } + // Initialize safety checker + if (parameters_->safety_check_params.enable_safety_check) { + initializeSafetyCheckParameters(); + utils::start_goal_planner_common::initializeCollisionCheckDebugMap( + goal_planner_data_.collision_check); + } +} + void GoalPlannerModule::processOnExit() { resetPathCandidate(); @@ -430,6 +437,13 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } +ModuleStatus GoalPlannerModule::updateState() +{ + // start_planner module will be run when setting new goal, so not need finishing pull_over module. + // Finishing it causes wrong lane_following path generation. + return current_state_; +} + bool GoalPlannerModule::planFreespacePath() { goal_searcher_->setPlannerData(planner_data_); @@ -883,12 +897,6 @@ void GoalPlannerModule::decideVelocity() status_.set_has_decided_velocity(true); } -CandidateOutput GoalPlannerModule::planCandidate() const -{ - return CandidateOutput( - status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); -} - BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { constexpr double path_update_duration = 1.0; @@ -927,7 +935,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(planCandidate().path_candidate); + path_candidate_ = std::make_shared(status_.get_pull_over_path()->getFullPath()); path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible @@ -980,7 +988,10 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = std::make_shared(planCandidate().path_candidate); + path_candidate_ = + status_.get_is_safe_static_objects() + ? std::make_shared(status_.get_pull_over_path()->getFullPath()) + : out.path; path_reference_ = getPreviousModuleOutput().reference_path; const auto distance_to_path_change = calcDistanceToPathChange(); From a1beca1746e4d1131bb4a447f156d6a39ad4bd5a Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 25 Oct 2023 14:02:10 +0900 Subject: [PATCH 065/223] fix(motion_utils): fix build error (#5404) (#982) Signed-off-by: Fumiya Watanabe --- .../motion_utils/vehicle/vehicle_state_checker.hpp | 8 ++++---- common/motion_utils/src/vehicle/vehicle_state_checker.cpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp b/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp index f5f423f881ba2..6a9bd01a5a9a0 100644 --- a/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp +++ b/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp @@ -55,11 +55,11 @@ class VehicleStopChecker : public VehicleStopCheckerBase protected: rclcpp::Subscription::SharedPtr sub_odom_; - Odometry::SharedPtr odometry_ptr_; + Odometry::ConstSharedPtr odometry_ptr_; private: static constexpr double velocity_buffer_time_sec = 10.0; - void onOdom(const Odometry::SharedPtr msg); + void onOdom(const Odometry::ConstSharedPtr msg); }; class VehicleArrivalChecker : public VehicleStopChecker @@ -74,9 +74,9 @@ class VehicleArrivalChecker : public VehicleStopChecker rclcpp::Subscription::SharedPtr sub_trajectory_; - Trajectory::SharedPtr trajectory_ptr_; + Trajectory::ConstSharedPtr trajectory_ptr_; - void onTrajectory(const Trajectory::SharedPtr msg); + void onTrajectory(const Trajectory::ConstSharedPtr msg); }; } // namespace motion_utils diff --git a/common/motion_utils/src/vehicle/vehicle_state_checker.cpp b/common/motion_utils/src/vehicle/vehicle_state_checker.cpp index 6ed9472d39e0f..194c49ae3bff8 100644 --- a/common/motion_utils/src/vehicle/vehicle_state_checker.cpp +++ b/common/motion_utils/src/vehicle/vehicle_state_checker.cpp @@ -88,7 +88,7 @@ VehicleStopChecker::VehicleStopChecker(rclcpp::Node * node) std::bind(&VehicleStopChecker::onOdom, this, _1)); } -void VehicleStopChecker::onOdom(const Odometry::SharedPtr msg) +void VehicleStopChecker::onOdom(const Odometry::ConstSharedPtr msg) { odometry_ptr_ = msg; @@ -128,7 +128,7 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati th_arrived_distance_m; } -void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) +void VehicleArrivalChecker::onTrajectory(const Trajectory::ConstSharedPtr msg) { trajectory_ptr_ = msg; } From eddf914a300db9cb09aed1f47d723bc489c56489 Mon Sep 17 00:00:00 2001 From: masaharuTakano Date: Wed, 8 Nov 2023 11:41:55 +0900 Subject: [PATCH 066/223] checkout to awf/main Signed-off-by: masaharuTakano --- .../launch/roi_cluster_fusion.launch.xml | 1 - .../goal_planner/goal_planner_module.hpp | 19 +++---- .../src/util.cpp | 53 ++++++++----------- 3 files changed, 29 insertions(+), 44 deletions(-) diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index abdd44a70d24a..60f6f943b8cda 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -29,7 +29,6 @@ - diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 0a4ba1f6ea0cb..df21bad862cc9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -223,31 +223,28 @@ class GoalPlannerModule : public SceneModuleInterface } } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override; - bool isExecutionRequested() const override; - bool isExecutionReady() const override; - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; + CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; - void processOnEntry() override; + bool isExecutionRequested() const override; + bool isExecutionReady() const override; void processOnExit() override; + void updateData() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } - // not used, but need to override - CandidateOutput planCandidate() const override { return CandidateOutput{}; }; - private: + // The start_planner activates when it receives a new route, + // so there is no need to terminate the goal planner. + // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } + bool canTransitIdleToRunningState() override { return true; } mutable StartGoalPlannerData goal_planner_data_; diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 7f76d538f0846..94bc75b805934 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -84,21 +84,16 @@ static std::optional getDuplicatedPointIdx( static std::optional insertPointIndex( const geometry_msgs::msg::Pose & in_pose, - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path) + autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, + const double ego_nearest_dist_threshold, const double ego_nearest_yaw_threshold) { const auto duplicate_idx_opt = getDuplicatedPointIdx(*inout_path, in_pose.position); if (duplicate_idx_opt) { return duplicate_idx_opt.value(); } - static constexpr double dist_thr = 10.0; - static constexpr double angle_thr = M_PI / 1.5; - const auto closest_idx_opt = - motion_utils::findNearestIndex(inout_path->points, in_pose, dist_thr, angle_thr); - if (!closest_idx_opt) { - return std::nullopt; - } - const size_t closest_idx = closest_idx_opt.get(); + const size_t closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( + inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); // vector.insert(i) inserts element on the left side of v[i] // the velocity need to be zero order hold(from prior point) int insert_idx = closest_idx; @@ -165,7 +160,7 @@ std::optional> findLaneIdsInterval( */ static std::optional getStopLineIndexFromMap( const InterpolatedPathInfo & interpolated_path_info, - const std::shared_ptr & planner_data, const double dist_thr) + const std::shared_ptr & planner_data) { const auto & path = interpolated_path_info.path; const auto & lane_interval = interpolated_path_info.lane_id_interval.value(); @@ -212,12 +207,9 @@ static std::optional getStopLineIndexFromMap( stop_point_from_map.position.y = 0.5 * (p_start.y() + p_end.y()); stop_point_from_map.position.z = 0.5 * (p_start.z() + p_end.z()); - const auto stop_idx_ip_opt = - motion_utils::findNearestIndex(path.points, stop_point_from_map, static_cast(dist_thr)); - if (!stop_idx_ip_opt) { - return std::nullopt; - } - return stop_idx_ip_opt.get(); + return motion_utils::findFirstNearestIndexWithSoftConstraints( + path.points, stop_point_from_map, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); } static std::optional getFirstPointInsidePolygonByFootprint( @@ -304,8 +296,7 @@ std::optional generateIntersectionStopLines( // (1) default stop line position on interpolated path bool default_stop_line_valid = true; int stop_idx_ip_int = -1; - if (const auto map_stop_idx_ip = - getStopLineIndexFromMap(interpolated_path_info, planner_data, 10.0); + if (const auto map_stop_idx_ip = getStopLineIndexFromMap(interpolated_path_info, planner_data); map_stop_idx_ip) { stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; } @@ -319,12 +310,9 @@ std::optional generateIntersectionStopLines( // (2) ego front stop line position on interpolated path const geometry_msgs::msg::Pose & current_pose = planner_data->current_odometry->pose; - const auto closest_idx_ip_opt = - motion_utils::findNearestIndex(path_ip.points, current_pose, 3.0, M_PI_4); - if (!closest_idx_ip_opt) { - return std::nullopt; - } - const auto closest_idx_ip = closest_idx_ip_opt.value(); + const auto closest_idx_ip = motion_utils::findFirstNearestIndexWithSoftConstraints( + path_ip.points, current_pose, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); // (3) occlusion peeking stop line position on interpolated path int occlusion_peeking_line_ip_int = static_cast(default_stop_line_ip); @@ -404,7 +392,9 @@ std::optional generateIntersectionStopLines( [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); for (const auto & [stop_idx_ip, stop_idx] : stop_lines) { const auto & insert_point = path_ip.points.at(*stop_idx_ip).point.pose; - const auto insert_idx = insertPointIndex(insert_point, original_path); + const auto insert_idx = insertPointIndex( + insert_point, original_path, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); if (!insert_idx) { return std::nullopt; } @@ -555,7 +545,9 @@ std::optional generateStuckStopLine( static_cast(stuck_stop_line_idx_ip) - 1 - stop_line_margin_idx_dist - base2front_idx_dist, 0)); const auto & insert_point = path_ip.points.at(insert_idx_ip).point.pose; - return insertPointIndex(insert_point, original_path); + return insertPointIndex( + insert_point, original_path, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); } static std::vector getPolygon3dFromLanelets( @@ -1348,13 +1340,10 @@ TimeDistanceArray calcIntersectionPassingTime( // `last_intersection_stop_line_candidate_idx` makes no sense const auto last_intersection_stop_line_candidate_point_orig = path.points.at(last_intersection_stop_line_candidate_idx).point.pose; - const auto last_intersection_stop_line_candidate_nearest_ind_opt = motion_utils::findNearestIndex( - smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, 3.0, M_PI_4); - if (!last_intersection_stop_line_candidate_nearest_ind_opt) { - return time_distance_array; - } const auto last_intersection_stop_line_candidate_nearest_ind = - last_intersection_stop_line_candidate_nearest_ind_opt.value(); + motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); for (size_t i = 1; i < smoothed_reference_path.points.size(); ++i) { const auto & p1 = smoothed_reference_path.points.at(i - 1); From 8eaa02ee0566fce834ec3eadbbe3d3e5949b3558 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Nov 2023 14:28:19 +0900 Subject: [PATCH 067/223] fix(intersection): fix wrong resample process (#5516) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_intersection_module/src/util.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 94bc75b805934..a9d0f56266181 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1459,14 +1459,14 @@ lanelet::ConstLanelet generatePathLanelet( { lanelet::Points3d lefts; lanelet::Points3d rights; + size_t prev_idx = start_idx; for (size_t i = start_idx; i <= end_idx; ++i) { const auto & p = path.points.at(i).point.pose; - if (start_idx < i && i != end_idx) { - const auto & p_prev = path.points.at(i - 1).point.pose; - if (tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { - continue; - } + const auto & p_prev = path.points.at(prev_idx).point.pose; + if (i != start_idx && tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { + continue; } + prev_idx = i; const double yaw = tf2::getYaw(p.orientation); const double x = p.position.x; const double y = p.position.y; From d595785aca975a1c437ddf12446f268d3a8aece5 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 9 Nov 2023 18:23:52 +0900 Subject: [PATCH 068/223] fix(ndt_scan_matcher): delete diagnostics thread (#5532) Signed-off-by: yamato-ando Co-authored-by: yamato-ando --- .../ndt_scan_matcher/map_update_module.hpp | 4 +- .../ndt_scan_matcher_core.hpp | 4 +- .../src/map_update_module.cpp | 4 +- .../src/ndt_scan_matcher_core.cpp | 142 ++++++++---------- 4 files changed, 68 insertions(+), 86 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 13721c03ca22e..78052cb8198a3 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -51,8 +51,7 @@ class MapUpdateModule rclcpp::Node * node, std::mutex * ndt_ptr_mutex, std::shared_ptr ndt_ptr, std::shared_ptr tf2_listener_module, std::string map_frame, - rclcpp::CallbackGroup::SharedPtr main_callback_group, - std::shared_ptr> state_ptr); + rclcpp::CallbackGroup::SharedPtr main_callback_group); private: friend class NDTScanMatcher; @@ -82,7 +81,6 @@ class MapUpdateModule rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr tf2_listener_module_; - std::shared_ptr> state_ptr_; std::optional last_update_position_ = std::nullopt; std::optional current_position_ = std::nullopt; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 9eb62230dad9e..f0d90fdfa0e08 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -132,7 +132,7 @@ class NDTScanMatcher : public rclcpp::Node const rclcpp::Time & sensor_ros_time); void add_regularization_pose(const rclcpp::Time & sensor_ros_time); - void timer_diagnostic(); + void publish_diagnostic(); rclcpp::Subscription::SharedPtr initial_pose_sub_; rclcpp::Subscription::SharedPtr sensor_points_sub_; @@ -203,8 +203,6 @@ class NDTScanMatcher : public rclcpp::Node std::mutex ndt_ptr_mtx_; std::mutex initial_pose_array_mtx_; - std::thread diagnostic_thread_; - // variables for regularization const bool regularization_enabled_; std::deque diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 7512ae2e77a21..f0a583417fb76 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -26,15 +26,13 @@ MapUpdateModule::MapUpdateModule( rclcpp::Node * node, std::mutex * ndt_ptr_mutex, std::shared_ptr ndt_ptr, std::shared_ptr tf2_listener_module, std::string map_frame, - rclcpp::CallbackGroup::SharedPtr main_callback_group, - std::shared_ptr> state_ptr) + rclcpp::CallbackGroup::SharedPtr main_callback_group) : ndt_ptr_(std::move(ndt_ptr)), ndt_ptr_mutex_(ndt_ptr_mutex), map_frame_(std::move(map_frame)), logger_(node->get_logger()), clock_(node->get_clock()), tf2_listener_module_(std::move(tf2_listener_module)), - state_ptr_(std::move(state_ptr)), dynamic_map_loading_update_distance_( node->declare_parameter("dynamic_map_loading_update_distance")), dynamic_map_loading_map_radius_( diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index cb66998147220..a2e89540a172f 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -280,16 +280,12 @@ NDTScanMatcher::NDTScanMatcher() &NDTScanMatcher::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), rclcpp::ServicesQoS().get_rmw_qos_profile(), main_callback_group); - diagnostic_thread_ = std::thread(&NDTScanMatcher::timer_diagnostic, this); - diagnostic_thread_.detach(); - tf2_listener_module_ = std::make_shared(this); use_dynamic_map_loading_ = this->declare_parameter("use_dynamic_map_loading"); if (use_dynamic_map_loading_) { map_update_module_ = std::make_unique( - this, &ndt_ptr_mtx_, ndt_ptr_, tf2_listener_module_, map_frame_, main_callback_group, - state_ptr_); + this, &ndt_ptr_mtx_, ndt_ptr_, tf2_listener_module_, map_frame_, main_callback_group); } else { map_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, main_callback_group); } @@ -297,76 +293,71 @@ NDTScanMatcher::NDTScanMatcher() logger_configure_ = std::make_unique(this); } -void NDTScanMatcher::timer_diagnostic() +void NDTScanMatcher::publish_diagnostic() { - rclcpp::Rate rate(100); - while (rclcpp::ok()) { - diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; - diag_status_msg.name = "ndt_scan_matcher"; - diag_status_msg.hardware_id = ""; - - for (const auto & key_value : (*state_ptr_)) { - diagnostic_msgs::msg::KeyValue key_value_msg; - key_value_msg.key = key_value.first; - key_value_msg.value = key_value.second; - diag_status_msg.values.push_back(key_value_msg); - } - + diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; + diag_status_msg.name = "ndt_scan_matcher"; + diag_status_msg.hardware_id = ""; + + for (const auto & key_value : (*state_ptr_)) { + diagnostic_msgs::msg::KeyValue key_value_msg; + key_value_msg.key = key_value.first; + key_value_msg.value = key_value.second; + diag_status_msg.values.push_back(key_value_msg); + } + + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diag_status_msg.message = ""; + if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "Initializing State. "; + } + if ( + state_ptr_->count("lidar_topic_delay_time_sec") && + std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > lidar_topic_timeout_sec_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; + } + if ( + state_ptr_->count("skipping_publish_num") && + std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && + std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "skipping_publish_num > 1. "; + } + if ( + state_ptr_->count("skipping_publish_num") && + std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + diag_status_msg.message += "skipping_publish_num exceed limit. "; + } + if ( + state_ptr_->count("nearest_voxel_transformation_likelihood") && + std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < + converged_param_nearest_voxel_transformation_likelihood_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "NDT score is unreliably low. "; + } + if ( + state_ptr_->count("execution_time") && + std::stod((*state_ptr_)["execution_time"]) >= critical_upper_bound_exe_time_ms_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += + "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; + } + // Ignore local optimal solution + if ( + state_ptr_->count("is_local_optimal_solution_oscillation") && + std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = ""; - if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "Initializing State. "; - } - if ( - state_ptr_->count("lidar_topic_delay_time_sec") && - std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > lidar_topic_timeout_sec_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && - std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "skipping_publish_num > 1. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - diag_status_msg.message += "skipping_publish_num exceed limit. "; - } - if ( - state_ptr_->count("nearest_voxel_transformation_likelihood") && - std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < - converged_param_nearest_voxel_transformation_likelihood_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "NDT score is unreliably low. "; - } - if ( - state_ptr_->count("execution_time") && - std::stod((*state_ptr_)["execution_time"]) >= critical_upper_bound_exe_time_ms_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += - "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; - } - // Ignore local optimal solution - if ( - state_ptr_->count("is_local_optimal_solution_oscillation") && - std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = "local optimal solution oscillation occurred"; - } - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); - diag_msg.status.push_back(diag_status_msg); + diag_status_msg.message = "local optimal solution oscillation occurred"; + } - diagnostics_pub_->publish(diag_msg); + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = this->now(); + diag_msg.status.push_back(diag_status_msg); - rate.sleep(); - } + diagnostics_pub_->publish(diag_msg); } void NDTScanMatcher::callback_initial_pose( @@ -476,13 +467,11 @@ void NDTScanMatcher::callback_sensor_points( } // perform ndt scan matching - (*state_ptr_)["state"] = "Aligning"; const Eigen::Matrix4f initial_pose_matrix = pose_to_matrix4f(interpolator.get_current_pose().pose.pose); auto output_cloud = std::make_shared>(); ndt_ptr_->align(*output_cloud, initial_pose_matrix); const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); - (*state_ptr_)["state"] = "Sleeping"; const geometry_msgs::msg::Pose result_pose_msg = matrix4f_to_pose(ndt_result.pose); std::vector transformation_msg_array; @@ -573,6 +562,7 @@ void NDTScanMatcher::callback_sensor_points( make_float32_stamped(sensor_ros_time, no_ground_nearest_voxel_transformation_likelihood)); } + (*state_ptr_)["state"] = "Aligned"; (*state_ptr_)["transform_probability"] = std::to_string(ndt_result.transform_probability); (*state_ptr_)["nearest_voxel_transformation_likelihood"] = std::to_string(ndt_result.nearest_voxel_transformation_likelihood); @@ -584,6 +574,8 @@ void NDTScanMatcher::callback_sensor_points( (*state_ptr_)["is_local_optimal_solution_oscillation"] = "0"; } (*state_ptr_)["execution_time"] = std::to_string(exe_time); + + publish_diagnostic(); } void NDTScanMatcher::transform_sensor_measurement( @@ -859,8 +851,6 @@ void NDTScanMatcher::service_trigger_node( if (is_activated_) { std::lock_guard initial_pose_array_lock(initial_pose_array_mtx_); initial_pose_msg_ptr_array_.clear(); - } else { - (*state_ptr_)["state"] = "Initializing"; } res->success = true; } @@ -897,9 +887,7 @@ void NDTScanMatcher::service_ndt_align( return; } - (*state_ptr_)["state"] = "Aligning"; res->pose_with_covariance = align_pose(initial_pose_msg_in_map_frame); - (*state_ptr_)["state"] = "Sleeping"; res->success = true; res->pose_with_covariance.pose.covariance = req->pose_with_covariance.pose.covariance; } From b607e5ca94913dffe7b24388ff79edcf62b53a51 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Nov 2023 18:17:55 +0900 Subject: [PATCH 069/223] feat(intersection): rectify initial accel/velocity profile in ego velocity profile (#5496) Signed-off-by: Mamoru Sobue --- .../README.md | 8 ++ .../config/intersection.param.yaml | 14 +-- .../docs/ttc.gif | Bin 0 -> 2467326 bytes .../scripts/ttc.py | 13 ++- .../src/util.cpp | 86 +++++++++++++----- .../src/utilization/trajectory_utils.cpp | 13 ++- 6 files changed, 94 insertions(+), 40 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/ttc.gif diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 16459bb64074b..cb65e2a3cc23c 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -86,6 +86,14 @@ The parameters `collision_detection.collision_start_margin_time` and `collision_ If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless safe judgement continues for a certain period `collision_detection.state_transit_margin` to prevent the chattering of decisions. +Currently, the intersection module uses `motion_velocity_smoother` feature to precisely calculate ego vehicle velocity profile along the intersection lane under longitudinal/lateral constraints. If the flag `collision_detection.use_upstream_velocity` is true, the target velocity profile of the original path is used. Otherwise the target velocity is set to `common.intersection_velocity`. In the trajectory smoothing process the target velocity at/before ego trajectory points are set to ego current velocity. The smoothed trajectory is then converted to an array of (time, distance) which indicates the arrival time to each trajectory point on the path from current ego position. You can visualize this array by adding the lane id to `debug.ttc` and running + +```bash +ros2 run behavior_velocity_intersection_module ttc.py --lane_id +``` + +![ego ttc profile](./docs/ttc.gif) + #### Stop Line Automatic Generation If a stopline is associated with the intersection lane on the map, that line is used as the stopline for collision detection. Otherwise the path is interpolated at a certain intervals (=`common.path_interpolation_ds`), and the point which is `stop_line_margin` meters behind the attention area is defined as the position of the stop line for the vehicle front. diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index adbc7b3e087d6..22f68733a3bc2 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -35,24 +35,24 @@ distance_thr: 1.0 # [m] collision_detection: - state_transit_margin_time: 1.0 + state_transit_margin_time: 0.5 min_predicted_path_confidence: 0.05 minimum_ego_predicted_velocity: 1.388 # [m/s] fully_prioritized: collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 partially_prioritized: - collision_start_margin_time: 2.0 + collision_start_margin_time: 3.0 collision_end_margin_time: 2.0 not_prioritized: - collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object + collision_start_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object + collision_end_margin_time: 2.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity yield_on_green_traffic_light: - distance_to_assigned_lanelet_start: 5.0 - duration: 2.0 + distance_to_assigned_lanelet_start: 10.0 + duration: 3.0 object_dist_to_stopline: 10.0 # [m] ignore_on_amber_traffic_light: object_expected_deceleration: 2.0 # [m/ss] @@ -81,7 +81,7 @@ maximum_peeking_distance: 6.0 # [m] attention_lane_crop_curvature_threshold: 0.25 attention_lane_curvature_calculation_ds: 0.5 - static_occlusion_with_traffic_light_timeout: 3.5 + static_occlusion_with_traffic_light_timeout: 0.5 debug: ttc: [0] diff --git a/planning/behavior_velocity_intersection_module/docs/ttc.gif b/planning/behavior_velocity_intersection_module/docs/ttc.gif new file mode 100644 index 0000000000000000000000000000000000000000..bb797f7df59a1ee9800ebae6f978bf1efc555ac1 GIT binary patch literal 2467326 zcmWifWmMEp7sr1a>@Kjt(jl>QrwB;M(nv{{bV-RQAt>O|OM`@9(A^*+h;&M~ARW@N z2m&Iw&;R+JId{&yn=^Orees>oXxvwqxob~DWDbr70K$Lz_mA-J=HGwu=7w)+`q z;rAxtbouP;?DX{X*RNmyPF7D&PHv8m2>4k%9)Em%OgK0o98O;x{QS4Ib-cMjI2a`C z^$@n2kB*KG4i5JA_I7r5wzs#pwzf7mH#asm2&=2x>+5T4Ybz@&gq6~Nvr~j0S%mM& zgz4zz<>jTNrNza?g@uJ5KYq;5&(F=xegFP_c6N4VW@dVNdTMHFa&nR|o;p9#H#Rml zIy(AqaFEbfL-_iY@bM$zn=7H)jL@M=_^L!`mL)Wb5gG&tbzH;4!$U(ugM)(u0|R}1 zeZ9TCU0q!r9UblM?X9h?EiEn0&CN|sO`kq}YG`PvudgT6D%9525-KYRu6lPy;BLf2iJv}`g z9UUz#Ee#C~6%`dFB_#@lqM)E4CnrZDk)))gBqSun#KZ^$0uG16U@#&gA}ACJfk41u zFbD)90Du+nf3g380(}3?LjPaI(Xk&?>Ra_v;J4rSch-TYal98hRt{^>Qah{RD0RNI2pUt@wMYh+(zPgN|DCmHbQIq@jw{1; zJ%+EibUjw6ac4bFtdDOaUUJrTBSB`XbR$vzd}kvG1LNOJR;6>>Owr^i+kCAfwY!ZH8u04LZmx(hz%QgPV0=)ZsXc{NJ#sA)69!`LF4{W%U-NlILPAJ z$yn>g7K_4)pBI{+8LcR=Yq@tp|XN_-bm`T*aJ(hw5ww!%nt_b@!FJn3V8esI!{ z-j-9zkh<>f{n)bHF+j#gUm-ChO#S!SaQCRr$6BeCYmZUczk@zw{598=tx_1CF2&m& z6=#z=(uZeL`WnK&r+?T8DQD0p1sOs-B*mz|+q_!(G-p2qm716Q@c4X=#hGj#P6$fo zUVP@bdp_&gUwHn*xtq}Nc{%VeOVes_``Ksp=W^;7i%%UBB(}jcl6M(mzW! zZ)JUKXjY4nZj{L=uw|6JpHq?cW$!~x!wapNjo{{=uAgr%9g7}jy-Y8Gbz2nOk-`zGgW3Ztuo0I1YXq2$&lyGrkZ4I3QmllOO-07M=i=J!84v~i+NYo zNF*W(5(vnNQD*82e9O4Mw~1Eb(2BsVv2h~4@szSBo8!T09~*&kA25Nv0mT?(^@T1~32MHB;*?UR+!6xdE~MG2kI+78$NGeYQDD9ZU+MAlGR zF-P8Ag0B0OPt?^9sB%ahX=lW#Cj8E%3~}H(<95LWHsZH^{6fPH57pl8iQ3|mrQ^yBB2zKx-h}h@b;R#IEeeY=bNww_H zbnLx!8%cl|S7EiS_5I6_JJlf9GDP-TtlVH4>Jm_=?&wIgo$f-oHNn}S>m-k`Yw)yM z4HU8q{!+{Vk&T5LeP9X?(piVy$3o#U`f)aMCm^B;clD+(l(UVq71lo=DR#@MMG_b= z%()CY%5e=3IfNxaeu!%CXzj&yCg~<(SAKw%1ZxYsU95;g2yS(PLNCK;fm)C>oC^7X zVUy9E1|cc+Qb+i@z?G(GTgf<%@_RL1V;!yFrPE&%tliJ7h|H{wBw5>pY2WaAX&zseVpYpL`O#>LYbgbIhQrYOOW)m>h)A zhk=m*%9$SM=tk3t128<1p1BH(f?d7Zb4FW6kFJ*|hmXQo9gkG0Hxu)}jz6yu*d-d}zru0U?s6xyI~BbA0$ z#=;c-QBH01SfI6So@u?^9bc0HGHJ(L1%&{qKBvhr@?Bpu23|B16c-0=)TxipFpBD;OW=C`Qv^B?Y+g~YQ+nFWq7=Sr# zf`ZqHne&$DaR18&AJ)kCMcX0wzfnK?6c=DU7@6>D#~JT$Fpvlzm>%^?4`dS&MLgIqQ5)$P~uFy ze`)fKdduX@XfpqF=Q{RMu5{yiBvtBOkugn++EpUe;4Rf(RP2A}M%n^9b3Win43t+x%W=}#17XdP`+iAS^k{k!kztz``05_xMO*R@ z6|RfM@OpuTv7SbaBd9bM*oEy0r4o-C*&)4j4+3G!?b%R7iwLM_{Ch% zYnRBAGsDYCuiGX@(&Ou*g@&+faS}CRffcMnZ)%{ zfHN0Z9{>l@Ld278h3tShl({7ub^st7vCx>G@Z~vkdlWR~4spO<152b3E%ib$ArMVY3H#@E7hVqlj4 zH7zl)5Eg7~k!~88Zl0BH{0(d{pKfy(Jla8GkOkYm15U+aWC1>%)0-?Cm0o}*3;6Q}JD)C+OXS*-78RI@%gT&x&WxYWO#G9X%$W81ZdRH_ zRz_e}W>!{Q7TjAO{=60zi1EoO%PMrsiXTsvrB7omdCS9L$VCKX%AnrKB+LXPpqdkw zTmgm-x3BZ>+Wx%j`1Xz=IeEiXZ+XuBxCwEJPar=}s7oe=VKV5W>>KR>`dJc~KJgDR zhgCH3ispOL`-xb)dAx~u7i7Yu?B29hFqX98!z+B9fv?dMeJ&k4F*ZUx~#z)n#C$CHm^yr)o z)t&WSoNsqfSmKGU?3_O#aH`Maa^A$vUwFHif_?Pif@oCCI7Ja&#~l|G?~{A`*~8{L zs7f@s{v~n@6PeA20%1UUSB3gaMTW9PdT-5MzInv7=T%eea7N=A-iYc#lT?h8Lha*n z=CD))sx6w~(gVeBr~wmwxUm?@D>|yTDIf(=sQo&E<+bhKbd!p4@>49S5iAcZ9!{BO zRh{czNodRiP*3WlJU;n*z$Xw}wdAk#i-q={8$SNq=dH ze}8$v=fVem%bKQ01`@aqmM{(ieK$}E8kyz?|Btd z9=0x4Q^fMsz}w1;x7A>!0x4M(4aO&%uByL3Kygo|_J`m8=c*L{7ZO)h%LV@40wvJA zoPHE=B~WE+PfYOE6Urr7)Th|UB{AbfIpL8fSn@oqsY5R5wiv~9av7u!zFV}6nj+1>x zqjbC}-U3kjT(W#LDs!CJ77t0SrEo)|__T=C#)&VnQ0e_@x%`i}yFN0q*C4cOdS!9s ze{27clv8$8LhD>^P((U$byl6AB@Ap>4b>|poQ)=fq`-cUgJ7McHE7f)zzqP%=F(BV zf}DA`IQ`=&11g@AybS!!6#D9AiOOH^^FRQ)2E9o}(s(yPhG^@=NQQn!LnaXWXjHyf zBv*?!(Hhd86xis90e2G5pgzyIhfKtUjL@r}GEtKRsK1Ph3%(VQGg!b+&@YhILXEv3 zp`L3npMZZ)R!L%-RB|#oOetaRnfR1k z4DrE3Y=eq|Z)@J>M!B5*o@2nCiog>`*=bonUm!x^%9QIAnLc;_xqMVw}`j zg&3bpahh8fcL(JtM!|O84nhKu__V9~j&D2N_oVLAMJS=qDgkn4Llr~P5_1EE3#pomWW>((SflN9TCmYf}`+Z-t_+hsKY z()9kOi6*NDKC=O2-F6`2PT~!3RR=UhvOema9BK^Tj1d1Kwmv92Dc7FbGeWJ<5H!@| zIKgXw^=;*J^#3q!pUJr#r=O0CbkXKBhu$a*?04XV$4Fu8Ddu{Ii>|S%sS~ zO2WNH!DGUp)F)`fM@PhsUE70%HdfbB)2=C3l9>nBQ*LC#A`{_$xsWW!DE5OH>b&pE z5#N)|zPpZ0z9O3w4yFR3hfVN6x?_3q_T1&yYNyt>Ib_dVTEBaY%qFwUzi*{77J{>* z?vBNhyw?4uqdS?m#2GvCIZ1dXm1UtMfr=3iyMhBLr=2@{-vt&77fldV;= z0tWMb-b6;vWw?@iB|8@S6&Aj=_Dc~GCW{Ui$6FW55~vn<$GQ|`QskF8MwU$Sr-Yv^ zEWTSfs9M-uT4bdJbu3jj%gQX9E%sSY4csitJm&m$lfM>Rcag9Hj-!f-CaPap2@VGV z4_ClP%Y!A0#gA7?M^?%HEppa@Pu_!}C(@p^kLfCw=(9`Wb-CeQHN^kcn90{cB2=L* z6GSJ{-O*3!jxYtSbGnC1KNU7qtJf85HrP)l?`BKW=#Q!Wn_00o{4~OeAK?%k{UUz! zg|ux=;~yo59$df<_0ngZ_U~rQ%|@p2>fMShxwx&<)}QN-H=o_xWPiHB+`8#}J4oAO zi|Xmm7Y08C!8-!$+p+`ScNf=K32g&B_5m9&Q0`NkH~rg`N;?7UJNyp2e9F6C?h^td zKdrNOXrC_IAMJRmZ1MlwO+DHQ4&CML+T+RJB{v9vH@X{~u<4t<^5^-s!>E*8;tmS5 z@3*$c&2hj5K0vbX*DV)+YbzdN?e(dq1mRaH_4aHayXQi??bUlhN(Y=>ha3(Eq@f37 z>_;2b2mM}0+oK0RM-R4j*NLA>6(8+WfR3K69kM$dqm_@36OTxgj&}9-KauZIo-A}O z9Xn3#|2jflk<(xPV<$UiCw*`TyxNiU+6NO*le$Z5%XenUw@GRaU!LGuIDRoxowQUR z5$>I=e)##pi?YHRyvuq_Ojtqjtk7|_vrE^o-?3f4Zae17`6aaSi{yxsX*}z?^+Yo8 z=^5EiNcNg?$O(<@i9Xx!QawsAs-(y2hzsNMUF3He>rb~kKYfO_{78SbmHZMsK9R8b zO>Gcb@b(}jXwN3+(2ioWp=#}^*NIWixqHnHivjqV*qo<(HE{1#s~jaEMtY!6@x7MF ze`RSqX#d6WZfefOYg%&I*U>in>4=Dqxv|nvONJx5a%?ghOy=lJ)vi+-)bWP5_uC5#I^?a_b1|?ZY zR$xcECr0-4`VzW)#Y1>}9!Y)$dhjQ`{hZc*n<{T+uy($6Wt-rwJNH@_YEN;#O02tz z`0d>tl5)zJPhhA&g{&O|Aj~QzjBHjCovFX397V=LE{Vghsm9WBn)YNqT~kY75r1|z zAO@t%nxlMGrzuP{Gsu-1b!0YHhO^#Lt-qAgru6^#do(;C?&9}y*1u7EY|%H z#cX-DYg}$pWz+lCxKGIcclBdR8SGT^i_S3lw7cPZLzUq9Mk2ga#bPsjjjrLAu?EXs zep#5-mkU;#>&v3tLSAO?#McOco4^7ZaEip4{|o)<>1wZZhV;Vz|WlWbbOmSBwz zPD|+X=4*+U2PcKZ8heaTtmwZOd-Owh15I%6J-+pvTTHnh_2iCwZa+{sY_KCEJ%>u_ zD_tC%jwul+)Y9}7sht}ply61SOlWWx85^hw7Woj#?sc#mVy?ttN!sGvpF;0zSDi*( zerZVNGqsKMlNWX@`ea(*JsDGSdy2+YH&QCkjYoYJ-DvKZq$XwI{KmP_;!#edl%-oq zQKO|tO|R6$$Db3VDCG9^H-2;&t~FZuBsn{oJS_3`vwptv!P7KgyXZN4KRQ*YmzK!A zZbW+HJ@t&z1KLc(Fw(>`y9h>;fHl=y{sF6M;=$NLAr72mbVx>?{W^~E+}zH@zVd=U zP+R@3bLkJ0X6F|L??g(@W+AJP3!4VvZ_J`bVrALETXp3*@E;!J?aErj>3Ip3FY>sp z)%ToA2_?l}Trw*9zG%bQ(~^||fv3C)T+dR-w*Q2UW<6>cn+@FlmLbBPxNa`6ni(?Z z%2fK*(NNkWxA0ufI{-xg6_0-#B%uZLDEDXEMPMq9Z)Ot>4jY48n0>bR9w9(Nd%4O$ zM*a?*5q^G7{5v#TYLT<+Vf2Tg?~Wy{TC;BqS&A3^w!fAwJ-kvV%quGGPC!^nh@~{W zI8F+T^{NTZpD!r6*S%ZOZzI1GIx2rS((-8G*Re%cUZSk2>n_y!>ZwB@UQpWo@4?5f zFGBuGfBhG7qmoJ}T~)YZ13r|b0se(p#$5~8vOb)@qY!n2j(P|iXe~H94*9cS3wy{- zOCa;Fm7_xrf)pi`NZJx2G%54cV47IKdJPa}$JoI(+D>{OJY#KOfSQ;ljaj=#_#-t}+JDHQMOl!5SKK&ii{#e~G zT8Jx`Hwufku?y_e1E-`FLwRm|8FU;3V&b8`Mflfc!`4#uS))B0s{S2s3O*4w0snVv zEc0_iZ2#&rJI=PGweJs@-23=`eZfUCB_f5U#{hoMUS*d#SKE(iD)nJyj?C}7gF#1A zIVDyOvP80+KG{CGme78c>9~R_hrwet$Kjaj}M^_Jj(+B-&MxWOfn@HDx9PzhVRJtCHR1p!(Hv_4VD}Q{~-F`iC(?oz6VZb7Z@Bo8pXg3f8)uvc>9T8+VSyG zipKn|fo;t<&JV{01i94_n|pVee&V}AZq{4o370eb4}P~so9#bj@*gy_spt{?R~6me zQ4rMD5HqHr6R}di0$H)1`P^1jT=Q+Hh4N3g?dPAA-jTBAd4NW#e6^O z`5Ifrp~vkjuNJ~dJ3W@4MpQGqy|6L7?YBqFm3HgJyY`)wcBm6AL|zuZe@`zKQ!B_s ziy@I!{wnwP-U}wFzHoV1&ld`)61zvc@(;|>JB*E1r@A5NZsxlJeg4LU+h8YRh)@<0 zvyxC}CvyW8JV@@doD$8j;z-~v1${n&xlg$Wz<3A#@vYL_U*cPpZ&)^!`1861u2F1A zWhP4{YNTRi0B|R_XyY!)qydZxUC(}oAn+Hy5$sXER_c&GyCr;}EGl{L<{gqPCY%Zr z3r05tyi}f#>!PY;l}=MZiub5+QOJH(;V@P?ZYI?wt}48wak~73Y4}RMs6c7lGkd>B z4@sdOq{@9u&Dfok2>fO!A7~MmgjA@6+I0v1QPn?4v?x>)O@W7fKk9m4UB~0n1_&dF0spgJ!7JqwED*_r61gTOK_D^4wNb-}r$O|w zl>@{2-_pOv$Mv+w>l7q7k^B>6l`#IGx)bf#f!)hj-wx3H;dcK`{F`7dE%VU(VQKe^ z3ceKqcmM7a^EMSeIr|n`*_n%!E|AwUWgM*Xj4Sl*De950FeWJpmt~J2hNC5UE44zW z6IL;VUI{Lo70x%X*{Zp#TdNioXt8`e1VK%U7x|#=~Vz+M1HX zYCn{dgGf3#zuI^bmsQqwUEhx$?nim*ys;l1_l)i5>K*WuCILVK;Qp_^xRHJNVI(mU zfix=B7$VWAjQB9YHBz)XLRi)znUd@s^+dq2VahT@j^;Tbn&gf$k;>j-r$&nFXT(3c zLpMod4ClUSPY+pFe%6JKLeBc}i{y5B#Gdc4CU)?^rbv2o)RNHs=`>7|cbH+W*jCTj zbblbCgDp^cTEIk2V4P#;JAzy!7+21bTUU4$9sc$bjXdcVf4>% z5G>fpT+i5Clh9D8mr;9P`ce_xi$J0!9c21EB=5)Djr&U<;_0|3OE~r2Kbi8OnHryH?h|Dh5YwPEBeV^pRC7V>**Pxl+*=S+o6xPm75b^z?@4py-V9+n)X zZ;m)EjIqD_#x;G`t;p1+8PXDpR%)VCk}+@`pLHiP^Jxy3aSwObjZC;3;cfEW?@oqq zr{Tq|G22g6is|E&ShzaI)Y;ioorvLKQL5!{Go#KKY%eu77^`faE8l4DA# zv1I0in5s0SOcxwM6Wf{^ARrkrVXk#Er!rxJPy23}XGWYJ^+0A?)!G;p`5+4UOFilsl%b58`%NySVbvoT4tgFt9lC(yv3b6Bnq3|yYCT9xwS?pquQa7=Lw3o zkw5m6fArBriZz9b0#Sb6Ai$33>FW5S(!}oR0lAr`Mi3}k3s$a5B4y5I41~7!7!)M; zU~YB90HGaxQQ2w3ElV@4k?CzFI+kM5FZtk>=4628n13eR3LARS^RUQzs?P*Lph8PJ z;l~QGU=DtmQs(fgQZHx*6Q2u2%fem@TK6k7PpMf~PcQ8K%qi~e$&6P(T`o!LlJMq= zSv($0M)b)xg{98fM0x|V$}s%M7g*Y7vJ?rrE>} zsPolpM4t`*euPVs)41T^RPi^$ zcGb=Zl27_bVbxo0_JafV*Gu-rJ)GPwkSf{G6{7XpgP24b6j;fD5UIazx@cFU@a>bk z;dte`K=b<5hy%Ts2454`9TzdGY>5{*scYp7A!1gF(W+atpev-ZNXi{!PRN;(*AAv8yAFsx?#3bg;;FJ}h;f zZvFYEp*l?y2JUMIFmsb2sLqysCVr@)dn6(^RCkm|<=p99JHFQ&m-b=H{a>=j@`7jM z!g1%uNRT}*S`tCB@vQh=XLndv#UNjo^-RQ*KC_C%#kxS}*Ziv>Msx4%8hQ*?O z1ly=0lV-$Ur%^`?k&$LZqyPSAe-G8<{bs3%FCq~weI6Jrm=_(IM>($C1z-@aj;=fQ z#qQ3-OYhFze~s_HCh}NnjidH9SMk<>|5w!rj@Dk6a+CntDu!2XxP$j$|CE+Ciwt ztz?1^KgSD^t>8;1PFTM8kiI#t6hk?Vhf}R+A_qXc*f2gj2*&#vW{ySG{)rO`m(#r@mgKa74Tz;#90eC)WF+Rhy62zZ3JUvbSH#-v1~IT@8EV6Ky+34~Rir zanXKFk+&ES;+at|@i1j-JI(8 zkuaI(bY}WdYvgbC`gFHFMZTh)eO4uGBrp%g3hTe&x`d+vKw$t5LE$7<;SmTTPX@$) zPmx~7=i`_D#AFw@i(?6aszgz;7r$t6r@AYCqHAW45X7UgCjz2@Y=|=|+<&{#4ZxD1 zi5@eQvo^ui^#RISBD?YWP;+Pi<}xB@z@-1r9U-5lPxwL{ud{1QOin#ycHPR%H)r*- zVpWXdKaL4eM@fy~!bb(qML*^<4n>6fjz_-=fT&??Sr-Dw%`f4P zFO{lEkhQl4>3rr!FQa7E3Zm^$yb6Uq^;z2zqSQDNT$K50m`D?mr_4)+ohW@*uoy#> z9Rs$O?PVz6-;cZq#@Rog#&C_iW1k2Pe?Z5 zdOvNKE9|3>(->;ca`K(bo9>y%1M=1N2;1c>am%kQiP5L_Or}ssE7xnD3WntKlb``;Y@A@ubDqb?0_;F}Pk5FY$@nrdj z$&clu8@WroP)nTXlYc>f4x&?4s@p#4D>^YG+ddgv4hasUT%69L!dwL>HGj4VF)J&X zgzYG(XNQr=Uap22E6K1&(nk5&nL{#))=YT0rYO)@q5=A7#zajFt)E>A)~`POawd-Z zgKxTg4c6Y?0=eGAnWUh_otLCU!pIe6*E=_p!k<3*KpcuQN5^og6LVAebx-hcKV zl5J|mWbC9Fuo?D1Is>><H$Bw?z_oO#7AB=mM2c=!*-y3(4?L2XC3LiX;q0XjNNn_6%ohiRRV5j94dOaovHdAKy!+Q%>Kjw6MuI#|c zRXJpHTf1BQ{BkNuoF{y#cqLk}tzcQOifnQN-1!_y2d|G02uw;|x%X0XYChUBZY*m7Otkwh3Z77KlvFVEim z)%MqDrthKHgY@cC?6aHchKv8b-gvO~nbe}?@@E{c!u_6ya(+0>@H zo8R`q`hJk)5{d3Ri2pN^*E$lFLbkkSD;vZJ8EE_cD@%9%Xlobk<$)dKa~({R?ZQV;fZ%M^m$wL{==Pr z22qyz(HV<0Y`+m4&;ZXKDnbA;z*9@&Kd?b3nmi%0`+XP{!cF;~>C7W-(c2#Zko)O( z%O|<&L=yRW-o%wKw$7KaT^F#d_@>gcUFlk_I^Bdrq z{mQIf_6lAqk(RdQ)4p*HRg)Pflh9O$UXF)jaQGx94z7e}2mA!3R)+`1c;B37p*U6f zTBFSKx;L*>`R=~}5r@g=(|>>eLHb`EX-P;)Swz)a9xCW-^LQ}unz36^h6nXj2ORg> zm&0;OW7zgrS=Er0_Be@Azo)b5$D-dtyLhJ8{xqRzRl9y$`U~73a<%q{c;#a=Q&8Ky z9o0gmCR?>QsK0HK;sTA6RJKPE2jw=aUG|ePp_g_IKYy8R74a|g2)$#DZdtw&3HaEu zbQJaZ>(nP+aaKE<-NfguN5M~Ct_ZFilw-)Bd0>LJD{K$8p11#-5qVA!v^$3dbWF8& zI?G8UaiO?~&u~@iLi&vLTXfP*Rkdx{69f>CX4x$5k2)n}ki)3yfj+hBXQcJSL&i~* z9s%OzG`0Fwb3mL%!j!fg4m!t|izXe`Q%mrg&(=_aU$uhMORW}szC%BzTy=X_6 z3Tw9MC)v9yQ+Jobx!$R5$=u{gNb{e1nv!`qO?1P6+Q?}a{Az?RK-~6!qcjv+^B=LR z!cgI?6#RM0-7As#K!e%rYW|}!KRNdf>Brr@SwfGwM1oGPnpELQEP7FU_VEjhbBLVB zT;|KA{Q4*^7l1+(z>w~^-q-9^ntUV=DZ1~t^)k)%$KxDlBHz+*;yPXLEztY4PoC26 z3Qs6Jn%*thR0sSy!zKj}kOFV;`|4b&qb3cGtWDU^_8}Luic9hUNRGd`1X|FN(y8G= zc?I8bEG^LvJ9XATcSVcUbZ>B;1Vc2kC#j8}L9!D7?}oYgW=(qLm|+`GQ?`4+#+{E}r>8AM+F864@V zm3GD6bL9QI#^QV)ca~4D{8&je0Cdr-L|A95Ym$3-kQm6mmM_3?BQK&}bRZmQeQX9& zRZLt1a(J=@2Pz>G$o7kZPxrViti+Tu(MjI~y};>f3tMCPe^xJcXjuTjB$Yri@u2mb zo){xOUTjqUZdu4X^_JU*nqTi7x#JEm!Afnb`g!l30O=OclgL*mXJ+!pI@2L)2d|MR z9kzc$Wo|6xwW{;*?1kx9?cEk?LUt&MzvN8UQaoC$I9Kh7qJ6YT3BgqvV z#>fv8GCDz21oU{WRqo-PiYqzIvQr*7tZVY9!dT%7cZ$@I%iXRE=6&m;i5ptE5Ne>q z7>uPju+e>+bbp8a!O^CfmzMc5v*i}{6HT6G7^ilG=|LU01G$qU-KI$oq&*8e38mo7ki%y1p`)i zvCG7vNF`)T>9Xia<9*jXwcTJx4Le8Pye&2F#BHpeNAc!E0bbrg7iF}P>{*w>T$ogD z_ky*{pRX9_0Vi)dsCOc-69d{3$vZcnZ@$HudQc$MRjh;ne(_PPHuG?*Z&O=FBJ9G1 z&%$`$$2`wSx_hl6lF8c^z!L`hhPDbW+;Y&pii4Rfoi9Wv=C_Am0zH z_wyt5UK{W%sAW>iaz~)Nm8CZ!Vwz>;o&0l}bBaQRfj@RXgb+#Dft8%P?wFVHxa6~+ zK^~^C=21Pm9c;M9FOYn-n=k9G7C@ulqpD@3L}hk`r66!NRY_BnwZ7jN7IB{jlr!={Nz62cy{FK0PZSA; ze|4)>ANLH_iT$$Q@&%bd5-~zsu9jA0)Wu_H37Tbb>HOl1+hUJ<9Hs>Q?j5tJgjbQ& z2{Saw>oX+__}4uG<1O{7G{rOK_;o-qf(3o-WHeg?%L0gM?m-f_Ds{nKw5JdM0cN-Z zM;tNC)RPiBJf@6OxK`nE^6Uj4CU$JzE3Env3*nXdVCGw?yu+tqqe}J3{ZoFC19^G7 z*Y0x2H|Nf*_q&h}yDH-fh(a(xS_+n)?v^Q4CIbWXh;F&2ZqeZ)3=-h>C3GufLdr;> z?u+5l7)Rxx!*EGEndGYZ{BP)F6<$qy-uQ4%yD&LlFSCxr{w@IxnT}(`)TDY9rVtxk zR~%LBnOwe!V^yuWv8-hWMegirqdSEQJ1OFoq<47!^L*sKcA=O%g>%EzOS_~Bl_*?0 zp9n|t(I|0YdXv(s{$NZ?=mh^3i$o$+)XAZ22nc}ek_w7E96Wqr(=);xZg?)JFR{Ii z5}KxZQeI!E=2;bvt$;u}SQopCJV9l{Xj(d@d&p3w2(T0qD(pSIv*kH+xva>SG4{Il zI!r^s_c2P|oZ`Up(6F?TN6dmLdRqPPglp{A&SA%u_vegsR&_#cn3yM2x=R+J3a{+8?Q`uAu8c9JzJuAIB=-{IL!u1bmv=S4!P0#tr@g;#+9!8wQ| z7UaGv3ix(&BYPOHRfNcTV(aD@R}wiRD6jMDk_tN&jKc++z<1_Un1BvW$=L<)ujn6m zrH<&O^J?&zeb>n$1x1ap+)%5HYWO|Z2uuB0Itd+B6;W4JB2^V3ZzcLguoPG1dy-I$ zYp0^O7>|bpFMS04D}aIRHS}7AIf-}ot;GE^fKQ(=&1)AmvG+`j8X6TL4AvoL(&UWfb{2=MMQB~c}EHDZ5q za>Z(hH14bTVJchkk%;KbXY>?ftSzy+qp<%-Z8JZ%7NK~0qFqyI;$)CU1x-Iv|8@1_ zR~J+g3BiM~T<^P;MX>VMARw(%(U+I{8X^_lRYszUcy-3eh;h!%Vtgl=gzXfP4@Yi3 zDgSmN202yyY~Lw_j|!p6SUl4@zis(ZmF_3M5)_o<746j1qcaUfE~@Gss6M!c{`WyZ z5~)I+X525VW+bm>9PiDyLe3DG`6Q#k%$5+rIvy@K7p|iY9vI=%l3vjKUaEox#J-U~ zq(4w}@z53YcCV1U?=(@G;cl}3TU#F%r)1{hss1S01i7dzpW7{nm~krXbN6*|S|FFa zR_QlsB(e4P(g}~4b*5f?nA0Y8ufT?9zT6|jsbj0wBV5`Oa%Lf?S})?kBf0;P+?B|! zOR)(et0?We0#mS4x4y#Iyu0%`ajT<{?0Kr&H*#-}q~{^)lGf4wt>5+~#|3)@s2Fnj z9$B6T@%Bh3gRBQP(M|Jyai349iY3la{@rIvr9WR$Hx2grU9evcX*Px7FwUsw5knUd zLw(#%D)b!?hU-vSO=WqCrW2kNw?4^pMCu5 zIQDumf53XP=DzOpIzLlZ4cF1c{eVfJ=qW^EzK`benktAHbZykcB9w^N{|BQszR=UN z@6TBcbfv<6rJ;J2HY&L=jAy^amFX(^?GS`SidePk(@%l$h9(u)>vRYJb(;iH-^5FJ zrE{MuS2-M&^c)TTJXVWgH|mwJIM2Dd8N2vp?R{LpKB6xooQVZRzpP7_@hVzvYBff= z$M3)2{q;bW9Njt2)_ztRbUPY;yQI+_W?^1gDh$x)hvi&X_H{f{=}>MuHR`LwrXI`A zRhYS#(fQjk42X=QoIX7H+kn+iA&-{NB-EDrH!;;ix(vxh-pNJrwu81=(h}V(`gePa zD`xAJc|}@rL#j7}8oYz4qmsBy*#gd5$<5Zu%|6zUz1K1JYH;pVd*62vN6|pO?mm*7 zfXB-;k@h6HZ4tplfD_}e9ZCLSvZ)?Vv?t8F!yHAVlSj0%74Pu?blTRxDl(9%K$ay1 zLl0oufMi4vDy7d4RbFe}()tiW#`@fvjSNO5#OBeuI3?Elqf~kC`ZzDVCJU8BIKlNH zPZ~CDzwBB0J^N&S-q4--X|(V*vlglw#iu9Jer>_v^Zo8CUIh4}M~nnyp+p4iFXspm zyV+;ByOV9cPA!1%a%XjK>ZEQ8i2G|~pee!&q>#Sb2EKVlWV=zRyNg%NaM%uD^|LsZh0ID`+rxNs@k1%BR7yZRz8Q_^%^fR!*f~XkSjhkWg(T zP;U2}GJQFJCh=RqFHS4HgD%+ZwIJ}Sb?y5kTea_}R^K>L0A}68R22lD{w%rVyK%L= zVeqhJ{<%Po8sYhHTj>|T_i697?>(LP{&!^20dnu{ihqQ-BmfhPH<1d09DD;{Q)mG7 zC9eEO!2~n8C}J+{yVGAX@^REsp@c#WKfd_UYm~fdPqZA1CKu`WD3tW(d8UB#?gdHJ zLYf~PYGkIY^WYa!VGytG9Ka%1tcta}Uy6;CohwqQR`$U(LCF>tY`|Y5`?{gqfHINu zBu(3LrjYqdg5Hu-Jb$ytYnT4ctEv`1_G?t4HNst!zA!iwE*o|Vx{ntW_hvDqOrywd z%1nO#*DLLDi`+L(FBL|=O_{zZ9PAKiR%~T?W_bk08>ePGjMEuiQ>knQ(;#>IFQ^F4vxZa0_edYw9} zl-utTA)F&yL$$_CJ9;sHUq}MlH$zz<`26!)D5>3aPqZ<{9+i7w0_l z_s{JyRdJ@0UVqW+m92bSL21rsveU-FNcg~w8O4bBM=H(&EL^H4mToFBMdklXNLuMRRT{Y4nav~)~{v*NwVi>AK(2) zMiFP_sD2CPeb-uWRoNEiMMl$ECC#}QSnD~=gMHGVO+5+vl@$wE2sqx6B>lhEwa%3N-KjxpO8*N)M zFHyXT(_TNV`C1^8v5{*RPgS>5lK(D#|Kl468+P#0{dpDTp-GEvYU+sZX=^>-JR?NU&igblrcH#LzCFc4C|Ndr|xSO zE_Q7~*WCx~hd%9tR1c-DxEI#fy$3w;My@*Q zX*JT-n_Do$gm=|V^Ug+6KX2~rr6L{vVqt!GLVidg1y6%Poswdp9^(AIW!3Y zE5iITGBh2pyOBUgvsz0D5!?R2_qd@H1m}qnY1CoT{IBu_I%v2 z6glRG$Du7-LGS1po)!fc`)m3wQifT%D0Vpg3l>=k_4?wHsyy7+EMrf$T4gkBxSSnt za!7F)WBiuDF-?(5G)TA*0iSko47#B*S3jLXwxO!J$G9og&62c|OMTc!h()*j8J-S3 zH&ZVC4k_^gp(v{pj;091(WQa;dHLs%6 z$K#4zXj?@$$<|4RbXR2MoUIc$bVkNhOB|zQjx4qVg=%Q;wunZHlmsXAB;VLFWU9)_ zNnqALPcJfg9J_-=Jkoo8TI#b^*O;ElU5=gP|28nZ4&$9=AqZrg_dbda=SgNpx4Z~K zJ-5SvN(-ROiZ$il-IXdJD*7L9c#?4`7o}^TMEG?DKOV-m#ctO{*{>LWztV}4jV6Vnvnv|whOz2uC!0`KTHRx=OdDU)#@}n1a}7lJ z74_BANZG$Ndb2WnGN4-wus$zR9N<%a*IIB=;pnHLA2r;fQ``KJ?O_vV$+y34Oe@W9 zKsjOKOsS0|-<(qWba@pwB{SoqMACiHQ0dPP>S-qjW8C+~meQ%M1kPq!6>k%;yYdr1 zeRB{vTQ%xM1`2rmu>Z*M0K)uZ-2VkaMC={l9WQ`S*F*7*0c8Ci=pI~rPZ(<~iJ@yE zboPT-hX=W;>y?PIpaFFT1!%A=0LHUV2fwdLy}sH`ZQY)@B*{__~d zZ9TSB-csUI4Jol-O7nlc1is|-nV5cS+2T)^1&i|QhgYl0Q&*xqCbQ+eMOG8hE!+wT zT9`kDvulwEV2r*^I#0(o!GF-dnb6CbPnmMTtPB)tV_UYNYyd$1HOrwkB}eHp(uPJ0 z=}ONyMztz3qkh*+YG*q^?#keP8Po>E+8&c*v?})D4Nk|nfc+uIo&&I0CoH$_Qqb&vNFV4F z<%40n=Z8+bLc{bXU&VZltC3dl!nk2Cv^&8rJ>!dHHFl|1r^QO7a)^ zbeQUAJpkBk$|zlqQIt91dA`kb+b6UK<^(>_T=&q|I*3lkO#@3A#qYgkkC+KOCqRDsBQsZ zJs<0jDRr9@9LT#w1z(}Y`P+5V19WHMr{1u-$8ArHLiLV!j9B;prruBVQuW{CCFq{N zAQi_5!aTg6J?LabkoY`;1W7Ur(4ja$7MlMKRT_WN^f_Px+TO$i^3X-$1REd>pzjyz z4^rq0+Q=y>&Q0p`{H@1~I@|(gMZ2xm4ck(w+y>@JoX?T`Z!i*OZp@02{(XotK97fgawjmA3$1<5=u%*(vy0 zAk#D>3BfkrJUw+7jL~Wbzlervo`zUd6~P%yxxGnboX7pxG1MS^lQzW|ph>$vQHniF zinoUt!aZRPuELV;V(1e9i}lAqdP-67OCoelDXJikhZ43Yv#f-t=NZq~ z@ytH#`&XJ_b9|U!_ZzfRixJ9#2(v@qt>N30;reg8JiQ-4d7#mufN%r;=#1vH7Ksdr zFvPQ?0MF`PM3Q^n8E5TODm|?yi&*{iF*Pm*D(m;D=AW5 zX%=2-rY31FLdj>mGD3tB0!=bfO(3K=uPpfnY8rt}|8EIh|ApQpk)fpLx-=B)v|@{m zViM0(cce+!Q046oYu5-1d+}yD6nNDP_AU{K|{{xuI0vq+ETW zT+gf0?55J*r1Hs4fpk;$YDn(IF3|&sBKn!!>kCHh0E#9BL@W=p-3v4(E^#G7DTNC) z&_~7-o)>>UO5b0Iivi{jO)v18)OmQ-;e3w)2MxXpbxJL1nm=mK-Pni~o+rrIJoLb4 zKdLUyE25e_8K*%oCvf{QAN?}M-}lqhlkiM`H#FL2*p=5 z;}1iBDY3wyy-C@NpfCl_N(zOMHFP2=bDHD?ESLn^LG}Za-287BxOB8QJlt6d2Z4)C zYW*G{#9dbpOot4Bm2u1P7s=$fbGrA!1Pg~QK^EIf68ovdm$5p8hqZo=0{H5`GC_0{AGY^oFpP06Q@P0*kC zIR$?Hy1rQ$PGBtJD8kiZ{q&q#-`^a$U`{Nrb@PPfA;FkKnKYftOecjc>~f$fY02!; zvRmpSxZd1Zn?v#)y*2j$f34#Kqe%5j>&8oc4*o6&Z9_={7dw8N+)MoeetP|8YU2f~ zcC5m8_-_q}9Gn*{uZ~uc!zmW50M+CEXz+~97(e?Y5&e0nEgQP!h^A#LKX(+rerL;< z&)Np@N5p?GosrsV;48ZAWaTCPFQOdQj?Mh8$z}$})}6^Nkw2(+-R#%|THM~5xk{T- z#>Z8)AP$J!-ll?OQr(`VxO4?nzpA%k@o-<=cHxn>P~v}QK4PzchELqePN2j8cj4`? zuO{*MT1*~ZAy=B=#B@s=C7&IVumzYa@jP4w91_ahUko~;4AX}Ouq+68JDYhwGqX+b zh!Xbj8PRdD*YOL%e?x3VVmCHlw&cp^n`JpC5OnY-6-5ph!ys}qczCIzgvk#bP5&0-k*Dza5KoT<%ihSBl?L@?+YI-={* zp2ApwP?}m2g_`mrv}3n)qxJ-&{-y>NzFByXA~F6L_qQ#!IfYR@_V1R*_9)!tJ-ILBg3<%YI64vQ&Gqa=w<&32PO02w4T924a8S&}YI#hkgUzUg0REvH*mLnG1<;?JT&}8{n`O9QKdMq*Dq(N@B9ol1ko60BJ(&1#!nT zx&Ekl?OGW}-rkv6_C=)inYSUoWW2hLr=vlKrE)9v9D}uesILeUvrSDvMjL}j*V)Qv zl%(1rOVn+UPJ_Uw1#+Ow0HMwE*|DG=^nChIBs|98i;h9__v9~Mim`8}us3wN7dpE^ z8$w9<8e>tooZCtdX?ughaymz5ub(9#eL(#)pN3ns1I>pMGYfjV=~>^&7?@d2V_2({ zl@j2S{`I!V;!aS|pIo(o{4&v>&#(il%gWVrL^X2_3Xpq65+v%^8lN1N3jPc@KIFex;XqP08|FkEnd zOA9jD$CM_WtX?ZR=$a%K^P9Xgc<4e5cl$knE^a+%(K0*GTFtDaf#^M)q8Ay>qGQyb zNcFtGP`=j|-ypqpY~=YgJa%VJm))sF8|Kl%m=eOZEI9e%ZZRNxrpL>}$`W?#NQR7W zOym=*E+>D7VZ^BRbcASianENasi%MytR(#?-)|V4~c=QSx@)8~=-j(dJ_2 z*j5n=b4Im`Wl7(M5-E`+0ii{M-sy#)p2ct93^F%SGQNdXet)6z{j3+@&PNWK)Ui<& zz7-B|yjj)?1m4Nd+fZ#PP;Jv0?qRHLe~_ySku2W?3C`W_Alpl_(LcCQF%&7{dfsnQ zukGRdts!2YY`#||@+Z7?Bs9L+*YN#5QcyCdxA8LYEp6Sw`}Lv4^?4<#inHh6k=GO7 z0ksYE$qks=CLoFJwn?!YKxTNhN$c=~_33eA0miQBlqp4P!so2F8F>@y+g*X93%-Zn zKkt?Mw$_WQnK|qNdAklz_ukd)`99qb#RWL?2|jP2F`80e^B<(t9PDZk<9uPMxT5Bj z8W-z4OTWny>7W)DK9`g3EJl}7H+$2j3zZ6xQk3Ct7MQo`3-2cgOjQa~Skl0uX zVW)ur$5Bl^r&I-#_3M3l|5~uegm`?D`qTu0>Q6A4PZbFIS{n8#M1menTDqD^&uhY4 z27CsA{ksF8Sh#j|B>_Dl*yO@K;p&@x5rk~uaBHr@!5|C)ucq*`!r@RFc?*9BvhA*H|o7%#mo{-KA6pjFjHg&ZbT$s z<=1M%PWk)Osq)2oi?Ix`DE^afo}BZ$KAyVSPCg~K51AXV;?V{MJ;pT;APJtUt&W*EK|Vhz;o(zLl8Oh| z4i%9G$GbH)ms;PNMcPg``+E)0PW>*a|pnBpkY#N43x@Q_r8{3xe3S6J!5kO89;)AIP&!%v2#ud$D_}9bDWBK&! zLQ#Yt(#&!1*=4}-!sq*i36kQRa+FR*dE0S{@=BJ;0%|svDOzUbmZ_ST`<7`6fh=#* zd0lLFqXkS93Y0wW3SVR)PYdI~fZM4mrzb|gqA)7@MYrfz48l;+SeWcb4MjevStbFz z_k~us(}s0%O2xu{afZWaxe}xA*$ZsQvSyTho7TWESw+pLZDq}8%(qnylcTn*_k=QU zYdU%(!^qsnorh|AaaHW<2dSd$8b+Uv*)>iIkD+H~BQ@ti_+M#hV%QadQxI>Tu4Fv@ z9yVece11n0PjW7)sm{@jae>W7ttnV7nfT>DuXlpmai>ters$gM+gnoFo>PRGL)m?GdAz_SA0NfUnhj65W!G z*|JNG%5a6@^Vl*>FKHfZcJvE5@sF^24DnTNhO(&S%4h?=HT+{tiP^ zl@!AusMPwQMy9mwLVR@aL;|1oKFwwQ45u8XK&c7s?)-a_|7`h}`oWhk_vTw)61PpK z*cPzh_}d!E9_Xh2*ss(;H-XllcjNH+6SZLs1Q**K zq`z8KS^!7(3=SnNXSHn=@&MnP>-96zQlAhX=HN2-a=|TSNT1ap;FpMpS)^ zZ8DCFE_U}7Qql^j!@JG#dE!HaP4eUNDYj`6u7`fNpC-E%SuPb>!d}CEpsQ|#2=Z@? z1a>6|TAfZvbQ6tRL|UYc+A)?&>d6^k76HSOnJnf)@xAjjSi9v6{Fc_kjvZnPM8H{kG=9te?_@jS-Y&waF}&?2I6zMz#g~M`}$?a@>C>0 zTL9m_;*yg>|5Mre7i3HpW9izBpNU$MK17nB)nU3qO>^@ps~rtySHEKl@FX)FDaz|9 zFAxPcN4r;>|Mt+Xme=V(Hs0I3>Tiqm2&S<{w|(OjhP58;Bha;7yl?1gs{(#SfH`l8 z?kc9cIwXF@CAxr4G9cLI2m6t&#Zl|m$i0rl)I}6O*;asNV52oHB7TL`+L^O`zgf5M zfIj{C3L?6JG!yLG;c%jn(?m}zXhy)xY~EUuzTVgN=x3?H4(YQtEq6%k+sx*Q2|L>S zC7Du5Yj`Tj9X~C=OFV#=;)E4*H$c3%l*Iq}%rWzLd*~xb$AmxdD$%M+$+$i) z3VWBc(zBWi)!wf#dRMXJ{X{r>qkx>*keMzqpuV;%9ml@Q)w(obto>A_q)Lgo@unh> z>f#kBJ7JM#v4bHTNlVlbv4{RkXg0CNO$CNCB2B(BPWO#BlgkMHxxAJ7SnddO!-+&& zt!=6#+bxx*%4#%6XVB`>ErZYgt#4okt&dDypk5?IXg(ja!k91d^@**;o{+!8QScYIzk{7Q=--XWUaoKUn7OA(OPSl-I7NA{`7r*j5)wO+k`VbeTE#DGJYrrZ+O2a= z(A^O8!H)KO=B%FsztZA_Lx-}+2KZg8%*C4>0#OFgD<|@`#Ohy8sUqKTTdKd@U^oS$ zd2NvWIvv={N)VJl8UE4>syg^<22t_(@t5&u`_1TC?4sZ<_t4o;y8AV@9=xZ<{ob6_ z@qMHY#j%Wl@VP_Hd{5j%Z^!o!$|_TEH%ui`l50iaUAzeU2Jf|R?WYsIFYlM9(5~)I zntmm$|2;|~yslNS3fDMGK3sTO?~U)}%$KKsK4pG5`OW`u{)Op^CTP;r z(E>%|V;}Cm4ic7xhF?c)3)S`C^YB1V^FK&c`?aWXq2qUI^#Sf_jhp69=nQ@wfRH)^ zE~UzbC7!6mZ)vX`FiE_R(A4x>;a38Z1quOqTY=B61+JI`Xj9=V@#^O?a@aKfXv6-4 z#ev6H9;t5vzybl>%$^G2!5!Mc`&Mw6IXaOuAQ~^?SO;cU^11u!E0q>F)f)JGNr|g1 zSc@*ye4m?_M20XA`#v7>Bmo>cV?Qt$L?0f)T;^-&8D?AtXAc*%v~AVQ9n=uGWDN-3U6*h_veLHYCvF{TP}K}8d@lpF8rT< z!&4*-*FBlcGRGQioOqx`n?$Sxy^Y_F(w`wO*r%J%NrQHJKPOI{d>| z&lo4d@L!%R%Ytw}I0}KUn9A%Ii5l<4IC>Rgbi>2JwIb)7XE{MlkX1v&k zL7lK4ixN=+0FjMIojmYs1@DHX1mGran)qFDni9@IJe^r06Dcih8TOeUMtl&d=MT9Y zOfcAwKHT@AW=W*$30q7`WL>6_!1zesn~2@x35J72HzFPKAX}aR0vH+xB+299NaHMp z#PpIV85S|=^5k)ikB_Z)1S5~-2q=HkP@ZGBsN2LQDMp~(ywS8VK3Pg$5KK+KNJgPi zAC*LL+u+yrPhlfWlx~X+QcBYoOq?OH|EZhGk(L~FBjh0jBLldGI6c_n!~G9Znov?5 z+tU+JJY5db^2^flg~U8CK*H)Ttz^(N>wMno#j9Usyd6quAkC!F&1^|e$C^p{+Lv5J zO7ZC+(*T6AX@WP?E!Y~I_8Jv{)`4HbB#7tmMyF*3)00AM(iS7K5$~h&NVBA%S>H&X zRM(@+Z(#o101qo!(Byq|C{z~pw{I#-3e?N~t&~eOVmG4qVdEe>raYG(ABj_mfT5b; zrugSv5rE1@avTvTEHHqun^H_Zd$~OcpEZ|oB}6tn7k?=?XDFBakOnUg&xr$GY3RBdFwK}twpR?BoqP^?Z($X&;jmPv>E(@_O3yUm^s3?mXEsLpO zn@P;a6U=Zvpr4#{$Nmr&z`iKxqT}QW7^=66Rfp zbLoVWQuroSSS+QY`UxDT0+zQUnTHKZzqH8~QciwZo{}|EnA?Z4p^n270Bwy&mEc7E z=7a_A0Ue)W$~Zw={c$nRK>M6n3e#v8PRzh#SFGeeHKNK%)!+1m*I4WEdeAO8(dDKw zf1ZLF^$Y*l)DU^)^LrIik0t3S(Nav~Saj1SxZ+9Fqu3=vkpL7pML#(Oz#z<31neg_ zY#Q-Qm8bj(R*{o(Q!gCjhZEjlL_8yT1MS-=;YehSx2ooN)Fp-zPP-<|;YS`CrP>X8SuH?%;Bh|+O3Z%%u zretOLWMB|>H7877T?5!afThSwTv%nuTQk6|$w%;=j@EZr%^ICG#~H0Sf~_eo)Heyu zj62i-EdpwWKu>IoT5XHN0uols?W5ZDT-#ekJ`^4WA5_$2t+s2CrqOxl`u%2fF2Hlu zWb#O4@>*b$AY}eZ(_---TJ9U#fS5@E{BKa>m+xN&mZ;^LpT?;I@a4a`) zd^_jZQWtdmP{z=r4XRn&P?%<$*#XMzxSEp=cnWSTt1&`Y#i(} z`m?2bwG2&h>>@w24ZJdFWiRG$^)$xgM z#}g|)kZ32!ch$)qyUFhqlUqKMN8^+G?2{+hQ)gL|XR1@jqEmmOr+!vV-i%MJ`b^zp zPb0CXm&Q?$b!2`FV3q_Cioy3 z+0QG)%qvyTt4z$xJs)J4K$2i}qwsT1A7RtUsW067Ea+7)JQ-NH=~{RlGxb`8p}xewi+R`QyY=)9&(%v!%@HPrY2reaJTa-m+BKmi>c`kq$Lpyxz^ebQx{6OWx%t@apYMe8+XT1Xfj@{8W-u!BUcPP0zaa%Prif{FK z`}tGY3#y%$;xLDt9fPN^p^U1r(LN8{e#ZPgoAtf7xcg8p;M4Rbe>c`e9&Q0_5rFNQ z8}CNvYtI7U$Lgj(Gcd6}!FXl*$gVhZw$|}~i^HTKkf?4vaTD@k zHJ(v5r?hTdYbS^o3@_0{YP}alW*YMgJuDVL705&B;Ka?LgSAT@yv7B@IPnV9p$U0- zZ|d+dr%rM4&LD_0LdP?}|BP(vEJp@o_Y_Sc9{N~K4Kb)g%dDg8Imbbs!X>Z?UY~Uv z|0e&AJOk=#?{8~CV;s=8b?BYvSdJIZsDG=xfF(H{g7bkz09(}w^@y{L-tnBd_MB1U z;%VH4vczvN=#sGky$FUXeu{Ph!vN=BGUc8(tV<$E^B^lve}Mr>1ES+?wVnrD%X*CY z4cKkw^_>V&(FRT$FD&@<+QM0QhKsWDB`g>Z01MZ=nAwDCOrt%AC47G(Al`y2bz4IH zq+9~lj==u)^oFk$tCkbi%83OapvY6Q;#%Ao6By552;>aCPrZef8gq#g)|9u!IP>=l z^2n!JD#9w>{>wb3EPo4MeHEa|Q;OZpiF=*VWMK;R+ zgdaX;9cu4?;lW}6Yzs}?K?zaF)Uh|$DZC2}kTxYp_fM&fB;|8hYdg{!FlYqOZ#*pW zK<;1+GTCA04ChSIJL(eOQ z%QI#(B_C*(6%}&@T{<4`L)&a}+8rD1?6UO#uEF5;cKv1xfe9ZF9kW5I$j5oKOD3G-JV_ejewcSMr72+6L%Z~e*4uncdP9aa)27?9n_TE$hT!v z6KVcXk601Cv;&$Q@y0)Odi3KS^NW>9DzAe3HqauOB+PYYLJlu1hjdYU#X_m5m!;~2MDt!EQ%b7~SePh{x3maTH_)#$$J zS|rCb>*?ozYJQ@Fx-yn*AaJ)A{YnRABU<~D<-4y|_LSj6R*e9Q zjrO6srI*xa^6s{&#op4I?}RR_S(9tIH0YTYM6H+Mx!fw6!QP>gDq`6_%nYR(dzC8& zBf8^nrZucd_vih-JxOCON`A9q1LUP-*jA$T>L1zQ4s25+{XkBp)I7k_yFBwG%8KLS zOkd%{^2*P`N7bM*M22qL{tqHM!*Aqm4oEd&r>2FcYlpmDn~3iL)78U)?yES0#$yvi zqV~PZsCmDq;PdDa?%d_*CfaEHULNb-SN9$b{NAh;(JN%b6${!lrD)l9XBm7p;t7!z zTi-P&LOR(d2E{M(<31?H5WvXb0Hf?jB#M*2&f^FANqC{$U69Jb zBdKu#0Uk_X{t!3}(^$m5ENGPk<*nc}u2L6QERaU`mfsooZp|X@18@3ER3}_z>}|;9biVwo zXCnWPan1JbP>}2Skfg099nXdW8NbU2-6I zaOnQy&fpz@(TAN+j7<{xb{tA4n_tY~Tn;xnZ=n4QWmI~H3J@LR198?05Y!(SteC~= zkao+b&E;@guq6H-Nw*{sB5uZME)zfkRvLpC{w~rlGdW3iIgvCNyBz&VvHoFD`o!^o z>EQHc`aK>V{O7=FV=mHy3W$x5RkwzwkAAdN5WCfgCqoelVwPrGn~B#|!~^aMpm6>G zyqdf>Pky08u|Y<;fG8w)H$Frf?y>S))udN~u_w6sRWGII=zst&3Sj!!y-&w+pcL1zP~*FR%0-7pV22s>y~rIQ z!*Qq~W<%KK^`wddCP(Zb8EWI!muIbY2F{+wGZ-+_LNe_$7({YFQDBl6?A;Brkxd>pn~ zWBQA@{b=>s_V!{UBhL_~#LK58=+p2hx>HlCbAq4ND&8vr6s^s*Mm2UeZw&xg4^<^| zFWllRmQ9bib7kkJdgx!Ht(tdT6w6WInlmiMG$~4BXt#s+-_?zk#m)hoTHmD3gii=5 z%7(T|CY)n~jX>=_^4&TGI+|E-*+Q(LbT!*{XFR()Ha?_@b5sCE{y{Xje}7{jNL>cY zb*+%1Nq34y;l8qE$M*dkpddD?GtCgH{dsO9xh^>A_nz4Z~1K7##p;+RPW z*iq!X=>ujY!^s55j4ev@VP@kuT;7>f zDV{hHpZyFsf5IPSLjs~_L2_4j%L$QZW}=qjU>JD-IvWaYg^>c7$XZvPplPH zGG%X7IGQj5hazUY{Rw7ZoEd^-sE*hBiuI*hX| zi^}jQV=?N|y&~kEJcfP{^;6!Euxx@N5Kc2+m~&a~SFNUnN8YQp9Gupt0e6ndm=7=U z_;m8Y(Pz)#``^a~g!_9(e>B4l2$N?Ij;~WNli?|cHA4?5)*sR`<89lh94H@q8l)j&^_jS$MGu#u|dq4Hz z!8H%fXkUiOYbNIB*%hVHfr^#aT=s)op}m>ZlYkzxd|&q}E2ATWJ+Bu<>+W@7M#tt% zA|p6X7*6wrWL{;8d&e}y#uS?TH3>2KZe=u%LmFfs!QAQjbHctRw&9C3N+=(8&GZy{OM=dEsBJ zKR-ZnUx@SsaH6f|OEDNqGulZf{SGd<0dd4bOAkOk=qNNB5SQyPN%Bv#I)+GS6V{#QAc|XKyH4Awt5Hq39@w@ zWi|;N7aKT*`E7Itqc`%(KB1!smq2fRM-nR9E%W@J9m0O!KB&v7tOkXgCi_5W5cKJ3 zfRra1m`6^>M@~0-K!zN}wJywI80wTHXS60~d@T3+PR;~d-jqV#j9uPbRNg{W-qKM1 zpPfM;dFyC-n=E=ZnF z6g;C9-e)OzRVjFPDfo;ld{|TPJy!6$Q}D-D44_a9WLFFlRSZ^D3^7y;wNni9Q4Eh( zjL1@qtWu2XQj8u~j9F8RJywjnQ;e5w^8YXXsVkrW96@eCVgDNu_%HJA>c5G=_y2&v zk0S6n^6KA3;71SmUqoQ!#Rc;B@7u@UKRd|Z-~IyyMxJdwqQJ;s>;EnS?;}qpko)_{ z?JeZtz{CERhwYX}4*2Nk=zqxpZ~q4eywQnVFG4OZAXn0m3z7dX958aG2087uI6FQw zGc!Fs{fGi1hliIYMjk$OAe)2MYZ1<;(vn0;{N~{D%nqpB%8DAd;08iJ(Rj5h3C5e>h+a3?vH5 zKO!&@fg2y+e-nYZxw-!*DDeMW1a<@ddH#R?FQ#F4acK1a#s7us1&x72{=@&}#~Fr! z3jX*0FJA>ZDXNpL-0)8B|Hc2E+-Ye3SO528e(Qhwzq+J>&0nvFEG^~9W9)PpBOW!2 z_-u(NYz{K|gITH{!pjsB#5#L>o7-;ttZrrYDXrx zh-q}|mbp;-eZ1xq6YiEPL=?+Gt(lFbikT zzxls`2U28I!T;j_F7KpS7L<2;DzOUD`@7B(m%4bYw9qGO=#Tv4|6=CkZk-4M*s}Eh z?*GbJYxEcXi~k!XFMLqUiH+EfVEw9uC=-v&$SXfSVPTF5t~orctm{CcQGXDj9hFA0 z-Nh_H;n2-{^nZOvDr>E@yTNcyA2QP%uY!zR(k4_>Qnrw4<46Cu{!Qh#AWT?K zuRCgV{FC6F9IUx|M_P>Ph_TODrCp+$BDShuUA%K!Z!eE(lkU{6HlVVvBx~B?C2TKI zWK~V*KaB>WpY>g?N0|*kcK+7-fE*wF-=)b>nk1-*Xm;;DEyc?b!l9_MK!VP{=Z!pl zSV@D3xJBnl(W|cY$yS`T)1Jd0Vce?hW5?&S_=|R~WjtHQzuhEX*#B8b&@#%LW)$&g zk}|*J33SPNMW@c*j(y=St@L8Z&fam3$iu=FOIyIC!t7i2SFbDN$(5>)!XV!a3WiLi zBwp9XfxRUbeeV*OGKOE;e(d0)D|K<~V&M7K(U0$wD7d%#MNw2s8%&j=@tfcH9OAca zs9y=?aCI7W?qte*yP3#MGR{2sjONF8>X-ks`4H#_YtxuP)Q3fE-DIXXh+wp_B1KJX z0nEGO1QR6aMu}>VjeTbC&g+i?o{Jp=eIO>2fEUxpt>0prN0m_^}VIM{1CfDpj;-2MS)6Erx+ zHj{1Rn@xyde}ZqB5`@ppP4lA4Li#DogspN!2EP;n+B!0UqI{Y(%(k^T+4k71*YCa$ z0jMu%f~nhnqdfzlSPJ1WRScNdixiJdL&)m6%(4Bgw-q23nYnM!gDw5{DoLSfX;ECOPHwjPcmh7 z;d}(?Jv#LH{bFZCZ&86bj%|o6Q*7O-Gq}nmOw?f$9EMqxmY|o(R%8kxiqFs56Q!24 zfyauT=3%8NLa>i|!Vzx0p}kN^V(ys`hSNzu~f%k4- zft#Z4rS;{jGBgmY8Sz`{nPwn}^bYM>UkaD|pT;;RR^XH@tr-PGc5#jNTR3AOfUp6S zjgBTh84$%lK~HcLuD~vxuR@EwmZrSi52c6B2EOi>X^@LPkR%r3_yXR??cX0_$vNon z<9>&T{7~cOM>JC%|AQO?1BqWC;%V;su)65dog5qa|9%w6Q=+fQzF-x&lxKuEn#fB4 zJ!=<&Ivq3FHNMRHo%Fi9PEL}LK%O5(73UI*;LDC^z8M~o^j7{9`5~q z7{;MN^u-(3v>Y?z~;7 zi*2sbun!X^ETpbTYpyZ<7B2FPf65#8-D`iHpbvFY2r!jmfZnkgiAee&KYv5h2kdPd zgTE^x@(l^8YZgMT>67cY9?7-rKV1ZXwcS{rjyd~XLTfnby+62f;kg6HDrw?hl$N?H zj>>zx5Q4qO>cOTlBLID~6V3O~(|*q6hL@rTOQFPzga7OgA%NwsD>>r6YxEQ`5 z@I`@&V2;#;A`gjBWE(VHwi15p`$Oo_D3OZGf|3hb9Q^XkAm=FUXbbbt9?>PyLwFQ zMGIE&i44+k{9e=b_x%6I(|y0Q`9ALBzY{_1*qhiCwfBm>x7MspQ7vlJZbIx)tEHs` zwOX6nH1;mFSB=`Gt(KOe^3C)0{v6+bAV1v4apkyk z*lV3*JkH#Rym0b8zsa7oa(4erPPmwVFzal-5_L4t6&4{N5r7DQgWH$p6qv>K# z^A~*+xqgI3H{F!%P*gC}wzmCTyLTF<9rcwK7kmlbBn`%Z0VC9d&#RNRTIWJX_F~72 zj{8O$Uh``n0WL# zt;}9U=XsILxaICA*c*=R07H< z(aHP*jTWT+DB#E+2x4wYOkGM$$6X|*go50x6SQ2KwE5!0I=}p!OOR_y>QZ+X)+S7gnJcH;-|3& zBN>v#phx8d1OcS~GN6Zvv~AG1o4s_lzm_LV(w2FO?$USeJolZlwDTqe9Cq(G^W7!d z`k(RYpHW%q|2Z_05*L=zQkkvLPS5xfhG%2%!U3>4NPZWhmc)KkdH>r|CQDo9F?CE1 zqe&6H-Px0@aWA`uSi84_cC{Y=fv@hN$*Uv5l7q>nr5UZo;9zm$kGwE*=WtL)&U!-* z_dY#*%(EquN1` zj&i{~{!eU$`@8*5Y@HX+#*3|M&Qwb@h{Jr$s5qQqT>u%_g{*5@_p!9`50av<0!8Ol^uhNdp4yfW zzbbmwRP^*`M6eklVE}sk4n`#@b8K0xQJnP4S=N7aYldwBi38yl`8o-(}zeGha@M&0Bt9KO1a()qGI;uB{#SFhh3mXxl&1e^mLQ+u9V!*xN?F?PO zndoYhm=s3PcS03y2J`dyPi_sn1vfLeK@3Mz{y zEwb_vKl6sm42vhNWQcUA`7kqqU^$w$u>DYYeh0fkhv@&5)|&s6))Rh?6LRc{b3&hZ zjsy&Esy;)&^z96cNK4|v-*pNW;R70-KGIJ|Z=;sW`p5FePz1qnVpeAu-Am|Lc&9Z^(m4>P^bd7-x@V_F#i#) zHJ2nA^hN+cq$mw3z!rXQZ(w6B;xb^3j}gqvdY{29WVia>aaHhDjL_@8#&?2MKMh#5 zmI4Sr5j{?7a;#{o?NfB2Wsrr#djBW3*1lAB;UceErZ~@_hk= z`hY*>i2u^N#on%EZ0k`FCV@yjG8qB$FyNS6LEo`&<9X6{KjPNS+nkD&j$XSCq)T2f zoRD}6IN5^~bXLE$4{jHHUosx~MyWkUp)QlGD>Izc0x0OyhXr_(L(Dp>uJVe66FWLP z(-%9R-Ri0qMlVEkM|~>7CBafg%_ea9P0aG<^+Me}n%(`+yXWx>N$nldD1b>Ik~jds z!@q=|+QkFPryumhCHBDh+YiTkmV~kPKlA;}(uuiH!w8$LtCsC|xy9ojjF@{XPO*rC zk{;nYh*913VG)oFL)<4NLVX}D{=lizOH-ZM?AnV>?maSWXJzY(0e$Grg$*oIJrwV2 zvCjqaJB5tie-aiKxlZ`biWQF>_`u5iUm8cmW@riPL()ohr$=o~?#9q%@~F$!w_ItW zU)y)!X>YeY1|}U29L~!6?T_14 zs{4E=Iv*V~TCDW}*B`#(uKM)JnGCC8;J4&V&O`SK3Q!ZFamphPa!2h0MzlnRliB+F zg~ueghQ!T>a;}H}<`0DqjlMGKsZG`QKhA#cJBnc&3qEd)LJiAQ54XPPuM+7&RSwlD zcQ-`R7P1W|r4Bl!j;F0LKC6b&_^JM0w`Ym)6&oSO`wb<<5dRUVOZ9|L9xgsi zU8GlDjCwu(ZG7?NDf zUQb+Yr@*Qt)JYe&-!`6xf=D$k=Nr2}38yZ5)GQNBtWADfCT##w>(es%=k!ucX>HQd zn88-XNn3Fk$~jnVcGTJv{Z-AVh5T=G=f`Vs6LNew$pE6xpJs{0uek@`II2XOjN&hdPii zGEXWkf2LhEhFzRI2CI|$%Mb3UY`&oDt?FK>c^LcR1mDtvbO4l}y;cotRyz*2)oxdP zU+9(&0LLeUE=H|z$Wr3d4;jvs;O}3q-q8;{gc0~tipco?nI={)TkEV@AAh(tMX^Lg z-PB-18$V6e?>ycY1$%F{R*L*m|8UvD1W_{kd4qi&{D}ZJ4S6RO^=Efiess?1`(j|h zED_GU8aoQeW;!VT-b#srIb=}1JRx{0PF1O}A57U1+P(4b-v)@12#1Vsfg2KTy@8*& zO33=zwmho7?OA*Cb>psI<0H=o$0IkLqc#rDRt}HuG_VIhYRnnzyl~XX;W4xhoR`CV zkQ8{w@XO?vpq|4%9z_9F*sY%CQdL-)YGr)OgH4X_UsS*EIDX%Y{(eySy()zGu^DmV zrq5f<-dEKhRSOSdICkfHMnfn6ivdM`-v{@WgHd1KMjxBLI3{}L*->~B*m6Ry<^i2L zp)NXs7J*Lw0Uj?v3G9Sj-%qHhJVtwtX_deIbyTFj-fKI1Y+bkuuiw4LvE}-)*Bz(2 zm#7N+KtjyoNb74)UiNzD^XS7$Z<6mABEt+a#hYJ}PN(8(r)}V>x`2($De9951gs6n?YtyTUJwlES!FO)xbQ{X?3DQ@72wZ zQ2ZJC_sN{|+?iwV;g3K4%sIVDv44wf(BKoYmm*o8p<&VRR$)pJX~_$E>$ zyHN+HGNhB` z3XSXCIpa50<`wCrX#y{Pk7qvFa~e&hE?Tc-`t7q&bFbejZ9WKRIqD|*p*t-?`f$x5 z>=6<_+cu>2&%&enbK5y~x$ZS*>OY6eps!PE^;WCXF38H#bnxw52FvdQb6qu2>IEConz8x2Kc-Wq(&;49 zdF-Po=;v>==j2Jl3Oj!AKS+ z5x+KLVDcile=Iai6Z2MvTSK;uIz`x|JKY|}0+|^x1-nG_Ye_AGN8|3!ciW}t=?VDS=`;~rtYF`2Dg-ZC4dC`>1?LpoWYpX`K zI`{?ESTvdV}ssFjt zAnaGFNea~Sig+L1;p$o?okS-*J?KxxZ6>JF0RWXU0n;y@5y06D#C;u0HXv1q$f!`> zQ=kebL}4H@!&({~<4KID5=$(T&MjGsxO@8d*t47&Y|Bba#RGXYXbxGZ*m|>dGloQZ zh`?UZelW=)L}6j6?Pa9KW1xQUHqkHg3BH|-xB-voN4A;9idxBDM6`K&|Kmj=8?}_8FBz4+i zxj(e#Z<|^u3EDPDrkuS{X`lgajqrgVqMq~p8<>blmN4&NC7{XlB0xd5*?%L6Ms9^j z1bX?xBMydC8oA8vDQOBhMYEMTe;LJJTLkq&w#4%rV--h0gb;~O<~a>UF{HG&&LCAv zfgQ8rNpoDhcw>us*{FoUN?0gQlRd}`MnH(btj`KW`HxvEMy9}>obO(5ZTPb8Y$+}tdd*|zEWBTz9M-k0?*O5FU;=Ut3^475 z*`$5ov`%W>IWymYQ}nKuVtmjs@KvVn#h`%$TM!IycQM<$J}@u)+B2;4r=fyA$y-KY z+4kODi>TMMch_5((a-~+w&~L!tp~7LN3+^W!rGGPE6#{&>9D zLs?bl+AuErt4FqHcRmStYnC8#EycAhL@9B3=X1TIT-)DnKeUS6TH#qpcWup`$A2%K zGU}};`Ji8$Ju#_|dKW7xiEg9$x?GtpYy=qgs^cq0TyTXK{9+b9`T_2_Rt56|3&zk? z-Evoky1Wq$9o&)QeP1_z0%m?zOxE+D>*`Y>9%%uKU;5^$cHE2#eY%By#;@0$S?4_w6-nR%Vp{mR5AN_I{5CIF@_Pu8pgO})ep|L;u&;Z4htsUib8}&lO#sMz_7Jib?$?@s{aIOxVRa$?$;kSo;6tkCtL=}1>(%=(^2oL| zQWD@6?ouL^P&eZ9qla>L-?96}P1*C#u9u{u!u%p5I=NpaeX^!4sdIO*{hXrK_)HI(J+&9p3ia>?UA(6^KrQaJv@w1 zfkyL5#(D(222RY}3{Y%-4mu#`51a-?o}`K+1kYz4tFNq4SzRz4*mBm4m_7<>(Ih?u zHnn6(xxtYK>Tu1A1jcGd-<|mIWl{wM<%)Bn7Vj4r5()O|AOD?ll8vSn(-Y!-bJ1iN zKK>y(V%1bs(qv+rZ4;wS0U*1m$=%r|JFh1`JqnARz{08!I%@7}SIdn3bPwxS8LdC# zV1`rbDH)v5&zIDMYDbq}l|?)DHiRUlk6lRahYrarpCm-Uv{;Je_2BAex~$UJs}16( z7lUfizfv~9zV(Q|^B<^IDsG5?;K}Kq*~^b(3R^Ex?YekYsOoQ zp#GMsooQkT-LaQ$*q??dn^hF?wJI@0P2iwe3xlQb1;}==RMiMV2Q}8p*4=UC-KM4~ zW>BaXp(BtTrYlYm*cFL6VeB#>*M0p;24P2u74SAL*!}$ zQ6C{-Un9^mBlOJcc7dU}2l_gt$27pSI$R=>1WKaSHEO*2up zquHy`$l(nT&Pb`u5xjw}^gKOKg%zk#o%K^e1`ux$WI(diRsIFNV@`1AOw4gM2j1 z<}d(mVeruhLcU~b_;!$js-?p+umQc zMrtPNv7}SRfN92SdZbj}vyR9^TE^VE8$*%W7pX2MBhS1D9!U@hT(57w*1~~wk+`t4L}q_>cerYJPFwvu=x{!nUN5l79KRMZ z)=1t?r_@{4RadU1n_Q4gu$k>4jxNCyz4g2vBYMWCogbQ@R1sAO&|p-6ZmC0e6R(W5 zmEi-o@g%FEa(STBEM8k)ig=T@>#VG1tvwm>mMxZ1d6U+CTEBI!wOP|}z-VI9&~UnV z$X#UOEplAMn_wbx(qm-2w$CV{3)(0toEZw-8Og#`(;4T^i9J^~F10sOAsBrQ1x797 z1uKW~T^=$+6X4>VB2*+>P}(%#WXGucfz;#|qu#l$!ug%Cp{^v2(#gcrPJ)asj|=J5 zHNzTT#z`NYjOpCPatX?}$IA5s6*bOi1&k6XiiHS{V5&?LFoUj?e?ueFIU2n(aYv07ZEZ*!TU2SYE zNtv0qy-1mxV#QS@#qPBB>9hdYd~MC-nK&q4A&y?f90f&wIl$l28|L|#_c$b;8i-}K znQDh3g`Q94XeG9l-s1dcu1RX4#bUuoZ;s252MoF6T^wdMc_dsDb=+5^K&t~8aKN!W z1qik5KC>YEtvpTJ%^^A~K{2bbTP9UzaY~nTzhG9C9xCYd%v~H!e`iYNRQ%}`lysA} zsC1V5pF|ZmSS1G;BATMcIj(exq^U>agofg1KprzxZV zFtts)+r5dq(=QE;)zXXGk@04?Qg4c%Q z)`n!_T?7d=kzgA6yJ)10?JAVqi@@@rISK?Ze7=O$t|lE+F8;ha^VL4-&64yyG)kSw ztA9Bx0Lg}okpx z^?;K5$H?lTEd_~AgV)^UiQMJm33Qy@#N*xch&;@Q+>y@idhtXd&K@@LWa$no!bIBs zG0!JAeiKe7duUrfymwK?@%Nsx&OEe&MSdpD{$CCBh618(B{&*qk!n4Q5%g`kA9ZI{&u%vFk^m?R#RbSR*xSidkByL+Q z!i{=QsgI7N6E2Uv<4Sv~c&6u6;cm;uzSR}Ap{~=T;aFp^E~`?Wcxp@37W_r$yA5z+ z(1CEj{M_;9w~0~uf}!K{50h?OwNTP}=7;RNYVmdJSKU^H?#WsPF4UIR3^WQ0-2$?S zUj*ZuCLJu+Ip{JFimL8v>pR^1p6YiQZ9jULKEi|F4F_wUcAoiAOx7*E?N2$LLFM)u z%y}^id1%|bcxvcvf59ggg#1j2QposFn*@7jK@<~#Pg{bYAS5hy_knD0>`h|S?o6o+ z3BzqAoXlO1?ppxX00{8hNFqWy-zF;pu>dfZ5($^u6 z3eDrYNZ|Z`8Y@(0Ga(lm=gX96cM@0l$NOB=&ZMQa%p~#8TWap$J=xyj;zB1U21Tv* z*MFB^uj79zZ=#7S0gEM~t!< zRq#pUNKrC--EQLQO!;*d$@w>___DnSB_HFrln}KUuTBU^=n+R=b?_$O;5131eUsfW$G6-*< z#MqAzZAF9ppmF?A0v8}2wE1v@0lLZXC}vu9O!oU-BAeUr8;#aEb7UU-Dn=RboLA5u9%_x~MsaCkVPb9D7cK2GQ5tgOTI&5p>+ zSs&4pbZ4QBZ2R)Nk1B3wn_RvzV=1#xEJNj?1O5E~8zAh00D$2QRw&a2u{hpf#l|

7HchEOpfh&ikPWAyA@j+C)_hQJ5L=J*F5G^dJJi2YVBU5O7hqHvZ=*smTbX*<>gf zeSEZ@oZMmp_43kjJToc$)z0F1r&u_p9I%-*O{q%bVHix2ZnbGm*M9-sfhCg?; zzTZO!?|ClT4IfoGPa8%Bc|SYj+67{Ae)$N{xh4d;nL;}+e*AL`d6xKQKRo33x8K1| z_fs>7Z4i&km7fGrRXybl+&T_Pz-D>q1+@1(NvXFG2F7sV8w-pdj=J`s$|Ho4C-H`f zrwt?_$W}^JMQCtKaEf5HAxrYy5==&ZD!2s~R>&4@cxfd3Den1| z?Hevil{87dfC~OwFLt5z7-YBWeahc-P;-(k0uM>`c z;vMMFCa2J5s<5toZZ;?qi6P6EHv{XWP>V_$@CG$3NeNr%CJPdA$g zR|{_tNYvQQok@t^dwl!x{ME`-^yWr5h7%fn5)B|x;lTgz|MsCt86|xW>f!jjC5J_| z*H3Pp6oKTw_KS5(NvYhrSt8!Qc*jzy1+u!%p5)X*2=e10SKAdeV35H%l(hj50Ulk~}^a0ExXEgV02~?)W$N7d$ z8b76G%Pn|zycpy(mm#ObkuTvOAHCz8aP;RL+5Q>@!O{1$fYJ|7&k>imA6?5kC-EqS z3iFVc|DTGnuU)(}uNC!9RS#_YK~}kQme1+2F1rFB!>ioYn{N?yZ=15oTfhqVBYt`+ z5c-x=3U@s_CG?Lu6n?kMg?C&KP$mYLajD|d@;OYrASg4<&u0`Ap%+|m>N!)hW zctXCnZQLm$g?X+iT(=%C6G*HqVN>M3wrwXU{Aw#D4Vo*CO%c2abx%>{Zr@2Xko?P= zu2bvP?*_H|n-OEpqT7cP5?DJmmE!eM;D1T?lVJ!95rqwDL^(^LV#WUjP^r(LU10*? zugg%@sLQ_s7!;|ZU~wEvxL`@rty_AM|3pdz-((sn3Y9(o6Q;`+T#ZU7dmVm>_kWXp zym{`pN|O=;sg1YZy?dc={i5!V&Y0TIk#ON!@Xr=gGDt%`Rmh=a6X~0U_v_27XqKsvkcqXUa@t;pL)nHc4L;S*>z*Pt9CB z?&n>&B`7b2f(x-!q|niyLXUpPNyB{m`w19j@LX}9rqi=UnfsolXTLr$CHZe4 zgpVr%^`&ON%`@YWfpQxKgM?%v*K=Tbky_`zK20hP*>u+_<=IyuL+=wnpJUypee zS!tB(o4xt7@(M@Tq3@eJXUGdtpE2CvUH+_S3GP$9a_D-PbxS9CeD0%iTNe-(R#L>@ zrT&82a(*|9R?NaG*b1dQmgm$Rxw9tf*P!{T#U$PeM#x2f~xzkzLWIA^IV<3U8c(u)_os;`V4@$7>?@3gnL{JlNGKIaK zT5OKEV>KKq%#z(3hxSWkNE%Vga~|MRM9UqEg8?=dyp8I@>UhXS`9zTUml>An@2nGL zFcTg9go~aniQ6yA#GxkdOt?)ol<6y1s5S}KbHWkm=(&Y7K)fFu(NMsmmi zNKsi3z$~AEwu*3JO<>fIVfw-&LRZQn5QeW`6;oPb^(gWib!0uWxcsX1Xnl&)ys=3!P-lDJX@32BZNTW{q{2D!m-1u(OfVifJV5&sPuR8a(pyXEO(etWMB__A5?1z+7nx?s=rZ9+ew_4QlZ0yw>nVmvX0Mlm)4!>hmJq=K$tf>#ovu)S zDJ1l>3MPoZA#?rZwFkV-pcyHqEPNnjd)7fr#Jm2nJk?}>MgmxwweL8S#3Hm*rF;1&=R^+Y2sJ!oFk+zT!M%ZSLg6d zNP2oL-neg1BBBfceE|#%K@^29RGk@YXKu_=OYiRK|5E#up;K?a``{n!Xg;~wt$+Ze zsl@SMInD?X()q8@JS@iQK@S60`9XrvjqO@0FPF+ugNv60$!haGu?D)A+Oi$uNKhz< zwPE_3AFb=Nrx>oTCbCBc@vI#OeW!3K8y&T?n3cXPUcF!}>hAMbEC23JbWky)ZeIjE zi#XR zF`O9;k*VAw-qEVlY=>hg<@5Z6i?{g^AS$owugoWacHHv_*BG-}H#Ux6Ql$!$*Cx3g zjQqDxeAWh<48nlxi(#HOMsn+2eYB86^nG>(`@>(Y@aMck3+T0-go9HGP8+|3*Qq-( zZzSeBoT5ef%+$fXbQ@0)^5B-aCwdfq4U8>N*B$2AL(~XfV%Y6*RH_ z>x4xFTsnrAH|C_k;cXyAXME3%3u=)V1PSYD(AJ~73?L^*%6_CM_F)gnurjPDAFz4; zu!_0ye!|yn&SY{~Y-nIoc*Ym1r_O`Qw?BQ&`p8_DtatWK^ouoapRi@drHZc{5eviuoe37g>xSf(l|9ne80Jr{o|(Q_0Tu`$}_sTe6XcJSOWkwfPT|;{B`u_ z4GA?gVejU!YIwb^IlOI-{Y11YQ06#m?&Sb+LX*0II=rW?xro905nEyBk-y)kMKMBI zea|g2<^jzw_osCR4gaM*P2}2UA(pwP_~;8)Hpbix-ahW+NPYFCwVU*5IJVP{CP=Vh z4>&-%&A$#1Yg^rKTanjCe_!Ex2bGkjKjLaTho|GoZ9qzVTj2?SuTH2-agddKv`HlLs9$k%TmU>fp9_BVX% z2zex^xHTw-&v^3`1dLTVkU!ocTCmH>)Pe=Y$nErt)jO|?a$&wXgsB&!PIP45!RlUM zS%>27fO+xM9CFn{(nRCg_E$G|oVb$nuRuscCL+yHkPI;X<1ZW4b-(<`78_00e`qN@ z=RdUcz-84V|3e&_Nn>S2AH;m)eCvA=Vq(sjj!5(W#L_wN1tIH@EqAnFBExi_v=M=* zwE7i@YbVJ8b-ndU0$>nd=cDG9{IW?=lJ`_1AyB+Ty}*T~mMiVEYgHVcDv!CnM@(Xe z#wP*^Uo8u>V!s_X)o?5UvShZ~4ju_PgA}i7Z=6xPNwaV(#m5ywp#n_kd~DJeHZ;^{lpBmC zt=Ev7Bf#%=qDUZ&kpFq3f|&?%1Yang8;xZr9bhu+SBcboD>NX#KEnvTqrowZJ&v_h z-BnH16mX`q%-P6TmkaVaYaS%ZyRZ5Ou@UKXuH zQDvayd^vz1KnWWIW5Qdb1m+oFxk~)k7U&xPhvP)7APmKO(9g`|q3-h%3>{$*+5HHc zf#<{u)aMCg;QD#oW0bCU%#AsY=o!3)VoCfxgh;g@K{P~`#A?Gn%MAGYHRJ#+Ltg)r$ATlaR9|J>l49)P>x>b#`+3P_ zFxi1*7WB{G3FMV!DPIkw&%owZ2(gk7g)0DV+{(FN;8<6saK>cc7qu!4b`L- ziC1Li2UDu^itqJiZBShkNJ}3(3FBM z1IT%b82aMc-#2j#lA29->l`w?jxI6RD|OPh{nAvbMM(P9p#2vMlw2+`vOyqaWG`oB zKd;Tv*e;P{RiA>+LqGH(d|m9u?%`EP&5<}SRGwFkdzJq>RtZw?a54nA{~uTyn=9d; za5+eV&4p{#A07^^)PN`!>j@LMzWJQ!A=s=G%d9MLe7C=eVxHG*WQjYNEfdhGGy0Zl zAo}pCXZm2V(KOnaJm)69;!)+axY6;QJ%4SHb^1*dljbH<`S&(TG_j+n=i6S-kiGjo zG`JoMGQlz$zrn&P`~{*qEE24Wpmr4`a`XDR^GI7yh?dFln7N5rIUdU`^_a2n>+kT* zU>bDDS{(52 zmpC7ftG<=sl51uBFLMF18EHg~;141pVf26OC!IRlC=p>bqRw;}A2iaDk=WsInwWZD z_Ca8FMvB}!yfCev(`+a|tS46_mH4Jf(G5o?-x`<{blRDt^&iV?C-ma+V@X5X!s;W5 z(t&zWl=4BpQci9IIr=ply7>EOrF63X)b{;AnhDJ$LJM8V$*_V4A!nfc;Wl&o;cT>cBLxyk2ePdgC`4&6En#Vp zU^T3%uy{Iyd^*>=pAHk2626ljIbMzn%e-=Z7-hu zNtlLr?r$U30pY}cl}Z9}y1nmbCN#B=?Z*e7X3#lIN#cDu{JP?A}XKeLy#M{AAX2qc*P#GEn{Hjf8XpPMW8L_eu&^N zN&UPZ@$c%Qb6;i5j3#z|OsK#yMs56d5-AF;lTW)pAaqwgl@%T5)aJh*EIcCzVigAq zpQPv7-M*2(fG8Mf`JU+!kYqR41glZ+9cakJD+4Xo#(5C=IhGG-ya~UI3aBn zx1rj25%`xn?5{rZZ|eD=7G-QfQ>cChIa?QVzHWQY56SkiJ$>n)v>%u-`HKqI1awz_ zi%iesN#zYT=kHPuWDj3BpsNgI6ib{=eiw!YlsYG!X3FRZR6J>~AY05x_~|rIf6X4A zWsN36+Ei)$eM>7>x!CrG*13BB)9vfn#|z;VhVhurzXfDke9RqnMeW)cIjO$ZQn8S4 zF`ZOY8;w%byx0B8h=^t!Zm>C`)9I|ZG&8)wl!&RcAeQ#3&gntVhm*Dh$96Gubn5#K zp3@q#_5i~Z#|eb@YtI(HhdSb)F-pqs60V+n=xB5b5B)7lP1RNJ61lY75jm^Pch9%q ztzPd;cGdi<)%v;(>@b&%qvq5c5QA&4vY_yoN20MxQ@1V=wWnY6S_uIu2?j~Kj1!p5HnZ0)^t&f znr_4^9RD00I;(y}Xc)ERg?BHgg^wR~x?U;G*)ND(6EIf(n-z}2w03v?AaopzSg?%L zuJ&X%17$u?YSay1vd2Zv*tau$otl+ipT?137q5H6-oH~ct$q=%+w+O@-)HNt z{rh26=4N>hdpLfp=ydfQPH7kK-z-`}?#-G_U0r|uu@%XA?f1N!+L&Seld8z)uAc&& z_YxISLfMY=B2uRduvI} zTt+XA$U4xsV7NOUw7AMlqAIh>(-j{ZV0PX<-?C{Woh*#YyCZ7XLjJntxsqJ5MaPpL ze_+YEej6G@UI-F-{Cn*Dd?Z(Vl;-i*W1D3g(cPvOqppQMw)IX^+MuTl#yN3j zgr(*cp3HU+?^nKh*m9^Vf^_{*FTg)yQDN|~!SBZx&s%Il0i^|QZ}0YG{eHX;=Yz8U zEC>%qO^$YOP_9*0MJKbdh~08@0d6tz)bpAK{hRuux^b#?GZ!8exAbkFQ7|Vi8dvx; z-=OnL8_!py+hqWE7kD+93aHydxbPGEl}z)KJ?Qh-AR=Zt`LGYZ&gck_r}?DSuHin` zzb$`Ek{q3?fOGC0JV~xY%X63N_fvRRHw=zPvmFo9n`(&;a$ByFjq<%z{3Xb}Og6)> zeJSK2EacSR$VF7YX$-KxU#lJ7?Bn&HXy0>ttROIdW;iOlwUabif(fcK$^i?O7s=Kt zTh^YJS8k`BVb4ydlx(G&)wN2ktT2k(1rI*z?b8@Q4J15FD%#=SymjLr9|*i8yX;Cc zNBLLArqkV4o;T4&p=G43RoErljsCr&vu;F_x-L4&&CFMr?3T`#YF#RLl$buveqT)C zZ&ae;mJ%Ey<7+muvYrt*(dsuYp@ zX3va!o=Admxe!q?k)DD>&V!h?I~n?tZ;D(jXlzxqENe95?7TTl_g}|8nzOR;2nplQ zd#+lQD3?F<{P1NK$KOh;O9kHjlC91_0{O2Q3cCqMiOpWy;eX?*fY<)3*_l{Ulj6d1;q? zNo{FcOPhE4nES8ad^Btfb{>6LQt%s%yr{@s+zN`~9jB6eoAX0nPUUyVoyz|ErRTTr zoivc?;uHf`tPOMj=5zer&)$F8%+9-JdX6{fE>R`t+dS)fv2tHCG`vpw01xnc>SM~++*F9K!+s_ZUciqwyORSf*HSUayotS3-MxSo6|D` zlXTKb{qNs*!4ZqQK=ytn?;ICpi6I7HOzb0S`4Mvx=t!n3S^Jb66ptH)Ys*4u=DLL) z;Z~g57KjAJO}P6(J~M%JWgmLyBuvhV&FIEufaUFAQevPJb(#jgK)Vg$P=8GsE8U}L z)N7=toI_W$$HNeQM1zA90(Y^=kLF_8-oSbhZLriQZQG1SdLvX{ep1F9qgel7iCAzP z7K1IXw>YozN}kd!=j^&P2qN<)b$b#=IjJ#78w8wBvvNQxxluFw4IN{jOPUAcAuZP7@KSHGsN+VdhVQ&yv%rgU6FYSeVj3zhpd+Y0Mwr6vul8k*?Vy`|b zS-<3G`SvG+J!2Y;xpooktLK+a^2 z;-gDJW zI?ujg*VI|$^?;1%5^m%Kls0r!-l@5Gr|Rqm<}%(#*odbelI%b?mWEZ^%n4BSNIW5k zH6o0mQX}W3IW&U`ptBZ>Xo9(DVFuQJNx6}p#8ss{q>V-i7d$q&eFIU!}usOjT8VFF)*kD2yWf6BEzNh?a-M(3C47- z$=XhT>`0QbOnZZ7`Ujw0wcCyBq56$i4{j5`8(RzbLP~|39uCI!QbiRE5ljI@&YXaI7vVH>c+X?0Reo%XA5KpD*4|Hs_lJUmBDS@MZ~eMnew-g)4=5lATPbx zgT&wM)3jlQnnfJ0Q+TP^P<{X9jnhf~mp6vI98j<$LK2Q_Qvq;|I4RIGo@#heC)0@3 zwZ790Q3yz6_D3}8h}!7?e3UYX2rWa#KBXN8b@N$J zIQ0{Yo&55ScYbyk)(dS4)oq7@?ZtOWX*4&{61bP!YdzmMxq1S8%=S_=m{25LOv8P^ zH0k3Eb+T!HqO7{>Y)hN6(J$2_+L9Kw0<(PCR5fokYItTOc4X>gVTsHIKhr}X{bZyl zQQ*&XT7)}6W#w0in)E-D)+?Ce$WWYFHD)2S@TYF{$uqaCEzVi$5qV#hW8QQ3D&zM-D9-HCv5VSI z6D@LO>?1H43<#=z0Z~mAAM`CcdW}2qZ`GBOAvpOm4P5lAK)KV*4st5s@IE!)X&}w7 zV4M9MKV|Se;J@txF1f#>GT+s6o<{EQIsF}XdGzZ=pfb3#s*k|6FfeDzVPEB$!c-K; zSvJAF18qiy(X_&#bXxWu*+g+*gG*7dl9+E@H) z`BP!Y`?}ZP9^#%{t!_B3X=7i14{p8sypc|3QywXuD7U*EZgD{mKRo6mx!sdCa?@4_6^A{}X9W(*Y7{1*!+`*4> zJ?ve7c!M+0Z=(S-IrRQ=G!`6r2Y`41#+X@j2`na+e#M2ue~VDi-#(Pv^pcBoX)1I= z(+s*xz@7@(H-<2h_8DcsW4IWsPKKC9*&I%!%70uN#0h9qNisc9c(_rv=xO$Q_-XZ_s}Koa$=uq*o&rS7&V<<<%F`)04zd*H6v-&bQ6!4rKrl7k>p;?N-~A&P*^9^d!f z`|Q2fI{Tb;zMTJH)|wA9&vW1R?_zY=zl8PDCHk-GBx~4tWnAfUykR&+pW!vHe?ae= z!YnZWeAn>JY@&VYZFME%P8CIybfQ=pzsE3^y4idV)&wnt{X3g+#UciIJ$yOYlQV0dqiKr!%@k*? zo?t3m;BKZM*CtQEx?*77ZnUxD|fT=-%#FVK79hqR0#g&Jml27~T zqIsk)(@DRUbmlw~xDR%x?veV~`?tc8k4{R2ZTfNq-Gc2=#`R|XvS9|hBQeJ;fzwy~ zxHvG9R|0lTq-@N{cUsysOCn6_N=&B6@5}&tb&d-M&a1o%=Jyn8ontjrUod?c7iU-xm21`P>~*~C|5!TY znp#wr631it%KZ#hb-_V5^_(N6aT+b61TBAJk|{I2FjBOKR#Up!OA{fX7Imn}C0TZ| z!e!qxq1<9mnf+kqF{=R&4z{PAp_yFeq4Q%}__nmJNVeLW$5;HMomc_piyn?g+3FfC zmyk31X+xP_&e|!FS-SughDxL9vBd8zgQwY?afgNsLrlh%hLc$)Pc5`#via)Z9IcMg zhQngKEjkX@4NMO&`Qg<{vmG=w1TmniYxGk0Gx_2XrsX{T!ilD%Ez$;$JC-Gl3OCh` zcxj^}8R?&xe~h_WoyB)b&a%{SJz>>-WQavfruITwXX3)U0WIJ zaUaVST9cS&OD=s-bR-AP=$7eoGlSk+WECp=&ajpo!8TW<)qrX1^v%oHZQHXj1Q{p! z97X&w*V~9&^G{rtj(r1XsLVAV|HNOi2(P$)-EQ)_S4ul+vO5n}}8a~+f|6_|IpDje<^w8^lxE$eEUhGXvp^xo;s z1}!|Y9?G%J`DOQUM(Il&O*EJjoqL}<-n`hC$GMCv8wBC`B>?94Ntd?lYjtgIGaqfW zE+war?q#3-=oawA;pNu-AX+}+iJ4SL1#6hI$6ZFVvyUE5mbxE*J)y_U`piBf_}*&D zwG+~$JIK9c21qWaJ-pB836k^5X>&$xI_p5#qBR+PWW1{@Zc6y^B5{mKDK4&>$$^y* z{vLZ={{1kY(SD~bVZF@+hI>pbr`2x1KiPYa01vR{FGd%;r`{5|9uAgXWV|1FBWcC~Bp-hEJDS*TaIHD| zua;X(BwBaQkm+VD$13=SKR>3-2pKOs@F`M)+4t}7V1whxnfA-KGz53c$$j(U^l~ED zdda)V!)`_bS1N37v_{JOig9@2EOTO8k|+AWL@*S@{X#zUg{(@UyebD+oGdHJ+%Y

SK_mNi+ z!*U4ARC9z3S5sDHWQzI663D^ipro8bRa6)0`OV$^-cmH`TJXQdK|q_K>>ZaTZPx1!lVj{CiAl)ti?AMLNx;=E35?DfM@Tg$^(3=g*v!9 zW->W6$)a5zz00lSX09t;2rlltys(|J>XN!Em~rHicB+pVRA-uS;H)d}hef7S3!O4n zRGU^%?P&{blU!n zYCimU0^K2j>+lvvbcJKi9_|BTug~{QQ4C;-1Ul{~5j(m2hbe(e&)ICS4;Pvstgl)t ziY9hmOcWF^!AsT+xcxzlP|ea4xB?sNHO25qlB1q#+!j|L;AMk>5!n5i0Bsy6KB>g+ z5BF7>8%nRaaV%83QgxoJ)uX>Vsm=quH!8c_sthTCtHRGL>z>i~vS@2yR*f)TBOiGN zXb*+WiStS~DSvi@)Wr(yG0I7?C}nOWxAkEmH?k~z83;bJsdHbzU9+ujO?<&vgz2r* z8r`k`V90$!-~?Z3JEQ`3cYmtms#mp9z21JNr+qsG{MzT9c+paUS8c*qjuXY!BY&)U zG>@_oM&-VPCU}u%>SOP1$21;{&!2Cn{usBL7~cq9+wPk9w6qgjs3@J(?0c@L>E2@a zwZ&o-L>5WC>41i5wn2H`4_t-aw2`*LupN#-s+K6Vl-nDEF&^BbaL2vFx;^@bGsgtd z-pmY{Dbo(_hgtW>+kZbgsLVQr%(`;yGe4Xxt$aNz@}_OHr<b>UD=B zqNws`0Mplc-p2D;42H`hMlb>2K4>hJ>lF2yu)iVeZ4*VV?Ji9upf;rA#y>5Ip!ddq zuul%DEIBoP{@gvjqO!bFwERV7qVRjA%H3Y!yzfH;DFd%-F*p zfjX2f2FV;NY=SXnfF62r?b+hj^0Rdoww^GZ>3irk)yp%wh&e|MSjTGx{D z)whGwlS!P@G``dF2+H5A9D5+<;Agw$oIsl|OPB0dPMm7x8lK-B3HWE!(YJRGmE_;hk{TSlK!jj`dEkT)`usqzZ;h_1D|X%+-iDBcypWF&X!wr zSA{8-O(~Sx+QH$qeS7a^mkK*Iy8BzObc_3`iEo}75E*O>9_)6!=qtHkm4CHYk#(Q$ z9{n*F|6*6rS>vrmPp5_k&@pfBu~RtTlU)LSaY4qeZ|d^9*wEWgens?!1*I`Bwbj)8 z84gxUQ&s8Tw|V1Nl8V3nPW%0R$(NOt51*_qTL1QYV;8c&^Sd-?msmSg;$csa8ikUp zQmh2Pot?^Vyr8i+Rx_jM(0Z&?_N&w5TWK~MnB*e~>E%RE3GGjHVd(R*oPxKEil{u&063hqZzP|S?$;mK`;hBncja*5TGxVt?U(U)J{Dx<>C>etc2a=cuf39`@@%OmUJYbwP=UK~tHA2Ysz@|eXx=@O%M&aq8F8RC7IfwuJ zUy2putO=PM-CS$qkj)hv9l8+d)cchouRaKf6fCM0VP+ELMcpsYfAs&6BJ)Wi05S9A z($8k<`}z!JjOn4zR3z6@+D*#VJl=(TS2IxyL5pnc<9-JQ68(^h1Ej#WzwuMD50m1? z+~FVCCojKkS*Gc?81eR^@#oa^LzD;qO#FIJCuoxq!jm?)7WNM*uW5;I}67~p~RoMmXn`* zp#vN_n#n($SJ=ux8`o7ciqiPK5;WBkY3fQnFjP#@>tIi7;w2bfBjvEp}SZso$3LZ$P-A;}q7*-}=n;px$dNErQx9**6~KyGci5eu1KA}=Lhf}?1q%`kHY{~c{n1yWg4 z5SIm<*HFU!^%OlO`L7eK0 z6~7-$+wl8TQYhcLI`z(bvkPc;&Kd6qs3xPHXs=c@V`qy$Z zvMctSjQ!^gRA~E2?ClWT%K}U}xDtRJ<1Ih+H?q|{@-2rx7kimN<8E=357sE&b&HIW z$L~kd=2!8%3yry2r1_GW^Deg}jQgLaTEqvlYnWvy7oZ8MmhtNPV+rrA3$A2s`E1tC z7@+;!5G98mE*i`WYPSU*Ve)qMkdD10db-5JQt01XdMd(ZYa!XWF#g#QZMb=yqVzMK z>>3raM5 z1EN|V6Eba}oQdMePTDheQAu%`sk|dqYj=zR*u$xRHEBZxYatA~C({jw=8eFitLe)T zbMe>o^#b%S?AG}8SF&@We7(ygWD{u^=6>ct21Mw-ji?VhwpIx|*<&@mHU9SENwdLJ z{f+EIoi|v-eMX4+^|;&3zLjlml_B}R33rqbmPuFl^w==8AYtiCRAc?T zp;50Fek{xN-ii4RA3d|9SG}pt9(7lfvJ4_0txM^}U+*+3G~eYcV})||7FS7Fq0aK^ z3-l1vr_BV5N^iA@6^q9teZBh^)>#ZuwNG~PP-m^I!I7&D!xkvXIq20rFFkN}zrEcxxMfT@ToVs(tnN%$pM763liL;a#AGQW{!;y7kM7g21tfy|sp z{(hT=mmB%d;W*ov%;Qam(oCbt!SXGI8XRu2VYfbMhqh#N+q%uyrK5h^Ytz`Sq%y|0 z5398_!K(0Eq6GVqCk?OouAN)C+u1A{ZTPx$r=Vm0D89!be>vY^Mp#nx1DhTFuZBL; zDJxGQEQ*DZXd6!r)5hsrV4m|n7{Z0LMv6Sj8x7tRHwCemSS1T(hi@wX z=$v$Y0Ft#LY-x)HP7J9< z{LYIvVkw4ouAnoSqUit+DBCjfcgJYRcb}JUmX0vw&Oh(c`2KkFg@`0AK85Z_i*>D_ z(oXtCLJyK3cCB%t0^Z1h_txmn=8|sxilaX#fDJm{n>Rkneb~J%h|@w!ik~+4sT`Zy zseH}s7<=3mU*LZieCktyA+wDL8d|J8vXUy(S$+o2&F!$}j6?cWTcIVKefZN_$ zqXDu{PsoJ;EZEYgl5-ssLjmiJvG3~Rct_fC%l*fV^wC1+A#!^W2x;a1!@l-;>^BVx z9!#Oc$jiM%u?u4GRGfQ>KzIdA$QF&9^$OARqH-fZ?hz2}1o}OIO4I(I&&dt~Z>v-3 z;>myRQ-DFRQ!}_W0e%8V!8O8;^`vz8;A>u}7qf1EbzS~Ef9UMw9l>}%n~9f$fN;W4 zf4ccE5lKagE~D9u_EBm8kd8-ofdSIZ|G!YAI2wWDT{jXeospb)4Eh~`5@HU`g#af6A~}QxzGIKR zv?Wbn?hWI{(^_BouUt zV#gjJO{b3Vscnme8ItivjLNI753@QvC{mqQFR6GW-r+Oofo=lGso{NDixXI*8;h1j{~wjCtl+1At0OonW22=)&v5Vof@XoQriV>b!GT-%h#nAr+HX zu62_0AGrbr>#BsPbcK9RmO{Gs1=>{wH41mz4U}8+J>A~tdHl&!uZ>^T&p*^RmT$RP@KUI#U9dPipkTJs;xQ%1SB9a@&1W1+yWK8I9mpr5a_GhH#aZVU>{bUFW~(&;wq_7%$_imUXslaJd|izMi2$aoOrxw76|T)ntjKYz zHLM&Ng6U&Pxw$UbzuT5N3uee2C z@fyA2cYk#$>6OrnS0baYE`NR19qm>(=tjE8-S^A0^cH>pN|fB3!uu}Ds>io;DpTtu z^nmnU2T&iBL#q_BsV&kwV5zqDiKrrS0D}MLdE#(N~o6vG^!_l{un$-^4uG>7#DQokdZVP<|l%PowL}Y<_CO`l;dHo|j zZK!}o0Qryf6o-=afH(J1yyED)>WJU_2yirAgi=RLP)EX>jua(yx=3fX5jw^T@v97J zm=wCplqb#oI@-Mh?C?7IYe$_@XO0MZMJ{w>>uF0NUAxii*DpG{Y|s!qm6r%w=08kv;$-QV>0V))}PbF&OJHqKoFWioBE;c_ZV> z*AG{ISP;=M0Lt)vm}L)qzARhR9{tlj($SUSa#^<1KI$(19dT3zluYlk4-Wvk0ekol z9L%VUieQ!oJ$O5m>!IV&!#o!7kN3nt@1POWUTBCdPS?Aag`KLqEc-esjK%&=Ah?I6 zK3fb&agK+$8R3@h;)-(Md+9LQGV%j)_>Hd_wisw5;R^VG!oePL3rn>Qq(L&MCSP;{ zILHx(QX2z5^@7Pa^_!gcn=1p?YzIh_F6*v=+vfv0_Q)^-#Hb8*w?BfDB2s2*@GA9y zg(&rPkAZXdA=|wH01u*fiD0gYh&Ye1F`$b%AB?Xb_7O#A?{^hd19JeiNjMSq6`OF+ zW6-63&||DWmU`$>*D#b+#vP@o!oXDa$$w(tVDrKIMT743GCOS#zFDGg_{T`)Ga!z{ z|DGZ5^uRxsp@&7$Rvipg`-r$VEt6dgcqL#9*A8I7zwl{f8e>EE$MiCKpb?ddhUlqa z2HCMVO7Dr`IQp;DgFWcJ4<2{A_9-FWR4t_6xqXx__Q5WJ0#+WaN=ja0s6*uk%hM4M zb1EMjx(jMN*aQy?38rYk6LEMEb(E7m`YJ_?h5r;$6b(|rlZD{nx6xD~(FPsSLIEGb z7HOHgKd^rLz=4bWDKrPZiiQF>=uUX1te{(F5FdrX!C{Jh++f}KLL&me zB7j#Wi*4f~!S<*qEMn81O8X!Uyb`BKP4}-SN{SJxpodM+ts#pC`f>21)A z6}IISu2dR46^yvQ+GbBhwnA_vUn%=M2Z)2FF?blwD({`uON|rP7s=hQP=74q!~Otd zYR%^FnhwoEE*{BkjMlrlDllOU11QhaQRm@sO(|p>7L2lo6Zfg=1yMvCf*JwP+9L$t zFM?MP_phK`_EF1PbR@agId#)*V)FrV>(SM%r{Sn2FW4P`dI={oEr_nxheoJwI!$aL z(l_0gHy^65c&ly|Z4(p9YAUmlK<*v7$i|(R?>q4q9m0t2Mqu~gFY2&;3$n5m&Pi8) zbsNC##9r)xS14a`uHSZr1x{=M*sloAN2t`*7xF7}@eEIzZzA>)C0GVt0F{FN_Nj*9 z9gt;}{q0~ZK(1s>=_>k0qpy)F?HhGO-urLM-@n5&=J>k5PkvuZ_Czn0wZJ8Q6n!M$ zz>^z^Q|zfzfXm4~mZiSMQ+11@c>t)H5&|hn*@}Ie|6=d;#g>f3K3Uj490gE)*++4a z_GqaXP(c1Z>OB&;j77O8@78hBaXs9pc)3sg5=BCR!Q2P*KQN0yxt;%KYMy<2uN z#R#B8Zgw~6)6H^)A_z@;_<;>KqRb5KtMc2@9CD`q1r_mo^9nlJb8cYxOM*$O7iwKG zgK8E_s_*_j4@G|sf1mtr?pPJ=u#eg#r^$I|y@7^9%Hf_O;1S=6A{EpNE5sQ#^{gzl zxQqbqAxM)T;Iz{^;*Zn0)4!hucF>X2Da#-hx=t~4wJEw51-wv0pLHbu9)58)m)2jp z++lb6{@vO5%Li42)V&T=uh*xOameYnMci$=VH7aJbizXlknG$ex13=AZg(ql4!$H*cPRRJ)NXm|sNUJHwUgS3cmX_8ef>Z>Pj^(<~ z0}Y)7dc8*J6VxOQv?YvyI=r0hajA!~iu)yO=s$(Bt&hyEIu53&iNRC^qe@we6hZqx zYiD?_MK(R>_~`QS>rJe~K%^6S0!H8=dBmR7V>58KCJ@YCKDzydsj?hPQ@>&4G2iTp zX!La7_gumdN2qOk7=bEZ1T1uwk#S$W#f^h4mdgG^CkVnce0C&%xIU6Q?#O7HE*{S0 zvvX0{4*?27bV16Imq6in-iF>FpIwq|^H^vDF&i+AVD=+IhOSoM`Ap)vf}-O)9&Lef zqGphu^%v67bZ>cQY1#rWZ4R7KLV8e3_nyb)-a1aKQ4=&wMu>-757qnum|u1seOQ~s zKnCGyW#F%G#NPd7+$&2ExG1kmUfb~;t*N6j1YK7_lA`qM{w z{y$>KjkRe2B0z7}zH?_Ly$`8<&>JiH{9sTHxN0o%=G*HRSBIHh3+~HA7Ofw=1ITUn zjl}y}gc%=yz;dTODT3IiNd($!71_XcL3EehfV)h-;p{HSVY@ETMqEjM+H$Y!Ua@)R|Ttsl%F z%rxLK*NwgU$ka2vzb8CTiil2#DN}jfd5P4D`+NUR;2K!{bA+xC6UUtbpgs5TcZq67 zt`E1{ulubaJ|%}m3R2hsKfB}X!rrZCEr-o=l+pR@fd*G1`d6YckH&S{UnlLP48W4N zIC$4HK!BBfWP?$_vX$_O4o7gm_cI+pTcC64vFC$71ifvV9!$9t(w`7HkQ3-8u7YtY z3dH^4)0-UWxzBFe5nKM$XJ06eksG->J*iULNzNYB_lnh>*w9(h?~WZ1SoCOtgI5^* z=6ZBsk-1)joR39m+`reib8dfs*~jU!_iFNL5Jsvfpt{(;OYnTZf5@@x`_Msd*TPd+ zT{%YhD><3yc8*DR8*%AV}9zXr9lSrps4J-LdNN`0_d zG%ue6+{9n=nO6lXSpX=@>_n4!&@5IexQx=(UyFUyj2Nd>Ujh=RNe#5pLP5>@muPC0t=59#Eku+1YOogh9vk3P<&cqnSzUsw9ML`weLAWNVb zMNm8lP{zdxM&rpJ3z}1%;kD6}Q~8l3q;ozT1=O9S$$)+br`>RnizVWp%nlGe@U|Ne^_OL!eeBSj#`oIuV^4UeQLwv=|)wXY@wKV zfs!c$d)T$SKKe463vSfC5eU~5pnk<(Lz~~?E*;bXqDpU%wnDC_+cHzIT$Hovwm<;( z6LOVI*EApWwc@Y$?ki1yiV2HfAwOC^2dxyrP1Fps3TFE^DewNF&As8_2@&d70tk^| z=Mg1pW~oXXr)KfGGXb2~Aq*0n=#K8EtF_%w*UU(Xy0@CW0NqxD)@cLuKA25>wD#>& zi@ZU4+tQ9IREs#AlzXSwAZRIEG_|Pw%0P#U4s)$fK^adr(=Ry{8iEKEfyO)(M)pv8 zr@$Na&Np6=vjF@Z5vV68Jk$`ORT}PtG+I!2f?czl2A>y|-+5Fbzmu>ALNQ&fqk*G$ zxX<$M=}p`N8M+M$4+lh$RsSnKTHEa&%yM~szpmvgergJU`wtWlBtd_oz9jN;7jpW4 zOJ1H5&(4Tvzy2rn^5^O4>BWDkmq-6Yy}UR+{=d}AU)!h0dlyFs#N)O96~0{l2Vd?J z{yTiRNBlNH+}a?imqe0!xzRyVFZcHL{%81dV`F1&ZH@Tl%i4ceFE1AHL_*!g%nb2! zDRDlV_%Y%C4Sf0G!w2HzAaT-vc538*z?a1S2I8AH#O7w=`}@QJTVjtnv0I1OsYGm( z{7?9DVq#)!Y;1INbYx^?czF0f;mh9MUfll)zSRB)U)I$T8###$jKsSC9lkuPVePGt zBf*yq4GkpqvbMIirlzL4y88L^=d0zp6%`d_Wo4zMrNo>ZVp8H_W+pK-l=#@|Taar> zNl8&rQDI?Wetv##Zf;IaPF7Y{Mn*+HIWidg#A-5r#U%PR8;;q_45B;@-qLQc=^AOmo$92F1u1`ciwX1O1^$c>hi%HZzAHfqd0wz z#`<&Q=u}OWhU}G{^(-^hdA~5_ zTml~qz8>y7!B|H+XN}z|m4GGg*44MM=GDzL5UpIO7>itAJZ0+g>S^fuwcynFCeT%b zN_QAn8~qHHD{4P_@v+{n`n4f<{Rd0;Z>>;sw&GYS=BZv^Sa$l2=#|t$bd$&CiEG%` z55MbuzQN{%YJ?@@8=@ALU;KC*u$fd8OV8{8>R2_jx?;@8tkIKtz&a-$i4tMilZ-W5ZtAG)3zecIwH<@QX*Fw7o%^=dbzJ zoXdILfPMI$7|WV^!(MwdbX?b6GFa!(`Zyp!p*o&nT`I$ zoP7I!_9MjlJJaSvCT0BQazZM8Cy;CXcY55*?}1;NuBkCw6=K$tuHZiL1^*_fUHrA| zm-AExu;DtxO91*1$@Uq4ca$tDer-Z<=PEi;;YgqEr$(;6p0e#h!khA!0l_$3l{p$} zv-jGYzHKANJWMYA^h)CmoeTL{euxB^B5p6U;BHggS#7ZWe0AGyn*jo3#3*D*^ z0U1tRg&{W>)&yICWRbAO(C**0E+k-$pBzAzQYcwOqrpq>~#9l*c!Pj z=e)9GMjX>K{u+S|Q;`q)?N{e~(U9adx zNPp+VPr-mcUC}BO2lV3--0OKWclX$otl^V+t%oXbvq8xUOnRX6mLu>iLH+T_HI{Gm z0vk!lnP3`2r`MdqZ*#QmiZleu7?y0dgoREFb6-#A{4Cd0%jJ$J zc%Jd1x!=n4NkVz+>l=1X)67=#x)C=>dF{4v4dciW_L^2lRynT-(n9-8M9pKymANPs z&MQHNxgT|G)sL3<)~N*p)Oq`nh;uL0kfS5JwpUNr#L4sKil!GXp00tC;>n>DQ6RyizxWL&4nflKfr ztg*M7^=gPWrTXK*^sCaEVlxhD53G1Z#P)TR!<`4$N`5_)()t#(p+$E0XC)e&^U`Cw zz((M6+dJTU);>-ape011z(T!hINPdLD zpsYmVQ`<`70@QC1+^<3*i7;co2UeBnReL}PzY;~DU=k0{8!{%5mw(1wWN~0aY`FBB zKg4mb)T4sMy-g~15cKv$bII?qE!DGtNhZ=m+=cPBCfg}Kg7arN)3}S)rPu$+OH#gn z$M8sj+z+FxW+>sRVRJg2`pf6(L-o}Q;r#bCoCR6#uT&!R^G7UYhao+^6moNch}-@e zaNqH-cg{{f;Ye?<;!O4&+0N#=Lp7LY?Y}xJoz3G@+ghqkzPXXe%ejfRw)XLF4}#7X z3D4U&_r1u^gn5>>FJyTQix;m|pMJh)b8M_Gs0pRDc?tWHepz)jb1nC~?_^h4 zP+SQM-SSsjm`V%{mtRMc+upPL!JZW9F-m3{Zi?zcqPyIqTc zX9|e6R@u2Q&FwzxS`(3L0eJGsvqlcntxHiTBVS(@D?z@Tq;; zE891mZoPQW-~B`^bJ8pMq?VIJW~^Dk zwRq)zWAKVGp3h{)$7HU`WC;r7U=chF$PD`gM?tj1)4)P2`TPE%J3|n#1Nfy2xNs#r$Y+e_$1tEBC`)VBDf^Gj%5vfBXKyhh8MF~*#Az}%~!G=qel;>{iM zByZ`&O3J6GwsVl>k&$8056yfiKyhDIQa(Ati8uvO?0<-n;*>+&==%WTARJj{rstGS zwIz=F2v9(K{zHr`gZafJuGS>3%g2&%$O!)|dE)!Hs2Y9kjnrs{+p*8&j6Pl$2T_;f zD7(;4#%mrAJoSfm`cG{$rQVN%nEzun5eA8$T@p_Z$w-=HQ5Lif2UE9)E!$IpSD?Sk z;2P?%MKmQi0$z-Psf)wUa4>LBT8=%mI2>glo+{3g{fqK_Wu*^Nc&gz~#1M0}*;;*|}uEjMMG8XSZSI;9u$S zd2qT(!LU-Hbmw9AVnK2zel(U?P0e6mkTWFKgrQ8D34=~ikm$*B0yX47Ns1Q{=zHp(J`zkP=8wN5UeUR3w;*@G=RZvRH#MBUgX&*OhSA zoTb`?F$Xd?JpdX(`CYF3RziWT>t&gA(h@P6O&I(EN5!WJ-!DTQVKS}@qMgN2PvO87 zMYM#lyMuS7JZq}r>-@O+N?1Yuw~gn|YRbfh%UYVierDvC)X}K2aBk<4)}aTD75_F7 z;!po=B6yG<&hYzGHadcEDHezZ?2teKEiXM+s8n^RbU&^2bSn}*s`O#4DozO2bfZH6 zd(c1UIm~?1I0dyKe6($6pLQ^xPql?s$I~K4*Y%|TP>W@Qts_#Zw%4!d5&i{F??ZKCpNtH;u8Q>p@ZyLzzxHp z`QfNQ;Q0{&{%r&t(5a(?g@^8xP9;{ByEUvwHc%}T`zK=4y}?hs$VKeY<@$}yyP~bP zE)Vm{Ie0_BAnG4xs3}6GKOJL_I64^rkDA0#72#R2nl+UWEv#vCHvC%MRk!LqVjec! z9B8;y0CfO!#e!*rN`AJ#5*3N)pTGPC+*~PK4UM=mpC}_+c&quKxYPdD|<3vuJa1Z+k5%&}Siv%}Q9HY!9LF@v~2XIpkQev_!cDv~IN8 zotZiq3Fb(4WIhs#4(f=1BN$sKMDS~-G^%>^f&pY-WrYD?G{68Jl~vvT@LteurG~Jt zJ`N)2o0)BGnF7xXU*C&-?H*aTc-khv$dso`9^!_^wo`As?*wgks%*5Ej~Z15Ri{z4 z)(Ur}pE1#*$r}>UF?bYhLFz09GP(`UdraN?9F+&9RvHldwBu*DM3M)7_4nG3 z4&3e<0NF~~k3BXN?K9cS=P*VK;YmwBv>R_)9|T{!b#8e@c?d_O>szoH931UGpn5Ou z4csb=70(F&8#F-g(Vv(clFU9RMco@@+?NqN=!Yg>$w$)|4;NBLKUsQj{Oi5{-msDJ zyK>PH>4PD^bclp^F9T)2^_ZO&)#&R>ql2G@%9KYsMBht*26EZyRL)0Zj6>prgB}@= zd7qCMJ{}q>8cGQs#l9GWtu)jYp|5vQvth;?_6FvZaSPNeY_`?I%A*92!C((Mg*~if z(;!M=T-9p4^lakW*hKNr_*H|^K--afwv*r~z}%QjN@94otDRXC4>1|iGaeb+>!&Ej zv!$TPD9Bye>6o$9`AdUemHQb(re?c7^xegikKtRp@T)|RNwV^4KWv|*1leCRYTEku z^eSVbpM3^{@si)B+H9wn3ehyUI2Vc!n>Z zG98&0b%Dsoi{#l}YMfQ^BOQ)uLzQXvkQseXbe<*o9}zk;JZd-`aO0Tq_&mG+YnFX) z{Cz$Cal;r(Sr`W%TFMqmIOp>n2{L;zRjOeD$KNSbf z13AN4DVjMdbO#=F`Jcy|E-#jo`Xx4W*T<+WmnJh(h8wyU2wHQ89&-gLbH&|59O~px z-05fx$Gbm&z@@nLA{Ko@=59Ak*_xoq@qst@rzMC}p_}dtZ;}?m&lactD!K7OnsLbE zaKs%98iM<`2=XpH27a(0qcqvlJ^!S5j;!2!{63xPB1)RD6n?wsX2`Pdby-mi@+FB+ z4u{=#f&U=DuBKBF@YyGxjppv3=l`xqo1lfwqPjfjZn_Uoa^NYi%*Y(T53SK8xiUvw z@z*}Nr0((`lch7yr8&|`+0=|hFrCMiFD!IHpZc>%DnYIZQDINDOPZ8Y0&4pxQ+(?0 zlr{FoFS_Gj>~D`as(g?+0EY1>v+z~&iT4KIN8}t(zX)(!0>!a71%QDO@$s!?CS)3w zJY`O{jE~A0y+a?kGBIsaUvi7S;~GT_-A>NkPE2))eS3d2?o;OA^dJC=zt~QByB&M= z5kv8&%T>CQ^e12m${hVI-_$Lrgu9)&`_Akx$-BgIekFzFTkd>qyW<&v@$n>hev6}Q zzxX=a_CT+3wd5*ZN&@*>2%Tn+w79xqc@<3>6X#FdPgeaFX8CRQ>bJa-Z_%;emXMFW zTxR#&4zmF1kwc+Q#XG)y!vp@taM?M!{5s8(Cyu? zA(N`M+iz}7#jY*Xdmuv5*_v)z}Zkx!sidV1(oY$NeB z;UW6U)x9-T*G3we?J9ACcmjab3F?vmL0)3ZAaY20)o5l3Zml@l%Xf2jhKZ|qt5xME@BC_P;LNKfU{*?DtqP?nD z(Tj+*F;c13%+LRDW4yFoK~?z2$~2tKlv3^OSu_%yXPG<8QWkv^lyLk$CWgs=s* z)g}zR3;ro-EHT6fAFF88Hhd3=RMLvdd~$29g=Y3u0O&I%ScDK+)x-$n`>Jtcb#i`s zGYw*#rc|GN*jn>jokjPVDg8ISX}o~C^fNAt)S{nFyBDI_7^4doGJw(YA3dqd?NBCF zmO##7#>_nYU-ab3KYDUzuD04Nj(^t7feF&up_lWm#c*!9AAT!Y+g1aEl+b_9B`6>A z>sn3xUmkXMLz7-c*>LebHXG=pRZf#g%-uq>ey#hAd>3WaMiM`3`{S?f8)(+vP2%sc zhocyT%`2-~6IQa=L;dHe_&MvM6r|bW`{YiA1b_$gKaUp8)b=-%?F}!-rvx`Z-YWSs#uUm~&G8*u zd8?gIjbwpFvq%Q6zeBdh`V^t#_ad~@W1s#NjL<6$&^?9#b57NteV0J^&t)c8r4T18 zL~??8;_s}rhT$Ms|DAN?TsKr08=m_ZogcqF2w1ey2$XyJg$y63Mn3{Pu~0`uj>YTUTL7!j zMqFN6p#+Ol#QNaVobt-z4c6^z)YG9?1RPjjQRGon&?HmwMboVda*qqICKQ3n7+;fw zmC#%?H+U-5kKU9}qp3ZnB5q>1Gz}xGWdK>NAidJn4J1G1U&DB%SFPCA3=0gp1KhBu zqTGORIh5}nm@5!X0mpMw@trtuo{o_7Ct~5@2Z*$n(N5U&_7eSzskDN=RbFzae$r0@ z(nmhxCNeI3OM5Hv%@|M5uqEswe-j1<4Jz%@AnZR9cP%&ZAJs`GYC-oZ3w&noiVm=h zDy~MSag91DeoQcKs3}AG5qh+daxtOo5cQ$G=}m3fiLC6bQle;{n&+blbsmXQn2O7F zd32o8^`5)EKY4{uGva@IrVV@#tP_41v>>|$Pi*XzRnjjg+mYV!Z%#=ng*Mt9ff?(Wgu9nvM8 z3R2q`-6bfXfQTrdw19x4yG1||2?YeC6{Pmt=X?MDxzD-(-Pzf>{w29u*zo2T%pEr#o_@i7k;O;7wPc?g-QDZ7SD7R}C`#60 zkMj1NxD0b4(kDdV5NAB8HUW&Fbz`#eftz+l$*hiNlS%1;qh-dI;Z5r125UV431JF} zm9{&tU2?l9({eK|xO;*B);0b*cR?ettsZ|bCEMR=nRl=_LJxV$ZIc>Lu~qpnu0b`? zFn1$p>4Vj;AdU14%C6?tPE}U_M=6^oQIAMt=mue;iwe$m$rm3k@QvK^G+cf?qwiTU ze*5aikb+m?QxE;G97$Q&_oh?&oWDcC=tPj)tJwCI9P2|w^c%OauqZ!4o}*@yN&&~y zzr8e%L(+p$?kIWr79LW;WGSOUfYklVVvs}j#N%>0AcCHL-WzS4#G!NY{HYl@= z$dz$xusG5T7{-H2{XLa3U^V0$l4ay6Izc52e=C&f!?Mn8UDR_@D5;eyKqXXq`N8op ztc3uv?s>jiQIlEed4UT_{KlKEP8-qr75Uj>KC`jLzNd*5N097_ z8?Joy`rGp%>od_JQ~4{1EN*j&%6dzFov1QMg2*)_=ws&^5kaRGq~qg4YaXc1HAOi9 zh?mO1RCUYtzWO$h+Ku}9BfbE@?$5UquLR{EYHD@5vUypC!x(&!8@|HiY?80?i=Sj- zwUZvAp(-!XJt|Qh>aq_qKZZH25feOGme~tO1>j~hg_%)3;(%qQ#bd8F z<0K9-l|<|h*x(fj&|#ErPizGJ@FT(0@un$XqGa;{^v*%H~>IM zd7LAe;+Tqj6{De5*8WBa7uiCs3-GF*DkH@;rHwRQuLp2rTzcq_{F7;R-E1Y--4@(h zskI9G_Co-e+O*`5M)+XDQ*DP>El25B9!7G`t3&48Ln(U5hy9A|`#D~4q@?D1>4Bkj zeI2hKuVT*>eT8-J|G?edG$C6b(w^#gkZ89M>4wtqg>kdoQ`Y@ZDvvH<5-~&A;{m46 zx+m(of^SNrt4FTfhfBpr4G9PFhzEQ>>7t+rY-Rd;f)1Fmq3$!yjwB;J&X$oVsgW3# zL0j%r7jAt(g{X&J<3lS=9~M6J&8QNQK0<56y;Zr4JJqi{(SKEz8j;@^rf-KHdvref z#Hi`1a8v%|NZG*<%5EfZpTvE(ATD++sJJ9;-hG1~fprXul~Gz&G9Fl*B2 z-B+W^Uq&-v-Pr)4VYJ=|%~)Tofocm1+g(~R%@1i?H*O!CvVCg&<-GLmYQuc%SQ?EX z5;mbUi-M$PDvyeI2%1bOPZP8l|E!jq^Ovsw)V;K7yjv)n5s*RHQK2(G6_sI}sBd!o zWAdmFI@dihylT?Jt?gF#?Bgt(=koAHS=%KE|8=!#w3eA!tif5V2|>BcCoAKRv&dB{ zgHiO%Vf7fk@ocI4w6)gETLeOrA8Y}~cVkF)gC|+=gZXR6A*@p0!6t9uh+bw$Y3MX) zaTc~UOGc}FB29ENI8u!OSwv;W!{@oJEj-1O1TeyB+^>JtPk*eC^aP-9CZ}|`P04?o zvx}(1R0>#0TUcn*0VSwj&3UYsUXm6+TCM~ozz^1fQh(OT9STSjQe&s&9PQ$*6x>KQ)=6N7U3-7x?Q zYi@N?tKURDR>rO5#?9}z=X2%rfRUqveE=;pNNdNePh6&oYwh=H3qh2C2fmhPoP-9x zk~gW0l}M`1&}eXfEdEa3B4OW!f4RwzguJr}j65pa3g-r-0eV7D&ggHI(67V1jpA!ypgcGD31G@nr zQ78nb3bL1^n2DqGW>cg?URFl7SFt+YWtvnk15Pa=zlCk{XOX$$kV#?FkGZq5P)8&j zQ7-_=zIDh@S;-S%JXjWtP95o1a*iFLFu2yq9 zVIyS524sk+cRzS6(|u4Tr0J;e$aU)U&mci0Dm8*sI-CIFd7gG_(`~kvJcW&f<;@Dr z)b1(92mmodQeXuwdk2Az9e}D9--QC|Ls71cAXqyoU;FkAdw)5b)UX1ByWBMi9>R^^ z1RfP%9x#&#EF$u0p?jQmGjU5VxrN+MSY|2jAz`cwl&Rd8$#KgBL3YYWSYpI%N&*5h zf(HohKqJi(6B-dHSm%P>;N?SZE!s|XGb;y?x!Y+0q`70lj*X7!2ope zx`<_(b@JvnH@0mCzeT0KjxT=qpYe>+SwuPDXM02){BHqHu#(!K66uPLK->c$5dSHI zyWnDl=J$!;k-0A4w70ypA9KImBIt$wc7qISJCwqaI3X%~sJSn9*58SZCMx@_h_!8z z7&igCr~f`ja% z2pCnLZ66uQrjX8a(%OGl&RZA+D{7YYvHkAJ2@?XgtMR%Nru9T-G0e)w(f zJc4$orWSB|=9cpJ2kxyB&Cpe)q{wDp<9(GC8Tmhte7y{)C7&9eNL_Lia2n^?!pZDv{CKJ%t#bxvyN5`jxVR--mNN#}aS=lZ4=Ui=VRFG~Tq zKROq&GZhG&A!Nn1%iR6GeRgK=JxO1I_8(2Tw~XgNSOKR$uj1I-Q9a&egI1g?XRb5O*Afi(_%c|9ZmzdYL7Ax&HNXP4;*!_LJ%zj zm=GX&W3Ux}^0@xI7Xt)q5rvB~%y~N!6`(aiA5(E#a#|fQJ0<+vdSAs4e{@knA&mYMbE%2H`ECB!F-ajOmNyDwE#nvY4iMs&+pjbVlCn^8z-bI?Q zg_V!25_1lhJr7NT0+^x_wJ4HxbN=>T#C)`cSn;Dn6Rx||>`KrnHmQ}UMu4&2b(^hO z8-c)6zLj6J_X{iDdZeCktNlsE5y>SWHyDJLHQAj%*-iKFC%Fe6YRR6kze{q-%f+`V za<^Y>%`JTAu>S9YI}%zK{2m?^-fT!9Ejw74-excrrrbj2za`mgKofPp8VGyEmow`!wrhb~7> z#x4(INAd2vZPo1!vFV?!iy0TSSG#gBq!FX8xo{Prkp#VW za-^{0#!OQ=P*F%``qU`Sbb&W|IDHc3+b?m;u*sPvJRilC&GoqCMLLC3C;fORV9z!yms%6tavlPy1^XRFs`_7aNP|zBfjRh(o{5o4#LX9=Izar=)HG6 zvyC`2>YL^E8jaK}g(uuv7I^Ig3(USXCFU(VC~@b17yQ-GA*aFkMjHc%l6?5xtmN-# z)33Cuf_0S?>$QD5IMaYfii0j6;h@Vt9CSIuNUkH#5xLv^)7goFe$Yh_Sj~On$RPCz z=~LlVec}KM=Lxep{;9-+t>aUZ9alT8y=jhXI}9V9>O?POXu!Ce!l@QU^R>cbpjzk% zBI^sbn0BP_kh$WqRZOPziZhGFDWSi8Chy);rb=$!5*(~!d?2Kol z)4wN1+sNt>%4~4otJ7k9OO;}osm%kduHA?eimE+ktSGQ$Eh?7~1J6Eu(26)AlfU-! zrZYX_k7oF+jQup&Gak}j4J)NwE9~8G-Gh(o()1mflbVEJbC62^1;uXx3ZC9Pbv!Ql z{G!WEN&vsQ;G+k>iZd~oS=9K@>CCRH0d;yIkj#2$+!U(l%K@`?CpKDpev^sJ@Ki5#dWYQ9n=L{~T6ZI3cMG5NLXI2tB<=5M zdE(h801lq}+sD7A%Vp8@-Ko~ZQBA}p`R>`{+_tlN} zu-YI%r+f$ocPQauIyXM-tXho#hoUAt?H3yq2Z?(({PAox-uIEo)@N(^XfZ5y)` zrDMR`EY>U)zW1hGidu9lfB^sm013csw!Dmk^4x8tZ@C|}a_a}GlnSgQRaCKOcpdn$ zo|+4`hIg$biRf3>4Xv0rqIsD`M6wj_%=6#k9CzY28~)wlNkkvZVy^QU+rK5&1z zs7{j#Hy-H80XzhYqxu{z)>O5i0j`=9^}n3zG%#|0xks@)r-V^j16H$$5x!&WSN&VM z>aL~RcPK_Ggy1T&;or^Sv0k0S$@s&5o48>$4AQNmVUV^Q2IYHPr#IOv--o{utfw07 zh(2B?!)2zr#ZC&prc3$=)oCAFzOvq9d zQU_Sy%zndr)v+Lvy0Q zKK|UHLrP{yg_gDh0EkG>UlVddzPAdj9ETaQKby;bp!|Y-uci5!J_!QbEXg&-l`RFZ zi6u~Ijr<%%b|yKH5t!5pV7OTxAqT9dn>8-20K@^RW%QGLVHNdbYCPy_7B`$VaXG z1^mSKaeB7Uxc9{%ZU zQ~9YKhj!G_qoh^SRsiM`Z8a$E@HgN~T`cP=@xu(%caQVu?#8CZ;9M>Umyl|ca3o_!H0*&qb-7~!cI4RFg> z9IuqB+-TOTRK(Y#RkW6$tPJ3PVMNfvbpz(0-nKu+`hMWM;mG%AUE1F@Nq~G&nyQ!m z;8T_j1xMi@45Xhcv^)oTNVIre2gvB2p#Drtl;u(iE|aYySwFE|M!OJReIaB5Gngg5 zO=TPDv|zvIHmNtrwyP-yuoC-`I9qGaY~u`oYO29BAlaV?ec3M>HYgue5K_5nAo}>r z29#&}iTho@uDiu`Xwy&j8%%-d;omQ^D$IrPh`6iF^Z_iZNLncTXH(@wXC*fsm|Bs8 zCLV+602?)81S2$6atHY9i{Y_A@$N*WOVm4Dah4TIZZ%QCvmagvlvy2+6MkB2T-nmu zuO<)T%YGtDv?*-EmSC4G$ZHL}8Ku+0%=eUW=~PikV!>*91Kg`%Bp?~L>`S!_Vg?`? zqcpz*F$9eRLKHyUCyEq9{2_SEmvH)Oa=;}<8I7XULaE|5cfuG)n)=js*X8I^wCqy# z(s6nqhCb}etD@DhBDYM&85WqS(y*s6XqlN4hJ>YrkwDas`&3HOTow^<{ysIW63QQV z!nEN3#K>8c4bVdV8B_92qJF$*(7}YN6OYZ|fP4r@3x9~YMpyT><$U>z!?H>%Wp@G2 z4Zk>^BJR{u2Ce^~NCZGB00g$f@CPJ5!9kH`I4CkvXfR!B_XlS+qdH9n^aon!uoQSX z>}~E9SdWGkYVs-D@#Q9R;jGI5EQe{Mm+hbvZ;!Lu;F^)3F*&2lLuZd@Gpk|68IXbQL=s6q*{@nD5ueM#a2@7)cF0)~9I``O7Svp}Po zSDod)!jEe9R#K*qGiSKfU9>dC3uoY3{R;dvc%yi@gpKJ&b624+0R-TW!am^gd9)C1jE~(04QK&7&%Q{aW_xCggSB^Eh!mM*dg9%5~+c zI5ZMZ+z3km7)AW2Mt1ivn{BBe@MPD9!=5q8+-MTR_MQ3HHCy>KBX<iV?nh4ivO> zMu>J*wi5Ssrrt_0l@`ADW^ZV}n%)b{c9LUepD-K`Oo(C~Vt?8GEGU)te*CUut@RJs zfwflsopF76&ju+Knj)&2MwEA?52L0xH?lcoZ~#>4K&cEma_3qW)g0XXghZvka!`dx z&LJho4zyiG?81Z|^i-D_YivJll^|92bNK0pAPL4O?%&AQI2K#$}_ZSg;S-%3&hN%cm-vVZ2e@AWNFYpgQLIMo}mf*fv z5$pB9+UegGe;VMi?)=$R%U?=^G5(ujLk5TeMgU-%5H(vB@MCz$6zTUlOjL81iH@NN z?tAF-fV~pIVyX zC3*;Xw`L-uTs5Va|HF#v5bv&E?Pluq&08%JIPWN)+Oej}&9eTN$AR#CarDtPkywEO zW1)I7_U`CXqw0P3;0Ldt)> zh@1YPVXj3|kRbWi@u+Es-MEtpm43H>9;OKyfvg_)g-HOU%WK9O>BR;~E(RHdv=|>Y z9gY!15}_kOfCpru;1nj}%V9jOP=ibdC2@^#WdeW}!5$mBFaLy*Su2u9gXx6?{k{V- zPltm`i&H3!?CUZ2)-jn68od{gLs3)tN~HMwvi zEtgn014`;!NH%&ZJQCLNBP<0D$QV<{eM$7JS^P*+;=`yodrJy;i=?GthgKRbvsM8W zxX?hL=qitI;*<2vKv1%zLD^%f(L~kmfh7D1T`4RSCTtWF=>ugHQ_ zAOlx5Y2-jjB6l(IGCWJe92bXN84>_`_}BYLsJqMsYQrzA&4d~~nlH@q zyq<+ibYut-Y=p5Zh%`^=XIMp0#e&qT$%T%M=`W3G{jqJdy`uNCL9*Ou%GKleNed!A7ZVLQ$$b7Q+Iv~fyUya_;@zeth@B+A5?Z{{gZ~7oE zd<|XhYko1=cwxc>RuK>CRyd6O%51aI{~%n>Z6YYVCCS_@D75swW@D95e-$J1Md(PI zla$=cCp0F*KI)C4kprOzWU_3{xIg*bc%MPrYguoCB*mT;#JdX(3WQ?wi%0Jtmh^gn z_|T39^6K(p=LTYb*50?2*O@((*NK(aAZhm9$Kpe{2Yjg-QA(1vT|bI(IpD{J64m#( z(+GF^LH}MJjZv}NFJgCh=O<}0IkxB=;?svx3NGg+5&;g}nv!dN6IQ$8$d>mL>5DPn z#&~H4W9|%M*})M1Ms(!+lIVZMV!6*Vz`0@_DCW%@hJU4egSyd~rKKHyO;Kh)wF(_a z3&{u5=_dOIZSN=jlbst-TlT0Rew3hjnBap?%AzeOs94R62BlImR)*Bs`jvfus!;xG zy83=hbe9Z|7(v!m2}zd@P1jRqIqod4G{dg+COa0r>0`kU&W`)xBQG-X=-!!HF1c|w z62!cY`B`Gx<~-P-FLzl_KG>)Ixn=3fMhPqDqNLS!w%9f@|M>D(yRH6vQ@_;bXmjqw z$Gji9)CR}rY<4u13=CpEB;M<8p~A7cpBI%V2(L%tuEX|+Qn~(B9kJIWNrcG#`=k1= z5AR<8D=OWq+5xqjo>$-|$5>}8fFzAVCv~^_Y$SC1_mGd{)P&P`%il4+QWw_Hu`S9$ z53Ol>EvAcXi3nKTK&*O)r*H7hR9*di%+f61`SkOrB$tp^SmjyU9uxi8+yVRq&o|?` zJ@CfP!Tg@7;_Dk@6{@5gb_tA|e~)FDieGe3a zuQKhO9}s4dzh3cC9SZ7oXjajbh>ziU_bcsgcOU938)OCrrj8r-B7|KvCXe0?w1JB_O(zh7c@B`|j?%tW|Gv$ld-7PjdCAH55Qua!1_{=ObKrfHCbO|z_ z3t(R^jS*9DoPmXBD~#^OhA{Z{T;hV~wF~d~L77blDuhdK4jUAHbde8`sIiC)&g&?X z3LG$;PxsM`U2n15*kxiV-_brn&2~|_fJC1Vi3*b`va?$BWzSpJjfM#l#WZJE7QEu-=Yf))J&!vU64sYIAfG7&1f!X~+dszN@)n5W?~YK$KWEc@I4 z5j-~4CmmbBl~9|Sr&sUpln_wySZUdlx^HGHC?1C`s@o6H@VX%9X@)F-N=3`>X8-9H zcs$7(T`sfulWSAb&yCONnj#pQ#1S46ZfpHYCUiddrApI^J5Z&#?a|$a=C_B`kLYTA z%ZcT<|2IDCKbC|&;~*NN%0YiV* z3n>rnEgqMzo^RKL#Vb}5bMvb2dB0fm-7zZ4PVJAUz-PRlY}2uo9hBp(_^WLMGV!a9 zH94k^i<=D|nfRma1KqraHlz4^kXR^=ZIN0z04LwlvFRneC*OyC` zB-Zu0w@1JhJ&!m7kzx&bv2u z=fzHE=usPAYRvDxe>+K+O=aIXF0=g9I9g^oDVOcFL|DaHsJ$1v*#$!MjT2X237_Pc z0}%LiyE-bP5=3>BKZr3=DN3;$=tM9F+mSewy~B+>pteuoS3kQE2~2{r*G%WiABu%u zDx)Y8qke=tsgvQ7EZ0f^q0@Iz&NAi~7MMj>8s8}-ELl^-WVl*M$ z16GP9`qjykzlXObuPM$OMWMQ?neBY3OA4(*Cx9zq6}k8vqfmsyK^1HcF{iOA|3Ul4 zgFU=@YvACromXN=xVA!%J^0C!vu|$radU21GJ#iGpc&*ydJ?W?M;|Ti&I$$sm1KcH z;!JnuFff7jCmi0m!%Ik+R7^E4#vz<x2W;^J>xuFc6rUdCr?9HaNQS$?8=akC{$C~W8qGxEuNd}q(f3d&Q#Lx)EWZK z=y?rsGZBP6#{JTseL9p{TnzN$dfd})asY8S8@miD7za;sH^K|MYR3h{Kn@F{)wI}< zp$B+qhs0W&5Df{S)RlVTQtu)E)ekf-erHRj#E`sdvh))t!`;|oKC(SJ!onmQ|q%_EZ$DjR<%F?LHozp(vfcI1c-0%HcxsDzU zM^QhJAS0(h)BX_Gq^~;36jlqF(1?ahUIFpNTLK6k)+Q2d6I;>hb_ELeeoYE)2c$Jw zO}`&ww3jge#dZ(_v@dnD>D})?&V6e=EPnDRs~{!r?>cs}wV};f;I_lW7BiCkJFX zsR9T{jbZR)s-WOg&~`;9tYUzF+An%e%7f#M9KZipCUD6bg4C>#w4{i_+>#zAij{2; zryyvDCy~jfWt;y@qJ|`#PcnSUwurw+ji~n?<)oDT_F{B%&kZ=DLz9h0H7cLj`GnCYc1z|icr@h(_n>n*Ho^9#<)c5~;#l-+;8{Je zzMn-_D7E$iPQh9BbmfWIlIdRbj4xgd&=JfrwBKaWlL)O0wXWn#pqvTyxBPpYH_YVM1nKgf|lG2 z5dXxtlH$!_ybApdk4}WJFRDVwe1y|Ny+reGa?ORN$oK+N$hmp{Z03t^=YvH!X(cIW zUT#JhY8h7UR4DP<1s`yhStq})A-k+o>`1U+3k&iDY^ zG#*qsPYU$Mq($N)9#&W?nH{np14Zks#C=<1rXvJIKs#zugCj55HO>B6 za=xXsaB(m8&M?KcT2Dwz(dSwTq?maO0CzXoKdECitgSrKv`!*8ePQ z#W|{28IaEZiYzCM-RqIUe`K6_+yBJ28S+)BIuh`vCu{F4SWC=%y2)5Fx&!al*|Op8 za-GQ+4VoTFUoLmg zXqyO$wg{;UTFXP~;dMyiI`t)xl(RSt0g%HYVQz8{URRm(^kV_J;R5cyDs-VmmNC&U z=Pjmb2RGP0ZP4e+MIUWb8jMpudnmpCnY&t!v+H1@-j*|+R{7S(e&+K-UHT}W;^e(Z zAp-L5jTgp^4Z;sUP@Y&MW5^>ymqHC@FP`T<|8jb(f2oiM$wF%fWb_e zP&qG0`2>+=_78MHz8wM(T%Q*&O_^9q<%RO&OCHT(2`}G^338dh&U`%k24YTmR?hv{uT;o_RZ+p%>V$X71c=) zu2g@Kq~p7p^P_#L6P5Ubc&n%40$o*x_SL|O^|ck41?ISRonz-o>Coq*eTC#4+}X?h zN+S1s!C(23_X{Z8>3aZ@9JR38^*hXlR9QW7|LK3a)>FI-8`P z*pUfVa+boF-rQO^RPm=Hh^xpC-JILf7c_{Dv@m6QFY%Xu3c@Q|jZ3+9pZ=#?3L;^8 z7&hLzcZOY_wEZ;Q^>4^4c-Pn8)^rxrf9*wnZPHJw%`~Vh@Ourddi_lBP0cuL(v_|3 zVOOVL^$+se7A}aBy88i;qUZX99A`Iho!|~hNVwU7U3}Bde!>BDMef_DzNdV>&pZ^T z)R9tZbvND&scR$?YT~bN`YhT!&kPuavwbQq?H+4sX@m9db=A>{Ll9I3$j6rWgCKGQ)9{}%d1ELz7c+W(Kd?8!bjP=+51F`Z}p zyCKGaGchCw7!~Bdbg@3V`o1qxADGHzuymNmJ;W^nw+*GSZ8Bv8wCUqJ#?$+OQ%6%0 zq#RSXLHHy&g!MfW-;`IsmaXEGeH~-{HgNA-1M8W0xw4bdT@5wBcXBu+6XvRZhjOcn zBN=64GK>YVaYNXu>Q|nyblb*s7n1_C06hwy3%5?PUCzNIBShnWdaae4>{&i83}@yf zJto&^coFrRMD?8P6z`dAxGT^DOZl8#(^u|o{IA5^zKvXz4l%woZ7Di%{U|%4({cqoTE{Uu)%DU=SdU%mV%QM?u+c( zFE7L746X=|^uG1PUSG-R%LzNZ^Pr`Y|7=P$PZNG~eQo zFD34q#MbB~DX!SIx9Fp-%gQ3tk{v(J#-hTpGhGC|e-XrctrQT_-xEh)Tt+9m|C8?C zJ76+!wE7_8^&YBY9@?5UVlnf{7nv@bj6}S?|l83qZWDl zVmZ%SXEBFEClWBi>VVY~&yT?fbhvtsDwMFH_w|?A3~ztF{}Rs-H0qY3d*AL;lFq%q z2+7-BGa3SXzdWQB36<_fj6~R9&dh`-#jLSr(X~ve%6CxDT;_lBg{j*2c(v7r8Kh|l z99NsPGeoEPowAzjquGkA{qDbTDgVu1?V^>e@BKtAyR#rq>)vBMwHk__+=VRM=q>Ze zFKJ%cPR^Y^kLC7!yiay4`ulq4dC8T}ua{3b zt7|LuI0XG(*AS&s+gBc1F%sRLd!Wpyd~wsStR0KL@;djrUcYia?BZ?A06h}4ucpfg zXf|dQT6m*q{Z~hA01GVwHndAd@V$F}_hmn|pQxyzoj{@Pz-aPuMo^bzc^y@!w6)Em zwc-%tNW*gcwQ%ph2SPzE8;}VxOvUi4AoByd%#eOs)`0vEQpOML+|LaBj(UKJb-~71 zvKWbB)|RIy9|i@xsRy{98#Rw{DhMxlnw=M921-*xy@u$*KQw&gQ0oq#P#HPr8LxaP z7%`{wRjbuj7%yw>!M7==b-Kd0=eXI|sy;6)_=3}wt&EJiG2U@r>3onq9O1;c=q=WVbKGcu$3Hra9Fv+LYdu}XnAfqX(S}QeX0K>QTpF%ScbCFOxty=(gGb7$(451 z1zC68M;EQG?UB5BaskPo6^pc_0W=?eJ1`f=d|Ui}t9ZagkRxrmnh?BuOh?N;ZwI7V zn4yt45jUeH2%%9qTu_rwKtDPoQ`OwunZf#8TWYEP*7la2z`zYa7_<@v8o-+N{BTc> z18TDy@4Dxrap%)VGK`-{M(B!{(Nb;I%B_GP-Y{XemO(s^#w4xVl7{OX~vbB(Oojgv>2hg517ST|i z4M4+oZX$MGCNJKj)rFBuUi3y=BE>4eBYD}EMz||mWR6ou-^8p!zN{k2kj9mY`FuoV zEF>K#%W*8>k5Igxvn3GFR-@v`Uu5+4Gir5Wzl|Cu^p;G%k9LO;M~|941{a#xSHHK@ z0C?!ta{+hNStF={`+*i|$b&%c9n9VQ*G_I4zA{5=i;@aSPZ} z3je;0>ocR`?)q)b+7&9xzr>Wc^4hxcxIp+5l7N43jVF3^GQy$xaqJ^b+NS$cQO>i) z+VeFSvU&ctKrQ_Bv_vA`3nRz3QWd{5YgEn%OryuCOXsVh22P9QG)~n;?Lh*o^NCo%Ox0gDafF65=}oC>=hzSBF0;57<=ybSG=*2Yi=tawS1--mdjlA zc%e2%+s~uu%C6>$)(t^=VBd4`G#@uPS?8n&&W=tIUY>mG9_f9*GTOn>q}{csEkJbc zDeu(bK2B+SqG4lJp(wr)msxh-bKvT0(-*7uKK}-PANghBwqM3Xc>v${xu|T&QY&^r zJ22AP&}p6VqT@Nb!Nev*h=5|ioRAPshVdW}R5tDE4HR?vw!i!YC3o-Z&me4mDHkXR zz`Y#SW8JMCU>vKNF8pABLnCj$Hfs<}&+~JH) z>F{!p$c=@t|G(k>Z{q(SW%n7>RR1>mex;B?2w4;<3K&2{MG>T`l+b&#Ql+W%CI~1k zp$0*UsB{R3f;1^A9YU`ny$C1>($z>45y;7X|Igmfv-g}c`y5_m1~S7dLRQxGyS|@* zsz5V|wTpeXWYO@g9AtQ#5Vtcc205U`a{1a^u6#fJ-V1)KCBCTp?LDi%vLJG@y!*l| zC`g1f=LHBG`4fs>O@bLdUcFZIaJ1NcyD)WpK{kUr`nL34iAxYf&T@9F{>Qr#?*1P zVXXGM>#{PF%^ZEh}>0 zzGbhtR`ve6RN5%O&|iIaVf;y%v=-K=!9()xKyR|-RExYnhmf2S>>xr}K`7zCiTC_8(CBKyK9z+e4x zEtF{FIgfug!K9ko{HRs?|H^yp zpJ@y2PXuGyg8Z*(OI|XQIA|9cQU(AEDR5PJTkOowTOUsdbSfGb+liznW#0Kt%S@!x z{ri&LmCMoCX6CPDcYA*!CkT)UNLf#?aex`+1*hA<0V0k_1Q`iO z44ZTAB72Z*2qx0nzdc04|7OFTz}|fOeo^OvDzM0yRf#CbC^w#2B66R=)>GKH@Yr%1 zlZ_2#(gp%h|3S)xv_p}$p%{`otSj_fm(_XgFkm;NhnwhqGE(4`0j!L95f49>`%kUW z<6k$DffF%ejaYv$Hi5MO0)P^@5CB+=3SR9D{^1AGqC!=wLM>5uZ~5yoHu>-HMBdYk zgic&7rm@}zVd=Z!zadZ^;E|35w!+3=2*fsfLeOk<^pXUCYz8(6p{4n3SrP$&F{YLX z4kQGy+B(I`8_aTXJbjLT@JyqPN58{AHi0Mlsl3xCX`-?UivLN_D}OAZELsxa*Ra7A z+rYK)n4fqUK!7geG1{}p%~?N2fb0(e&4@Qfh=w#eTE|VC_dOYQI3BX&A0PBGWH&MB z4lVYjFTMCN zoe)1br72|^FC!nxSHt+Y`^1*xiO_3tE**28Kjc%XPi*9)FFhwtb0l3r+nq>dZ&@br zynNE0pY+H7>Ckp!`$iJM%t>`p;=CDMN&H%@{DZ{3l*F@>v5J4}El|&xHIl6FBwaim zt(*GvFWDjd#4}qbHT!N;bEoJ0W)B=*KYyleK2vNW8v z1gxk#tz;$b4LZFXoi0a3$>GzhqSI?$r@wVduU$!RicYUbXSC{Ml$_3JkIra%kkQ?p zQB}jxDl<#}WDM$L_Wog_Q%G0Uq379rW>zx4ptI&qXU*$mF?7qN=&Y63S!>-{-&eAJ zqO*UU&fa`Yrc2zj^~!|2&i>n-eXv5$W;944XDBdT3X?Mh`G|rpr2H3oS(t52&=42= zm%J>@Io6ZIznUZPFh#lIJZh`U5r9s*Yp&t!Ea9rlX%zkHkK`-6udiIL=Z|{j6BF}ayv-M4 z%YQhT?{KtW@j?Mv{Z+xe0wuEozF#k6KIuiT9`V-APdIucwBcv>CBfn z%Fvf4xG84}15^q_yy%6&iG?qYGQ7*e!o5Pv>cS$)qC%6R*Iq?05{vS>iyBsonwX25 z&lI=n7PmVWcRniaE-dctDgLlp{E@k2@Jz`$Q#;Y;2|04!GRd5i@7-oPz;FrTP6DUd zF2_4^iL_{B`AcbxB06Co6rxo3T)k;mNv9!?<*TqmM!^Nxs?s8%jQRH7s+WdbUH zJY*n~bk^_80OrrV3np(x(<_jPZ_gjAG;pbu4**5{?wzi>ch2vfxcC+jBKt_b&*!pysa5| z8x8Rf)$&hs;AGeG;)?QORzcA`AGbzvrYB&>m!TN1nlNO%_AltTKZ0(IporC`YuBpf zAhODk-Y);6r$~%K3)X1(-oBJrS2yK-f`$nqz-{o@VJi44ruK4Ty*CC^@A-JG3T)S_ z=_;!84tOkChT5mWO#N%qQ)q5?BXF zU^Tu<5d$bm;Bsu>i4>d@$npJeI4qmb?bjex(D$aiF+^+= z4engV%HdB%*Hf{9Eo{XtoP90a8K6dAd5i?}Z5k|;fJ^iQQN{nZA5)3e_3tI(W5lbJrJzs=6XTHo{0g&jXO=6%Na?@<6?0;0GTYMdkH!Qkbu*P@Vl>AAD4lKG#r5l#)B*? z4pd447NvsWDq??O*^{5qQ&ikhvfoqA0-Pn_9Lm5_WIzQsM`IxPDz>Mvucx#aEIZr# zD(WFXd05=phn(wc(C-;!=^Ih#8)E^CY*;0!<<4ceyuT>gz>(_W-uevo0Ty70uWvLK zTay=f@XfFRJj!6V3lR@-%Z_I~o;4$bx#Ra_@T%ryNlyFS^{l}av z9)Mz0h5?$l>R`86I_`P_9aKCR{uPe?DgnQq&U&KYVMQSL4Z!3HGS315TAr-3KmuZ& z1y_xt(Wo~bkD9ynSsjd`=ODH-M}ll{p$v4=7&CR2j7$ukc424Sc{5BHo#q<{W=Cz# zjRCVkv!cNZ+~gD%fK?!a{e%O>V;E=FPQb}U#fM2b4V))!-fc@!EaL-@?@?^4uWxg=mcQr z0cbOJ^d`@dAPSBp9qewH{%|lY*j#SM&>*ca?s)%>~1&0VemWVn;9>EO1(%$S=2f`;B_xRajfE0V15s8EpN)o2{L zLBmZ`M>%Y;p=DJH0pMrjIb;qaG#Y&pGRJN>#}zks^bp7A9wET`6={p!rDB}`L=zQj z#TJ45MG{P5Kd&@*`Uk+B^)HUuIC;dM#9K|`*Iu~lzrdEYaN+ZUOfXm?(a$%kZuDaWk#_N0422SZUbI*&`wV zE|#`*Lwnj_4pV)KE5f~7(c$xQ$!E0WEZk~VGAmvL9A_LNQ~WBS&&Jiu%DdYAbSZQ!^g4XOPFL+H4xu2H)@<$V4{;O&Yi_wj{+PW z{3DRUY8VK<4*KH|av`m+<1KOppu}jCBAp%CFjVX~_mSfRtefdzRZ5JfW$hBB3Tykf z`s0wIL)TM^_oI5S_~RBU5i@CA!vS>93+8m>~cyKn?;sCFhh(b_b z__D$uemyzxRU?*HvLfL2uP0Tpsz>jhaFk$JlTh9+*p|fCwns~mD)w)`USi$%=O>nrJM$j<5Ij-3Z?{OoGOyQ<)=NNEH6v#Ld(6PujX5^Dq($7^%R zkZFeV0d1jMS=Y!FC|iho%x*b*3I*rV!CO>$ek<*t*t_p~ zjP>3#Z&i5&{Bt8jzcjGslovg=!?yPjWbS(`HBv9aH1OANs>-X}!LK1m7GT@FbW2(} zv*J$Q+V;<-FUn`mdXH7x#@}y*65}rfd#dqS!1v~!h`WMn+`gri1+gKzU{}-w!f7ab z&=8fC06|NGDongSpep)wJ!`USn>GV2Iw1t%H%p+|3utMwcv7KEs$R{E4Hk(Ov>2R% z3NV#~qRl=hLWsw_r^~gzYQs0$;L#(?#}(n`z%lC#Z8d%)*>zeg7<5*$3s!ecQdojX zSC!u^qb^Pjr@}d?On@1PG33ca1PdvY)Gnm-k31;@Z(lyHD<*>iG?>_58vFRpsSd?B zUR)CJc7zBG(lsJ{IIkE>s?KK%iuZ654Sud{T~(1R-pbZM&cgWvf}^kFy=2SD#%gTe zjmC9tYiw`o_TtA(0d;-`g18UqsK0|tP2RcDr}dpyYRbHMKdzu7SE zVE?b%rIr7Kyd3vPau$C?Qds&AdHIF^;rIWLm$+%7Ud!vwqe^G(=8pvsc~7X3b_Ny& zyiRqK6Rfa>o0CczuN~3^18t9P%tk~UEyo6U!q~ss|A)N1b%J9`yA_AB#a#fX$Xyf@ z+o28X?tRwl!%uwZ9DQ7po*qkVB7uB!p#MVkiF2N7*n0V2L02j+=mDC+7^zTW79rKF;SO( zW%AfXou8c{Ps%go$sqs`x6D!6HBsZ>@`5RG5!uc%w?$ZkWZpxsObv!SDZr2?zdFYI zl$kt9%DXLc92pssAc#t53GG=YYhhOssEIVcL+(O`h!X9!~v83tyswA?uR zK+kgVO0o}(qzF$;G_q_J$|Qf~WP(0&y$$Cu;yiJNo}&vW=;KQ{$rmq_>$%>&nm*$5L>KKeLUkl!l%tq*%M~nMwKf>gk{&1s_9e7NMIuS_;*O-V; zhlx0GF`{p(D$C5%3Di)0ToZuE@qfs4lR!g zdv)!ln2h7eo@NGldF_>y2IfQ~4W?2rY#{y3$tbAyib+PRz~?UY(cp*I@}TGO{~e=L z2i9N*|F0P3|0YpxGbGA`-Cc%7dH8#qzPrA=yZih1Z~FftQ7-Lm|2W*-q;D@UB+AXr z&5ex>`mZ?#LwWdf=06PO;r9jldhg-lB7K=kUwF$fDE~V^xwyEvu(0rtK{+?~^?w?a zvkml_9Qybuee&7=M}U$(m^D7sKR7t}@#9B&PtRdXBZHniWYCj6&h&OGdh-=}qt?Il zq$K_A8G8AN|4vVKcXxMocDA>-|DWi|%m2`m#l`gEOaIc7ApJFlo{ylvg3(_>=r4h- z0+G6s6b3z6TwKhcC;z8AnU|MG&&r~wq|g%|zoukUC=_~lI6W|s?&m}I@|q0@V0e`O z(I?Z=(*8R=85b898ym}TC!?aG{zFfOhK3UVS9;Rl-~WHtCtY0Vx9#YbW^@x1y1IIw z?JZYV*Z-qFdHwqJt5>g@n3xzD85tTH>g((4=;&x`Yins~X=-X}XlSUZsi~@}5(ork zWo7!Mi}Z71bYWq-06+aGFZ~E79R%qt7&-#MU``HsxL=Bk|ASCozI^fGMR|F7Sy@?W zY3cvJ45cs}&d<-!$H#Z<*fCySULGDEZfT027cg4%z|H3Hcy;rBZH)kJl5nA{E4pkNmzR*rOW7YHa z^>DuN3*F4s*HgsTrj^b!J@3TYn9S}{dGy{FPgXh(7h3hcFPW8*NWT`N^_)@GNOdE$*MmI^|0%jY{2g!QuYYbw6=rbxMb?yIR>`bbfW5iqFrv1gND z>FQIhc(*oQX3xMV>)wB#s`g&{FO1T#zWUdk4WAytQ7aqMCS%K&ZP-w|y*5$l^5xdC z$Ua_r#XdbqZytR7E1)-9EBmJ6-<`!TU+$m(B7U&v^K;&)xAwkBctkzJk*12s{hK0;k5GW{fFh?+1>r!HF)0bhngDg0#D)<{tEcRbj`FWsu-$fC`G zq7(7+kL4Hr*&fSw_~huH&Nay}) zW?n#vg4X6IqoRL(#QA6CIWREF!jZglzjP9y96qZn`IN{rs|6hX#*xUpSA`6W(%1P+ zVa^%4#Hm~vUfraUs-d)^TyZC7C%u%zGwWqCOm$D*z^d_W6@9X6>y-nVb?e|w7QyfD zChit}e>QI|_eZGU)C&9_$zj6*BDy+7(`y5{!j@Y6-AOeKqAg-l|ml%GvN zRL`3x$_+{=_%XueYYPj9({SxC-v#$J&YSv!ZKs?HiQt*C+f-EHk!`Oo1pisF+W9Bx z7ka+FFV0Qp@(B0plOA^+=tD%0r0H;^w8SY?lu;92aiB~{o%mxi7gUd+BuOo-TIXbv z#ERhMAGklpY>!!TgnO$fGs$oQ`LVE$BOj%uq+e(-h_N9d(IDd~EkZMjS|j{<8rneF~Jji;B2J3*aJzF$rilGn*%bvSrLN$#pd&@0Nw( zSp=bsFc7(`FPsQoBv) z=r6Liz8!nI7qiHvU(q@v;W8BY(3{gj(To*(-oUPQ@rS=+Y*=3KbZU28Nc$D*sQ=>V zcvpvP?XSn4u`l>~{mEQC11{!uF9gcr4czT0px|mI!8Ezy`+Xc~?wIu>P7ACXW%zDe8 z%3dP*@(;5=;mC6^qLF10C333IP8MLi-wR$ya%#DAAu051_@qG9(@rPztC|BbLrEHGuaMA||fgLtylIkOdAWI zlezhbbFo>+5Oz^RzJHO$q1Yg!Opn0l+cTWCx0O$rae_{tuG>Y2`)=(caqxSO9{3RO zHS$cr-PsHh4a$M=iqwH`u#j~}nCU5`%S_~iFX%UUE=N!6INW=uSorj%=Qs2wAJc2n zRx$r(iU!8rc{~HL{f78$#TY4c@dXrk4V-FIK-i&OS;CK00tDVe!T6pY;p1fh@y^TD zIAxYRj$1RCP=83gDPD+)ao5&tiEF5`bTsezW)~!u07TRI&fEL?xX8@+Ocm6>6MF1@ z?Bcl2^w)}{f)i3_?J&RMNYn0k_J%Me;y~Eyj?J4fD+q9jp(irm1}w|eWkzyfqhqY9^BFxlg!_&U*y(TBol22{i{z6MRh`y%>wD>5p(!_xl|d z;$tgl&aZvbyQ9~_(szEhpY`%m zhw@#1k|T6f+E@k8F=a_oNN!;ms&cCo*g5rF7DSDjBFitBo&sl=c>%7(H*l z?QZ>H-R@kvNTsGuiQk3qjlL7_+F;%(DlHH>_>1E&Qo0H*RxI*#)J`rRPFKcn*ShHa z9lP}UJwf)nlcaV3=VK&QzD6v{i~dmfo9|rBumLTC#ZqukDZ1XP!t>$grHM1Ve!3@= zeuaoFz`clSl6&Rw5H(9-h~MXCjNwLTET15nj_hvn7@}E@TTI>WeXqq#h>$1bOt8{+ z3+EngJV~x!Lg@U_x{<}>|8eRYu2YWuEI85jO%87M6{=l|ePao;y3OO&%aaQ6Y^GejKd+CMH=1bmhX#v==AH~?x?Fz`aC0qMDFQNK5KIpo0y zW%Rnt6;mVB0^}UPz337WU?XL9=Swn~J}e9ntFkAzE<3C&WPh0&ud<**CC|3j#QRLs zZ!xa&4^{>nLjX?-)(r_jBv=lp@UG+#&N=_w%HZ{US4Akta59@`C38uR!`3yOlS5W?mCh{!;K|FUzTCFC0Jh?3qsit{UC0+41INj>76I*rUdpO z0raI{cWkh?Z9Exw^00JN_}EE?c?EfD8vWcqIwd9g>4ahU^=o5(rbyq2+w<3qMXq0a zCINU}M@V9m@L&p!1zR3EA?yFvG=_r&TnCY@q9DcQt}~g~6Lsa%6Q(Z&?AT3sg$+Uh zKuqH?P!jw%0j)U8G)YB61<}b=CIu?$uMGofWZIiWsd}P!Jsr`_#JH3zj|=YpL;~Cc zI2up~DiLs(gM1WHn_1?8z#6(U@9MP`7A5&eq#2Y;kR8l3`dByd^Z(y3^mWimMqlG1rGrQ0kd zQ1r5Iqytx%{S)+U0CWty;kalD3ftiFmNS>HKl_~gEc0R(w%pe%0mdZAaxeh@j*fLj zWm~EIbH+gSUlFq6E2N)_`SJX$0fzu=j%kC4f+r@&wkOLtWneyqVbA3D{>i-9oNC7% zJm(aHGx5J_48Yl*+efE)Yl#RL!*83z2M3s=5YUe_3|9j9T!K|}lWBwC1cxNS=2)cv zsLD>}DOcqK<8eMW0?z(UxOp`3g_%q`;W>Q?B^Zj7vdqiEAP;;Lv&MC&`UUzEP683WI z3fW#f2WqNgRwr@mD@CuPMKm=om#V;^gBS)4`LT>#Gk>&6;>naJZk$k}w^taqn@1bx zxVCpM>-96!9`J}6QieAm%eV&4k4S1-<*+v}kDV@{oX5k za6n(&34hrBos+k9t-d4Iru1`#Gf?s?0z z7K&v9OhBXwHJVBAVO~|G;8f*C;X^|DyP(>tE|^qz#ko+ib0c==!WbCk+S!P;bDyf- zI|Y=w_JZ=BSt}2~c5ZiHmv@^zRXeLy)e%=RF1#<4i>|KV7l!abtQE#oDSXR;6doMf_lnBDhyslZiV+k;*t*etBuDj(} zDe@0eS&g>MayPC)3O?*i@J^*q)vqqs4D`AVxjX~bstsZqN@BocRNpgcpm9{qoE}H@ zn%qZ=#v|U1!nzIDb#v)!scm9R??md}TGTP7qe_4MPZc$-j#DqDRMDBKko~$Nt_{eX zhPx>s(uSp=qv*Yu3#Oh3u2biW>y_%?Lns~=wIFE#mrG@n7HeUz4_hc|J>Sv9#@)iF)7*HhjVcCy>Mg)P7;i>M zUH$gC1){N~=M{zK!+>_v>DKR;!Ba<@m~$ZA12{>r1Krnl+p=TDw?i_Z^Lj?d@LCI@ zuhhe$4I^mXLVWg>9`H`2xN~u=OY&2jXn9+RYqRTgi|M7BI}>2`04|%-wR5>8C#flp zMLvP=&FbIQlrn}(qD-N=3?cCRsXb}UKNP|y< zx6FGL*6VAEd#n3;*H3ltCpVfY^pz@fwMJ&K{wnv4ZS6yT=nrhM68f;a)Vb`?PO9(V z?tA71*0JVP_9*l};Olqq=uA4>aSz$GT=ek(10c)Fz1G0)BL813q{i5$5BeX?j}@Jt zWnMSNjS-o?-1$dOtS3aEy_zt+AFsOh|2f-Lc-hsJ2*F9Vb}X_zRp{_R_A?)RU{8e3 zQkcytFgtqLHGqctNknKHV?N_^k6KkyGx}H0jzsE~8LxpvV%xX%4~El25}KFNz+@&# zU}+Ww6@=~(ktn}`WBen3`v!y7FI0Dxv)S4Om5s#I*BH)N=Otk?LCh*1tH}&prr~rb z@!8s7Fd8~NulO-srEP2c^n!lq2bFNE32vVWGIrwV+X=k7>X8}*4^@TN(^-zH|LFU~ zp!7$V4;Fd$xE&(;1`)MAYi3Eq74TqEuY;F4b-cGemGMtiC{De#ntC5JRehl0U3S%* zq8UDb>meX(6sK*jX)WwmW`3~F3&Y8ZfG>fV{LD{9CF79`<8hgU)Swxbr!${Q2-EbL znbwhs*$)%*nG@_=5En`eex#d1)BkdABE4a#dnP#eD69BsFxrOI$8FrdVYJg~V0^j< z+TT*S0eI*!@$jadUCnjm@1ZyJZhoH(-ebOk1u|`}UUM4_PaQqX>=C&20WR=$A-CI- zh0W*h%Ttd(@_rb_d>CR=>IqI``h!O+CLlKlGUI1i?;6A34h-|Neih?eC_MYM>H^Yg zrJqf*>G%4e*x{_ikFV#m>dKuFV>Y-+iE(Bp^s)`E-uR}$;oRx7ePar)=Bl&XK*V8h^pDkIrFC(YuXUPL%;{_I_t#L0%k=^c z=*OLH0*er(#W8UXL7+G1)q?H8QsLpcLBr~Z;iBr{s=6Wv%Glck59GXGoGD$yt*_5E zHVyXQ91iYY_`JIJgZ)8p&Y4$`pu-=%ajTpC)D3~=#o!-*vS?&Ojzu(56mUHA9C47) zmDSky)sl81fQHsySz;N39$)|4$j%2e!3Lc?EZ?UG8sPl{8 zSlK808se-KrW^mH;f60549jNzNjd*b^LRJQ@ju?@cd~!7i5i#562YI}+HKDMU4LF> z@_n)7=U&>EKliNv?kfG|g{UzTl^_*RE2CE_>Pd(p7d_T?v`IKw$3D&bWZM{OGf3r3EJO74W?!h)``So9n62J~f z<5P@t3W7=hVwAZm;S7wj4Fz;43*r@YwaFhRsaHN;$Wl+e@=fE`YyDQK2QVV_dwr-E)i+*k^w@oZmXYSlP{h;>xDj}Dx z_2to&u4&Wv_N4a_$8P?xtiA8o=w|W0#I%knamS!*yws*P{DGY*$5OXOD|~qC7#Dus zy5`~WMmyQEVQp&W^{?A}=39dAWxxNBcdp@fdbCgAtYU~{6njiT6=$8)c<@5UFNnQR#Di7AH z_lQr=r0}}zR0tM|vkfU50au=WdX?p+%VtZF$cRQ}8gTKT(0A7bm)Jtr2RZ~?y2_So z_hlE#TCpQ^aFG6 zd|B^@S97uK-gaj=jzeE&8{MdrdKdEO=w>c!HF`ezkj`E)FMyDYzKfSy{RI%!KRqDe z4c@Y$xGWG47dg+{GD}}G(K=G7pWSa+{;~FJTl8qUWeIvLoVnVKdB*PAeG2T+N)%dY zE(|kjY_r*5S|3Ha19C=Z(Ay)vK3{6Buc$!g|kc_2Qr$P5fR`?yM z@tWH&qi0g5uj^W+XOP3NTkG(h9FaZAMWVIWe$q6FR(2O^kK@;l@RVTFjt$x{o@Kgw z*bO6E8S^@#;s9#C9f?y%OAxI9wH5Yc(!6-*-Uoj1*@lH6?Bc}j;EP|H9o^9p@?Qyp zB4bJ`$fuK@?!3nL?r0;?q_`l~qn7Wz;Q~SQ#mS$nF_K)`_JZ;|JV3&c!iD4I?Mh~M zDnD{1eajrUpR{~TBTVjA`px^7MOY`uFATFsMTjZEX*>_zUr!*C;zG7m_Kyc|nE(JT zW3JsM6yccz6+G-#HFsvJ;IeS5*_O>oRJ_3JHf;3M*ew$kRq6iA^1KPH#YQV>Ck9Lr zVm-Y-W8n)togF7pA+irGagPX%WJmKA_Hc*ba=egUhg0CtBZ+2CzyNu#W0-tROEK_Q zH(cg?a#YmR&b1&9g9D$*(+3fm$A<%LksW{0Xes#NH#zKB41TdSh!-;IN9C8vc)qKiGjD7lQ;@QTaC zFF;gdPlnN*&b^k24ow(o>ns1ZKO*wz7UiC{Bi?tSL$Oq_?dP*MVMgIX7E1m}U?X$H z>3X}hS-Hw{LlUAQi~|ez@N&`Xy*w?Oc4e+S?RD~rk3GU)+@F@OmT}GxH{-PB9-iR7 zsX<}(B8CE8JZu!STZs2-J3dJU>TMjc@0@~Jh zR7`y1XQHg_!s+Y0?bn7*B$l_lI3nrPsW)~(^qZ3!`t!>(C%0bk)K3Xp+^W$HefuP( zlOQJLQ_Ez4k;jY4M){iq5{ z(*jZ~$G%A^&A^w{{=q0ionD+4T*l;F9C8YE2!|vbKNy-6{esF3V!1D(d3ld7q<`cU z^zSKM)mp=pCuMmjzn|s`sBPiu*$_NRV>Y$p8hO6H_4Hzc)3tQiXsrA@zY|ucZjj75 zBpyk|<0jRV!v#}crd=r%f4yQhn)d!}n$D}W;nf=W?`G}NaA(qGs!ghqW#p~y2fm-$U zRm(iCm-;@#^%u23d&3H@h?;QB0iv8t6z$Bx@pIaiX!`r3WC1pm8L*|Vwq4< zxV?pt@Z>kg0l<9x(^yr<{nGm-E*MHPv<~507NO{B&dBMsY5G=#xw+nvo0@!gcc=2D z!MY>P0$TN274hovx}&lU&%lgtwVRcjmvTBn2jN(t(J+7dNi(Z9PncB897$n13_m#0 zrq=SRRgKd8g^uv2(wUSzL%FACky`#OM;bjN<)-IwQT}ZrN?wm%s9?Q3TlvoX@KoKJ z=ea-O-=!h&OO5h3d-YZo`SC@lKVRi<-p6!iUBB+3prt$leX=XmDfWm4t(e3e|V z$kl~#Zbxc_Rk1x2Ag>`mu+Gw-;QMoH{jVV8=L&g%S&n;*6%sy(Q!+Jwe6{NJ6o1py z>Bbhm-={jo{PA>9u*zPb(h-t=V7Mo8*{qU_XKAHoO+ z*~;Scmm7C`^TNS;LK^RW&bj@~GQQ1=|w1cmZrD zC1;W2B%pqBGKNr?PE9KyL{t-o*$L(LR1$?dzzKVW$Z~9$x-Zs*)Nek%-?Y?P#=EY> zUVkA}TU;JcuJ$L6t`)K52@5Wq;@oeZHg8UOqADWQB7CBSpA)s06ceO^V8>J6NjBT( zww&oJpyT zz-zB}T({Fy@##1w);U3e{V8v*^#q#c!ngxF&EVx8#ah*B+RqZSLh)UQ7?mJ+{6#X1 ze&a1hX&GtfNsLmL^uI=q5@)P8S|S84089q5)BjIrzybFew(lR zzL?I_=}y_V>U9a4r>J7JD6u;fVoI#Ga$jq@LQ{s1RO;ETr+rdX0&yxKjAc0nW~!JX zty^$gMeA*6#5LX9fr?qv?N=AtYY49&ro!^Ck;~3R=1%uy=DqP;5KUy!leg6zVxiY$a-{-k9M2BdLZ+_ zC%BQ@w84I#(I#i(s)Al+_(1+HvCZZK^jQorA!brW{b||%$<=TKZNPNj@Uyg9?Lu8w zU;AEP^j!Us$=ki1gvh>oDy%ccI1Qs_J7czzUcPMw4kkrTH_bKuM{g}*20nw;6rzVW z`RKOM-w|c@QIk*eCT}(efrXDNoL63W8l8;5*z!eUmIqFr8?2m+KirK6coXPQHu71T zpx*$~OE$8k|3Av2*{mRG7wS|U<$fxhC3WbOMyvAU&SUL_S)T#a_3k1nNy05gece!# zX=qe%WO0`5I0V46u?tDE1IvJ~F%upSH6tLy2Ot4dxIkH`bpnDkKzc9>7c_+j@xZXq z5ev?d_>7VK*pW;L2&2zMK*0&iVJB%}x-~;jQ;geFJ__H#K!M0$FyhXgF)OAVOOeMa zr#Ztf3TZ%qv%5%MkSw$tB>)gF{p%}A%_74m!d-aCH@le3OGep-jn4I5c|jzeL`8V4 zMFnq<2cJWjOu!_ro21zc!uT<<3JBhaYif$zF8o-#i#+t(CS0AiQMwGMj27-{1M*i# zsTl)o6EFMCNO{9?_DmL-K1_)b_$#@rT3`W>!*99v^ z8kwrA&!B}4fKRt$cxcQe>ZVcmuiO*l3A0TLH%lR%3U!}|3L1#K#(_GojSSjFI@rhn zvys|7s0+JM%-ZCjW9i9mlkoeEvrn~ONsx@Hi(~oVCyn1wDPbb0@X@uX+o*`#gAaM9 z;&ZQ>fg_4L{J zr|Vr)-+NNrD(oA`JpNtekt9!2$Sf3?fV=pQ`@0G4J^OO{_9Rp5=hYzNOl{a3d4v*inwRN0 zpbcwMK`0SyGC3cG-Ji{qCpz#m%{{Yy(QxbUH<11S0kBtgprHZsOoI5(8~#XcW0_zI z{CHWYC4hYIHfn%^(lruBcin717v3aH&&0|Dwh9W7=j=iUi1XNp5Berq_@TYQ>n{?{ z*;DLiB0fnf9^)GlEU&pL=@{wf7~h>kU? z8lqA1pH;f%L|BPR)n{!aNNNotTn|4g??fNduA9iav$oyG6PybkEON5gLmLzx3a2So(EVKKa# zklDp?$N!sumcBCExAwp}x2(<}!@j`h?MMN#*Un3b;m0Tm(x}A} zzC9XFfzCJ$(o@%?JGBw4l@5z{9^n-EtrwS!(Ra%N?8y|OgA5`}$uazvqHV#FLq{|~ z4E^)V-ihlGj}1;N$%%AV`_>P9+>d3+Kg%5accbNj$WtqS8_3~G^^I;lS=!TPjZRsf zM2DbhBCFF`__wT5ogS-?ttIGv6@>Sz)tG9?EyfFx>u!c;qP+j-vN1G;ZNaG6*<)-a z_{ZJi!=76A!kYI3$d0aH|7$NgP$D#DW0YM&N3@@~t7?CA83U_Ra60+!*Ty3M8T zq)y0t17h%cz};vO?K;t?lQE8=z0mK6edwr2$4hl+kzLo(EL(*<^aJe(aZj_}{?(d@ zJF%K*I)`!OzK&~jKezAx|D<7!H_a*>Z6Z%hC6p5Eec==+n4KO zKfKu6FMMkd6sr(kGpW^}#ekajlv@k^C@2k!kaJ7dUVG>3mWm>xJZK-rzIVl;st%&o zn^BtoDvNs6vza?T=^d}dibvEWrKGP)H4Lxk@BARyg!b;O{m?|C{KxDjJOz@`5AKD2 zDV~*-YLt^{cm)$6K#dw) zzjq$Fc;xAX{p2N*r_8gL7YnA|UxGp2lOq##djL9;RUZ3BqOx598; zHF;uHC$;NT9JlRzeR90F&A-UJ{!6=ZS>{ay%AXL?r$c6@z%|~uYX1B=mH8<;sD?zX zIzC^On6%@R?;E;SeH$O{oGpLZRPlC~uUm3;axm;M%#SP_{uYL~bn5qghu@FIYT|au z;hu8-Nmbe;GN;FhEX|#j6roh3$tf2V&zU5fbf zjz#`6!Jn9x6k=vXO{*eTv*_hr6u!@EOX_MwFzckT8e)G?5pl<+#;;oHiKXv_) zkOVThI0h9=e!%z-_mJ{Oqv{VKRS2yqz$~y?C${-zXw3=hEK*&(`PuvV1nkYJNNI_C z%XiS1sx}L)qouX$OvoP8?4MCbRBPc4jh=%!#%Z5Bmt0pa_mEe^R$P(_)oP(a?0s2KQCTUd0^x6kr{%MQ$i^N!&o^VM=YtR6m5rOM9~XP88>Xik$TTL`*WcryWS-WxKWn0A z5yWt2?hCHVG{H79yXci-$6rDnu}9@D!GGc4oe6-=ewg4BdzduVup%(!-klDf&b{wW zD_35Ah>%m?UgIsssm7j{%O!FkwfZB}q+|uhaAqI!n3Hwy=)7~*cyhA*-uKmKIa&$U zolib2FMVkW*6pcqTiZF;US`F0)^gxm(T(bxbE?x8iJ}rvs{{I{dNyV=qp)1~_FSbX zcA?8D&A3#*0G-sQ|NK<6ii!|Y)+@tPgiliQRJM!W{DRn^^i)0H<@>(CCcbOl0*m^$}Vr(jGq2IV_M<1(2D|gEAU~BTXy{S8dc;s}>=|LHB5!jRiHE>hsjY7j!*+U&k5mX!zL2nu9>bn3-2iX~ogk0(~5 z8Fg_%f}H8scPccGO@q(H2DAwVRT3gkEo@8mIDbZ`WYA+Rd6xxK8iF`arlJ$^y1b6j zs;a4OwXfN{tNJcDocpq1Cv@NBUd=c4fGzJ>wB*Kv3~Pv^r`qFeKq~2B?$#hY@OtVi z5_=H2W%-!_oNy!A?Y{YFGGBB;i|T3e_M$0!?*GNsUB5N`{_o>|jE#nEbi+oD?ygbN zDcv9nN_VQGTe?9~xUL#^i zs7YR|*!H&|V#EF&BFd8#f1)aq$jSPu04}faQHt!Z9TA-FUPhHZajBf-JOQcA4h?H< z!Tncvpjg6wCVHOd&+qyU(1eicsE(pdggRfnX0&BB76T=rhMkMqr;w?ojN;X2m2o&{ zl;sS|pp1B_siL|NEkuz>|Ge!j)+IWhK>nYBi#45f<}5{elIdp9VCz6h8t+W*txXq~~*hr}vAy#OitoOnr+C$9>c=?}C2+a)7?*9Vuffayqs5 z?}fM4Wu3qkgpkd6FvGG)@_$0o&SG_sRfs3QXk~yPL{Am#r6>Ls`-~BwHB@=sJDUIf zb;%C>U$ZyrwPJU|bRLgx6jbAsjQZYN*pk}JBfhy@_kV=jpfW~V5lL$ zkogUZ>c`CI(7hg0J=oHBeB@>{Ayvyxmpt|3*_LrM^Iah(PBhC(d#YVrtmZiN0IhYYk z-`tTB{Y1BtRc%ZavTqjjVo@0SmQ=HYfQ6W(3AQx0t4_k-*BhQ2{wr$QkV7KI_UH@y zpA}+ZJiF%ij+V=#Qr|+5F<&Pjuj%j##m^*R>S}OM)#Rpw6RguV&m=M{U+qqY%{V8p zUu0L>SR@JE94Geci3t^9CMEG`c9`3C)2(1Zjj%PC%6d-An^NBC6f$h}nt4rBy1t>P zJ{1+dO}$vl$=b|6Io_JH@LN#DJ<#nHwwah%nTJfj($J z4;inM=)#w39pAp(8$;WOtY%sMQ1z~F%OS}@^dE6I#pV!(oSb{#luUWIlJ*p%8Nn4{ zK7P44cxK@FwI*_9?S!WRzBkM$0AOx>KD>e*1Ge3`&8_mk6VSIF+KR<4#E1L^L#~I! zHXR?7rf!7|NpJ8ykgSSvJi5c72%rVz=C-J0xmj?TL|K9PpZiv=25E_a*t>Rp)JeAz zWF6a5y#=!^cL<1%FOC`8#do*`YoHz-Tt%Q4Zu!F{=Xd| ztDe_%YQ%o8C@^eMl21H`JPBvb)}^NRXF2bm>IMk#gV+#HDf7kS*b#}9`@IWM3FI{l z)EOjX%;eG^g{$f2lO7LnE~UTo^15nXkbSS9_f{%F>lp=-{LUthaFdT&7ur4 zr(Sxef}$)P6tF1k7Mj2H`bCoin<_ilr_TsFv50Vy!`TkW`6QEYQ>EHDj}Vr}NmoCd zq71KoBm1~LLHWRxQn`KQxmAd%z;k842Ky{1SNYj%Q=dD|(=2N?bl~@>N9`GMuIwe5 zKX|{*B|$!1#_L_&=?MpahV8J_X~{;sIWId)UuOY6)sI#EAUl>41%z?A@4O40 zu+N*lZ(Lr}@Dn|hz5h&R-pa>MII)ImZc|%|agLzjw)E1+i^;O~r{@_fv8@wy_X3nf z0)TaA#ZUZ-PKeZy5}~KZ+M!qT((`9=S2!&7`qZRIkI!yHT{smk>B+_@ZN8_DD>A2@ zXeDpx)uPw#LTj@3mrtzWQ%#>XIwz*+Ye1KzYTF!70W_IjM|wnBHLaPU4t>NiG<27s zhm;A!)#DEf%vC`;WlkvfnK~x*C^ZTD-Ps+c%~#mvVsM+$QrXSCOjH@-5lxOh8M~(6 zb*#J2dV#xk|Mlp~{p)YKxfnjY*4Vuk=Qb>BGWv@yTBr~N!+`KB4+sJj>j~iSXrT(Q zL2ispVKmf!cn-ioXTW?U!<@ULjGCH%?$W7TfjQ&K6E7y{depglW9WidwY3Tn_PWCz zgu8yW*LzMkOYF5BY})1Zn2+y?*6-_ zDaD2l#&We|65G}JlwC9sBMRJc#O)e9N@&6`b(z_5F0WXwD6m}3h_E=AmH>l9Ffau; z7E5DQ*JGIjbgVIe;EO8aX5-CI6)(=C)oRjy^u`0ocr&2t*3lLRfeV~{U00JWaWh)l z002Mrf-qghCJ4ttx;b?h%bKL^1dK?M zG`SRS-I22&p%RbCq1CO2RpC(C2rfAZO`Zxuo#H!&N9~Q2CTZP@jeVAc|;(= zJBF+Q7b|0xHbH=Oj608J6;ae!ooq;;HV_9qqG`6#h6ir6hKb*n$g= zf9GGiU08zCwP3BoL~;<5A*3nUxU-|CGyOA%i4ea;sc!WR3|8`LWEKVCDg`GB zW0ZDq_+BXcex#Zf0hYJIQ9TJsmhDNp+>nb*J&-X6r#2nFx)y5cJ4BGL{UT3D_Xq=BZM~;>qmq^*z-@ZvRJg zfGwj(gvg|J;jprahCt1T)JiN9facuI_kP2Pe{{0lbvJXKq49e6xT;=@q~3)9=Ye6~ zQ#aTczq>x6%$l5Cw0WhmQM2oNkpT4=DRm==o8Xk;(S{PmWgzsfh z?`w)Zs9t7>(HmP9j{Cr0GGI8WdPMN_B*8Z*T2OA39Kf(=8e1JT6eHlO5ChA0o;EP^KtWj6J-MAZ_#J&it@|3hMCIh-l6e- zVk z*~?p+6z`lVT^k1~38gKYe@5XEP!K?}#zA4M)jf(#0#p{&)FH#F)*hM%o->^X>V<$S z3N)i4fM9=+6NPRR5GpJ3E~zbgYDuTuj+pDyveqP!@c=0WMYGp~x#FnU*GJ))VO4G& z^|;Ye2~C?A4EzdADTUb<5&0t1`b9-#N4=G>BAQUM^{b=EH%FYv7@z?*@cDXAWH&)% zH==bnU*yZ>J<24Jy<(9c#Xt97h#Wi-`8pwT==$@=vdF>YAgxa%0*GyU2>@KaWH&651}Fi2luQ`}t)RKZ?z6q!`r}eajyg`&uDZvgQCez2Ogu zfqp}>5c6AYqFJx*`ENAyeCC`kgGBc6MZKw`A@;F*WEW?xVc%xQMJK7l#m)4{o6q7yA2|^5G~^Y#w?)VTg~B8fQJ43e4o9Z1ddw~ zb!gZb&z)`tur^~xhkSv!76L;%2BPD}sFIz&u$8iLZprC$MkPvFu8RxD2HK$lQ~_$H z+frI`YOI<8y3ue+A)DfzjtQDF!Ls$upnL6I4Z)o_-wV7>Kn3 zE%wbzizcwyJ6L@Y)F~hchzTAkd<0j-(>Vqk9i7R3zGsspDIY6ss;x=d9H>|>eY?EH zjN`k8jz-_jO5eNZU0+94OA(GA;~brEEo#JFp4?}*D1%+CG$HFYv?Lhe$1+aurOfWi zC_5iy+!u1|x3#TOziSs_DQkYu_{1l!12Gk-1pciH2Xf5SAc)TURuT^~SoB%F=WkZ# zhe8_Pj;NZCdi^u>{xI!bckHuUZ&DZJtOz;lj<(H{v6Y<*^OV+~68^L%yrCdlJ-n!7 zAWLlVa@zinWhd_-2;{&)1H zl+(m*^NSFS=$H!ipLk;{|Ajh3lXk*|GUh&PvO?Iwlx$AN^Lwx2Ls&-%j{-uci61)8 zIZVhU`i7;vWKH>J)mwZK`|Cn?1=r2>itt;e!=uFWCB%cMXAX%ue_ZN>i`2r@UV|ep zFK+4dYLLh)_m30Kj8S*{=ZMCMg1h$Pdof%awm;<5a+oCJYV+J7`Lc2OvQkbL$znQZ zkGSLk`zDcm`6mlsFdw8ImftRg<-lJ5E`iMz+r3Qr^4l&>yaN-Cxr3(s(wm_A_r7TG z1KB=xx;|07oxSK^Wem?$U8^WK#4ivDFIm-ub5Qr0K8<~ar$RAJPgi&!U(1?e+NIWJ zg!)WxP1pECU-??mI8(0Y%^xoP`Mi|1!y6JA%=W=;IhR%MW$QkK+QET%nt#o*W7d<= zHeiJ=TzDtfpB7ccQ1KpGW1QkWi^wPL5fd}BKrG?lT4&=BGCjN_5*w1R0m{T1zG%y#78yHDBWTpsRU$|a}Dd+O7 zj@!-4U&SWvU2lAen*NB3>n0mA%jj)pAKJDWS{8h9Px=vS^mUou4Numf7SR9xaeQOf z3&`)|b^L2N;>`>BmPOKMZ+)aR2pi`>vKM^E007i<`aEhuuZj zi-B5ONR8HDoa1GuU_7oUNPUKO$T*V%nx#G`IJtSxsjcK(?Aw|>G&&7Ky_oX7Y%+e`2ut+md)uWlPCE+gOS@xSuIDcX z_Ff3=gWUg?n^TbKB)dfxv|XslZB$n29U z)k24RBIC8^e*3T?bf2M-Gi(X}6;1k53$Z(O{yeH(E`KvUnWbjHi{fIVjxKyInBEVN zrX}?dP|f(D8wPTWUsRCv2)3>0RPRHoGXs28hW48pH5yb58ir$bFSN^Pa9i3Ogw!)$ z!}KoexbGZ{_gN3Mw%m$6NAqkIiDFJd3=Y&NmXp4ajz~pi4k130W%2VFGiM=SDfONB z$wdCDTQ7aq&H71`ZqHAPkM2vL_|@E~d5)*RW;5fZoLCtFYIuMYDt1JYPgzYp2MN3u znw~+IRY&)LNDR9h)$X61>Pj1O{x?HeNM^R-cDpSdE;n#CAgf5YWb}enn8ZYjA)egg z@P(Y;l9iL|;t;Fq-3Q5!()_VzrX}VF5V`Gkkdg5#t{2vhIbKcX)`S*$tKau8_{!ZI zgmstm@;@!CJo#_jGyNj!K8iElp4!GhaQ%0apYod*whgTh3!2St+6U==WpL^|E4$#oe^WHRozBuIrv8Qza{pFU=Mz3N`7A7Hg!$g}_3E@wdt`NTPz%l2c@ zzq^e4w>*E#^HsE{B=-p7Q>{NT;vDzx#z0ZE9K00)5%1+!l152C*Ye8w^e&XyJ!_wg z+u?{eL)|TjnBf1a5E~Ib$>wmyRi7BPft-SRA9N(79hM#{2yN$gMQyizY`JXcAm;pw z={|gOJZ%h`H<0#7iJNaniq#_PLsnbh_0kJGLkbMlB1qPu`ALQnVLloOF zGbE8eWTo1sj_M9d3VbWeyvY&L{(0c!r&57DN~XlDgqLsI`Oe**XRRNvlR6?S1zYhA zflngo0U-6U8@xX0afDc=VRse$Ef^5;63=um-9~=+!LBuPlwq!P+qy#lyZt>@sc5)(BnvSTX-$w($u$H z)d+@j#8l?FNeb2XcPqw~Oi#F7n>k6}&QAfyeExL=ASrxGlnfn9XR{I`)M^R>X4Gj2 zhPi;VDQ#7H&7>@(D`#NmtH+D*!ZurOElqh{Lj`WeFw=YPvy%yMzs{V++%oC5UW4MW zdF1OEqhzC+3|f4VD7zn#s01-aqh=H!2*)ZN;Y%#zZr{3;g8*T>8VK88k>g6q{5NyZ z$0PfN-Q=I?pZ8|6oPn8`!|vVlYL}wLtE*gYpZ@8EnMjzv*0Y|cCV6^HP7aTw`i`ar z=n)ypWW##d7;P#uKP-f7jEQ3BJA(K@c32vBT~nhqcNG;57CcKp0xrVvuOMMI?apb; z519>txeU`NsuGqhG|M^>kka?MN~lS|f@ZDv!h&29(Lw~X&9tN^9A>YB6HwV6Lm6my z^6jS*xnfL6_ods*l@E2ul19O=1R7m?Q4p$3zf?bb=)aDUn6dRJ?VeO{Gm>0T4KtUa zj0qOcPm84`t5|ANIjeGTV7&SnUnC02mXm@fF%};`2|05mC-3C}4%*Wr?e7Fcjqf?j z2PDygWKFH@hE)$x1W}7>2(=4s@BY0-?*Iv+Yn=pAxoL*878fwVsz5w?Z)tkOYk(nF z#D9F=>ddHy30JrmF&Oup{YpdM`C^iUi24aT?u1%Z{eqa18SV^%6=Dfxj-p{+ASr8L zm@>o7MPj&aF!BQ$Fp6dr&D@naEt)I6C*4-`*4wDd&vX4w46RfarYx)UVcM6ZQUX?M zWM@{^%;%{K2CM|sKh23X*6oaoNbpv7rDQ2cU<^qHV?3%xwzwL&M~szx>rPU>zE3M^ zy~tcE{?zx%&Rled;l539s^2}bfL&)C;`ewP`s^Rv_YpNuWTv0YDm8|0%!QH>H5JMi zbC86JT&)&%3NH)WIG+zsp1e*Zb1bV!p~TXDI|8ZYPTK>(R&QT^2m?QV$|Hba#WQ)A z#R$vjetOxx)e?$&Z)pF3g{orVjZBO{NJ?lJvPC$P2QZ?7PAQBs-(au!}AU$;b%d_XQQ+d)S!}$Y|9th|iDgdKKJK`2G3T7L0po;^tnNo+~X&yphDU;0VqA|7-$2!dZBT%!B7=={>8aL z0r_D=8h4}7?h7;7CJzW3DX-C1eG_RR!k(D+@8Qv=^1s3HlC$0~OedBfwFX&5&wIXW zo;;P+<&La6ZwGFPDZvzPX*gY&-VHhn5E*=*bbD}7(Bs_v$2ITh+RWQGH-ZkYC|Bf- ze|N?{z0}e6UVQ8;sd-hsHTuEmH)!_KO}nG-Lrd)$X%+i#DVFQA7dLYnJeMzHKf4O8 zbo_bcbY;VaYv9`&ZF~PqP-F-7pz3s@?K=?3ic#rug}UstgSmLpM|`62&U8$k1b zc3C*~n=nDjj*b}oPowA!F6h1Zd}|&1kz*!C?!bef1AHZtd2O^!kXgy$g8|PO8^LRh z)Y~D!qd+A523rT(5+wY}!-gju?K3X~;Mz$hUNd}@muie&z6Ukxx8=S9T7IBFV-mw7 z(z$7pCM{Ufmyh{=3eHE6mRW9eB}XTexP03Rtwa70?m8f5)9U+m?8rt4Be(vOV$KBD zu0bjd?W(oxPnu5ym^g5p)hJLsza>FXNZ5h?baS34lfbocg_5g-=G~t2#p@=>ZKA%Np%nDvGV;X=i8B7Uh?MM*r2c+dAx#rbl#gYo4Nk_p0;dY^;zE+F=e z!*Y}Jy*QWZEoQnoF6glrI)H~$0NS0!Z8{I->0ti~`{$9JDHJUiq0dXWgNnVy!w|r! z>CbnY6Vm>MDms8Y)(jOtcT^#fWu0v>f|27*;;)?J|FDS!>iJWrmOzFQeSKKn^tm4FZ8Ia{6r-|gs-)OR#FEaJ zTs^iJ2t8&0y>8A;Dv0R0l=3-REl*oZnu(>`me!d*iHj8~VsUpt^B1pyS{9cN&0m}h zfru(O-2#n@jkJn?-g%}4N94K9EevbYC_Q_gb?TCqa4Of+92>zH@&0N1reJ$jI_dHA zC7tJzK?shdJFl?PW=IJu2G>{tEeAgJ>ut(PzivJ6b4%SIm9BFO`wF>=ACAY;=5-d8 zjQa!-`rFcZKM#(@v}jGq^OflGV(2$vNgB+q^DY*7#-A)WZ;Umr>F{q|P%y+{uhxO` zw}X|iz28W^O##6IXJJ`IyFYrd^o5Hr1SrttDPWo*>7Wi7C#z5- z)LGZ~CDOxKB=S#yV!kiAv|n}poz@EWq&o~j1*GC1Jh-Z)Q;>QbA3|Y7vN|urKp!Gs z704Hay7F$)rBokReV}J}iT~vOT?L3Z;fI~@sQ%D^oPtL!(jmiUf#eX1u{{oKbi@1~ z!oLi>t$AGhBSEn*5x;*@D$zb({ov(L5Zp!Y@>s@1p<*csOhr^kP$%n)V^P=j_VZ#O zAWU;T9r^Gmqad#AxAi&0F&U$xZG~JjvR1)5;)7K@+ek#mpNAj>WG%t+HeMb^iWJ5vCS-dHw{aGPoaM44GZKY%P_ zbmb!a<)&Gv8!HP$bx2u-$JqQ$|MB5YIbpnWc)aayysJk-(tSj6G!2Ba9I~Al^}~h; z?VB`87nWA|x{yo2=07!&RSltuW#8uSQ?j|kv~8I(Y*1pZtUyuvF)TM@C0+2sVg?mY zqMp8j3SB38a1L~FnJK5_Qsxp-j+2e4?cL<~riX9^(Ps-~=FhwZ zSSZ_t+MiR*Y@;bj6!AZF9ZdZlZ2vltku#eIHdsZS^V!KM`Hq?}iF(2PlmaH# z5ZP^zd8J(3=JV&2!uQu|{h6y3JvP^HaSC^VrT zC0mtVc%Q#Gl$;f?Onq)o4mj(-@X$wCMn8Wv{3s~(WglZ~V5J-*QcRgOd$0$bjUc_L zq{>D=VIO9jsUYz{78@$LYA^}0qbav5D0^%slEbjm>oX44ex5a&Nq1PVfv-VNczp-t zEI~jmJ=;Mv!z1js6b6DQ79rNl=-2jDxRMBBeElBlEvZVmPR4ht11;pIW3jWylYfE{ z0k`=sXKweFB+9*=lvQ)XgJHv9R<>ITx3Q$##;-==zHCxR(2qMsO~@;k5}VHVYY(!- z5SpEF{N8%2uRMe-lL?d-f5sV1$d!Ye3RyONxbUjCYKv~P$Q59%l$*Kyz;PXWCl86* zd|w^|PGBLxm>AeGV&{}5?Bu;Gl~Eo5=`$Yk=D}M=4$DOq97$@gZpZwtMSuv}igP}d zl$5QO%_6BQnKwb~PhI#6L_Rr<0AiJLMq5jtAM$KFED)+M6>)+@8pzVTKl^6f<9A#w zU~^>|p_sxFKLTiu)M|8%wk%wMs^P#`#P&m^7wXaR}+7!uQ+gG-BwpGRMTHjUNr)ew}_nhJonbY@8>y9rm+JeazzZ z0<4|sPai(|(aRq9&}lh1m@}gC-R;j8w_$%NuMdMo_)HKprC5VQ_RHY%<=CN1&re8+ zN^*}15{YPzv5Jdc)j6%9fY5CZ%WX(I85s}*V4@+!GU$bhivMAhQ7cEz>PdKv(jIkO zHIYt56>vo&!8Mh|fYZuWBE={68KJkM`|F+*Fy=~mt|^gjb0n20MP6Q!O4Z{rO5bnm zHs+Oj`MTuA_9V@p*~@uW#*zcDTMM;xF9YIt&pjuTUHKD)Q|GwWqV+%Y1xKE>toH`} zSSw?(^0Mo2m*)QAUd5Lv?O%fk3$yguewq3~CZzed2xd~_kKT}%r0BP|rHYY5%|%Uj zTir{}Xm|^ca!H)IK0mXk|82F}P|ePjHRX8%m{~ql}@PeWQpFlUK${^5)4J z@xh**ZQdWo)7KRo4ptiqlvS=mkB@eyOa3T5MTJ$l$DZp4295>_F!nttpC0tMsr>i% zv(;6(zhD`$eFOx@p5z>(%Y<5txCxidB)taiy_i z=BV)Vb7q#GN$MC%eLe$K z!`a+Bte#AVGC*XVoQ|H2*b9ZESBchLTrm^p-t~r6A$u~MY@LO65oaJc}bMCEC zeDk`ZUT3#N7Ys7rniyXOaDE=I0NCJ|6VG&{Q2K z>CU3`!P(~lL-FK87pv8iH>PwAGPiUgY)2Acx%V^oPWrNmBsdlM|BSD&Ub9tVDzmF2#^ z{298eqPa+{m+y2v=4T2r@+;Q>3afl2fSX@YTTM>@Rf$*0y{sa{>6 za8q>gsY#~O6Pf;?lv1p~W^olA}=?z3F&@DCOGEw;EIV>7V^x{f*UBJ>7G!7Eh==_GbGiZj?JaOD&-0Z)egQ;Tx)m z?3xfR?ViOyz)F6Jh_Q#F4cX|x?)y+=e*_vKo1v5xHtS#^5vqI3{Qa}Uo zxtsD{*vjp=-YN5qgp?(&TC()y8NW{BB1+eL00^V_Nqj7jfxzNj_o|N9&3wTfDZT?N z|GTJL>7}}z?sL@J><4rZknyG?EkUSZSiad)2>71ZhnUy*w{DmJ&2`gc;-oSp#ML5L z>$g|}5I`4yP$Adbd%A??>NG~VRa@Qlsu?eu9O)p0mNuiLDVoOdW!;tX4)^p}dd%|K z7oMqFeBvdI!5HhQdFbD%H=Wen3%VPkr0~EG`xSm1p;Dt-A z&o?shL6I1hT{PTsk+b)1IKVIUJ%KgKxNq5EH>e|TmGSwq_u3~BlUPqGhO1a|$SOpN zmJ_A#zs~rxJyE&Y1^PH_jN8&L zNk46ys$6bd=-p9*9mN;2Hn|D@+To}MOQ(OWbg$^7xKSJC_R9gX#{2lC7QzTpN` zzhXiW+l1{HHMBE$0sq2V)bBD)ye(BlrGy`50)sXtl7>Dq>mikIBa zj+F@k)~+{>FCsrqZ(t%9bene}0Q(UB;^of&E?#i|yLpM-ZmA$t!yaYO0?w@Ih$No+ z$^iY&s2|Yqrni9`UhSz551x;ULfRZyOH4F z1i(=iaSV!+jhwU{V^I~{D){I_vUY=wzvJ)r_g&wP%J!d;a>oYMM;y|{5{dAdfjrtd z$?Y=7rSSvF1HT4;J%(MOiC$$Q8N$D&!dgBE;x=NqlqxgJl{DRdGT|?iImU3rs%Mn| z5Qb$MF!_guWfuKbUJ)2nCi z-ZQ~yU2e3JZV7&)jB&pjAs}=alP40x!O0P@=QC-=<9%+(O z=q{J=m@yo~nDnwLA^Wy(L_In@O!|mVt)DN!ZSuDNN+Ne$VtQiI@A1TH^TcB7I3O{B zK_@9MEcthSGKM?3bT=`!9+z_0BLsUlxf*5rZ1>g^RASjha1&$lE32fez@&CY(au7R z7h$Q*sH8FLwEL)(q53=66@xmDloGkrcZ}(Mg=uek9I~arxJ*JZZ2G6&^v@(uwop&D zb-;;e@Ry_~d-YF#Or?JfdvZXMaa{Q1Co1FIBjb}!#-I9(gTjn|yBWJH88}qtXU0sh zO@_@8EYwPqvzi zp7Kv5GYM&}G>HH(r%5*NYG!Cd0lb$sa<2foTJZR9K{S71gl=KHO%^8ro+suz|5})G zA(FXDlkqntU@o-~Rix=(v}09NkyWJ8QADa<^nAX^@3^SQzqsC}STMJExd&dtRNS#z zoYhq4xdRaDBnYJ6s{{Jyb-SYGM<$sdP|Nal7+=|9or;J;ZBR#v9 z<8`S>=isn?G&vdzj~9#ljiu|OmZOwc>N~jc{}tu970w}@bw7Bg@!vJDF4h-#+%US_SG0()|e_h zv(STEH$Jm}Q@P{}+i$M~un$^8;-xBU4fbomTeap7o&ktDyR~Ov(+73=56q|PWRB~+ z1nSN7>hXqR4^RUZ2fswa_OYY^q=4IlT95rYJ+gXlJzRsIExe$(LFb5U#{{;DB_TvM zx|2yi3$|@|Zc8}l^NZg1G@rKDghUeqc?pNIwZr297;=T+W|=n6k8-AwfPAj$s5aKH zgJ6c42%pp-t8AXxZ&p_$Dnvx_T>gK>ikne{(M|QwY*ocuzbe2v+sQ)!h#f#VhlS4y zw4lY?ipYQ_4Ec;eF!^z7U&PaFEc7lK91MqbDFE-W6gB{)-me)PP2zwCTbhu6$&7-i zk-vo3f-AwNSW@+Nl1ninso{1gc?Y$A2YqVC6dAzsv4ex9^NBMw91GTQCgOAR*{$`F zKJJ9Ebnq&4F_d)3PIs`AcLK9G@6Yr;Ux24WCcsjZ>uohTu zC)Y(2{QyD%zfS)CPT}e2l&Rek)=V`zyyyM z8re=5ok?Z`&;LkE&`)Oc2j2Xn@B4l71~j~LlMFZlrz2g@PxVd|LoB?>)^1psE#hdlkfg6^FoT(54DF+brou=8%RTR5CMeewxC|o#be<^Zvku zceDRn^2q>uc#zj5;7oj(Px%#2ev$eR3<@TWr1of@(7{glcufKDNqi3=!YW9+AV@zH z_ppx~$YY%<8h9OV057Ki=rbuj@H)x^(gM#;oHHRXI|(_SY*Lyky?T=*G~LbG57{F7 zI5GW*VoL1Go$GTa!v8^|PA1H+H>pYKH$=fU7?jN+_I1(zNGBER1XY1S8}g+Uh24ly`W!!s4d7CQoFJ(-E~;9 zDqfy6i2W-@1HeB>IxM^!aGGs?*Gdeu|Dme`paV<5CqL4=;si&2B#DM^?^crYCNgGv zzYk1!e>wA>&~#4i#q8~M;5mZwnfz*=!x}}_*f+to`0MxIlZkgQ#99@^2S>zUf5HW^ zs9rzv9yFYD6YPLld+>p@O$;tdxgtRc1g29zfB3O?@FOt$@fF+psKfdsC6Ijtdpt<+ zZ?@Bsa(T}CV^7P+fy0lN!1{Y znUV%CLpc4>@>}5#u@9-|(>InLemW@oL}0Xe+aB^mj1)q(^8W26jmE^ifzfqhU}KW5 z77bM}q3Wnuze`0~Q~_5~+E!Vom28J~Q&0(Ptb((~^p)U-25=7car=Q`N;LT*Vgf$5 ztv>t#+yPA%oA_)o@?94iqX^HLt>$dEZT>NK3J+UohmF02jk=RgA56cEqP}eew{(PC zLjl{HFZNI%0VBBA?vqpcW-XE0!||)t)34!|-=c{hrs+OhcK_a3`rRA~JWyGG2nC+{ zMUB6Ny%O8*Ie5`$@C|%Co%r-y)W)~5ue)P)cnWbZvH%D5R)i0x?cFmHA0qN<(+?=7 z1SnQ$!OmpgOzL5kz}jY@>m2A%tcftIxATTB&ktI$2JapEp{?ZpEV9q4q>p@fzlFt1 z&#_AL5oJFa6<(YKeGod3Ds`WkAa0?)!yl5c_k9ep4~g3d6tO6bP{?+BYL zs;LZUz8b-ITYnxnh8;m)wU-gxIAXy580pGi-=F>@>-c$S1poD<_U2Cwfez--8FQmZ zO$r09-W}a+5S-Qdr(w3q2AYxp*i85@q|h*T?QvtP=n+ zBAMg+Z`t?5_w9!dW94^8H2v}aTnT3$EVPK>&T>CNPazTD+qog^v%nLz}*y z9o&nR3u`fS0k$eg36IYK;M~mk+)|X5Efb=91WV6^g#IDbj zq45*_6Ql~RGlc43oA*Bc0Y{(PzCT}4x$sy06Z{!e+D<41Cz{7nzF)lnj{d0mKE<2u zP<`SbnWt%2go+rV&59XCIH{Ew*xrQv0P(ldw$n!uRsx5lIQO8`E^9L`!7jv2pD)`u z{&hM1>(?XyfF;y&CSS>f3tz;D%e~^Fx{~s{Y;d}2{&lJF^s3wUAApYGO^OkiiV-1+ zm9VB+eRVzNd-eGhyeQ&DgACFBEbay0^uHm|mwa0{qj-$+AZj(5s8k3br6ah|=5wJ6 zZm~76&oY@DFjS-6W9gdxqMeDcPi?)`bh_?z|&0zw$hb_k5%a>4CKxn=c+A@AML%q{SDCHJvg2( zhTHSR3)&6Q3TAt)T1dS)x!R@|!QjEl<>&pO7K9G_N6{MN>RTUsgdC`A?N?9k&J-$# zky*WGsU;?5${J<(Y32cl_&gicen*#?;iiqc;yir%vOG>U^d>DLXm5ekqAP?_5t(HE zbLDMzC7e_;@+-T=#vxO;2X4OB6y|$vTUmJT*V_5oHfvwdere0UckEYpG~y+F=Ikc# zgYa7jztyjFHn|5Go8XGWRawLZDb(uRERo%&ai;cxOTku-f!W+8;vuLpc2Qs! z#9@TNRIi9?Y7-ZrZfn}0=)p0zzV4pk>QhBC9BT-@HZ?#p} zm%LC%G*4k7dAwOTAz;{SN|JNWVO6Wru>J3pNxZ@J_sqDX3*xjm#2jy>&xwf#wfpW; z*qtYeH`z&#cc^UGqbfj{d~=kyC9@u_I+%k{NnH*Z-=%{uRCSfEVFMH{5}#%r>Q3IN zN|m|v;Cg;BnaW=Lvr<0S;%Pb_sLT(4AJ>1)mmKG&U!NHYIB#(%m;O{EuK6EEX?KQY zS5}#?VQz~TAr0G%lj;4&rF-?385ry#!g>N&qp4EeHOv1n$`5dw(D3${tk8^4JH(1p zf3+b%Gv;@qYW+0|7M^V~Y#dL>x9$hPD-*LgQpC8;C;tzlWX4c=ADQwMh)_44&1>Ei zAu5gZt3Pp(y7_-EH+yb5xH>Xwgo1rs`#WB_{y&UTIs5;ycAs5My=|MoH%UlB4@C$_ z?@b8OJ0bKYMUgH|iqb^{MCrXFO{DiKK|w(2y@?`72k9WvyMSi$zwi5*XV%QTm>07@ zz<#mUUh7)xI*;@Cg=HTMOX31fY79AJnNECRuTEAo0{>pfiu5zPaW~@&^{z5RS^wKG zd;+KdhySNxc#ZpW_2pe;bCl-Cf+y%-{8Oykv;`*^OIo z#50CFJ3HIk+gn>(o12^eSH=+cqYF1Pg}mKNN{AY7XUu0eZ{{Jv}@;+}+)Aj~sDkX1F`LI1IYn=E47J7~0v{ z+1S`Tc<{i|($d1h!ra{4)YR12*cfjZ8X6k@zZ!zhA1{r z*nb&@^*_hUjjF6Ze{A?~!*Gn<7TIxOox=&({EbH~|awNLy|RM8)ANq3H8&6 zKDa~LxL&@RAa}O4ny3WjD|Xt74oVjK054_<{7bJA?G;(fww`*|*!dsBuwp&k!sq9D zhIItrMy7qb^TunZ(u$2Nmk-h#Y?9x6Y5p-0H*Xw6tqJ z%$Pl<`M@Sk;&P`e;qhLxSh{R7-d9xq%C{U894(4W-)MvpJrI7lvOnYxU8?zOP&eNNCq^yXQYR z_7~0}H>z17FKr{q?#@K#Ei{cfE0Q#-d);ySy-t76Dy5ScUI)^G#$o3S3KE5qmTwEc zy|@!swb%43DY8mp1L>@Hwc8|Yf29Gv!>U4e!!3o=hPz^d@8( zc8f|0%nb?V)?vfyHzoh}OAPM1>g9nP0dxUmoK!SXaQIU^<^+VE%;o*Y{gv!t_b(3P z7lf0%8t9R|W#CUt%1-)>1M_MviA@2rLL$GV$dPg@Oz!8BYSOd{AXgXXBsfgpkLs!sQ2KRt@&sD{(OY3dWpIuat*IoP0DnW1tcb{oup?Sp-P5haY6?jl&1&5=mY&k46sbK?^I0jAc#VJLWwA5 zO9^HjOhVTZM3|MzP8YqU=@Vl3qKr|4e^v8K@yHW)AsP+PS_kgS%gf_DfQ(m>+G7|w ziU24WM;ZNClZ*z6z@WiiK0qn-iZqNa6BQ-uz@FsjG#+w4$pHP1x9z&()vG;~Ii7pO z9W$?wa!=!a>RU4;2Y{^eK%Xo0U}pOK%wh#?sr^d)!STUZTUr3st+>)T;kyK;1)R23 z=Efp}eOHPAeL#4Tl0>CED1>&x_V?^h)pWfzC>Jsssk!w{?AzT^53c)TKDOh=-;Un; z);zpJpsyPCZHx)rT*z_DiG}rK2`k@$v^52QO0yeP01}|%H;DJ%vc@V3^6Ba^sG(K_ zQu9=QsDu?zC`Z}XRHjht4UiXuR02^zFlRBskcI9*kJV+E0v@Zf5@|uto z0$xbi4Na;l#Ng2UGeZdB;B+K|-Y?UbxRhw@(;A;ZiK+B~51c(1Rk26d5UWX%MzCM8 zK${Ida>PdEkjagw1Vgp#pEUhL2|9Veo+l9iDR@fIBxp3+(}$=0p(eiCz!DnzffZuX zt#E=S*j6xMpVGDUX&kmma%sY^GUpz=Jc#qVwo4!;tX6_t4M6X%+{9Nd3#NJ?G|R!v zRnrjT@T6Gp3A>xI2snukL1Li&w+^?Rop7UfOKD=JTz6=nzxQs6YtyXDxR=ZmZm`Rz^MlJ^KBZkamw;3N+pH{hPbD zvofk2B9LhE-Xyo|Wz9RXtG~x6JnPXHf>eqWy(7N_A7|x|BvT(4(O)HX7B;}_Zar8sA-ciOqy^*swJ^LoLd$h4fp7F3b-1oz> zwqwfR!a<736(@_NW{5TdCS9xqy~63Mg{vCD?Wp7rlqICt5Sk_-ByvtFiYp|5(Ap}cGPXxP zB|qtfV(akL-ZS-U(z`(qUaXo5i*>$!k>uEJ0|r=o-V84u#ufb0V_J$pUOw`EZVja# zLq^eWEfa*!E8hSGtER}vjNLu|dD!toW35cVA@AGQh?O?E%|-=}4FOKju26_lNP$zt zxy+sF1IPmkErd!rhBe2!52sXUs}Uj=x(^`KIU>x+LV*F%t=}&WHrFd&`pkUB-7zi{5xw0nx)aP|{?BOT^-qI%oEeEjzWKB!A5)R0Jvr?eSbif4A zBmH|U$PkXLmwA+dd>0Y?$fulaevHA|AA7XDAv#?uI(=a}_5(Vj5Z!Mo2vCH>w zLCb`PNpMKP%bh7-FL>k!C$)wFr%P%)JQ&+{5!-=`>za-=kV5o~-&bnTCp*=r6gRjL zE(HV`K+$B%Z~*TgQli83(xc(i0qVX8qe&gUi|EZ*9w6qHbE0XR@33jdO+H4 zO+aKow2~zA06~FPLwuA(jDCIInG)NW86x0hxcG$NDk+J$If-;8iTrgE9rpf!hPpBr zLgnFIjgq^%>;Jfmc$jJiVfq7`NKp{4-xqIq5%|Ldaq|G`6$A!T0>qKgB{18v3?6)k zS>pE&@SSB)#W7qf2=dB<;wdY_A&N-;_r35bU9=KWta>buRFWYdg0R^X_B+Ysbs8~! zGNEUjVz{|Lsky>klc+Qk0Bdr+L2=*OH?Aa#;XG<+BficDafcO#*NDKuUi|8>w#s?# zohS_%fI-V7drA~v4j#}HGq$4;&#+`?9%S0EG$ZNPN1REw`a>4GW4oJPXKThizh~Z< zX1gVB(Xwt%vP_cWLEOYj$sO&cCY6zu0rEn?oW&8g>OKLlgW?@tr~dZ7NAHxzEw`d- zwNYXVblB2DfM4IO_EmiegW>D>r#N<=^c0`V_b3+v?}u z;-}Ix<;Y=d%L7gC=Sv^_X^Y~v6LUat=u?bj#>Y0LO#0b5K7!6Vh&3{WxGoy1l1ox)v-w)-JksyCqhjD$ z`k(&1Kd=2jl+mx85PBx0+ZzQoYT=xf`5an-WHE(8<%P!mg$X9bY9CXU%L$-tt_2=N z;=c=I%pAF9i!LQfZl&gS@)c8R6$|+nQ_s4vEv2BG5eHDX-fV`sL&@DsCq*;GZjJ)a zij)U3_-rixzb5SEML;}AuTT)j$~SF&MUO9iUHNUzVq847^E9N&hH>kDj2;L{EX5!y zi0QIeIwl{lW4^_bpIDQbSR;bysgZWl>@ww`iTn<`a`#7yec)mq=L%Lzugxt*hOf}Q z2t*K;qG%~A$PB>`kXPmt%AlYT8VHILu)JTnvQcH}w!*y`>Aa#!dUZtkap4@isxGF8 zZA|znA0Z?NQGlf=JuO@DLu9eOBsTD?@2>tFBY%$wc=|*#=vXpDwDwG^Heg&N{E5_! z?Gn#z&3E)Lo+O0Z2ah$GaODGfDt*Mv5>Z_e`FIc{p|O8@u~(>?Z+m=p6~czI+=(;MX0*pfR}fSFq** z(H{iVL!kWa^G8_ois|Ua`ni&73{1NTfjJ2C!^u>&Jw`ZKlbt4!QE8)New;%{a`H}f@j zHVn68>Kf@kA_%NWudK1bj|*Xf?VO~3#{O@iBEW_M~fH%~zK_TJUakXM}I>dUU&G=xBcQ#Ntb;*C!<63mKwfD2d==p7(l(|Giw# zyiTjJ)<@%e!dfFetV=!m0i8yIV*_=pZ$ku|pz_~*Kd7ufZ~J-E6hE)Q2NbBl z<5D`~vyaF0N3md+3$Nzt;z~>1^j~+ z49CxzlP!E|oj!G#F8ec`@?vU2mnyOkx@t0Cb=-KDbgEf* z(UWVzuw`-Q^N-e6Dw#M$&1!T0&Bf%o`Laig7fkI%@rxDlcp-6?l6;w=b2edt>MN{+ zs8fo*qX0UpM$Y_=xNWJLWY+A(+?3^y4yI3rmKjz8OEIfqJ^Bli;Y;jpE1Y}t9B%$B zZ&w5sfBbc&bd<;5d@FUby9#4o$;(--{j@4Ev#Rg5prNQjxVITCH0%9v^`^~oiSF_Zq2&Vd zZTjV(qy+@Kv>mUQB^u(tCt4Y0@2yAW{v>|CMJJSzp0Hy6lG13Q0ltK=<9I))yLCbH zD>7lVK3D$zOGK{x_O|6%E%Q99=cIG%wk*fAH#3B+kdwaAkyGJhv$VT@k ztM(s~&D@{_EJ%J(+K9T;P`I`JiX+=&)ZT~H3VitcbIoe+o8AFQ@Yo9yN{P^2&M!NC zFXbOB9$FtB{=|JgAfwnN#vzOo#;I|_vaZMB2|rP_s{^C+4DOUG3d?MHzdpXCoOx09 zgP&3YL;4~9aFgr=9k@!gza^Qtfo}V8^Kg@f66ODzK;glT>X&-Pz*8^w<5j(5jytC$ z6jWavylzmUnrFuzepxrJJ?qas)owo>UpV#qOUY73+0^!M z`aro+{dLEiC1lfJ}xl8 z4ff1S{n>2bGhnP+TS5=OTe_RXnz??_q+WyP8c`+BHA$^{d=FTn;+W)LLg)?GG*Y;9 z|6>^5vTO^Zr{;=^zkR>&g09U= zSkzpQ9xJhy^x)}Bq`mzhGvEC_U;1O!&w}v-&fPW@cS3c~DCe?Y*Bka%biO-+$dmMQIsdPMqQ~>06yq-cFw<)prGdvF%3#@ znG^s*YgaK8)@yHwj=HN)$v?UrALP}I#gl}RapK#Vn#jwR0A@EAv4G# z$l)i=+GR)NcRu6=82xxy{8)d(5(!AewmKkmEd!kiyuZta_yt--v~M-8d2x|bzpq2l zkli%WVR$3(3M(e6tVAqb$lKAIXFsjZLghe{QkAV7(wX*js}4$%*p}3n>xTQA^fn>z z$mWD4@aW$T-$R8ssPDfVzAninQmO>0)g&XKA~=uzTkU)IA2tjNQ<4~c79Gp}-XPxj z@y3*yk*zYhgv9hE zKQOqI-9w#|9!~FG*9cBkLzt1)DLov*yx){( z91(WM)yWSM#RhK`>%MJ|=Xda$i&5csMPadJ18k%y{CMc&{%Na|+;nmYQE zS$Qj*qy-Pxn;r8y3#YL5gd8Rng^4m|Hc^KG6=9NVydk^=I5^57kDGavf5t^Fnk&Z{ zaTxXb5klU6PBm>z=TU- zY^guR*i5D`^d2K8v@~gz2vmIL9Q7he8hAX3NX4h0Z&#Kv>%7$nV^)+|;ZBJix+nv6 znS%m+=G=K&&N?F|pE{epXcRx{3BKd{8SsCI0T;huuxByIf8HX3-?`!}dY;`}p6Y1w zY=L$9VSnpEPB%~c_4B86ap$##l8F~PVK~I!iv<=wnDmNLr&C_Yj3dR?x+0NY7~p5b>Gwrs*+*seiX)8qPf;InBtw1-q`a{&87L3sjW~tyBL>X zs9y?A91NyH-J_5&CQV0s_^R1{P^duqvyK+dh`ZG#nxEwShJp!nJD*k*t|saq^>*hcs93Y(3?Wm8-<+%foJ%lof&DWXXF$4>jGQaOMGSS z{%>EOa}FK`5LS0)TC)g-mGe+Apr5);6e;VJYtzoQMcgLKr{IeIb8tVCKYfCmL)B43 zQD!`MuwEWS=%B{*(I_{hIE+Uuj`vJNBj<>!OiVmVH~HhlJ-&Nfs2pPX&8=@Mnos>$ zCV-o39btS_eFOu(4-Fpp-z}C&t8o0BB3@x%;-lL^^D8P+&HX7dFeUaz* zi=OK4#{x(sL9c=u+ibLZ6}o=hT^$&2&pE{PDL|ABauA zm<|wAm#B_YXz;`*tFsSN zt^48b_~O=JF%zY>^IrFt$J!6Bwx`;03+^una(N+VB(GE7bPN%nar zJZ-VV_nP-BLcNm0x_}T$0ji z`W0G(@Y@?aJbp^zR>nE2^FK}Nn$?wGdKQ0S-1<==V^3&rw*o);HiGh#iob(ygb}_W~2U{}UnluzG>jlrtGfms;PM(FSc7G(4;7Z| zhh6)``mDKs47aCa6|@-?ejneyoNFPl=(wsPZQtgAYmjXj#h+3)pH(SRgepSTl;W{( zyLdZNP_3_!=vTbx6sgYSi#P-AcyM{viBbCpYQFQLQt(d4#9T++P{*d3!p4)1ekG&~ zwj=qX9iZvh$5b;_H!`-Mca1t;(s#AIQ8@dB?z*U8&s0va&fHp!6D*d=3cbbcqP+54 zSwE$7)J~~;pb|Ia2MCiA)sj>R#VJpNF>2J^A}uYqPdZstFq{FTWq=@Dqche+dT}@k zO+z#h`&PCG(>{(dsO;j%!cci*QZC{oq;9D|fFju*EfodQo=ysv9+3bQO}TC;=iATN zyfEpmXzhp>z$d+I6)i}wDow9JOQ+#{y_gur3PM7IVxx)a9P((k*{UR#Q(YoawXj#C zfJigkRd^7lq9_+f_Lcu_3T6bsANdomn;kb8+UM}8*CAEW@~+e)Z&`0nQiv}xAEMeN zm6QrgT)m}sr?^)}PT(e|`m$XQ{oSryZB>OZ<&mWFuSvZ_ydP}qNS}+LJ+AxT{px>V z-x}3Yfs5p93F;Zht0GO~PYg{Z{Ywy*c%YW-J@7D9!?0N6A>)9?ylU_WF-;UWzp~%7 z1^(F}Le^9xi>5QBzW0^NpeH02p@NQ>*UVwmD$-FYgaD7{EA3SJ`jrwl*))rFhRp06 zQcnieMb+I3hmw$k+4h5(13cv#K^52C>nW7)NwrfDS`y#-tHU(%=cQv$6f$;HpWY>o zzD#qU7{omR+I0HLi2E)4wVN!;YO>4TLPi=U1bXx~VgL}}W@jdZgH-;YymNbLg{bS(IFK4)`}UJLf^jKo1=J-XC}iU)0}p=H^F zxDK6Y`{=qrC%U)`a6?7pP`B1}vCvGt;+&Y=m-^_sd7fc=jlV=;l@PsDgx&!0>%pNY zMc>GQtSVi9-3{;0>uaNv*UGcmx2sur18%O-@K@VQ(c}fS)1MPrQ{+ zC%$}v=w4*^bz)hhf^>dm_fGKhTw3Uwf|!W-@?$%Mc30jeT!aR|BR$IrIrT?JXud{s z8kC6Y$7k!m6^ygy(1oeSkpKcnLETTJqdzN{<5)$gF?CHHQMb0h0tX;-U)aZIo_MJ#sTIfoDtu(Kv1-(xc4+^~>i&aa#gE4kJ?aXdAj z!JmoY`PsZEWu!dmj@;07@mJF9`lP7v`%MT=5t19c;jZ~GPhLXGrYONJ!e>q}%W29` z)=eth1MN>OSl0M+N z1tA#>aW99y*8t)7W|-k%wmTY6knMnhQE<_N$h@Y^xSs`nd`8ae{nX#f)9#L+L%!ou;U8>1^>+;f z(f^r@TKHD9A{hvlVm2iVJqYu_Mm}i@7r-K>^C@PrWSXWhEj)F25$2*#!i0_d4|Rx& zg5HjTX^GzTG>Opd2!E)3ma5!)_w!v>&BCNlXPj}iH=%;6-=kZNx}p<*ZzabzC0?VV zIJY8RZoyo)ghCHM-UE?=9#HMaIaAR&e6Mp0#mx{!lfLi9pR`P71U22%}&GKOs&{QFIqDAs~oxwjeA=aiV6i8?xkKWY)1heP_Wu-J^|!Gwx6DdP;y*8ai%Yv`t>t8c#F@-vKzPk{H?OVbxM7fqWJ;g?htNk6Ixt}f3=**`$Ldv z_0hs&Mv&6j>Tc zpN}?u_qt!IEu}VfiE$BU;E%Bl$2g&%)*DWrS}}e(@n&;17H@3u#9Y+whIjyo!1`wn z96-O{iuG~2_jxVLZB*8NW~N;1kiB*+ElFIo{%ZDpH56O3@d$UcUE5cSZ4)N-jp6G6 zlsJAto=DrHf+6OQ>k?|4)KIE7mc)4eipcr79*y3?(;(__5T zE3wn=503IvbA`c(YHc_Qo7!Obut;-!b)4%W^-@_VCjTD)7>0W-&f z8#*@P)A!8Zl^(CBpM3vmzWQ@_amVS*&0%se$$Ds>b3X$f_JSAcq_9fx!y(Qj%>N+L zyBuH0|2TSpdFF%L)rU9<)ze9t2QJj_YdEe8RZG(!%L!?m~moPDx(L_*{Z?GTkaV8P)T2bm z!?G=yTOTa$6mk=5ChMb_$+*uI7!7zdvT&~}M6S!jh)DDHWc!bq8c$Bsy|vSwlbV9j z$ng6u8OnuA7r6!=^>`UT#Iv<>2-A;z$_%A=<*{iznoan zWj}a!sMik{N7T#E6DlD=Rq{b>(_jO{Q(OH|W1LnZDba5o{S2i<8xIdt3ZJ6Nr*U}v zZwscW;j88W!I@=3y&B!0+~M$cJm!@oD45MgH+@NB4MvwUd@oe@z1!b!v6Y4diDx)H z%{Z#Qh;ToEdHVi#pN3j`tjLx5w!QJ~l)JdAU@h*!^^g^kNlQeG47;xrp_P6X@&!Jo zb5dqW1mg8k=kawrU&-x5d6Bw{w`fMZ#<-3QP1bxXJ&J#LH9RM15!kmPo!N{;1 zpa@y#=PCQ}N1J7@)QPA)N_Kkes#s*J_aQBNVdLt5#xpM7Q}Nq6fvigXgEx}Q8!0UB z1myp9z)>yb6(>e>dz9ED1rM|IB^*4PzfTlF1RZGiO`meuI}1NJ3g623yY=8jX$pbu zQe=P>*{51(^4~sj7r{S!`$hAfCZPzB(h={UMYEZ_wQUL>67!Bj`SqT|GmN08wf@%_ zgDka5?##$Q0RB=JKnOY=uy*}#hG8;WR3IxblJ$MxxZkv)ZT%xsq^}*xeIMkMR7xeDTKbp!)MaTVU5A3nW);vBJT8wcbC^uZEFn(~aoE=xAKP+DRy(o(9 zQBEeC$!N|!UBs}n?O}HxM7ln?n-g#d$>Ir_m5d9S8Y`fz-0<_gC8P?aUNDRIt=*kB zQ6-4~q?5Y0)DIr|o~V z1y|f~-?Z{+HuX^^g_=$+Rv%tnGNmB6IOY}Sldvqogq0612x$>27!JE?LKds_8g3iq z5-y`0Qw;0-JG}XnQzn4UKxZGc*&q`^WEgBa86DeTLK$W?SQLiV8nLrB_`Tf3f%d;% zO(c*bmgZFL+f9K39QmT;@)}t;iY$dUxVV6z{IWhXGMd5>oIx_w<#f@}LOgEdV3ZcH_9QQ|6yezmgV50c?%nqKbh=}& zKVTaG6iU^1RaG##yOR+i)SSf-klcJ`3#}a}=)H%=4f4%7WHX(gyeB~?FHvEOSa{|R zm5r^O_;p5Ol!F@B5=;s`49VY7G^EYSp+?`beM$%UXs~NC5tnBp2Jf$)4k$J_{W-P# z-Rz;71UOMbK1=?3wn8?z1BMsJkS%}6cqoD3X0-R8uUFRH3gzq8zQcE+!gf5-Epep5 z5id7;07#%sF>S^OPkEH|hKc6irSZ^X*TPPil0?i0M!Nd`w1=gv>SeAkUnadTIB1br zrlJ=bztt2**g@Ph0sX!4+O8x>5x2x9cXYczd{~W5T2XseXZ)`WI+#`W{``V&>~fg5 zcc0309vQ*7tY9M+vkF9smZpWL^Q*5+vlDi@IC`?rPWm?vb(jN=RA-LvNMG_O#pbKt zU|!O;rb5bp(fz{aI@iyPG(o@s4xVWeGU$eW-NB1E#MSi7&fcrG$m)FtAt@Uh@~-dz zIc0cylR6c$i(Cj9MzS;gpa$BME|jeksSp6i?+P}HxVY zcCx6i*7+cdGls3SQ-e@8ELQcO5{d}y3WFK41E{x-zqf?CrPvcgaCu0f(o&aTGQ4c- z)|h+zedlSumRiF*U&PQ326;zChq9+wlHAbU&B$~mBc{BKjUkNch&NKwf}lDys)&-X zLPZ>jxBV`Wy0*Rk{b&{86X&k!qAy0RG%WSk(pz!jvc zA3Mh2?+=6t5e{lZq>Uw@Od~Mx=Y+OCUKSA)IMv(p1;> zNN`B;udwO1Kz&;_4&Qz@^4p_cxkl-G#hV!D*MvZ8f)YhBJ$^x(B&~Axe6={v9}yiT z1~&CPifFacX%In-stt%zJV#kbzta|JlrMFoP`qw1$qATX&AGPcrR@4rR3mS9LfP~GlPbcbPu=$w70@%{?czU2BHR7wD?tmPwSnAWD;+KOwB?W z@hRP9K4U7PNb06CEN=+uZRAI@Pw_r%*$2vGO<0nrSOBOl=chYZj$+jZMeNJ{bhz;? zKG1{x^8%=N;$?c1mElB{>N2^f}dv zxqedBqJ_||<9k-D52b+Xka$RQx5SQT{H1g;%wA~*K*213G565mnqc8`(dxib0sW4( zx@ZE9Zn0hA23x*zpDNKXi@t|5OObx4kMD}UG?Gmu;(Vup*F|!R*}xqXj$gay zJBSbGe|D81$ksg|D5UM^8<$gJZK8?86rT6#-J(l-(-mXU12C&|gC$Z)*P~iiS&}SI zz8A+;D!q~_g4J1x*jBGZ4Ok=6&=lpETiXV&803efpeQARDDKRT+T)r*1pfe=?zvx! z5&66OqXvWkk^zwY%5oq<`ZLmFrK>xk9-D^wc|TDSESs>@BuEu>69CZ^A)q2r25~r7 zx^Cp6M4w1PaGWOx2mOX##O>6>hlbQ(WDrvMXSFIw*@KAwdDMC7Ei(HL9YvO{eIYMG zcKhrk?V+B*1fAO4&SlG&rI&AWoeP`Szq5`L>FRg0s))or-S0*g06k;}ySy?%U9MkT z9@W=a+>n2_MteIvlAIJlV#+JCOp@HMSo!GK_m%~>U~Np*)I<(xfIvBQzYfv7l3j-c z8%+^P+Fy>`EBXC8fI&j^zEYD;9~rL)x%u8p2_mJKW)-pS!uqrq)K=lpVA z#3t7_b%|suM!f57G_JRzf`J=rK)B5N4KBP&#+u8#Z3p3?37rmQ7zzN>_u!h3+}c{+ zOjY}d7tM^&)t>Q6*grB53*LT-I~>Z;rJ>Ydr)_NNA>nK}YofCUvPxQOj>ch+CyJQA zZ-F;EgscRpnPT&g-|L+4!}#?@*y5!FRtl`Pe;T!47OO?@0&FzqZ)ktNqIuc%ylqYG z4shPwU&OIi7cH6{Onv0h6ZP74y@;r2zpP!G{fClyczpy2)8We-rHn#^HWiqcZ(%-` z%r)O)Z5Fp~3ZH9yVg4yPB$KSOZ)t(qlcl>(RZ<^hW&`EC?&bl4h*P^HzJ^MrhVWCW z(4K_I)`tr1FrZ0;I6Ok-Q$smvdgwGl<-NNd#ltQhW^!I*bYDNnN8R>#5y2Gbv@U3yhdp2nnkiZ2(3*&YEfh&s zpaiQ99+t{DLAkdB@@I%)Vo; zT?<~0v3#`{vE*F%_ORfb>;X-L?Y6v)!L<^X2UuYzglbY1<`Ig#?t(M-Fim%ZE`}9H z05or>BK8$x35;OHvx=C&G>956`(BNb#ZCgpVzj3PhMYEx(*(n{vA~lxO2hDgZc-Hj zSzHo_Ky7;^K{>RBcJ9mJv^p5Yc|rkSP;hS{nl(fQfeV9GgSqguVt}&5#LEAq757k~ zvJ72jHtaR5ExOst%uE6Gf27@;ODp(PBHjvaKC_Rni((Kf3dv?{X+=6B}`x>`xfS{coWmOQ~II(2jBDE|X226T#<&;od4kw%67 z8a%`p2C<-q=l7t6>?FL&FjSf^t%C&w69g>K2kUc-G!Jetv-}+l{`(NB8M0~`V<)b> z%=<2!udq<)q*Jc0moz_=bf`FA2`n_BLZ}25un(pk=n~H-<-f-7CHLI8?iOa?GUVq{ z#(q&#E#Z*qQUuKJoyCawa49e2Qcn*Sx+@6DvE%`-*YQ}D=AN!}Ww@dehNE7|YNAtd zE!5?&hJr~vObRTV%7SJD$)tV;4`7%9C9Wk5`XD+KZjVOTD~qj*qt_p@J6NbpKUsQa0aimhg2=pM}a^1qb z8fd`~X^l-#4_G?BQ<2o<29g_a2@#{}5kS~^+H>z}Dp@S8cr!$K(!AC)c2W$(aHZ;+ zyE(iu(G+2vaP;q$AZA`p=BA5z=XcNC*D=_r2CLDU@d9fJNxR%AsBG+}oBkrlgc zSa*tc=&%lfc_6r8c1Bxvtx}H3Zbe4ZFxn{3lTIm<5E;`DDb5hi`fgFTEwz^#On0I4 z`MLMK*N%eiRif+-^7#zPosCn=(9=x$18a0HcP%CWbR1f=2`qaOLQB&_G60gx4&~=9 z(w_~Lyv|3fmCxN;dqstRc}Nr`g!u#noOE9K+GIS^V)JIKake#G`|&rY;?3KiNRar%zdT4z zdgV+s{Y3|bb(cKN5MLAq2{?;NskCqWsxVdsl%V%6Ds|$vsO?u&Sbu3XRcm(asPa~A zANK5>F76Lnb!6r3{sG^ot*&>=BzIC)w-3otgUB+5z~{k5#(H_TRR;Ec4M_C*af0*0 zdGF8!sb}%24pgi9y0+@o_?4EL7XP?x_;K}}5wnub2DpC31AM$n%+p{h)C!zNMXG~k zVp6b@9A**inw9?OZ(7I5_OD?Ew-I)?Wsnam7Xr)vrk zWwl@#Aja^b<<>%FClZ;bL(zDCP_WF1xKnXL3EcB`XH;l+^6l=T(4IsPVR10w+S~oV zLI;<7h%jQ76So6q;Um!g9)tT4NEo}KbUeCuq$Yf7xPM|Se8#+g>L7f+v3KUv0 zc&Eb25JsV2*dgy+M?ktk3>zN7@K1Cn-|E`Oi<~C_t$m0LYv<3>y=?{V9A;$(QWOCl zmVgBX;=zK1QD8|dSkZ$)Lmj1rBD{|!d~g67Ctw`tq_)Pw0#WctEIbiKlz}BG>tu`D z*ODqitE{dGanN65WIniWtc-~P4{9w5t`s1``5_A{HH)_&{%XSsU6={)(~3|@1`##s zQZsr|@f@Cq)IuSP)N)E^YKPQMglQc`&fG-kZi*Z`)Lp!F(vh=Q(d$w%w!c*4CF>zv z{f4z#8k3uLuH6ML6~ct8yT0A#M_hN03x%z6@7=8J83Ve(yn9on4+)geueElg&6Yn^ zI$2tm82{a2xKl=8Le97u;prQSJeW;B?JN{j;r2$8@uImeLPN8a@ggRzRH$fBHF4su zhrZHSufKWhM*a>GSe>)w{nVjsVm}$ z{zP7xlHR#Mf%4Wd*0%R-``?3(aD2 z`P;1?DmI_xUHUe{J9|ef_K~yD(GeP`V6JCXJo;0yX{J<()_GK7#s7{>eDCy7(aA|a zQuofQnzwKJ4*0=moZ^1z8$#ztQrb^zR8O=ZN0^by-?RL0D@W9frr)=@nQZo2v7}2W zHh82)?DWvx6&BLQ9-9w8wGj2z`PzWduWGOrpmoCiGVb1%zwV~L7Po@WpbH_Au$mzpvr35|TFp+#jBXzx*UrumG; zv_Hqk-I(PXylpFKUVnZr^2{nIM#L%0_jwU#@S`7XXDW_Ga{Gu)f1$0)9QW}>5~Zqu z=Y%g_A)dunyD^@kcN%%jAa;4r9^Yy3$4Qt^6I>7B`xf@)IXFWleecON34$BF=K4$} z)53*&ic*7G-kt?MyNFPfaIxzp3%w0&c|;52Rvol?Vq`B&p8NW5hTG6t+43C4$2&vg2^GuR06!Y*&&Ipf*6pei^;b7kp;b9qfoVS!z;rGTtheRsKsKLzl zU1ID}`psprYp`%Yb23j;S}41N$snr7JWDoj=|a*R>YFAYqpjhC5jz%DKNkDZ{QD^g zIBecvl-A9_e|$%@wPJS&R~|ge8}fx3Fa& z9~WH)RXwWjXSyx3@&34{27FY>;`XWt7d3ZcQt;pthWEi6uuRbt-zP@in6P|V+8!2{ z38weon#Ya4XxTRRt90;$6@i~Skv0yrJ}=KpbP4Bg&AV*9DcdI8Lto0KeBCMAv(?=9 zt+U<8;zYaiW&R z;OgKYi)`6cuODmZr;l=tBv)hO0gd-tD%Eem?WvWk?PT2o6vDctCX@>@?~d(T2wjJg zlDBGJT)!!OepeWpm7S4Q`>9K~M?YLWy04{i_`2}UjM~!)bc?;th8*C6W-$q-o9>cb z^RHHSs;j7*c>tM}d^;;3VVeYGoZyhQPYR9>?-^*nn85t8xc|z?>;-ya-4gWD_Zhf) zZfteVpzf#Es_e_@D~mPR-?k=qPzRFpRiZys0_ryZEa3k3vOrvh92CBme&Z9ca-Ka+Wpe_%25P<`=$ z!|#nM847qtX~GiAp(xDurm67hQ?Hjp*N5J{u&LJn`o=>u+@&&u#0vJ@e!|4LRlXH+uQ9B0W zHRSn2(2VaJS#Y*hP_t3YCO++v7D!l|A)b%4j8Lq> z6J%(#gZD%@i&nkM>2(( z{GY~8KV|h$Yw=s$b;Bdcla%UxE_@YMCW#2Sx@G)*|CF`yUnfUv>9EI4HV)EF`Y~W< zt7E%HlQ_*3j-lW{-GTz6!0Sa89|G3D2Ap&?Yn=z`x}+GMZ#%j4u{o8P>Ns=?P;#m~ zyjpA;!|YxqYJ0L#ka3QG2QLo?k z=T-+N+aZ^^RGMth_g?LKyuIW4qw(aEOWdQ3QM;cn`^MCf3LC_~8gJC*Z|paP-zeNA z7{9E09LAu(^lm7VzVOzRu7*MF`1QoVuOn(-UOfC@4?VxLq8Rkif5G+}siq)IP*2rz z-TdMw(a+RA%ejLl8A<}Q3u%$@u$ub{A$#%i2EmWPl1qP5OmA~n&r*7+nQfS6+!FXP zw@{tynO&3@>K2j{@h|gVXF_vo2+1B`$Me|q0icQPj@Pt2BEqgbX zQnUL~9l4Jc$(L-OM^()L;@_A)+J8SVq~m>pnq-iTu)+2$mMX+s^tt#KTX9Oz4G1lK3isGK-{WCSvAW&y&YJIFD$CUxK&JBmzFUN>MXTtq!z;L~^ zSBfle@h%_1Y2XzNRW2T=;YU8il86nT^=e9(2{=zLXg!rzQKdQ!$9mcsE{^*5lALwVA^HM9xDtWY-~{gxm4x>2 zR3W_VKcP659#BLGQi~&*MNgp49*w}`s}UF>4fTtp`Y;=Y8c(G=55`=3_e{;~7uF4H zbez!_51a33`EPaWU8q&DDi7pk9HHtDj}PZBWk1`9z2vfM;q36aW$OdRhB7)Ccaz zg2STHbh&`#l%22T+@Iv2fLqYpLK0O{$8%>rw}tPYPie%M!*Cjmo|qIQe4Swx4q+;u zruiZ$7p{XCQUyS^^;{M5FYV*}*%Ox5w2q!HT4cd8(pLGk${All`(#4xK@np89D5KV zcolP7T>F1j#*Z2@6r99v=4#7MDEn6f<_9`>6#V`-xIr!?d2>WyqTcv}Q|M#83~)T5nM6spGwLvdW0Fe(@Z061KX1ah z{7SfaS7dFDrzQ4M192*=x|H$4L#2`73T!jrblLVmr5|qWg`Zcx26Yq(QiU`B{r*Yf zP2h;}VH@e@4|meh!^Neh`<=r}pM04W`bCqc%BjV#Y(T}=+0TyyGDTRa_kke1&LE*_;j8WH}u5-s1o+zu#cD-iJ% zcNHA_19Jqg2v*aK>#ItDaxsj&c&zz-uKK)hA=9GAe^Qs2xGKV46K@pdtHGl>x6_8j zxIP_wok?vIk`lizw+O7TzdRmfu8jAu4@sF@eAZ>)8aXMJ8B=IfsU zf=uV?bR@Kw;%q8NP0UA%){TEkcsoXi1rHfVL0r8k-@-@9F=3`3-1i!w)@#sjsCds+ z^4}neWR0jn$w9yb^5)*@j1kc%?PkCV_q#qAz0^6A6#RPS{myM%Qp*K1+?^Ob$~X5B za$_V5lh%i=;2JtfpR9IS$%9hZW{x8^DBag&(T znIC$yX0|fBM%3b^FI>W1)1xRCnPzd`Ln)iEwxUbVv4UV4wrDN3fpj+82q+D8Ye!2Q z5}R4qKmJ_0`=|F{dyUb;1`mx!8hmvA^$?TotCgvAt=YX}uy?pyM51TEd3!Bw=O|Yq zhFjE(Ti2V<2$4;*niJugo8XG2&xpCT!u?={yim;{L+7<4}#wxg~-$Omg!mc)Z;WVa^IUE` zR?6@RTr_3^xXw#CkkfJ`@Wu3Wfh{QO?)oK64fGRk!Y@<))m!k3J|htsiuN-8OuqXyzb`gq3dG;l_Ka0_jR2`k{_4+E2{xC6$zD>^ zDB|tUIoW;#Hs+@{59Rv8%~h&;`?vZtGf@lhufKN$!FbyUlpysiJ4v2iGy5WX4k1pd zF&|)zHGQiw|4r;_hKAgl>KE+*F0Z5Gw*s;k97KE}f0|YHE^5u)5iY7$Ox0q{GSc}G zp|jK`ui)}SYvU+!T=*(3Fz-V&xsm0vgki@S=S7fmCvHs_ zd%gnh-WG~?K-+z{t#DR9=x=_nw&*ey*cxOx*0t2+rK`51bDuM>pR@ez$H~lS1NzEr zR$koWZ*>NysQ+%a|HM|8msfN7u;!^w>YnY&HTq4)+b%qEbrQENvaO7VtZHQiWZV07 zc;yj?2AUSQ$~hI`OA#z{N|rcIGffAc2WCv~E)2@G;vAf@XghWA1ku+~JzMMYrMnj% zTq_WwT-f2}!aBcXbXM*2MFEO zaL^UFV|2g6Snbd-n7L&SS~rgI1LbVV(o`)gmnCA3J(qy6*qLZLQs{ z>(zAG6KPI)hpu-X^9%xlZ||`7TbIh+Q$8}0%kd&N`M+F9I1gvGsq-^tzHfRY!O9Di zIa%93!%_iwDBS+;kvX;eEye@i`MVS$JaQBGhkFcu!WM1qHoedA&A6*Y-1;4#97>pidtQ2cY}V-&A-xU*3!|6hDp zTI2gX(=M0md5-IsVnt3lH)uI|)g?vmDCL(+D!E+d*2l3P z&Sqea1=`Y(@wxs3)D@lVzqYFd@&%p~na0Q-tsRy`NuZku=L+cCZGTe*!kH^X-;&jh z8)7bk6|`hO_i%LPGk49tv6=1Q`q*vrae@Y&7@3(QU`|SdKt#UiTJ@rl2J6UXvo-XB z64E@AMxwO)>kTZK@tYw~x%II-D7KvZ0l#_>@GKHJQ7(dF&kA0AmUqGz^<477jHqv8 z(I?^JubbSv*;r3?Mrhe(&~izrxTVT+4D)EDVRxggMiYetFkwHVMc`UaoJk4r$tVq8 za}ap})1X=m|NOq(RVml@OSy)dEC^p=L{)h$q4L2)Z2rp5uBajiC-&;S#WgIOSvi+r zP`5j;M-Mxo@rH`Bzth?9LrwC}smY&B9uy?GkVPrt+X?`pTKJ=9T{tw8pG}qxfVL5K+95&q8~!WEWD1mv3-5UCRg}4 zXxE9f_kNB~{+*asnVbumeBU#9KV^gPL003p z7-i-Y6+NKe$q5`P$p6}0M8n*ja;RiuW<+$^^UW%XjEBvGdPK(0-!n9?Yf*K zpWlpmz5*he-fZ-A^mylHjJ4!B3FXm#*f>A-eCo8H>f|SPXkWFds(>|k)0|Iy>x5&A z%tR6n*N?z;oB2&(aFqs?!|pfIlgk?gK^u2Zs!ntDxNuPO$j0aAe{iQ?yNh_1fBAc? zR*t^2UH{av`KjgU<&``ZZ|$fzW|16r%R3Os-O1p1&z3#*W?dz+#g@x^M-`+hCSw}elf-6lvoPR){x0>}nC^}qX`+Ox3OZFl^t#B5v&>l3*Rq2(=y}SUFU40owLW30Iq)Pua4B^scgYjg;uqRHs zd?=ZNIpP>r#y8ADB00p(E?|uzafHKgrS~Qfc107Um{Av9)s-lPhd;MB%`Z$5F2vIP zaGAZJpGiBJwYLX(dzqh#)Z-ie^wo5u4QD9L`)rp)59p2sJn>TFho|=zdH-%Pt;}=+ z84?^FS0_y=&DM?LiBl3wL=l)K!#xF_)j=4u%!7~KOz+F%1@eBJpohuw9^Zcl zeO+N#p!$Px-EP#Ab9|vX6*>*Ry56!fg>JK7@(VnYNc!;5W`#wc3KVXmp-BodgeeDV>wa0WULZi)A1o@Jq{_=5q}F`H#`D(?|fEv@_K?Oz?!4eEG8GX)Q8Yy^zg$3>9B1mg># zloT5^RmBM+x|J~kLP_c1Hk6cV(Q*uj5p;Q@vU~I7X62<{AHMtNam~63+RhTR1kaN| zfM_0v>?n&e$!3r0vUb(;>AD5aagS$!%eY0oz4)C~tg^S%Tl!01wnSYA680r}h)DVS z?gzJK>qM3pGLe!K;N8S(Ab>9A^0$vZ(a+vn)_M&f%c*`^uFfp{RKNM4)*O0mgogr3 z|0;3zg_Y$*)d(N8`$cVfwH}K>v6nQz{Uzw1{<4f?%%`D{l14{!T)T(EjBp^5&Bh|x zeu#|bzPRZ-p)|SeH)}>3-3=_5F}&DNPK?5Ncx0JirnN<4Bke(kf8gXW~nl$I;w!pNbp(4cW&i0 zUtZY2)8FpdRTY;g-KLKG60$#|sinL)nQGPgj`s`tYi=JO_qOX0tnu%Unzs|j`%D(i zp{LSMUZ(%h$QB+`{ptf1EO#s+i5^@1{;U>X`Q}kmJsSuGS3Y*t3YBW52BowrCJPxL zb%@z3WAbXG_qybuDWO|RuK~m>B{#)hieRrMCP}pjS&wmEe3zZhKUq1tvVs2c?m+4gIyBu{+HFK?sk6Itt1buXKH*3f>i~OJ)ZA znQh%p0=MHiAu&Q35x*_4hdfkCghWR!b^(#h>M_-Gx?FG%7ndz!+-Zg)PpPbO(oHtu z5n-B_V`1U;MTH4c-bMUkdx4Dch>>%`6O}d_YEelmVHiJO+U!RbMp?UF&&Oi9u9@Fd z67wd!QhZD9i&o!w{pUrLtUdQo%d%G8rVQcL@AUnUJDQyN#vWyFav#oKP?OwJ2%{uz z6;x@$c@8lN30Oa>U7K5cmB&*l7iG&14K}wF5^#wQepS5bt{Om{0v&}TcQ9c@Lceat zylJ-BP`Osn_Bp!H;B}R($5yOt0#hXyiidw{Sk=gDDi4sW`N*(k@^WjApvUNAkk z2eGj1o2_6o8&HjrPQQ9mSz&XAHDhLb*YtI+fPuo%`VEy8UDKULYL8JvULSDd%+n^- z9??tjY`QHX(Jenu-R&fmyW1Z)Hz>@arGG^%Xc*YHCcUV3`Y|?xe4XC*C@}4 z4WL5JraF|^h=?27AgKeDM%PEDi!ZjcI(&S8xI@@)zB{1>bMX-nCT z+|(b-ZplYIIxF)|4Su)&Am@3IFC2O2I7-t@zPr{)996GO_l45*$#Ub)l|l9f2yV)d zwy&=&7yZhtUp{2pV+YSHbbIsBe6Q@Q9g@Om8gQI~fOa~B#|PTQQ(aG7%jSQ?O0)Wn zwqxKal!)~jMS}xUOeq<6qY*v!Kb}8KLNu+#Y9_56ECrPHfyqa$t!OAw*GRmmHPMm7 zn*XL`iSp~#%-Z?&(Ts&si=|i^25@+BA1FZkb&K0=8pjs~d7}a$ZFwa(zFJ?&^Aho{ zmttrO7ar-O6@tsS^)=W_f6g0jvDwW#<#6sj9Mclg&~xzk{Y+)Y`c1MN=~wzN&4w%~ zaK_~EzM6Z(D9k10B|r?PuOyf#%d@?)6+Fm!m9S|^nLl&&LCXu95oJW|CgSa@mRj)! zr|(KZ*|jM}CDyjn7QV;w7hYGU4LC(nu^+!n`uNi)Z|Po$4%@;kQ$uzTrwTVj19CYr z@+f1%g*Euk?20PFd+qSMTkygRr!`bz3q&ifvi?zGHPRwSD)Um*m5)2j}hKMU}pC+`d%D$7ODx$kC${f>YhXlc7q7FW!HMN+ec`f&A|`*4U3a z-^MEMR&IrSYnEH3K5wOn@&dC_r30x^yQyrlcH2&p-S6L|9Jbe=L4Bndkh936&hbY- zou1*?#BfJF--~`e7(V?(LLNW=e0evD6#SVwHJ}%zx|ekQbcH?jkWK5d4^MTFbM@=A z`nzY?o7dq2(EU`+3j6&E$rqbfQ%`2=i%~vPu~OGirwikuhwbDo{QIe=AHRnl{YN)k zrVcx~Tiui?8r&D}3q5Yi$ZL_0PK~sLj zQp2V}-w9MWJhaUVDGCCATc*-WgZ)l}!}=)x?7}td5JzcHRBi}n;~M-rDijN)t!8Ai zig+>?zOjE_;4mC}>^Ja^oCT!a*+ss=QPPy+X*Tfl)1Z%7%9m1MRNk;d@~k+Xf+Pij zl|o5V5Fib{y$irf5g)wJEq2uKJ(_Al6#YmPkDyMXiPYYu`xYY-)-}<5R&I~=JR{yQ zT*WY&m!dVTqI7ek=KH9M0jc}B=r{ri30nbu$01NApprCN-w~>IJlbv-B?17eQ*gK` zVy*=}4FmI+#wCu}H9d}(osZ_MPMTz~;f7(dO3_g+adB~M

cAN(@yixz37!r$d*f zP-g^MSub=q?gA_vO2R?`FH{g7O|HRG?*)R*l7_5qj~w4Jn!m{-8YmS#0m#h zUt%vjshXU5#p0_Kl&A32il(3`B9%3PqRor;Zg>j3HRZ=~%AP{1?J(b9TxwWVs?A2y z-><1Mury)ewBd9P3Lh+@4b2^h{uRgePr;R#`A@->+_PK;y(UtZd!u9VNJ=j>3X2My z66**+ch)4r0!iqXxp4x4cP_Ac-0aNG?M%HDpK*g93;o5XevyCPfo$z%RZ4rxTx=YGONOn`yjwt{ z7C!2FSMHUn>{O<-OyNAk;neH^-$Gs~xM?onmAlrOd>aU|e~5ORqWMWgzQEpxspAiD zNO;_Ts;aKJxrWCDs|NijA)q z@+uS#As*Z271EYU{#})XVWd_Ri@)UIHvW{nec-VZd;J&d;|X{P2U|%#+=t;tX*L7l ztfmxxg8-r26 ztr}?)NURAY)u1-pt@bfnZDvqy!B}msNNo{SU1@$zo=9CKRb7P}sjhabHovZ}@k33` zR$XE~1<5X@g&!=?$JbR?-#u3UVypfoRYRXh!+=4goe?&hVik6$*qPrC-wZT zVSdu}Z(SSb6B^&wH7<@dE^Re_rfOOdX<9RA`r_8~Eum?%uIc+&(+{`CWso6gwduD( z^MPCQQ9|>dy5>`=phq7t)M;ecslJrzfreBIEVzauu?1G&LjApt_IpbsRV${Tj^41f z(ybL{2(gxmZE*smvEZq?dPANzfyH`$_cq~zdNLmKbvoT z=D+yNZP7nmnJesOXOt*cOhIRyXlL^G&Q$8IbkVL%!>(-iuAIcKy!x(!@vfrpT_x1d zOGTe&fA`$&DDvvW(=ITjqiJ{3knI4JW)B87LwT5{LZx$S5@S3;NWxv8DfMnwGMqWZ ziF=5Km>|C5P(8~KTGQugos49(Fu4`+4vYFiq-xSn1!r_?@w_0}^#CnY;0)^5r=C;w zo>X>-&p6a4DMT;=5O1OSB8BRj>Vbt*eIk>VCM4>s8E8=)+2jPn_sB0aQA@ipsnXu< z@4dUCFZbPF!qZ=#F20;HCHGO0FR6j0K)g~b@yBT|Y>#*l{1TAr`}_SRFcn5(#zU;| zoFR1FABnswFZmnL5IpsAB3jmq`ga<#aHXbQz%#~C4&ooL4vY=>}g-Cxz^Udq#-f(!xKVD`40KM^FUZy9_u+84c z6|vqkS;bYjmd$_pgKcRNZsJJ>D}4oLkEm^lPXhY$NuJjEi_P}$LT+fg_Xke}f|ztO}{ z(!^-e*y_iLFEo=IA?UO1!I<5Du*^qNs6_O{fX&3P5l-NtkFb1lbO1V5k6G*=EORJF zojD6fi<&MJGG;EBqTNkIhb_-|t_(u#kSXZVgXJtLo*4k|!#cuPT!?;hqaFczdvAp_ zS`TC+O=opIygCR}a31O=08raSy|D*2?a)-F6l5(EPS!HfltdbUtYuDE_wt6%-I$ys z^MDR7(9VzEiAeoJWj;EN1<-L)((|y^Ioq?j3$gP~9`F2IVgqVoLpEaZ3oqDB7XYt? z2aOAkw16cJDX~20G=(zHh41XfdeY8E70t!i&c}PqCN8}%X`F@IQ}ueGYc9umH>#>K z_i8-LgX=SsnapxH=Zre%d<6Ns@Pce)8YiQ#AplEOW>gE=$Q&B7|iEVm`=Hl6-J*!NgRzXOB9r=%r=?VZ>Y!K3%6QndL z@*@s|e61Y1!g{_6<5}0b^$A#}lHOQGORW4T54qEq+CFeZAL&V=?6 zcJSULZCxnZc^7qe8dDj%RolDOc)r!D`u!=_a+(+F1CH_r8OGd=Wv@-y4xk%M+3NiS zH2mCZk@zmJ|GfiA_MB6my8QsA(s@gN4BcY>RJ^^CLRIU9zLG?>!nIB^iFuKNCQ57% zcy29*Zhvmt7Bt$?{3< zKW2Kv^xSS{zi-ctXCo>F9h0(wY2H{b+NCw2o*~3>p?)R3Mt}Slr zDk-EA7W3dD%XC^v9qOZ}I^+zuj^;TPdAYQ7wp7!ZRh{}-=?#6m3GF^Drd{$kZ7K3V zsTaJvUfP_WegUboQz#Wh^dA$%%}?vLpD=T&=!FvW2Nduz6>Wq_ zjhVW%VTXPiM_Mf_Jb%}GNX8A>XwU#uHLV&(#%r& zkbZ$SMhw8oP%LM@3=t+BoKg_zp2jJi+k%MO=31IN7k{p^dOHrMVl-38W2er&+2Rzu z>an9`#)V43S1NDJZCNx}*J_9gOaY2|%=YgSHny`Y+nHgxBHzmEz#c_2uU{;LbMm!1 zQRG)H=45nHn6HfeC^)#y84j6Hq=T2;8c4Kx5g~4K;5A6u-V|Tq#(e)vZI1NN?nBCQ zC*bx##GR!N2kr|j^8yJh@$5R>XG3;bQadPsOFxSJA>p|ZmJcMRE_wc(eFU*`^28G<_Gp4&C|ro|hp(kKvyjASua$Fq zEf_Ge5&J~zQ#t^wXE`EYew$kSp$1U!qk$@gt{V05$B92Q(VP9{TxwCc$|5F?F)ggb zt~Wp2;HN(CVA2)uVQOZd1{~JX5^9$r{h)J|F({3I;k(jP6P{>0i>cLRvW+qw;*+_E z5L*+z>I>GBw*+4ouml5+0? z53QFI#wAv-g%F;2zJ+*u-yT*&S z*#f#6Jae2P!487`XoT534mA%@*@rZVRD~wGXdg7cN z_j6&W*nMpGm^;_;oED!+@k?vn*Ryof+-j^fmcuGQiq-krbJ3U?E!10VA~lo z?0D@b6u8%_Ey(KHPkl5Sd9}ZExWJH-0-x^v6ERFTe7lpPD0s-50-ofv#5nJ|y?5v9 z82Wml_b^XRp-;Hju#N9)cJs<2|2ug+Wg@w?v4y%fWFGAeQJ6jYH75Bc$d?VnAVRee^4b&RlVo_V^QSHKWkzZt`;9LKY*cRBf{g{;{N<9gwb{06>1 zBZdC`Js%c!etJX-11L@K5PmxlZ2%4`XcA8CWC!6q#=&(=BIqmZD8vKQY3`Urvaj30 zE+4C-V@#s>`0WwK0U8WdCefl!_SCk=8Z1L5F)|hQv>pMP9A8aHvC8ZAs7J?|SW444 zO@0SVa)1`UplQ6JlLI|Mi0y)oX@Yr$17o8eqXChhSE6Q?@x`&WRE%lTrHNIR$p9VM zD%0e@GC2NT^;EY79^ShfI+sIMV77=s987{P zI_}=ACVPUFqkwpzzEPDa-Fxf+^4tU^$-m822xxGPr0a_9JJP8g4+M#sfv(tS>H^qx zH3i|QyIKRxHk}&suff3OtO2A_%Yf3~G<_#Q^Sp8XGU$41bX>(MBQT}q1NDhldG5fB zS%F@XG8>AU{e=dPLLNZD@dUpCEI2(%Cil;kfFbi@QIb}_+N$@PfR7M1fDkS6HCNZw zh?m#3GZriXz7jrrks6!_zf04H1pJn{e-rOso|3+rbmv+*dp3dTd?lJIsvY+1`!}_R zj8oxE`-B@tLJqTcC~Ur9fG{!^b7L2EIj$YXyy|lG(TO?X(;LXa21G~JG&#t1{Ni@~#Yw3lOD62P)u6P$SE}(}0JU};3kSR?EY69j zruI0lRr_d0v6{zH6!>pY9}58Mz(sDc(9!G-Hw#*}COY49U@J`yuHa*~MZ-CN^d zAb{X34hL~wkahbScckB@+VR$W-n(nqAULP2a%k&|p&`qTCkJ)>L+Up_ezkno-I&1J z)Nw@pW&FR%m2k` zuKYKrxk>u*n)K}p>HF~cW#`iL|gl zS}Y*FOZ-1rnsak=|N5Dv>GrvqssBMTNu#5rzP`DM2~v0Wd3!tQwLfX}4r$PeL^LM# zsFR+_k=jMcsOH4P#Q6C5zntd(+0txpZ*OaBBelr=$I`4f{*R?uL;YWnCWKT8B3qg# zHA?-BF=R`#v9YnPuCBJWwz|5ys;Y`ql3Q0^URGB2A4@YMgA^0Fn3O~c2_gA;tp<4i zkENNHm-qPbRpc(}W}ySTXAxpRjsYTDV^kwwj0w{HC_YFb%Y{VQsko16cSsA*_u zsIRZDr>Cc@tE;1aI4H2)*i<5;2old8!A1>dcIAx$~vd$rQ#|A92e+H2od zo0Jr+n4cNvM4>#_2hqnG)tcq+KPKoZq2tiju#tucl=l+-0f-DYc{m1yM%s! zOlzaCSKAlMotht_=)3m1Hp zb}`^R&KQz=u=Dm=Y6&UyOybKtH(ngEk>UP4@a|(cDUPrliPjNX!OmNu{FpFHfVX6Qq{u|P)%EK0d`t!YpgfHZK z^a@vld5vAyGJ|#UGK$T9vDTDa$XgIFyvzf`@LDM6?-f=+~E#7(^QyncM`*FDNE_Z|Z5Ps@G2gOSw`rPPjG{ za`X`US|=_QY`1w^PW7WN*4z+nY|fXh@0j-~@X%k(aB^wpJ2Uv%weftxE?ZheN{d>U z)kMQVa@0^#^X=-UX(#`la>mQR2h>f(Gdi)E&dnev&wd*Dq?vv`b%Q=M1=BY;?AIaT|C=eUfGQg@n@oQYleZ6gr1u5%2EaYsn^NMz9dv6pA5%)>C zb_wydQTnE=FB#IDoSNa*pJ;t`)KMX$sk$S&|3(~LG}!3R`h^6{#eXs_wwHEKu#4mFr2 zqW6GW3%mpni{v#zeW9K2Zo{}b>Z8;WWY?$_U!Qzme_o7PS9~MdrJu*V-t`F<-8;Pz zcHcN?tBr~~WbIP|a_4X97*Tfd(!46p@fVY#OxU1SzwmW} zkCp|lopD8_;hv8?Py$Jdy>!s>I}!F+VMtZI_bq%^>#hozcPC(Q;N3#;w@QEM-SA{z zyHtm)rvU$Q1j_`0Qhub5nsOQY%K;>7iHT&1;|azSVgbcTdE9D zU&cpW4z){DS%6^FN1!UCuSbfk>yC6PQeZyS-EiyevM7|09w2j(_?dAk0VZn)e(@9s zXW|dKMN^(Yw8DH4utT~Sm9x!{3|%Ud24UNm)>mWt!}f95y4+zHw4d4nAW)vvJjR8l zBO-BpjF5Or%t1#~7=NkTfy@Ylw3#;O)^vvT;3^aB@#uSDRD=^lxezzQSbXkua*dHQ z+e#dhB9)e>A7oI4(kK2N%{pTTKx94VNxe13$NdDrOP*~Y)o9k~6QOu;C@A%YPy|K5 zS`mNsrJlEp&6(GFoG!@(M!`+Y3T95%A%==$J`#EndUbg?k%hho&*>w%?^S|4b%(8b z9kE^IC7*r~NU7N4u?PUsll^7t;|>bHHPJaG-&g8RK8T zBtAB3oYBC0Z)5mkk1HlM=C_wUgRp)z6@MmIas-|6W{;&bEqmv3)ZyT_zgQ}~6@Cq= zyd1&*dTJnu0}Rh$agYTOqxGZuC<8imSpg}8H?)s}Gv7(KPtodL=-ZZPxh?fe*w|2p zwH8~3%4@X-)_F$nc!b2`U*OTSL4P5^_R*VG-{nfSj4hD`ynxg^~U_C zgZ$15ubtukx*DH9STx>0T&fD~8(Jz;*Mj*5XsTsk-c-?bB(2&^GZDR$M_EgmTsFd4 zo|{sK3$1Wv@AfgbPb0#O!1T5o;e3bTl;M8r+-WRe!QIvmls7g8T__C_nA;rE+jB`l zl2_vF9wk{Ry|L>4Ec+kqn?L%}L(wCpSdN=Y7KfnKC0 zQ1P>c%KGNZ|HzaRt(fEqd}6s)xa9UOz-w?)QmaY|CYn^n9R+U>Ox#bn3M`W~uR$f~ zD&j7U6U_^`5t%v~ythKc<9R7K^uubtjPJ>N3;#p?IRsuYjJ$v#;QweP`17@$`9)dJ zII6GcSbBzXZj&^*@c0VYJwKXxz$;vV3ISZ)c0^I7h0B~z+efUgaA~9AswcF7PQ?KB z%r~jMbka*KyOWo{Tyvozljt$!J(At8-?6t2$I zDWF#g11B4;z1Vno^^xwc(6kr9P|uc%e9bh8^rXeWwdkEr4J!`{5U@Pg8hYXvIZ?J~ zd(L)Q$ew1O0>Q@+PIufAiSsE&e9@!_Y)4@HQFe%nZ#fU@P--L{tNZBr3rpER&Brgx zDyJ+ct0R*)Pi7e}dMXy;utT_qYsS5mi=#iJS?OqYOi4C5FT!l&LvK)l1* zc_iPxWg&bqTl#%@MMm`tANpIS>UT$U9+npBO`DCq`s1754s+P9e3-En+G6;cRV+>4 zQ~wN#P>I}VT2N%8w;!jFw*Xdy-$_HLLPKm_LyBKh{;sA%g{F!YTH8(+jEPmnM{(3d zaS4UhLc{f3S#M>x0^74aStFvka%} zZ>AgStC&f_uHylybo8@;IESoMaeWKPKR4S(9#Rr5Zc$iDJk9jAu)LdX>F$q?w?lq! z@nv%LW_h30k(=?|DhEgdyHtQF)Z;8zlj3r-@qc8+HZd1#Fa>kgC6$?FuQGegZ&YXB zaJEDX*r9^7vcjHuY`Ek^%I6#$d;4N3C|436)n@c7e zfYIMV9z>ZQc2z3>urnh*AU`}Wf372+B_L1YK}y$fN`Y{}D`zx2K7i6b;|!nSSF3ci zp<=aJQ2D-qIFrh*aC=Z#yFW0?fTW1g(=T4L4*n)w%t;4aYe~!#LSLOiU8^aW9W7W0 zECGWGbzE~lE4mH6kG+~(7$igh(jYr5sgykMGn2S|SJAmHmHGIRjmjb#9!M(@d4Q+A zffmjoBXqme zSEi_JS|Col@#(urw=`(yE^V7a8H;II>4UPm_t`$Rg>^cWp9Rr9*8zCAO_y~!S~uj~ zXt|Qx!;~ioa)=V*g-jzT9ui>cp&;R(U`d~?B0nYcpNujwHbO~)8;>H)G!4BM zNHeTo6Xsfj-&8oXL*=zV6HHKH_(vqH9)P3nyM`VgV$$42sZ9a>9{?E~RAL##k=8Kw zykX))!|RiVu`Q4!zG3P{O8KiHao-DuiTYCa5VJ_u?)`Ox&|B+Cj7+NvW|v@~z$H$#J4R@@+icS~97N-6ik zl6g#MGs_zi${i9=Q&MQca)PZ_J*2cAe#8<-pyW4fb7-NkPHPkCZWCK#K!+Ap$1jk*fwE zZU7wA{VZhhS?K9AeD^akFG?|VXH0Ns-1ldZH#=ibK@9kozX?rg%3ZW}Em?*wkAu5T z^1Jfgn|IhiR=auMPk_}qXpv|`Ves=GbuFSURn(YZDf5my-3lpu)OV?XlC)OW=T!g} z>~T^h4X)!=Ae7eSz4|UIAs;6h&hi%5Yh#?evAq+W*DXTSi6oK47~u!vI6i(9O`@-7|EDgn)o_NrQlt zLl52YQ$SKdky1(!hVD)glm=-~LImdJf7W`>S?he+pZABop0)P<-1l|KxuHldOGwiA z((+NHm#0JsjLV!x*C*btCb!D<9oC?=rzRL^BsJkJzfih80d7@|@n@f`+V&@=FUlp3H1b#HI>`T#9L^b-HZ$gM~ybd;$u z_OT1}u#S=Q!tt-$q4*`lz~(-D3a92UJ-QFj&J10O*S(gW4o?pI?Z^6`uJoFXkaNi3 zKag={rpQKo0Umnd{5+l6SVZRzKlIfpA!r@qv4*1oAp8f%lR5nQe8o4Iu`4{h((bUA z;}ACd508Ed8a_q#)~Kf<5lUg*O>;;{aGm-iL%AD@x7t1|v^30@G+4$s5^+1sY~K}N zgwM`SSU)iGJ~TJ5X7u0E*g9p$g9);eacuT>l=p1V1R=7kVVgiq4#(A*Ivlf-oj`Dn z&l8XI+>VbN4)bJoc$EM_?EZHM|3ke3JHpZ(y$SaI(ZTPd$AuF|#8Vu|F=?ofsqB=L z$D3Q?&VQadEaBq|0#jFvU%`Up%fx_nw)*{*k+GU#l2n)bm42Yj42}K_HwpQv=j(O0 zatW(xM%aWr;S4L*YmiJ3*3CA}q(4o4H>pHI&W9M_heOw+iSMQ=Mebz&dNxSd%=U-O z!ZK$S6sx%IX2WV`>AC@>M6c9V1;8xJ*o(XM~Hv*82YIP9P2sMd{-%bBWF?gy}j{!+1>Zq@#Xic%M8;{YPdE9lrQC!eRI0)PmPf3g$J+G#EDkotOY^Ag{WE zE>QniYrR{OTAeednEq;$-p#Z@{9}VW6L7DNd&2uYR%~$qzQ!%|W9REnj$;W}GV`r^nZbER|mAO4qsElV~$2V4cD!?MvzHUO_o5Ys8@ZOA22I9yi!W9% zN|Tw4_@$op%Ohg{RpfTz#0IG!=&F64xPh;X;6SHn-~H2mjS@%g@%P5#U!NdjUd2!= zk|FWhtw@JCE&YS*!vh%OUU#ubFZ0%G??aZqy>HTBnxusgicQ)j~i-FifsWYwUtmH&m;Mr(_`(qS}82)Sx3(?+Te_a<^1T!DZcSYnfFOJ z)&V$b^j!dJ`pf&=*zBB|_Vl>(oEp22WH}*e067Vu_bl1Z5{bu^PG!b-H;Z=U>h=|$ zRx6#Hs|X)a)m^+Rh>r{Xh&(*#xWKPFB5Bw&8rISFftD~q zoa<81hOc0>zyWKvLa4SQ-SsP-E1C4#hrAId`QKvw1M=Ckv->2g(R#M|ezzz2$J zyArAc4Jp22d&#M4?ga34(r$Lr#{(ErJDX^DvY|*DjKHA?va}m#dnuR9VFfdmzt+*` zKZ`d6)6eo>e&h2!@JwGB5&6}_GHX-^k9BeL`+!Qs10*lFr9V8UNR7dO*VuZJ92a*0 z${jlNfIer>VY$pxyxsqKfhP(qmB-Z={>}7gpU>w~?a{Lq>W8xZvyPy4%tO`r>_PPv zZGYbY5Sf4>0r|C}u|r0E$}pIqZC`=$rbgQTPo!BnoJjRJt?+DeU^J6tPNKx}w~Ilh zl;1h{7lqqYk*Xpg6CG-VQGnQh%~|XH8+bW&srfi<0G@d*!-ZWr06|-Y7V2|m({lOA zj4M`n_Z(8NhqLK2q z-lextdcOc?7d-L-n04Ve)3)dEF}-0zD?fG(Yk_8~IJzNNgDFJ(X1g0@&lf_rhg^sq zKAWCV-Welkk7u^I3EZFOd=$?3w_&$-r7d)ju=9OL`4($2N?cQOKyQ%(K*YMmuEWc9 z2mbnG21SlIF+{rz$FaJZPVcEQw`?`)3OCGTDgDAJ|mrvKEGXqo*T@5k) z;*k>xF&1xs*?i;Av7FNJHh~uJjtroMP2q_q4?l#X!GX5CZ0Rp3S*w!6;jkX^aP%0@ zn36KCq^a?jLz~MDE4QIf{=M14-cfID%?pv@oFg|{obp>(J9W*H4+7X)|mOl~uaKWw-LT6R}#=&Bq z;^#{nq7cV)Wjwm_v^IJRvqk#ihP6O5+x+cQQga;x>c>QtZ;V8w%r-M%3@=>YyxeKt zeXlb>H=j)-1#_p&H9xbPQhO%X;()!eEZ+-@+G#VbY1xr`Qku%PY#W^(M7Q2ZrS#f9 z$PDe6#+Y|M92y@%py`Q06~ zYS&wCu=1xtdypqd_6O}p-{`lsa+f}56HJw>5G&h}r2 z5zOvCaX3TTubmx@M16rsQ&Cc^s1qyw=G6UO!gbFGmpBg&ZE4U zY(^s-e7!au^XBuM>Of}!=fB#f@BQ;yoSX&y+D0GkXXST+D}|9SqNT@J2{9?of>dZd zTf*%BT0aA+*n6UVKVzebjI`_6XgA zGPD#gbYZsms?SyFqRlY!a`p`t?1sRVGm563E5TQHQ=uA}l$S^&4YH_07*3~~sLhqp z;PS9l5M=7hIIiFKsi*DXbBLG4bjZpi1MqpJ{PM_2GkPN6~ zsA9@1CXwz|ZSfOipUYti9XQBnsG5YwNg8(`yY0z)wRnYbbG&StoAc$|0^(6}*h9b} z)&N$Y+a$wM|BC0Jb%=jyYFEf*_RIyj&}k6fjc0S(FDF(-=oiaMG=104k|@U}1zyCtLQsJ!|^dB>43A zK^IQVDIo#Eq_(8~=c1=+1vBRmcL)*8z)rP-AGeg0_xF+9utk0)mfE+4!J#qGU!I%CFY8h*T{zLk9vX zF5Yg+)=5oWk^~)C ziqp@=#CbVLt;Neubr13TA<9fPk7TiO$;$&l9jsdJ^|_X_S4!foU0$?!)=_amGA%mT zS0elPdhOHmZ(BO3(%NEi;=T_}1a_V_IEggF{?w8*kY{`j5 z%2^`n|C;#Lk{2n{?5p^RR}qkf z4ub>++TBG!cZX70uZ+BAnfY`1yQo*l{V8+dtCM3#m4(@WWPqJ1)a=q*71<~rn337L@| zysa93GFnF{n(9t<6a!w4!bECqU^CZ(Uta%A54&cic#&s#yO-V4@g7yc#{;;0t(0Dm za^AydEa*yi!=zPp@y#gTeiyxCQ0^UV$9`y9!XX4%5DEY!aZHJM_VAq`DEz|*GBW#d zHs)VBqUICg{OOK-YA6QY>Y0 zHCE$&q|l|PpsuagpMhxP=~H_=1|gR~THdNB{8Rh);L95hBt+8^+arGV(ouxD$F5LI8*~4upVJC zPL>Wpp9JogGaY0|(KhWEOo3?p4bX}&kW~^HE+kgVBxa?a z)ASG2rmYy7`P56#IP|jACrEmTrjt)A5#sv{oTsV^8*)F3nQU>m-1uM}>^jGE# zdq^Y}{1c*u0jecZ=vnb{{%8xV=rnm~*A;4&)wEPtt5nWuai?e`BLG+jrou6u=qa`L zm=RS|jnWR?_S??nj^3dy-QktdwCj2^3~uab&+TxV-iI%NdIZs9!xG~ojH8_$ zXv<6-&e5?#35}tK!LADV#Lw#WjQWK9`g3DiBYOJSpJNazw9d~_ZR7g?q$NgY9LK)* zjjp7$tlo~#rWpKK(Msom4`%8&ZzbW#q}u$_>%V3E?xejEIB^|4@gv9JPlZ9(A2i04 z2_UbV5FQ<=g@^e!@t`UV54&M3@a`QV(Q`83gqWZXafo z?Zu0hq@pn~VHNWO68IM#L>U}I!LmTGvpJ3C|U&M zvy>3AgeSs=7S_U#xW;!2sUCV&Gm-@P>z*d2z99d>6o_lUpl=u%2T6X0lTk5HYNzVy zys+FiD-=cY&0>DJHT6vuz&#`mE4UVIHH0^s6y?1a%Xtd2zkYC00z#-B-W=`lH6u*0 zE!@jos?uEYqJOf4iV9=;3O+n3U}mLY#@tPIXSaBNoerRb#v@__EldF+s22|lKTNE< zk@got^G2}`2FB(&5!xn+#`OJGFF#I8G@+^7Ubp=BEx&-iSi-_Jt|NAvoCQeE%1X|T zBuBf&1^_Gp7JwIMBEt;4_>8ERdmw;Yy;iPOSmiQd;j$OSXwCL=gueAJ4td_wIT>8S z)lcPc+(~)d|CAHs5p5+{C@9P*j+F;w5rR(#VUMheWw8L+Lhwh+L>U-nF-$9QCg1AK ztaU%yL~x=b9a(9tEU~YqByB%^^CZ#ze3WgM_|Aki#x*1%2!O}R22m`*dtroc4Fw5q zHmX=nFPXJ|i!jfNusmT}N(L;A_pW9`Q195jH{w1mTCTrleonW?tLA}MBVt*iAGHG@J@R{ zj*WfM4fY?e=x0o@N}NOw+VF=V-!4^8@4N%w4=dUGuH_F7>3hag$(r!WHHuM4=pFt| z6a+y_9fm0q<#H^kE;aSC$mc5;XIuF1Cc&WWy&34e4r!(CfRmNjdwpt7{mZT5=uXBZ zC!_nyzozlT8GMGvl?E=(hDltSpTI=)ImAg21S)}O`HiZ_y4sI6>YasnFYfqOju861 z7d=%@<~z_eS;_4 zbD{ju)l{LO!iH7K| zu?edzA{X$nesFwio@iBOSO1;utfg;vdt{pNyjqc)Ja0E;gnr7JOOf45+{~kska!^i z_N+pRy-8?|&qcJL^ zcmPUYIY!8EE1q4c6K`q>t|k1Sai`%EGylK;YWE!uuth(=M|g0`^iY!Dz0uGn=Yo|F3kRRZ(f`{8z9M<7 zCF0kLA2=1qxdb7z;NPJ3<~VjXkvtx7v6~4xsm%2F^c8I+sExn1NoLMclaXM43aUYF z{XV84A^kbu`E#T;Q4Y;+&*6(NlNuWC)ju&QatV=d#SPz!*MhGW{q+G%(f|{z|1$f2 zp(d#6(}1Ky@|q{{@%=6(iD^P&pA98gx5gmu3P^TOz0Q0Yq|V5=Pc!Wpn_}JFK6y}` zoUQApXw>6J8YSpzk(U^pFc{hw#CoyO`1LrYM9+2Xr$Mgjb@-)E6|+y%Q9!M!cL zW(YZ^ z%h4v6`(<%J4&0B)%}9|YF{#?n;HjTESzx-GKUU+yRQbY;Wkbf$yNdK|mo)Kn1qfJm z;hiGKx|pbt5H$5bmIwi&-J&8O|7p-%8b2H0-i~XkO{+-0vx}#w}K3DM8!f8mkc!`=kml zj5{cNvLT6E-0|t*WzfZpEy2RvbX1o-F?28D>dH4ZI2C~JyO!W*@xpg4-qv^1zUA7f z|GIwen#4TF?<6oCYH)!Gq^MJJ^mSKO{=0OXWQTy*b^U#{%MkG|I-_IA>gGm7ihBfJGra}!>PydzF5E{aL z4A=g3?uI4N{F`-zcrFHcKMsq1aB}X376U?{2b;EYYD<1${Vj*35Iix$__4*?G5p(2 zG2o+C9ZGoIFD_TXb^Iq>5IB0dqa$qJ`>u~A$#U3uq-gm0NpRoOeQX`s@#m~0N4se2 zYM;^|;wSZS5mUGuEw~Q`V~AtK%GJ~NPs3k@m|Q5T%M;uWC)|(J5t3VkM%zWz4?=xt zs3?bW+hpTE2s|5fi!)!tx3s{TTi|LVBGktII%!^N`-COe-wf&p@2CQC!4NJ09{Gbv za}9&%K@a!bJ7raiCZyA-af7X=yc8GmS8Gi+?pFUImnGnSUWR_jX3*&Q>)ctF=ikN! z1>`r^M4?>p`Bs7dHb#dzRBp^I#;re5D_h8#-ne=;!RQ5Bz1W}*D8ZzhZDqN^sLNjH ztG}RDvj8fEp{SYRkr71xvp?B=;j^n+B<1-1-9a!h?hi~fK6bZ8z8;hiCCQlS=OJ-w z`8jjcV8^P>8O0m0?3uAldG4A;n{yE(CiQ1^RCivZ$hD#b78=_|U+ndoyE^jv{_lb2 zzSQYj4{+|X34%xr+}dZ-yrHezubj>_;I=BNNR#z5M|4cg$|I3?NiZ3GnB0C_O%a~1 znMm%Zb%kf6bw8)U)wWt8sxfB_7^;hzc&ar?BatXUdt>+x$Gx7dKvyh4RB zVDB_1*55b;DRy^ymK7(H3z-eoeQumCo@=_Hr)Ud?P(+9?hhz|i-}$nqE9RLpC`tkl zx}5IAJJvBJNVmmA5lL-_1R<}f0Y(!rW<85SgCG+dGRO#U&SUnbGfUFtW!06M{oGid z&NaXEHudneoAyOoIHXe2qVH zz0mxH&Ld3bsZ;P;&L&$KQzeo7?K!L31d;tNY+rrLPJqFsxIC$k5u-Z^CO*mW)^4iJ zSdZV6vu5q>`~eo#W(<%JHvDqf(}NH^6wAVPfbz5t)_#eWm{rKFIW=OuxJcIlk)8RkncGmARZ%J`s@(>kH5iZ%seEi*` z=I9~yoMxBu8OYpnokx>-kV)90|MvaoNj-|uyf@(I(-U)x9)cDUSUqu>jW~kH#Q^zT zo68yQ)nyF`(+4lMIvIi4Ns4DrJI{87B|pycfAbZ^0Icmcb=DA^-jA8Xz5dA^aT}*r z^jMX7+3aDIydSmgT6KmQ&Zo|#^Qy!cg!hgeNQ4@2uJueRUL6Jy5qw-!dW;*M+Msx? zRBcMqx&7LZ>FamFZH^`xujKe1^tanESkUHcT2OjNN! zBnnUBy2PV}h{d4hjLZ{JA5Hc*F`2KFAVjT~q8NpzAd#sgO6QAGd$4xuHMB+6XT%NC z_ESLMEu~FPINk*@lsSu;bXFV>d7rwn#+k_dbP}2iS%UlWb1MfqE=jm0HAT4vgSlN9 zJm0M!LSojleHKelVW&ZqYoB6Ii9;uNh%W~AOAy=`=OAcRDL3d*wNZB>xwF8tBWzXr z3~%6MzGa6iR(<6m-v)-a;jsQ^!4OjK4p&BLQnUAK{9Nw?4?33ef}(Jk9M%X*;rhy1 z4e^RrPX4*s<*+MF2?EA)mRPJCGjH3BW*)dauerln1n)nsVoGmhdySpf6c8N^U}MVs ztjEWmHzJAhr<6gV!Pj;gKgY=YF|%o>MzY%f6x9@lFaUvGe8$kX_9SQm;e;bhnDiN-D3O+qM{o zPEXbnG(pbPSpeT(!6C=BOxP@4J#hwPck0NZaQ%uqPn2*-Ef)yQ$@)muAOV`cu?mbM5StW3lf`X?BRWLmA%BfpBJ*z0YoE zk9bu7YyS~d09Px}e_|7rMAOl%Mq`#TNJ@+#l6!I0v3;b)e&3yrFMVBW?R@CX?hk-- z;k1s#8Ub#xZ7E#vfMCVk=v~n5dOX@eK~j=0J~Py&jFy$Dy%k^Za};TfA165$fD5q5 zAoQMdWGor_foKM#1h{_Hxc@|U_>z`;<@4Ph&s9KtWkX!rCJ0gCYTx@XejE~-8W^d?$^y!5|| zD6Dr1k`^HaVLomE0Nm_-G_Eyq5;D@^jIk6bCbU4v`o2{Fm>!#f_qE#WwdPn11<_%j z0<+(w^V5HD8TdH=l|n|$6+0z3UCTfJ!{EbO zpoKslc9Zy~0Lo=rX^vJPfp2UK6$cJVypsf_ikM-o=lsNSZ=4>k{6T7MPZD_#NQ=Uk zTO$2W>ikcKLoC96N&h7z@&=a6o7p%b?F92 zM%t0RbyPTn0Evp^pFubHdV8NF3?;rBecq_D2N2V@O%(5(_q+l_^7k~9!lMFrE7%Ee zSY?rF@KhV43eZeQKXt27vZq@h6&BEg$U7wqq9}$Z7%CtIy7P~ei_h_@2bDXp)yq!3 zBj8dnuHWw84^Jux>=+N8kocqQ|HRNfS`=1c0}S%5DBpjfG7Mx|ym8lgq>f8t+N&fJ z$8?yWv=s-gtXx;dh$w*=!A7&oo|L?UwdztO2ke0R~q0$_4Ei<~4&zu>Q? zZ4G^aJcYdvwmlOR3g%P_)58(yh=-`fi0F+XBzk0hDFFf~g+m}9qg&Z7m0W=Z;Hz>2 zM0AXQCt{2JpEhfSwQx$4x)0RZ*F%224B)a?L-kAlH>J7+6AvU!p;Dt9i}HVNJK1Wh zoYQ02!15-yf1oJ#Xx&!$x*LBCcQ|5Q@(+TzVxtifrC8Mir34Ce^p?>9Bq6=zPDqKW zr0Q{1Zbx78dL%J8_&|2t3XuGesvriTwv`v^T!0km{-@5M z_PL;6aRae}Vcg1R4W$AseCw56uSeJ$oW@AVfFyrlafhS2FTLKxWOR#nsLBIyXrQsg zb1DiYs{AXA06=k`pQT99PoibOQw5ahrIwdSv04%U^3b#`iK4p&K%GEJlxV(`7}~WB zaZ|@vHk(|`v7AYHY)Y}Xw5oGOKaidnhBYI(;}ogLRZ@q|64}^Gub)zIFtcZjqFoFf zqHmBjPbBHh)?IJ5VnynlhRJG?>2ZvVbjByK$nf-Vw8s3E#Kwa5x)q^Ow704R&{!Erp+z2t<$Ft2I|Q2c zv6V_6Ju36r17pwuNIp}Ur-1Ng#F43ftG!_kba^AG&?m43LaIFoBOg6V`uU(H6jE|Q z&EbjEP$IX0A^;T2Er$wil)_%GJmog?iYihMha28Ukc4^A?2$Z?1WDt}Sn#OLd;N zd+ufT4lyV{zPdoEnyIjdiLU2C0l<{v$W&4Nx|6ri_7~i9g14{w|A8X&7P9py6Gy43 zppZF0W)37BB1R@eAGsDoPYPzIHE|GnclEq`YuznkPD9#L1?dTr&Uh`W)+bz};+D39 z$a(uh=OMee`|>_g1>r4#Ls_x^z8IsY6IHX%{Q$FwoI#*7 zdT<~IC_MhgnRkss&%(u=6s@9Fa{vnPXe19GQo=*M@IM^n`zw9EN~`39l5Rz79RB)f z$)$(cFosR-;S<8f@OyHS;sGsG`YZ@b}HZR?E>Hd=r? zI#r+j3NFyQH)6~sa(xnLX!4gm1cpa#?N#mBs~2(nt?|!%rv^zqqsQHP>ZoG5LZV1$ zqqt609jl^cVv*Dc9El94kpbH!V5UwFho%gMlS&0U{lL0??RD>B$%wJcEk2B5=f>Mb zh9l%9qLGx`NQA1t9JuQ*13jS7{cVav);B4=H$&#{TiC$-vAv2_y}~)m;?2DZODfAn zE)zS>mP*}B7azK8)c|PCyI)5uB5E9+-2~SzreH*}U@yGJc1`N&H$o5)*h8~~pt*1PXc;b7BPSQbp<~5Nkl`6;&z9ZB=Vq zq?_$8r3&ubnDV#BLqZcwQ#kxfy(Xfd5vbkj2GJ0b&t}I=P%;!cKr95JHMULJ4{h4l(T0l+lYJ^kfW zw*;lPZK|>)LPE81=-1DJw*i+EVG*iqp>6P*8;}m4^!OVk+$PK@F9?kgfpn<>M1ZUX zD(J#YcJ3J73=nThG*3Z~XonGxlRp;?h&xz}6$)ZO04YikT>B=L3P?0Z3_A!w5~cyW z%3ye`#+_!ml=a_(@Ud+FtXm+BqkvQ)q?@@4XI{?lR^<$#B`S9#U;suDlmJLYkQ6mh z@C*>Oe52%3aVh>@5j2R!GppwejAvmk8e+l!OkH3$^SOGznwYKnGFFtuzgKxBT4++k zix|T(grj__s%Q$^&1Ih{o+tAcF}4FxoB~fqJ=%&(w|j>#kiAIc%e9AsA)RR z7y=w2xvN+(ScN@7g>ZI~-{%h=1zdhZ&D4O?%&M|`?mS^z~ek7TiG|+?WciWSsh`Wj?OUn?9@FChaoJ zPRBRa^8U4AM2#JQlH(7%k2otBbgO`*7`yaT?uHKqQ7A-tpEP@`M)_bbed?lo$*$_tkm`~S9}JetkLJq!L-DD}R-?btW&f=Q@?D-~5XGwZt#9yXe{g=EYp;(% z+QSq<+W5~2wy}|c;txGkg(oAL7pf{si<1y=Eecmn2nZ2Pkx5LK5iOKSdUGvOBa@u1 z!UO4{U&Bl>gB@pE9ork@w6AnCKD3p6_|o{H-4+{!+WjtVVHOp3mGM(8nn0X;$7RT$tr_@7f+OE#3Wi?v-i8Zz9>%qQOti$ z;g5UpMJQ-M2+DB7q~mc73oU(8P+;Qc0z>KE)8y=eL!bUlmA``X2WUUDCjHs>_wC6| zvyVl<4N(u^sh&WUJZ{NLz1P3n0Omzvx002+;Mni2d5gZEHm^UlI7iB><9=8$v9Fi^ zDf)Eltd3~tRq{kVxBL>&m{spaSL+28B~^tcR^I5feD&1}Q;vqFPYWfxq5I9f$^up` zVePdgHCq!`lo$a zUH|-=mY&f3)>jC1(t)`0V~cM(`|Eq*hMpbjf#JQnS=srGtu1|x z!U|vHlluf=}p-t17=?7pNVIK{n;Q%XJUu=>|A_+$XSGL3P)*9O!rG~6Hj zd$V=bxis8){PI8GX;AjSR_qX0zIgfUjSg0S zEYjFQd2KSzZSnz$2mZ-YbLG>u_UwM9j(t}en}61;JVpI~MVk09F4NWwd({LoR*f8) zhSG<8l*dIvX7de6DhsZZ(JX*N3wejmz2(WO&;fv|#=6DUS#|U2ynYlGn7FDHD?UpD z6J~Cvlxk*j;o8BK_{Az)|gw3^z} zxw1GrT7xfi&$jQKGM~m*tLmDUx)y_ZA0J7Y4;0C|3eKOH>aKJudxwZ?CaKM+rsL@U z2xyzw5z?Q`ORK*OJfO6>3kWOO=whdN&-N*ddGWJ;xss48Z~Cz^E$c+F5h2<9IaxGS&v_n@ zMlg+Tr*Qu-Pwv|^M)=#3#CYlDw>(lKGlmh`TLTggeMGU|YQ3F>z}oTG1*WqDbVR-6 zBgu!9B6%;XhGz}meO5~vC2OO9%YxisJl6+E`NqhklCQcO=d!J4G-@OL&kbupt8*e& z_tOKj#?SXZf5v+`N|+E?fGnLE-!Vl;@vq4P9_c0bT?|=-ZAnVlyspVMH8^7olCr)} z99VJ|7o(~|s*dsHL~0QbS;+Dd0#r$YzRoRjblIF+srN>hTe!UOr(XR4!Esp)=I09% zeQ0tlvJ&L{+9h~4YKE=Vhp$5$pWy#<{$wXj7C-v~EfLqk{hTQ%X+(#u_FDeMr|6)* zSjii5I?(k+P#M*RmiXf|UK?8TOahG$_Q|@@v^%BNF4A@wSmH zhnTwMuB*sZl^D9b`0?JmlXthurg4XbyecSUKT9Hh-z?7Di^}aClL{tD_5m#A{1)G! zX}jgk#B$}w?S;MKm+-1En=i`yUsNh#N%c8VowjmpygP1=IQfLZRcG)T!wqj zUs*O7exvXI4x-2N=M|Rf_MQKg;`m#~_+nTeizUczSRn0Z8{*mn8@=Rd{-D)w5lShN*l zisBpM0O7SWmmVi{x59i`@ebcSWE^Cq%fm6G+CS@xTQahV%i$;TXxF9l_!bM1nCbWH z1J(mwF!GAnweQ(7K_QjQVq39m(K>)M`#fr;41bOLB0!cxwD>r^G;>O08QQN`T$}-D*DreFKU7SWmO% zDTOPc2jwBr59&c22A93HEAVjJ%dJQ1v1(|#%4^E-i*kaL4hNNEauhFzfogY0#Z7Ty z52MPs!4trsq?~)KRY@tn!=8p9_#7DYnGK>|g)0|6i*nxs<$-=hE5SvXA9pTqzB+B2Gn4(tA~QhXCrR*+g^N} zb+7T(1LHFW-jQeH!GUD76dg~;bHtd1*Jw*;JiHuomjI|kn ztzQ!FR{GgqkUY`Eqq~4F^u0v_fa$bjEp-Y1A?32*8I@R4HSo-mx-K6)^|5CZQPYqH zF2F8XAL7&us58b$C2ONTDIuWn!qj@%1uA#r5U+>^d+F!76(xPRU?Hy*co4NHK_z5EQ zHYi(d%#-A2s30^o0(NrJ2LUFdri`+xqFpZ^5UJi!Ilq24kpDG_jnhgJz`@Jdsnwh+vf}gBx+e)>K7kPWj zKUqEElKQe*E2cezObgOY{s$aT^JGa@1jUH>7>VZVF{ZLUc(sW8P0$Bciud1S;f`d> z|0~jz?o#a}o(?D_E83H3=?$y5ODGdA`lTOyGh531yxOp6-z;5@E#x1Wt{bfD=E#re zYZSqP02Q&NCKX-rSy~XFypINp6=iPqOZQwl-{c71y*{jkXG?QXZ7p>p`lfcI2Q7QL zNTt4Rk9+sA|I-~FLN!r!h4_^-_<2F1w#pTK#&nolm&{x`Q8)yXxe7e)*)L$ecGK3q?| zmv=q-0LJ<2(DS0SuHV2;W{2k=@zf2e(Nxk1>*WEJ1QN~{MI2&B;8ebXIsEJ?soEc&VSiO{ z7~>kaV6V)l8{mGx3j&JuN{HMbxjak&&zQv0nA-?tW`v>a266H1k*a6X(j^Qqy1@vd z8v$C>*q?DCW9!toXB39&*nK1R&qTCsWhGyX$e)T59r;dyhv}x{aOHN1D`2Aj)AW8u z?B<68pJDu=9;Ew-2mK}kZv$1F4&y&GA9^J}M1hF5xW_ODGd#v0+nrAIDv{@tyFL`|G2J1_~SY z+c{^d7?Ly()CBk3hAR!8nFbO=97mt?1el$@^ z*m%Byz_mK$FV$4%tmHp25f1pJQm2Nx@5Yt-jFA8AqeQ8q3{v`-r53gUW}L=l4^-yP z(Ilg!?Eftj5E!5UZw*}6@XJvUO%y@quxa=^XY?rUpd!(KkSAi=y*bLff7q%66D-tD zD{@pPB}hI}YKxc2!Ay_|Do^6ibo(jAx=js#f95WjR(WmegV1VSpp?VOWn0eXq!3g3 zMactji9gNJTmPdqnDc17Qe{+A<0%*-r%6jVZ}i<%`{(CJoNT&Hlsr3U?~3a2D6c`QQ;_2A%Gfd4@|JbB8O3CHk6lS&0G6l0Le=ZVp4%N3;f4|{KCkGt6YxwLEmh(-2^A*gs#kUPJolh#qCyqTl~#=Ed1OO*WC!#{S<3v zLuC%fJD_=a!KG5-mc(w~-DH;CWN{#AE=mLIZsb~At8F^sLRIB(Bwh0@WfEk32V6R)XweP7NfBX z1P?Vk*avYw_O&=LXWu%1vTbf$XU;?On7viXXFSM8Mj%%2$meO$ONZts;?aK#PuzJO zMA@r-Bbr^KE?x8U6yv0xCQ3ciDG6BV_7S}D58w{aUu0#(U|SnG_|l(1g9ASa88?`-7niVPbt{EEW(%DS(9I7teC!t`?UuM0oFXmt zPzaRUJt)YxFu$^$mI`5Tuu_TQ;bxO(nfB^x3DPtV;SBr=Zw{x1i(|WKW`cEqmk;tx zfWOmIe`)sC9KsrD?}%V;hTte}T4R%zXNxqhBc%Zr_9%iS2P_FKpsMi&j|JOdAeWAe zUwOVaYe?90uJB;jaKm2w;~f^t?ighmUmPi<2`yV|LxPP(w5kQ#%tF(iHqhx>#O)8u z7eGP)Z9rlstpzcffz6CA82z;cy)7NxwiC@N9rJUWNb10{$RfxwH>mC53M!NCeQpv> znPXy%@6qGrRhgGZGRl7+TSp{-BuWE>qJ~G7Qg|s+U(&F-NpaRLv68}F=eaW5LgM%> z!rB*A(?bHXT7@G~%yRD%asDQ{UXi}0&SC-iRY)bXe9Mek$}#yb>)&G^YUC$OT{iBE zf6I>pSRD$Mo72cP62mESxxeLKENaEbT3?Z;Xvcx8N&~PP4_%FK*^@H3tPe+WNE!{B zJdsiE%NNOy=?YF-WuE-!af$d8vi|-Roo^|v%sS2M|HIr}Mm7ETkKcbY1{(~v(G4S% zloAEWQIaBH0RmD|B7%T44(XDR?(Qy;9Nj4>-CZIg62h*1zTaQ`&+mWLxo%zD*bUCv z;hf#rd7l@r*Ykn+pz*RY>Y;v0jef$PXNcc=_CueY#xhf1e|3LQ82^)w9h51MiB5y9 z`ZGO_-I=zeGKdM%SL0`J5}e_)Mb~^F_^g-U>11z!IN7T)joX$XAnbDH znMcq1W)`)qN8@r);C`Y0VAk8WG11hLcqGf|*!NSUN5*Xf6>-K~@@%?GdGnNH6z!wu zuidkXl5#ini!UGL;l{fGVfh+80-LtvptCRRnF%R~)hHDY6bKVraJRTZTlJT2ORDD{T8F zDB@+xkt|jp`Lmc&!2|;N)Uxu zt8^$&%lAUBZ^<=fu&);-<+(BRhj1b_PQs8~x0aBaNuZ-;R zjaD#ExcYgsgOH4u?FSF7Qw}ZTvIKxq1 z5gp-|!i>HpAzrgAEnJ1ouu5-KZOa5X;_Hj61v8cz3A$g)2SsellMjqGRMIyd$*eP( zY^WJ+DyD5d99?W3`yD*grItV)_T0Rbh+0C=D-q{V&UPa4inaJgB5ms3rnNF z|4*D0WboECS&0#f!+QePlF`gu2?65~j%%$zL0N#u z2g1&+{qC$lj9ou*M?au5(7+6|qFL=5N_-YaAge3x>4+fAa7_ZLrE6sUn@=J6cCAMp4;eKO%gZ?n zMsLnEy~8#@ou8a$RQkF#EDTy&va5Z1aY;%2DJBlo<_}|%4R>2x>;kOQl~ZZ5NGz|k z1!x-EhnaZ^$W#RXCOKHQLP>nXhww2yGc)&=kRU|S=kKHG;^P)J#(GGdc` zx>GkNF)y`fz(Ia5T(oFB9`E!NfIc5yzWBZ{FLQdBPN7g1OWmF#7rE%7*3(7>VVkOm za+G?qX_5pmcwVP{KX3ZJ#EeNNQJuEk!LcNcxk7KQ6UkEai()@eYN?tklhS@$^dTd{ zXv#gLSLtPblX{f#p7FGo(ItU`hcV2XL67|d-P3IXVcuJmrs0x@5-Z_8FX=Nwpetje zqLdPGoy<=27_(0|^0%{Xbh7W}+0OnAw0Ym65nGyHdo~7a7*KJvU!}+B%El(IIK){Op@kR*r4cmq$mV<0?;_sQgl@D z3+}~buz!J3Hna8bQM54MNh$O2x+MW{@g79K!GeC(8=EbFno3buQ6FNdIr2?}R4CSR z?bB&~xI1Prgo!!cKZAQs)mM^dYABsr5WF4WW8xCkh442;@m_&Jv2bvN`^AbDd)+%T(~bW32hi_czQtXrdjy-(if>btP6 zmGgkH;}_gjZbmWl3!?&~!&z7e^t&Ynsz0XBTiklXE39px6dop}3dF3if21CjJu}_l zSNS5YH$agTU6Lp0Nb*3Q=%;eF(zJYVZaAk+uHlve8&Raqu!X2o(u!R^cLu|-^GDlc z%i^0uWYzh1ZMXoqpCT!0TK$jjue7RWGdYO0icI#SG_W_VRMLi42}>?@%xv)RDwfOZ z@KM&P0QbFfcY3x^oI@tjL1C-)7SDTl?$gf`sxYU_(NHtz_yLO@3Hi8wnYWWUV&pUO zOm*T8H#(i^zW6e)uB*rCo@5Bo6loMOj7g2u=4<9Lb9d5B#DmbLWSxDa%UwOOlvCL% zMnyVpq}o=CwM7=)!@8ei#zykgEXA6F8MlOqK&qk{XH>-o+#b)GjFofPrC;geE?NrU z!o@-@=x_Cw(Nxy?&QV?bN6b?9Tkd~LO*`Q?5qd>2Nb8>vv6iv~d`Bu4$3#2F6QbK1=gwQc}wui0Z<;(wi@s=GG~}UqCDS zYf#;ApVBN29EC6|t%7jM((=tBjuor<>t_5nd?^-0dkbf zvs$!3cJQe0@b5rR(umejyCa8#S8|k}Mc$jG9R$1}`%LPj(b>JBElkrfEH0+)ck@~> z^w#v+rCD^F(TPxaO0wzi<4>xCl^6x6Z~##`&?nbp67|UICEr86B2n4u1cn$3?(RqI zC#j0e`K24sxu!XOCh#C

3?$lBc|l zo)I8LeIq%j!N{Xv-yfzJ_mNkumEJ?0GH`kSCk<;vIa_C5k|&S&&))qeFObdu>g`?m zWQZYn^mqTvmho{6`8*0&5cpCJ*MhIh*yAIN58KQnf^aViBaNj|0WA4PMh~jZCVPqPLoQQznnj7@* zIHFpizeb<`gKhtZ&;aryKnKvw!M_Fv;Kj>-3W%8jFQ9=B`T~sU17Ds6m|F+h1P53b z2EOJAG};byEcCbI39?rWa!CxldxW_9^Pc!8AR9%LTnQ&SlU~G-kOlkQ+t!hq_LHOc z2b+>O`a*5dA#v6r3Be&rg&`@bA$BJG-q?^Vp3ofC&^+tVg5c1iLR@G`UufBODE_v% ziYKf_A~YE54fzQx$wbzoV8J{Np^1j>T)xyiNLn6$C2N1x;2_&+0v9ZJa5~Tx8ez&4 z@zpKR!8+olUc^j8;B;Tach$h9hJZz$k2-}xccDOgB_%-vdAbQ}^bx|W9aMxR$BU(z zXb@o)5%vgvI0jP}{*MS&6dLJPNq&kU7d*4Up1t(;_t||0KL~pI!}a||kXzLs5B7%l zbo~aOp?LX<=&lJk8H=z0fQn2KkPe9jmQVu)`;88suOeD@AU87w*I|fdP{a$`Fwjqe z{V`H`ZTxTGQtY5@BuqIIa*_!JjT2n}B#Iau$(ae5bQ}Ypk?FQVycY%!K)h)5UrOJN z=Zt^(^l3cVT?>+S(iI29?h%ZK1n8*zn1O=-!N41}S?7NeEC>^unj+mC5D#;R>de8o zWkR45dJx46RFcf0kTp>-LJIO?Ok7A|+zwbh+#w;W0GZ2e!>al^+vYVYIGX96`F0^^ z#Sw`UFD+3tbPt6@Vd3#d01ZGodn8ujfPXtN4hsT=;U9&O2@d4MBL3GZRBee#T|r5# zYhIj*?`Kp#6cj~&--#9^j4{oIOq<-os38SW@FZd6{blmYO2nKtA!r5G$b(d>3<59+ zfD;)W1t+EmdD)&itpD_B5H5N0UfKljha8(^VAm;IlyD~s3?fJev4bWmVSjZ9CXPs- zV~Ogb$Y}uJ;2!em9{5--12D0?^nI>>CF%82=|xNQ5xLBPyna7um*;+Nqz~I}^oy@q%|YJMTOj#F+C zJ_H2159Hq$Ca-je<3N&kUs&ii6Q}F?jgral63g;Hk9-DFEaE7 zvVDrP4fqNxMRUwSiIyJZGRvMK!t@Fzh+<)|G64I5A_UN&?ITiUJZyUu3ycw+10;CZ z_NjZ)SBY`_hrtri%78MHJz^XowA+TNd4DQt?_q z@vKdBKyhiMWC@{d9>HvBxK(NQKtUIydjCM_=x(W@N8b2Fak=e{;&V)|df9Gm@v>y$ zc4MAieEf_{JnOgt5F58)Ail*|vg1*)mu#8aUpCh0xXM@YO}!#TrJO0KY`3u#no@Sv zShj!hN|dw`ce{cRcIR}rth%^NzqpbqrGlg+jbcv@Piyjg-{k zoiyt3kf!si&#th~?j@gJH4)(|)6rq~!t{+@tOi>ap4TtIT21*|*DmWe zUbX5yCwzV+mTrOX(t=Vw8w}aoewQ@hjm+~`4QC~|wu`~GtCThz3>&Tix{c0Fs;MPk zc>%+tm-ASYQ*7sM?dRL=B2U}@@>aXhwxgrl1!~&G$J<}{8k2do)1S6KckW;`>{yKM zU~TSTq39T(>2#ayxcRrkTclIWt5Z_6<4&`oY-wj0s0+_l)pyZz4b^%i-%u{4xM$Y| zTkX;zAczMrAtK#R?7ANhF+OYVHV_auPVLqUr#JlDZI;>vmhXYa^w^U1K&pG}=X>Y!+YIJdp(DGz4v?HllA!u^!aJ_1=#he*%6ik@ZZbi31f-gEAE-x9s%qm zUy+Di2blaAEp0>_TKw7gK!s*F zIhJHv7_oUonovyhg=~;Gixh`WHLw{dEFAz55SE+3Pq47h&7_Okh&>EUK^u8X8;;Wk z5fTtjIv^GSsCd;-`1}xXG&C+fOsF&bJ#`pN0R3))*p2c5u}6VzqBgw-wo^Ix1coQ= zhNnx1K~<4gXOS(%qkr*S57{t*5t6VH)-8a%lLa3^6g+L2t|!QApw}y)9fr{ct7pPimkGjkK8d^2 z3n1ZTSRyGjv5W(b{u35%WkTqNL_{ppy^JDpMUMkWk{_AGY8coOko!1m%J4xr*D}l< z2{uHLe_f`rT9^VkLcW>6Z;^-VKA3tMF-3?ZAE_jguOwBvg$xyr(ZImggy{(#VK;sa z1C@lomPr(`&vr|qJc^u>JWOt zBZP4jj^6t`Ax)D$Wtprj8dfTdtV6;A<;U?g=}S$}DJJ)Y$oC6qgSW_cQEj*~67E(O zOlZ6efrCd%e0HOt#L-|JFa@fDb^!E|!z44p$Z9N%qkRQrx(pnxz^nldt$%iX1<(ky zF}HADWTZRQZ8&hpXN_HUl}Kk*+bD6)F)`#zVuac{yXm?reD$Pk4U`4mKoU|L5nm$X z!vI9m#HtYMnyA*Y*x`zP`kDqDFuLBT(nJ;^$v}>qAcD2;F(eLGG@W|Bbcyt`M~G)3 z^rbt=L0RM(XxOecd8ZNmCnQ`n3%rBO_K_c#K0*Nfnb+Pl6oN=|EJCUjhctQ(w4+lQ z(vxDecH-eckozithVMxrS&vAT#uAkr;CC>Tkq2aHUeF^HWhv`cIed>$WRJ*nuK^CY zn;?8L$v4ojx%QM+lGIMwoo={ruOPBt3ptq1TWgcjP?Vx(d(f^nKV!TzH?p?S`jI)4 z+!g?+y-B_aBk|}d_0K&*iv6mx!=A;%>g&UwvOk<U%VJS}~Z?!PPC4)ny8B!8n2e^Des^5a?jL--M0Kc$qKKe=<c|F>TVxh#acUVn4FU2%J0BRRt_IN=PVxYSsDmk5!Mf@v=t2klMkuw5Zf&p*rwYI- zAIcTdGZ*BG+b1)edc_{}9@3;{V7OSCa)S>P0_cx1uPX3fY!vNe|X2;#846dtfcP2lG8$~5u4K+h+^ zQ7_cRRyI|*jMBt846}2RIoj%b^i@dg7!a=b0uTV*p9fAUh%p+a`qn}3UN#lxbsfnQndJv%@%{7*xTY)Lb!l=c*mGG^Pw3CZJAtNjNm6e@#9T z5o`h9&SpEM;NgI76M!+Ssm>K)bigt=CBR}uxn34>p_`3{1Qd=b`ktwT`|2U7G0L+x zCYdv_!X0#JAy)}V*G5s&_M_WsC?{!ew3B(f`=&4QX`*Qm0hW-AbrM<-@9P%D6~@?z4M?-31FdCH z63?2ZYx$cfW%y~=xUU34X1{D@_^~!_=cKgUND&P0yOHup4ZRh|ahzx+J5%1H{|cAx zP3%!u5pkapVBgny8O&kgu0jkPg_@6YVj z)z0;j!C4K$_SWpn?d-f1R%p2Gd?!xQM zToRqE3XC5K<`U3n{gFQKp`~j89ca~@!-DN&A->ZmKjVh1ouG|d!qawkfximfTd2@^K~=2|9~{jxy%{<1JZnD zVa~L0c3+}L=c7}uIm>~Yiu9&Vr02Rh+try0npii=kIRCc++9`arfzhYg#{c-}9z2x0dV0x6V8&_iSl3&e+1aXUtc>L|lTd&T5Ia32jsi>UI+9BZbn%=*d)N~1MoC$$v91U|QZnh4su9TZba%Kf zlTYA(OH+}x$&Cu2%p&)+^ONhau##Fh*Ltd@!1NNgOn}<|88EbxLnS|^crQIEz*`#x z#YE94@r{Mp)rQ@)+F6tiLPpqtb6^@rfqcZ(5T|)li0culw9JK0R3LQ>GEs$&wu4k3 zFroUoJ9XQ9B`g5-n4{Scs)+Lq4)wA{MVovSFMgCR5c0TC@rJF=4?X|)eTqfL*dQ^$ zA?zv7ucXPsE`>=9g7ubvz8MJpr+zH+ee(|T0Kh=5DA}iFycyP?3r5eDRclb!DX6+GE_{(nMt{{2t2^8$Byin~1d z`}gnVUCZp?Bl)8>#a@PZZ~eb4Y%?6fA=~!H#gVU*YRZMF&^yv7uk8eT#cLg zhMP;qO@G3D`}lvOcH+jzaifK}Q8!$_%?#e}oSgjn^((Hk6W7>?>o&xF3C6Xm;2LFd z4R>*Mg1G9N6B85vC42rC+1cOU-`m@ZS35g9JKNja+uGV%T3VW#ni?7!>gww7UT0NR z6|PeFKfKOTMO-Njt{90cBEuDu{I6u^d7)r?X~=((orQ&k|3!AzXJ`F4*%=py3k_V4 ziN^W(;GFDNJv{!4>`X{Vh>MH+^y$;T$r_%w`fsdL@*eK?Z5%%zj*AP2LgAPgaWphIN(vk~ISvBB z5fWarFca-}nv zir;vM{zo|0;MLz>*_65DN_Y9*H>c`5sf?t{nZt)E#C9U`ADU~H&2sF;7`;OOLv}7v z;4B|63^#rLv4r)*mu9?nmMQA3;PuglC4OS?d(# z+0U_lYzZ$$SuKO#v(FA@JZx*dx;%rmMhd-mzy5VXAd!JNrkGCmh1dtNeb^Imd*pGh zoH*}8`P6zPfZlSNHQ?&1bN&PA;#Q^`r_VDESMF^3Y;RtJ?`E1vTb?yd<`L_)2#L)^ z(}?|Zh?xsVx!zLPFhx>ovZBoSwb%OLtkyT7bwTkasf? zPj*@+u_gX&PqM4u$xpH=*WU!~v+Jj%)vhEJd?Eq$b7Va4PRt8@4!7OT3f|S*b~OSC zqsf$%_;zytgY5L($xnUPSd^dGBaC+UP0tgZJMo6ZlLnFQ(qSxau(w^xT5m9koN~QVkQR zk*4xZKQ_7FD9|G12|~^r6RVtYpk~KtHtzn{FF>3_X&pBUN=37IzV}piBS&8?bwTfV z{cMq2m3o^Y`A744KmSAMi!mj-TdxM?JSC!rMKqWlhlSUe*GEe6Jp1UQCbGQoVfNwQ z-%ZxG?pO#d%`bMD{#E?o9IwZz&0o)~^h;h-o9ipw!RzU$2=cRKe=BYY zlb53qGCqBIptEqe?$#Le71Me-zvEYyx=;_N5!a=AL9$F^0ZYzqJB0=Ihhr>0Q1rsV zEy3G!_HEAYo5bzqZ~E$8_L+aQ5Vl!uHBkvs?Gz6>dmImmM~)qH@!yI%+^7T5qHO;m zJ1rd)5x406MRrb0{fq2;@NcrS#7nQGC_OPqxOK87h4 zH3n#)RO|PCxR-ing1Pmmwu#g|D#8o^YHT~)8#>8l}7uM-f= z!~`N_ArHPi&xru(ci(PZ_EVWAgcA4r$>5Oe{+d{GAIC6xS!Po|J^>E!?Zf~<6Mzs( z4aT6%Gy7!4Z`~pu4RcjkMl)L%{_BuOububb=;A#P!@tqR1~6dS(0y;yG(rXmM$A=0 z?hY)cLv@d$g2jS~>S81S9us&}crF*WTEDu2E`d-q3#QjeZIf_%ghG$NYkbrOy+NX&+h z+SDTZXbyEk*f8=;X~;e<;T0k_F*7zxWH8+c0SSi*h)u(-pM$D@B)g32DShc2=Pk8S z4`b0!;dAS=fCw(q*N}sW&{6poU=sMgZ!PnVN`>$A$fM_Ft`!f2sSr{elwR;d6?kvwG;+}EvxflxmS2R#nA z1DP;?JleWLChD6`7AU7OZ1*dsIMvPmqfCo-z+-*Z9+m z%71u*1H0rn4l^31w9tqX)cP!jp$r^rj@U;A5=n&ifiP+b9(n^@c1~5C2I4pNE z*A;fi->mxRR{MdfnyW)_(iCAY++ifNtt@?AHNE3qpVQndtg6_!87+y%fnKBWb@?&V zYHtahcV|Jer+*PX+kRSXnEOH!7lol$enKDuKWS=tWS{!eG|A1X+=$IJVvxS9Q_9R& zhgaf@yWcvz6*`#X$0MmG8Dw1VPeS6cyEin~Xm-ft#W0S({)T4Er=)(;^g75)IG9l} zVA+lP!G7kGiyINrbNP2=SNz}vWkE;GN~py1?yWW-tGHyrN|_eKg6b$EedE|+CsSFSaO9S zk|&(>>4&Ec;FS7GuWh;?g(_mu^ZH7_9Obs$BU9b(n0?=4i3i91tc~LM$8WM`8;66F zA}g(5pea+hJ&%%{0)^va&&xvohhN4xsh$05o27+%PpT`&Xy{i`{?iSV{;n&y@#ycI>dgkl(oq+c2xh*oB z2O2Jx=qI-oEKMIWrs_Nzj9jfGCCq|u0>D;+4;SqtfdcovEVZ8-lKa6Z`CAA2-XlUo`jgW#-pp zmN{kD&1JW9WMAI=Pw^C>O6T_K=k^eN=Cq^(kZplA;)(xZ>M+2sK9}KXt;pa=QC>Uo zDxz~?5;=DI65UA{}zV2}~&*Agj8KkG|RpalZYvrvqQ!S2YcI|eH6GSq0ri@Obk zf5Or+q>U&l7MqV*1!>U6%x}@aV_}FY8VMhRlsp5`c*xTwt1=X4jrV1JzQ?w|VSMD0 z4LBI6TfR8Ud-3rF67-GOQE)LNa&ejNY3D7RSK24?{C`vXcfru0s z-gDLZn)K~lXPP0uK%I&IjF{O32^Y??1xl8zi>Sc`^^%?qwuOz7ADbnMzZaE$4=uZs zMev~kUl}79Kt|3QApO3V)?SouGnTc?GIwpg4QMPUIVrKeS>e;3_9*iiadZs-y>hTl zIn{dUwyoQ)ZP~kF0~m`T zq@|fjuI;4slvrXX2QW!ia&~2QIz0xie_6Hg(S_G&^EhECz@vk0_^H z$>g4+2ZE$OL#V>kB%=Ahe5$Vp{k-7}`|McV)XH?TMT+~$+-EPT>i4D|A1^3{dC1CO znp}72mBy&3w2{l)KI^VX8!GtL7)-#UUi4Md4lbn0ld17W$!AjAW^ehJ;(=mfc2be) z=DZX!6FjU*;jgIYucC)kzyqDjM5R#(J>=awSnF1Q{QNl2wr62y3U<@8wWf;DTt8lz z{U6r!XpUv{5-~nV^;H8I=N6KpmQjJiE@@!xd0XN8aU1;AYZ|R}?F4UxA@`6}P-MBc zL;G@cyO4gw_rwUHaT4~SJA`%}$pIaFn$3bkSb_Nt@vPPoMk?MUvUiwHQ3~OT{z!_K zAwuIY!i^SU&8|_~uHewFM=2fVnmytK?e>)fqK@(H!pS)$og}88B#J&w<&kib0Ux7? z^Jg1!Dgq{=caarNmuZf4mL4U*$(yG zHpNq;;Hv%RSh5;=rhz(vf`Pv%djFpA)Pc~_frfp$kJ6pD*&A+X5B=OT?F+9RZXS|x z8+_^2r9L#c6+Ys_4wMeHl8l3|@Q;!yoxRQRtEE-zrPv9tfz8yx-FZ4&!%{JJXvw|N zCjz~-UZXpVBX@kU*F%+K&0Sac!*IvpyCS4(He({D-Ant@ilt*BQhnRULpx;SH(nQW zM@&4|0Ve2(KqgdFvtULURw&NMn2mg5Szuy#Wo)u^bV_<0%`$n1V(e}-fxP5bq4x39 z@UH|PW*RKMTmqVjs zzQCi(R&fHq+~q0%rc#Xu-yChfQKo&vqoO`n-$fi7Deb5Z2TfI9vzi)pX+?b3Xqw*M zkfgX8wT<|Oc`zg53o39We2ynuqe_D!km_k;;bmDKw`ROszQw1_7DpgSD|2oZ(a@l6 z^G|0W6ti~^rgLPzG%O^zq?JXJzs_drHRiG{Y@#XAP^f)f8gk&$lr|UhbQUW!#kcU) zs%4gVJku$&?m2PrOI)qf(EZj&rL_Fl|STbycHB>7qC zhynTNbgmXJUp>&Qw#~gbSe7dM3Nv5aFI(g@UJ+Pa1u6+X6juA_fM?=$S&gSq@Wq!h zt6cDuoAyl7X{&;Q%WQ`wZ37bvAr;<^&ybMx7Z1Mv)?Ad49gx;4=kb~S7O`0PdW9Me zC|%J>_Bv@T&fTY5ePgik$frooKE$zbhyYjqs)!=%k zE3FZeRUvS1b7^5Y@z4(`yP&|jYnZ-Kd0qK7a{(h#C0o38B0cEcx~o>agX`bPkX@&^ z-cA2FJD*%#L$UcqYbSVk%Zz-#wOq2yek!=NCNO=wYj9-2eb?7)mn2ivA|gh1XEohjGM&@X|GsV4eS5G9fKqX`P$4uW8Zkkv z10;A?-S4sLw*6t((*wZgK$mW7K{{9Os;|a$cO`wd;jLyr7#N(?9Ho8$2tSx|e(;e7 zv<<-2@ymNSthK7D)~55Dn{+=Zar0Q#bv@QSG-9{+N=FVSz1yk6i`WGE3(fss0*dGpaS_0tpN0Yus2#c5{gFT;Yvp7PVk(bF`+nOgh3 z8q;vKAN!fFcLH?{djtLqbQ_Kk8BHh~0Z0SFpFTMY8vtT3}?r^R3hbW~P=es{(M>F2LNd9kTLhmk$qb?YSF7BQh1!kCs3tbMS zT|LCDp1pp!Uw(a6DO(4{I_PAs*T}E+o2)qr{k^c~cdxg)7_)j$4EWx){z69>*hBZ8 z%^Zh116H6|tj2d@RwXE^s|`uQBI{4Dv#JzI^FPVX05UbRf27X-kMIczlm77=Ly3%5 z-)he(t$I?VL{635EVNR{Mb1z7H;{!7Lp2ohQ`;Z!b|N%N1(Qx~LprRnf=bO|_5^_P zfwkrAU2WQOzcF1k!)b?I!$y~b#qN{@8^dPaXS*`nVihLM{y!M&!z8M-{P{MAzUbV3 z+@_$;KuC-qN1Bdm=mCjv;8S$r3h6rJ@dFmanj0!E$g0QU6ie56zA`V zSq;w|R=X*#d#rbsj^Eo5XiIc!v6j(MUxB_$i(gJ2=r-NHf?taQ-;A8IFr7eq|?t_0kzq;xq`|UltY95Z~X{UL$@JGz`L#q zr6?bzWBD6vxiwl+d#O$w8k-_pOnSBeI{dw=getQyjyV|xRt`CXKq0IFV!CSFd9}J4 zH(F2;Fu{%5M-MrNoxeU*xk2;zfrhfnr1qniabKT24~Uz1_9zN(S(?pt}EjXgIGaw6`1YoJ@uyr7Yf%4d@OUvjV8|W ziRXdav>D3?%q%nLX5)5{f4nv01Mm%Jlwuj44`szYbgro^Ml^X;6&1Zh2i;p1ZZ9B> z-`VmH>Hw1*_%4fi@a4`0N*%sj^6B$?$LN0i(bqqda<^@9uu-s1hOs#hyTdo{K)sx( z2+2>}-b%bP1NPdBoQ`MWZoIwK{0k)x$)pmtJIYRQxvQj{ipcV{>}n&>@XDEXs%GAs zt%HyFN);w{hV;8m#8C%ZZtXZk2>(gt8vA6`dTzvFjjzoBzC~hLY+b>9P=3({$ZVASTSqhMJbHQN z5#=C8L)5BlV)m`_!Z4wM?8ji>Hs3sZI0w6u-2Lb-p=$pS;nY>~EP55mZ{zH@_xotP z8#>!-bu@g|DN%}|Sn))36z%yl)U@0EAIy~O4{FWTHtE&WwJ0K)$IaOoc+(%e9gDWP zTvv&ukETvMdYTok3Pg<~ZVFTfz4>5%BjB;J{|O z{EJ-zUqokJ9$-8CVO1Z?C6?!|VW5t?@u_t`@1QzFs=3ShJ_*mJ(7o(HAFv`vPHG=h zhK+`y*4MNlTdVu!MZ=c1Z&UEwf~tKM`3~wYMdM6wvWYZ|81(!~gVcSJXDQV1{6>`m z&nqxuCQQQ8e`UWbRiJF+N~t=llLaLzik4+$3zU7FNwIN5$-A21S7t%>`H(7+Lv9Wx z-2 znksavx3v)T+pS7q`{`Dro;2?}Zk$nff$7rsZ&8^wl};k8IYNt{dwFW&7@al$zp+v7-{P`ol&6NVl=Xi3vL|60U z=NJ&NL*Prj#Y7~1J@F>T2XS@NXtJ-aFiR3p%y=Y+rdw^$tpoZ0oX5GT{#%6Y@S*?a z5G4e%KsZr$8B^mNbt1zl@Bj?f` zg>{uq_YsvA7nE}9%&>vK+Yov=->Jp$@83>Jl7FyOU!s4oRXE;Sh3f{s*TcG7$N$c@ zxoVWHp=(`ucU!|=Dro+~Acq?tc@jnKs|lTa4JEy!a5UcNiw9Q6;!n|quMaj&rRHoG zPb+cVT{ccssS84j!7f!L3w|~JsU18GST-9|AlRG+qT_#$IeXWy_F@W0{AG^uK@5lI z#B$<0p$2wu%JYfOUpdk>c{mmiuXLqpeOddswdfp%bK=3RT+lf8?8ocxt`-EjPm|2iM-f*BX{`&@%dax;m_ig);X7azNqcv>*Zd=)zc?!zdf5z*JRJ0 z-#f3Vi&Vu7?@135R^&|IzV2-OSC!TCyFmiDP2(Yv{srxdu`! zjH{6>yzTl^6D5ACCecc*Eg8=fXu>HEj^z$rYoUJJ9%bH6=qx`lD8uy&`lF=OL_yr8 zNs8s9jr63Q?eAyQJeu1}o}a5DVj1{VDK$%49&{;9A09m6!~u)#h{{%2VN$^5@^{eB z2NSJJkCw>CAc+Q`iUQ%XJcdoTsj*`IQqud_yUfL27uX`wa#OuXDMQ7DuZptHN^;E| z%3=!gU3Vf9<&C6BoG;66#wvxN6q!U7RlK-WhZNAMN+P97;b;X-E|Ry$g377r30ozd zSOr}R#m5%PhGJdeCPfz-%F#UjK2i7doaIPU^R;u8ZK}J`lij{0(kmTM2|MfyGLoXT zF1^x5^Y9J}>gt!$%8#5oEj2qH@O8;^g^-OkUG8;>thevXDcWmFy&+R^5K~bfQVwnC zatD)eDsZ@T^{_~{uX?Ds8MeP3x?z9WD`%);tJz09M_@@7atV_2g(Meh@6(m-^` zeqWtU@5w8*grU2M&AkEA>d6A#K|CtKf1#Xa#FvBexut#jT~z0ZbhU;LPApMMiD^-5kcwh5)_%k^S+yv((12v&VAop+rFecBxEMAe%nD|6$;j-YAbVf8 zHsa%D(#P&X-HOhkWlHVW*BWW4ktTxrtmi_Rrn;Qp!T#;|lU86G83-#P*0(qwa|DDq z;^Ekgz&0pY{u0RT6eIxP--o{!VHAIRnliC4-tpnXJ2l<9>oG+0SVh0KV|TjO&M8 zX9!|YHx;gN%{~d>p$!WWmX}aK#xPDR?jhYRuL;vd14ICxkCh=yJ50?AO`d;SU4y5( zNLuP*Z{M73$B#F}O}I0ychJe*>xno(w{guNwLzo%D+;YfcefXxuz1p39!rBr)RVz- z9VJB0CHer_7$7!yGBFyRP?^-~Rnr=`MYDl5rvD_uKy3v3G__Mcfy1=xvaP{?&A)%! zJayEpg)G1XH^gA7jN;Sr?TQJA((x_lVuXt0y&I(Hwh|0_!6HC{JskkdnMCfI#Q9Gl z(8i+7?})(T=CP#P#i=jFrtyc2ji_tB6pp1JUqw;P$l!gDeSwg_ghirfqL*NibWh08 z3HBmiFt^HOl_7xsKguQi^BrSj;HZ6**i`qfFhTOC?`sG$5IOnrV5_dt^S>rvW@Zy}CWQb}kulTep*eYse(tZVlq6C%!p_ddXnvE@8p|y6A_Yo7-%j znbL`b;bd4QF9^-|nj++S9NA@&P^X=h+$B%+373LWyO1$8k2E?~%lu6-|1e+(if4> z8(0^VzQ`_9w=o?nsA!>bq({mcfnE(!mAX;uD}bzwZK@Y-%#P_3U#I=$ZSA4^9~<*1 zJ`NA~9~(2#mM&({wv%OA?|DwkI-3bcU0Sj%+$R7lY?tcCmfy#<&@Z_#puRB3l_w`s zB4>1OP%g;M~s)&I6ohsjr(?+`TQ&~#9 zkQuKld3J7pT~KnW_hRO|ES9%pYS3!G<)_BH@x8CqL3gGDW~`>C7p~oSSQS3+eJ?tA zZL#S#4NkRBTt^PSh)o<+-{7dd8nOyZVY`lZ9I1H%gy@{lXp>wJko!X%)P}%T6&5y* ze{xJ~^p-^<9S^U*p2a(XhKY7wfbrUIQ>pliAC@V6m&C4@Sq}Q#y7(R}E^V$mvbPe& z^Jgs_mq}0*F+6k%Y5w&*#Tmy(qa!u2l$2vH=)0PK#2{M*nf2CB717>&up)}T#4~a4 zj)qG*yD7!&YB`g0E^i50x59W0_G|fT1tC|;wPhuPE^)Xt{I+99IdrH@3H<}#?1CJT0(AL<<`xp*NyDgcdEt3AGxV_ z|5Ph<;}Ke=tX#7_aFNvbr8}`?Mw-NwA1h;o!NA=OXR%!O+MIu`|7me^%bjrb{prrF z;mJMLVO2<`Si>bxh_|s}|8v!)l3NMi!}Eh1o786h_)5A+N~93qyLhMi}>6UN_t;*X9FXAKoXg4DMCGN-qg24`>cUt zB#?MZ+dq)w=XWad1}Hs`OWXH{ zy+0?wi#oSDTYYdn_%amigu)O-D*O7Yu%IOd+{O~@HIRcfFn?Z zWBxJsp}eSHwyB@8hF>BIpqF(9<^2SJ);(rVmm<)e#Y`)L81Sb)eZHC|OujgR2C^*d= ztT^D9Rx^{X-lrnB3;XOL#3qM~c5rV>Ntf?9aGhXUZ^uTr-H| z=bp){K(=@+(O5c(_J3q8@oUng%XsQJe<8B-ulVPmZ-PF!2TNJ{d385G7h0k~KG!(d zv&=i}@yWyjaiNHFN8I_}Bq9;iKE@FcS-SI{JH(VV)UzH=>BuzU?CBXgMB{rJ9oB}x zw#Ck6DPB<~0?4Ji*D_LZXd17Q+}jmZ;iK5wL7#i*#4msFRIcLl60h>4FJpP?5lb)| zRxHwSYJ?&*lcez>>Yc5YNy;HG`D5kpdb{H=CMzH}aI1@cZyXYUDz zClN(q@hlJ#=IPMF5rRbN5Hs4dMi}4?oc0GrQ~_HS^mQ=Nj`MAu82Z27G2NO2PPtzabHAVkUYZEr@QrQV_AA* ztZw<*bZm&oO)MQagf8-ngD#QdHwJ&GIMMG0zkjA45sO7|f?mNVX^|WDUfkU`^A1%# zSu8t^EDApHg_MbpQHl3@W0LX{@1U@EiW4`;UQ;0P-pYbZtWIt5u?U>XnF$oFCKq^4 z4EDSwI|s28ToacbF6_fk8KmX3RvkG;(;4KWsJu=%flOY@7_+f2sBBp?&f5S>6ZZsG zS~Piw_70C`8Y;1pN~hUrh+b3jM(+G5`)!3u1tGEM`JLHXcI|VH;W#TL6PuAt!3P)K z1J!%kfL8E6z~bY|Z?E{M>yW1Ht#j^+lgT~zezp~E04IdXTzwbuE4h9$S; z--@EQIyr?ie@~?SWYpnF`PUGS`iSF$H>x^* zpC_3V=&k8>6D zhjC>uGy+%|<2lZ3M8M3r5-yIKE7v-KiUCJ##WabaRjnGGPuI=Sc1-WCAjkk2jjB;T zBbMUjQTuck#`!{UBgr(w=3nn8g|9~9pQRK%`MzW&##n**c(T9g5hUx}@hbJ0YPr3l zc#-5%nOS!==@_rw!uN`vi+ABwn9hucMaNc?imJd?=ErgdbDNs@_G=f?H(e^$=7N2M zjC=W)5AV2E6FJ}iLNd%IeZT30ftj*cYDswQv$>+dI~J#A$CK12mv^S>R;xGFb7=D4 zAB3AXo(Odw(#UT%xoUiLs0Ikbs9z_pS7|7XBm8~3Gy@)+%b&=esmt%lnY|gPCo!sE zCAVE*7<93_U*8H1y4Ro~J{!i-%=}n@9A_C1gw|uY6N8V;>RqRY07x)KpP$AfLewkw z+J*hI@@Y$u1tTL-ljpyUGh2}F#Mh<=*qmZLCH309CJUWk7ilJL8U92{zZc%7336;H zq)%>}7fAhZH@|&$|Ig1QK3>lF z6FZ_^wPkg{H!4!QB|GU~6UqU{2voUC)P;EQZt6x4R$^bj8hj5(m?BdoZio`N6*=4D zTIq`7X>phMBtiMP7`0NC;-gqr1JN|Cut`&-#PmNMNfqqTC%=D`%c}X4WNxm-@wyR4 zzb8&0VpR_S+K(?tgTxZj8M6 zq|=#J9Gl2?`wvoAq2OP~U5*IYbSP>E9x4V?*-`v^sCKQa=4!me%94TK;7mN89LV&6 z7Za1p4*)s97N-3}zq}FPi1%tqKR#?~aJ+3^xM08jv^WK}Sh~h0t$lwJfHE;~V{$Vp+H#k`q11f3ejB^Fi zs|;W7fdwa)AfmysG$hA>ycHXiYZA=Nb!#<8D(L1Fy_x6HFJkvv~c> ze<(eCJsBfao>a`lM*1eN>-+hsKblEb2un-G!sJN9!u$mGP88qKh>|_59R>l4;{`01 zSyMPvaEfsVa)a6?w#K=5{m^IA(P74Ka;9IgzX6eb$|+%^lEIT-Q+`70z4q#c=?)Ls zE<&E0$~A6FlTYNknc`h@eqF6Zp#xDOpW*={mw+K2pmzq#>C8-W1;`74KtyO2MyGhF zGz%!zzZPr(_-j~#{NY#1u3)xHA9dgRmc@H3tXMjsHC{9E^uiKi6kLV-sE@|%sVcEG zc37P7<7Zo&z@`*D09Kp`9aA9(4R0kfj1qm-4yhC1$R894%t)e3S0|e*MtcVRNTZK;Fg!9}%pk-I`IhRNpp*os*6(m(DD#kDWn!bF1kc57J zpuFTsrWK0e&72CYX9mf`*DI{bo^YC*l3AE$Sbx_)A9&1PC()hY@l?i9j*Y&gp@+^a zslXWc%%6-MyUfbzkCpk!ME>h07mfpBAYj2QWy*Jx35pV>1d$ktd&sHOD2Z}d*OrFn zyDz!95@o`5+d78xAcQ|9BdTHBm|t$XT(PA@o_Q;_^x4;H--k60BoAP7s8Orq1g@W! zH1gM~tlc*-rL(?rGE^Dur4O9_i?IfLT$K!HS5sti#zZ$$wUK`Jx%X*26Gv^9^n5f(|MVQgPr7}Te|zS?lAK7{jZxF>0XG?5r(pJ z313O3|FA1Twzq_oAX;XSL+D8H%!NKOU1nJPO#qgof7UW!P~uWFMWYujz-k5lkSCI2 zDF6c4u=pZEM+l9=vNy!(BP_Rt!sxJz2+Iwq6w}G9cQhlH`H9{Xvjz2I3DT&GNjNkr z9Z$bD7QP=9+WDK?8aEcI-QdzSC9alP{0wR;R&XjLs5Hzm71yUU}GODLnJ)&Zb)7N4AY*d zTVM^u=!p)EG$I_DxY~2LR#Eoup@1%&`jff%t^~YU+RZ5Cmdb@1GmAC!R5AFH*%DTdDaPz$VA(%C}Ib= zvZu_)^I1=p=}+)rTR$0~)JBD*JLSscW=y1=NYkrqFlipgeMW(62%dgvsaZU0I)qz* zl>2EcyIzcZu|3ZhdtO3TvC??3ULTVdhB<%b%UWj7S)5fnyD^{hmrtbyUHwXN5TT6~ z)MX5#tQyND7`Vh-ImPpEuZTviSV7U0lel8ImWzbS>X$RnOfii8r#+c_8F|#I>Kdp4 zRGw?5es_xj0F-@?P`*`VqTC$vDz4Uhz(5Ibr)W^!nbQ((MBB|SMe{-`wczDH2oHs8 zmYKS=cfabb#fYV@mvJT1;pF{LZUK}c!NW9}>I7!G;Sbj&FF0%jz7@FTYs;Z>sPeUo z)=-7FnBu^l+8D{XSb6}>&Pk!SQGVvQZv1rRKvGR3dC)R>(1j!xbg-&tGRtlskIl$W zqGmIG=Bju-V8&fxVuMHKtJs{K8=n$ED?payctEck|D3mdn_y6>j;ZdJn-MZN@(Is)5t+*-XHB=e3=^Dg)M zxpe`AxE|W#hUB;)zWuIRhdR2c=+w~k}4=vgcqmPZHaZZyZCx(uDZ3q>d}x7$@}`}QdX zr~8v`q831RYh&)xQE*Hq4=a>=%2jFXK$p#hoyR0z4SGR}Ri<_*5}5q!2a{ z3_ZA)ph}rnLZi0|rwq9AgzG>p+50l))e;RnGZWPC3N4WeURqU~T6FG@XXE}fvU0UM z{IlM$edhY8p(=iGSY5`HY?LP@W+P>uSB(l}1w~LwyjC*P65`HfNCAHFjC*SW)`c8@mlO9qsJ`zuyS<4jdm!hMi` zyqL(IHWkWHAof!?x3xdOIF6x2)@B*(l_qPjoyCd}>%F76Gc|wbF?iQ_&sn&rPZ)ny zBv~Nx*&1yv?}vB8qtBp0I{a$*C_`S=qh%;)ZEwQe6)aL#ELVpm9U?H&KN9pA7#7Sx z2^wQvP|rBzocHr7T#3w*I79XyMAT`;)eU!VyKD;>m+w<;uZD8JuJuJtxeHjF;nYMV zUN4dg{xpgENjjw5zjTxDyzv&K57ToM(?$;F`_`e{#w=Mi2OoYfr z7$vC&_^XRL?wW{zj>O!zInh+(eN@EN5Zf{{Dl{Q8JDySl-X^z}$)Pj@u0kGr1SdK+ zw-E7_id*6xsBs^1VN*?fYOpR!&quOu88QEdirzv_He4)d=gkHx2; z<$wtb5f`CaMklP0C=n_0g+na1}avyCM@< zu59#7Z=kUk{Rzbf^%{sExUH8^E%2sU>>;VY=k!UnU4Bj4q99kI(ebmPCsJ8#W1jSs zph|4~!*`p?T^^J#tdsPhd#hr2QM#Z%|UBPxF~IgA`4w-h8@~s?Qj{ zJR25Mwn(D;dg8Ef0_yXwvN0x*NML%d4)hxEq0kZ^L`Z%#X#3*={^a6WW~+$44>|}x z{)i4R@T}&4S@ufoq@sU72~{IiBZ{L*k$xh`eLg7Sd1CD!sAT44)acIWj|!7J)sPqw zQxLtw8pPGMYsLG3R;1=FVYAY6KIvo6t&Kut2oPLV>4@9`fnp|# zWdY;eeto=~XS~uu*1)8wS%!5`^PRVT*0tUrN!J^T`jxUFW}4>=r|Zh^16lz+u_YlJ zPVxPXID8R*(ZBbt4<)R7j~(kv8%v5OrIk%$n7IECvP`V(iKT#XEz0&?)ZCceqIo_h?OfLkjcv z5<;MK(c(%^qg&a&-zgSKG2W;4txVkz+UwdZ`tgF|y`-9ziWHKCxEZAucI!!l$!|UB z<^=(2Y39;ne}~k^htmO}AdmsI4c6rXF;wPYC z6(i{yC$JQws-}A9@*=`viJspng7UY?+vA5>q?Q5_QEH-&eo(^RKBlKF4`JsTXHd}y z;f1D4g2$oppJHVrAOgq=)u*a%_WhDpVTpz~XJRvLJ0BT~>kCzXDc7{&g^SQwBfvtn zO`A$elvd2v;p|*Xi0@;2&Hy_(y1++KjeZG3oeq+~s{T=cDz4pA6#z$7lVz%AqQVL? zSg+z?){(*;o=>^Fg+CuEHf!Zek-Q4Y;}6rPYcND!Bxap+O1|WBgc9@)1iY4g4naSM zTr~=za?(RzB#yptF)sQXGIX-m1Wbw*)@kU4KKy*yyfMhdA^6mKI|zryLIEz-=8xeu z(Lr^TEwE1nOUrfx815 zD?O9b9MU%ac;Fv5MabSMIZfoe)*d8UqY$v*iOr=|8l#jM_ajpLNO8J}fO!8oRaKf_ zebnhUNC4E&I7VxTUwVB>2+(@;+|btpcyT(+n26A2#%{q`>j zCQo=@FmQgY$5AO)8B^M;hq>lAML8s85UOh#S-*9IRG2ej4Q<=*FAb+W(9)-TAM(Vk z*T(3978uh>F#vjdXkSA@!Y{BF==O0ijg=!_p`b|%smSj!+j-^rX+%#_SjYxstt6R< zF`_wR+~`e(!B=;)gYfEdy1 z2q#XUb3&;3=ev6IYfwq*AaxXC4d8ACQJDmBKmm8QQP&5#Y`ENkR`%$73gfTasnG}8 zQ$w`+ayWASBh)pb28i3%M09%>){5X&<#P~1vcFWvv0oz8^ND(FH0V_FCv{&Dkb62) zack4>RU+b7#CU~S8OSwg-I%8J(uJ-PUxc*}ntRM$M0Lij* z>BX{&B>lxnDhVY%1x{)NXpzi`qZ)PNXtMR=$>mS9DyaKXPR&>723j!{43qQ*ysM zR|zH*JSY&wr*~<;J8bKhK|o87@1?3il^Oz; z&v4XYq3U<~_zfOWojb^xrw>TlC#v(JDZe7)sGM{@ep-1Vs8LC!@(kt3i_Ut`u9cx2 zWBF_B@-F?5&rJtvJ&)s5Ks1^aLSK&hL$6^1ct>sDA)WX46AtBmR`+~PC3Vfd> zu@}3Sl2yH~WJs*3*YI_XeZbvORivNrs6KmW_Dxar2LoHarr1*1#v(4l+wQl<$^5`q zs(fcsJ_Yyu-M0O1`K}%%5{1%+8L8y`K}lOS`C+z~1{;SrUiS_Axfu7i-AJG zEVf_t_ha#PQVT7m8{1P@c+g! z)z}8ry$^Q6oJgiRYFpj}?ruida}L_2tg+ty%9g2ocj#f+&dZE*iGix zqq$)g?+;ks-#>oqP_o>B;Fj2Wn|v7Yr!S zwL8enYwtuc2uQA9sDF(xn@)*BB6H6+qdyD}7_uv`%oCTiuFaxTejZR2MqId8Hn z1RrkePCH`d&q0-vE!+Cj4G9i2pjUU#w+%52II|McoGNw69b?O6c*wBs?O`IIfcIKG zz_k>qdo-+g(U`)3h{Ic5Dn${*q}`=*CEvdE)QbEvnZ&?Nf}0z$k(SjliyIJSkkrzo zB>adN&CK28^pN}aPIqIUq5;#jA#AOowA77giF=LlLX+%_GyqCaN*U1rM%B7X*6^QyFly&^r^OWy`_|!6%_eEMmC* z9^w5qUYTj@;B%R5_@t9xWSMz_A$$d~8W1ONuewID0ZJ|G#8B_=3@-%{=TXOzZ_)wE zbjY+u3a6ng^azE8$e0cVlp%kxl$%H|dxYzI2t;j2z88S-y{7@H5F?NhPzph&3~%3L zhGzK_O3v{T62{SkL_^vQ!Pf<<-a=ZTy3~er4g)Zg1m#DGj$~#CWrF%JO=40pTj8}; za@7Vk%6}hS%LbQN*No2g@v#;!ff!`}gAs-Mpjg3|*1YPsAy5OroqU(GQF`fwUe<2K ztOq*bo9scy`DsB^VHL-`e}qR55!42jFpR%PHEt;WZI$G&vZf$H_B04?2R1)_Lhz|6 zX@SUR;^XcHSq)TKw%_k{dTjUUqM*(8-Nt-ji;>m?Zq)FU*>1j$M=7j1 z7@o{3F|8B-?kr_q%0dR+xVHUjejn@11qQl1yyssBj*cYoGjAV_f`M3grr%zO2}TMaGF{C*^q5=iu~B!A{5 zM4nUiJ|dp{i+kn=ZPWNuI|2H39~@Cy%q?PXc4Q}nm zMr62-BO;{)`bhs1nd7;TjOYk32}YDox6vV?@t?o*nGPBKlhXOrC3?vWd>>&J|J0+d18H^=D2Hm0{zy9fj!z*WD(3!i|WB_wg22Gy`vnlw7P=LkG1BfWa zJ0K^2AHZuM$`-KleUJ>9#2!577)&Tes2<4qH=R@ZnAvoKjm_gf#4^f>ollIl!;ck% z;DPtj>8W1C^>3mLNJ%J|qBB{49CP1xnawf-ZhCpJ0Qd2+xaSFlpGpu5iYK%m`V+lp zBg*^0gbfqOt69Mizt1}}ykMWo_dL+OsENi6eElquBNVK)(REIF}+X(f%}jp0S2oqY~(=#?^s>e4`rCQ}9Ax-Cls&52zx}l$|@3t~*FV zADp`8xh)`}>eZ~lEP;9%E4!JhiP;4zw^$QUTGU@v^+g4ZkGcI*5rt=5#E#D@(G(n1 zs;0a;{Gy68V#4y-r}!w^2$k;6Y`MnlMT2YweP=@JW_5KH*dmhVbFzYsg1ead-@;u!$Nenjk zGBo9Q%lW~~%oOYyH@vpgOizDq_Bz;r=dD561YQI??GdTP_c$$F>^U2h+EP~qDKFp} z{*ZzCp)vDq7|ukq&e%fwHO~!(VnNs1g<7vG!{XmGXR3s@F(v2lQI8+OsWovI-f2=kcT@A#Z6GmS3OOs4pj8e0d*n-t9*;4Ca>upgp7S4&^ViC{LDQ&$Ds>f=GN zSvy=t;L)fOAx#lkQPeTo1V@SFZ4V6FEKKt*crBXkl_}w+6r;tk1|-dn6JK8b*x+wg zChue?E7pHBPr3RH(v>ALezSeaes(eaWI)EQr#+FVL+7JaI=X}!zVbg{G#hOLIxve^ ze7muI?=saxERFm-yF{ivN52vIdDe*4Q^W7+mZ4VXIZ0PA+K7I7ASg?=HCa#sNY(!7 zYsF?(EU70LKvs}WN$+85onaSJN(z8+kt>m&^q8qow}2%BtZ*!uisimhnt5A3K}b$V z!D8oc9Xr{;ge6TJh_SrA;6aDq-Dx^uI=1p0zgFw#7}C~Z?5X<4@Wo!y`NXubof(due$Q_8_m6)jhV z*IZHW30>;r=~kY0|06K-U5=65Dq6}j@m=-mRk{A7ilFRLzY&PgHy)bW*Dfao^$!Vq z3_OQ&MeE*`#D~{yc08x0c*$t;5;vkorjlGe_>5|R9%#**Q%pkQ{|}lO&Q^Q)y^?>9 zefHce?NB1=PxTLmCf4V5pR#H=67ibZ%1@B>GwG;X3e#e(9t2SQWFx6vqUmztZ#jE>G`UJOZF$z)7xSD71Pz~;$>Gk>J!Qkw zw3bjCc0{p6^QqJOw@)7#ig0Ip0Ttkv!w;Cp*5{~S>0eN4~xth$xiWb<38D z7=9Ho!4o$?Iv7c<~9oW0NmRNxlq`NZB z1Yw;9;p^;6WMO`>WwlMXQum5~Kpw4oTXgi(4D}!Mh8K~?R zKb~nX$u?2QOM^y7g1;?XcRrHn`u4tyKe8oOq7$!|^My#-toqSR(qFrS8s{{~H7$yI{x;0(R&#+y0pJ z7d?ZdXZS_?9W6fZi{Jij<(GG;`qouJSP$y0ZqTVgu#+8>ggkhH{ID~us`JAM3U*{G z=T)w3>}pr;hrC%LJXj}eC8StbCa&(KF|l0`ZInTT^B~a!iegbSw*YA5x9^dq+e2?r zx<7x#HR}M@Crs3$*m><=uIw1kk+$)(^_~6!w2F7-lCwWI!01_eyAE zmVV!eLplw3%X#oN@}6y9RR%1+x0bV4vFg0UbdD2s0a;zc)ZK-Q#B0jr#4+DV2ut+t zd7mK5sX)uPSo>v{{Ng%Awp26TgtvQ@iZRPJYll&bhmYD!U9sl1*k7E(#N@zz;=@3J z!GT+Fa~a9|8ksCGXHZFe07~Ax+3Ek=p+70@XT+1AO?t2WkWz9{m8GpQs>VTMq7*Z6 z%bK4({d`S4Iq1kD);AI2H%YiZ`QhGIB~~%5CHe>z){y$s_@dfdu(KhI2Z7Q*EcUi0 zJIB$jmA&6NO*#+1M7+Mj? zV?PCzkoe~vnb*kL3i|(%ohXbt^wK-I-!!PFZ=ZMcN-sBZa?fn+y zYz76N`#-|g;!h1SZiUyco`Ao%c>j18DNj>7(Pm3RxH|%?Op*>t1*-m1`&;x`5YYN+ z(Kgx+(7*4F6c86$%Xnol`$J6j?Z&4!$IBB#W~mFQfYHY0zSc$#L=RV<$ydcJ5)v zivy{Nk8Xb&q(|;rG-$*UX|9`45mdXHer_b{PYO*kRJr^JgZAZ|M1mNzYC|UWqAGC zD=2iHXAstM@Zo`LTh#h?+?!lShWq?%qKS-f2F?u=_mi)+>QgwKzk9wjU)HKDyXM2E zTYpB`^1l+n`&+GY|4f`%SA8r1qB5;==4rYsQgtZlpyWH+aY_zB0D`fQ`)ARz%A-3wiwFG#*dP@3F zn?a00GUTX18sV^@SXs@{fDst3aASn)J?F`!25X(!lt9HoS)9ySnI0ZH7jlTnlsCPx zdTPIuVp!_8x8U4dpdg}7>p}V1_xtsNCiC~GYg=yhQ`2NEkc=pdk!h5_wJU(}PyRQ{ zj7W}U_qTQ#Kd{0RVVXQjFzHGBoG)oe_I(jeCca+X%hX6**6)t)7msh+N`;w!wy!Q$ zPK58$^081%UyA)fiwPzK$1(+NEq&cm`g6l|cP{?sBXWK%Q_q!Oj}^kZ+GYv3bKZ~uCF@GD9uh_PosQiuTCRq_%>5cp=t zvmEt|kp=$IZGch3*a}X?P9BdPy1pmMqak6ZtiguFrSy7|iUqDvl~@gkSL>y`Jt+aV zNF+0;bTzg5u6@W94KM%J@;*N47;mJ;?L?I}jM6|~nq{!N@sd9NFwUZLmO|z8+F16~BsQr@;v+9eO=c3` zaEGdjq2j(dEyGu=O=Fej{vFp$hPG`eggrV_1$>*moUAafv+An0U>-BC|Bxf-n8QQ| zD@PFDhebT7n=`n&m~Q=}UuA2zc#rJwOnV4nWhavs=)Z9T-ZeSVLN*(`kF#0eGi;%q zwvJt!$zXD8Wb%2wNuzd!E7H+zG-hBU_4l`0r`9mcjJFE`k>x;YNZX2l51HX^UokNk z8=hR1!(T$%HSW;Xks(3R$d5m^C`jJnE?jG+KnUVa&T`)O9|g4KZ9gB{Q+BdndGD(5 z+fB{3Byd?J5RnDO%6N{wUz2j;}~Q+K89a@4H*|%+HuwVEGk6Xgx+(rc}C7t~ccO7gNLM1ZYB-9hiE9 zs8t{1_5NTqLTqYi%Fi}OHMgj0#UVT&gYl;zQeR7VW0qXVAl7PfG5UMKFwL*LEeFFC zG=!LjAX0xLOqr&@Hp}MUpMOY~t#6!?EGq{H!35IE!*&NjSpt(g?ryL7p&f)5r{dO|JG|S^PW*?F_D$K#bkhqUN-eKYByq& z{#PiY;WdT}9!W4AHuMrFz37EOLB0w}ON}!MomLXi0#b=q6QV5Jsiz9Nmbeb}{(pq} z@Ij)hut9{tvPZB|uZ^~Qd87B_zO@NGNcojNPkrUxj+siv{O>t(-ps^B zi)NQ@q{t`AtyIU_O}pK@zpoa#qRCI2QkRoP*dg@fq>r^?iSETcb|l6Kjqbh}t6>!g z%BykoJ)s@-J-oiRo|pKTDF$BcKT^TIaxlN(MhDxF-xXAP^ueL~Bul7v|D}+USD^|L zCZfqnkvUaR_>Of*x_h^xD`I0ca&^B_Lh%9a`pr8s@SlbO)V%XSPXp?hS3uv zjUxVsxV>$~aA?JF-4ao^lc$a`{G&0n*qA$WF`}L^!o0DPGBFaKv9kFXnX1^kTY$n= ztSmfE(Gvm+i!#te^KU4^^3mW%G@cUy?t%=Pj&JT6Z}~rDr|oFGr4>xf9d5^);G&h_ z=9%DuP4KEpcrcpavz6cnPYmEq4AM$;#=6TPPA2ZjTujOqmLHy!VHK05mBe|gcD7?~)lT{Rm{hB{jl4vy_CzY0$Y~e=Gs2O6 zgGE%fML+%)en$PI2^+B{eYZ59)jY(F-=A>7h-?)gl1^`}p7pe6pFGKN5|jO}%;*y##;KBE=Kz?g2DFoBi<>Zvjmd5qKH2 z*Gs5U3~fe}l9KozY$+L7pTO;rlf3h!=copBG*G|JD%rj{CQa7#a z!@^i|6TF^rhyCsafMPsWQ#{AUd_r0*89et1pR4Pmf)Jj9j;myb*Uz)~9v8f3V%H4(;~2;b16To) zu3{Q62EL782Y}ld85kgvWBw?|`uhXh?}3tD&+jBW@BaS$*Jfn1XTeHG7Fo%okL1Cs zmch|9;3(4_Un&_^O<5CXu}Bg8W__@`GfF1~ne zEVtoR?$%gw^TP~iW6?#)11DsBhB*G`BhvjPB62>&M^Cc#qo*;NVF|wxg|uZU;$2y!zB!YfXA3ZHURn7)%SuP(FIDcc;Yu&b_E->#V8sU)&4u9VC$Z7B=BU+J+^ zOtkZ`qDPMsM1q85wCJKmC!-U+MG1)>Bt(lI zz1LA9f+UDe1Q9_n?|iT8ey-p1p(+dj|ue#I1LvL{0#3(7Y-rUdo0_~PpX-qZ<>)(P*{5r9r{ z!FrZ>Mm26q$@qHtH}wjm^-8<-DkKd&3U9e;!T18AW8!yVaScBz8}wdO8|*f$6XV|- zGglMT&SmHKW^bx2-n^e5dB1lLa$hV>%?FSa1JnL}XBF1ya=*rzKz5SU{6lvB&AhzX zb2GkU`%TC0XvdG;j-Mo*hk~8I^g4gPpp~g1UN)lm>VZcJpV1Or z%Mxw6G%>Qn0`f*QQF39t8waGOi~Kj1>|PBW2^M+2OO}D=y9Uhz6a!C$$nwT-=T~6#=6;DQEYYj7_Dx)gl_O5xQf79){yWDp(>Zje%FvU zi4j4&!RrSU++rweRkA82e*8cM@zshA0KrC0P<%F?5+pNH(cJ$ z?y(6W6c>&p08L~?z%4PfpDl+V|H3V0h3xuV$A&J3|BYMTC?IYWLOlauGFWJn7`cEf zsxgJcKnSHMM)6XWD4~F0F;njaj}4Oo2SSs_u9MetCjTx?{u{Sc#y}m=C<5yVswfia z#_eC=4izVV2anQJOCV;gu=161M@f%Gb7lp zQ5K+zgC*jKFR6Hb;Blz@Y3j=vHDOc?K#ajbLRBde#Bk6M95PXW09-!g2$^*Vai0R? z0hrrLDvX|vfLkVqk-QN@H2@@b#zO?$GP!2_#3=u+@dQ!WyYuU`5yFu50-}|I3BkLc z{PI7kVH##%lgD9DcMm9ff+xE$nTDi5UJ4n6lB5lwP8LS_lL2W}L>X?Mp<$nU+QG*K zRM6VAtG{WbZl7MWeooJSmKpLn#~_V2F74WIn#kEJ5$gp2yHGj40P%#b1CS_7*k4@Y zHG=GgTqrVF5KUbg9bbemFM40K*KF30Q9wH9AK(#R&PrwgIUX9I% z%Pd1fm)CsLa>;--lt0l5=+yz)l^)Ti5kz(8^F)DD3_w9*unbFD22iUIwN8lkv@+ENXciyB`;g$@8vkYUWeABqK&n;_gq2J}n*Lgxg3n?(b zXebLq2I+?2u}}c`4&nGNwZD$OTH_Mguyfy7S3=c@CA+hImwdpd0#Ja+Y4yvoq(gLY zEXgE}&ch0Ciu`DLx!d-2x07v;Gc+rp zB@1l4Ulp(~O8KMlivHvN{(LoYi`7si_6Ohr!sF~mlu_eXd&0FpXZC-7QtksM@7Qh5 z5>M_;gtEWrs`VlLN49KnqmAB=jP0N+N0FL&J-MQyUGHbL#chzlyB^MXk#oYZR`wCAWFQIc{UTrBPtzsxHfCwXY?7V`k zMWaMSPz)3RDW1w8`PX$(l(EY1J5PUGbpHMaw_KhTuAv|f`FW7~Q^fk@)~gefcNC_N ze=qKx%oflUTjajZ$$jIrzx996sB{2*dVuWQvwe3M`1qFt#qUsx zQ$Y3X`MXWM8uAP=l+CS^lPRz|@VA!Y?-euT%K>qy0`1{tjH@T{S{KAkEsw{~>xz_a z6@By!L++wR{y-R&;jvV8)lIs;Ec|qS{RhzKK_=Aoi+vBlXXf=6MQ+`A0a>{q5(f(d zfP)okM%R6=hJw3^g3AvXO1_ERr~3X4e=+&=YWwj3r27g0P%&5IfRUILC-BadmI%G^ zjX0V>c9smKuy93ZG-|R;5wOeK)Eort5-@IsK(%*tn`;WxV`=Rt+Os{mdXw1I!&hHV zZgz%r0hV zB|I1Y-qYR&>QP|H-4eh@E@w|3`=E`bK^Y=9+8^CYNzA+Ht5WewJkpDV9u+6X?OrjvB24v{GrjE;t zFueZdX2MO_liaA-z;Ou_9b5K$@GkhI?t>TfVz`mtPNu5VKa?2TFvyc z0hT|SJ5E`fhrma-KIQpJh2?2 z15LEd;11b@6oU!5qU#jCXZF)<|KOd>9B_6|u?o3p%jxbI7IWux{%Ktj;^N$(cE)V! z9G=8X3+C0nX3=qX$$eD*cp_l)&Bz!w{t(fy!U0CxRQfDaBe#iq?3C0-p`y@F!av*DzYW2^j=-X?NaNxVDAZq zKNsFOb@~vWX+7CXpV`}HAy4M+`&~Ynx6KOiU2ti-^j-4)6yoUcEz@0ZuSAl!=pF)H7+x}by9rV&a4L%x`#RnhHm^}?SS@gq) zoIddr4n5y(!iQe`dOeg@#1Ia;aS1iTLbx%YH-jn=UZXG)I}AkH575OHvwiADCdg#hHD6HPXfH+*VQe!OwzF~xqQCKSk z@fDIu90RBmpttFO&_Tad$igz#qs&i9q}s>FNw=jTW4=~QeFcfth#im$J%kGRLujF& zBjoqHA{1)AQz-q5>>M~Wz_2~Q3|+GUVGVR*Rahc5MHx)`-b55F7w<8M?fc^@?(qGt8 z^j&~rg3k;*qHpKH|6-Lc#8M3`BRH~`i`hxQI&u0pk|$phsY<=JkaD5xW65A}P`Nz2 zgT9W_vu z9tcX9X{n&SfF2wd>$a@U+Q!cbh-9m2UPR~v2j~eCrc@-ZhZQeosQr_1+9i$B=?5^t zdhgt{Ti{K5bI{olyS69QRzd3s79EAgj?_&>Y4X z`1tt$AS-`pX>#r6*;lI4X z&!_%RWF-!VpL&j;@FS3w3;!W2ySwpCP58ch_;z>v2Mv6S9R9uV|6i}NrMbDWvGKo= zl{fw&D=RDURdV<$I(#MN|C_A*Th7z-_St{P%8H7L|E*RQ7UFYr@#*RKl#r^z{6fNO zbo4)DrN2Ag%WEY#xS*im)vH(ku`6?Oa-Khb{@?k^q@<+y`1sh^*y!l!$jHdBu&}33 zpN58p1_uWR1qB5J1o-*+`TF{LdwY9&dU|+x;N9Ht4i0!58@!bj-pmYdY=FOc6R)mv zXm(}wZLU=ANJQE|HnhH-!iig4QVDJeeor;RefA=b7Wo2b#WTd2|#Kpx$MMXtK zM1+Kd1O){J1O)i__;`7Fd3boZxVShtIM8S`J3BiY8yhPtD+>z?Gcz+26B8pNBRxGm z9UUDlEiDZV4HXp?B_$;ag`%LKASWj$B_$;xAz_0+h>3}jNF)M*fWzT17z_%95)lzW zAP_JZ3<81h08j_~^AIW%KnNC{nu6{K1U0c;LH|HP42tV!o=$C1e>{Vv^U_dl@nAAq z{TYjHUCD4d|Lsa5Cv_4?l$h;Eo^E~F_zN)E7z1U||2J9r-uWY?BUlc zfzktWY#$b4_1hYM+;b#@RF|3TQ0gX>DmDKXS^0}TQnXXq`*Q0eJvsz3VO9_XZ_FwPUs`V} zxUs`Slw@Ab5E&zLVtG3{^z3kOB?cYMzZ%Or;PCA!xlHW0i0`$Cm+@b^%kvW?EB)CM zi8N!4NW_l$2UIXLvr)0jTuj!sepHla;N!=OdnkeXPbX zM&9S(G~M(hvD)cz0QzNmRCTJIbNz|wgwtle|AxF({=S7g4opLIZL1)XjzCt%gklEZ zu`)Yb#j)2$_zOuG9Lq}Qta7#!vuubluf-{~B5zTniNdaDF>ohwL!4|9U%o%YBX{36 z%sIbNt*hJI1jJD*yYISSf_pW6bb3T|1H5nc>Uud9TuEK)_;}rBwC+}6KG~2|HZ0!Y zzsrkQFT6zxTj?ECO)l`>eb`dHyWe);HNWp4dNL9YP1$%O3Z-xM=Wb3fXca58B8B=e2FQSE+KmE_X> zy04|X4|~`Y7D%VbXQp6`s3bn3sp&XXt2Omuf}d6Kitd{^?;&}}SnuONv<|}tM{Jlm6_72Y!`nBlYjp2dE>Gp7S65SccPCPn>JfUJ z7z9?MxtDaY04^eeMR+t6)5^a9_(#MkoHVA;nW}I_n-x5g3EUM8?(UV|sZGN8U~(}n zuVq*GYS|a23Mr!2y)JYF|Cxj_ToNW>#uXHbTnwZHbz|TpxdX9Aa_C5;_7(vM(P^YB zt#HdY+?+X!m5{I|#e#iDW?r5jzgGR?1W-wYJM`T^h@TphQioAsELTW&fC1rHOmq-8 zHBjpjO&_d^3TzFF*9nYHDt*lJrj-ST`55O`&^L zdl=~+aTBESjCUb1`fI6SzAwHIb&)?|n&nlnD6iuA?lSB&5ms{aN_O^NCa4JE#tk^A zBV1&zgkhSaWoattEi=j4BK`3#?Xg-uY8q<3E>QqCaJ+y; zXY7HZ1?_m3uaT^c0AxKX?Lhi6!JcH~9Rd%DBi~+yXWo1+$^L6cz~qHCba+df`c#p6 zuQ~Wb2{>xR+J9`X#RMbZhqZ7G(it#EO81;!P!kCX#%dcSX)(ci;0B*{7)3P#*}OE{$r zg{#5}klwRg3=ebr(d(7f<_J=!fNK2kg<8HP5rVzG5+?3w1K zi%)?OIl|1B!Q3fW;$|%A{Qn{=<-%yp!$`Kk<`@`Ja~R8f7~4N&WjLqYKV&7Ze>i`3 z__gM6q4{tjN4Sp|+$F_1Y&l%UKZ3Ivv8QcE;31XE`DCLgCdE)y0NMHAQ^?`df=|>% z+JR*;fi3h=Ce4BMW{x3?a_3(YDPYyPNJ2a}g@@G2ULcS5PF76~uZ7}-ud+}kvTT9$DzEVwUjA^a zXMQS{4r~Z9D8aRJ#!>X5QDSiF>H+VAjhK>C`C@+R#${gsO{|Xa^P+e0aquJ2ypH)5 z`@7gHl-_@#C|>lBpWF9%aW!w(f`9bClI6IrQyJ052=#%O($fSkuiN)hD6$S9!D1Ad zw~;?QV5T)BxA@}CwBx00ueO`+b>;{n72$%pdptQPTDho1qxoSj=<)N1-p4oW3O- zIPZT^p3IrUcj_p$WSSH-=(uLbPReauS*v64*b7+A=;5MRM}UGw{jB|LC@T zSm?3tW4PU5_~Y2{Q0mt25+g8SS3ngtheb+Er5Rc{h<$$ksW$0{9I6CI5$Tb2T<#r+ z%y`<8YfP0LFY7@e&#L*vR9Dm9;J2x<^qo6T?pVCPV@2x$DI}`nLG_$La&(g-88fK` z(({mPw2V-&7^)W?TJ|{y4zm5dp8K{XA6uA@l-C9kD!lOWFV`$yZUnqsl{W==?Gt74 z0HgZ^g{lP#w0(TqVUPNV%>i)8DKY9?UG1@!C+_mBQcmd*N?-^_p=p%w8jwHc`0(p+ zK2;z!K`;55h7oBbAgq1r=X_dI>Sz($@S9f$f8|= zqBurZh3EG7H|!tMJ+hK{B-uq_whTQNdo-ByyjItWjL98R$>Jf91^E|xM^u}+X`TF& zE<Bc4v0HcsbzL@Yy^O8%fzeZ&RZ$Qa-Y-Q!Ws=XUkn6*l0c~)4AM{G-Z;!Yf; ztS7DCKbU5teZ|mOrEF^juCn-(ae=G_3iFAmxV5-5JNLox>$!z@soj;Hze@C-uJ5*1 z`OTGC#MH-Pi1?;ei6ZzzPgHG>eK6FYoz9C6=fv+X zcRLeEx^kmCwgd&xiaimWJsA=W`>lE8uGGv2FzpwpnF<)4P+Mtk_p{M%IYks(d(Zx2 z*R_k@oO60>g+}}PC?Z19fmm;cVEw|P#p@Tn1lUM5uSdW-b&jP z4@iJ&sqT+TwKsMw_5GR~ZQIK#Zy)Kg9PT9@o71P3l84U|mtBW8?qEvS>IZBvY!EM$=_W*L{Snpqm2 zseU^y^x?VQmuacmDQ_%9#`;6RwdtlMTnp*PM=Vp@E0rRwI5W48PKh5SJmb94Gcwkl z58Y-q^lxwJ&&gWyI2wGsVfC?ZVa`>FTElHtQarcRV&<&WlBim&QUtg1EnGC^ncxg>Gwc@+wYjq`G&)_z;?^26Nv((LBNeBot8 zaaBv&kEX0IGi6ruax4AnmGgBWGln6HeJ+co z+?L*7&JN*~GFqzU+LQ>zsBQTz3!dY&v16Getll=`Szj-|a4~*$w_2DK{-Rbjt-%Vi zTp8XYnEFMdk50}Pgvf;mGHmrp+|uL&=b zK0y82E4C~glREh3Yq02FwM2L24O9NiRJ}N!zpQ5E@7ndvl5#>*v9(`mW!`i}@aq?b zi6v2yui_mmPcJ{Y^1}rV=ub$W{rIu=QwjCk_wm^ylq8G})2OU`^_`}A^_}hnd-bxm z`-0d5RNjj?tT-`&jWr5gMRNFPIQZyjqeN+lmZ8pf>(?zq4TRY?&O*M~yMIF}_nBbF zo)!{c;&E`dtIx10Uoj30dQ}$7B^PNc7YhNN^~xnlqV6n{o`{iWs-m)rIm8M#gUD}& zd|mnO_H|v@zYNyw(KT#I2@C>@ye~g6P=lEyQR!v@S$-%{BJvFsY05M9p<+d#OK}3C zGz|e}ZI$NLH90)U-xm-CsZwOiauedZx?ai;LU)2#?=gyOX&G*4D6jn{1DLy#UXd_7 zxB%iizFUJth{T`%_Ir9}hPr`6nB$;zDTEK6D(YD8xvkpY95ryQ8tWQj&&Ui|MlPUk zJeIKJmg4zFzHj@3{X5&2u!+M>!~HNrz!;NCgkqTg@zpnfx9x$hIzLJiK|O9na*8+B z(3VmoD%8*~d1gdo;{*db<{k*Gn-GC+bD(cCJgujH7t1WVvGH7^#`JMtd;y{Ht(3O_4ujCcb1MnZ}xW}pc&8n@AoM~Pn=J;Ci7tC!3yfKy02|cgF+GI)BYgwzm&!xUw_cjJxa>;s56}Hx5o*`Z ztG}JMAvQuNmcmm(lnS+t6i2bIP*;c)usn(KbDuA&Mm;Fl9|F4>W&W(+9Pk8nsfH6t z$K40IC>7uk1t(_zc=~RKcf=2fP=uo=bZTXjS-rk7|X zNf=L@`t|ba!JU})O+WwQGs?ITS0)vBY-du+lLIyqcSs`6(LZNoK5MAZsp9pVm}i>f zlDx}UZ1D@E?sfynDCh5voSf*Q+;kL}l6*JSC3413HXQjFsgr9%#;%oTerPk0Kq5O( zQSaGZoggUM@m9`zbv!obCPoq-H?DGNV*gt{$IChM;T?7!5?~CkvhbdV#M?}iDJT3+ z-e)ee3iM02KQ)=iv(w*R8{_#ZF)xF^kLbV0s}ZWOKDPR|JcvygYyY)!7(E)V#4d9= zR{|;+OHJ$Itq6@aqPX+ns%UrX(!ubLs457~UDK7Cp)Nq}IvZXX750FVk5s6@6V{&B zXZu6?GGpPOoILIvRbJwo4I!uYWh!Hr-tR?qrk_fts1n(h)M_z5rg70qm#Ek%`Y)bx zg|p<~If>_MZnt|TWxTe5RJ_IdSlc94Urrz=)C)s7O#1j7F2wS8##3K%QbW=pVT4;C zJz(sxjE)&Vd}pUZ5IdwL@gfRuabAIXKx%NF1|xMmg{G9Tx~R@~uqJzy)btI;C#EKP zqWKNR`m!G~Obk_`W^Ws5D`iY0O0pru2puJ61Bw$B5hG8}qa8%^p6D zN-|3w>MDLF{t~$fQQjAD%)NEJa-vmpx}fo%%e#J=`)*C^jrSjSLjMo4@}s70lFYt2 z{i6E00PlmKpFez4EyLXO%|r1}x#i*up14RqI*Z274&tjbw^W^?=I_R;W%}C~3N|v_ zPLOQ$u}!i!fWRv}PUk^4&IL40lJ)NTtZRGH-d^rSJa2jQ;_>rp-mJ3ik_iR)$jlJQ z2cOzn{)g8WN=xqF%YCi7ko`Tj7;mz@Ns*TOKtO}R^X{`p)txW}%scfXY`#utyDgd{ zmgb%WS!W*UZo#rluKVcT15)tyW%Xr#+jHwx=XPo4rJn5GuTHLg^bW!L{i5LYc;;4w z7AyQAQoG0DWi9T<1@RwJpCb*~WS?VwiugWR8M$i_q36S@2Sq<$=9g44Ki&3R^4rYU z2X5E(=LHSb_Q!-Z*gCLTVYb>eH{(LDek@QIPv0zkdu>2q_VZ$BXGqXvUB81tzNg}c z_Sa3$w^UxetlyUpW-mvSW!sV=GMGx(O&cDo9ABxmTAk^8DTC;6*tox6Y^Dc0e)kK9 zq5}(JIT_LcIcxIU&AoVYuV?sB((tEb$0L8pPucSmagltk#31WBRk-tkkBI3cQ4Y5{ z-xQALI-wiH2-BO4DrPr0MIYbex$zO2FFLpwHQ3Am#ZeH03ySX4aB9KQj1ygM zF0(`B2|AdBxO*QdT~3+KOEC$Tq`Vh2ZZ>K%g#T1ip>e0v`JPN7qeNG3JAOv^2uEO2 zy4T)!mfJZDECU=+NTH3uxf&wfsFqN*Y{#T4aPxteTNXxQoq8o(M>i0Wc1LJKPi8r~ zoHFv6vgH(S)b^m!6}~R(6HT_XI>VS;sbRpMMN;vUOGsRigmq4pZbFRyzp6RbA1T~&nmm{P2=Yaj-|jXpLU$QevfoRw2aa)tbkWK z<%So{Z+QU&GQN?l#@TWS32qyd#qGlLcNN9GPP)XXD0z)SfFbq%vmyb5&<_66SNc1~ z{m%78fp!)9@jJ9Ll~U;v#}yJtM`rVwJKAij`IcUSTI%LnnbA+)K82cFD0tm{z4QJJ z^T#b?#haN)nDIOKAu)#se{ybhgujo(_Pb&(uhI3~_+2G>;Y#|6IL%&WhRb|cT_yT( z0%t>1q)X%a$o@_Cd|>hmNogT>zR}q#Zfu^JQWY23RI+i6OcPgtFqMnK{f%h*7NTv} zZLP(jZRNVwRM#Ij`E_y07z5hNtq4y)g;{6!#+J>}DQ`HH6^@O*>T}e$CnVD&X5l4H z7CYLMeS){wLhod4Xgfpl50K!W*;G0{8VWn!+61^4X2{Xbmg^I>HbzgrEP3$P^>#q;p57Kmi?(9)Fi z+*bUul2+8Oe1+HXir2v~$)2goC=(~Wp1)ho+1x`6BaU0ff_0t`5UDN9N>^tCG zc{%ICxMU}+dPwMV6YNqHI`7P|U z(3!h`l$FyFRod{NyF^v$($`z*L6h=P3y#%QX%I)<&c#q~-He2u#}PpTt0I452CIGs z#}k1}6K{OO&*i5L8U`*$84S1IGJhQ8!tiYq_PfJd=rE=4Ni|$W*V&Bh@vVrsF-im9 zUQLm-n5Kn#8d0ecr5g`-N7i1SbXSi&yzrclCPW>6>I}yu+Q+_FT;r->%eN&@r*V4m zUGdMg@k|%*JlPQR^-Y(d?E9h(7G-;*y`d$ns z|Mr)1KzO#&k1&<9Pq(Y7lJC8!aw?@5i+S)ToPQ~j^!0_gaI(*sw&ky}ySh#vFVC`7 zB@f@dI{R|F6aQCo|3jQhQs9OzMbMHUaOdt5U(=bEiA4&PKm8ja$0P!0HOC=?Q)M5< z-X&9^DQG?!YnI=5@zcLe{o#4r!w<{%J5QF|zH)O<7gjw?8`iw~Fw%F@_;V7!c}()^ z;)P$w4@o3VECl{nIa@5sqEdxb@`Lnr=cPjZm3Jqes{>G!5}3x~Jfw_+;%rU}p|c$@ zMf7Y$S74gziMqm^iwezg?9&JeXmeMV2dfxZZAq}Ernm_%q{gJ6R#~jt+1tTHgG8qb zg6!gW3$pg=)hMOVR7>3tcDm#0yBTJcudyIc--rs@#ih$bc}P`xh0uJ#H@?`C?#}eE zOWlxC?8PVRgn?;VrS*}OwM-lu>S8o#ahBeT;*KgYb@IF$Dh;Zt7qO(S4cdCW8O@Si zhdtLL+jAFt6*J!R=SlpHkdmg+82crBnvzUx8ixqNYFc)7JNK0aY3R&K=@O~xWpt`o zY9?s`r~)s9ii-PD4gE|Nkx%*KX&s~7%Hf`lQIu$ea95%)024&VipRqIjbbc4 zn8gaBgSMhIhH~uNTdatBuC@0)U>OL7$7~4S|J(2p^6$&4Ffc$ zonc}fl~m1GMdTZlicy2^)`Aw~5O7CD%r_$xo8d43D|8ye#DKVV8p93%ibHS+L#*U- zO!O&{D;jbC6q?J*V*gf-@z~*S7Ekt00cCcxpQZtNrNNqpiBCw8dyjym9*eUoQ*U>-v z)e1}x9V>APCuxq2MuPJAM@N=wMlS}(hz#~D+nnAEgi9eQh&ZS1G$ihWJW`^Bm&3%x zUdHPTXSxn&xh62F#$01Sd>BJG9YnpV0h|h;!pmUGF4$%y$o(`@@D%(A5e)*cYnBrm z?Xiv(iQ6THp!$isru~p(Z4y=;ZZQoymN;tv{CUdB@%HZIgGgdf+&j|IT36D4iH}qN zh>tq46#mheg7GkOA|Kq%f5gXm2rwV%gdX7x&<{`1kKRt-(ilZ5RTB3b-A$NQb?wh5 zm7^6xa*w@Sd!xx|K8PnPBnfiU_@TV9fm1Ax#|%$)^gV_I6c+Xfg$TzI zc^eUE7Oej=1OT8;XaWKmBLZM=HAmBy>hmRPT<&TO&64jQBsCh3PPG|{WEMB|nWV`v z-p)4BYDm&=Mg*aT1sx*;2^;trTo}f1(=uru5mv7g{~o|{)Wn#f!93+qzgW=q6}UbS zE_e#{@R-QBh~)4m%Ca=oQquh9G87Y>g2+M97)UJ782)T;FI>|X{yS#C8YlYKl&T*o z`h!|b7!kaj7v>0cG`h2HcLyHwu`Zizmw`##1LlW;Tl1%d%|o1HV|xr2t;Y3 zQ+HNV)M9hyVoT{_>zC&W^UT+4AZ?k8ceda*%Zpw8^dTIQ!b357ry%9*7!@eiumGBo z7h`L1_tcU_k!DfB?)q8Dt!&N3Fr&rXCk%P{3mQ%frNUo|l&lI3zPz%}Aor(`0m7!N zGAc7^rW&$8u3IeeWW2dV;3b=3K||4!P^<+eI;?6i+>K@QgXIwinm%f3HP2W)#iF3l zqP}h}vH!udk7I2Diqy!iPGp|P$2ltL&UK~H8YosKWJb;k++h47_Wjqms`A3m_*D(zz#Us*V&aMOFmsDUufI!O zk1ScwRor;qRp_knS|GYH-CWVmeLaeX+nViBp1>o=r4`kyb;YloFT+bE8{hrW?V4KK z;PsWZZ{IMNv5PZUQEs#s|4OW5m^no3;Gkuz3%=#_U~QUfRkm#9$;q<1iJktyTqw-G zh#zZ0UH520o**$;#bP;Kt-yu`g(KMc0dqUb zpNZv{Cr-s+XFb;MNy?5nmHH12Kb~tAv_+^`$o7{!zuXcp4Hg8P0e9*G%@ZIjZ zyW9EF^?AW|uzM9+WP7B{@rkc%1)Iy$q`mn34F%qvv~o6&q+Q$yR+PB7Px+CsOdL7- z4erXdPuwNp`yM_!$srl7@iu59c*bO=+NG#{H$4_^aRAP#-B{euT#DXgdAUCQ{92`i z^fk8jm21#d*xrOYvBEqwcscs!*2kw#?wfb1x6162*mhQVOLq6mHp(2s zbZer6x1tn0MuO_xj!#Mf(VD3Zw{4k6J8VdnG{`{D{_kGkiOuWtuWoI3Np))Ap*nDb z=G#{Ck3lNbzm@I(e03esLdx$NjYn(_4<7KsCDck)|B*nC&r$ z#*t6*%D?jdRsE}@`ats2FYV4A7B3Hprf(~B$MX;NG6;Gm|37+WX!nuEt#_KT9{cV- z^H)dl=q?%xuf19KX=S(1BFNC?W3?){k+zR9{9wSHOH2Eg-mTv!B1o>+J14(5ioJcz zRh)`qBX#Cu^c+ugvWcwZbTP;$R-0lbPaSUZ9V)_+^fbQ;CdTH<)G*1v^=0E8pTa^> z@F)0aHy}FX%M;g_o!%O6(LwJwcTZB$J*P?TV=s0?RGu7tA+|OTW1oBycP)^!PR$=^Wf^GpRqWb(YrT zQHp>rkVoY=kcw_&w~6;gXvGg;8-$T7uTO(ggeSlGG}3f{wb(v z1ywFJSNFP0W}hSBwJ`E<0M0<~C% z-)|1Kz(Vy70z1E*P^tvp~^34V4B3igxiLa#y z{wR9bXLeTf$0+vd+n1+*v%eAhqQk=(!k=V^EIf4uYOo6LLAnK&xX1pzKYc^kW5bqI zV}CwMU1(nA3kiSxETAAfyZ{{N7`oZ184kd-0f0(1#c9dJiz1mE- zTp@Ipx5(EYFGMRt`?G0wV|HYZ)<(!q8tEzq+C+ewyf+uOw%6wk-;1t?nzj+kd;2aQ zS4;jve}6c>X_xHt{pge?X!M;*x|aCUt4Mg`Pkg80hkq!_E*iTy(K%~4v-4-^p=FoY z{zf%sZ#1Q90L9I6jvKwl-vG;tXY;`gJ9sL#;bU7-;x0pd4Aw+|*2zQ&5sNP>c(Zp0n}&E72Wz zb&;Qeb&sl^wG-q_`(q9V&U`AhA-)?bbeUV@0RHa8 zpp5TSFc3s~e=1Q!r^I`r_*uu*R5;wkLz#;(>mU>^`{RlT!=zwV@ozZ|2V^c?kC82M5fnXLWR^62klmChR0cNQ+p>gqK@LJugN_bAz_1md z!Q98<(Xnzh;d(2BDiV(U!ki_tndRDoL>#eq$BL;~S=jd!8G1-HbpQ*-MdZg=RIDy( zVx!=zjdm#*34j6Q4*}V}F49vDB8op4!bFZEBn$t=p$^ zVr?k$oSN_L@mG=i^VOfXr+q872GKj8o70ZdcpFapNteaP#2NZ|gPLK`G~`5h1DYj9 zaEPk4HaWzxR~+zEogob)0=-Sw4B!%MIdgK5w*Qfg&}pKYmG|dtclt0JcEC98DlT zriJJcyCkV#Pf8M<2)cXAV7y38x3>8O7XsSSqr!VOm6AlmkyB3j;12OjvBrT&(36+? z6kgF100$z!3vTp)BS{PcV&YC6QYgGRI~*tqzU`5Qd{sHA&InO|U$RH?E1TMXYoOA? zJjP(}fFh*kg#7}i9j|STwe^T+v>@rDc?Sxi0N7?&}L75Nk&> zT%^vE9JZ;E!x0-T9SlUsH#s6s{GpT?MkIcH001k{lB~u?IWiysgNr^C8;7RBPG+xk zT(`>3isR(R3R{N48;Zv(NfH2-;*Z=AA#s?}w)&erUI$WnyK3i7ee1{SQ0cd}!n+nT zt#geX($(HoyLUdRDL$E(u89zKwS*V34>$MLq*v|Pe+#6vB}kqwC5e#*)bCERhY%uR zB>0COMgI?JcNrCR`}U1~f*5KTy1P?KI%epS1`!qM5_OP}5E!~srIii=>CPbpL_oSk z8l)RZnLXG4+Rwf2{j6u-`^7%jyqOojwdTdF^E~I6_sJVn5wvTDRW~w3-%De7G!I$yPw?btjmz@n_=$m=$ zt7F<1>_v1K2PrF?lJCX4aXia`YN&PhiND-PT&nzWxOiMm#{ zBO+<6%H+q;Obn&Z#o`;)GZK%|a|iO%OPmEo(F96cPTDHg>L{XMn?qrz?A>d`DXt>++m6qgPSIkUtxzwM;pJx@riF$8W@JzOFlu|CEks^QSegIsi5M^_N zhlSs2>tqRE&4~}jNR?t(yL)(0FtO!aLR)Wj=?c$8VMsUOv*oXH!r6(ePQeUU0QE(+ zbFX=t0xAqE{@=e-46d}Jtf{j{%Do`z1r=GG9&#W`uewKm3$#o1X>AI6wt@>C>SCPi zqW{o`9|Z#}7%Lh+^Y(f8*&d{lh?WynR`USwSmDqZgvg41za3+tD=@xm{xz@=qOKBYr1FN10G z>NQs=ew7NRNH54qg;y2lrkUl|2VK|3x~~Q!i?ybaw6M6eVo|hYkPTZEwao5S<>^*6 z&LLqD%iR#g;XSjY!3mMog$c=1a>pV_p9Bd_s&Ix7~q$C-!4!nVM*ELUQiWR_pS@n9^DD9{v z8rD+5+tgP=&4RD4Pn#U7Md3PhcyCpe|WY&9?95!~XHXcal zTg-CtS`AH@F%#gnDYQ(mZP z^IL43^YI9dHa`yXld5+{D40?CV9(xB7^?hiEvn)%2=T8; z^};J~V=vUjYJPvX9gJ*)?l$>**Iy`eD_1${F8@O8G0|;0DlY^P8}Xt>BWNbO#Rsrs zY{AdAdu?AAKi=HbMHfEd?)6UTjrLW=H5oCbF7^#5GG16j0D=yN9o^$Mz5c2MS(o^q z^)ZdA2+m@9L=eisXUm3OzhjGj>lkpGGddx)x3$)}d}Ti$+QmN@$H6f5Vjl1&QsdxE zMn;4?`=8<6KZ-GZityxh4$N?RcKust&q1|r%h=$v*8AXKVcw|gLgQIhs7)~RBq#oa zJ?x<8JbgPoo>+l5%=8={FT0tX!W$AiYV_9e<0@Z_i;G6Ano@5`too*#dKg{aimYB< z9(^d*uA?pBuaAwD5==5BP)0;;6})uJ>i(<)aWX~je5_d4Wh4|cLA{#gQ%8O?6PpR> zeoB9Evvw(w3QA@~fpOE0u$))a_fQH*jTn zbty4xT1*^i8QX-nDqobbO^ZW-C(80iV5LbF!WO>lP5wqNRl)Wy@o<4=tW?>dif0m! zOTF98@7l_}tGi&UxWl0Y&ClH|CP#5~9N@*m0c5T~j*68`YF8$xp!O(VPtBg;SrBp- z(X(hj?BMYA<+iR>f%+$)hA*e)Yr(p1cpTh%AbKyJ(6z(?dsV_7fL)c{<$4PgY`TJ9 zwO?ST9CUBj5s-}tYI_B4A!~JmZKi#D!RJneuGxd1OGa=inaidec7{Lo67Z^!_kCHg z5jt{up_{l7_sQNO{6+t!qq9Tm+@~+I+NJa4d-FS`8Zh+gS1#k_7w<>DXlZ6Qbzod4 z=tEmOdab!PZ5$A`;e_+hk21GC0*u0|(1Qlaia~a}2aK-W>ie71p@e@Co0c#3Qy@#- zy)F%#&-*rAr;CWrqQ&wZgKG5=#@r^x>y$c;7{p!G7pp2 zfsR43r|?Vb8ex~?UvFJ0(W66%nHA#^|o6xi9 zVv2_jRQGU5X1|at+B5X*GwvQxv8d&{9E%`!+W1}Kny6?~tFGqxuO#_U^e0-Qhm5nY zC}u=2{;2t`k5jH4oyPAN^_DURZnY;@5ct{0l{{vpaO0WjB@;NN;}KPXBhQU$bYO6| zv#uvth8KK<*VZVM;0xH?GK9gpXf;Q}nF_nKJWe&lY0_hA9gHb_w}O!2urTc&75 z@~LVXnnAEexwuvM^*Z<#H~fCmL}T%zP$#I zhn74_v>e9JDh_rOlCPZ9(V)3DQqd8>)Bdii+kY=*{A>-|{`lL&pg(kI{764RLhL!8 z3ck2?fS?EW`2))HMYB3%mKt4g914nBJ-^V10+JxYGq_HzRs{JYj45qRo%vet)6R%T zD(A*;1n7-fUm1B?wc`BIvovcwH%mP;s5E}o^B&2xWSMYo)Q?d$21{CG*Q+{7XgoY| z=m~B9)cxf7{gKz_qiTP&_q&t|p4z*Q*!QS95P3OGc&W~wF)m9u$%*KW!i_&j+GaP{ zzVRH8eQehLM_2WaYcbOF=O1O-Q=(c=_ePw{&@&tTi$Ulcm;MG$y>6vRqSp^e-n90< zc9ilu{G(i6@5Ay(OMb6-vC0`=!Ug=%rILdCRz*DQ&Fh3Wo457u&+4RkLZPq*htmd~ z0(?=yb&Buj!4v1Una2K^@BRjb1ROR#%tj)=H?H|ea)?X$9eU`8Fd?%Wm7YuapJH|M zwEHIB+c}qCFB>Do?Qkg(6qg7V2?Uh4$>Sc*OO>Gb$~P~vF}) zypMX6Sl_+t#ChLynHKRBj~MjG>Pi%*!e0UsHG!tkgs^yDWt7#+{CF9ZaH=z~C#tKP z@$NEyhSP0LK;l-VZCFNo(&sJ9HKL^J6AhS+GRTpt7c3IQwkIRXSQjpU1IJwGW`?G( zO$e4<@n?Exwo3nv>rq;dD|*#Zaq3vSyJDO#92#zb?;1vICq3^^CP>p4SVPw>@Q1IpChNVj7lA3z3v^FD( zFxMxE^rpG?suADs7r~5@2f7J-6ZTWpC%;jc3Zc&s^2l2iaE91`h1gukDZ8$k*m}@q zt1>ILFzK{d8(({|yj24s;%=R~{8XDmKjzyl?y6Zwl7NLb5$Z zd)E9DjK|7u$M9o53f$&V0w0xtsyliKDEmd^#ffQfiY)!Vui@aGow1BoC*k`*AGVYc zVr6HOxpy~nt*_?aw1(m+>yw6Hf89b8)%aC0HyvO=`%>HcMpa)*aO*3D0Z`A&`!98yqy%sL$7kBPo=4xH6K+Qn z{w|XOwn#CTq{_Dd`6e&Ka**U~&wV6)zRxjr$=yy!?e23$QxvIKujqsIT>S~*_Xl?$ z`*AKgFDKpo2mIPg24EyW6v;{=bSjk;m;@s;#NNl@m#^_rRy6+aBVD^2L#jgR?yHn z-nOp1E)0=?Mi!Y&RAy%skdU0Kq~v4r4GW|M8~eAL8cCHo$L7RVwGp$DOZ@?(_K1Jaznf2DclO4gfDBMvK6sK`aPwlTV}W$DpdnyfBXAh}Lx3L8)WpP^>TJr~dBfez=+z~Uu!Kx0@FPFux*``=aI7XpRFJDi zB#i9p0|7jaLs|KORpdHCEZzD_QQrHKU&z#5x_-KSQ_vcIN4&LhA8^^!pX;nRSMxoI zTB~Q#?|As(lK<5{W@af62%TMm4_K%zhurMHNS6bt+r~@pz|B{q_$p>sWA+t#$KWCd zvug>6J8!b5-`fY`1JAUsSOU%-VQUhf2-G!$sS*8HC@#$rTeQ-8l$*9&2QfcLgW= zvCiTn8(hH4mBL&{ygG<;kKrq)jKEJ?zs_IkUkrS3^LE-AmL|xk?Vc4GGOXohEF|np zN%5u3Czq6Q!;++#*c{fW4lb21t&Ri%ZS0KYKI*%aP4Y0KaM)iFJUsTM zuLYw3y1!d0YM^BtJzP*&rlGaPqEk`{Yz@G5tIyaRtU=9PEvB=+mTq&L;CY*rn0dUW zhOxR#P=%@T?4?BrTLCh0_3#t;>2!=sIQj~R^H|362cVmP2udd-@ejJud<@CpnzXO+ z7Ou8@TFtFkpHn!Zz&;2|*J&>#r@B_#TL`WXj!68LNq<|Y1BJ&1ykBMGkL>wru$}DG zV3$FutEOF~HEeG7DwBH7_Fndh4w4x^5J~@A<}tfo1x{^9R+6Do^m3xBODKWvXEH?M z!z{p%G1qOcgOoT(el52*8zavxMY{7KIafUE+_ofW;3&aK{(T;|;cw&FZ}1U=BT7=f zEwv044FD@^h#?&C8X%jRpm(p3+Q%x2*tb8WMlFHp3naCrATD|t!SJUE560(<8H?8I zW5&Q{43bL8up{>Q@3XeGcRmxB4xD~wYa3<-ph9Kptijg0Tj!-2{Z*0$F@1@ax?yu8 z@7~t3rK9mE6Lw%Btg39pK3hib2B}2txGVj?KrA1Rn=rj_FfB+MHh(aVuc5GF%`f6$ zaX*9H)TSmoQlZekkj|`uoReY-4Y6f3mh}KlR|;+SDU}#nOp%Ay36Pb$nzPS@Z53{>IqJA z1-2Hx_@Zs;r#wvAz>fX`p_Ai8Eh40L6ZLE?Ta!xkZUxbo{!+`pE1ebl93&0 z!{vURMiV~vtL&WK{p^spTwvRnT(W>8b#9U5s|D%Ll9mF8$#Qg1(b_idg8{P5qi{oM z{!fiil70;@ln&hEH658PPTpVAd(kUae`4$+tJ6}&K~75WYfIH{M6&XV4R3%; zkXK<+Yw2RxK=DjNx2rT})<@c18iWwb(Y4Ve9i??XFUcm9A9OjzOr(DC%ndAeia@Or zNo^^MOtJ}Eyq)tudYAq5`IAlE#$G&*tA(0xS?igqJXRv zsl(O7bCM6@f~l19?)Wr(-I0l+r?3!d4jiWuxRRciem>{+bBtw6I?sx0N!h}(ApXhh zoHDBIFWaao{=eF-)n7J=tvE4aH#2E`Iu4+DjhK9_Qz!n#Ru$b<%~HS`G`5$@y|{Jq zu;a20KuQ-aG_%}yF7Hj2Cov!PXHM5} zIyeP>kVC6m5AO#;l7Ed(DHS6~d`{WfUc*s|a@jf6@^JU-u8Rft&YSgq>7V|jM{BlH z4>8`p$8nt}gSt$)uXDR%i{_E1YjpVBui?0OE0Sp-y6_cBy)H^^HlR)rC2bW@V+F`I z3gbkA_!40dYZ!LZjYgj-#vb#sgQZpJMk0$a9+mvsNDlJh(`o&BtgUtz#Kez(hjzxL zDxK(!5z1T5C`!0J`6hjvz{(6KF$xk)%Y(!nL6SrWJ|yx*1F0ZE1ZYU%5Gkis0px_6 zuJ>TDD3MSfi9dFDA{K}D*M(R;7-A=KxAXE&IpI%79_S?pk^VhC82sF<7w647AUcQi zZkZG>m-O!_2q+2@N(2#*fpplYA`yTX13D9HSoE?A`~V0E5{zd1sfi@wOSq8C+aJ;; zzR_mEStlNYow*`!W|gaBt^Z^s2-KC5aE?G_)^O66N%gE%qmgu)xdigiLwa^V20Z;5 zNF|NDU3fr|B>Y!X?@o1$O=N`yvtUo>_l<%j_>PyO!7L0GAj0Qi1zks1d+AF$Et7^< zL6TM|uX7q+CbB}|B)&Z{lc=Le(W{+%GbRRfxnsoYd7L>(sReFf(;`gS?D(6mTV_eT z+WV7YhH}!&Fzqht->$U82ofhaRT-HOe+~gQ$oL)G@skQ#1=wOD+3B7kb!3vvAM| zX|EHSR5OS+5=pRsB8)k%fyCufPFm3fj&S%Kcc2ZnO~~&;4_V4t1+S__g0@*6BnhOj zQ%$|*Y7m7Q<$O>i2S8DH8E8_xE|@0vGa)6kY9$`5NEnLWCo=#(5(jEoQ{Ckd=mD5N zkJCP<;H*07>pRIhu;LU%h|-9Y@Z}2zeqX6LW-#r>Sw=OAh>OgP%48d#;nXsR8RLam zaZck(e@zzc43@r^B!FW?2N@@N$PO~XA)G9eDHNBTt5skzZpNF~ZxY{#CS*n%$q_h9 zwTm;qW5<7S!pZuQkR9-Anu3*R68_7bLPd=DH^s6y(0&j{iAYO{>Ga+^kdUJggE8p+ zG8(6}oc}SoDn?~e(mqPIXB;4G&G|%Kxv^IEw~bQ$5g+?Ic0*XT0cy8~n1bgNF7#gY zH<{uC4;Fkhow_of`B@5Y9i`tSmo!dMA_XTW>k-~P4YfLHPZJe!cdcUg1FzadJXTtD z<-T|iWd;d8E0c1U1Dqr5`Rm%VX+=m0Un@P6^FPzbt-V;SrT9KMgtX=qw$@GZ(0{tB z%T>84?M%Bk&Y8GJB5$I%>!Dg}qC;^;dnzG-d)`I6#{vf$fTz?R)+kdPY=GeDntMue z%D4*-0!}aVu1@uqCQSM6YuY0L(0A0*^~PFBruS?b!mHJP5gon9pJ6|j^f56aqvRAY zmAXgOipe-;aa}QUGnItg-!~7YyzZi$bmuU7b*`svj!hQkxo_f01$ceh)j}Bsx8{t* zvG_J=JZEDOH8Q}T6MGQ#00H{e6m1bh^(3MGSsazVz2|`$N)wZdKYQOo0c_cB%9WBw z>oRVs5R4)8e8Tg`knQ}j&U>BI`bu9`mh}Ux#}W^PBst>6A16de!;GHweAua&dS2A!2Yl46OC!@{`x0Wt`1L&$<$Yw zr|}(C%q$Qeo;?VDXA%S#RW6%drV{Wnf0Sa=Lv4F6*tzw)Gf6+d&YE+?8eP)hLh;9? z--`AeFiCMmKoRkHs55UU$ZC!M^3HB-n-LyA#pF9gzj0* zxK^rz-e^C3>6!BK`2`1*Rp?P8%~Xld2TA9@DPB?!eZJKoH%^hK(LgV2&X(La#zwv~ z1m2laT&Ul)PLwt;4y<1b``o{<0XO;?HnNXWw@x-Zamis)XQ!=_^3#{{zqd*`9jARy zStfnr?aYke;}rRiQeNAJw)LrbcyRI-yZ#+1M;Tj3ru(4--Q?%g08Uo5A`_H-s^bqD ze@wcRU(Q2)inLrSE8V+X=I~|g5Vp$)N@qjm>gXWJkQ7!ND`OlJ|6>{ymaJ6qrq`G? z(z(nk&Cx+3hRtU^o~F4z#4WqLc&Gf?5Hahu`zJ)E3H9?${o;kLYz~dOG81;g`r!TY z8SQf!#UT@0OCKNEo5M~-j05X>{ zj|h}@U!sjynBmx&ZB>?v3I{N&=P}|nC6IC^k5$HQTykhmg%IQcB-IF4>)x%=Ch60C zV4!>CM)R3*S>*n?gNP5_{i}Xy8E+|N)_1uNDL$~~=wIvld#U~(q#EWib(?G3d>eFd@ z(#2eE%$3(oa~@-{&J(Mgd?;53il${8N^b*@=wjSqqs8Nm$&%tXOLcrqmc}KU7eZHL zdtG>S<;joT%x!QjtQmF?j26~7^vXn`T}<;pT5<{i8lC?;m%f)0;5}G;JM7VS<(%fg zX@khekZ=v4D10dj2=d4m*horIG;P)nE{UcqGAHXE48PF~JibNsG8G&2shH=oo^{I% zQlEo3667`2vQlQ|Wt|y~2^N9(@qc`;-_I;YNxI)XfWSS?#dF4YdFQWGBXk2;c5 z&2z2DK$p(@yZUeWSHqqp)Kovx6oKX&E8c^qZ~QR(^0z zemumDp_@+9(}~f0sKBC`o8h~7(UbnZz>~Pt^pIGf#(Os{= zloz0kMI_SPy^q?yKE3^FE#GJVw$JvhU2^?nl&WTEAzSSFcK}=~tyhZ|3p64KN>z19 zb)PqU?fT#Vc%P%=0F2^Us5S2H7HwmbeA{}+sedGAxGHC0p1Clx3EDw1nC5)nXBfuc z_}-c|eEf5G=}G6*0&tnp;F7`fEw1@pW_|RAd9wYZ47F$oJMkt0MxTcUuzq6#6}J_n z23RqvcQe@e4Ax%Pw$HaD&;x213LSr1M8)#nHtst7Y_PYe*Lj+~d+n^(=V(@BZ^`X2 z)Z$<#Dv+GWBT` za>{5wv<9}x?d=f0|73*1W-dj})?Bnu0Do&2fiuV{S4R-|@wk2b!D`s1+LG!u;~pDr zFyKnPL54VnSGo=={0PHp`AOsBq;p1IV}BUAR=CqZIMRvQDw6Kcmxut~Na3FvjBrNv zZbmWrO}^U%rOUb94_vd}_$^he36>390jodnlGp@yF$BG!QeT$WOnavvzj2j+toG+X zX^1`UPGn=c61psX2yUfqV}(~FZi!SjUUlN&`2sFmt6jLX7;Fs8%%9dpI+`Nja;+y3`$G+5SHn1<{Q7Ii;!%8{Uv|s_oVF00^5l(nJn~qf!WAcZO#)*Vj08Dho`syoviE*BW4gLKE4;) z6Ge%O9lg)bQ;&v@OCvSW=AGOO7!vg~F?_cuG>$k5(Gs5#k>np_)tnI1oq<~w^6k<0%cj3P2@%`3II>Z%!jE9L8z+5)n*qui zvgQcNc~s-xHNEef`rNXe`CH2VDCF7r4QG-rn zsW(GGwt1|Z<@wbq9lqDjE>kF`N@ia3n!V)rj`{^BFL#=N4SqLwB#hQCs!~{Np$6sI z^cj4sLt}=u=PNT>pE>FSDE+*)L%;Mxp#jTBM_@M1kJsM-SLb^_Y2r1Tnw}p(V$O8J zt&8v^-4k&l560gD^)#}d&10@SSc7rL>#bCl_)NYjmD9c-u))l(SsJY+_2ViUr`wuf z$x6*Ub%vK*EJ0vyRZXRmp-?!byJiylnE*6}RZnKIj^lyC^(?C;LimhT+2XD3a40U< z36xl`!(dg9Czxm0` zjaPn9wyavQK|cS+FC{i^)fisDtyZq$N^DOIdECphtuHMHgJt32X5nM@*3fZ%evw>2 zKcfb(iHq9sYY!LCF^r{@P<^hL_m>b1j7+(ag0`;zK4lx>7W^s1<||EGTdhka;l|F( zwv&;Y(MmftewPMt+;+dt&G1SnV91PNvX+8w57te>*Cx_MxT8}LhOsj;AlWiugO!VV z))KUL&+WPmu*VQr8eiJ9!btw|x+`np4)BJ7h(zUUd*sICMS35vWYt#5@_3LnE>hd| zD_t}GB~`i>OoRzH#OfM+Gthrn-3`VT>aw_QK%V+>JpvV z{=oDyKk|-0vWr-DJy>dG>0^y2%JwXTfF78c0iA|Zs*kz~s6Hl|@@l4}H*lw%Wc}+J z*~2&z8X|Gbx?U5OV#}Dr{>eEDJjKJxS;`xJ&*Sl}OG!^*fpD}*xedZwnu5hhm@R)x zgO5L04)aU2Dk|BSJ#AoCPNHZmRy8P(3W)kDHAseZD_Aj4_J*zVMzAw1CtS_*sGM~r z#9i62voWzNF;2V1$1={bOXaD3XX;hFOve^^;pi16qvtM@>#S1F()11AqZ3>U_%=)j zqg89XA#5qtjN>VdPRnm{VxJ0i&S>eck|n?7+@RDa7}_hWiF@;86%js`5FoP-$wqY1 zD>dubsvBoan%LhflOD2id1o-EYFCw`l}J%uZcoxR={^V<5nrqc4A*sJ(1;p-_R{^6 z$!<|Y^k==0%iQNs(JqGf8@-+Z202Quza^HwY5I-3=f)=&r*`-l09f_hh_6z$K|3SL z4j4*%oL@Fp6#AHCdWTQua_(`YnfJJkfmtH7HpttTW;P7=hycOUqOGv?cyId4=I;?J)_?yS-> z=!tEk7DVhtql0sB=|~MAgm+P)5!Lr=LhXM$u<>e_PA60s#3kEWb4ELfM4O|2LB@b7cuyH(0=Bit${qFC!CM%t*_vR?=! zD}JYKA-%(_0;GEp#uB5t78idCZ=ycY8l#KL}WFmP+=^>QzPi%UIA5&D|4O z+~5N^CC(`40;o3KqCUR0p-`FW-XS?jtX!A{+LCn8`vb((&0z#Ns)V91PU3&;+4AYr z4f?z;gFcGgpr)Bid$1KDY9o*ctg%iZQ?GTOyM1>5f-cuIzBaek)t=HVJ>L=+vkQmh znA}3Ie*`SPDir$Y5XWj3f>e|U`dvN(3x323l%`-DXxY@!ryYG)&KHd|TYRsC?-MV!K- zrO~pXacOG*U}GNX!$klvN-VceqWQ`(;uSsTKf}^5KDJcRh}+ZN>DK?U=DBDP1Ax2A zlgQ%d47FDmZor;755v-*hBvjRg>)n4l)%{r$s*D_yElyt(=;!e`UOsqcnCPB3+yy@ z&=qNm&#)rk*!;D=5UD11yY?O0Jk3o6qT9b(m4A5kUEuEYJqz`mSh3VFCPDa9`h~&L z(rz9f`g=IVHRIZ3k#Ff^OV3w*^3~cJEx9k^Q{^J#78AJy0X+Mt;8!29s)GOWmmz5*5r95jsju2KYgc31!V@&2EN-GGaN z8QBHn!*e5LIExo8M97=%rXR4XIMLz1<*sxci`~EoFbYQrmV>mn`9$EWPzge@pqF7N zY_NMUcqHNOtSs>F-mA`=smc)hGZm`C%Fe%sm3Kr1E1=86PRvXtCh+zm5Ih?Q)I{Ms z1>!}bhz0@(2T-Ju0Z>Q~F>es&4OlgmjZBP9V3hEu0qN@KKZ2tLEAhc76m5kIHpCsV zB3*;|frIeptw?7K@T5HayZXJsx&8}0u*HYi6l_s!Xew4LRdWi}hz!*#2~{`8XZL{U zK*9`p!;Ce<{ySOubSvx`B;1-eT&D>_JIkz*%!%b5o3Y#@3~vGT5BIpsN`&Pen~+cz zGSF`WBJC>tvr!0W4EGvNpjt(6iIO4+@|B|1?bdkP7x5N{EZ~=Nz@}6XX&NYK6qtI6 zq8f+-Z$)Kq1?KWbUur}brlD>kFwywl(Pdi!U(5q(O1yWwcmj-sK|%NzXaFD)7h?bh zA^synE<^UPGUN)uJS(hmln6{lQVDpe-XD2CH3ZB?@@3g~{V4cFxKAFBe~yO#M5Eg( z?JJWat}n{McwLYkRv1eTG#vn>Mib6e#ne?{AIHN~fdH(~WD!_~70H-%-0Z_RP%i!- z6y)6u)F99FZK~(!j34YOZc#dkd@iw;mU%@?7#lAp1cPRCz;s4QZmLMM!dN*Hjv=x@<2Ip4r~v@J=H#CsfH1*3v8xbr_jl4)p195r;NSeHno~&UQdA$k zZ<6w$rDIfcm$*)p&;bKjj)=QNghADitsG_mR*$U02UsOsmL%M6C4hj5Sdv%LIfWVD zYwUMQ3PEa`^Lv%%bob9(uT`YHLZsLLBtu9b4v=6I#YGGwz4s_qc#L2W0>J*m4>%$o zEs1oJNslp2C%a1d_&NPGT~_yYCYeg=E>M6CMl!t&)&qgD{ZD_6{vjmmm;XaZBB6CT zIKCpJK@h;xMAG*nIO(WJP;=(_bf&9J)=H%J-lMGjsP`THyj37P^3w-4%h-V*X!kPa z9jH3^Pfi?85dKdj>8wG>R{E#KhEJ(<*+&GqQ2JbQ?c5h$Sr@gDM6$1rR}#~&a;ONi zSax#R>GKetxqsf}((_x{JBu+{*OextD)fav8*ExW7hp46BnAt`cM2uv3!h!T{q)G` zk+0KZ{v!Bbx>ZJzszrgzwU@n1kz06?t4p!%PJt1s^vj&1~%!m+O`6>QCt0ae zozX%ea73z|^JQi*`QGy{ShaFoyY~KWxl~N;U}>$~^Kz_O`IWE^aZ{$kP%fE++bXSr zCj#a`S8iEQ>I-1%cj)VlpVzNjV9CmQELmyxz5eO<3amvLqGgxu`>O1ka zM;HA(Bv_!?PwwG|=gs!JO)^o<(p^nPbYESB5<~!PQ43=c6PU$XF}uH{Qi>LaYfU0HoVhM9MHa`Yl>91EO66(wRiu z&}u;DQTs0xhQPd=YR3kOF?frGC^M{}=P+V;6%{}b4O#(YBmaRY>rfvpy3k-LEbpu$t zIbFNKN!`~_jy?g$L{T|7W}`$aqrilq@J0x=003H3g)1+DrwFG_&A~t& zkYH~BX%c|i4o&a|)dw&jIKWEEXrjfVRP&X=DtR;qj2Np>KEW!KRaC8v-$8EpQwGrB zJ)5G~!P22YFo0w@2Ui(DlqLv^JHnMh;O-te+K!3G*%(Ev9NsPT3y0!2%CKskXG5c` zLgS!Z$d@Br1y;xzfB;lIzTGx*qD-&|pf3OITXjJzbVT}WnYMlalN7K*Fao1%hY^93 zi0VaXo#X+VZ~~Ah=npdOiQ5pz<(H>!Lt=2KHUK)bU}F|HWx<3awClT#hTs|EV&H?I z706Ix!ul=2tO%^(h)4rC14^0#h|DyA0C-k2-d|<_RiHCgJUqkLwai$A+bke)HskN4aFZ>D1P+{Xtqaerq)*0}2cu#+y{4LULY2-;6O8}f8E!+$DL zXr^+1HiraI`}8NRF06tT+fY9XLd>3Y6Z8&I^+a^_U(hNYkw$6KZqZKJC6VNzh_>M* zbo(@^04M^vuyvFi5Y&ftDEW9{!>BmBFAHEcEJcZF;UfEv$4Y!RJ8d4mxbp&c@5OwQ z5NvH(9%l@gw@k98gR^M`zR(&O2Jl8>+2O3k-M`6QO*4R;W!$l4(*IbL!HFd6D5AoT zX`rNpnl5nD#5b2X3+>u7#zJj~B0)eg)1pw!;Mi;6t!{9#_ zr4<#mB8;|T1?S~5vm#9L)4Gl&HYS0{4FWKUpP)MsRyu-iex#C{^42`G=yk__YPLCP1SZfC2V_ z%v&J`=oQpI6eSsmScDEkipe4IQvgo0LXd(zpe~Y7VVM09sl_%$hVWL^0pJsKCr@vu zsAJ{>igaEC?+J`}9vS*m4M>h|~{^KPvr`zMhqbF4)< zO42n<<+>R1QjfM00OfC`&`lT3TA;c-A_k8Uj>2jEM4*0f+~6vx|G^^o?N(IB);nRE zHaN-6@Dex{_qRb;nxY-!;W6vI6LSL+^;4pbWg@UB2%aN6DI%PEBvGz6at8$*GgC@n zj@j;EVA7SR@`tDJ%9FL%Sc`HTYfOE2yJ*18AryR7nVy zS~YKVym+htJBvGkmJ>~*L3TlX$vG05wWP~P`&uPfgFcKShgb6{EbJ9T#Z>`7u zWFP{1)sjSOb@nY;Pb^t!tC=O^d9XewUO@b^f%=kj-q@ln5^unif8OLb;Nb>Jy0G-L zhrC>;Xv)H9>bb__5wU3BKT~_M8gxQ#;=AYBA0xp-hS9X$i=P_QmK;2Ch%(V_4=zAf zNuF9V`pTet4hyqxrgbiJzBo0nhWZK4$bm;mremGL!hp9eDPz->eMuY@f6cFI`iC+@ zZYe0-!t4R@voevh+v_${0CVF$lE>lz%}qR2J6MAL!LRl}uzsuWYYof{z>4;cCJG-Q zcB2Y*I(yl@HBP2qTp@hx+qd_#)(ZoL6SU|vYh|kcoeeamYavj_qb0m0{fUK(k%6VyBke;l%f#1n2mubIcpeh+*jN&hwR6gEn4-J3?$}b(s1zZ6+ z$zCHlHZ-qzdCAo2oa?%PmVMQE%8-Cqw?29WkOnzT{`=S306kr|uhhqY{0Is3H?BNp z!LIIbVedzdZL#Rf2%M_W|FiQ(E^eKwa4Ud) z(W2wnIXdQrP~(w4)^-Y%JRh!e71#LZLS^)8fAJBS&%Gi^fq5TNv^Be%HRy%2;xsLs zr6#61NIK&NVxRAQ!!v!MWW|-`+p@x`#W%I?MGe3kU1#(QCg@i4Dg3yB_c9+hzc(Pi zurZ(KtEsnj>7@P4Q*RDB{A{FTkQCmt(Jsd<3(8Z?2a+71kPN?;;}p?|pZ-$pQG5;3 z?6LPZXKew>k%b>UJwCJL^Ji5%e(p00PuqwR=#XBElN-?_c3iO5NOR@bxpFKDwtTn| z853}2+QeSdMdLdO3=5LblAIIGeTbK1pC7R=`wrE`*Sd~*N7r!kvh8%*?^VampPN@` zFwI+JH<8pWvX|oFTem)jH@9vB9I0<#4+=Eiz8(^v`Tt8+UO0*T{=dme<^o;TK}h&% z#lK|bvp;+N|B{uMmteuGBIf5u16#2#_sH;)?sK$oWcs0VzjHWw5&`^x=FC}!3C=hO zqKU|edjK#%-L8ju-n;i&&>KPQF#0xippVu!5#sk2h)pvIgZ+WW-&$L+F--?SNVpB7bnI-7xJ43#?Kr6$04N@8 zfVJLwB{h0rfT!j->BPP_JSK90`Hn0+(qvWY7b_V+*f52=&oJJ-U~T*TQG)ln=zkbW z54M=AjRg9%0W3o)`aV9??J*LVM$Jwh9tcn;+XKMy?+~O4^I#^=bvqt~t8e{oD=g10 z5qyDFwMux&4?+aj*%a~yfMO>sX0S(hfJDd}z%njoIfO6JfW-jMIIV|svs=-M6!Er~ zVtQbJyKdlXBzEYZrMZ{NmH>bnBL}d?K!iDrpvu(7S! zK?xqW%AtUq?7xi1q%1(IK*}2ySL9fHpsPbpJ#o5Jh^CmA#2S>M(D}g&ml2)VwIaC< zXMO*ccN$K)_`yhgo&aBy0&dT|Jdp^6rXYeEKGRZTAxrrGhEv}DA8^XQcUYV9@6BH< zPI>*WOnHlab93|e`Vxy%USPkySGPBpH`mzL#SIp!yt_R8SEU3)wT;cSjkUG4v7J$@SGlybge5As=6`R^?rhF( z{aRS~J-xFzwY@pHy*jn{^XJd``T4oIx!Kv->FMdt)sCsj$%%=HwXuzrq4lNFxrLEm z3nMe*N2TkzZbxol}xs)S22` zmGQYPuBsIDu=U|n};;h1~tgP(xPao5=aubWv($e04c%Ph{9G{R7ADxIL zDx*S@f`fyxM5T3%uN10QDxeAD?sRDVtn*FMkn^iB&jkOsVI?lr@s24zK7n3uyxcuP zux_Or^7X$s<(;YFfu`oShc7>x72ioqZAwX>3JG3tbG$dsPSeXz)ys>~_~7^|>|emr z+S>ZrvuFCAMe@G2k1Z`NEG!;Ae24`s|4Xmb*4D<-m8$BRSh^AphyUwSD#|L#$jC@b zOaF^giirK6aY{~3P7EUh1_r|rKrmo17Lq(=V7P#h-9R9JK_J2ZC072+RsNS%`Cm}w zze**RsQjOON&pamUH=I3=D(=7U|<%iz-Eqjfj(#w+TjH= z7{g^-=%57ngY^%5Jhq7#cn_<1qC{KW<&PMHhV9KvWFMbnyriO*ZSoso0bCxXr?46iFO>!_C|T036Gs3FY`?)X&GWf4Bg6T3N(xeBDL&qx zm*L2T)cEFbz?G zzW~BOJ--SJi7S(`@)xju0~2iPjk=0U5D)E8A&{^Fg&<8bxLP95KJ?Vq20>oXv&cZz z4uq{in}7wX!YHS#^2*e$spFvo4RFH}G}mnN%{b?*^UY0M(ZtR`2Q9SFJ^!5Z4Flx) zZ=eVJ>t@08LH%CBDXa0%K3MB&zN+%ePmVD2e>(rX^X8_^sKnO@VZ-*QV?sp}n&hK~Kpms9y$!wtu!TOBD4`;Y zvb%iy{PfpkHOrZ*GfAhOJuQt8}=- z1~w0YKK$VW|6#Vm`LwWzNK9f1k0_uQ;_yE+Y*Q2qazi2RiH8ER+-$VCMJ&#WdPG#B zY?vs{DTDc*+exsXbgl*kswu!9^`_k$6R?)V1LXH=FaGsG!pWV zh$NLE?XyN05l>hYutC!1Bgcrr@gN2ehU;tyLn{I-kOt!;1A$1&A?_-XSy?11SIJ5r zsq#IIM9?Fx^q)$?B$JyoNFEEg$5LKVl%wpWDO-7yR}%A>$jpy1%@a!*lAwcLVZ<8& zz=(L1VH@=z1_u~%4tTTzbrw*Ca->nIgJ7Z^^XLUC<_G{^)DZw|xQ0F6v5XFs%q!&_ z$S#BV|4Uzf5|}vzXb%qp!DJd_nFdX$LbZZW*)%c$35cjfCrZ(ZS~Q{oz$6Jw0K4sh zVVaD{hcc|dg?A)l7)>YxJ~jpbUOVK&u|0?neW3c64LG_07yux{Kjy*OdFW#p0BCKR;PEj? z{|WY7%a8{#CgD58a`K5%jVd68J6y)j2Lvjp2^VEE$jV~Yvd}%|bNlkpi(2=(63wVV zW=TGf#)DJrY-b(Yun#31;k-w%0RYgeUfK>s6}JVz0JgA+YqY}$zSZSYc?s3WQjR~L z2!|{N1j?vQHH^;XYIGOO;OX+EnF1o7GFs7Hw|-Y3wiGV_lJE~Mz~rw3iAH<}q5ySR z!T`Q7({DY=G~x=fz?XwDOe#=|aJYiNE)FF@5iD5;Gx*15^l?@o48`E_Vj4X#!AC6& zUemr)80TPv543=Z5)Pyd_Gm;BHnCGW0)Wa5!4eq^unBZ1!30ZF>_Gc#-2d9={{`L% zM+|W6UjR_`vI+*Wp0O(A^LTZ?&NM(0qEU~3NR!DJ4sTBZ;DAk>BOmK1hQkbk33trH z7wh!$5|Yu5du*c;05HH2mN5@XDHXV1Y_ppoJD(EZ;Tz#_0i9KSXNC58&$zbVtpoFC zRNLo{MFO@!)Erz@PtVwofq@>v5e^K@n#~2NbwYQY>uT4I+A|?Ce}sJ_ZWBAz&~9vt z?W2OQhNBzGm9cr6+v7Z2``xI-woJ60A8y;o+kjqdxLM8b*&tvBdI<0<(w$=igYlFJ zJ|Vmp9%OgxuGee?U=8)_>lYV1#uvvpvi6-7 zLkZs%*YUo`J#)ZlfChSCfh)qn2a(g7$68f6%7;EGp(ljp^Rai0V9w%I_uJ{o)`JWL zP-9s?TigO6c`}Vo^sd8+>pR}nw_DyuCNZ6+Vb(C$o@`xtfy-QjxAeBJm?5Tw6H z=`=b!e+|EO((|R`G|&J5Vj$rDWPIHRMtHjwuKC)ljPnKZyDVMa)@}=a*n}^3%}bwl zzT8|7FAxYH!T}1`j~wV(#l7vPZy)K~S@(g4q$GV`_QA*8;2VG3|M0b0+Mx@b{MWJ+B__zWnz97`w&8-*n>prR{o<0s|ona^`$LCwrGid-1n`MfZLO zLVxA~JkZn?hel1-giYGSP2L1f;zSSRWDuwz4Fq8gnh+DB$4|wFc&29)0CgK;u{*cV|N)loLEWYi>5BxO=4rBW>AQZOY`G(`|i@DFeW08e-X zCWwFfCvz((epyHpsHb`YQ3Bxr4hTSl>}P{jWqmrBhBU#0Vz*QQfB|qAhjKWFbXbRQ zD0u{7f4%osaWz+Ubys;c5PW42)lh-}5P~vsg8H_FXh(B?|8acDHxR5>3pYV|fMI#j zhl6Uki8sQA-X{g9`x6@1{vh@+Q+Gy#ADNDu+0e(MK~W{79k zSd9XSBbum2e)ooUn2-v2hiWxp6=s3ss9_xDVKBiAs;~>mFcXScc=o7;9T^k<#&`xn zfOGbYj@WtsXln&IkStk!E6GSbSY!rpWJxB3)fAD7{|04JMrBqu5Rb49?$8{GXod1v zT;u0J^q3H+R{;jm4Y5{<#aMZ8AE^-K zCjbWF0_O%GQF)0|8C`tYmpb^DS6F}ecW*=)n6QVJk_noj$$tsK0(yW4b7v5&H(+=9 zd#kX8qge#PmUROy_||2dv56Px(~fr2TWgh`$Ch@IB?mNVgM zIhPPMR+1*EcG1{Ml}VnqSDT*s7=tMzg*lIj*`Du-5G^Q@2myC;_nikAp61D)5{eMD z**|}$mYk`U1GJk+*_#A96J3}Pj~96kT7$1C5H}zU?_dwtuond}L0|EXNwl96s&{|M zJL$7~7@C`Ec|05np9fl31I@~&^N-a1YtQsqOSZ zxX2Cj#0>c~qgPwCRtd8lS+RLbvwM551(BdKfQJe}l06Hu^Z~R9XSY?0x4x;jjmx)> z>$e0EqB0SK;V^?A3!ao&w~9NEjQgSZ`n6rlwHONkC4h6n>967N4P%(O54yQj+qstc zxmxR?pewmHi?IQ)cvD9ctVaunYq*6Qb`UDN^GdsIxwWHPx}uA*s5h=M!L!5ry2%;4 z#@mv}i-opZyP-?EGb<28|5_8Ez;nT?xz&5UrJB9qN1DvLyzR@ayDN18I}?OEy(U_` z=&PmbD~!VHy2|^#xC^9_3cWHB0C9%7{#&Q`o4*sP^-5Dh4+5c%0f{adyH?7aZo zr~v?{HZh4mo5KQ&k|%nGoSVWq=)mC>G5Np-0-*%|pamtz zoX36q$Af&xh)l?S|D4E-%*ch@$dG)bld}0 ze0NDa#_`usWWWYgFb2?o4j-Th_&^ZT&{re_7LQ;Cy1dK0+{?cF%fKAW!aU5xT+GIN z%*dR~%Dl|X+|17W%+MUo!>k5(pa*xL2F$Fhq9D!O+|9xK2&L?P){Dw%_*^6)504f%h3ZBzcSFeS>c$JSkfk}GPQ9Vxv?9)@gl)79K|sZRNxHvkPevO z9MB;h<(bmU*-)zB1wF6@%is<*006sy4qk8t&``q|tkK-t!5`hXG|fvLC#ih##b9iy zbE6;(0ssyIAre9%0AL{)q9K?P0_-3RP0$AQz^NvJBJcAlR{gS9I}Gc959%-sQFsBn z01xzF!7*{edHKH`UDIqWIj4(!enFf-eZMOsB~(I7Ae1GC$Rz^dC164c@Q_r87{LHg zCT9{m6ne^yoq7AKaqRoq9&FQjLIJ!xzgbbgC5+lCqbR|`+5+JykW#WARVl&nPHyBo zY=dEL|3eUP69RJc+jr~R4;IeC?b*f++L1dX&+8Wke7Q+#(hB1%zydJ>K`h1s0LY>& z%;GEnpbWhIgi8PbA#*L+QVBh$`tW8Mz#r!qcd=pEt1z1|hx-Zf$Y)f~8gA;j|? z)Zt<^ShEjW!!-clHDFT^V^cPJk=0MIFnJ>x71;W#YeIL+fXO(T@+7jiw< zy?WztqB)%7IiMptq=OKq(=W6wAEgVK^F84+K32sJ!BE)rfY|KgJ}Z*td|r)Q-q{;`#gMzvGJ*h$ zcL%op7tGD*bWJxBL_rpWK^jC5O??mQ5Y-?gLL^kxp)TrvZWEj>l|+1>6RzVs{$?I` z1{r6$2n_3I4(MAq?7?1bqi*b89_H+g>M#O;EFfe5%G1(rw$yIQ4SwxIm+hmOE0W%6OLJu|w|MC#~*RY3(#o?Cq}J@80ccJtN+l0G3ncW^V2atnZh}@7adtq>jY{ z|K(tQAf_3Bj3#4b+u^Z(z6@W^4nJ=YukG$$@ykB(2ok=Q^Xld9xBiYud;aka|CjEW zHS+&n>g$X1{A(kC+qzPN05VAO_@1~jzr-QG**1UgI-lMWALuah-ai6k|Ek;x@A651 zNHJgZEKBo#@$wum=*k}NCT|~yP7qRK?@HhC`L6XUee^R;@!l@*rhe*xq3TkHhf*V_ z5kKt<&-T;D?r9J90e|vNFCb$c^%uACU$5|D?Dy~o_=}(HVL$nlFB{-)5K>d0d(ZeD z@A!Z3_BMR=Ef4o75AT%^81v4tW?x_oO2DJ9tzJ(^S?~Ev1o~$!`GZgRIluHZ@x$85 zokmh%BPzJB52Ufbr?yY~C71lfOZtWH{JY=uTJhHTi1`JE_JPm&Yp?v8{|EWSFZXi~ z{n5`KqmAfIQeev$a+`1U=Pu6N|KQB8m!_ZlYd!Y$-xqe@y9fa_iXZuIdi($ZK;S@v z1q~iVm{8$Dh7A#h_!q+AM2ZzHUc{JD<3^4hJ$?ikQshC15=Tzd@lVIei4M#-V42Y+ z%$OHv*0gvNXGNVmVd$BmL19mf-NLy5NpxpJr2sGEEOKyF- zwJF!JVqbP8SXQgrkSz4*VX=@cLk!`XL zRI@Nc4L3xszo`DJ>_Fz$YmCJ0MC=a5k1Ci!4;TV)&_sm@_$HhdCIqZP4zKcXM<0I# zGNvAP0x_xtKRVK*Bsp4=Nf|ZzX@&|~dJ>@)!ue)611X%(v>=xn@=GztB$J^qYbuho zDnsN_#S-0olO?zCNP(i=VhBeT0@pOMOXtcQ=}bTeB@{?O|5-}YHa^valeR^1dlb?} zGb$mo&FqX+pyNQqZ?ZQAyim^{*y3Y7zn9WFUa2OaXAky-r&# zNL5oELiJZ+hlLJ9*}RN1$6Lo+R={SR_0*!DXb{TQXb-9-!d;a`(N|&<3iexZ$IU8S zki2E~+CJ4~lv`duatkh-GOg>bZCwSG+=|TAw_kq)HTEiWPkL3Of@OLZM||03sL}@K zWmurkLc3SKZjt?WA$~LFxMPbp?r30W-$gLtE#3V{*5I_vDbqcW8yV$ZG4|LXkZZ;{ zXM%3tNaTu3j<}|SAtrev^Qc8Q==MH|dEtY6CYNWO|EKO)>WrX1*=d=9E;^%l<4PJM z2qpY^#Ebu=+G?uT)>rL|utw74tS#P}>y9vU5!Ofp@W#fb={5-NZ{23Q@L>tBNbrt^ zCc5qvyS7MW;q;EUgmA!Nd2YLBMtf?+4F^5c&rzcJ)1Y}fJzd8i=jiD4D8C3#J^$XE zAjJ<4ICR}}9^IkaVPE~b;MaOqg}1;4zM|ujquuPMOV_#g-KRG+_o;q2Snjw}Cs_N% zz5kwjykSr>(p=wbo^{R*m!5j}H*9|)?86>DS-`c%=(m;2k2qVh%T}N5pvODwQD*}0 zL!gif_@M!=3v$Hc9sq@x5!Y?cBK4}41R?mm|IS5kfv;IXDN2z*5{l}BL~3BW>gT8k zD(rq1Nx|_n*N};+Zgul3Rs5DRf?M3;1SJHbS5Al%95xPrFLd4t6QY3@k#B|!S)L7# zIFKTWZiuZZ#Vx)NL@s7ThY6{owH|1{+Lh5El1qRK9Rdnnb+3hLbV>?6_QjoG;TEMB zKo|8$5jt{kf>TT)5(7z*3c`^gW0RsF0T4z)^>HH%5P?E65Q|%^V2_tH(-mXFNGiSY ziGMU>03GtR^eF@ZHM)@-yT(aCIWi+mctaW%Vu)K90+Y9-ib)nD$5koObiM@8q8#Q# z4O%H2-l&x-Z^%oIxe_BafWsR$pb#kB{~{I(z-2ZE;!G+s6Ln)`Au!oA5y@rllL?XC zH<#H#0_yTK18@Tzn4k~?P!bB-)FwCM$W8}}v!99tB}1l_!D1d{Y3c;zBE9)9eOd$! zaX`Z?Yl+WnHk6g>@uUU)si=(dZz7~jWJ3@c(m{5UpEYYJLHaO?F(_mMkzB|MteF9d z-qNBARc1m1D$0^3#9@~r>5Tf8%A6|lqGU?xKr-QpQE+4cS;Rt3F?rLIaul2=+Nf0- zl7JS`N@#q#QkD>ERGjuJsRHSOCxG$8g@_=J3HiburFu!K?v$r@-JlW!5G8^Zl_BXI zYbcL8rn3UT0Kf3WArvxzHNfGd|0n3-2yQJy0S-HmWDhO*+!FE(6aQd^ zKrXP0cg&+0Hjtli4XN4N=GM9c*(*?{v|WaPz%Cd7?mF2=T&dt-wQ!K7LTDLV_9pOV zSvZF^;tPOXqyr3Bhz2zBTUF{-SGoZ0??5)p!9giqtMPp7Try1St80AR`cDzEA}KkPHAY{DTAo zL5C%xJY$Vs_P;5%>-b zHz7=5LXRap(LTFxV{N#`1q2;mMc{)V(?EqmED!=>FX10Oa6qz^y=-PT+u6^CcCtBO z1`b5q+SkVRv!`9{Yy$VEPKl9$}%Cr5e8RlahTx7_6~hk49pK69Ga+~y{?gC6oAh@1CZ<$fqfIC$=J zq8FX!kNC$Dh#dk86eJs}AVxc?F^PjXW5WPwgggpP7&R8L9((Bc^#Lc; z-U-tPh7**`|6~9-8OmT}v`43VY21SHr;j#Bn29fAr4zg91j&bp1=5OW7zFg9Cp}l* z8($N&VjK2IM=Nxhg=NG89?7Vt9zTR#6fF%!cofxs>q(5?tn2upiFyDAcN=!Joxgmo|o zs~d={;|dJZFaU6ZVkiS400V9y27&N^cjyHrXaZtj2bl1I%o74Da0Y4+2vH+7Q$w{} zDvU!o1hz_u#&WHMfUN-}K>Irg1Dr2-pojY!G5$inEu28D5dh$j5=b)$|M4tLO9)}` zH-S(E{{|cgRJewL5C($NiXuC*s~ZS5zy}5ZfGqe29uNpB_=h6^05;GE0}zNZ=m(ep zIDwNxBb*KDkLrx2n;Gi!D^r^&<9L70!5$) zMGy#72!hH0_^ZqPg~Xoh9TBZdS3huk>I!$h3GfrOg^9g8MeLx>-HtB-6aun4}< z8cDx`!0iBmSurOJLFDAhb;gAH-y7ROpVAyi&guD|GGqo zNn{9GvZcqwnUD;}%1lm2qYXfK3l>Akfv6X}@JtSzOu`tnnY;!euz~JeE+x2!U08x9 z2!?pL0Yd8sO+W%GNQQHmCQ+kBTP(ueJd6=YxGvy`YPu%lM5(0=nd{uLtt_RIl#1N~ zs_2v$&}cDJbimgbG%rxfV^cq8Fu!H^JpgC}YM6(1I0hw{$9hxB+ zpM;ps1x?2-#g8KuPK1anL?~2$X;MmE)H!WbocJkD?4*S_$1khYOFY!QhywgfhzGDn zg@CMEkgQIP8aBO}KE()AJyjY#C#m47;2;2B#V9a?8Bn#(L|xNX?TSNSwFleCgLpz* zr7>N_2saf7V?9=2ZM3Wiu%G|{Zj}oYxl$};RFksQ(=Y;0@B|}(N=c+d=d#wp!Pd9o zRXiP4WhGFSSg~z|)Lu0aJ>65Y%-5|$4a7psgeZU=IDm!7fF44D|9Z7oXWgWO?L_9x zQZ3wxE(0oZ9SRaLFni%wgJss?vRJNw*5Bla38PqI`BYU6RVR(on2@wLz0)dF2t0u? znq5_HyjPYuf%{~L0(jVjpvspOmY6Nr9_83{l?pV9(VWfLgV@m+`%H{Ay_Dq&I#Vr$ zU;;P5GlYl$N-6@S{S~Ig+NXtDwmpeyc^#aspL0c5QB_w~Wewj1&VxV$I9P)uMO!}& z+QiY?U)9*QEytK3N4dQ$zBvlJ{aKJ4+>@|?K3F}45CQ)4zl3-KhYQ>|n_SX4*&6Lv znN8f2I6i{_*(qC(uxbFv&DznuR<2zQK}`s-6T8pdTC9}a|8Lz_(=FYOsK5&>h}GT1 z^#ClNjoo!^4Fk}_SBu1|JczhbQr&H((Dj|djS;G?+TUGUmiR&eJ6`TJT!T0$*j-lU zU5!Kd1;vWhSxpF;x`i~gUc$oOhS1h=4OoFC-}0?lkT@FXRNej6S%erV1c*uiDS}`7D-gR3iR^vkch{6+K)~(_kMhJoh;=@)%yg2v^LerJmqRMTiZ^)Ys$Go7N9^VpQhl=P=@p z0Ki-50IJRps~%8u_Tw*evx4!C(@YqN# zBMbnCa9C$uzU!Sx>p-3k6mUw+eFGkw*T1fhz$RUlcI;_xh@0i#x&damhTZU*hhE@< zAF<;%!g`%}Th3erShHNX@EN>XT4_r&I`UK8OjR zBp{e?>t68nF>Uj$Y-U=i51z?D5 zBaKABt#H`5Z~HR@CrfgJZ~tYN!Oa0{|h&hxN7&{F~_g zE7OEf<{WR0`X+Mk-R{9|i0}==|1S?9IL7MY-f4N@1vM*(4Y0fyuaBj|NF%KQ`6dW( zz6Czx^40M28SUxt9&v#PVC)7ZN4D$J-suEq?Hvz^Dp0G5-H3kf^A2%zEzNKs5Awop zi2V+3^%>bJ4RDzaFMhx;edGrXY3+$9YmMmK{j7Av_;VlsWI@+-0Kj2Gw=ABmbv5tt zhUkY=7l<3M2UWjxkoaPSsDU(S!h=ZB6^(VnnDr08?_1||g^=R?*=@@Ntu)8lqpE~T z;0H_y_e!t?W2gpWhjFg>0e6MhgxE2uJP1mU_QIIx>XQz1-?nvu;ANiI^<)|D&sN@xQiZfug|7$uuUB{dn1WIG+Jvz9gdhUX zHTt8+5K|`z6G(NZ|8;!#_D#=ug3zBCu;#oUC-5HhBsXJbI5cK3{KGf=vCofH1BU13 zTfZGt6>WRB*QI{gT!Bb}z`WSH@A#YpZ4%;|E1%|;^zPMolXWy zAc#po2F1^h)WheCuxaiG2mk^H5-e!&Ai{(ILi`Ica8n0`5+^3q@lOZEj2a6%Fymk& z$dCg&eiUgkBgvC06{eh+V1^zU1XfaPN%N+_l&-?@!AaAm&z~L-TErMMA-p97mApIZ z^dv)vPp48e@XOO7i4U06Q26DRA*y1>k}YfYEYyYrH*gTx!_t_tMbRDvN;je1yLE@^ z#miS=02q2^|7a+ix9>=g0lI~Aftcgp$B;`FoLiP26@paiNv0aLvr|c)bV*DD2aQ4? zw_-s6?fNzB*dRX(R5l3!iFWDiQ6g&@@nOlq9}n+aT;K~mcv6@>ewSp6aNioZcK$r_ zz~5t;wIaC7nQWZ2!=H@uE0Y0*JK(%gkZ?e(TTjT-uW$eE_;*bJJhEnhO*Xz=Bpi02 zSx47_XC0RU9(uf>V1WcW5JNb!yp|w@lo6zzSX8l@-E0dK&u zgF=RYl_HHb+8EM!_3!`yF`EFu17~A#c%6pTMJQox#c4o;9xw!uVUiw!!qbIE5*Oi+ zR9PWR|2EU~g2as)p%|u0rlp|}6t|Qz0GVyNS>t%uRKkNiTL5qcI|3R7oRxeQX<(mv z4TpdXF(rT&hK6~>SPWJE+1X)PzS-HBlMZx2A4aIh-UA6i5Z?-xiaIK2x^7wq!RJjK{Bk)%*Y`6!aG4JQ~4B_J5+btr@b4hD|O7U_UyDZqv% znyBF(sRUIj>L{LMqEG>Dz`;a}w|tQ;y6KjMq77E8sD%;=l|cp)Nt}|;e!HXt#ud>( z!)vsDK8q}ozaqqf9(u4)u&`!OXrZ$P8`SGjM{Gk6HPq0fjS%W?YiS>z{DLh)Xq=`H z{}yVhyE4l`eH;=zkA#p98v-fuj}{V9tSGQo_AGG2kCwpXgA7+W09S|GS$YzeM_&@$WPMOBPL#mGIk+!QI$20l%I z@ec_Dp<{{80UJl~u|E%PxX}Yu0Fw*?2ue7Fj4Ca0WrB-^nP&4?EmgYRjzUu@=AyMz zEiTj&jw@}e4qH^cd;mZ%vCAI2L{!YPPdv0Lf)7E{pmLA}Aqc<3KRq~bJo3pazdZBJ zJAXU}W^nL4_0?P7eDu>_zdiTZOW!^C;AgKq1%(n8KKja!pFaD}b0EmFAhbWf|N7t4 ze?Rp0E8m0VRKa8CK(+vn&8-X!o&ZJ$Ceo>de5Dj!yWRlhd8u@a>C%l zAri5OH55fSXko-9GO>v_d_@1I5)5o;VE_Zr!ZmzBKy@+TDt%DM0oL#a5hP>;VvERG z1o01ZGzNoiM2rSEvJ77At#1PP8}Nh|0^%7Df8kr7ALj?iK(cR;g#4ra9Dpzf9ddhy zY$W$MFpF?}0+Q%^q$RJ1N&f9=EF?HaKk$JMei(yu*^1+vGT|+WtYKUV{|Oxy&Qbz# zoRESRd?PN+5|wIXte3u|hDMm-i<#9705{8-LYg*~MDc8Clp9);g7q2-j3XS4njAJa z6h*2ap$ug>f>7=r74r`Fp3B@Rb5Wv6< zVhF?o@92dRnm`P8l%y5fD1#5K5ElUWfF7z?LM8UGRfGhzWg>_J{~W${kQJb&3bL0fuIfvmk812Lk|*g@5b_095z~IG3Q0cohT{*ciw#T9uHp zz6p&9X(eh9G5}bj1seaThFz2El<~*|OanoJJoGf##$Gn207#A=m;))uEtE=(rS8Nu zixXy$x4h`si|1+pV8=fP|H6oNNY`i8wQkTDw zLKJ#=PceL!Rv&NC>2njFN0X8otPa7Knk3DD&bU zNf3w?{t+)G59G;FCJ2H3FT?#U5ly8ZGZ+m-~o*` z$feMA#&a_TO&m3t?@)d23?Gsx)0s}&S28Y(36{|h|9*6=7wh$j8ve15asQ(q`*6<( zps@@x^QRpvq5wUJy$OA+QFoDZ=lk$eAj3 zo-?wKU2Vevu~?Xu%uZl2@nl~d01aPBFp{Bzd30rT=7R8XIFu1^J;MH9PTTo4X#r~&N|xBb=$&1I*|159wwLR08YPA^dTghJlAGv2uj zWCGv@#h3>>{;SVw^fSa&U$D9|pfxaT>J1A#h``U{ffG_d^yXipa0eC-Ym%Q(LDHo0T2UIr3?Czi6ltE4=BU{hzq$O#1pK>0+4<(6SPAz-~%ya z13UN}x@e%fn9Ld^gaO3Ie3*qj{Dbvj|6syZiWQv&2l|8ub|4Evp$pzbax6y_I^h+n z1O|XZIJ7_(-oz7PVgKn8CJ+NMoWkI3QF7G)9K-<`Aw>9@1vUJ`F(4t;p~xa!!#&)? zH7r80?Ot8Xoo{DMSW z2$pOR7XmP6V_pfgaHx zL689(P{9~L13J78L2SVySb-NDgFJvFL1;lW@Pk6KjS+Z)CoJGeL;$Fm#WnncT}~xc zdKeq*Lo!rLGU$UEsN>;y|7APUh3gSST1rG{7Q{~U#Ay13SSn&nQkh;I1PRE)BjCj} zQiK+;!aC5yFbpQ!T-ii;O+v`Xxs=5z$|7WL7>ZnhFl3A{Siv81rE}imT`W#aI8In{ zrdg0(8=WRXXy;xK8e0mFTOx$-CSbWAVkVIP+1_s zKPXvoYT{9vMH8xKYJ%Ze4(gaDXN1x$u@mWAwj15RLgfCs=sB_xCb zXv4Q5L_bIaLb8o}+6W2&!!L|L_eCT@gw5ELg%kXPVD2Y>a*iJ9(Fc^@Rzl}U#u!>8 z2MuT!Xcp)^3h6}L|6fiJX+9$9KE~wkse%{uz!ofnJ9I@bkdP*ffe={1FxZ1n9z->Y zXn(2;4opM?x)MT!PH>JzMg9Yh%4l7U$F}{Lobm%YY(gm>#eWKDfI^}zQUzE>sFI>& zpdy3{?!l4nDNG_NS~6)u48uC$gE|a@&ozS<0e~u?13s_=GB9UyjcB^~AOookSyW(` zx@j(r$0DS|CV0~(q{Ad&0z6zLp3O_FR1ev6-s%5c? zCZn3Fr``w(ASObH035)<8ybWe-GXn41wQ;kBbe%&de|}$+d#CzG629LRN_?RDW9_A zW}Zb&#RN`u|L1~^1%=Q;b@u7HUYnaPYmG<(Ff83~oy?iuLM)L*HvB^Ya_gyjm_2+c z5^#nO1PQ~@Dhk@GOP$4IMHXttt61zr(j2PBQX33bCcEM`DW)RA z;?j6@3kHtAh$GA+~! zEp`DZyi%-KV5ehvtko(Oh0?_mvJA{P=&lmP%xLWicG#5zR=m;n?7uHX(X;TEpp9xmc0E))Q+;x?}1J}%)hF62&b;l@CN zyk4&Y|7%E`W`n+~S!!;Qg6@)zVOiwi9`<2-hH27y!sna>t#zJQ9Dz8#Ee4^851@kF zpu+LxC}J2b6c7RM2CwiAFYy+y@gDE-K7koL0rEDl^FFWfDlhXwFZC906fllkvBa@z zujn3xk=CoaR&3XnMJuAhE5@R3s!kUiPy&%D94gdU%r5P&PS}D(&Z>mbKEVp?FaP$h z|Nbuk2e1GOa1fY55DYK^C$ItsZ~-6i0zdHo{($*J!P;`~$3BG$UX#{_FH8x<{Z52A zHe)&(pz5lN0(en;y1@e)#3?>3bnpC@N|kYeFhIlLEkcR#ZeQdt1phD)^KSzO z|1l9i@DLaA0uzf1KtTm(?AAWTN`^zAZSanE<@l1tMiK-Pc%)Hc-|DDR>m~%K9>h1^ zLa23Jk%i?U` z9)%tM@gDoJE8j6J$MOoa0F%JL3J`J=XYK_bMQKhb2XigHj>TkFrY2lwW|FWMbC?5G zn5c@yB8ZzPt4@vx8Qcj07ptqBL5A_dIG#*!>3-E77t8*|r1=0ZONIP{EKk~lS zXb9XWC9e)|f+E05B>Ymv2{E5d-!uRW04B^sKlFn=wB|z7^HT`5Q714`&vhOX5UVyGORyfu!8!AFI{S4ziv=)( zLe>6tAd>D_d@DhSE4iBMsQfmKbhSyKDH{I+cr14pONLd41awn(b>lUE-*qe#OAGw( zYmfJLPelOOqk%sgkIpj@GOWWwtf;tmia>TIqruq%z*iu`Sj;qg+jo0Awl+(~e*gD$ z^Y@8EFm|y302erI$M#J`$2T;~i<5UqI(S*gEJ2_`&1S*Pk_v^J|44~?0>BAZGaE$O zKAl(#B!~mKh@Y!-<3x$0xOM+`|EBl?yFi2Ba*KC2Y}+_Zd~b~(xcCmUSja8i_JZBw zt==~FGGovv=)x69#26O@e8@-qx^0t(_?tI3Tsy^-Q#Y2Q_MjuM5ipJbyEr^EI9X)y zmy>x1uic-Y#O>zp?%sD@kxVAH;j|LOL_P&W`~$n~`I`heOOg2UTDfWax2j)xl?Sm! zC%Ts}c!QJ0PEGNm*SZy(d2yQhsDz?H)TdZPC8=AAuUABr-$bBCccI&Lvj?zJ53r&W zHjJ-Cw7r6NGrA)u`$pI>4wLH+W4c`#0ry3AHyT6-oRL_Z|Ion|d#OKp#7=rcn*kO` zfxX{5zURBX?>oQud%sVC8BBq{4?MvaJii0Hz#DwO2eN}8@U%0swo`?pKYGM>rU!F- zMzFyf-$NYFvA9dr`U1nK8-$jn)j`DcROrJ$B(uA>$+06ueuKmbm_a1eyv^S{&gZ<& z?>x`*o5y&3d9 z;0M0o`~BeaJt5qI{6&HkI6Tzn`mUG7wNtg!m$^1!|2;_5gEe;yHZwN{fw4r0K!yW= zuu}y${DUyKz01Qp-&+1n%)KMf0qn=V?9V>!*S_uFKJJ?V?(aVD_kQmCzU}`35aod& zC_dxwGOa&;qrX_yE5EMC{6QG>)^|)obN&T|{5I;hx=#f&{DaYl&`maCwt3Ue#f^q~xAsGMDBY)Ie{ZmkV^FOD>OS)NL0zhQbB9Durc9j4mRJf2~ zLx&F`MwB=)VTgYrC}z~Skz>b(27Y-uG;u%;hox>|@tASfKW8gp#*{geW=)$nD_+Fe zQO7?WJ2~bs`Gk9QHtk!OZSAha+py=)ya@+jn%A$Ny-j}+KeUK3apRbhJpGa=!p)lp z4GrBg^!CWVV~#0xiq*>F}Kh^er|4aL;%8xtr$it7Kxbo_^u!3VQzUkI#A)IeOa1cHSRfF)p`8bTI zz79d_V}yy&fMbn@I=JPQ4&M659uQ%S|1q%-N83=e{Qk=ksQ`7%kw>ZQ&;t)aj7o4p z2FtS0I}CUFBpg>JVv;l|N7K+J8L`})b<+Y^^Q+`KQuRNo9yq$KC`j&N}_OlhxN;RZ0-7wCdBhKgUW^(B>Lt^eq>{@uq=A zd5zA|&>$@pzEhQ5sf%B9k%$R6+(>V|wXz7c*=^NiHnCJ4TlH1iVjWkia*y&Ow>u8B zRlz?4h3Ht&=9LMQa6X}^-p2M#|14QYQURtT+mnL;#mIcUy4Pu7-xt=l0@1a z3J^0Th_&6>=;(B|3**Ez?wCKP$*n3+JOWY5P@Xg3^ zpeEnxX1wiU`)&__@dONy)MIZaFN((8^t?0&itoJq792p=T|*bQta!8f){})xnQWTP zwh07q!f8SB-lrtKO0=&$|GhoEm47G`Pezfb1~fQbXap5A*vX22?rGk8oKoLu0M$S$ zzjeD>hkZx$pN48c-P*PNU93^o+W1H3mnkk;G^!jY{cpPb`c>#{A!`U zkQXTl&V+(T%S0a-5Rn3y2R#eP%oldjgMUC{hDGE^4Qpb-wO}xV8+2W)@}!5Vf$(d&JiL=q=^}K!bJ2r zQE;v*T&<}1zQm2NA^fw6A^#h4FHmd*ku+)KO#DYjjo9&fUV6g@7J`CX!~z01amGKE zAxTjxgpxABBTn>aK0f~KPP5xhR6-~g#TD{}hm}D>ILae3&xkn4 zMD!xU!-WhW7PlY*PR{X53#ABmK?^ldshx z0K8163E%0MNK&(o#4KXLJTZlcu#q7@#ECrqfe?Dmv4)tK#yr|#3?(S!0=sy}Jc?lh ziD1(v+I%860k@POQEe*Y1j{Uq^Gmzj5&*IY2Ol^>(z}SXalstuM65|MT|h4)B6tHD zf~Jr!+yW6e>Bm1l_y5u})-V~2XaW_Gfesb{U>E5C!xf@I#E4L|CKl}@MyZmNK0*W4`5>0AWu8K%k3EYBhVY<3hYeZ5CJkT{2mWITZZ%>lYw!;) zXel3TNQe^tp@pd?4?jb}>gyh>6duhEkW%p|pa>b#vf6U35P=+&QrcO|iFSW3^{Yc- zIx&!V!e<*XKr>fh6B~re0;io}DLdl?0GNpc3PFb@8e)ME40j3t=z#-}n_T5Cm$}V# z?sJjL1II@8eAKP3QP#&U*AxO0QwYL$!5iKnJOK(FfUW~LUe32Vp{QvHkzxw6xf8FcfSf{0rHu_jz7oq@kc zNdq9`B>+$aJ{B?!R5WB0p)&C!%#dOgub9OxcJYg09Ag>Jn8r1>@r`j@V>NhC5IOeo zkAWOyA=4NZ;i!cghMZ(2FPX_RegtDNoRc)p(E=eE2}IJcsfFy6ZZt8IJfi$RO77wu ze)({SN6Zl664$r@cC&J&+ZyX?aL$7}%G9Q~-R_E)&*U{PbOrooLBm(QgI=x$5VeQ? z7TVB_4s@g6{AlD7ILrs0@*E{GiYP>6T5cGCLY}b6Pt!yZ|2Rygn`g&Xq{9aa;jM3h z3lXZ)#Q&U&+*nvVMpdw7o zBpHH5b*d3ekpZ+~9Y~;0VGoy}_jky}`A|76_!Pha#RCIXZ3eb?Mtf71(htC;Z zq5lvE#mVssQOtc7L|yh&1E~b!v8D6jgx80pE~Q0L+ahCI}S= zvVOW6n%KmQNJvBBL63+|H0=$SGuxvg3gBV9eMRvDEbLB>Q1s|28x1FH{(kJhCmSb_ zTV&$7PpC2$zf!(X1pp@BkVm*9As=|hCMd80R%9cGyFEt;M6Zx^#2Nsbu!e^M&WJ{V zrXJz|>h0bV;*Dlv46rWu+D6`Zg8af|?W`+SiYy#v;SiVt5t5@EL}5;%sH^<$tN%nu z`xHXuo^9k>0CA!b#?0rSx#L{;;&hkKxvY2in2hZje5tAsO6a z1Ej$hvOo)n0UI!>7}5+00YC|v&eRyUZpLsU z$}lF*&}r^O6v{y^rs565LHhh7yPA*KNKlpl?*v&6lB5j;bV*VC5C-$mA^&2rIMm=D z_F)?Tp&#}kZax4Smca%S;t|>*uK<7o=%Eb&AReZ1ANWBU8vy|JPa*v835QDx=}E4D z;b1btpJJi|LL~`W5pP~mBc5?3X0c=FBoXXx7TS<0{s0ceK?7;y4|wc9?r>L_(SE`~ z7TReUUvML1Py*BB1DqfvonRV*LAOF68kzz36rvK=VbmC49uxrpmOvyiK^~mI1W4~Q z5&{}h4~^()wMLOVbn04Sf(%0C6#MaL{xKs0(jx|PV}8UBREQRSF)9w>?GTbS@GM6r zQg=ylu;v>q!`)4@k%BALO>d>K?uIi2I58u?qL^}pb3H@9{+BDAuw?Z^uZF8 zpy{5@C+TSn2=N4gS=zS1KIK!s4sHQQ5*oN+tdYAH`=>LP5yU}CSX6FXJIGJ~Q!BP&4s04w+7 z50YaRT*DVv$$fCe*if@<{*c+6EhbPfv|_U++Um6M({y0(0RIwVr%HjsI>N%5;Xl>p zLy3a)JU=*Ma zexZOG;yLXN09K%x@X8|qN(fX`DJk<}l9Y7_^s)Nm5bRDo_hU1~p(>Rk1nG<`P4lCM zF(EQEtz_bBD5T{!6i?ezK)q*4xdkX6LO&fwMPiF1k|0!Ya!Yr{PalF$H3Boor9aR# zAz|YXCJq*&f(`+RM@!~SG0Ozy)GRTyvrdjfMU^a%v?E>AL%URs`k*iyB18cIB~-*j zHDVb40n8M2QCn4MzLb2z6sv6GM#EwHbVLowp+=QLUH^0g*f`Z)A~fWPF;9(=@eB{~ z^wdaGb2d?pQMUz98=?T#01Yl9GgPF@GQt2tg%Wm^SF^J+fAxZb6{Bne4jHsZ{^0Fi zK_Nxv`ku8&JXJy|Qd>L1`(zVH#i%}4)vvsDTV53ypcEq1Lq%c%DJQ~A{vqtzbz&M; zRaFC0Uqv>E)jW@N7nSwSge1?}R3ZabT0@mui*zL0YjJ8xB zmaYnE2Y!N9`7mRm&XelOaQ6pZLXkNMLDgTJoSnC8?PnNRU@Lv(6W#d#jPSpiH zq6B~^W@@%9VRlq;Hq795RFpHQ8lps~&RjhuBPKx_-S%yJ^(~N=B9u1R=wLJN)oJzh zD88xhVnaOv7gPmzaZ!~coCJTk)@JDwNf-7$JNKnRbf+lRVj&__25WN%25vuhB0^X1 z$h26^MGeQHeRNc^Sl4QW(RJq(j8>uql2H)57M;GfTX&a^nsXrv-~dlRMO0)wCc^gi zfp|GKe8op@fg*XSugJuKQgg%)CN4C$%5WfyWvTZx2Uc-cVs2XQL z03-nzT#q59j+xMxOd`Sn-~p)Iw|LpQTkT`ey zW{J@!Iri0Q;E)!;DWlvJi$4`>Z+9bRcr0s|fNeH}{gI3XFfzbVA+ih&?h1YP%^^zd zA0%pykJyouD2cNPk6|Yi;t&y_hLpiUin?ifU091@mvA-0i@#WrX?Yl7YU)P2g;*cBfmAQCN zL79$pxKy6!7m64F4qyk;;0@3=h!?`z{vlD3Sy`0%G)A}=P1tGH=i;2$&H}lW2|0{k zNS0?=fhqKRb2gV}2nB!v7|>Xf;ozYy0ewZMAvPdXf+3ze`CYx#j=>a0AIo|1S57?W zo>{nR{ds^1IwDqZm$n(3ii&Jo{ws!Gcnyd`kaS?ikY}ykDklr3T4s79q9U@e+ zV5pm=s7Iro^#h8-;rhl!Q~&8;WT)ArrP`HU+VEPirNKC1aTjd6T7sSjtUY1V03gdA z+7!^2ovke!)OxK48zye~A>5iaP}qu@BD-oQsqcC}d{nHkSxCd-`>^`2y*9AHSEi|H zmkk@4bQ%s&L82L=3__*;BAZm$TJ4USo8C?oG+U$oxF|?DSxXwUTlb#F1q1D13bDHxxn88 zB1-S{da_T|`+vGSp8(*178`vj3}ctj!_&LN*Mhwp!o6?pw|8`0d@(63H9S?EnpqsB zX;+LF(KYjyOms+6#BIRfC1`FwrSe~LItvs zJjny}o2!bMJEpibki?53B9+2^DbW1Kn4S%poPVtLJ!pRwGE zTKtB`C@#Lix&H?*t6^yT#C*8O+#yIn9v(r|j~oC>9nQ1v1SFiMgxtc>7h|(q)+GhR zRpr*lfR6k-^35&(G8)Z?6*w4Kfsd$un;7gChrM}^#9G_rDC*Lx&-p#n{-65c!Bnqhcs zAR;cjp|4Ng zUg-UU=&M2v%K>izf{qzF1PdBGi11*cNK#ffdSiFc4fCDoQGJ5<7GNj0m z8~;0EB;YEXw-zH?y8Kx3rOcTmInum|Gp0u!|8(H|2{fospdtQ+7>YEh(xm_-d3x&U zl)rz|Zdr}BfT`B4T)TSx+Op_Tup)W-BpWh^8Al1*x_t|m;GuHi5*ZvAH*O$3dI04` z_-9r)afb@x{rh%d!-x?lRurid?aRmj0(=Sw&V}TRls7}R>A7WRi)KTc_AK_a>d+p3 zJq5<^AGSDFtpZt%JGbuDsaKa?t(Gm~;fO^IK6se8K|y)+*il~a(714~3`0+-m~mr@ zBS+_^%qLv97^=PFHow~Y@7?T$_HGX!sne&*xWR#As`i)o{QLWV`QB;kofh162LB=? zSao+DNXH*{=y8W12ZkbECgfk05lK#bzzLpLgQ z>M5q7X1i0Gw(f@Ox2LhPYC7{h^#&Za=qGNw?g9`lSh}Lc>#>MADvGezIjBb-hW47s zbmAzwkAp&F~tDP`z~1VX8e@_$gJuN0~fgV6el^>W(dbB z@42y87=u->y>ZPIPGQJh*W{Bj(-Cku<%se}!3<^T5W+A?92x;JxIz~=d^7;6#oT&n z@yjb~)$-L#T|mvMzTgSKAy9Qfr=4JHjkb$fb7i$xG4Je_apEL2EL@2$3ilxmizCXv z${D=fV*oTzf(tS1!AIhJz`{oiF|<$u)RF}NLJKkQ;fgon0Sj@|+W$&D@kec^J=EHy z2bIjKr(k3O$)3a!t5qnRPCI<2Yc)DoZ^NBXf^;iatQ|q~t_CdRh*yp{w9LYM^Rv(b zee}{#FH7~-S5LhxwP?P1_ug;*jW^wlPk#C4dxL)Z>Zkur`|iIF&iCGY;sVm9DI6O9 zo}qbG?OfgNzn2)`9jju4N5ob#b+Ide3_J}0my)}!?2dN^@x$>5cBsGb%U=`}2(n-? zo$rZogd{AXc)-yOS-1iep!ftRUf~K^(4rghGocM{D8E{`f)6f0fJW?>KOhDXbSkQv zw;H&V2O{w!ida=U4Db;Okc@1pK-m(nNERg~C4yR+U(glPpq#gx{$V4gu1;1dMJ7+lC!^qoi%jui2c;CO-y!C1enDfe z00$AH`O%V+(O)lli56e}(un;-jYn7k%Vkl8>b++$U!a7iDYLN-q1 zrw{fl=smNk8dfgFmApfQ&upfzylha6yi4bB)>*W6CjV@nV2Ni(IrQcMXRHu@ZrZq(rCs{UbvpLo@!I?6b$9Jw7zdS3^JQQYFe7B1+GM^fXTaF{`af~YtV@>z45_{9IM zYo%7K)ELWC%Ojofw7gs7@Xpqli@5C~mI4M({Gx28aBrBcsYNavV;%oc!$k(LiFMdx z8Aw2~V2RXC6aOlfZ*5C+pKIdi#s$Eq760&Rxg63L!`RED`SWj&yeAXfwi+a0N_r)H z3tUwA&BoLs8BU>wI$s16@h}4wj&Y6)l*Q7US@MDK1(#v%cgka|a*D6qXckj?YMy(v z=x8ljOt;Ad(^%Cz#=4a>yEH#UCiN-tscHZWU>%nT?>*WuYXk!-&~l|2B66LO5gUuw zR2JH=pM_<-N?Iw}O-jA(J#T!&*22p6(EuiK+kSQ>y=&IdDMVoHYmXTx*%rb-tZ)%$ zw8A462!X|y@Q)riVB;L`xW_*Z@{o&s<2)cYQRNmFEBWC;Qf9Y*3kHcP1YzbhuXzxj z0EG^W+yNXg0|#~v^q>p9<30cR(EpE)bfWt_=}bp@(VGtSpg;ZNJwWzg`#qx@aAQ^Z z-~w2>(1|#(mk9~aB)07gfGzxks}>=~Fg&t}+pg*nW~jT}?~eDp>wWKh@4Mgs{&&HE z0`Pfn?imP=_{1xI@r-Z0;~x+C$V-0ml&?JGA7S;$F5G_uz{G8hVF9%K0-EcpL)mS- zd75Nf?Q92t+bM4G5MW&6QLnuNN-i9tYL>H4rb8L^z+aau8ZL#1xy_G{bDfWT>b7q_ z$C>YZ+e1J4wVyuqp>BN#R9)P$#kz}%v8sAdVKZQlgN{;m`X!#-A`XYRMI;_>+}IjA z6hdywmqTKgXD~xnhIg>DJpXK=V{8MM5lOZip2rFRU;?eM4fc=@tuPh?rGLHVZbV~R9s+5RmV|n>giJVW2ACUJa1PdxfKE^hWgrA#zzxJ; z5gzaky`Th5Kn(2A5ty(ETOb6Mzz=0$5nHein6Lz!kPl8E5+(>AR4@;#!VG5<8hyYC z>oNo~*g#t30alQLmS6=u005W(4`o0F#t>^ds2cM}93BQ@Z*drhHiSgTfA4lM@m5{= zh7|WU6r@;+qIin?hW{!azztx~3<;PKY=93em<9i!hyXwZ|8N8zfegK15yOBC7a;0xNe3G8qW%a85`)iJJ9fw-nFll9$UCs~7XzVgCANv} z)`><)T^2EqKoOHU@s9M^j;(cU-KZvQa1FAij~HPB=&(8#;RM{k5B#7FJ>U^-fDcVz z5&2+x7C{N^0RMN>IFV@60mpD#l)#6p@dKP7O|#;Wv;&frrjukriHPwB;B=Bf7$Gak ziC2=2frEqrSVVStmj_lWJkSmp_>#l>ji6 zuoscW_%0ow538~bCJ-Nna0~k}mZwve7bB8ik(PhaWGAVKaLJN#>4|iCDFpasH`!gZ z$rSa3Dyg;)yZI0Oun!6V03QGi%OGnO@d!_35fnfV;KrEqFbNp3kQdRA#dwt}V*mj6 z5Bgw0{DB3xPzqfcnkzG!P)HM}nHPhG805&BaXBe-nMHh@N5Dat}0@2V69Dos(unu6u0Q2C188{D=kP*Xh3>N_n#26Bzxfx})Dx2^h zMi7?anKt8Dnr=gqJHwWFk&^4lp3uQ)b%~#%VxROzpY@rO?xK$&APv_b1UA5kr9|3D9m*&l}>WCR7GS|g(RX__T! zFNyF_<5W(`1()aO7A+c^23Blt`ld8CqCcXK(m0Ju2>@f@3>CNxT3`{$cw5bI5p1vx z_<#*0NS!J(0G4oD$xxjC(E+*;Q(fw%Qu-C-ITPjy7r#Oa61AEt`f@FaRPgyjF{*Db z3jd=|IH&Mssd~}_>aZ&JkOe)02_H(SD)XiCC#J`8qHwWmpxT=4`I_&!j-hC(qd229 zF_Scks+bx;7}^z0a9hD(kTYTg`5_6nimR>K70&t+n(7v0S`JRu7PO?M&_!3n%1*@^ zpU0Yts7h?JS)*YFty-Y~AM+3HpagAFMYaH*+G;Dgx`VmLJLm})#bQq9N>mDq5NzsB z@S2x!DzAD;uiQE#4!{eywFP=o20Q)WiJBhp6VZGWG6BVlK$*>CHp6lwO5}T?J z8?kZQw9Ky4rE2*>v;jpMBx2h$x zXL7atrnmfod8^W(wt@&TH439}0*8w#i92qKdn`tq5N_!=lUq@4t733FwK8$LE|I&s zYqz+&x$l*=IKc(0LJifqCuEQb{aU(zfV!oky0u2K2a>ji<|K%gvaBh)bWpjD2D9;6 zF{)a#G!?uzVF0LLpyDzJrJEnAFbclayn6Dy-pIOwvU_gvd$qKGDoeY-_W!bR`n{Pu zxATg%ohyhZP`XuQ3Z?6m@7pHvOE1xT9mj>H1aUVinZMY(zy8<16YIbK+r8fUkpwJ= zmoN%dgbSq$2@Kr8BCHf3+!AMN5WbUcXWD!Ei(*Y{yS+OZIxHGI+{1KhlLE}S#tX7w zpuV@jzN0_^D*Pi3jFu3r95iDWfbk&C6=J}8y)4?Y8I{98JfB|7tljIqq#3@fO2h!m z00&IEqW}g>>?2M*lJmZfUA08EG&bNP`c|GoW*~$#Yfnt9X!UJEP#Pr#)Evu0ILM*i~kD=JPJLw$ZA8# zNa4aG0mD2~rU#Ltm5jxDoXIa4w|(qlU>wGr{K}*=zL}H>rEAQiFbJ#sB8^ObSuk%)y*I#=#t-t(<;yaLlFazRK($%-j_)tXY@XAfJlIpo+`t%Ei|l zv)cU0z%0lHHOyE<0^wY`A4|^tVa~b(#l`U`$#uu~N6k0%;QQ&1jR) zSVY3%90~sn(B3Q*6a5h|Obg*4$w0*y_&d#cT+Oiguwp#3+3eD0`DPV;MP0zpqwuI2 z%^m?QK?9u^;_76zERG57YdFl%^^DCgJRy--;F7WGRI8)UsF?anDp ztVP|@NiEi6ZPpbF*8nR7k+6(z%^y15MRXlE1zivajTqUxGhe;XVO`dO-Ovs##K23{ ziVfOC@!2@x(H^0xYbnwsjW@$V*)n6cM&C-7j*f34lp^e)PG}@IV*E!|b31PGq z3>~d)FR#tNm|feO9l*`n+iMv zw}luoS4gcQZ4a#SY-v9kS>MdW*eObSK z5GKi7{gT&{UEh4|viPmv5ia4f-QTwj;1{kGjD6MCJu?^NduDVX#C<_;duYYxb5KIm^Q;|kZ}b8h5yu2wXDTsgz% zecs^RecV+}=;ICKK~Aw-uIQcq5sY5ocMcfJ^8X4T&f}9l)KvcCv+d@YE!c3LF>>zd zf(Ys}F6swi9OO{a#f|Dy?%kH|>RF!L+kEI|_vN#`%C$~kzn$mdPz&oe;=L}azrN~L z-s;2t>cx(FiH_|5t?V22+s5$?5W>|VF72)f*1(SK!oJ^_zT!jN?a2P^K(SGbrw~qUhoWj@HoL?hj2W=H@o|e?yAnc)?Vlmf9)?Lg;bdF@_?kO42>TD@y#3ZH^E_o z;SDD3+77S9@T|$|PVoZ&&{muDcT3(G!T*Y`2#XlO2=RdEIj`tDU!GWP9N}QW4Uh5< zukw7%>Mg(S!j3Wbn2%9^5sa`8=#UP_u)u?e^Hx8$Sf8mpEeO_93s8>cLXXKrugkmp z!vWuA%)JD$7kU}NlRl~TZMXv0-R>gmbkFHAKKV+H7=o}V;4sA$is?6eUr=YU_QsEF{OO+n3Z);R z0NRj{vrqktKKCI3>j0orP2w}W2md#rZ|;zl|W5ngjgA7uZcvIDOIji8RB0EmN8|{q*>GEO`JJ(?&R6C zrc0PUBVNoX6k-lDj_539+H@%(J>SB;a$42uRjf?SWaZk`Yu2q_xfY5fWyM*vX;%<| zBH<{d~>BS!$ud#} zBUPF;5T0(~YWWdc+G<$Ssa2y^-IT0ZwQAYARmj(}ZOXWFH?+Kvw?&M-gJzTfs^XSV9$NhZydxOp4&!=DC z{{4aSA-jhh{pxf*$_Yml?o9KpKm?aMur=_)Lu)qjDl%`q+bFD1LiQ{KfIs|@)2~Ai zLlkjDo<3xZL&p58%8xsu3TKu-68vgG8MmV`wFVtrYrNVt+zrDEk4rDI_JSkPI1`Ul za!DqcOj0it7gMpRKU(xgG}3D9>P9V7(QcN@T$x@jp zIp-c}v`{EYy{3GsPyg#e8I-F+S7kN9Lt{&HqDa+4Q_@L4L;3f17R&o$FmkTDB`$q7E0%xCw913i#e9b zW1)*SS~;R0y5XNK20}%ef-DGO>Lvc^!2ztZ)_QBMyY~8Pta&g45=R^%BoA=H87Gvo z+jjeHxZ{?4?*F!vqWf;V^Pbyoz3GM|5-gq&d~m{_fC7pRz;=KGGdNKEamXXrnsLV^ zxBT+S8^?U}%PHslbI3jCx`&{TPAO^AQ&$}_)Dv2|X@QsY9sxYS80f+zcLau%CxL>bHM?{`>d;e*gw>e`3?001bFR1p1GF2|VBlI`BXU zMi7D-c%10ucfqV#5QFm5;0EK@K@WZogbpCx$&`eNe{jSEt=NV=($R{b03Zv?hzC59 zL4|=(!T%ZeNXNbg!Uk>J;~HcDUku52L?r6PdCzPyd1Xb$@XRM# z_ib+{Ghc!6jgkqFI2w>m_F$Cg)cl1IDO&|t491;R{2%`yYsK+D(vW0zM zVhNkbhZ7XC#3UwCkqJShLE3N+Ml7LO&q4^hjN-+eU{WWV#0e)m3C5g(GL%@%BG9BL zA`fr_3>z^B8}PvZ8UBL@0-?e`jsO5kz=Hy@(}qBXfsBDjgBOPk-y)59%%K%CCzUWv zs7B?zpOKPc#_^<0s%cG8_Dq`56p|^K=6*qYeY1L^}*3wW(dCp8%z4O##qInGAHH4?Pn# z721<)(j=%t{plCcq|^8CpdC20Xnv%TjEZbP8otPa7Knk34FF)I12HK|RmxJA&dzqV zo2gCBdQ6lX@(ej$)aX5t~nX%OzJ8VF_K6P|JX-g|Iv?qC;$K-fW|T^Dv(FC z!vF%I06p3O0C>uip7zA2K=k?2_Q~|DoAqZ}S+Z8Sz7?*bC1_85N?M@Km9DD&tME;R>Hj@FJ8bKUh_7ImGc~{)dVsI zXVh>RqN3#vpGXikYy%(IAR<2z{9^Gb7$ppDZCfdPVY}iu#}K|Qk9%xmfza4=GKO)H zk3{65yjEg9ZZMF4b0wAB&^OCD&}M>joC!@3E*q`SduDWR7H#G- z8#+xo-Y%spJ!cGKI@3;0bkQE&Xi!%w&x`5wj_Z8IK~GxKrcSk+3sP#1eLB>$R^q6k z^ykr@dWx-{a-n@KXh{E4*0d(JP=+03T$fhTt_Jq9BmL_`_a)inJ9e?Hos(+w;2&Ag zLASmAZE%NM+~X#9w|nr29+X?%>t^@3&zbd-gSe29qj)W``Gh8M4In>;tS{b5t)9wEU*a+9RKI~**DJiyN`YCgMT>Q z|33G}FaG66g!~{{Kl{<&q4vZ7{pqKF{q28${O4c)`{#fE{r`Ue3_t-KKmsg413W+k zOh5%(Kn83;2Yf&XG#XC<6%wlqOqhmwXa{3Zg5yA;ajJ|P5QcZKhifpp%20q!I0t*+ z22J=a$>4%xSciW|9{?DDO;`teSOz433>cKb^l<=GxCVMyhhVrb#^}KrGzeb!hsxSB z6jVVLbU_>Ng>|ThWY|H0;01252X{CI4kQQ@P=|jY0ePYZeBcH~=!qv>!4?#VDXhXP z90)DsLN6o;M!1H1Xop?Mp&jZWpIE~vbVDk%LM#M;Isfd!FO(q~vLU7d03G5XDAEZ) zY(oHeLqaTw0Z4`<6bK$bhI(iRRH!=u@B%YL!#_+xHk86aj6;IR#7(4vVMqsi$c82y z#ZpYe=t`DlnIy|d21aNCDnJHw=z!rMBQxp^6F7%n&;lP23CqBQcOZivV1s$6gvlU- zQ`jpS#DsV-11dO%b2zNUz(#GPy=7Mls6{n{Mrou*YaD=R zaE2^U0$vzKftUm?=m9G@hIA0DfiMPS7(;>Z0eVn{C8&gb7z3WL$7!s_8r;Wz{6}I0 z0D&Y(gG5M6SO-NA0xBp2+RLLo>Z6{pNPNsle*g4Gfb__LEXacd063B(Ie%ZY==iMh*}Z?mTCqtU`PN! z1#B3IVMqp^xJ-cnOaRbK&NKke1kHaCO%tdGFffQ*+NIM(uAOjA0Dw)|#FyGEh|r8B z$E>AW>P=p1O}~82%-l@l{7iwc0(G!~P5&eVexRgDkcVADP1R&g=)}y}q|VN?P5{78 z?W941*ac>Yoz(Ot@;oc_8JXo0jwAR70<#QoYO2b}22~)2cBlrRqzp_rha_;sb{MY8 z*hC@t2gMKwXSf%|bkBhRgMK)^op?tBU?0SUd)9NkeK zEzuJNQhQ=iHD%Mq90*}>BRU-j9slL5*Kr!C5e@@DhP~{KiK-}8vW$DU2UM_vNw5c8 zqznTo`_al1psR8)n8?)Y^_oN;3$s*DUounuG$H7oz`7t*K5tf=-fnJ zs80^~2O?V5foRreg;q|L)?D3JYb8%!_*Yf^FRL_Ifk4>JI@H)n)ZW;IbD%oLP%5U1 z)XK;QXc&lAhz84OgLG&ED*sr7cgWPq5LHqgh*M3~g*XOk;Lr|DpDSPoBc#Y!YZw@S98_cmgU-`m0P+6fHL3)4-g1| z6Z^VD ztH7!Zbcjw|S_jKW2TB+SO#sfBO`iyz&>OYT$8=8zFa~RY(pLolO8_jt;)io!G~2~p z-3@^n003#&!-8n6mH(;+e&{QH;Hym-RDmeeop@f5h~DX~UW3410B8g}X$L=Q(yBGy zoFHES$X$YvUh1`8f>7VYa=gZREckuW@x9&hz2EcQLsn4U*5!w00Dw1*(>cXaLbcNY zhF$~CUjRs8*8K+t=BjqksDY5+@TK6hYD)t+vC0^LR#=BZw2auAt=j6($q{9fnmOE(jz@+n1_` zG!%l_V&5%zmLLSw`pk(b-qtE6h%2^Ag0KKBKF{3*029FCTrw`*CF33LVS`BHEKbAT za>3vlt~q|ro&P9f9zNrN&|@2D;(w@w)a6d^l!xpKV}THcF}7nW&SNZ20UeAZ7!|ikxRz_W1^~OpYrRgy5aIo4{C!Ko;JxP?9OiO-fr&hZtwnX@D6YB9&hq4Z}UEH^iJ>Y{!{gCZ})!hc6s1|umSUfZ~MM) z{Eid(&TsziZ~tBl14vMNum(05h{L@HW?%%g-E8qs}RfKh510P_6$vtr?pYry$0D6EO0O*Cl4CPZ`NMTS0 zr^yC`*l*1R0MfC}Hu#4(#suWzhLr*d9Hw$PpL6jxsd>2bdB_K-F$UQ!1BRrA@BbAD zGsp*o%qKYIZIK}z6P%|cZUlG$fDZVFdcgBMq;pHZ^zGJyfAE4M==39)B|bOsKM!;O z81zE7tV37aM4!{DwNXZhhf4ehMey_^=wwX4bzFz;54eX#Fo;m59WwlKr4BcumTgvzGUxf zfp~SqGRq{Of<~y!X`gp`SHJ*`|NZ>^{r&&^`TzU${QUg; z`}_X-_xk$!{Q3F$`T73%@%Z@o_xShs_xJzy_W$(s`1JPw^z8ri;P&?R_4W1i_4V`f z^YZfY{qf}S@$vBS@cr-N@bK{O@bK^N@B8iJ{O9EV>c;=%zwPer?Ck97>gwp|=;!C> z?BwR<=H}z%(^)6~+^($CP)(#_D!%+1Qm z%E-yd`^2;Vxw*#1#>=Cc?q^hH%qoJXppP!$;o{heqjI5rU{FILUl`6oS ziNlhCx|x}}lzzI9c)6OIxs`yplzzC2aJP$aw~KH8et!Rh5C4Av|8oHEd>hSrXupDF z!Fff$c0-_?p_-bSqmrkijF^>`m6DQ@jg5_%gOizchKGlTi+`DfgoJ^Cfq#F0gL|5N ze1LmNSIEe zm`$>92pmYTpuvL(6ADb=#Kwz<5F<*QNU@^Dix@L%+{m$`$B!UG ziX2I@q{)*gQ>p}M!$|^#Fk{M`NwcQSm<3*d=)kk5&!0ep3LQ$csL`WHlPX=xw5ijl zP@_tnO0{ZI5HAYc+^W#Yzpr4!iXBU~tl6_@)2dy|wyoQ@aO29IOSi7wyLj{JrR#*N z-@kwZD}1rHu;Igq6DwZKxUu83F9iR!@z2T1k~c2hxQtmd=aHE=e-;^fG-=PKKbB6d z8a3;TUTsL8O}n;25dU6S-OanV@87_K3m;CLH(?OAZ4!>0{O^J<3z`Fd9$h+D>el^Y z&%Sj#_nO|n)Bg-FKH>86=+k%j*CD<8_weJ(pHKh$`u6hA*C$ARe}DS_0SMiG1qCRd zfd>w_pMC^3NYi}|MkwKg6jo><01)PvTZ9P4*Wr5~f~cT_A*NTNi6hd-;Dr=s$l{AI z#wg>A3b_d1ivFcY;ECn&*rSd)R@b19;t?qwjx^F|W0FiZ>Ex5;E$JST2t;7zl~`t} z<(6D_Y2^l8Y~baXWR}?_m=SOYWPL_**QRxE!nx*+8$v0cly>H+=bn5XgeQ6{4$wjo zgcfS(p@=4`=%R%l(ZmsqMk?u~i#mEl3j+)}=X`NW*J*N}g1YIHb@mx0d#0wU>Z&yU zS>B3+qW^G#nY7j#0R|~xVC$~D-l{?hMYN!)ki$wCYHi0NJ8F7JvTB>F&PFTkwBkYg z9fJrIfdYL6h@e%3-4=jC5eV$KEPTn*mab&$vU~2UrBX|qwer?$@4YqAn;nA@6mbE! z-bxtm1x2J8q_OY1*KS}7Go0|X@#6cJz7kh#vAq-@S!%xq%NMS|-g0a%u_Gf)GMf*h z*YH-&Ui=`cF2^i0#xTdnZ@~b6>tMJdAFSrdCh&Q#dF7bLE_-dT&sMj4xrD`s)d27jj~Cq3(+dWBfCEo0d_Ry1 zIrLPM1wx;gBM&a8j9&U3+1P{5GZ~B$*7E?I9(J*;qb@e&@UA_3?X$P<{!Q!)c6$H^ z)NlX&_~);G{Q)Ed0yVc-!3ws(J3i#&8B4&z_IhyyFW>_Y0=We>un+`J++zp^xx+m! zK?GCC!+Kq7fj&5K10`re0~+W>GX&TG(1omX0z#j{9Oo$-ib{qk!XbBD7q|Gm?}tG2 z)6)Nr#yNu>;0#Diq7s+L#3mx~01EjW0IGJi-337)wxEXw1mX-^0Kf+P5SBomVG4s# z!;1o`1_%Mrgn!6}Af+3K_=2Xo@{P}YDv})Ld>F(&0+Ek@x!n<+NXSAyF^YJbVgczf zkWp-7AiC&U7ydDiO3p(cy#RnEy$Fvz3?vn6M8GrT(Thu54FGX;VF7wZM?2oJm41PO z18l=M<>>Kpfb^p-WtU5?%x{0d45t11mk=pZv3K!k%ZNQXtMBl);;fOV_`3d%yKb$AH3UheXqJshIi2EzZ! z^gN>$0y(DdlsS;W4dEYHfXNvLqQzJjw zY-qb%TF##MOli|lYRk3t6Fs-E#tl*+&}0h4Zw?j6F1}%h96aF@T`&k9?7@d2jN*ei zeL^T2atC~H0RW*02N6>8&28Ot^I6^Lx|hB4@ojbk2Cmc=*SP1KEKCS+g)@+$9mKd{ZP#1R z=)U*BGvh5xo?uWbR3Tr&U+gh6R;0$E|L_2&TVCQx=b_zzYh?x{(^As^>Aj7CR zyG!8;-}fL6D8m_g@QQXcqQmO_@E#33;vV0t#0X(wk05Jfm0^+P8ET6Q_caHR)@@$Yjm*<%ERq>h8 z9OyE`qy$JT0RW=Vj$kyWmNl`h(OzY1hKSrq^LK(p;pr`jxdv(tY3o&pbBT8 zffB#}xsPav==-+MLGr zrne1~Cr4Qz5@5%9Bkp0*GTY)nmk`Fm9DoTJ{pd(fy3&_!bYddJm<3ch7PZJlFM?5w z03f450xl4L`-R{+Y_X>i4gfWufd&K7K|6}!^a=Oeee4dp+_y6H>l$nV=FPj__s;je z=Y0Z*4Co>o`AC685&)C5^BnuUy`_)7+7F*Q@NcT>w$Iy==cve{wc)@U?#;SRefd0KxYiZS_|2Hc$juP!EMydc{|MWe_58 z4^;Pc5h#2!r-Plw0W!t|1wjHJB>|x4d~ip7BbbD=gM_t_an@07rj>)4mtPe)g$7Y* zRUiNbL26%Bg!p%a(5HlA$Q>nkf_z3_w`PVEScO)|TA+3YqE-;Z#$jIgf%!LvcxWF? zSZ-iuZ8{TNQh0f6D2UniYr%F9;l_L(*l2f{hmQZ)9A)@_LxzTcSb4-Zfni651#yAj zW)Kg@Ty@BZVEBln_$+%^Qg(-8nWl!BsENZjb`>CFJ#Y{Tuns#Hikkz11r~;-*o$;` zielA=QTT`36^Lu-iaSV%15s!5P{2JP^9(HMH`1B}(!izS#X+p>)*HZHbyiTD_EWyW8Jh!D${WbP+Fb9P(q z_>QDlf&dUJv(hUJi6ywAD-9WuU4j9>5-hJMf%zzWoR|<(He2gxgrZlF2I+_hDJYb3 zk|^0IkCKus*^)(IDVTDRJcxo^2lGpf?KN*zTAV4edd$u4B zTF?a5Kn+W&i&vS9b19B>8D8TBhYG=k-^GreHI`&Kl0mslf0GY)AP_|G4^psT1G#~ z)LEU@d7apqo!N;2Uw{GH`JLbyp4-nDI*`Dw@pWoS@ zAMk_V84OfLpW!K={P~{?a09J*ZX(&6`^QHjAP<*toXNSI1|gJSaS2~Ap%hx77J8u= znxPuHp&Z(w9{Qmm8loaPq9j_PCVHYMnxZONqHJ&mYcK~KY6rGR2rF8nHmaeQFrY~@ zdIs8KfTWzKIS{JJoX!cI0D7bg;GanPpGvx<^Vy_M3ZGCKrR+(bR4S!k&~0W=0^q53 z>CgaII-OG*rr#-`a!HW9*`o(3k{W;xn*aj&UshOIQ;i#$KfoeBV0%mY_GZAhcIjFk% zm#FHK2&t!-Dw}(%tlzXV(2AQn7TB^>vsd$B%B}*{6G)v8oRSA5Vd=|x!bk8TM!WX6~QaK z(kHoYJGuWGz?YjIZ)gH{^)5Kj4(YI!%gd7oaRT6g3r~;(Td;Bj@x4QUmfR>EbMO!R z@WKD!5ByLr8$b=uU^s$8FqHuShpR|eqqyKV5Wd?1z{|g-=)VI@xy_2a$?G1K8Lc4_ zsIi&125}05s}SFdn(46tNYKPcU=6y!v*#NP7?2R9AP(i?wbfw?W7`WBB@hdh5RYra zDTTw83%5ILxo2D+Plka45h9~H#2QirJ@Ehq!Lq$z4%a}l2JyY%Kn~9^e(&))=bH^d zfR=p22}=KP1fq}+bMQCipbIfe4}2^IBSZwFu(Lf&#w1C+EMvTQtGuDi!?=hZz6z{w z{4T;O$D0!tqfij{a1W-i1eahBo>UM-a0yKy1-PIOO<*^8^Sxqm0|EgJ@n8?taIpO9 zuj3G~12M4ppbg55ww}z%cV@|&EK(+1MwkU`IQZvv8frqT}uuykqYljE%aQ^eRR*| ztj!Uv!~C2bW(S1f3^{x`(ad5}yl}(-kP7UK5YO;X3|-9*?PCyKy>wa80=&l7VThcU z(W3uaZ1|ju3E>3#5DG$o2lViOVJpv$_XR?L1hmi(S}@Njozf$=(gS^~6n)eCTpJgd zdY89n-PiBs)}sv9PtDDb zO&i@-23Eb;%R*`aCe=h_r_1)&l-+8UE!Y5@!>#SwwsDiQh!7pZw4}XHe4W~eI@zQZ z*rhDdgpJvmeb~r#1q^K0%VM`Kz1L!?+xoZKzdhK)E!WX)8*{4=9m2WG4cWeZF%AFi z+&hNad}!Li4cyaR*az1fK8TYEfglDTy)m%e5JTQO%G=-#TF`CS!hPB1ecs6t0Gnq3 zFo7Umx_xh5+S7R7L6_g@-QWBz-TrOe81~uiJt{&h-(N=Gk}ci}?xXe{mzTQPB0l2f zO&ex6+XFr-|A^uH(%lyG-5tJ*L`>cK4dDlF<28ZURdC$cJu3AF(_5Y3G2Yf6ZmXJI z;xEnONG=$iP2oLmG;K!CO3qnAKIG2E;P2PcxBc2c4j3ms9-ESA>#%539yKmrF)(iB zr#<87o#k!rc2F%CI?m%MZZxE3YF*CV8ZI+wuIBa4;la4)texZ}9^p7H6IK5W9-9)! zc|PA&?&p$*<#2xFH_qi{E)!p_=th&(mk!v1j#fnu>309m>GOgHP zZZxq4ik;qsXD%^)F6y8T=mKf#4UX!)uIh!3=o5Yu0n(MPH|yj5=(x^hk`9?6Zs@?i zDu+7}3Y9~2>30%AF zdeZE(!K=iMuG69K`_8RQ0II+Wc|h;=-tBt!?f1^_&O!0l zVeuF5?+(MMr;K(Pj}Wmg?(-z^G^6Vc0t&343J#wq_TGNqYVdCU<^cb&aQ*o424U?JdshXb$myVFFg* z@d>f;m=N?&GV~k&@~htNRId=mcLoMr@j$cg(XR8&%_3Cr2;i&`n2_>d?<8W+^v_=D zIq&!6Dr0}zI6zbIFu&^vPaq}m2#x^t1;GNYzzR%|_auh(1rgcg{`Z4!_685&P$uAf zUl1X$`JSHm`w;+v@CZHt6RNNZbU^vfX8Ey3@NHBRolXQP@@Yg&$7DhD5s2W!8LC!Mm>O2>Sh8i! zc8q$q;8L{>k+wbf7Ou*ma}mm&ivGiP|DluN8#6t#NGvbCG|V%oVjjvce{kU)Tl z2vo76qgeB1&Yj0HK8skf;lg!Cn?4;=GiitiuAHGl8L0p2f+X6pn^2l|ThX3<7X%Gg z)-g;TL9tTxTlsS4%@+ngY;rSev((92zm7UFc7{~WjB()dZIpJx+H!Z=+qq)sYV%l) zsDKB7hfG+lVzFNTe*R|Lk5w-(?d(EtssarhP{7?N;^7Q4N|5QTM%sbpyade(u)nkZ zGwTFoj!{CgKprsxqRWcYFhvztBB!LX%7c!4ipaBYbc)NQy!^68AuS@HiZiM(z(?%_BW%pM zw6wA&EXRsKA`>2QL;Rf$wQA_vg>r+P!BG0^8;ZoI9j8F~h z1Suf;;Sn-?MK;;afUT+5uvirj*6d_;Gqs9bgH5(u3!1RPU3rsE*_4=d$_QkTx!|D> z9(kk!ao>fvEOK3P7C~yaly=p8^}RRNio63aOxl2Cbl>#Cjkm>+G(%vxE+Fz0q8vc! zBw>p$wrJjz>U|1YzznwcMvz0EsKE!D(kXyq+R>rleqTfwTpqIMpd->asUwa-28E6qSOv4K z&%U_pkvNvRX?|&RTP%-flc>xy(`4EpFxm-b#!IzEyCJoW8ZM8zAv%tfz!w*H@Q&Ed z8*a%bUrpK{ditqtgC=~%?>7NwTxh9khEH8G0@0QsC+-tFbk{R=oFm8u7CCN`E4Tf2 zhfJvT_Fvio!*gCie?4}YTsU`yha7O^5eOYB;KbLb|I>JlW=C{s+HtSF`-dtR1GZ=D zA|M@>g$I`@>P7FYixwiX!bvElT)%!6tDcg-ocmO}zyg)>~?0ON~^4%(3p z`e5yE>a!pI$U*}=;jJM#SOqB%U_bv3YDj_?(ciWLI6@L`M@*1<9?1aFj$atfe>e$Y z!anGd0!XHLG=PZDI=I9A%&;OcjMfVyS3(zhk0B-4Q4ih*fLFAm5k-994t?kmEXX1g zOnQVBc(}zWO>rVX{Fo58M?~~NaUs~ULh6tflVAYPjKhOq{k+H#Er5+$CBRd79#ViQ z_=$^uT-MMw@`-=Yq975l1v=)j3>82GjC2Fw8%-$2{xt+(dX!sGB(RQl#6Xg2d1T`R zshI|RNDB`cpbs$F5K^$>W`Kkxdq#;7Cwv1Nh6I2u#G!>IRD&9hBp$vfxxZnys+h(! z;z3N7!c4YAfy7XwFtZlN_09j0Bb_+LD>=fmRU{ym--OHHG|&w#M8l9E$j2QDLWF+| z%ORn(3IB*0$xoIMYDzRzP*&)RNlsIWvs8=|z_x*oP@rs60B1t|1JH`-A{78ICjhkY z4-pt79GqCl13IwLBK+e93jk?IMLJTFmeiytJt+phfB}@Y)TJ*?=}KWbQ<}zkz_|&Ki04gk;cvPl}6sS#Y>J5S!I%{sE0K=IBL>%A)Td|TA zic@GK-zM`)EL{r)^5t zY+#NMLDZ0GU29trqEU`|6sosHs!VYU)u-AQGpxWo&uK!XE*~5i2Ku(+NK>O zST0V78(o)5m73JstVV<&i>xk>UCdmFWz2?J^2(%ZbNB~8)cX&A@MEGCEyzV50?(Pq zQ-t+&AomIawI1n)Ji{O(hBCXj>^3ESPkKn=%DZ5cbZrAjfG`rQp$jCS(+=xw=X?je zMEwT%TTryy6)YI5Zh4q2^hH*IlR`m9H1L8`*dT*t{1Jv;B%-+t2QR7dOATN5!)45` ziKPjE%S9?i1nd826g#NmjI_WKM0kh+Za8Bq>-X?fWRP5fJQvv@r)%HWDC`h$2pd91A}DY8u;)AA0WbH zjDUhTSkz)fyjf*RON7w}LGecBHj+)(_n1Mf9e<6cKy{2*%%I$`XKHy%03cx*UI>B~ zy3vb*XaF6!Ai@!PQI3}6;2x$3LKCKOje_KW9;qn8Cit<1hg{ksU9d`w8*(QyMDrj8 z0L3c&SZQuE#Mx^}H3E}~-!NO~0cH}h(N@?(A&Vu`PZ?)9ae0tC;KQ3v_(x;_poD)2 z0RVT>4ZP0w2NxDmfsL%V@LP7Y9zmvlMRKsoCQnH(HT1 zC!i)ivE49Z^Ku;O+J#)=90l0`I!4ie3(#U4-pm0$E`b0L^x_!>nZ~^NAPhPk;H;d3ghJyIL?|45q_y>`z(GI`4v{ARMMJ2ok)}kA84N z-vG#hIr#ApYQVP}pD+j){*kVO(6$35F}iQ00JaQ7gafNw$OaDTbc{n?>KLJVPV5V6 ztGDF?X^7fr>cEcYem#BsS#4`?44i5-BPJK9hAx~SgGX!WsrC$*_WMkfCREqksQ>VlaUWOJF6m5aA{rQa(y! zzU|AWPYa{Us}{SsoHWpx)i8#3;HT^(8UyT%2aB)?LjnNkfNF>a3^<5QAcxxnfCQKa z_Dh9oFo+h&uv5qegW!dQa|o!bh!i-1h^T2!a)$!VMyVd$5HfI09XWhxgF}e-MQsXaZ*dhjcNvR3HLPShoM7 zs}h0eFNeScP}nvfoG~Dzz^jWsA)E{Tn!J=~0P{(+A>23%RE~(s0^frxLIZ#;n1*;j z2WW670KkK5m~MQ0b{ch00&%n zf*ja_AXtbqOtv*lmRqcdFR+THJ0ew*7*=S78X(67GskrFmsv!|vJf@8KtlhI=(^xZ z#i<~YQRK<);3Rb+Ef^f%+m;lc6B$zyy zBDg;REQoDLgvW#xQAa`f=jT6Jy?j`D+s;gJ6{3FipT=6fdI+K3U_e`6et@ekjm4d z%7|=9b#%z4V8^(4MUR*eU=T~mYfKRO2cFz0p9Fw>;4uKG1rESM#VDV47zEs$I@-J*;^Bpk zEQnONOoMPi7z|0dTuS}O!AE$&hA=2q$N}k0DC)FI>--QQ5jxw0IyC6@EP@r_M z1M!5s1H}j;aRPk^1tGu#deDP{I0aoOwqr{}e>6@&aYKnANd1H*{v<*GJyHMk2%a#5 zUo=n#rHFNNP)(ari_j7;$cB5^hN3KpT!@B3JG5(5mbtWu6o^BJ2*p6)P7+*Qj6F|CLsgxS_nE=g{XW}E{aoBtkeIT z(~A&*R&i5TL`E`RvvoQj&s)joK=~Cns3BbFpY>d0)uPSQ+NfYT0EO>rHC!C zBXwaHy=;gX;FCEl*J>iwjoH>pV%8~L*OZXSbeq;}{T~0$gD#0Z3X6TGgiV`+wToN? zh1PKh(=-uRDp(FW*XxW`NljUf&`Ms#Scdqo?p#=z_|@v+Si6W$hXAc(d5EP`g%K@T z*E!i{P1h7{*pX=8?*`I56=R{(6TnX9aUx3NU24pnWa;xwFm+I4uF-2wN;>Epp3SCQGcpj z6#)XUae?J=1V_MHhM)sd$PCJ*s;+$;%%wceCEEYO+zAI!)QCOXh1e&Wd|BZ|U6aM# zxfqWAdx#Q{#fLyX+r3@O9YoFDT)ypFl;Ddi1=Qm`2qZII#2j8<)m?aLT*oaPjv%d7 zfG_H`#pNZ5^Mxed-CMuC2=F142 zN1foH(OZVaUs&DXgJ{|BHDLfK-VzSm6Qf^jWDzb{--f`WNAO^S*a3u8h#IzG`7O^2 z?p@bZ*BqV*G80#dpjRYAT_9Oh+~yvZl&U}wBq~qU6tM89NCdK zY)}&>05lumAqJ2l9?~~nj-7=PRjA!IcH;_;+BnAHIo4q@mI#?d6B;#P5$f2Gfd$XP_*SVc|>6t-0mW?NJ~T}(EJ9{$p{SjJ1X-zQ~cj8WlGxR*NA3n=Wez2e1MfnB0QkL4@Mwc)4MPon?Sd zT%kIX!1ZCZNYLmFV=XRaa5j}&o{0a#@rdc|XY_^VA9CndhUWUM)B*ZjP6OXqUgu(N zXm^&Oi$06T^$2cifQo*Xe1l38o{niO9_NbaUMvmEvrrkYBVTb|Rx+NFLnXc}f(VLkYNwXRjpk^X zo@t5D-`Ge%vxvo=X6GtS)+*V8PUy3TxD!V>ActsQuqbQz^kx|H>4Qe=t6ta;>+7@@ z3y~gawWj5%D7-iUYLrOhN9baMu#8sV=fEx%n7%K_7HE=gWz5Okve0R{CT+qtX^EHz zT!^>>Mrq|J7M}I%DE92np6&lIE$sgN;Z*)@)mCdR4(+K(=RkaHa{lJlj)*x}hJ3iY z_bHOfmIwrpf=*b@g;I3QF4dV4K?=c>WO}GbtFo#kA zK@a+Fv&e*O!U{+5<%M7ZRiNSjX50)H)d64T0zYkv7|@Yhaj^j7tv+nJ4ht3dgl(XQ zUC;tO(1xGG@BnX)uL&DoH0XnP;#DPa0RKD{*I>~e?TAQPq<-g*sE-LeeFlE7=@f2TKE469^ZwjxpHWFUwr*;Z? zxCLrNhzk$}G6(YJsAh;D029b(03g>jm+eAFSS?3vCP#0YCg>^<0P=2%37NnwRb>aK z#i_XP5{LBVfPpg=5fXWb8sHN*b@b_ObMuvS0;lu^$8wJj7)?)#w5?Yxhw!H8hZHyn z6zGThiS@CN1zCv1hB&a1Rr6OT^d(2}aISS*mxx+jYn+$>PRdD74{lH=;#p@1e-QQ+ zv6gJK&6OTbxbg=sJHl` z!2hSf8Y7l*7d`rEpcL{j>dc3FEjE07af`-&r{nStVKzRbNY5R>J>&d75 zp&|E!7y|#I%Y350`;0em?R@t}4p27ndtbNUx(<}9I)+_l-}`83+OK_)ScYZjhh~`m zWnhMHc+Z8Xt2R5R#OZzZ0PVI#E23nQmkn4BF2mwH*)Og(P4*w9RT3M z<*!#sT(>@@i0FmOkRhh>9RXlVoR%ils7-wF@5RTU3>SP^AoM6fqDGMhRmxPT(}q3H zm@)CRV$`b+0k!ibF{{>%V8d4Q36yNXW||CYYKHc0!H^^2(uGLm7%~(QIXrswAtEVO zpz8k;E^PQPVx)2lipszd-6atD?hqvMPl`mdi6M^NY_PLu0H8y6E>Y%8kHn+3{%Qy4 zYthgSR~yz07hMs9M9|3&y0|ymJT)bfdE_G^9agFe0B`R6IdqA?0bIa9&<3Y16%pXU zcSOrS5e36>%KY;=ZPl@zr$;>2!I(2v0;pdKcY?ZhIAGgv-oCDFZ_%TKK}ysUT}IO( zNSF_g1QL-3tGKemf)!eLAzjlwvz7?vh-1%M5h*bbKk;w@Kz9aNbBaR`bns#k|J<+u zjWybMBaS)hxZ{o(e1QRvK?*r!k3SN5B$7n}nIw}<`nV*G4ODT)6%{mjWsXl`$z=Z& z?F`dEkXmjzrjlfuN#hOY!39k%2H7$Vh7&0mXIK^VRYF8l=tU==efn9^bm-J{2{r}X zv5iCx2+_nT=Nyq@K`S~m%0HD>ddU}=YPu<>oqGBysG*8FDygNKdMc`^s=6wxnznI< z8hx}nE3K;<(~dE<>bfhhsa~SyTUgjLjVPi_V-FU8HZ-TQ6gdG3Cd57RL$lRddu?1I z6;zK60Q4dX05%+0(KEMzCmuoMwfJHOG0u1jWxIofh_>cV%*Rd$H>AQL_9c1z(gQ#d@}#ahE12v zCN{`}Srg@01WhiI*-_bL=0ObHe}?r;*v~+(XTfPy$QE=*F|@Nz1rs4n*VADIm~w{N zQr(aS$Q&hy}e8)d+hR~T?~;bC$03q?`CCHYlTqlJJSp@d=w0!MxF4=n(kPzyKqh*Jv) z1vvptJn%fTL_q^^(hWZ3gi=rz*Wlv~AJV0LHUOX;)5%AeCLkMAR0giE{Jf1UX)`gr1L@!nt;6=&?6N^*aSbY z_YjR;Eem*QfJbJ~3RdJmc`ke*NPc%1{E>!!HMC#-##a;`^os`Kdy4|n(GDHV4~IGI z4Gpi-jAopGAShVkM>Nn4Ekq-947me75&!@v{G(d{P{Kci0DvOsBYF%ug*FP(3ui=x zgj8FA)MjeQ^Lpa=?mK%)pr@Et?zZ z@=kWH(`PLeS~)$_05+Uq3{CUTOFL39FsL)8+Vp8*Rw@)-XyXY37=RSAk&BMlz#Ih9 zr$IVUjb<$60@cuk6Qs}!ZA|nQ|F{?cn(&Y4ITWH2WeESJEEP<%nJgj!2!wGWf=4}` zw5}LSDO`kFn07)Xr%>}NU8bT2JK_|mLBYY&CeTwI8Wup;42uYu;SYS^qaVvi9Y^Ny z4}Ng=AO7G+=Qco%XXKM0moNv&8bA*`0ALjQD98o=p`Be8#Fq`JXa_E8SB5lbAP~U> zDHgKZ;Z{p7{W~sl`)AFak(052YiwakUUFW3kXyi#ogUuZ!@KG2uH z0H*@Jhyeg%;ES6Qx565cOR+?83VBo`6{(x`lO41>(a76h8MYt$EF2 zTa3i+_Q{k|%|;MbpySRF;U2aq!Vz>44+IzB8q-*UPTU3n4yJ+#ng}5hm6u4Nfj0FeX5(9?-iL1k!*<7b}=m)#oo!p%(N8_V- zxX*s}@KH>e1+`Y{1_ar{G~$5{Xvh-)Em(#;%7Keq0w8z0>s^##m5D>pbIWhsFXX1$m($qIBn&?G(q@a4m7Lz z*3In=zx;J9iFV4UOjnH*0FR=E3#lvhj#T@*;n~9IC+txR zJ?Nnp^mr)0(|qD~%Z6x>6ivRha%=(=qa9Je_rCv{a_;tg6O4s=k1GVIG zkdTAJ#SWDcyu)d(70km0>l(2=MsOdIsZ^yPy03g#cA9(0H*)Mxq5Ve60lUrv00^NB zJs*Q$Xo;BM5so+jL;~}3x(uOGor68OWlwgEzL^Q)c$wLklKrb{9^f{9TNW?MuR*TR<4AzCvAs7NC zAmOQ0t#Q)@CQ=4|1Oys{03`noNPWf-65$d8z>8%>5f;(>?b#@3gO060OE82lU7-p{ z1QM7-GvGrnY(qKZ*Z%e3*@S>BAVUZwSYJ3^Z=}LMc)Q57EfnP2%4##HQD zLqy>v1))QbKs&Sp2|!^Jc7z~0#0O$SMDRg8Tm%S&LNB184!+1M9%REk+(S0#L0zU#yrVS_1!zqAQ zD$qlDWL(rq9Us<(#~J_4Z0KUv$s$8Mp(5Jj1Ja{K_=H-G0z+`Y9Vo#TP(wIKlR-$q z9xOo?FoQf89sqd5D8SmrOe4ks0baO(M+8POy+sgspEz3BbbP}e7{nfY!_)O);;AHB zAP$v$T`uZlU&$l@Q~;grM?QAo3@g4<2$Y-UFaJ7JVYZ#M0N$+u-zU%=H!e)q>6~x zL-YbKOvDh3LO1BcGnAwz^3kTrfTyHcQG^s+LqE)1Q=ZMV z9fJ`>gaJ6hBY37m%oSaP!$0VPV-DAJ*a1H{L$Nr6K6oNoFrfVX;^D#LX++Xzq9!9| zpakTHxVdFJ-p`(;LKfVB6gLf>W$uLx)cY@{R z?O89713rvHFXUG=EENExLO9?5_hDSnwXUMX7XdgaimtcXsGy)`px01x0#k zex3~q_#~z4-DS($Lh{Gj>0z63O_}Qt1Vy2R& z*cng(hw_J&Vg!}0DzXA2T#nnTV#@+hnH)I;8IVDq8UzA3!JeSSGyFrc=qevg2Q)Yx zLEQfVL+ODC&fcKPnTIMXTDTdNU|$5@>qg+m5M?Kw0_tXXsxxIPwhU88K1A5a6)P+% zT5Q5UFoU|TYueZYMGnD%mk2rmIj|h7&gsx@M7;TCzm}}D-kZQis}Hg)QsiMp9_ra} z;xRxhL{vby5=7pu!uOHIprvWf>TKG00X|^EE!+Y&+yfnI!fPI1z1GE9>S@S!gvVKD zs21%+0PLUEX|=9wU8LeFwjxvBVKZ5RH9|!71p>+v1O+67H=>0KRLVq+t@0>H4xIl& zAf3YWStf+ukltPd)rAvG=I!5_tS~gLFP?5t#cfBF<2iakI;g4tq#mT}^;&Q3E$<*+1@HOp>Pjy~kibozrqjM6 z_IiX?8bnvprtPj84On0476cRM-CKCWaH{Y6ri~rc!!6vy+HFGI%rEN#A^mpLX{2BD zDs4q@MKEaB!0s=24sb_Ara@390#_Ii5N|^e0B<5~K@>nIOaYvR#WMVZHBkSs@utl+ zlqB;lfy{Vr^V-@6W5fi`2etC=L!GU+%`OcJYazym;-C3GQJ9ObOwbj`b!{xGDHwSm+=%96Y~PP zE=RQKi@fO!6W11;&_)zMLI_t_2=6~2Brc=ObPPZ!%!5DpgFO%>9h?8KC)aUA#N#t7 z^Fwq=I!M4NLvyD}^F~-Ire^AaTi1unudn3Uq~4V;P4G8Hi~?7!S>cMWtMFLpyW} zU-YN0u<3Th$ZoVdLqwmN+&=PjPv`WSxU1U4>l**bDr1Zg;6)okL~l8S0KUaM`~zR! zbm1a3M~j_4bEXbgZ%8vls#@q22elS!1;!fi#&)bzQ>_bW!9+8Jg89X=tWXW01v&gf z&vJF`dbL{1t^Go)-Bzda8a4A`L~D>HNPqPplLgNj#3}r2&?5h`ToYGuz%)S^99m?< zKP&@acXh$?Gg{28Sr#^0_S)!*Q(~hsLm(DA0P zG{}QA1V^Gp5MRS+U-O5$aQ!N_sY3Si+SDu(vnju}P6tKuPDJKzZs!K}mnnfPd`#9Z zn2zoMr!qw?{6jb_clWlgbAxqu7d1!V=}yCTK^Oor5H)s}HND2Sab~vioPgG3K}2je zVjO`QyEk|@_k7d0f1{reLihb{1SK_aGD9}p0=P!B@B0Ek{4%$N4O2@y1P_qGSkpxT z{KGgf_-|Y5gV%Nw=UjY9@qG*OwDz}#M>B_G#06*Y26zAPi&t0>P@6{30VxdJQ~bjm zySSe`HAZZ=jL-NxTZ8~O=@sm;j@vdtkN`W>S#|q&WQWBOW3qlNaf5%E@DNW%$TV4` zfFwJ4pFsIVNI6iGax7*QfrpA+QVxR`G^UA(cG%dv=Cm=xee7CyuW_yEdwEm?q( z*vk2w3-~_w_>toGY5SE4OcyR@I{hj@$vJbF@A#$Dg(aK0CLel*SuNHw#BM%9o_4?r zndw!e$)r;{ozQtdnsx(HxM9~Z2NaF!LU>sR8!=$`om2VK(#0q2axedKFsJ#KDO7qF zMEH(xL3p-Sv_PEeI)?CiS@=4ibNQyPnZ8~Dzn1?yo;yTigL|ZP za3B=sacjj2d^@;Xh`3XPooBeY|GGu|G{Rdi*R2C>m-@jAdR;)YL{F_46PE^Dd#vj( z0F>`lzN6;n>wIFgaTBZvY&kDo>MRs`?62HY?%EsS^WzMfz~v^965p`Xd_%S0Kkhq zbddc+*nQU3fD9}?<2SzJKR)C~zT{7S4SfHB;!i&2XTIh`e&t{OZ5&;>i$XLezg#R)*N!4sKQJ~?cm$~*th;BY5!AH zz9AHX`@cW@$G`l~KmFIg{UgE`AcFnxKmYeX{o_ACASyJFU_m!(&ajaIfMG+24y(c(&%8ejZ-@segun>QbJ_}2kvPoF;< zf;t8&qXCCgSgiueu*g4jOQA-UI+gz_O`SZePK-G-Ysng45Qz~xmTXzGXVIor+viIk zwQu3ZMa$MLS~zLWtYNgUE6T1V{ceoXF5QHwf&XemoEYL(#*e37g*@5jkz>eQNTd;n zio*`ASj||<>7P8xr%|VlDw(ol)eXOfl{=euTDrAy=e~Vb4x2M+3@zfDb+PK=6Mwa9 zMD;l8=8s*!mR^$ebn6fE2$@LZks|^QRk5P86xTm)*U_iHULA7u*RgZQr@dQ#ecNr( zwmGB5O(EfbpQ9{5hjeIX9TJ#p$+`jma!)<=*n3byh754z5fdCDg%zTJvgV&>CJa%; zsv=~}!PMZhPsOw7ThYZ9$2$M$j5fsZZ@8)$d@M%*d}-$u92J~y$Er>oQMD3{q-+I= zsCcBahA?48m8Hb_=aeL|%+jizUi!oudCXach=wAt1)X`8Q6ZxuPfO9oH(`9UzBunn zNRAr+>nljYjh_P*l@RBT955 zXZSc`iDtsdfFWDN(V~fJs994c>)e!6#W-cv4L`EvSmQT1#Ig}ULX879q8@!APFUxT zh3-{OC-an9sAM^&lZXhgkcNgtP=%BTfcod3C!P)WP-ja@;U6pj03n|{7$V{yDKIj0 zvRG@CkJftUyLBwz_#6MrS3L#gGuei8V5c2G1HEoYs^k?HDsmmh>50p3h^WaYrOLqD z6C&<7M2I&M;vXac(BdBv8VZLKh#u&`<)&^}K<1fguG!|Ban3pC*!t+%=bwQNTIivP zE}AZ*kxp7^pxgS{jWcHa8IeV5(Any%Z^qyY46yFnYpk{A+G<$Z@#X8YZ4Mjlwb53a z?YDEjVOfu<0-5fYqMa5Z6Rfy)ssy~fTk!R`tf_!zreO#Vd>pdo%7;erR`N@}sNC|) zG0$A{%{lMf^UpyKUG&jOFa7d5@M6RC)md-db2$p?S@ICNbj z4xp#5ntQL^eqVl>-^`hpMSLF#ueuI#CZeENZvN$gjGz*Ctdi*EesgJ zgxz&pR1e=S{F$M9=%HummhSHE?k-VMI)^S9Iz>uAx}}r>De07y5|B^?1VM?}{H}Xn z*FN@rJomHLdsu(0bDiJw(?|wptQnVA)QT5~ui>`oH6(a{7FQG+$H&`yu1y_eoEu5S zW!HqGhyU59*|vkvOsH7vBkSd32^0kQPsOej_V0?FloIwuVuIo+GA-0829K(&6dgt) zW$p%G1hPjHeLw?{HN(l-&(uX82C%preT3sIKLI@DU&6$ctOMMZdnMSB*HLk?zvoRE ze(h7-Pabk}X|2Ffm;wC`Q+oDjn)rkadymm?Ov3+(eqsNKeiilbnpFf##=snBF{H|T z$}(yq8CZR9peQkbYj8P)7u|bo{?^gh`RF`m zQORB8my?sd$B}+G$GJkCE(>~SvsvoLbIQ902f7$m^W~%i~i8LgoP> zPMq}A2dc6H^(r+YPPN4^R$c!{W_-y*A7VJCFC_YL**Y4M<+?R1fQ{xl-r{S8ZElLgX9%CKj2gEbm(HC$I z7AV4qn7!*MC*81x2{|=UtW@=*2#jQ!-KbL|0Q>Jdtg;-bL(DWP0p0l4?5)B&>jCEh z{Q~b?27&w+L&%9wJi>OsRF>B|qBQb)2e>j?v7syFC~VbPWhsj@#F>UXLosxa-HyXj zO%WYaYI;yn<5B-cu+DxY{E_)=ey`qa4Vka2|{ z(ftK(r^_+?|DEC9tiX0KXs z{As5mH;en?;+=m#4(0=6%2&&<_1rdiThs!mTJ;tlJM7tiIu&A`05>X#OT5(s<93XE zZl1#k$0S+?h{)J9tIHftQ?Rr^LwYZx_#zCK7Olz{tKSgI+<_U;2eI&voVCZ>(()&y z-lJYsd6pI%ysjV%4>sRg33c|-W&1LKk8)R%jE4a$BWWi6DgA2wzF)Te-6nRj8&h-_ z07Tq5l3L2vZJG}HzulmHC(Z`z-+*Fjp@nlO*!GsHAzlVV?Fi)(Nvv0t2iY^0q|uC_ zp;He=t4hJq0EzQvw)5y-FTR|$Gly#^5s{BfES=v_JHgqSe$T9bX}ZQ!flLsD=vA{` zd-lCY#{)M=i7|uIYa|RHhncQ-j%^+94u5IRhn0SRXn5a5P75BKVy~dn6}9+)lp0)S zk2RdotoHXDU>J~stQq0&^lm8wgi=*m5Z@Rsk&h#82dxTs5%4>`@w>gs?-m~Sol|c% zes0L{0x}&lBy|7qA^w~abzaOwp%|eS&}5j5-4%pKYQ&L+_K<-Z0OayOw`W8r{Rq^= z1#ML}jxpZwdLOoXeqD@SJpB3fJJHXZ6ilo!Lf(q~+NR?RC=n(f%h(P>sXV5u9`NVs z$>2*Q=h<2*>qQ9So}GwYs_BB;0hIb&+~6zz)GS&w9LS=EQ{W2JYKDbH;Rd{A?c2w0 zZa!*9*n6Hm@dg+9>nV4tfB!JcJ$}ZvF-y#|`(w8;{+I|ogKysL$wAk)fB};2a+{%V zhX}||>i!)3N(42!g3movD_{B_p_*wxu_@r8Q%aNx6_qY zbZV!5j!7np|^`I8`Ki-=(k&Gph2iP&;$}!N7aVoY7 zxBH%JT+ELUa;KGXquXz+z<9nYEa9vJGHjfJvF{pbNr@`r;Cq{nDQQf)x|9b+x9e)WE{`xY2l!Qns0wr4?IZ0z&6Nb{I|DXHR+d3Fe|zTQknyk~v%MCF)$p!LY+I ztiePA5D456Yiec0I49xyAyAjLiz)w0gp>z;;4n6tXHH?)=|VtKq%U@Sf~J?_? z7-!*=1_)AYXMae13PjU|sC6v5PfXm$%shNuU|ySGC)87@Bnp3i~4| z)IorU7c9>yT+sq{a_cC^fD9vLl=N?^eam2H+FOicR>4>p?c`L9KqhiSDMk=c-+s4* zh`a1>1KSrIDxD^FmDXG2yqM%dM8b$#qa*ehbm$W0Ait~O;Ipj&S9eAyrr(ArVqVgK zHj>qTLNh4Vs2=WQF0(h0*BRQfJZ)c8W0DLmpbf36!`4mlRMloe?NF;MA4Q zJA*}ul2`dMzSBg_opPtqlq&2OnMvL2$oH`xGwQ`gAC9pBTKZrvd$O*vpk6% z5aMgVvLMg>#Ed+;fbM!AAP?YsxB)MXWwnEg;_^4o4hh|ETEVyOiu9de~ z!e|~|WDs|NB3Q`F*~bxqZ@|4LN0MqEvswm;2SNbii0ADNfoX;dY9TWk6Ke7nc!fx#FC*)SjlQ0T2FZLY=98!u0r)lp!xa z#yL3Gy*oT*hmsnIpXg12QovGTq|*^gF$^;M(aJWVpY`e)9?IV^p8tYF9menwou$^D z&9IWT1xX%e3_q#x+$rb2f@Bc?DH;ea1{Of(2kgXxAT}`ELjjjIMgU-dB1t|nE;ugb zjQ5pxYA_ZMUoe!RjKm5^+ZXqwdR0U_&ox+#A^ax6%MpBem9($md(WPH?}+6Oz_)=x zEG~S)f%t3U{%s(v%nG`QvahW0Os3ULW6+ylWLf6q1+UU@(#x{=4XFEuac~O@&Be-S z2y-TgWDN`;#~)w1?mN>tfXcVYBl7qpEKWUlUDQj7J@x4Tz&|<`Z?xfWm=x+}mfq0a zh^d|k@LkaLy`k{6sCG}OR`)G4%;4SYqB{%{v09Zu9WKK_a#+;%Zx_lcv@Ki{f*Jj{ z$vs;<1H_rSsN;Iu3l&dGvnEM8uU@}brWU)X4_0*_5M%MC)LAQsE$qZRb$oN7pzyV# zu@}23uZJ!cmgfkimA!8ILESW}%@PU2HS0~WF4Aw2sPkJlUJN1o;g1%?O#!uMc-Wyc zvM0C7YyFttV!PX_&DdsJ$x~w(zOzfM>Zhz`$#~jB?9dy&0E2{;5d(nuWkhP(1uEuzy>9rx1Gm_2to8jW!$|#U}y5?9EjU8&dBZS{k4Plr_ER?U!FG zSw7A;&Dnb??`5j18rL>(G}6ixrpqRU)emJ!g2^}t1d4~T;LBl^1Hd)|lo2pUtUV;L z43ZoTsp%W92!k|BO>|g6y80&GOF@uQlQBD#cJh5MQ>!>>c$m6=Y#`raj|zs_^T z8Iz|n3cNDfvGkF0@TZ+lYab;z$7`p0JhvL-2+_YUnnEp4-I_k`7VKU88MxNO?c1j= zreI>TCug^t@w1vo3mRP@pRLFM(^HGqubZ~?j&alrQ%O&ehF05K$!Q-j9NSa4^jYp_ zFVI!ZH2g`sh1U30K;N4zZKW?+hn=FJ;VXMq-ZJM5+d%Z(ZOG}JsIKwyaNM$PK|}8> zQR*qVx8qpC{VW&dJIgOiDXS}JQuA0+pCW{UYYixPrTMQm*2FQ^-=OuFIt9Ykc+E80 z4Xrn-Z%XFwH^?o&u(Yja)xw&$KR@jwuR?5|d|B`zT2wY!1ga-KRTR>K7hK< zISE>>a^FqDy1p-raj>p&K#n*rbEI-heJuskMO4A7%z@>IBlU;O zds>q%`giC96j<`7!*X9=Eu02Z{gl)@xtCalJzFhs26zlu9z>V2?1FahUwiePwN?Jm zN837yY5M`V@cM9C7qN8p;rBC!&wuEFf_5~0&NPGmjC?!a8Gz(^w)#d}ofNi>RiWe@ zLev~vtm$9Aa-)X*`hR1V;-X;WdNxcta%b0m3n{W!L@1`>buMmtTWW^J)%4Tei$BIe zf3t{wnHHYpES%7Vec|%JV6JADWh8wmvkU}9A*0dpsHGD5$_C@`X(Yn1`OAlr$hb(p zpEbn{r-2^x(E)y^0cu+mI7vK7;LUgrw`GqL$6IR&aofLrWK6D81wua0|K0_+>T17^ zqxb|q`X_N!E8=us6WUv-VXQWIb4a|m)LzzmiB9a(`<|5UoVnLf;*}=w83k z?SHaHesje;P#;2`DTE``yq$wwqayYA#ZvS*tBM~{Ov0~U;otCE+3k<-z+@qg?}y2E zZEh*Sszp^d=v%A0odU$2C~i$#lwlK3(j-Kyz`Hr<^{0 z&rRLqaE5OB2sf+SAC1Q- zxB0DXegu!OX~By&l>Ra$9EY0SBJ9Vj-e<|blB`vm%V@-l0}01<|$ zD{_}q2&kMaLFehE6Qdqiqtdn?eo57~wfJ#Rg$q-}ifN+UW=?WYUgBjelb5l8Qg7mHu^Dt3;itm$Kwlj##a!_WVAJunD~= zvCI$xyS|QKWoEXPwK3Vxi}}Kqn49!=G2Um4>UbfQbBW!w5F^*U@Qss==>F>$7{?q2 zY}|gIr9|{FMldfhUN1mMwBE4XWNyM)iS~LPZT=CyhfAc=SGM?#5>xyDg9CxN!S-$mpEAp zF!fQzXkWl5_#yNWwf$Ae8hXk9i7bF9f^ri_onS~-6JJQ1$C8r!^|I?b^d}k<-DM+< zSxwoUkf*4Ldy$Q@b>VB1H%!K&JJ?h<=ft}^gTG7+wG7l*viZtGP90k!5Q_$P3xjg+ zFCAvl=xA++WJS4=VZWwjiNY`Eb!G2u!>!W8f3JDXgkNtuGAwAVF8hbm-Z$)wULQBj zJY4P7rH?TR>*+?`&pDo9VE+C&(|><+vegg3MFgX0N`beg$jABo5Yg?z(^$+7EE0LI zW#p_?m0XgCHCGHYs1)n%pk&MqVbCCxjl2r1q|IsE|KiNSNh3_)71CTf#0|cRo6%=%2iKL~( zM5rJsM<2l0;Jd?U0%`Cb;YOFLNLMog%=;AB2~H>Z&KQGV!bU>%{Ua8NokW}j-6z?x z_$#i1)ECLh%{VbIu(G1wJ)FZy3Tx2;~S} zYE~9za(maBm_Ukls0k5p<5|~tz}oZVKsOa8Cg8TmL2VC_=v?6h1lh; zlbn<2UwZjWGoCRw;-)uDM~;6$69fP@6oz)mMuFUYHiA5rJ*6 z2P(%^!Gy=7|6$bG@jmZI<#*!5qBriBK;he0KuV>Qam|KbzncSHWx%&8=v`KD?c8S>ZYUpGYK(d*N z{`3%DNLQmG#3zT)MpRS+)R0o%>yFxFm6VeZY+)%}c7(@Mz@RirQ}DZFk&IOEd_m5I z@7q*z5mMZe^H^oc#0(>fZfq61ms$ze$}Y2I;!|RrJ_R_xD;qwG)5x1eH!Laqlb`-8 zK7}XP8m@$31cIW-E(dTJQymI@2-fgMd~ze~V3N@M%Pb80BMvSLy~14bYEd@)kCjS< zGGv1JR|OssJr+wIA`3l7pMU)JG;WT0A1&9(mljltMr{CA@d$ z>}Ni5lqFX68hs<)2{sCQU~x#iWme5moD&W7&w3L6!}D6d@7=?t3{M%oYcS^P^_av2 zSL>6#Jqe}0O|s@ucGi>aF37R+YMUEzfPVGlS@-pS}ADWc1_|k#}oz;fmf2nG4IV zB@WHs@`gpiC!(#M9YxgcwQT)fU8jHXh4TJddJzSDe@*lm5VGeQ1-^(ZTZ;56i@3Ds za#jsLXNz1)@K_#wzHZ8$f%R0(H6p+VGz+Dd_l{y>r=jaI%YNq`1(VmB&HcF z7!pKf=|&u~^1}L1-Ytk+g^9lJ4B+CH=;a&MyqhrF5q3&KdTggVmtai>@%{Bp{7N;> zG%>F5#$3cKh6dsjrADqiON7!R()Lb#YlafT86)>_Blf(3C@wL0f<5dp;{p;R#qy(r z*cnr5B+J#vE6#9S-y{#SQzFH{jb_Bn>=293gc){EDqT`uxFs1L>K3mg^&MJkjYikI zrEaN-jja%WP_s`{bjKikEA`Dcv&rY4naAXN^A z?S+kFllkOFV!%(em|tq?u2s<+kmSvpbm9WOJGGalE-&L1g501<-_?>d;!;FwQi2oH zI@r?h65x{<860BJy<#U-o zE8#C|d@`VEf{uuk1cX{3w=|BPfjBBhmcv7!sqb<(_E?)eW@De@0-#vH0y!fwazKK}L-X{*_S<5&xaHX?Fox5jfGr9{i z5ib>Iv-qoPbK<2{v#wQ|9!6Ba`=cV!qnD!YX+>rw7Gjy$A*D0}36Y{^^9taDIGgG? zs?BB#a>v&8tQ@Q?^5^s$)JGkcsr+=(LEpT&2IEsI>Menm}g zbNp<%fcA70?qpF#QiG~AKB|F=7wh6?7azZE87D6No5_GncFKko2gC1+t~|}GjsH}& z`>FDoM^O__U2AeZseIjchdLP_BcJWms*u|A>pEuf`oW%BBjTFr@;9Gq%O+~W%Kt)m z*)e<8Xx@)=EqRozCg-NsCSI-@d^v8o#%X*pkgBL*J{QuMNL`p*n9^|E`1GjOG`Rkk zM>E!F_?bu3RBeHF5XnJL6DS1XT8M}ZZV-nwCz;m=Fg0P(6kTahHe-jg!EmVA8dS%d z)Q_9$lN+eGiaqE3=}ua*aa!@mnz{H}iPi~K#_Kpv>bUB%29jFbC|X z?%D67>zF0W*-}ugBq!NqcsV?p?dEuGUlJcT8#)3Fn+sgpMYtNLLuB|Eu^mPq*DyPf z?j27g+kLp+owc;+FtyooWeamr9%Etgw!UndB|O$ECk`$5qABs?%EaqQz~SuVr|Arm zYzmR2s8(%cBStu?G8}4f9oLppt_!A4l$Q4Ty;v6t#Oo&E=yrewX{jODqF-*PcezMV zkxLdT+;%5h5)){IRBGl~hxYWJ_qNXuexHiCgP^|7z{M^^V_Z zHAxg#7ylrtFMhW#1@Aqn{CgsPB)aE&LfrmH_WoZJ)mN4;x48Tt>_5aHi%jPGZ7=$} zLy@4qfh8Iwi9S;H3Nbi=)Hp#>;0!ngc78R13;}w-t#@v@cX1rI3Qd0adD6vfH7FQ5 z_^x13RXEoH&~*asXi2F(e%kWAaHuooqgC%m-HngZ2}L<6BryP5z*Z?~FNuW(1(`oK<1YUMJ2-0lIR2-M zK4fnZYV`NhmpNf1CaK*8R$XnO9f=cTc439(QsYRjPmFWCx0XOC6h4}}{|#dl4m zeJLqclhYxOf7NOXnbAW9Qs)I0W@VUxx9fp8ctp zxJ^YZlm*T|917QR;~+B#6}1;>@7w6D7X+skr7i}(UC&~oE$KJBh^WTd_9j|7LuX7a zV38LQ7RQd8Bm4-Mp(9vO)$aALUyPvp{8MAzExg$(0qX{drRt4$W+(4%_StA^0&a(& zGekIYHWKoFil5+}9nXA#R5Q2giWGN09Saykj<7x&EOieS*2ChG!X7z`e_gd?Ik_}| zKT#Au8O_stBehcYqd{UBa0lfDmEpzZuBA&8OCm7cz&M$9_=BZB0`{vpX6xj@L9 zJCn0op$i}G*VooTs9CSawc({Gwf8wv6JIrO_W&8Qgg*(kUc2DOM`2$*+qzEM`qO~g zx}DnkZB24dunpwhzPsN7JjcFh+gw=Cz@eAJo8GR-mL-aiBjnwgN7K~V%{7Ttwir@I zJ6E#!NcL3$(5Vro3cz`EJ;1I7tg;1zWf&4_$_q$TeuEM1mR&c?_ux* z2D}91eJVxv@^HT5Fy%oi?es8-ekVglnv#(Dt$G>gn;rn5Pok`UA4iBEh`WJ6>C>=) zE2nl{AHMK>055r~Vek>MJqOpmBBT30pwTxJ*)aQxXIdwMYOLT0G-qr}ZsKTcqE&%6 z!3VZDBMKyO0`WUNJGFFaJRWvixo*Z%ZeGbaTKPb@(#QKb@cU}dhZB(>uA1e0B5{EQF1?jmss|){7@PBxuN+(rR(h7%ag6fFPKg10@CyJj1}A_ z6@bSN0uiuCyd$90(IV^n#OC*>OD1zR2eh4-`^RJ;I*Z{Y${XSe55w?(x&DYGtB9U7{vqWY&QSNl%eJS^>lX9yhV{v9*Zp6v^e_JX9UWVD(tq!C z((kmk?s0*4`Sy3)vJbnc`@P5qjI!HE-_NT}$gZZdafaJD+xrEtKl8SzKL-)%lRqB} zrcj~4M?DDuHJg2$4Z$Jjwd&fQ0L2rt=y={Bc9m1fVJ>?sb2}q1VH^=;<^qiBSsbM0 zMgNTpll%?`^3c*t+Pktj)T+6PRE)O+#6M>NH+q~gP(N)y zSE2P=^iib`y*yWi#*q1{F{TJzs4-_5`Kq%P`Cq6rzlxfz&MR%d(BN)c^ws3;y}X#9 z&q?M4vU!@FO;RS`RAURx7-da~5QPcqpnt2(l9T*-_e59v`fJ!sGQu=^nyHX2v1L z4d(9B9qktS?}bg~eeXY+o&-1>ue3z%e_C-&+J9kQfcP=K>Y8JWZ_!ZW{9DMqZYr1a zsq1m)>f?I8>4tHWu;?2vV__ca7d~{?8}0Ov{pg@?%9=JIKRZmf!lnk_ZAR>n=T}6k zbFFNL6BC-X$6y8A*e5dO200{ib>29n3Vsf9d@1?+#u1@N5$u$yDe}iD+t4J~IoC4a zk8{3bZm>(?)6PFG#qRUy#i6yq3iZ168KcF{iFzklk#77Gan`dfY&0Cb3dn4)@8>Gn zz{Wv1mG47AMJZ4NHd^8u@9lBY*pF!!ZP;3tKx=I=_NNy0w(f((Q-IM}TyaP-e^IGr zU&}XImsAn#IG+dNvQqBGfl(TnfZBDBdYt(puYNq-u(LseU8bVY$(A=zma1;mV%?y^ zyXO`G>o!7)-a36S${a6}_JUEW31sA>GP% z+k9sIYLY;JJ{XX@txOx*xjIyO2%DiI3cC^8r3f-O9H+XA?FjTM}l&S}LLN7scFr91Q$Ps1)=l(Cr%Q$p_<` zBW)SwepDhw_n|T$NlTQ9l08*kq6*x5H^@U#PQ-sS&MzMhmA5glUNGJ@ zrW~OT7#;l@iDpdihQO3|i`5)>!y7Cf8%Y}t#o$w=Cn$ehctk)86XPk!R1t=5kAM8U z<8=zv5!N6;;k=NuFfm*kSW-%Ffs#vPot*=C`#Q3HLzk0S7S|4>M=$B{1IssapaWJ& zUjxMAWTpx<{bd9T0UZYtYEPznsz?Hg)XWV}F_4(E{K=SBQ55S?G6(WoqLBmi z`rvR+5j+xee9y0VfNdKTN3%YHR?E22zvHQ+x}?cM?o~ZN?T3f42EzKXyte(lIo<;- z4qjPK?ZP1^=;=-&<@6OUPd*`iYM;zvHAo){)&%P85QX0` z)srZki=;4bM?8ZdOwqGHsg`7W*iYxxV~%<|vA%ajp2URfKZ^sMBb32d- z-t-bS{tP#s+_j9&@9^lwND00r;stCYG1SlCFQm4xs)GhwNH4tJl%}il7C^N-3w$y( z!TW{76x(1!Q%{r~AqzOR$NCeNFs?z$egFp1E;5GXGK%mt)AZSa@)JNvnN4+#KX9^3 z#dPO3OMLmybntV~W5t@tRj7gr12_Qg3`oNxArJ9c5&(2*Wht#w&7iwqRxnAs+glXQ zQsNKG(igxZ@XtrkseFk2Nsg7X*5(koLT`-I+yPdl)IHvCvXHX0$9pV5#|Pn8%2S8d zuc-kxhw+%$gYOwB(b3dQ1mNTwp33RefHwzMm2aQ@fH9!se8X0jm$-K?oNBKUrAy%% z%7|&3+?l)E9+kZtNN2ZUp;gdf7aw9I)FxvlBV5A0uGBE@wt4a1+!`s+91T}wz}Ufc z6$8j^%b*MxD}k5ntRjC0env=zkhSrsS-)uYfpc#_8L;HWhy*SiE(Qbv-qo%+tt)wK zQU`R^-BSecU#x{_MgX~<86e=Y7)c8ds1_PiRZWTfb<1#{hzYR5vs|6-*zZW|nXT6G zuR{Zz+?|RpD|-?uQz(7UXAYgJg`I;^9s7)^qIkxDy)B*qoETNOu>Zh9ZOr0-H*qp7+of(C{mdx*CLHZ*D@nWy6nw%{ac>JiuS<2WL12cdwwR z$jdI#dtB`F*ho*%7WLH~%bxs`6;h?&tLc3gc!Oa-NoDSCYyy4}W<~(&Q7%DXPvVtP z{f6eaps~lYy&Rijitqw1+iZd!7$jAiP<@@cwp=1h-N^H*%AZEMxXHnQ-b}Z{d#t^yM0=Gf7 zz5&_|d3f_6lvd#y_MiDvtZtl-{9$r}**HS&1MF6c^itTT9L!%(tDr7RW(JKx7AFN< ze+9X01x_vOQ+bfzY#imK6tj`Sm$m|JY^<=e0-K(UBYC9xG42z}BYG5t8>ZhFmd^^t z8vh_2DC&Ykxez*HW>w>4HR2LB;#RD(b_B4B!tyu6bf)H7n3F8oR&l&kadsMsBT;p) z9D%REA7|_RqvD@9j)r=VzKR-kxl;+L94a&@2@%8kW=}iH|2jHs__@+Zu&0WGQIUQZ zvA4I{5wS}8of-mPJ%d&~lUqGYNpS&Qe2p?%jdE^{3Mq|BEsZx;8ddfATOJxUsTyyKHQljg9M)<}K6-by?V03_3uU^f{ZriQ_Yj2SX7WmgV!+3*vG~ebJ+GaGLr&=46+Fw$0uu2mm`!H-gsofjgo}8GWbx5;?H{NOozulM;v%fG;)F1>M(3y+_uHzc z;5hgVJPf<5wr~9DZJ}){wbzA|j2sqVEGn`l;SB%P>76csU=|q!j~oNR#Pnc6hzl#t zOCw#lo$fU{;2>2OaHCwy$)}Z^(Dw&RT22pEDhnjgC#IV#TZsxyl#4<3?^+dq)oRQW zNYsN&A7tyU4vuu~q7h&Ke7*HZe&{pY&lU4wNa4X*SI|#eCk-KRNpM1BV#f5{q%>GN z1{o7<1}7_}{MI*1Gc~7qRteJs$<$~<=?n#U7UCdL+S~DAd|0k-Z`@DfI~QXkyP$x? z31_kecum>BPjGKW6Vx_RwqA_G#_+K-QcE*Z-^bDR2I(Xx zbQKwCe=*V-PBelhgdSq*2bJjX7#kA&H%S`vf0CqcQFqt>9h1JfdBmhqH)nsZul~P0 z=^v=eo&V-ZpI=6s5oI@9%%z z`v;VM^rUZgzW#4ddi&p=^!D~6DUDhi*Y(B|gme^lwU zwYAmN)#c@t&&$jI*wX)orRN@D>6zK-si~>)iP6!~;o)J_`-+oZ3| z_Ys!9sU-MYfxTRAGV$7b@NL}3lIZ@D7!so|Kf79rHRNE-5Z9 z4i1Mu!qTx3NofIjVPTQM!NCCmi2(rtFJ8Rx@$r2Gq#gWAo<4t}6x1LQ(eYo-w0L+Y z%E1<8Xt-c&@(4x0Hj2wMEzZ>|MJX$y`1lSbg;5N2C{mJ3D#|41^hbQ!#l^+Z(b3M% z?$MvNv9YnTvNAI>Gcq#L*Vot8)qS+3H8eET|DmN-{>zsBFIZYkOiV;XL{L!h$&)9% zyu6RFG&?){qbkkB#PokuX*xPuTH61p(&S|1kE-;e9*x4qeZa(gKm(xw03QPU$LD{- zr2l70+6aoFn)?5eq>~hr|079j$6`370tWtnCFwRpO`$G;`%zAm4yv8vmh z>Sm)C{rDq%L4?*4FZ$=IZMO=;B?C`3p9P?ZZ2hGE6wJN&E;Az|l^6+Kdz7U6KiuEm zob;!A^#@155ALz#qEN*7ucL2ZL9gMz`OR!YPH@=mwQjZDcH$r|H9PS*#w%O0)9Q!N zaHeU~@-Vi}JjPJ2l4ZtVuu42w+=0$enLTK(WlSM+q zIL9@WxgH)hXJ16w0BC*9Lv_s~D9)4m_Rk(Cby`XTLk)eukDoSlpY{yl70`E8MrCd0 z)<2v0{JGvKhjR}gSp{*@VMi<5oq9`GHU8t>c068f&G&}mT3jkf?P(A7BS+qIHWKRE zOYKxT*o;A6-D5mSHl-@4sf`zJB%#^3!Qn z!i1)H+J6E$HxHrn2-aS}4MokaVobBd&SWuu`8UgpUkZ-MFT3>e%ur)B{9g0)6K)Sw zmVI?OMj}8EHK+HH`)b1I7wTEZmKj=OM~DDxEUv^8s=di6kn=B&wYv_UKYQ7fm%jsi zzFEKi@`5Y;-A2e0&X9h1QGUl!ESHg-cq4cbp9`elGQ+N3>ToceXWDpsx_zKyeE>~4 z*Tq>Zn@^LQP!i1g5~L~}f(-4Y^^3)hJ|`kUw{Dx13ysa1c?r3lzP;Id$MN8coC(zC z29O~^EyD~%NbDh|>^r&1n9X;WbJwWH8+$GWg=sb(e(Ib*x%3w*SHbV6W9}M@mK)4c18T1=21bRGc4bBCJOcx z0QanZ`m?Yj=o`IJDOBbT?jLP$qOC40$@&(cQS2K$a{o=td(mNh1D+^G?j7uRW5eIv z^!bkP0H6`I5rM+SrOZvAuDm`2b4RCj7B>BLHFq0Ale$F2ilse}J82M%0qP-De`<05kG7Ga)pZc@idUK2hIB7-@8q+h}WS}#xEMoHlklN;esA!7Ig8FiJ z=V$)d{M{M9mDCzGw1feq6@dQd3eZj6gt7^Px+8Wx3!FQ&s*v&wZCH%_vSQ} zU{S5l0`YchH1lwo;bVsMfI@ykX?%O!s%?Gw8*d^xD3CmLk{ckmj*#AqQLSQEB{4w) z5>dMyMP$aDcJ#A}LFg5=p*;2MEgm|<)TS+|?~@!q#h^c1`O3gm?`du<2{lSpWH^i( zAtiK3elh7trEK)$kv${~i~ULpGM5)V*kM^0FfLzB{b>@#ml{L{>Y|nM^huxCN@vXz zhf^5!E{!#_+hDQr^G0__%n-=3kk*MF-gIR5S+PM=YAk;Tx6&`O2wxk1b zZ{iRxF^F-OIGsq%Or1=mG@f7UYw463E3Hg=!Y?$34}}mFcFc?P3bMTzJ2`@+#8EyW zi#-mifR@{amTd9bTEMz-i9r}xU7kvvIqX9iWe5u%$Jy2*mG55S^$7O%!$Xq6{lPFK~yX&9L z04{SgMT+BfGzHz8q9JMja#iUM;vXxgcakm-5Xt+}Uq8<`KK!CyY>o*+R)9+4`D?iP z+zf6lo>iG(*S@bf=5G5t7argAoKh#gJC>Zab4%mmkLfCs%ub|5W zJbxm6YPLLt`BV)J6GEJBr58Gd=n1Il(DwS|Lj&9VK&W}*YUlHjdSIOOS_>QbxO)Qx zz*&cS@qW1IFW>HTom{=RNGr1Z&}4T1!KDs3?aE+k!7BUMsG*mO!U~jFzDFhd0Dlsk z=b{q!W85#JX8b0wT%>094{qx6q)E}q?jD&CpdChvua`~EGGSo%ye`HsxZZ{c2fC)e z<;@^ux;b8Sa)&VVMiJiZK!bih!tq?-i1eeS!II0bRgNVmXniyu79grUdZ)g9)N(s4DzH`327y;; zPayKxD%%}M>}j$#zfh6bGWFu@Ct^+|PkjH~RrhvnUFJ83@|fhlSTNvDARho>1tfPr zQiluBFAzz9Sy@^`w)GeTWzd1Wg9{I~9CRQNi%M(8+q3QA_POtSl-#^2kfI26cc|O{ zcPjm9PN!G>MIW~`hJ$X{an|bx^g|h0VO;NK58Bf0uza>~bhqb)reM`hOb#d*?~L%A z4{hVxUA5Xx9V>zYo0(-#$!;ey&=3E+9MLS&u$tAc)G*>C5Y9g4@S{4^VaZ^@*+|gX zP&CI-5(B`$O{5QIWppE*QFW>wifflweiPl{sG&=pE{07T-D=i%D$q^BX)5!_YOygx{W^*&BZmNiKck zJm(sG_YNATDZE8(oPa*@A z8POph;j|o$4N?K5Pq^X$CY~kLJR?#?0;X4hTBSe?zO+TNw9i3lEBR@w`RLOa)~Het z#w^YcxwH|*v`Hwz0t8s+ZG8wP(2Gjrj3T-MfY!{?F%SS21Yn^Cs5J|mzDWmAAwc4Y z#~Ul)TcBep5VISBzluOlLf{@DNW?RU3J_$$84#QdlBDPEP!OOX+$kyp<820`c_w}m zLiH>*AwQ*eC6hTe5rY^r^bFk&L9jmyj6flX&|3%^9KqDs6tDO&6{s-vksucDY_)=H zjqYr%)oh(V*?Lqt2I4vDpFsLxOof6Ri|!n&)f}5YId)XJ4&u2^=D9Axxo!oy9^JXt z!C23lF?~yOf{_lv$lQS7JhxRG&VoSh$Ei7WdPZZ=k69e??ks6@@TW1-iIvnDNZRk4 ze1v=Y&HrNQJlxrO0Jfc-NQ~H<#NK<)5POvtwO6guT2)om{vrutv|_YXMNzFii>lSw zx~Z+G)uKj27pn4k-}n0mPOft$Ipnw@YJ1(U5AMRsIDb}6|VqQ{15qcVX_w~iHG+)E{eJjvec?%9tUUMlkpRr z7FmK_tl3D{eSTg4Jeq9@77mDoI3f0^!8jfAM9Q@<;It5<~$GwIuD=!k1Dh$Fh=6h}6D^T$-t(RC3?2+F$z?0hQBBP0(yvU=sS`05nu zNMF?YN3Igwq*bRPS6c*~C zSCOMyej5f@&r#ZMuDEWhoOo10GFARfRDScK{GDtm_CAa^3eChAjuY^35%LK0vZ=_^ zQ_T$%tobPSvbm}-UB2UERf#}#@4g)UTxICDa!on3QAiY=9Wa1qlfL#SdM@g&M~y{H zl~im6$Vr-TR6+SzLo1MeY4h~yT)ACX9Mf`K)U{LI6|0$aO-IVZPiZx6)lcFQ(sryL zrxer$>)qrQNPwF>F^zxX=vMa?$vK@~{mG+tq`JN$3_Y2e0`84yMO2I(Jzg(pfM?ea zBX918)ux6$y(#kq4$N8AtHGZ|GH6C}Xw-5P+gCK|H5Pqpw*5h6t*7b$=#Uu#+qw!8 zk|eHYnhrLrJF0$kEYMi>t#~WpDL@__CYOQm2e84C?l5fXg~Xt%ODx;tkWmcGdsyYa$Ix@paHfgUzl{aiPKND>8V|;2&DIlOK(WeRDJ(Pq_3G1iR4?}@I;aKcB zkUKQCUnPz2QQcnZ-M8|d>*LYJhuo)atiQ9}LEl;zUNCa=o=pdI%)waVm zj$5_1yE9Nd_6Y#!wI~&nqN%i=o{hCyH$j*DSQvgn47Q z2sUz0Y)>wvq-N5p=bPbgU-SN~Q*-iV*LoGMP*LGkQ?>m%O=u|Nc<^uTMGs5^EE=fr zHJ~Liqb>1GUcsBp`Pc8f`qPhyxZ$)eR|BB=J`QK zVd&@fTZJ6>BY1ribIpOmz!$wycfAiQnWJloA7Yq*`&~QA|L&BsExPd(W@x~<;_V6?PBCN) z4(WRPiD2%eUeWk+;<%TvNCX@nsLy%3V-m2SiJ@zPfvin*=B-hdTiYKQxKlz#i=)^eE@MxlApZou<|3BWei% zje1vso?(nKcNbwjqY#sJ^In1Duj(e>+#WCS78Q~ON$^Y%>*j8_v%aFMYydbLMiY|?bug+7t)@zR6xHBG51LXqE$ zhUx-(_jzik7MQirS`DpdNS;3LQ_up(R5S#(FQ;?_#L17~#!a^^AG zgo+3Sa2gO$Z8UJ(t)*8z{t1igOULUEd$#^tp2sSpWyMxgBep+QZ&WGq4-}xqsE9NS zNX2P0=H^cL<4x4bXPYsZ_+5o&9S{KgA_~2%PyL7Ww1c8R7F0 zXlb#~lkF|>tcG9Nz?U>s*b_8Lc?<3jyo*7x(0&?`zIU_8*C%e^m^oR>Ya!nupD-azk80z9We+0oDH`b739&?Pg%iC96>tVul2sq zL|IWNQchF~Yn-TMv6t?v#c*TaHes!V%QKl3@cM{fL|Y8UnXUBmlp~+5@GEC8ztGBp&^`E%xge9UC_={rqSeNvnlGWHUOM>357tDQOj{dushVDu3tCD%Tsu z?>zyeD8<`B(&A|WrtFpys#VDTg!gKo29L37p4^0{NX{EvF= zK(m8a4cRxoDzg-GD;^`J5LIdp#Qu*-nnGEV8{8kUy);zX#f7vh9&p|ODot%DSwfk_ z#EbpPJ;ybENVM$BDU6*>=5>lHAnhmdALOEYN(GoWch1`LXPbv^GTk-jtlI?^ zA?4eg`SBw(?vWoJUp8IpCFsfbmBfxPh!wuRJ{}J}oR;Th&T~`MZl`yTPWLZD=f`6B zS^kKtPoqsAk1dNJt z`99p^EYyJ8QeQy8Yt!2qd>{!W{|7Z$s~2KoAZF`<6pB@o`MvCrr~DPkX<_;E zUg9TBKE;Er>C>8LXF@e*2}wHVv%}wS1P_tp<-|l8wTej>YZ~s2Tr7>zx)###=kK9$ zhP21?g|cbL83QW2w?KGGiv=^3@G!74vwC4jKeGMWioimn{K*Ykle^ITU>|><+v>BB zpwZq|!^`@ScNXQNW$m-hCeqr@4f z9+Bc)ul!XHcy6DD*~G(1;Pz9Ur-%@OW1KEd4CR*zk4(*Q9B0!=f~T+QsTH)} zuWV%AKK84SbIj%Rb4>XC$!|kR9maf7MogNH#ydVq=ite9)KjoU4z}U?RL7zm$YaZ= z5;#(qathPt8nPRy|OCy1OGE`JK*es0@j%_c|8Pw%~+Ho9D za^(SA zSl6-|5lw@FVU2M)2CtCsg9!MR?I2ZBph7O`HN`O}sZfYh>DoT-;G)|7tIUL?_kOZ@ zZ=pUcVqZj~<836~!^7MuR-A!A8FyF474?4kLE``uDw7aN_$LAOl`r6p)R5Cn`M}RM zVX@+tK^4lobf2R&$jJM#k4biv5mvxg2x*O1B6Z?^%SC3v(uZgCUg;H z|BKSq+4s6_5POa<9N3klmcW!t4<^E&2Kg;z_>wVK6s|llcF}u74JLz^5BfCQbU`<_ zlQ7l?!(2nNqp@-g6|BEDEkPy8V1F*`3(D}Z-s`q3So4!KS=_UqDnkb<1MqTsuT5(@ z&ui5S57nTAQwNJSAWxi2UlQdwd33JLluNSa;yY#bK8*ZEX2#kxX=}A!l$e?sM9Ym} z7U+-KyFA&5yisj-K)=ldI4y_V8c8*2TSk)20Fe9Mea3fABa67HXOEzlL(TO)#=`uV z1u&PxTsr4I7T;@aNZtvx&zPH;YHNGedO5;3!*ijGCTTo+IrRD`_vyh^aIg7pRCcG= zhl1Y-`?`<-c09!A7zER)BDW^SyX_WOb)b5a^onuRVT(3Qt~o;Pq-pV2TmbX;;F%BX9lc^ga1K{gMHVB0vrNK)h}}*FyURW}@KW)${CoG8QCBgJsY)P)E)i zdFz<-X=#8ItYl@f;=qhI2OBiv+Nq)1`S{dOjjs*V3=dL95#L7Kd!Zdnh>0%rn%>QS zq4zsFB1vfN)9;x!oEw8AXts1gI7E*36xg0!ddYL$$1U=+@Z03(KO*=EDz>iC+}GA1 zIMH7hD;#QC@Q`*pSR?7_IViy4Y6m*TXsj@fr5a^I1Zj2++?i~`G|_AA&Jnp3I^BD- zbI^s$X64LNVSopc?}XGXA+=CNxaqSd#}*^!57+Ol7V*Xq)N8RQk==5WU_LfwW$qZ) zA1eaHV{)9McLur+HLA(ubltFCZ~+c-J>jhZ}EFDhK4F?e&nlge+*eHe;6t<1Ek-;G{`vEM6!?~Ix1{~8^30?Ga!pmG5e8bROnv(}mrc=&Uco8nBN_po>KlAlULAT2a=79wj*4Y*{Z%IL)e=gBVF zO~YOZ4iM#iKapU&LX=5|*1e2{Uc*ZA&kp0qF)f~n@=V!Gz^{@>(PV+XD0 zRYW)Ps>oN$AOa}{4R3iYJZZ%Npq1RdUJDkuxC7GO$FkzQUVRPqH@$kE;O%zw?|Z|# z;2G2hMqHl0&nB};j927l_J#Lbe_|`n;NVDt6b{d9PB+ylHbJvC;`y!p`qV!rWn-5} z+~yRJR=WumI|1ggJ%AX~=vwplC9idQS^*qY>XKV91EtUZl>-}Yd~Ue;hwFx z0}JdhiRJHmi)h$WGkre;3!_t*XJElpqHKIhq#u$Ok$Rp&ly8TH^PS4R2khntNR72B z5c7BO1Xs158DW8gvgL@WS&qD$G=fBDnXxE@eb^fN^)DyfI7M1q!j!3`u8ni3bE)VQB| zPKPK{0*moW-@lP8(fEdv$EHl9es)5DRme&iNEftvorb~{t~Xa(dO!X&Cejr_LRo-z z^I>c2Zza;_X(^O=8=_3_>G72g27ZZUDAQ6Haenade09JQIHDx=DmBGioT9V=D~L6$ zpJ#!E-cueet~Eo*G$wn50!IxL#_ViA8rY9-8=h6yJO?R^k4??GVZU7>9YskFaZ8P$ zlgUw5M8e4agV*&VogWO+dIhw1C*;0+eUQ}CquLFJ{&<*cFr09lDw*Ge&_N{9dt~V3 z8wX%=r3G=+%t0uxS&&JlQmJ|F#fTrmsnQVOEequSKxKaO-Aj-uN87=~mN)s`f>| z%FD4ecJvL=ktCBEC__2@o0BWgFaYgmuaa{WD6PYJx!F6YO zT(Cr3SJ~OTYt0VE+=2-)DYFt3x6v_Tr9GhC{+RrJ)eo4MgV4;RY?ncu2F_W1Jcs|) z>k64Pl%OoB+nVbNIJvy($R*xXfr`^f2`V-KzvN)d%LK~XS9udASaZC}8Ilap!x2i@ znlQLLo<+B@dLR?ztsSg5TFj4opUvs-^l;4i6^fG-NrOk_pCP)XgcAn71{wzPf6S!= z95g8rcI0|IB35xq^Jt=}@S~G(Ps5?a_$Vnp+Fl^&46dsnM)K_01L(0WMG^D(nqpJ@ z&bjLg<2+YO{mQs*nX)kK=^3U^&i6G9SL;vJkL31r+Ta`Ah>ip`iZ$6qJo(Fb-qjiI zCyyrmDo$pg7-tvHS8laHH!6nPmyZ{W0C63-kO=%Ps_yX%Znv$b0z6#HFS|au=^AZq zf03Kz6nx#dJq^ulEn7eaFGH1SX<=1Rc3}?=)7iU4=To}f`jZG}KM}jEm=Tm0H@{5d zf1R&+;ZB|5JrQCeHYGEdJ(~tS(seu>Jv@3Zdw>?$AVHbna*r3S9=D4o)~Lj9`veLu zNr5s(Ch$Ml{KO&f$#~~uGSqvsgyd6dK0xgptjjMrrPEKQi*Ce@9Pu-=^CdKC^Kcy_B<0gqz zMO1#j`L{Zc%Qxm_d!188$edRf|0XR4;=RxQo1dRVN@Rfb?7d#n-u|u|8)}{X8IrN|}r!V;0{MHa)=H=!7EngC!m~vaYsM1oi;SxK~YME7%5s69TJ)%5- zta)o$W-(t@YEiByojLSgo_m_Qn5#jYmm%u~aNK8ADgQDR|2QnO`8^8253Pm^lqvS3 zbLUj&QNWGBG(!Y5RKm8WS=#}Laadal@>O#{0vj{#fdQt)i0SL8D4j2Z)AZ@B@i@VFEb1SuNHW!`!^8;QDOBRN zbJE54pTmY8ggf|Ej0ZdHriW@GqJt?dd+QKvh^A^tfk{YCzE>Lc9ES@9L_c%A-j87? z70~`>-Fr9v>Siwyu|d{(Dl!w=Z56D&cyAACSxXEJyBGR>;j4qlN;ARDZ))ShJ<1(b zLRN4F)xtNyf|Z9pm>h+~>s-u+t){tZdq-?G66E7rFOsO8PwEj5-lq|ZACRP&R1T84 zohhi$C$6Y(1|ng1r$X$NR?C(`$WdX$(5`3qP?bvS%Z4GA?~y!?8W!U#qQ*Ki9}nfB0e>sD|$F)p068!kV^`T9#(vSSijeztp&2i>+| zY!v1*ly-lrzg1*|9GV;Mxt*`HGfn-LT^g2y2I~$n=}%rFFK>Sc-i#6Z#>k4AWo7*` zptAOPamP4(hkSh}dx;>=4c^$x0~^JyV-?hvB`f;YN#rIWm{1BFsO_3E%5C=(o13q`ueC zbc=!z#hqT{_SHY{c{ZPhj@CzBl42UWb$c@S+wHTL9}mp{uI&J?WgF#p$7zX&1Fc}6 zCmT+_Z#wM3pQkVKgbo0F7%5S`?B7Yc5w+BZcxqcRHOM{cEN960!B-|Pi!aMsdg2vc zCa#<)X$q3^;vsc!UaL^x<$Xa*rfw<9yEMuUWPjs#l$d3(1g`;oio!U)wb!n5c_?^) z+vi8c)BSh9=`{%O1%h!hAxr7MaO{U}ySDF5J(2SwNTA<~v8l-Ch+SshD`^Q=mea1( zIGXIZFS7lOHfZ34D}OU%*r-)dBHlAetw(&fh_%luGmoTOoI&y}ofexz2AGJ#z7(TM z=({IBZ5aE9Cs(*1MdQ|)wte>7DZ|$`zB~HvIju*nYW*swV+!*Hyq5Oe8#ru-*S&_X z%4Si{@DTO1!grJ?&MsG29_b0=+>E}H!N(hS zkr9Wq*u-Iz#M6kBc!DS)n5^RDZg~ys^hZ48&sEXi$xA;~EKv;U`!6DfV}m5G9*E=_ zjQNpht<*0-sk(Hc_JPOx6{dz=qd%*6(FKI>zgn%XeEc03F#IPs>Z@$iel8v4QsVH{ zqKfyY8@gFo)`BDP`dA$CrLCPxnP6IKr%@vI{;SD`$yzcY_~=h-W{F zf4Y;<$DNK7mMZ^_1TUSv&qzSVBqXcvq~bU9nKahgyine2*qXAQZ# z{x@Vjq5qH7_=ng+f>Wb%Mnd>;ORDHd7Q&GR|IaPeh5m|hIC|W5`JO6zZ;XwrMD$9T zXu=I+M8<3XRJIJK&>rVkyLfk{+ zma@t}N}rVYGM0^*z*YtU1&j4j!tqhR*0oQD;eRqm!52qUBLI{$lBXu=vMfv=8Oi&< zCTTMw<|K*ozb0wE+w`MfpcQyV^Cg#$q5BfA^W@GqU)tQ4e4D{3KQzI&`shx9Jb$Kt z$(4`~kL0c&ai!-}+G4{$`uU|zg!Y^65i}E#E{`W`_^y9D;Kj=m;zr69-V%_P-aZJO zR?`@&k+4167T8o5{zqxCOMdce_k(i{eYFH822#X}kM5tVHC5X*rl#ubw}*6L(bK^O zc6oIZC!-D}KYuX&OIHit>rYN~yfi5wbELUF(=48%b@=L2*Y&wRbYWDcuwkfz*wM|R z!`)Qbnwg03 zlmwx&j*gH1JhOk~WXETT=}kAX14L!&`k0m4YYi+176#3mAGlxhb7>z1hSZiO1IO(V zJp6l*)zRehcM+4<{0`McOqA#QMe!%SmDzGHDZnwdG(HX*KBiSooN9us%FdK-8h?d2 z+BR|IVAuhjqB$Zgms3+*(q``R%YLz7oD*?ix~H_KVj6JodQqrzx?>W^#`tM1la0(+ zthxli{Nv^*8f*5GhD|G>qj}m!1A2>+1(4-Me3CRvBfI#$tZ+acCo+%ChUwD-)1aes zPc!PWL3R%dS^%nhKXG60yFN`1I={rP`CjKFAH1cr?EGVmnkEv)A&`dHa|E@F^!3*d z3ZNd=qYX{ijCbf?EsdBiuOjj6gs2@3hEOly`9i{9#rEZN{rYx+%u?Ws&FapG7wgS` zmAY07G9tQuP3bpu&zAv&(TA^3SE9dDtTMrjkAfC~1@MMv{sw3Ckx2a$Yv)=c{>P{Prc30zPX0V7(ABl6fVR>7RIw;^piHcuIy@4{R za-|BsSfd9N>vpnT`Nyds2mqiqpX55MPp7CYp_Kh_dFEp7X3lt)@K3k?`fy<-d`!Q* z>$b~DP}vN8@}JX-YM-*H@RsZy6J^Xn2mSmvoMCEq zy~dShoAGB1$~jdz07KEszyjn2o7#0&B*7_zqeTMxvVuD-Q4Cw0KXf=1-)U3JCI&%( z1cWxJ*;G(gJ;Td0)Df%K#oyq%4bN)ZD z5DExU-vhG8DPXbIewH#jsbC*E2+qbtz;f)7Qk?^o8Vo{4Oml%B02p{_)PhS`RkfFZ zS~ibKlE9RTgNE=AiC(&x>fggRI~Q}Xl?N#(4!sdFpiG$QDlkLfY?idd8q;q_YuOWa z6rd8rv)rDl8=wjzTlEU;gj#Br5U9XRF`+|Tsx0~=G-3@eL?BoRvfNEm)&Ur$;rj6& z1eE6ipva=m?WB5{36O^qUT?RQX1Z9F@GYm>^(KOQnhF)!H8EIpN+Kj&B?q-S zGSq~L>AJe*rB^=5nBGacooD4Qv^W#WS%OUwi^mFmz#!l=rI`{c%lw-%HVQP=6s%b( z1z!nQxJPHYMSF(TZ7o7@WK*cMA9>1jgF21Y^2Kw(o>#$BIp-xSf_B=J{dq1{i2hq!Tb{~HxCx9#6h)ovCng(FhaiVFfY#L z)Wj}(B!h34^TZzlQ1BPEcB9DmB%wnNMzQx>y&Jx+Qq`Qxprzf)fFTtp7|uCyjbLCKiW1cL3(?$>d@k zqlUEGOEbmG$^3$YyQX?gti)J?aAgz@#__l9-kkuUH7gjZDck$G+7r$=(;6Qr6{M{Sb!xfg2~T#N?qf00U*msIumb&zNu0U;?TPfCtzu zcLD3G?_(9hQ_(n7xDFWfHi26Sq%kw#vp8Ha?U@SU;bOH0==klS#mSFF=9erCX-<&b z`DM}L_QTWZD_i(AjNsIgx`|%ton-wIkwgGM?spQE`FNFJYJtdByg@(8F3V$E<}-60 zFCbp|r}q7-b?w6Z*0hb+Hk+=>xhb(r$yPD7BBD2%@FIQL(hwf+Q6P796YGg4X|@6Y zW-nXHydm=(J6-}qx!_nF!^*+-@rj)6W0_JD3~Rw@KWP(O(j6e$4EU1{2GHnP55NHA zHyAEq`tLVBd*N$N8we)XvycA9cK;T8jL?uP>tDc=-qcE}3?v!*k>g*hhTZSP-|FUG zTjel~^;Oo}k7f;_o(R0bSSh^D&Wg1YN1`8unwH?Q?$Y=mb94)Kk+2}B=agzz4xteB2cRZtbe+10MJml zeuHw7TFKbs$q9SIfoX1}>{u3ln?bk}$cBd?6}wo#M$0bDSX*)t)D;7}H4Ahrr%yI((=;U2Vok(T{FFuTW5A$|Wi$00qW6A<~zyHjYdu1MHL}zRc+& ztK~V&GB(f)?`*2bS1M=m*yioPl~Ry=3rUOWaC-93dOhwl`3_75aEp;)HkL|AC||G{ zfAN4`ff+xyklG@{8fcfKss+)J>=TiLz@rEnzgIQBo>5!kH!bOd7|qjX%X9?9OfZC$ zP~enzj?)^s|` zO_k2B*7BR3K%jZAt12&;g9gn7&RMjX9YUTQ#;-A7@2$wbjW5KB3H5<+xxV>Yor00Mdbp1f}p^R z^hhKq6#`B%7D`dB&O?r&d3}ZhM9~8ig$cZDprnqHl;RZUgPn2PA+!8UCiCCr<{ZvU zCdups2JmULkJdu=5pLD`tq*^Rc|J3qEtb9U-xH?EA(23^ej{E>AuT}bsq5lbgP=** z*{`;Vw5!_${jw+g9#W3SYqpgH%>%sgX+1)Q^qTz(GdECM(!)$<*|d_VNO|g1h*KRQ z84UERY)FQ;NqG{@u`ypFDC1n@^uacbKU=;+fxquMm?G zOxBsJK+1upLwv+URWfRY`=rv_{PTWtddjeO}gy~wZkW#-Pnyn2Q82B1HgQpEb8J~<K8oS#U0FH9=XCdx4)c|$pvBkkLO#?q_-vkB0k-?u3=Z}2`o zkf?hR>eFW@^7BikFxH!kceZ@#$Ig!Sm!+#8gAv{L1*67VRD%ULoH#DS2Gv!Vy4xvB%8pG;9c7MjOk&wt-`CWb^4!A46YZ33hCNnb_w z>u{f?mFD1qz^6}|T&05VYslbftZ-Hfnd5#&NqEQCGcpq-`O&xX6W}L& z5-C341{afIuX}sGt(o7V>6>j-E^Z+ne6yi|<;u%T0oz6KxEm!U_;MW2+67Y$0@o7U zO(X5PO6?ALNaxtZ^te}NAUrkr(%4t?luIMRv9%IId}Nk@;3O2(?b#NKmk|Du?eVHXl{JG#%s`0O?KiKjYtJ-s`PkuQf#z zM5O#4hnZ_1_j>^&^@P2+H2U9YlK!wOCJ5~On=^OyW(Sx>j(3J<~MT#+Deg6Ew;{#1d6j;EZm8(MH4C8 zb0a3>w zy}Gp^)q0|CJW;lV^ks@H^w1r6zKLHNQh$*frQf97Y?kk=e5!=Y?^O|D+Anf6u~e8a zEuo$5k@or7Z~QhwA|(364SbnnK*X#-wDO)qVzW$VGjYLuQ1gyg0bRy;#-@;VbuCbS zTve@iU-*?;(ZH_fXgyZQG=J)UJj-gw%@XS$4E-2;>|PUSfScNXDjd`5-9FGc%>d5z zJx2Y&xWKr^vj;zfqe8E%7tQxp@T=k}fL$pw{>nbluw>ce{y)_}s_L9{T9{4RO?3bS zt`d@?%oXAAXLU`<-7uK3v8pXOZ1`6bLQn;RN^bOt4Ydbs&5v07RbU07sAIf>hlV}p z0N)x(TLP~Z3pSb`kv3R2h^#lfwtJ32hKVTHz<=T?uW4(IwyWPML$UU?;hjBOs;-H9r=f)`wNy!Y!XDTMofN&C%!L-bfzF!wUCtGQ&TeER_KnTsC-=Sc_ zuP*$Zh^s&1G~G_6)2x@logBI5uT5pXU@KdZGekuLNoO;_+nMH&4_24GOw*}g$f6y;j3*+a#cfVD zk_;ulMk?#lDvMYC?g_2_u`y`CZ9O-AON)%rjwQ`syI}T33i35adm5{T&y;ne_Zu(8 z-VnTY5(^$JtGqX>{6i|biI^M_Fy>MbEBA<8EEjNX*gMI0fX?$>Rw#1+mR6`Ffsc>0 zB1MkaQUi=6Pk)0n==~=Dune7H;2lb2*c*3lzWk}i7Jn)uzi}_>KXF}CF9P6vQkwkX zJo``Ef$zu7+L@v*p!UICHS%?3$WF;sdvd?=&&8~M$_Ej2`Uy}iHP+|5X3=_s!=(+% zl~(+SG>W(Fu4h2{=PVP!^o%27vCzKNS96VHFu3mU7CA+>a@oKuNwk*qN?6r5GT!+) zxuWn->|bpYM?$5mZe^tUz2^gHUt4zhcBeWA9rXbwL~r|wxxz8nO8;~b@BxqyGCUv| z&y#Qg2}R)vPa7bx8Ce(O7scviBpb=qvn=*;8yS*dcIsn#z9$HORU()!k|-eVX(l-W zdT(kTpAD{GPsq^)aN03?pT9ZuX1jq<*0%{vu0ObVqMvQLjFPE;?fk*H`ZSr7l+{lkadqVxy&-$t2WMHDq?60nC zkMwL?p2hb+GkEsm_2)52C6Sl5XIQK~qqgA^OL+IW>(ZJ5e*1XrLf40W$bXMja@aCI zC3&^@KBvGZMvToYq#>3!Vh8Xy?W$ze?8I`{ir=~LTne= z(gyPVn|aeYaq`!enQ_%g^y*nK?W}0xVk(c&>OOX3-zrbaIS=qw;?t6#*Lrw-*J>xn z@W7=P6@~kkDeWW={NFUr_K(j7yrzG3KEBbLjFaNSS9^7v>gYI20NzeSeY@eky!z`q zr+(K5AR$Ugq8zOS`+Lh1ACD>g(_GbgniJECt`D=HhOanSG=7 zHO43BuzCsHWvn?@i$tGBrmNp@hQD)`#X(EsE%naceFmLzb?LrcJ$%f5BWPqB)WqmT z=lw|Em%`&G+&a&m`jK2&YG_Ybt;}){fhT0! z^f+S%DWpp(5-8$n&+;x;gTlC7R&AHO1vGoxwhx{pv3c4(oe|T9td^^uA;qS_^8xAe zKiajP3*u|OcL>n95{~!Qi(TH@{jlqeYp19s(HqV0acSmHjGtl3iLKKVmuS&H$G~%! z0-D`OD2^N3mpepOk}6VL7mw{+yjT=(E5h^hi6nJ%=-q06CNUb-jFoEy?itpkSPjG_ z^v;Bf?>MTQ{groh8s~IWs@v)M`mWp;1VXCV3v|rm5Xm<9yEfoUP#V-FF}nnV9WUG#4N%jT`!Yfq7UrD0J@YQ@!w&Zt z`I-k`(CN-T`Mwd-W?2jl%^Bo5EK2}NTs*()u66fuSiEC4O7h70F{dBvv-11+-VA2isMW6~^ZKe;#mxo-9VLyb%K&Lxt(>3cq)V~C+roU-MK%Z{?{T!J z6*o=q^!oFZc`2OL{^Us}qj{1AAW=#_@=h`2H6ouySg%U5!l)?pg zc!-`W9iJ5=0=^c0N{gJ1oCg-iSL-B1O|F_FxT(00qa}v4-gUu0&25D-q@x3dfO}FL zf;iubI}9mat+KTB%&7#DnPi^IhJcgqs19eyw7hy6Ti|Tzeg2oNg|`>@uhjKb0Wd&H z#5=vG+c=lg^ot-bpdCbVOcH(U)+hIKjJ)FAkRXvwcq7+~hSM)ezd1<#E|A}Qm#+aM ze=y7qP&q9;n*49!kt?7hyD9RP0(tIvOv_{54wYLszUAu&Q(yjMum5ksk)r-q41F1M zAqhTSVwtm!LJFAiv=U6675Fm59rh%IBq;1Br8wo|#}Kfrr3^C%5S$7iPj$IX8s7z7~1>CvXvMRi)V`;FPofVlUE_`?Z)VtgZyg9!r%3yggVkDMxTQmwO z&c$!7p>{Us?j>BSIwpe_Ln1a zA1?g-s@==)5PgTU@S0!0z#J7GQ=eP3Bebrx;>3KlBe(ch%evv-#di+4AEK2qR(!wd z5S75kLc%f>BLQjZnM&}zUX3&$Yc_=oVaDBtF?ZhH%aYW~dkp250^BjV^IhV~gLeuP zzE`0Z_Vrx3@^yi>-U8P7ee8(U^i6?~gmLq4(YForh52I>7{i4y?kv1yweXjjS7+`x zZmfmn76AWl-_E*EsW_HmHrh)P!U9V~NThW9Dg>>Q=% z-xxYBc0sTj0eSg*^9<&+zBwO9(XUk`3)aev$iY`$rxa*n6;y_lZ!rM`CHl~WKB8i1 zb{>{M7SGg_hr^?oV^0ByViS0#Gknv1$CQRkY67s>waIQ+9OiUgz3JguJ+DXxZ|8HE z6k=~D1(GPPK_wxmvw#b9kU7X5XSP!Y@|-Dy8nKhssGhE@B9Dc=0VSwD*vFVmWx=oK z6fe7HERr!x%sHjAm)32lNFAsg;dX-`$`b9yh&6#bR}SexW|;dy1ms^na}LLBT4&yh z=vikIg}!LED+2)#a5hnMZtPB&!Cv~0P`C*}+F(U;t(xU0Nck3!lvILcH$fv5FC{@A zVOB-gM|MN9KC$0A0i!{OLi*o;EWCx0t@ZCNKj-O_JAV`4wejy^$o9j+o{_c%+V z_sf}Lh&6#Xd?TmPUDon~IdYYr!u1fqqRQ2aT8>Y_CDi<1{5--8Zdbj{h9VPSW+fo& z!c{>q?nPI7B~Hq7w)vImkiN;Vak_qJ>b)5WxrybQszvDNs^#ljCR_R>Iahr=z%U%=z*yETf;b%Hl%$KJL?&TkPv^dy(^<2Jv-^Q`_ z#`}r?)~1bBizi4c2iJG$Y_~3*h@LE^Ue=?sgcH0lMUHSwA;+wt)(bz5H&VYou8uqv ze3$Fok6Q+!$@un};P}Q@Mkmox^C5J)u(iR0oM;fSE9+7^!)bUi+OyX8#_LtrGw=fH zKdGq4{HNnpt@^R5BmzhnjHZA#mf-*elfO^%Ejhn&&M#XWVFoLT;R6_|sAJnDo>r!~ z)H9^*57;|dE6ou{5V4f_wU2>;u-eBxG7XywAC9!v=6gN}rZ06~5@(_>^W7sb6_g6s zCSw>Y^)yz6Uchbq{_baw6y9LHzvb_!3Tb=Ll8%D088c&t7y#kJvm=#t4&F-y*9rPL+V3ovs`h~hF zAj$yGzS{qfaJtf;8A|_ckvv!V9ZMU&v$6*jZ9JiWl;L@px#TDou zHWn_xkdA_+5I~~Mk+lZSo@NKSs|Drlg+DW-YBlFnHKmJZm|u zmZ2^np%W9qh^C|%c5EDb4|S}^uSNzrrV@h{p_m-?jPce)Zs~*x&Zcln$|GQRB#~c5 zixmZ6D zp{w>^So*lmn2G~Ume32dYp!=}c63&ob3NT-(_lneaKV-Y&h$7UCPpO(6UQNYV?T5s zd4agEEQj+ZE`xm5>sdcuyt7|_k7F~2V~$e7VTOaLV{07(kc<6Ut|($EJu8W4^!R~0>{D5&mA-$F}Y8FlVuCSlk|0YibkB~~D2Tp5dT?q$;} zD%&b5_Fd<`SXLrE!n|)u3k@=OooGZ0bCdVpB7m!iuHg2}^^}m; zGJdGVihRH!%8Ahy^f%Bov9szUp8%Prat$M|NY9V^Fou>mv`WqFf0{XIn7hQ9yXToJ z`hiwD>o?&2U zhVCvwkP>MfN?PegLAtwZ=x(HA=7W(O z3A4v2LshHtvjq+r5BA?eB-5svTy2`X7n%aXTEaS77-sljGc9RhZTUsbVgegopsJHoWAPcB=feIq1D>ork&u1lyu(RNu11LPyt9>$mMi8{tMe z!M6d+I!|kvqJ5h{d`n?B&?fOV{`}QG6nAwXujoC>)ZROLrKr)NEzFo}ud( z`15q_Ku_#0ybMkTwAZ)onwCu8U$8ww!g{@^#!Yw0WE>ubIWR6ewAH*yvBy=9S2vJ0 zr2_Mz&FT)@oy_)}Fj<{%bYK5z_mI^wTt*mjU0AkxF>@pEJqEu{H^Gp#%yi3aZXIl1 z9o$#e)N>SFvI`XJ)u*y|K^;_0Y&Pcq!s1tYdnB)HLaE$u5TCf~X?d z74z#EbU3O9#*zC1<@NCI7_dlkEQO4u%T$A5P2l%%6V=g(mBgT#~sv3No7MB z9mY&Kj)=Ct@a%I{bo?0T+JNn|^Ttx0Vym4=G&8(jKSJV)?bk9}dsdvrJ?OoPuPs9O z70@CQwE_*q_lP7&VNu}@;$|fX*e(M5SuxMjWO!RC5G_n2JB%YcNeOX@X>XEMijztI zMBXhXJ9-e*FQ>S!ta#4PVLs+b>Z-j~+_ z!Iwo63phSIF{C@hYZrKMFvWOxiR+q%bT?moPF#wirF9o#v%6}R#cPl{ASNV1X)kn2 zq~WZ)Awl0w;;S{M0{L#Hjh!%J0P{zDb>fPQ3x}lnl(YSPF9chNxdSV*0q_A7VpZ}ADA;(8R7eUhdeXL6wl=<`kKv|sFZCLhC_rH0EeSTvH`A*UmZQ947zQoG|fA`_Wy zJs6Z9ayOW*Oy4hN!32G0XMI`kddpL8$|)DgaW`ek^yj4ar)9-w7U?o>DB>|TM)*va zzZjd%q!43iSjz?$)%Y2M`i!aR*HS@jwPqD)Bk9GNfbqb_@k{W0mEOFQ5BokQzwH6B zT;hR@<@bHF=st@zTFzCeo(De}Q>B^Y%=$CCHe=pz2&F`PzPsnmwOdx3Pw3a>!|{tH z1I8#9Fc|V>|3+XH@IBMQcqLs6eS@tlK~A@&wY53U`D*6jE3KY&JGAfz5E6_%X#dG< zlKeWspME=7ihZIl@G=$i3o{?C47p5}4e#}SOWF3rnbjZQwUUl60_5@Q$Q1YfiI)iC zFF90HI}p*;&N{>LgrJ2U(p@1N9KmZwv`-0Bw`o6-&etloFNJ|${umwedZzUKJr)ka za@+Bb3V~H#e{1k7k9)%Gr!xOu~^v>ZX0J7k<79KGvZ8#o4x{z!>F?d^tc#RcTCR z!1#yq-G$U2id+!e$RIa?3;X=)11Duil@|K|}HXlB8i~NP!R%aXNkIhny!~ z42Eo-DB?yRI?oFL5G)-}VMD9rNK&T`QeizX>JG5gWLL?0Y(HvjD^&3!TikzMyXy1n z_{_4u?^$pT3+IEc0>lHql8rorsn;0x#gYS2p2}sty(3i`#Z5_~f5u~<)UCBStba{c zUgVvmLVJwY`I@Vi#s%CM8n2-Eq$M1e2C7)Eia5;ZJ|C^QF0;>$^K)ut#Gea($1r0b7NVrv&5t?3akJvgC%jP|L|Cc~g^mMuLXpNkZ>BrW{ z^c~pADQYH1)IEpMm<^vn!IUw==yw72pUdsfA;Ao>sj{7X%gS+*33-BNSHC=8G?tU) zt8H|X?tC$RjQ|r~%?H$?sVNKHmUypF?$Z-Zqcm>(qA;%?E^P6vk4N;joask@GdnQ1 zd%aSbrdwptyiIpce5?w~dK<$30XvoW`~iCc_(}HQ1Z(%(x6lL`Lh8c!9Ome}P_joc z#In;fXOZD5GR<)kbmX7M=`$T3yz#$(-2Si!vNk_)vfj7*O`T(x=yBi8-+Pnv z?3T@CUg*Pv*}GfFWtA+50M85j@Xj3L}mX zy6m-itf)A4q7823S$waPhCkDx=Yg&}*l^&Yr~RnL`P)MVro5WRGH84hEo1IO_kC$M zmj21gVRMe4vMc&k3%+7gdfH3zk8+^SZN%~~IjMIHA&ZUypCc!}w$D~}8-@>CUG01j z^CeEtdJ^R-dHQXrX)is=x9dx0{*C09+_XRm?Jhm%RE#Me&q=^$=IO7Tl_b863sw_m z0&(;P@jOt2bWaj)oYm0__4~sha7rW}UR56I>eq&)Mrb_Uk_UR`CH6Jt2d}6RQjH2l zSXPRGWrqW~5+%ll+9eBrAyuN%FN(T|upm338YV3jNEFGp@UAjt3Y6 zke^(cJl~-y1vw)zVqUz5$g)3tZ*CqiM*|Mg9}w|Uiq?=*BCg?#^nb8Vj_DHD=;xjx zj+@HsO{PR1b4v6e976k@3kT2Ovy6avcsw{}ZQ;5(>!Dd4pHpofofOU_|D0Kj#H;}=-De6iGKAfXXc&q(IJPF9r-{N`H_-k0Rb`BK6-TJZ|qQvW*J>{POA+Nhu;2cHF z#oM7hO6X216`tYFC&zk}vhi{~KZ3D~Wj!WZEy=~4c;u1d{0_G8{xj|!m^ zIXERvY9vJh=4bs$N<^$SGtNbFjIjl)^w8AfJHf2GT04Pkt`D_#o;Azq9OxCM=sNKs ztC0GhJ@??NJZ3 zjq+U7CwSZzK%R=Bju?6-1Hz;O5aAs0&v7+!OZn?F(ykwtcn}U#%6r%)B%7*pex{n- z2+~aN%TMuJIoAfhF*Ay%4n5n$LvY>>W3y#P3c`2eZNueg#~VNM&}Sj^dG>JwRU6`t zw8kH4Klb>p0)1K=5}qO1ER?e0ymW0eA*^`9qCHP2z`|L#{z!iiXX~W$IZg@bAlFd7 zK2%YBfKXeM38M*!N_-xgkOLZ^E5gR%?roZSH6MYbu>eb@Hz!cM^ZBqZac1dNo6T_3 zsZ>X<_=K-HdaO>sSLsVpT4ul@M+5F8h8_B2t{rA7c{+w8lWnNz^&FAQ9)gWDGWTgW zcIwN@Fg7wr^4y6rz?vt5+^xK&#+-GlVEd1t-&RY<^}}8q1B==-pD4mi4^s|SpOv9U zq$L<+H3n)1Y)mUy!d9svj{LH?T0Wy9f=ncQ3!jOY|9B|M<$rlxXAq`^QV8n5`s&fa zu_T@?Y-#6cuWV2qOcWxgVlTnP{!rYaAs+wNgLCI#cPGUYKgwsj!hC?o{gvqbLSJ1jy(O4FP1%xS%POk*~yy{;YWmGp-U5pZw+&(O2Zc?G}kmrlCYV#JLh3CCNg? zdu?m3*N)$ig5VK>@hmu%SM@P9e??#x=3GjL-TQpzZn@zmkIX;unNBOxN0IrqUq$M# z|GE1e7@W|NPpcVgVLbOa07QFY8YNr~q@J{WrD0x`75!;uFdfuqgXOunpTw9wy=-yr zbaZP6IzI>>&q%nExcll!>)l!C@Exr47ooqMP<9CVv*#UmX*P7*F8VqZFXpMtV}b40 zEhe8tX8XVPEdA(7KWsUum<66Tp~+>_EOK^W>g0MgW6LY++bbP9ybG9Ha zzo?NArLz`Q+y~J(J<%s~l@XSTZ11f#)@_pH*pk9zqY2HUZC66A;9Nbhh^Wr^T+(nS zVwY=9sX6y#$EIMV#RP*Q=pQ6m)2Yy9bP5M?%BN_G9YtnU8-ZC+1jH-411oO!LEN-r zoIZAvPgW9S9@Onag!48!pl|u>stupnyPdchHEGs$< zJOpf>5-m1@o+zQ;mMx^)45k?Dq%4^|mwf`mBTkq7^Y&|W>T}!VnM!wFE=6Kr@|OsI z9h^*Q&$k9CZ}pqr&g=wj4QVDm$T0U!J<*S{?n?d9nLaO?=^B#-ZcY(55S8qD?aKuV zS+XZv$;6yUwh@c6%+83QP72M+Dy-6u@+J55CHLl{8ahWnny~YC3F}4EGjLq+sB;M> zC~&wa+hdY3#)6A+a{6%Wdkx4-ZOO}5DbbZVwMRJ(N*Rdk)Xs7sIazolODq zE1=5B_3q60nT=$%Bge}zd}^iihni>vAxu^sKb4(6`O?b{DY#f1#G9&H+daZPw%IxfkyiuzX_3#oa!+aaVXk8j!cP8RT zoG|q(!m@+nLTuHpsVtDwX)K$Iyt98wzZ-@Co5?k&u%w!%xYn+AJ%=yN&#h@qre%`Jgu2LzDfw)>cDB2w zm%A>JrnbMjbSSn?t-5Z*t^otHMtdy_G0BwdTR+6FbVFTN+MT%cwH~XdbhumkyD3?P)O*mjB>H#w<#s&wZwc^k$4hU|!i&vOvCs1_oG12!2s9mXQz`Yh zCDAsgNYtg}HomQC$vp0^!|nOO(PNiY4B2TW&+SRLDK3la_J7zejMp}F+%aO*o9@@k zmD!68$~Lxdx)tu8Q)#q_>rXXmH^)s0?&<4a?R#_ChXu-3SHxF1ZriV^oHs)ERjt2U zxGAbpd0KbVFH7|Nz~yqbhM=tT>4JgzyE7)|GS=ko|w7-9g;L1gG_SY??wZK zz5_Fv_g+Cc<_b)*BWq61LxiYwN>e*TXnj1EV;lEyDfL7=1T2BWeMI zWbvcI)sL8%p0YAqYD!vJVv$&Ty*E(3uP}{0$LnzI;mt8MHRl=RzkMf&-{rQ<-5^Mk z*zUl(<5={>&SQAkOEt(xGX9fdtfS{sQXB#O&$$ZTdIvjNwGro*gV1 z#btu$&|5oG^lheu2gwpg&UP$T=K5r{%qRZ9ry>6R(MH8gt@-v^yZ-S9tU;?Yi2Wz=hGJUR#Ok3X6fB@KfBQ<94FuG zG3XxvTNQzS(nv#G-_XpB)9SCJEoeF+8V0-y?Co3ZHz6O8Y989$s*2raBP`7BAQ%Hk zFcE}h@MXR&8Slp4oJKs1QC=E`ZJWOJuO~b7{ht~Cj#wz~g&fxr4iJ@K0@Lar64`dR zIHA!9?8HXAA%4^KP)WYn&*v5UCLi_(XFjX%e7>1p^tU7fw)O7$x^PUA$O!#da*~$_ zf-4t7g9ZO|@_;1DFK>c2*v{^Kpq++B0#;(3d%N2EJ^H1zsc^y^)%!-g3>Z$`_pc3v z$4!rpTV5QeASv4tkGtxRTMKkc6JL7mA778W82o!Y{Nmehi*I9pU-;^53}_4w3LC%o zG@fWPp1CmQ0fCQD_^JcY-!87v9VVN?s0_a&Y&*Byt)s$6BxMv2Bt5mtZ;y^4FuE!gj$ksv=qMY z|1IE9_+pj#1-Yf7RrYP_74)eK2D|gmd#RbL;pfBIpS;hoc!|yh_|6}p!OZWzO*ow& zK)#7Jybzr|KifNh_URmuKW#i4)wZ(4&9pRHvJ{_3V9zykh#kM6R}7%R7*hG8xAsa^Idm|J-pY($R;J z#BcU82tCe1{PpvbtJ9l~Lby0l|3VG@UgPZVbg7%>cZ;VpH17jk#%f*g4_shS5|U;4 zmy8!$jAJy`M^(-rSwCz@x&D5a|J$$s_xz8o1-?BQk`IqCgzA|+r%hPCYcN&#tO(kzDImjCTRw_bVN@S4_}r`RE6p6$IXy-u}zp!BE)DS|7mAVj{#5 z@YNR#ASU}Yl+=&x=TW=zz_BAdbdo>DrOPQAtI{Ju)oy(B$SnZl}; ze&2&SaP-eGRVolnzV_1^Rs1lCLq|E?cCzfH#`Cv!KPwW01*(7dQsBWegU#Omgq&g; zNq8-l>j#7qeCpDmybPbZ;My9Q9@WN7Y}3bQc-io;dYtG}A-% zVN5Xx7ugATsjA$R;)nx&tw&8`1)iSAnLHJyeM%L+>^IaXku#mf7>TdsoWhbSzTkT* z>-$yJy(BGI&Kg(kI!0Hbt){qK89t-D+E_{;Ka=55rNlQ(<~|)a@a<@Vp-fI)4Rh7P zMVVznZbDV;xYb==+*amX;r@$FGR_U^(?s#$YzlsmP?!|bcuw1P+B)QQ-SU!-v&~~h z1xIc{BZ*@FmzKK1`Qvh_u=^-GnpZ=LyhGc-M5jyFEby(^BOUz3Vh!g-&*f{TJG`ji z@@O;tH*vzh^)1qLo*2-J&zTw6l)TL_u&!wPZD^SrNMYpEwb*XtQg`>n*e#R3!`LH1 zO2ot~H-DFr&d1RvycXVg`6}Ri(ff7K&Bf(w1O|nVX(-;4E7NdNT_3YZTCb~}2u~Vj ze(sUx|2IiGqb!*c$T$5*l6GJ6wJz}g{pTRn@kAveILq|%ko~X0u1)D%tDMc!%pjW0 z%8K$e+nR|w@ne^cFWu{<*~u~?*?7@rkm$QbuE^GP1|P?c&$>OY&|SwLD4lxFu|Up! zI1J2@VDJ=q#URcldGBzG3SHBXt=-1>d&~F$D{M~2@2&&u z(LWl4oDh4Ob37!;u@+OHe0x-Ki8z5RyqpYuI{C&Fh3~cT8BHrFs|wZy$++gd0T5lG zk5Oky68aWE4SY?~Rd0$>=QCHNsrs3ALXWGO4e7PqWqn7^1|5i2kX9t`^5 zNGvkiP<+=7bNcz{9eHh+#NhM+7L)DgPe(w}73l)u)(|+&^2+nL0gXhDUTmh`kR(sK zFkYt+JS_}n5bTsNf+i*z2?f&{IG6#Zc6jp|?`|Dh?-Ie=+8G=M9GA^}Ql z#;6LI5?oagd}#a!)X#?Q*omr4~u9IUA_Q6vS$N-y8~+jkz}cec=snG zq}S6ij&`X&Pb0L`Q6bNblmURHi_%~D|P7(C#UD+F1 zQx`&xyvlV9=12K}MkL^XFX ztBXeA*-%FYg`ZcRFfsekvTWUcSn8dPIQ2l|0k}q;os?pc!Zf>P0774>wzBdy-9XZ= zpe#+Hz|b@9W@;;+vbJcD0#89xqLZm-#2y?RySNjzu9>AZhRcz6DbtE zo`T~tymjdm%~dTRCrGNk`OQnjeDVyRT-1~dT^T9=R5~db!P-N7ij{t{k?hjj!)$h? zfR!qEiuSV413_P24bj${M62{Nm!Y7d1N@lwh_LWQc%*z5vb7k|yRF04HAMaWG##%8 zXZKLy*+5EIBx>V}C}r#i`7QUfcN!zDa-$RGcS$`K8!U8}J|CCq-NINm4mcG?7m`kr z18sDVX@7JE85cFF55ehJeowXPU<3Bf` z-4zC~Z5Qe(iW%40w=tDOt_X$(z@e=T_x+t#*m>_do9Nb?-it=MQ-MEphAn)C23UIYo*VDKT-jfsh}HJYk7 znphtMT-7GJApB12oDQMH-=Y>|BWNA4U#rBjgiBNNV6$7u#Jk9R0*5~W0iLGOn)cXA z4`X>D2-cB)K1f|0OcpqVcs9btRb>Hv*&>@^k-SV%2txmA@cvcy_gbjYu&_yw3@|?Q zG~hn*I>cryqeLS|%rheE@zfKWCvIGb$KeT8NQjF|BJFJ^BN7!6pvFAy1Yk~|Nz#c9U z>bS_)t2rAKqd$IpPNjUM zrV)=uVmu%S2MYzK5o{j_aNj(tstNcZ1pOVb15{%Jzm3J&C;%=YHn&jqQ#k%d{+Bk; z?*a-t$1#z{V^Mq0V@l;?f5FeSqVxu^6XS`yTCk{GKw0R8ayg?==lR9~(MYdDaF$0% z{Z0HJ20qscREr<{tP=V_Hr`S+Dqud$(*<*28+d>K3xtOHFh2;3jSSz#t4yC%M=E0_ zN4g_I^IQ4)Rwk?1_~WppK+2P44wI297!x!YZivW8Ca_jCm<|cHHHGHxvH$3<(o+nb zeuLY-04n!T1`sOtIaA%eQ@tB11V+!fZNRoykx2gN4#Viu2h+m=Q=Jy7K%+|Uf=WLG z@vlNu7{cz+u+3$Mn|||GwU)<^#gcuwk_<+ z(16BBj?Z`(WO0@Qv2jP>KfPJ1DpUKo$TOaouA;M%K!iIg%1s{=ClAXL73J;{Y4>YN z;wIMVw5;Ol<#{U~SXdq67)`0Jj^(Lttc2Byz-o2C(|Lo7N1%?+i^5PtVLGDJ1@T(d zIb)xf{ zom9(3j0J!M49qg4q6Un6b7Dh-L^0WbaOaU|d_;sZLMh37F&ZO`9fjr8h{YWZb_IB! z!J$%AV5!4*uhsNCO_p(D5PqFK7L6iQ<`Fq=ST+6;&WG5_mh)^wvFP2f;H)uCQ-0S| zUaD{MUTXRgCi**_VtzjQeyAw>I4sMng`8cihYryKs3=VcBJl0IpgSnT*Lo`m#0$6| z3qbu5`T^?D$g@C$dy;L&C-V_MI9E8-r$|3;kv0BKJMn#V68k`MUGv(xFvWeNc&7m? zzf!iNVMX9t@gWc(IvMAJ>D(BtQ@QLvqZiMQS&wM|4B!@D)bq$eA>oFtYDR5=IJ$^l zmT0g#yu;iRlWhehf23u=)dlNe4rI(K{g0>nciz-VpmvF77l8#}ev*!Wd65SCbs?w=n&Zcp~_4nCv5j-vN^|Kooj9v>7r_4^z;AbU|C<2c z+1c6swEgM7{O`L@Q|Rr=FP}EPY^`6dOy0~6pqJv&(|-SV{`Y_3-%Cr2i;Mpuz~|@Z zKcePlXJX4Ct zS>TQTSm5>L|F*y@YD%k%i;MrK1zuW^|MzVWI)!;8J?LF-Om|k+J@ws{o&DePcUO{U z&D)}T=NlcN`;QbJ44}O{)K?3}E(*=cEM>B$+1iHZNi|Bn5S z{~Zw&6Yr4`;2-jj|Ly%R|J%*Y-NnV_o&a}n_BU}yDtlEu^KH5(z{LXY{qI++Z}idH z+FM#G_XK#CnNiw*6X0?(XhHr1F`*k)=39E&TQbs6t7sb=8w(4I|EvG4_aFaTRaI3< zNl95=<{kk5U;J+#9v*IP?*AtOoR*fBii(PYf`W{U?4AIJ!C?0aI3Xb+8VBbu7Uo~@ zKM=SXF7E$d1)P{WOA{k<_=DjoHkJwE3j@|)WlKD|Sb4xv;!8+V4I zNguwN?i4Vg3b|RjvX-}0qRVm7@6YoUQku?@ii7a_c^u3$DV6-K^t%|Y7iO6%P@^@A z4(6}^x;4}DZv{N>U>nwEOE{V$DHtY*pCb|VNb21^2b<>}}DR=~r*ZH~PT`o#3-FUB2|2>^rjO@pCZnaDsqUGFUfYh;5dt+(FRwKlmK~c*&+jOHyS z|H!-f3(ZRX*Y@M@J-?dblDXE&$U>h6VtYU=o4DiHNgiz6|L-!;(1#N!v%#5bm-45O z!xsYhStHnGcn!KgU)7$C(ltmFsg*B;C5lds{C@w86<_WH=iMW`0f?eD6aOGNMPn!l zDG$DDv_#U1d(5*!s>hBL-gH`{&pGRU&0{c|BvS>75|0Y+xoj&ug;)+xN)w-kk35s- zXLj``wW;_=0q;2RTEmG?9$5EScD!82sceKm-&~?kE#l@fBU*#>~psBQ!&C$0jac)#hFfi^`(rDLnU&I^DmaLh;cJG zEEk?el5xi)Z@%|le!uxK0Oh+q9ieoV{K2g#@cd+2@ptn zwP-~;w)`ns&S|WEZxXr54kn$88O>Mh41sZtT6?A%ON{KI00+_Jkh8`oPva+GaXxZ1 zk2H)`+4LA@+7vLQ1q8Jv3&~p)$7RaLVyFKJdJe`j({XEDxM1O>?h6VJaZ;NSk34fy z2c%og@wXclgm_@lu8kNJxEOGVv1_8A#V{T=j=cDxE57am9^ejvGj_Wsd8(RYG@s-0 ztm}`l?Ve?gs+PZGPq-jAHw_(Db4)@D8<=c4ve#1Vm|vX=CMIaB%RC_H@!ABf*!{5Aei>h~Z%aJX3U z4H$vHYSISSOliK`jB4r?Frxk=B^U~r0&(NozvE{~ji8-o_$N{FtFkT)2YXDQrMV4L~d14-? zWFYl|q6TUJNN(?hO}|-?&SNjKk)ATKaa!gue>?kl>3Z!&yKFl~b_wy{Im|3NPbOt@ zY;DX`gnQ#RDirdw_QQ4Kr%x%F;mJ@*22&GyOOfzTC-tFCS*H8Rzb(rnW(ArI4;)$lIRZ%15lJsWG#iqB)3(%dw%8Gkw~go?h!FdHu+k$u9C-A1d)PD|6O zT5dtZs>&#`6yJq9Y078x+Jx4IQ2nfwL4Go~m}9?2Az!Rjm|vNyERD@!g*^^t4Lm?o zK(Jktqa>9Zk1Ppk1|taD>icr-&qV($JXW~~@|HY`w$)W6oEo4(NXC=V-|*#ItyOxf zop`DByeYH#6`)REB;JxUU!Tz`jX*^zjk8jIxJST>`&#YwZZ=!oI;4X(4^6#|7DxWJ zH!bEnh1&pxj#m+q_;b!L7=0%CB0Gj^vRphYC7RdUMZ$agzQ!J`?}7(qXq)-*eYHE5 zj?6md_xes#Wn=ar=pyftPohk*uW$EvM>}y|C}VuNPl5J+ zW)1f)N`8=`Z8VK!!b|wnLflp9y>(vw`r83mqbs0O$~A!Y?pV?JJI>kw7EF70_9bQO zhmY15?cVsu07^Vy^5)PijDACsum=uqj3~nZsDARxt`P*;hqr8=L`P9>>^~~V`r;Dh z8FjUJN$=E$0f##3%VN<0M84yur(*9|Hb`Gy`)KryOE>Hof(9-!{5O9pjP>Z?puCxY z0q9Sr=c29*Kf{RjFsJm#q`H|g!=}l2(nb~!Rc3E5d7fVU7~IpVbanBOo)35scL^XBBA5FrgTTrPn>h<$^;Dxg4TDpK%ZP@{U4`{T z!31<(<#=d`wP^t;t!L!gvO3zBO$2*Tpc+AdFbiUhc0HiKH5VhkzNmml-rWIT8KdjN$$e z#R`_=Lim+Q-{?Uo=}`po@HI^)rosakNJnguH*A_e419)r77hETt~Uuyd(`#zbTFy> zH-q~94}a7>25OmDW@-Gz($osZiXajvPm$wF+*wIcdF<|J3dSG?vVObT9NOE7V&1@U zSp>V>QZl`Bv-63Ep>29FYpBiCkxM0-OYtLh{udmo9xjh% zvCJ1rDeRii>?i{akWVOO0d-mA9(DXdSK)k0!S9{iJLZ&OuDss{jPy)UE`8YizAwgP z-c^^z{zM_kb?Ws|rc`CY&}go_67ochY0oAR65`*zjNI+=BK0e7B`HE^s0p4IW+{1y zloYX5=L;z_QrgC1f`WhQl~jrpkdxq|?|c6MyloeveE@Hq8TQ(R;1`0hcAEse16e{4 zeSzUZ=AfStM4L?Je1oYEx}$Eh03fVrGm^h*uOKic=x33uGoS%U!Q<6ON-48yF%fRK z$f|DRTku0(1B5e7F!f}jGC1VbDM39Gi~&J7)d&efn-bMmB@`hbRY)RLR2lbmSypUi zCbupT7BKUZXO*PdM22^XrMjGkV|||YtwM<#4WpMW)Yl@C_ABx!E;B7aXbRKP%OQGH zguBKMvv47zyRYJGB!s=kjRXVJ$*+|nv`yQp_FW;jnN_%BNyFq^#i?~`;#_&VTf0M~ihv&sjibG9{%<@m>f|vl#!^*@T zeuZtgOhG6DF|7t58N3INxM#A1k^w%nDFK@Q)bwK;S%)QrN(g!Tpv49Ns@z@x%# z!drDBcy)^;9`F>eRYn3PPb*>8)C%0UAgJT{!P-tKn(T7gB67>~{xIxiU|};csZzHK zWH(=?{KIEw-2B65;|_zC`3Yc9F7i|108k@_KqH{u=n~P08PdvtY`ri8#F3a-04e@M zywDq`@Z8SGnx1I9uH7P#y?QKUm&5PKwV&3L2$zX&05UxVS!=|9`xUgJPC$_iD_1AP z)v8@7!ky@@#W;I)h(7O*g5yyCA$h5e*Ny^rs5o}{_a2WG^!YcRrljxuVl2TSBG~Rn zr1z2yJ)fT3o;V+bQ{R>wQ}YhK+th59=_A&woSxUK^7xjP*})^gw25Z{MRb4DLAdoT#e8$LwUBH-!;N@}Dx}gN|_lxGh z9wVWPJtN4a5&fGHd%E{gQ}id9AkZ!c!aLH4r`=@3>2*Bp1%NAaK>~;4*da!BDn^+D z#vB61)zQZE#<@s${6|zUqL%id@rPZnraMAHaC?~2aX{d7I1W7%skQ95vekG@z@(Gv z#19F^J;lf*Ntm#8GfQu=ucVuQ04%r>uMb9Qhr|+tks|r=^x%_9R+CkdQ*tsxp2gD> zpk_W07!VoNo93{Na;olqmr*;Gg-^w`jo0G>;TPx;Y{Df_nZ~o4X0mQ`%=@6pL$6$s zjw#KMHASe~b`pSs)h+zup*1@UdUQgs)={EH;Mf-M zahDml50!>v2Bg9J`CTzzOzF#Q>M%(SeWjeYO<1al9iJ$27@}QVNqMi7Fhep!&jqi? z(HNw>CBZ!Hpfz5ya$FE{W%ry}S~*(!X3Rj-feA*yc9?5a9G8m~R)PdZ(wGXdLAaIt z)1h}7)(H;wylakq)lxGO2x@~ zinM=F#oB^KGlagYF`u3bh1U<`LGX-s2HF(mPnW1|mN}yA2pC^FjwGwmo1*Yhu3oo<=>f*$0x;f!9+44=1f-iW`-0`)=KkN%JVnBf|j|jNY`vcTB*Q-lh6I_|?aIZI^L-=G_&EI2`900coW=o-8`>i%~ygzTxi6 z59=b|KR+J)B;-m@uYhUrA|JxAr{V+)FvWcR2!?n1e=v2{Z&AHb*FO`$&_jpB4Bg#1 zz|f$8h_rM_BP}Ql0}Lr35>i8mNJ)brN{NIZ2vQ0RDJV){QJ|Z-|og6HFCF^_}ZjYk8 zkp;gm`L3>M>u2UmbE&=H%bkh+{Yi~4_du=gkp&7zTw*1Ac`Ih6t8Buk;U}kz2Ju^O z%gP&G?e|M=FE{<@{lO-o`MLAz!Z)7PxG8RZ1eMe!DH(cX`-i3P>b|1XH_Ll#OD!vk zM_l1FdykzDmXKt<1ZrM@DM4dYwgS+YKKSKfW7IE3AoJa5Q@IDtiN6CTZf$xfz ze&dfV&HKj>r2djjXin-p_gD$vUmd!a^E`exR!RePATq{SP`3e3{GLx<=l#R``tRA~ ziQLS%LjtJuZ*=ziFLAecUc8);sUXjj*`d?{!B=NepPyuu{e%RqSl|EsjGjrTpPYS( zO;MRf_x;bRkKZ^UkrT93B+y5S#W{J%E|v3{ZQNNs@ssWIvx0KC^$)g>?~Y>Me^-{i zQlSN>Km7Rmg7K+V!!S{MHT~M(K)Qbq=r1WOzuc33KXLz@h8{7XwXZKgb<^VC%Kc*U zlrx(L7md7svv`^ER@sn&F98sWfcifQIFh6+GHYQA;Un7Y43f^nBnr4e0?%bMfxQ(E zkul*Z!-tK=8|6zny~1)_-!Xfv7@+kFCg)LmzZrT}rZcOojfGx#qnjhQVyK#{Kq-6~ z{&nQ(b$Of2q9>EAVC3D=yA%UoZ#;7cnKk&>e1BKsN0GKH__ZQIFYjvio8p@X&adK- zo!ct$E?b45$|1+FWs`x58wLE!wE`2Hol*XsUSjXt?OLL3oA9bM2Rx^3-`w7SYeh9BxMs zqB*>)Ev1=}$5q8kuwVSVm{!*}c$fx)G4+0$3&L2iz@ybzxEw2ILOtG$FcE(~Y-J+W zw$*AX{15N^^?U z0aXG-6sb1$TgPpdhP-i<)7aZaZz&U^euW?qv~t_L*EBy?(^wh`c35A(rmuM8#!b(T z8#iwyDcab1Kk2Y>2zv9#M(eZBCaq&gj$xr=ilEX>^E0eM_k&+zgg$K^dwdfe&xfjf zJ4PcC1-$Eb&{D?nNeXWW@hF8C!oX~#gG~L^ZzS*=+x1RzGfDYc%=h-c&I&(27MR@| zgH~oLsx|*)jTS5FT8m?{={DAy-N=^=`iT*c!p-5gl#*2NPx8h2$W^yE1@& zq7?@A$llgN&95=;&KVL+%P-vG$DY2VQyi)FsfQGZz0}ajz=*1s0Q(q|M-v8IzIUuf z`0h2Te(iZqBUB-fk}_3DmiL;?JN9`$(-~)N_}7r+q!AC+9K}~pm$~YuiqB&4ywLf6 zLHVsy!C%GJYoiAv(lIZe(Mr`oHIk@A2;nP{DPn&LE9EmuQs~pvlcJ0QUc!s-X3;j1jieKlb8k>FQsn9;NPZ*PTf*_FC2{URlVB!?tgXKdIQR zz?>EQ3ZmIKW*T=kw`ie$BkBRd_D<-D1ShjzyicGXCauorzIs;_5O?Tad@;h&4)Y)G+IYEPa9|rB4IgX*+OnOS`sHFk*Q$|nYK&|O;SN$ z>BM4~2MMbRK93mFs#8tuHc&l3xeH5vust<)JD-l!O~ku!jTY*{`(>bs&OV7>`=5=HJDV#CQ1t2d%xKxD2dVrtuq-R= zF!>sWR*ey;RK{&eT4xWedPHdKqpeY%AXfeNIgDX7X5&m%xo{s3z5t!CtMVg5J22X+vOvOkRE_+c`#L!z~ z%6P~ls{w`P6%Ipqjw$@Mn;z4z*rVk6OxlrFaUBgV22kU2v2h4H__W4AS1sFNrxkIA zxB|E&WXAruj`(*W+$FG_s}0*AgFj3E3ExP_ileF2ZgiCkD4I;Ko2}%K{HpI*geqj0 zD>W`n`~4w2BO!Q$i=1Nzm67`H=brcN+wr4fw=Gfl{BQ^PKA8T;&Z|PnZBc=mJdO{a z>OiA}AIs(l8f~lf_1Rp@fw~&-lO3n!(QW1Alz3c8qAH=Yz%UYVR-;UA9ya4%)Qzl` z-_Enrh9{31_(7%+LszhFm=?=3%YWZcHO=%^@B#YY02XE4LX%L~LNW&OUjg+jzO;3r z@i2#tjN935kayIl4s&_S);U&5k(iXhOxM-VEc;p?-HA)WS(C{n2NE`~3@{tX)ycx8 z{q>R+w!V5eH>W#6*O3Hu=n6tNVPihhpy0P(sOBffOWj8=;Hv$s%fUB`R6e#7^&5#l zaJO=3;C+4&Q89Ud1TB`Q>o4~aL z<8|Ad#^Mf;WQF>YWlvmrh~y(ea|bDQj+XRH9DG79M98#{?((S1f*?N&F8yfq)60y0 zwqD#I*TJm2)X$x_urdD&qj!_CcW1{0G~`V?nFyc-w8BmQ(4se@Us7vqaJS}1frNB8 zxTHUr3aKmU@0uvZ7Ncn$C~J8w-NoQw;WY*2BBz`M(-AucVetx9^W;KX!y8J|62c1? zsUY+Hu{8bE+4Lzj;||RS)uyI0@rF||zd{d+F_W59kj7S`>C>guS6ZVr6HmXUtKivc zyPxTX##=B8Lm3?m!rQNB?iM%Or?#*1Hs4g;>d?YYLd#O=`!|MI*p`F_g?L+}twi)b z3i?omFl1C~2G!T9kEaE;XHPaR#TmwY2+TK>B2r;|(|wkw;O&uSXxjM{9GIE5I&wHD zH`vcFWX)|y=`};>x5$Mpw&Uio=Pmy{0-m1{q-#2zt@@3VxbhgEJdAp`q8k#c9y6o# zzAJ|o1Ar3m3QK?c_LUkEBbZ8c;9j3iQ9|09dZ8=nGXUzjsl^|$5Hr;q_t%fNx+&l)mCTka`2a6Bf6{ZI z4gTYl#g_sg)%nD2PhN(1+G^iAU&mC*=Mj^=7NC%$>=YUk?N9~Mfs%#!mXC5V;>A!t z@~8_PH0b-%O(LRW?QBQ>!JQK64$&L1c^z_k2GU0)tfd2z=nr`i+Rq2Adt#uzC`&6s zBS5o=Pf;sD%CncT36H;})=Y#U3ZZ*yIAOQ~uI&}sJ`6xVc--5!KdbV2Rx6>9ue?6> zHTBE&iCzlyt5rD7AOHvjlgqJVq=6JKIF8nq!b1fk=tCYBj6)PYMdHAI)5*(fRSNc1 zF#Db{_C$`VOv{Hg2)BN+VXetx6y>l=#UWg%)_X6n$B}tp^wvME2QYQUaqAMzZ%Wq zem2aEpt!*f6M~U&<0(Pipkot~e=x-l#TK_Ad|wQAHAL8U|3OkBjI&=~APnW+-b3Y~ z+xO{J1CxO6ZK|VMD3<+oipc9Vd|vJ8~us@m43ykZP`ByQ1@cKOcuH?m zF=kUli-4xvuMQ4P&CR~=2u={!(@WZwm%wQyHb1`6|9&jif`8*0QNtMi{n|bO0-6AW z*r{EaCtIPytb#C!mpmUQU?2qqGzK@?+f4hYd+YP~PJ4G`HJuuQyG=%>kQ55^?&_0? z2boX^t{=?zvXtwSEO)6gPoEirWkzC>nh6JSY@=eSzse>^E!)>6ps9YcPfyG%gi>9{ z?bY*(JyH_?H?zHOIiWyZ2I*@#NsDxumB}B4%QQXbF^QruQpoW{5Sh7 zSWrD`?g6zbS=>jK6+U_HPCBRb1Ppzmu1L1o#}^JCJI8N0X5R29&7fA$q=~19K9Tp- z{O}5CuJik2N7Q(_D%Lk#$*!=$?R%?xUz5l0+1ru}WAJJU8O=i`@)q@*5{;>-l~Rj0 zFdbxGN)!-f4$~hH2>C7>O55UTelx6t@)5R`FY~6_Zxn_8?3ho!Q=t_xzc$|wWGltA z$iTmtplJJe8rT6n$muB;JG8!|_yN7~F>GSK1BN}t!k~xqiOun4J&W;9OBQDq0Ig*y zw`Dy7n9^u2UYyl>ViPUdoA}?BPUR$Mbr@w$?ZHFOw*&#IrOHA;(LB~d~2E&9JNX5(-A zi8;<%T#rV>EVIeV(;PP*JHDe`>CJR1SnOM+7G)t@X$-KnkaQxpS(s5N&SCK_^WiJ2 zZyHKGud0X7O>AfEwtjwwH#GKi&R}0zXt|jQ!#M9IStMF*Xm%{b)sM5h*vssAc{si< z)>Y#(Rv_?c=_BrIK*_gBnER(B=_s7Wz9yECkotSI9K3duf6b2CB?EVbc4oO6HZdh( zpZv%;)UVs0_CfVjD-NOwM@h11K^+A>U1IUY6 zzZ*`P6H*4Bq`hb@V2M_q8iT2JiHIq?;CQ{j4YX9TzSoVT->$rIsXvoGRwFu;TXCtVg*2)&{8?y|g;haT0H${M@n4Wbi>Ti(T;s0n-hp zx#Hy(k)Gzh`T%5raN zq%8O4VX8@`hV@ibdD!r*L*2hz_E&sYykV7&b7=4;=81bT2fC}Q+NJ+kD!{uj2iz(S zUeL+%3{m>zxVo9Dlt~#yFWr4hku<;U2HQo=;>y?TSD0qG4cn>+mSHu#LA_ z_1$rLsFZ0MlgbZouglwW7Q9X0=u>>py*9$Va5v-C?8al;TUGMAcyoo^tXtM)RO0M; zOChQ3&R>h1se_z7!z0k0cpLMH;sa0!tddzkcyO`_LnfY&+?8En#YFy)2+DBXGPUl{zor@kwt>&jz;?|7{rC7n3HcH#J{tf+t;nQ|a~ zsqyt)@{b+~Yl1L$5}#G3$xt+26rq zo+pRYUnoLlQoL=!XFQ>`utDeDAZ*kJV!jlqGb5X)4Q+h!g+4iy{eEzeyk%Czp>3}2 z*M^^Q_fU>}j81$o*rzIyypF+?RYRrTI+(c-Mc)X(&?)QB_YC|w*wFoiiV8Elk9 zd!M-~f|5%y%>3H(3|92|)Wo{jo@Tyr&^#}aeLIGarNx5~m| zVu4?N)V_|@PGL5a?StRNfiBo!GU~He*9w4;+ETA>iZ9nC0A*Sh*{#HW zc6nYHw4F@<<4N0xYr=Sndp;?cuQ|Mwx#6O@{Jw?qrv**#bDvY3i!+?JEaa-SJT!tN zsEgi}JMEpbV{cbJZ}w(yyI+WPArBi(x#L1E$C>THE)hCP5r#{axO-y2fRT#l?K%(O zkBzBS_N738MJ>p}Eik0utp?)A51L1AM;GrY{!O#}n-Pw)Zb_7CO#IOGNCWZM$l~8Z z%0C-bRzvTf(&ZU6!4kxUktqA!qqjkM8jq9RfzvRCXd4f<$f9#8-}5c++->iBf+3e* z3fNuZ_3+7$@$S7aTINQ z@A2Cc4n1gU0E3nUH(3Bg}i+MNOWVRfOi% zSs7kY5^}T;@O3GCDJIry_0g!a0fnWSX?JzzHULH1hVhZJ{Kfha&*N6KpUqn$p=4Xi>=FEs2e?joA zzI|)BK76RqADmZ%fGw}~klUNf!n=PJir9zmBH&i{aZEAHkMtnd><7R}MH8D2eN!eX{#Wi!@9vNofeFJ1DsfSVo2EeaXH zq2$SL1uvU6xFS4^-9+6OmCpdNUKK=S$_im^c;4?qu8K&t!>ZE32`!&;Xgm)gL^yq^ z<%9&CwW?6j4J*n=8Hz%uOOJ~{r|!jYUm5#?V6P%8sblNG55@E&qMvg8pBz#upQDCS z!2D%z)>J5x2}If@eOm08%U}hxA117Dd}<=9T=L@^n(_!xztP zh}~RfZ6|Odwsybkd5!XC7#r}t4M6u;b?Az$&9%K_iw~1GzdvUp4u|K}t_v3SeOH$m z2-rKfdR(1rN*E+p%5WJ{?;P0ges=p;x<+#Qa9|@Vq=)rJEUN0gQfY?FG!cHbb=PtL zo*?rqk=8DLoP)BRL;;uP-nSa8Z8{IODkAhSk|BOYkT`O_%e&{f}(viiX# zpQOW5*cxj7L5@J?L@(-KKjm4RIXAUymtOt0tJ9o&&iJ7?Q15_1{QbmmgYUic%1&Rv zXD&<0>&@;pE4OHS_d|#D{$1Wx+RCX9J2BDh<%oKtO$^|9q1_I8YZFzEj+Z$uT<_Y6 zqvg4-Ee6NxYKvPmBLk9)ynfInSD&a`g!-4n1t+(cy*`Bb%G();VzM;rDXQyCx&lBNs&DUpJFf8Hz#6kL!9_z1YH)!sOfq0n$lk4#5raZsRLd`ekXw(akP`X)u@?AzOS7!wM%L z7%6siXd7vh`D6J&NDND(ihmNBEL)G6zAnH47n?(Yit!zfeK(p0M0m%^D~a)WXtU94mqUhAiiR*<1^f0C6Ex|K<*cyKZw z3uHia5}=}tY4`iVq=hsxl^>RLwpbU$b^QOSFCIVzKr-Cwq$Nb@TseiMeAh*5VeF7O zjEXqvBi)%s&Yygjr0ZlbhQ?~Rt!g@KgJ@T72Z!Y40s@+pBY&_~*>&yd=BWn4u)$Ox ze-Ek+f`NGvfkuvIotog2j8bZ*^Wbu&oJ75~b~&PzgX&PFQ|f9uCSb1~^3%{6?}i#6 zczM*&)L&waz)j;HKawX4)!06`vwu3%zRFZh_<-vCT5Ixj@=@n+jasvL5^S2wm78-3 zQ0ceGe9T%+e`=J+d}#?uP+8}Ftv9H}ZV$H!b4R=*)LOf%$yn~|=F*NO(20Fyuzt5e z*%0^K#m6eaWre_$E-P;Tvwr>`721vY?l*&`7uVK88M|elr7*!Zpm%-H9M6INP})k$ za2OWyIuu1FP+VJePnT;`CE2u*IN%7tFl8)7VgohJ)VI2s1;0YbV%_)I9-AdH0qi&?3IJx4q4q_|0N>Yz4z-A+RL=_FM4jW&jRU+v%75A)0hjLhHeClGn0m)~Yy74IHq8BE_BdsOhF5wQd&^NP~DGHSbpJ|>Y~rqBN) zy-cbEXZl*$k$Q-fel81oZJ?j|oZX1*a)yb4zIvEE^=FBtnGEx&FeP0}y3Ilqueo{e zrdlsdSd1yhkYoy@x<*x~*>~}Piy7N#Bf<7v*|Fh`7!h0(H*iw0&D-$k*X3dtF z;Sv7_ebEV)xp0Sp6LcFv{Z0p%NF+Y)Jv(6qK3f-pl>Vc#Xs7#7YqyG*OOWi=i+}Dx zLl>VVq?c!2Y33YmZQO@8)hD>;0$O>M%(2Z&#(euA|6q5Rgv!gwtay5Nge&EQPf8vY zp4Jad)S+4=h(G7x_mfTGDb%uO+~lud^6CN+{nTy(8jcN8_xghRtq-^q3<^F}gjQm8Fz55tcEgEqSltwTV4MGn?~`)y)hT_KJct@%e5G{!1vi2rdm<0(HfkgGMNZ0m?i* z1gx4-jZ(xNG8yAm!LJAg(`egC0*wLT(wuNUGXu%9x-@=_CS}UivK<)X50+T08i)`! zIFyaOpfbLk{?Wo4ZVYR+1+JTo#@Q9AT0z^&P4|cAvr4>zr7O7>+Hom|Z4eEs8He9>e+(PjQFJUJt~wU)e_1o#TkZe6Bn5y?EPxu@b>2aQIh%#6nCq-RcMh|f&`|W6i@lz?^c?A&eh%cAY?GbdyxQ>v7(k6E_esle1$OYPMl{+ zNPSU;x@402qpy8B%8?IfbZ7I&@C(G`sB{QCR@}Ohc?-9wD|z@vAH1QD*R!V7Rokyp z94t5alf*Nlqe?faw@-V?;$gu@qx;HIEkD(_&s}b3$-I)+96PAl4<;=hkucsOCmz~T zf<_+PRm;85r9;N5I@s54p;I$-l zp;5^1wyWZxkhrd}%dTa?T#emgnx~tW*N>e)3frc5h$WdY085}8^w?4umpUAXE{%_1 z9cH>1ke2g)+u^0x&Ku9Mb!;YNlIO|V{V3cE?N8X*+Y+`Hx>oauOp_};$^^uOfyKQ_ zL2z9$tffC6{SvG8)Ntcz;B67B&o!m4WMh%CXBIy7euT7kf?3Dp59K-`MFx2g$J z0_z6Do1jWE$}P<7C`u|jKFMGrQ3@NEyXziE^l{19LR|>!myD2^jm9(9dPN9(H$j=I z^%S=Bql{w;Y*h-Z-LG8`0Jct+%=ti>1)`Th5_>+&6 zwCgO0?x9OYaE!kGa@%=LXjrzcJUUU#$T(ytgAos|mVtsV7||>Ygo-2@n4ZQvJq;Kn zsBf?4Wl|pjLW;B!!E7tCKC?O_bLdEmIDUqXPmW&|t$SP>Sy@%k`972r3Ux_q>`0=Y zBY}{IenfwL>O3qw2ND0}CO$VLTqtHiE{6Y;lyaLK7eS+k@Vr}dJ8Z+z4x1?I!!5&l zonIDvwyWdd_*DZc{*=+LB_>`ak64F-VpLS>-F3zDz{&SHu=NI5@6mo^y1BTi+ZS`U zO=B@iCy7e2gU(X7mudl#s5O)aiyR{~t%Uc+mT}KUqDHr9FXxm#K`$1JVjw{J#_Rex zMIE<%7X*DfI0bdEZ>6_fP0IYY;SHwj38L{sT4s=!p_%87le#D<7(42WExc`;zu-7P;3Aw~P-9Ekt%i^CX7w#*w zV+K~C8m1biKcNml3~S?3XJZ;D4nf*xdTZuGTD4C0nbSm6$!DVd_}oOY3)XCpx442ibfMgduGaue~0lY|i2ARln3J ze>)nx&x+U$wP8DU)ZXZ$^&dYRDwDK5hJ+j9_d=&-Hol`{xgBjuSn|Q2x(E8BMgL*| zie~BB;HRC(Rc0EG>w~4gbMB%Rd1YNtr9v`YR%G2*#~OFc$W+n@oLEo^ph%0&{G(sI zw|N2P_legkCUQC~4-J!}K)-go9tDISQK%>O%S|kANGKbuZWJI@7JMQW%=Q+$ z-zh_xL?IIv(0&%guv01;HniS?vJ*vWW5JBo7%jkQ0FW(G$!EQV*4?lZ7fmLQd$m$32uht8AhYoPdf|ln)(^q=!I5%n^KdNtuLLISfMPa;f*Gp?FF}Rr zUem>vs5L8<(-ul$dDyUL?9vV-GPT*EYVWLmwvJZtkSy1b5@ComV-wb}WsqzA5p%@< zdYBS*O$E|M{Y@U?2-sdQ2-OE`3bvI<%IjsstNVcU)D-~KFFown+CL5Ng)C`DDKZ(c z)n=IQw8Kp7373^*YQsTBcc~_zAaR#GvHo_-1$oW)KhgcA0-JZPuF*sGGi4kf$j-{Z zmL&imh$0~{v|Fy&VKyFs!>(N>R} z%oAY)a*jjP0Dy@4XiE6{Mau)n- z`$NK938Hf?dhrrE84do1S#I(vB6tk%Td44bUi6>Npo2zDE{GNuEnMxCY!#WC8G)Yr zMKU-zeiGsv)ziT8$GhA6Z*$Az^{iwe$2StWIOVK5Q1W=P6RN22FTa;6iO{vP08v27sOpZs zA)N@Idq@JG`3#I_$vZ-e)7H8)xssx&NTE|I7LYJv6BLMyDA(#T*q@X^$T$$Yby~>2 z)=7QiQ_?T(N7F%*a_=B+s)kNuReoWkghIz6qB9{eCZF39cvEQJjXzXU=>eUhEtN=_ z7by1lYC80r<>;)<=(~tqlW);|2!(*y%UW+3U@w3ZyC#kbv!$et15W& zZ`|(kUiTJOM;fOBY}KJq7{)IB<|Js%wF!M1Ky*4$`(#LyuvyM~2e00n`C!C>EhYd) zsUd=?dl23ETCC`1r*r)c6-c+X`{ zjLu1`%U*NTy*VlX6gcST5xK3rPPo9U6=nU>JC#d68)4 z@X}M|Oy{LgCVkx7>(IIh#eiS^uLGa|$-Nk(*RY-rjrk-eH6b@*N*8dqjgD)OftaLr zG30t48|&1!?4#lQy61Npy6md@=pAwp09k_qv+tY6h7{+NlhoSU)Q5f!7N1Lf7TF~q zQN0+F#l?96eV+GE+sZW!8*T#&Qr?TVwC^^~ej;jyQcra~g&G$tnA9tn_O{!;)i|7v z=)Eo=h8J?s_#?-D`Tk*Cywnod;H(EFx1qBfl(xJDx9qot$xw~@U=CMC}v1c)Uf{8^ZQE*82-`XEFs%K(t)+xZR;1k zjeS?p`p6^kAhNtRImYM+oFM&(I*JO-a)<X6vch3zf{Q$Bq5DEcY+S1|N=#=CY6yNxjhfqoehO%NBu+-Uk6~|&c>ot^`_A|d zuQ%t9#m#*7c^|-iN|dj%k2Fkb4yD|TT-&^KlGsWA;ozblEmpvbxZ zxg`CHz0?cP^!fx-cjet$lc{|qf8QGTv*duc7^f6PUf~AfY0K9bDdyNCeX5PQ)2GaD zW!KKWrDtha!LdRzUZpW5t_l2IIszI&-Lsx?{MPO!roZz;a}`BqTp~0(m#)ic{H#+V za*N1jjT$lAHDwd)%kC>Mte*NMQY?O+3y;kFTbFDA$VGWRcNVwZekP!R?>pF!sosh$ ztK0oZ@f9i=2H^FLw&Xsf{yBP`^Y4j8BuC`tlwr}aezljf!wT^;AH?mmxN{djFW7-% zp#4PZzS7byGUHZmK*5w6fa^P;?@)l+cR`)>imByke0934U__#Y4gm4-o~9$E4+7 zc2h#@$wNk%9?u{`$8AuhOJU?m%J%UMW@9;h6+ZNBkP1{V>=0`|tqTfniO<<#AMF}F z61o8;a1z%)jFb=WgFZ2#_!yosa%5Yw3&KF~ z#cMCORrxQr#1|I2->}OC=47n1G~Rp#cvR5(*0KwPsOsIN)gw=C@%)SNedXRc{IFRe zU!v5Q(US#8HSwR}B^;;T@8*BJ^3qs@x1*|CaQ&`g$FO%kL7QvVN zQ1Y2K`tg!^ut7+kOEW)@r7X4oD>6>G;~kwFt=Aq+%VD;xk%ngdgFm3!^Qe*1pV1DF_Vbx8NQ#YZ;v@fAu{L zO4w$FH_tWZp-}6^G=@28ece{uRmkv~o2H9o435>nbyL#fYCE)vj@58lg2wiasEyLp zjrf~T@V$nb`8w+X=L4A`v%nbRk*~pR$QD1G?f@%*2UrQ+hN>!`_hc;Y_Ag#K&gr$5F`Dcq;pn0ZCmME0efy4liSDN>Z#PWVpq0m|{im{qks_ z36-^WIiYPUt}Ir*%6*=%_oPNBR!2=&f(h1~)S<>9Rf;fPI`sSmlD)({XtL|1jf z*1_7k30UjhD%HDR145BjfOxzM<3p6bWc8zbwhR7iFrod>xW(3xT*V%EwDGrF;$ zu>4`|Fs<^Q6F#0TMJ(`2^zU|1aC`-4K#mdb@ryX6eVZlTyLu9}@FwPu=_CRe^Tw;2Q!di;o zXP6Dg{!tl^A_H#6GMLvwkX#liqFfdr+t{iHQw%8-X*4;Z78J-Dg2BTsE(XheFw10& zo}|}0Yk-gN2Z!&+>5BWG=@u9h6lddK``dx#+rv>e4)^%hN;Xt@gNaizojJTcvLKC5 z?0lk#6fwjgHuzT+?^-uV*TN#}nE)s9>=1%h%gOrc_!hz(5?bvC)M^T}D2otGpcxAB zS6}~{<~#^e4DUy>dMZ->MdJQbXleeD6xz3Q|0%S)oJf*Fn@VDFdw03- zl33i+#a%u)m6+v)md>#QsEC@y1|xjOMDDVMu9?66Gds~T8aG>NopSrY=_L8C5sZ*% zk{wcebfQ1yJ9$j|K51%r9bkgLhXzPgsq*w2D9R*fU&ZTv1}p&0vP|so!$EGdL#13~ zD6Pa&11+(h8da^KRQt4alP8c+AU!NKJU?C=#%SrkiPOMk^6KbzNR zZ3&t5?Q-=F%jgIVWzuYc)$BX$M24I(zd0kK8^y=;Wl&2i1bQ9L{=p>$oO*8>w8cK= z(Yzo$zJ46>ZN#bR*Hb_DsWI~K)k{8V;ML)F0()o$RR&d0?(;wS2lmJBsMX#Y!5}mZ z72NX)oZzbS3>x4J;5ydnY5-rBy`#Dile_@3iJuStnMiN@JpVGdKf!mq()tiwhhUR& zuf?si*5N@r@Ba+e%@-cvJ%VudE{|$4S7_>>`s0ul-Ae&KvY~xYgc!B6WCJIH+}naD zxq>m4(D>sAa3fgZ-W1d{7_v`*TMwkxf}1aOEHVz8vV$>J*~IR{KTtx$y;Kzhz<@c} z!Gfs22T~U`Z@+A&aDPtA&_EfJz&6^%YEPg^r+YDf_~;(Id^MP2Q>KB(kM@tWl2;Ss zzGrRIG(}}LBQf|8oHGHFeZhrii$Uspt?TDk8p&)kAdi?kbSXvC)(GR5P@kS_hZfqoI@KjDumK&U!633kP2YJ zPJSHsj^05%WL8MIqwkqR&zZ+a=Zd%BgJqy;>%(wOzs&gW$R0ls1yL9!9dU~dZEHK7>jQNSgdC) zt*=?z5u?M6LH#eMzwto_xT}N6mfzkG--Tt%>kGO5Ho%bB>s+BXZrWKJhqO~0-;fHt zL;W@Q`lC9EKw>%3A~!PEs|L&jc-Od<7d1u?0AkB|A9 z)5&QQLc|L~B_sTcP59}gk654g%kY6-txx^wbbL$u8z#@FRH;Z@S9JOtURogXtK=DiSqM5{Wu0 zSp6uhaW_`8FwtBk>BdRo9>H`M&pF9TN?SQtq!IUxkPfnqskZU0M{>Y7SVob&(@4(v z(1gSfAUUM!Lkj+yU%b{67}?R_bpAMASB8d@v=){0j;Qn(-RXT%44f4-oa^ah-5Jlj z>2~n6s|ZG~czFi5$i`_JT?XSjD%b8<3ysl6P}DP!+r&s?Xfn2z@G5D)qblTVr9N~q zOuOW8yvX4`%|WW>3P$J7xWLC<;3BFI6{B+w;t?w@42y;GiFL!rU9Ja(5i`F~r5!5T zt>hN@1`LD3OJ3PO4bxKjbCgvJ!i#bxIUYuy7R&(jt9aTi0v+l_CPx(o5gXEb@i(t{ zDUaz92X#@sjH}BPBm*CY|8!l`_tgHWT@9V8R4_;3m|el$7bW2@k~Z;l(}Y4*FeD6V zvpN7jn@+Y|%BonReZs2A(LFm%NRW4>fV)v;cu@5eWuJ2-c`PW7aFlY}=e|F!Aicsj z2$F0|rHX?TC!{r@KLO=SRi$>1{;KLQosA(};8&HII6;6-zfr_Dyx(c@jCX}jRfXVL z4V!9Z$XU(-if)dbUP>)b)(s?vAXOi)>CMTz@jit!Ksd^2&i| zF%I2+=Iv}l-4E0Y9-dd+J$uT#RBDXq#ocy(rrz6f-m|ADUaBTij;M<}=dI*q8b80~ zc~*}*mz=xXr}(08Cc5EMKP{d5tEED!eKMY14)6MN<)GgCL_M{~-p8$bYD}?rc{~)E zth)N|KYi}*KEP2@Ag$VvveeAak#|~?5j$(DtdV?B^i12{-LOZuyp41+#_BV;+&Y8x z%V@pg`Zp(U#+C-gR6F)ix%>$SfjakBSYH3_9r~^ax>GEx4B}O|%UG$#Bm)BHJ4V@- zRFrd#-?tmTAN^ttl^X(*mq;JF%hjaKRjuRL#KH6(dhw1jj($G&4ZWklV1&3M*A&uj zD*Uu>4d1}6$`CeCo0>q?P<;P&$!wBR)3vL^6n?)d z+#M^Cj)O=J28?ShrlJE`Jn`-Q!odRz2J6wkIiR|MIwC`5({)WI>->+sBOeW~%)9pu zc&}7Y7LV|%GP1&Wf{`tEonGJP{+#HfKjg@&Ng&mH0T;W(Hn3E#Ia5U4$51u%v@{3l z^zi!K4sH%Mw{nfFA=!S`>U6p`o8eLc*tM!fsKPfii_>BI^j;ip6L18@2cCxxZv$7AHZe6i100_UF!~Bv+s%K zCbDPweo=FJ^jg*V+QMbS>;EC_E`!=?*mVIX0TKv-gaR#2C{mR29PSBq8?ucZBBL7VMvlI{KJ zg4+9LX1!|#^@S)X2Jo1MgBKg0Lgpj$7Z?CWDU98d4-1JPVSCjX$z?GRMK0oVd+9{~ zj{?pf{WPj!dnB2~>^7vAyL3E*N9^{G1W(yy4vX~N%_G7mQw1{bD8!<9KgefErHH#l z^|OpnTTxJVM)Ot9RvSW6$Orzi(g-+gFSA5OrgwT`wJ{k+I+uKlbJ_K%vJQ1M~DfQEveMiur{cn}ZFU7TD zSj96a!)^lK?WPH@8N2z@xSyJHuXH}Uh^JTo96|GLH? zTK^Hb2k!5OVdm(_uk*nV)D-9xpo!n80a*FOP-(jLEr{H1LMn|fQ_T-!TlayPK}wtr zP@HJrc3GZO``?SKw~3^~kK(+q%D)DYLOnL(gN1s=)zS9mmPu+_dJGEW&{H@Gfj$<# zERk0a;{!BFuSB}}dqwLE>)a^oOi^t)6Bxg2rzA|pf(h8Y5F ze~(zEQp|UW?i_L}X)?E|K)Kdpc+3Po^IE0oTEAI+u34b_JxZ=9byMeLL~eTE_g*l> z_r?f&+wi5bd(#VjwkCHKsUJ^?$4y`Jf&`QbIXxC_pEdC)lRIAGNzZHyT}m5-X@*Je5JCJ`Btq>ni4Gm{QNvm zLK6#6P$wPkwf$X;H%j)9phMEnkb$=0emt`7;OE0eD>cOh za3}-aV`-UTsYk1o08@=bE~kM$=0T;Xr$Ka@ue?io)7jQI8NwE6cob5(@{kFxwg>D%P3)`v@w*h zVjlhej#&Vn%J-9FKgS*{j`<-8OYYDNfzf>4HjkO&Ds)0-@qYv`3G%DCX`uiV$vsfx z$!!QONfc%Yw-08+i%mH=yvxCthO%bfCw3<(SAQa-5l{Aw6IYe_OScvRH*=>z{oNv0 zzm1^my+(y(@d1LTLa?e?Ch@!GAR7Ro6>TF$4ckBot8Ad4J)4w_{*io!z40!~4*;d> z;i;|Lz%W=0h1Gr&{ zEMzk(|6TJ@c7el+J#*!?HCfQAtQyUIZyW;MPkXC?*=NO!>5?IUOa*x$*(Sc| z6rQ1VFn?;0I^48~;-QnmlW8J4oaz2%<9zuiG!MRp8y1y5V&QfL19}1_EU=`1^0*$2 zw|8`@jX>G4r1L~!6jz#~B&Uj#-6g~YDMTUg2d?$x<@ zKY2tWE>>yxdie`+hT8|HWR%gAGIs7CVx2R$LqAWY70L%^Z7{K3Rk;CI`bxcG+Ro$m zzBk;|Ybt}%90zXbwxp{3xV&s>UH@OVhW7yjwSl5X=Ff%;zW+9rVl&=P^mIFT z>TXTmrQJ*U0%3GF|CRg8U(=D+>jP}HTuH21^nuvX_g$NF;WzDzTLHfom4BVf3k3(F zxd?P_0&e7i-FvmTzrQR^uK`TPdNgy-rKP$H-$mR%&UkCNFCTX;BMIaW(265+3Pi88 z_&Ik^q2)K8co_0>ouY7S3Vim{R1SxXs&)fjd{+J)A$m4MY=(*Y(!IDX3zFIJr-1|% zKXMrlV{h%z!_#x(x(=NJcFJqSr9V7yN?ZW_uCfZxLV+s+$3&G^i0( zCw|#WVIS%7WY5i|Tt9wTpIuKt0i{c%L1c`h<4LCLT4G^978%HlX%Yzv1_$GLKrGGB z4~enhE%lMO^WjiIO*I=QLb9;2M?pR2P!gh7MW3Vo@>yKsM2qrAfA-=jArm);NTT_J zaSB55cES-}?^G3{zU#!!Sw|TLM-c*zH=CkJ%uHHR4Ek+icG7uZ)E$SHx?w|a43n8Tj!A!r|(-*TEW{y+#0BJ$>?3T)m(^y&6+J?NMfqBvn1KVnYP zy&4pZ5^angMi~*6$6seu{DfDB@*bduLLk74c*LcD}yvy|z`6ww8j_$wFvt4JTA2orK=WxVt( zZz_9oRGFZ(lKaDF8Khi_P97O)UW&0~WBO??yvmT2wFbQ`!)o0W_r)&ZBK{2oIL#7g!XY*V(rnQvU8J(+^k?Zp{ z(T0-?)S~xEC}E)uwT9>U**k%-o%l+~|7IbNH1h%4I}7N;>(=v_BN&{HWbSGcI3+iO z3crJ0dofdZue7x46fV^GWyH z1iuaf!>wFCoEGtr#2W6GV5ngp&+L@449n57N35kdR#~bQ1&0aIL^6nP-X8K+CGVq3 zc-!(lD>Mx&a#m8xuG`A|qd)Nad~o$D0*p!&V)_NV{Sc+)H~eKD73h-Xj0!5955(;s zGN6_2=Vel)<*$XyE4TvCI*2NTl9RUbdGcZz+dNs;D!Ii9&g+W$iYf-)%Eq}5Cngn-y?SpQZD~_MaVSJvaFAOJEn{FUTWGIfAFYnv ztsbH%9bv5*RjRqNt|{lr$3E3KnXWV-DkH+Fb*G3pjn@3jsOEUU2V5j2fv9RV)G)dB-PYM6kg}{Hr6NdHIzr!rSsJ$ zy{`3-s%3unftAhgsfdTLEdnS~H<#%LQLb`pZ{%n5WE2sbI6!}Fz-yFdZiE0!A|Iti zwbS4zfBYjJ?PZru@UHm{ ze!87Oy2Cqgq&Gs&j@Q_rMTxEX^JuFIrN8yNV*kSyTf9~UOedD@Lr8rSuS`o=ajQi~ z>wEn6!O<2mkv5)JZSs<#N_^Fdj4csMZ6arFv4@QX1|7we8c%%NZ`0c4xcu6^NyEq5 zKC$Mhm$$%uI>{A3lyr13FLlUrd42IA&B_vpJZz(8YcLgQZ}e?Z$8TF_ZJY2-oKhx{ ze$oXgNaw=u7{D)H9P1LqZ&+&YY@_Vn^o`#ZA-U!c2y{i07B5KDX9;-Ve;Vm1S+MI| z9qT;rsJa{@z7DU^>&@E6>M;%N5<2vG2=k@L=z&sI!a9i+&uhVwIbu+eS+)*Rs!uD? zy$xl(XLjvWo!K;1#KSM^^@4EWAG*Jb^gayj!>+0jKgwaxR&K}d_kYqal%PlY&Z|JU z1ZLR>6zwRy>GoD`PHXFxT`rSXA(s7IFc3;wwTB^&2S^M*uGn>0cXlz{bTJux(#vje zP$3F^)26=PpljyF!#gNyIEZEVS=(<==cv!|_M_90`xI-renJxhrm3Gi^yG0*K=xpZ z$Y)>5;o$MISE9uJ$-}*D%<((&u_}U^Pe-&=MvIQnDZ2I}<;uhG*Tc<9B5(0~bH;1b zI{V*09kmf18D1Jn79FU}9_>6FE0`PIq3{SD8(H8UYaH+Xwbpn1+Se#B@kV-JR`l&W6|q-Ho7208hhMd$Nhc3a zhks=Eo%u|rhL0YN=lvXi!1!QFmk7^RGG)Yl>L6iiifW|QaMbE%3ZR+`%6YI4>;xy^ zwj=193oP-wCSOF}fXtuK#i%J+T6@}l9gatpIb0bheR#QAS>bbkM2OGYVJf1@tsXXu6lpkb_8Cm=~7GVQd{*>$HY>X|I*8irC#>st~=bwLS~k) zi>blOBh;+1eara`%TxZ#lk6*OSWO31*}n4WVXAaA`{TMm4p1z_IasOXfTiq`QLgo}3m_m=>%+>*;5_L*!eG$h8J|@whFb;d;)NCY()`@G735WaXO@ z;Wx3aedFpWhORoP<(DRZ(Yr7%9V>U8H%&T>O|VD;fKVhqNKw}VXFpMVHsNQs*Qy_l zZ(%02gO71WKB4>VF-g~DY>E4;4^6MC|Goln5)4fvluqCZfS3!u_k=)B@01_SKVLuW zO6nGO=vgh9T;5j`PoFy`SrIh$+ynjyGd}oi{F6^&istyM@$qK4K~M1Ea!t@`&4bR| zl0J@4pxVB6n!tfvl3QkT25WQXQgebCbNxpabYBim|HA8kMm4@a_G&V@Rcl)~{&s7B z@`>>0tln>~AS>KB66z5vT0DTcoV9hhHLSpz&Sj4ZlLsIKcnc=Fh5xwudAhv&E5ZA> zfc}|~_t_f9PI@Y1<{a_#wk$htw}!qB#TdpCz&UOj0^| z9C%I&K4DR(TlBz0Y#r8_9EG~KY`T;V9&R_$oGS>OtF)X4nw-;Sook9;qOMc2doY&{ z;k;8S0Ud5nFdT(@=KIUre=R>Oa5p_~R}uXSW=CX+1k0LYSLDM#?jVBK2`iX(hj7o6 zpXsIM6=thrN-uvlsGk?UCpyf>gVW(2qgIlBUHf4Q1C(x>2v#sq5Cnotp&p)(1u zxMT3TyS~_cbg&psU{o&^y>gy!iNz^fiD~|`Fl8;BMy=X>rrbyN(!F;>CgnLNAoT;c z9yBJNdHknPRp)P)e-v=|6OP{(-zd;kJ*KP6n6EZdqF(l1nwSuMu+a3jHX!H5^JJmg z0&cP@8gsh)Jy8AAs=w#&Upvp=KF_;J4&>vcp-fX>X`Ba?gSi04bWdpA3Zn`IlcX*o z;gyg7QNY<6Po!Wx-<+fgMb1v75z-{iG7pq_Pi076XcLtoMmNooWERQJaujxrr*c%T z-<;)Xe9unhks%~53Xk9M{>CWaye?4iM4zG}b5XL35^H7SZ>6UnsTw#NG%jD`-So+9 z(lYdsB&qNmQ+^!h-7)y6DlilJwM$^vuvSf^pb`ToWIn9~kV$DcOZ9>IzV%DNUuyTu zJaSL&lcP=f7NYRvm=l`}%6!<`BzWvrH7NR0`CFrc?ASL<|Ic67m(3DZFTbyw9;?od z+E{%T)ZK4zuP`b&X!>B10zEG`!xVJtSo)8BpR)L6%U|>Qc{PiEYGK&OqFq{;j=>wc z{_~QzM$oiZE<6;TFC585)2iJ2ZPR*jRYsI*y>?4!ji=QLQ%E`-GBd z>#;1Q&o}QMk;76~kkk%iJ?k9b_JrUXY%Ox(Y%Q=tCBDt{)swgoFegrqZz)UPQ*`5Z zYu{%&?H?dHR)&|}6?H=#OZlXUl0!6YaABrw-{R71I+Dq&*P$Vu(@c3z*qW?Pg%C*o zNk6fG&FNrSfC9qtL~|%TB)bkw>nimo+O=Wge%WbYmnO$~2%Z_7=`o)Hj-EA%^LMQm zX`wz_rlUY+Ho+_CD15)YDNzr3I%N2#$mSy3duA#8-jO+-Yd80;xVOU1I13?G#?r9D zP)g(NusnkCy_tMiYblW>9Er~&rU_dzCbQsA285ZHSM4Vc& zEUaQ(`V96U+9SCaZwfJlJ=)MqxXOyI_w}n_Cdy;3^PST_{+{ss-}4bxGm_RF#?1iQ@Wg21}4%^0hJ&mmY65$w_^`1AbFA&B0%086iA za~kXn0B2tsObg&{Q}|fzQXZS2FUr=>%mqBMB$>`dU{65|SVABDc+gEg>6}UoV6Gc_ z#M&3-PDKEyx(wH9@E*6E{gb;HiYr9V9Ck|v}NT zfkV*A{r5#pUy;AYnWfrBG@ZCf07%mP6{I=Lw(cY4&(Ph^+C=>y1yQv8F9&%jq(cKa zC7+F&jz8OPNVhJxpma!H7mVTj>IRU?@Fd1WCSN1$03V-z^}{8*<*K&(iGk)mSLjgt zAY2i9NJ_6TLF@`_w{Jc8hu9K&@W;5G3JKL3!>oW++xS+g&>9aM3EC52#=h zO@cx-65R8OQ1?o4A~xNSr{^}9^yCaH;N9D^4-JssBeceB`$8YhLqHS`3a48W4DgyJ zSrSx0+}9&NQDE0)I#im8i5P$u9=2GD4RdD#bxaB8%w?P)FDEuZJ5q4=+}m^>(DL+waS|@!HH8ceU5-L+u&u#()_d@bPb8^eX0G8#mQIE4KK z&IJJULl&GOf?T#hzjj6#!Kh>cbe|!>$&41b*bpuh^HgVg&l%t)DY)&uaztU-;lnj3 z*h-Q{QQVIQX8HB%%sDos2Sn+18X|PNjxAAD)MZ!y>-h;j;4U|;4TcKmpQbR);Juzn z$ZaHPK7|LU&{NC^D&R(=_#M(uNKJsKFoG}E05@;u!tlmo0&`pK%FORzXTB;`h3G(R zW}Lgo$BDrF?V^*+Z=b~7D|A;5bUhbCNr%I^OHIS9-HQ4r!}&FekL>_}rNt^HX~6>p zD>e)LG4jd3Srf;5#%b+~ePD@>wFwgdrzCZWAa0GjeN%>>ZC2_7#=U__>*$e`CXD$SSFfARZ?^hxo@*&`|Ktz zTe@qP;|c$FtE>1*ED7TMc(27SLey+@7r!M0Fda52tQWexh2E3r1Jo_8-Z$6I5FBZE ziC^SpQ3Jd$E{AT!x7@TJvzjFgDvZXyeF_~1AsZcblJNr1` zZ4iPw&E07eSqvD`A?Q>23+%y~Uj8L%zZ#o=NX1;A=YLG66&irOM@Li_@gv;ny2>CZ zkQE1@93kZwGL7zjJgj>!nO@uGcL>;^}+6v@ofVJuEHO z5N9V$`4~tmKA2)1WTOYcuA=IGRj4Bv{8AXoF#tr8^bJD$xt{j(sPyy6^t|2!bC`l` zPQvrhxIw(5l82yZ;m-bN-=w**0X#C&e3sGx!T)Z}{3JObsU;(PCMj~(CrSe1ijj#t zK`Kz>a^^FHprnPyiwkUIUSLaWFZV~EAcG9TAHl@+v!$a(+Q}p{u|~jb<+WrRG~^^~ zO=KaCJrQs9WSZ6idPqp2X4q5ScU{3m15T6}sP|24MZ?};kOG)0p6Jz+#@kd5zJGI&Rr)tkQV|R0>}$g&%7|J;&vOGKYLROcDoQ1WN~QKnWqwNKF-jk@l`5)~Dm#^`#+9m< zm1>TZYHyY5V9NDW$_-DIKZ+_hswg)ZDmU9JxA-Zy#wfR8Mjutm9i14)TZnf|x%)`@ z)9qLjpfki27z9-57gZThQAtCne708^@*8h^3eX~>aNG+Cu@UgYl!vUdiJye~kwq+v zP?ODM?R8OhYe~)M2 zmP3-Ceyq(Gf2mhyWm>0m5*}?jzHFZ5X36~g5^{=EZKYhTKt>f-r!h<;@xu+o$Jh;~}lckzv>%^h%|AMDAH2f4IKw_FCsxz_m!GR~B z$6lI`r{Rz=jnRbZkn(B#JCRk8(oIa;t1UK3n~13^hy+UWajOKWsurWs7t0OQPzA2e zdU%Ke&PC`{PB5-k>ldEGnc4mLQ2kuV%LlrAz@&8BwE5{G^d%k?ti zVH9YKH&{YLE%HAAYLemTy(29osaBJN2qV1{ND_B~$4Fbw;adY4O8pY-e+f4_XmJ`= zQM-f?gHV%ILn&w7)}|4GNL7xBTuCw9=ZInVIYJZG?~fPnc6ZS~dj6rPfBnMP(?>@~`}_MCc={i8 zdTZ+x<4kXCtgWr>t*)-DtSm1t-^|aT7gCm%mKGNm7Zw)g=jZ3<=4St=DE;LNdS>Qo zX6Ak-aAsx(Jw1K(&ui*xYU*qX^FD}?rmrSPugAu2M@BA3M$RTiuLlRuhK5eY#{Ml( z4-XGxu<5Ibp6lM;o9^z5?(VCxmg|wq>%sh+&+pJfX1AZ*mj*g+T3c`G>TWvhZX4g8 zH`SkZw%)f%-8D(xHHh5Ra@|!ip{pr+dwVfrb$54nXJ=cX4rd z;f`myc}FS9$5GLDK0bHO2FD(r_ZAlShU!Namj8CEb8~Ys>U3siW=cv*Vq#)!Y;0s? zWO#UZNJvOfP*7lCU_d~CpP%19(zJ(%o12@nv$NBGFw+hW4z{+o*4EY*78d{3q74iT z^!4>Gv|nDT%bzJJUCWA}OGuuH2>#*Yxo2m&XQKPT_VgY}yG=`XPeHa#Nxe-$bx%ri zPe>3UE32cU^Wwz|O-)U8b#*m0wSP&|^78T+Xvp{Ay$qN1Xp zpm_A?5eA+nB_SauCdSy)L_|dY=BHsW7>1m_$Hl$J#{L&Vos5kQg+lT0@NjW)ArJ@{ z493C1!N$hM!omW9KtLc6003aJ@IYKDg}VIS5L{xY3}?yb=>J`yuE1U}hl0ZXB~X{D z24U;OU-tYj0(Dcx_k0E&MC-`QjpV@pRiHjtG4NEH`-H;6H|}luw?JKQ(a(kraXhUZ z9ZlkR+SVGQ&+|GdLm-fe+=utgRH<)8WIw>PNnuA6@e)F#b7=YLY> zt>PZH(0Q6GDRHsG?3Wx!+#0Xjtf9) z>d-eBfjZb*B1lXsve@&jwU5E2CyVyM_FjNw1n zD~ji?2q6)c`A49Zs{mm;hbWAyB{0#`?i6N_iVXpbgH3qeL%X;uy~x$ z=%`)-xmNXO^7e;{aRe5g%I|=!%v-lW36cEmHK_nO+STNuP1 zKmE7uG!73;f1$_+YBGoEDm>9uK!yG)Y=Nb+(zhmAi}DG2j)Dwb)rH5MPNMX-h_yxHo6+J1KR5UD?1z2+ES<#2 z_keO=qY^cZ0kEDPu<%I`0@Kxs6_0ozAx+An0Hn&*#q)nk4|R|j;tmh0@xzruR-)u6 z&GYg6zV#r3dm)%-*fEx>YDhvNC^o3IkPMLD|9n+)%=5^C3{bv9Jx3Q6lpY+vYAz=d z>5NBQ?BLL-ys(p+@myh6)d)E)H3qQBWqBNzG(XPtuy&sYN9iPM-5!ZUTqwsc6-SK~ zwQ@bngd4Do0-qF1Vph=ANdTy{ZtT*63IG~vmu(>w{j`ufYeeOiTpJmg4&gBVp^|Rs zVv+l;RHmMM=AlFVyI=ZXR&4Xhy^u&-sNPg}DD1o_H>cnb>;*4Hss)w1demOZ(HKhLs7(XIFUms+ zB+U9PK=~B}crxPK0DxNP7Wj$ABYN`L={=3#OmCYM1FaD;-jP9N^WMyZ;S}GxAH>ya z9zB#>u?Vr5-=dwgIFN^Mi{PL(DX)?8Ts}?+wd{WCYK1&q*ZdgQbqmT21THjn<9*<_ zXExkTERwo*)4)A5nm+)baiETBH5xcu+e(TQz;mBTNQsfMGtyUmGrCBABw6rvypqJB zV`*7fx3Hz;)mwb|yg60o){z_*gA9ED|F$_z+_0nD*<$UU_(f-*-B0i6S1W_m>`epT zYn*iLmW{`Y5Svzn-oB;AXV-J6AMSf@fxbqUj%iI5I9j0jx(KgvY48>GvdhPZ>*!Zx z2Bd^5sHh*tAT!TqJVGwj*rf>XGxKZ>yUK7o<&Ase%g?AWPN{hj+QZ!Oo)=HRK;Qr-?u`1VoMVFw$R*Y5eAv zw0TPV#FuPHM2#nMju8m{>W-#So^A-$H?({day6OW_|XOD(14KgcwA%lG!s5fk32FX z5Ko7QK0xj+9(kIW4}L5*A$jwTOJDrQtt(1AdvoK#qN?X!KaI6Ur1$jZSA$a5w7;VJ zIwqB00LVYy-^v9C-z+}Q4#+B_%t1;VNfH3P21Ln%4uo!!zt^ap&z{iJ>PN`O3htkj z&WPF=>n=T~Iq9d71E7q?>0zHec+((-!Mep;G;=4)k^@Ys-eBnL=z9Tw)8nIK&Sy`f z#CFdrJiCq@)RC)Ld6%%q&^L$yid4IDF9Fb5b9|3 z;y9zW+RVp|KVknzTROHo!X6{E*stL)P7qx%{c* z=tysVhueGiP79g~=6G?6VhTJ6CMZjn9yX==xf84N7xr_?$V#Aa44^i-B|9WnCLg)L ziNiIi8LLbsW53Qk#9cAXTJ3uGXXeyr`q~~ipLu^)uHJQ^`WE=Yg*T5(bFzM5(ErQvSt$ze9}E3lWzg3R7OTcmQteWh~af z(K(WaR{R!4?+txYwe~zd1hL#5%uNN%H|J)T9of79o@jft^W^?6ej<9@1`2e_qdh0_ z3vGFxxXnu-Py4zKVthjN2nqj#1igD=7CS^7Cy%%W5MTvC{mKwiC(w-u`|U@;4+@z*DMM;j?CME_EYa|Tut4;@942c!u>^!$L_Am0-R-3gT*C%l8x zkG#wlL_}E0iAa|qkV(~#WU(BTOk-xaHpa0zK96I-SFqFkbrgItR%i(c<4-_^NTuowggtF2HcJr zis5@RO(DEJSY^|2Ckg7T6L_QrsJxEg0!dizLUU_RIvfNlQ;;J$-Z%Ixlg3vhQLz&uY+ zP2-og_6^v75HPHh_mk*HareEz zWdLNFA7TFYK_MprmL}w48VEq)9Z1LkIH8M3L_gpKh={;*AU0GlQE#96iK3}MbJWCK zV(>Z5O3HiC22}(nyaACa6h&8K3I&`bft>Mnk%*G%2tb|W))sUa8}OEsAAlreXGGjF zB8u{~1Az@XO`=5-jGoYEPXEIMcX&xvqJy%{W4f%tBlLB&3r#8ny|7gL`>wmOhyDz}$ z9vHJXGf6xadi{})5W@eB3aU+M)+wuvJnxrKVGcuK+Q@5c`fNln=fG9swPOBK0dR59 z0knzx#}uE#JNk)f$|ImX_#TXe!|8ToGV85Fu`mt*xdARFi46vLmw`6vUWxT}{l% zWCg0(u3)r#pvxCj!&^|p(_4duscOjwf=}Jr)~oEIGm4U`7j4UzUu8dwP8z&QnRkBg zdx8T=@Y;~ANb|1tEvdb+Ex9`=G<#L8XjwZ5ifeK2C}>7az7fxaoNQu6rq{X)FT~1%{KIbnR1g=Zkc! z8+0GAwawypUMW+XoY>v(x0n8?;WATfT&kO}`$Ql8=_ae2K(tFWv>gCw&C5h2kKkg% zh{2tm@!&3~N&w8Sy<&{_cSjB5a!q{}>NS8ExSma3g`j-eO-t24x7;zO-1i{6QwY{w zjvp$8OHA@4|5-MI%kUG=Z5^LVm%yz8{rJEt7hrD>hfC8|PHHgM;CoA}cQk|=uM9RE{?68yX5T*}*&AGmC~4NP=N@FP zYK0iK1d5I<>5aH%k0_0Qf~!!bv3=$a8np86a8}{^8^(I;x zo(dDM;W!rDj`8S>j(3brRgRIjbX>n13GE!6%SMRFbxIgIKWZ7TqUxfmdS;G45s)I= z;iW_z58Xc@96+Eb1LEPhaVBpxNmkPi<+A_Pz1+VKLv zMVovKCNhtD_|OG?4wZtI?eAvIk7u16 zzKc_V%qKvk5Rex8oa@S*#me`9obMd#)F`UN#H*pXc#XFV%f(KZ>naRSx?5WrW)pE+Ra$iE_<&NOJw@k@S=uiDUE{>ojo z8B|qk+c87K}r&rsw>bBgQXbq>{t$Fz4 z5qk26G5)sQ)1BB=9e#ge@$Mgt9Ht=w>tT+2mLj{V#=FLb`{u^`q5;H@#)sZJ9!NP3 zWKND{t8L}y?$zFJGj>lLco8p&z;#gv(KL33xvLr72cF@34K#b$!+Y(5y2PuEfbL@R}{Q3Cq5QnwP`+k3MwTjqbyxNx-Z~Fb&{jXGyedg7JOG52EUHMk9e_qYJr|T z4CVMucX_fDu*)4oBB63Ecpnlx*2zTo6RL^lY)iF(;;A)y6dD@%d?Vs$>KLC@n z2haYzG$Gco-!XCq63SJ}{QCK&B!X(!8TrHodjs@W11c1ccY9KyP4-u-R#E%Y9&ui~ z-rEZSvq2*w@E?s@E|W8UX?IR8Xal4~NHFqR{9^Crg^S%^68M#u39&B?8Sc`?=6&XS zhfo^ls{MYUfh-*;Pa3 l+RO-Yh0bltOUU-sTn!nwgdgT9A z*MIIcVz~zoiwlB|FH~f@D2JO4PaQJRwlV+u)%I&l93D-FAR~EXke+wZDIP?N)(FCK z4k8x}!y>xvH@S_@yEQ1gPN2Ojn7kG?Bqr=JZ6YMg%ihSSjZoPO)xfe*5VN6IG3cu!j@rDE$g+h2VtNE5Sr z5bwtummrnFsd;{eC$SYBT9-?}i!-raZii*Yf=}`CvFtmoYU9tDFAsHUjJm8#u2b^m z-kU!H@l|qLE`GFIV3N73 z7JuLW6k~QeGHIF{!U)v&w-+5Qaq#ZR;iYJaYE1JcAHnUsMR>AJ#%}zDl=L*+^=1F) zbC|$(oiv=MDv})lNsjvntrecBASp3tNAa8s(gTv8qF&RGGl^Eqq;uRNm%(g zOeuXiW@PN!wqdLqabRGN?v< z$=fSdj0Ne9TG4Rbl5mb_cw)bpk&@>9N1*;2rTKv>WlSs4k~&H!&i)veuj9Usn~~^8 z!Y)XogQ}@SQlD@5rDd8`>PxHLCFUV>i?A~`L$3Do!d@y<`l;0UqLKo8#=^hz)ov)OT>E5Y(o|_85R0UIOV)0hXq)K{nMm_2p0b?H%j$ss^O~`(w2;}Sa@$d;34ngPtoRw+n^Nj_PQxO zhDRqvj9`}B0;UEZr4hQMG3(j`kE>k>S3tc^xZsIA{j;}MPrC4dAynH*{>KB(*EfkP z68%8Oo?h}aHU;GGAOJum$WH7MLI6NSqWuvPNcWQn1v$*%5r)NzH$r`<-P%VYhaLDp z8ad_z5e2m3${F;f4+?tpkYCGK204eZ08S)A3^%Dj`v75aAP}1Un3BXzQv9hi-~r5n z9OMng25LlkkTHO00Y!30EmGX6r;ph~hw)hkKb6$izj5@VpxOtgv;39BlI-o9a2f3X z$XDT=M?S#E#3{oL-NxQPe3tNpm-5Wg zLUKH*Uy_-NS3K?qJH(rRdv+RVgcNEuiPNdS5A9%-4q$$aNtz&KsD>fM1u;n)5)?J* zAkxSn0`*c9WpShwWp*zN2tXr~vW_ezyU7N%bH8M*$!tk~yR0{4t<6^bZIb-uslkJlyS`Pmgb@MH@B*aPsUb14Mr^-v_6j(F3q=5L( zK~6*gYXi)3{cj3hLVsqXZ_0(GM<){o6&WzoAPq~-I4@kgTrq|ekjPgc&9`L8S1%m+ zG%3MrdlWK*S)LDwLU|%UfRgw@3GI_ORsf1cO^8m4KU1@U!>*$JXzzXxPdfeQvs5e? zw6(EWEy>s_ErV_oQfL-SR@_sK9sr7KC4^9S22-;F093adQ4|W25Ogh7;m?MNH^@q)gI}D`u`RQWAmUZTsm*WbwSs#_p#EOe7D0Ar|UmK;o z^%gODtayR!p@!SME?Ifye4(>C@tyhvdp1APjHa!Jj@E?yYodNy`>(rrU;N;ed!d$& z^E-|JR~+LQQB&)TSZLnxXA=kKN9`4f&-_To^ROd4JZTtfEa;C?Sgz#J-PC+j^H}G6#v9`LR5kH7xaOzqs@$BCU$ah*)9;CCKIas_q zWZSNqcOrndqLseaSX=1+emWGfwl7|M}Gb&vkMXmVZ} zmz?=304xOpc`z>2uEuJkK|JYH_nN`HHmjNk&1ML*Ix7Rftc)yGyyM;4*cdtRl!5JQ zYLj@{qy{vKac$0Rr$l%uwNwH3D{A#Rxog+1cDkXnYGMbv-P)E*0A(o~DLKt_q ze_Lu~JzCxW_6WQG-Mr?34?8W012Cn`tEGHDTXMQ4^Qi$o@z4mIh6U&9ySXB~snNT# z0&cj*>j`l^OPt~-=ZwYMd~ueq{3~ml_go@70AS1m3;ESILZWRdf1}*zh82;pGmi1$ zI@~8ROPot0YqMb7B;-W*$j%kj^Pg9pASy4m$cNtYu0*ZlGJh;B@0;`M^4nSHwtCt} zgLWSZz35thJJh3MvAhU|tO3}Cr^aq{7n(h~Y*%~WTY`0W%RRV!PYKd%qn45`VaB?_ zIpXn5a#IW5@?If4yy4zz$&-X8Y{(bmeWK*;l3Qnfq?Uu0@JEt)f^)s_#=i=;_V5KRwM547s6gq-ZV;&_it55wH}MUQ z{NlSDD*?Dy=n>*3(o28#jP*N$UyptEA4L0r%0L6;KY#ky-~RW%adSzyn0U`zyc%WWf5Hl0T@s+Y6}x=#($pJ;QsrCu_eAjE?oIr)+x*46uVN zAi)we!4pKm6jZ?#WI+=g!4`zU7?eR3e8CyC!5dt`8pOdJB*8MklQF2V=1Ym&fCrbl zK<*nk4dlQjbUok;HV|Zs{>uU;pu#G&!YjnWEY!j+HtB*QHH!Z0ku zG*m?Q*FvL;B#ZC;xT;#<_+{Io5Mn?R_V1&diV4E*s0#p=2k|07OJVNgi zGvE6=Ka|BKd_S|eMPk&(9~j1M?8R>M##{u)aQuNJm>Dz}f@G}2WgLmBaSv9UzWL%q zo)g4sw7hE+i)>jy%e;w8W4^OGzZkeMEyjV1pxIN@a9Pk{AHKkSBPQ%6+5C zYETGDV23lgKCs-eguw)BXoq%)hQgYFR7i(+Acn3)KPXHKvRq3|Y|G08#mv-9VdTth z?1DY`11?a+rX0WI$s-zzNy3!lcNA zse?JF0UHnneelgx5C=Grf@n~R$pj6{?94<|%eAadw7gDH)Pf&eMAH;KoS27NYRSFS zIn(-wPbdgE2!tSz184|`4k(B!kOU-X17v6iY3z@j1WuIm8g;M)63~Z05C|Oj2iMv+ z%EU%6oX$tg&Z2Bkp?uIxB!byc10v{7x;)KXN`RWXxz&8gzH?15icN$lfp)M2xafvZ z7?Q!RBbgp}2Yz6OIRF4c$OnR$hEX_(ZTf)!9QcPCP=Gdd z(>I0FIF-{mrPDf901^O0Bhb@5< zKyB1WRn#qDkT3YtC&+>fu+t5&gAK6LP*s3^c?3~4RX6oiP(9UEWz{)N)mCLy7ce^x zP=`!Nhy&1uQn=Eu%u>N483>>ODG-Ho&;c;o$RR88g7I(=1&Re<8jg$Hn1SN+tPwON*}*_)+PS%tV^ zAcuS)hhd0;Uup$`Fokf)hjK`UDELi-WkRoMhE@R3JP?Q*C{P{s3?7|MAq_~b^+&H| z#F5;Cl5|8QEr=6=5CbA9mkcfZ>_ex0+Sd~Wd+h;H@P{}6fK&*FH;@8ocuwX)(0o+T z1;xy>BwXtJOu_|QMYIAu@d8LRTcwku#c3RoV%z76NbAE=xTUs)Sp{&&hjU;Cyaj;9 zREK&fh7`c6z`e-9JzPax+;EItZ=BsBNQ0V40?5VC@5G4zM6+D-EIYTQM_%RJpA$>2 z(Av(N-ECZ6ZJb>q-GWGrT(Iki09Zwkx?B?zUWp{$;^oiH?K{@(N!NW{wlv(=ZC+xG zT}xd)OPpShgCmu6Mh`{8LCjo4VNvg;s^i^?F+qJxGHgaNpfc(vHZ9 zCBt6erM~+`Gw{`4NaJ6v@ZZZ6;BQRa9_?UHq=}Qg#P^jorrA&pL#I|$$hO;F&F$U_ z2Dl5(iVU{S4_00q{$Cuv#LygDOeA3gF|S_OloZb1>cd|O4h#`cghYU0c9G#iB;WGg zV1Cr$8b04oY+TyN#2;oFapN`!md6%8;uo%tF!%-kU1-uKF1er+-?5Bh^sQp-jN`K8 zTHD3lEmq*ORT>e9hk5V;+ACrS?kyyiiv`eyU$_D_-Ze5#iCVM@8kXZLR@^yuP)cS* z=4&^}} z<>?TBTlj@CAZFF;=Avn1{2#^D0Fn-Bx_GLm2j79i` zNEqj0rbV|C+(TSv^F3&UPG}$HVbc6WTZRb#5U7zIy60@3Jgwk>Un^(mkbz&|g*pr9 zw;kwn?%#B7W@f%&l+Iz5Zp17egHeR&hhPs}NG~GB=eE^~cVLC4%Fm64j#>BxCJyQ0 zHRh}}>6A`rZfxg_d{82|-8INvQH<$^u-*utkF6z#JWIA5zu8r)krQ})8#i?cpd)8}c#4)eP1bpy^a{vXOnvP%giAeZ`MOf@H zZfwqY>`G>7D^BX{gk}WBMa)(RiJpi5M80Z^<|wU(2o%_aY^aA6-px-);yamWVt+27Rc8Okmg;(1$dk z?hxdKUnm0U-siE_9qV3b>?TL;{>1BS=wAHpgBXAc3^J_NUae>cRhR;Upa4&RZ~PVw z)IMeVHj^i|#iL&7>yGV6#zdC}#sN17ED45d9`9Yg=&T@Z{V;8x$bvI=Ity=FzaeQ1 z)^H8xZ`sXp+SOsFzGDHeYxs2tS>TrgC+}R-ihhtxL+Xd?XmOY*fJ4p#8E=>PF3%dD z;TxCj{qAtcX6b_TgXj(MATQzniCG-w!m=YrKj3Z%e^_z=P=R}Jaw~s}QU+)$FIcrc zX0~2u{~pRNhiyybf@35`5hsYM36~*5aPxkMOvr?O-~>m{1WhOgzqF1ghlwKaXbiw} zA;IuR)^ZQ$at@EgBj^@%EOatw4F;&Wyi9Wx|81=JhHvl(ahUaQ*oI{=&{lIjX@Mi}W z_F<><2*z?K=5r}lcJ*EN0RG_69L;T%_5pYs&Qf$WpUUc}oXg3a&FP%a5s1(kozfWy z0nh|)0NPGaj@OBu+$wkfwqSu@@P*19_YNVAHXv+)K!7$_6M}BtbcbU=KX#Fi&YGf*q-kBp70R}RM3Vx zZ~-YGUCCe{_bDu?dU&<~YN4)p4j~OCCx{bh@+Z{qwr=+U4toxkxO?hHr=}Z2S5?AA2e$`5*mEu_as0 zpJ(1Zhz907eCJE8Ac5Hz2orF^KpG@q8i+%h(w=7|N4iZ_z=vpPgXL%jOwuHQ;3Q8X z2xT25L_uxU_I-^809F79R{n;uDyWLn2>=QgGHmGZA;cB`TtKX7@ghct8SFgy;qfEL zkRnHtENRlC5j#dsvTW&cWXhE2wXd%VoDM)+V@;s>pY7c&M>=GQF(jVDvCZ22WR|GMYyVHN@e_qbkpg6}h?`3~{8xi02=_ z?En1nI{=^qG-eYPS~4dY0EBvj0D#)Jkix$>0G^#ySgD;w&!Cs{x5z-(FHH0|Ab|xM zcp!rLefHi43bmk#e59F{AVjM9b|FZ!Vd$HN8`9R{7kl`zg@+&kClpZ-fe_3*Vi?#Q zg$%)X*>kAX(*r|2*n?3AJow1NG_UXgzz5Md)8Imxlp}yb2)siG0CD^igF;B$1;8lR zECh@HG79b&<8qGt;s}^!nt3LgX6m=lGF_Em&N%mU#o2^tT3BLj9pcHFo_p4$;TC`F z@r9p1oG4t14;6IV=eKfc;d-3_q3tuS#JFE zFTkh8@eDiaFhj*cDiGsNIjoqlkQ>$H;|(PjA!}@90{|EX#vOb7@vs-$(*gj)cmlxx z3Omv{t(_ck+f$z}pA@sqCCzrm9&A`)t+~lP%FrS6POfTO>d&zqlwo^2t9wbqZ0O zM+FXNQ|q$np_g90+@fRuQA|mwv4bDu!kP<2B)p@5U$P+pX7P(efU%5b?Am8o z(E$Jyq>XL-VFH6F#0L^_dqxDE5$>RqGt|t93uzAQg5^Ogf{BWXiC<>aF}8(NK^FlLBp;$^moC3eF@%HvTp1QQ;|gq0 zK>z}v!Zlj)$TNa~7r&6fC4(uxeymTI&dU0AB;~hRSm#YEeYfCPH1=n1!-aq6EZ%FN=`Tp$hY2s|W={K*0)= zf+?9rRB82CS}2_L;SMq7*-U*_6cNCqMP*9pfWSHxo=zsDW<6{FNY9DRF%h+`mAqIx zqPCD4;D>Y5!>2N#8bQ6fjc$A30$)oc(5gJbIE^Z#PTdDf&NQR3j(u!1)M~~o{Hg$M zy(}0nR*s4-gc9apYK)v}$H0P;v@c8D9>yS5*bJ5^OPI$zlyJ1fR&lXy^(g@p0H7>j zwzn?4*e33Q3Q0%;74_HzXelJxm712B&9#>Iz?X#8wx+cYpv62MaVD|yhr3ZB>t$#l z2fAF8g_f`EoP)Bz1apyrrOMQL8I%3S@rZGsh~BY*eQS~1K69y6Tn zHeb0J@KWXk%}*RKS14lz?vSt?uuoVX4zm}PMUF^WZu#}tSbFo!boL5ysaLx0BN zwg9abKy6bzO~JFJF};0KyzW`t>Gq8k!Zj`i;<_RhNM9s?&FDoFNZuKdh?hUn5IF=Q z2y%c%IM&DzeLzVenE0$kNYII4I9pZKE+Y#V2ZD+-y-ZV+#5M4N4{J!Gz8b$T$6@X9 zS#M|vXvmoFUCl4Y3{5Q`a#AQnpxyhdC2jjAtX65mK}f|eWAj~A-)HSs4vVM2V? zU~t#-ki`Qyj~vfyhWZv^FaS89j!ZNJ*$aUNvn!&BY4~FrnMgrI`Cds8_~I7_##k(> z?1c199QVV#7(O66S9|~;LBiiF*S(DK%>=lJ3%Mv?0MZ5q6+(fDfc0U<171c1mImlG z1SzzE3sk`}oC68~fGdn%73_m1;J_zv8b;UvC~(6*ECcU7ocdK#Ec}8Zc#H__f;`Ye zmA#++1=Gb~!(S{!CuqsyeOu!#-{TqoVNc+U&R9>$H3SH#%lb@UWk?}qP$5I`)G&}k zK9IvO=#Mk#l0pQ+Hsk{~m>E-0K{fQl(V5ZfeT)l79)$c_~@#v?LDB%(|Ok_Hu=LOImKFsxx2_0lhO zObzBk9PWY+(&1aJniRZ({k%dHSY79A+}6cn&1k_ttqvk0q2)>06~NXU4wUr8+b@#F zBw}A+jtL>L8zDyFV0r-f|EeaxQ zWmN*;LU#R8FmlEuD#kEYVrKaNgEVA92eRG^RuV;76voJ2D*VGa*j_bW(#6=Dy>$Qt z_@RLS;*ybL@!_INcmV}j(9AfbPh?fl0K@J1V%o9YM)t=$4qIld9@Vto00Gr62vx@f z!awLkK=NP(JB7io+?27Lz`w{HR-VztFav!pgdi{j07wFub(>k{ zBwD7FP__i1?S`PaWo737VsJ1ZJh&TDW|?RTn_H3O04)H3^rEo{z`vA0VM5Zy+=EEg zz>c_p%9Q0@O=f;^i+@QZ+id1coCpZ?jf-VaT>|5A3S(YY1Tk78Mx~d>w8KBVCTzA4 zH;e*9jKVemz!Z?fo#CXb>E!SM=Y}MrNSGK<{$|NBq9D=bXkr;@@(0GHUsPJs75qwj z77IE2!$DGK8C^^r3fW^VGNZhA;g>;WImgn6C>aD)Lb>dkUW z;D%bpM=l4{NgdUxT76cM#{2?rVN5dogB$qgf3BJfjKU6yLSzn3jcTKK0^oyUNN(&# z*u6xBn#51k;5-!nr|Wd+6e4LAD(MyOoEghA{6n(2s12E> z2;HdvZR2?E=!MkUGDHyK=^4ct#z?|H+~%te(8W|k)vZ|+n9UHv;-l*7ntC1BX^Y#$UoSY0vA&z9 zF2;wV#vSJWp(pHNADXH=$$-)siyT~KwGxoXP{f+SK&j&Dhka{WlIKTAUTf^?NLVVz zq|&i|)w+V}Vx;0KwxYA1QStm8u~31&?yCS@j5ol6nn{=>0II+;9=ICpg(PC65=z1b z>quaMy2JvX9;v2oMmuUnyAl3;}lSLKxJnaXu_!-Rwn3tX2@DVHo7ano-ipP_YQ+Ka>~IBG1JLKqtI|KlsBv zAeBXM!Zf(UIT!<9D8vM$LOQ$yG1Mb-f+voeX_;b(xU#{IQZ2U>M?4flp>3_YdTnOx zEN8&~q)f&nP1>Ze^sEc{ov{pU+X@fjK!6TVK{8r|GEl+}AVD&OLo%j z?wICiAR=y0AS|!KEJzdrQZPbmSuO;wt2;)llUl}Bc4ZxWWmt~ow%y|}wPCT4Zs~HE z^)>|x{KLMGfIb9*LI^Fw6z-xXWTW=()5b>2=85on#IPF25F9Vp;#7Q+24XVAVm9Vu zhD`Sc6Z^Se_D<*ax@`b21r7Yekifw|xTZpc1C=gBVHidZ{6h^WfCg_c2Y0Xse=rD# zum~#v32=lFoG=QfunMm*3%9Tfzwik|fgL~r4A-y?-!KcyFb(4{4Erh?@bC-kFc1&_ zF$&v4m0f`mJV6#@zzA=E9c;h|N3j%7@drCG6jL!4XE6v{u@+~s3p8(K$mXclCbjYk z=(cXsC13I%Q&~Jv0w#B|Cx0?1hq5JG0vJ=qb!O*wc4zfk zX)sArEfjE?xiR;$GDf5VI22AD-*FxjhP_>I26r(qV{r*T0TCDT5DT#}C$kMBvoae& zh}catqcAf^a|;(ok)p5?GqDJBaWHqY6mzpThw~Ocu{ewH7eD1?1n7Vk=z%8x=z;<; zEnAW&f+ny0%M{4+EH6eXj04&@Fa!gD1nXt`7KlRjneVy;^0_RBz%21*mx)ZSdsgoK za?^6e=!_1u(3gGh>R9w@{Oc(g$0YQY{fOBCS9t!%K0 z0gKQ=5j?ckMl^i(bhn}N{fV?CJ%&CCi#>z%@(8sAP+JC}8fs%E>MCDW0|eEu{L8W+wc&v29{&Sp z{jECGLouM=Rio@nw=YdR^WBu^nubB&w|fjA+oG$AjCQn-gQZ(38v(NaOuF0Fo>k*@$tnh=2Y{`ZF` zjqWlk?=B>Ig9P%mc9m}F-ZdDjrCV%wQ)=^Q)yiSJaT6ZHDB zc$|;Kiw|PDg#mU6jTi*ymMgE$`g)gRcxeWBB|+<%Kx2@zdX+Bus}o3p%NlwgcXCsC ziaEg}bX7b&f)a3M`GmS+jXFk^dJWktFJvT`z@Z%|d#i8%S+f&(tiw5Jv&4Ga`m9|6 zBdE(f;KHuggnS3Ox0iP*XQiPJQ^uMJYwm@*uQ@ihdw)FplgF>)o`j{-`%8quBd|!7 z9m3RdyTeYmzk|CwiF*zGteH%}zYIpg6N|{Z-GDdzyBj!6zpnuD6%!mnp2JoyFv7N1 zSFa2DlKT8)fO)tR`})ODDIy4oBYDc3G0~%V%kziBQ~H6!uZa2Z##;-`3_&5p0>;aO zEoi&~_WZxE9MCTWp=VapLz3u%$@kXN(yM&hv-{I8N7T>!)PIOx^(f;$d`yYKBcu;( z^}-`Ow{P@&*N(kH1w4gp!atma382C@+=Dovf;lPw#1t?CJFLSp#PUMWfIF}QLx>rf znPEk&JPl!QjF7@VOz_)VT-*cv+#^TbbBn^hY=EIDw10%Xqa$p=gDeyRpI?aK<1e7! zPKHy+6nuj1*WnVh5!VT;IF_Z)CD8Mu%1L!NnrDfWtb=o_QFmkYGWB2M03A(f~k1 zhYtZLu%iHCMT-|PX4DvQ;zo}jK{}L3F=R;qEB>u8xss(r4&2~4J5@1IJ_G=!q-@yZ z9}S12UQuG_a2PU&(Ntyp@b5!Qr%$0qbr|damm;Z975w|B<7!v0U%`eI+jVKvu^Umk zINLIVohJz4#+5twpb8BrUT4?A5aoPaDwubZ}#34+~sVIUEI7G=T z{y_8y1YUlTfj(6JX(z-LS!}T-=$e!Nj>YQUtI;6uY|IhIg2vdxk1cYfYluQ(frqhp zXgQ>aAmxg$vW{BJk3T89+Rw!m%n72Q(j59g8f8eLKpI!3pn@1|C;*_CQ5u>MfC?|n z5TZ}Cs`En^@dO}}UlyTnoPS!$Q_w;4gpoNJSEP~28h2cDyG8}#Vvjw#a1)BS0%Ep3PQU=L}sA(GV5=6gx=8-3wAJ0z0GJfx=LX zF?eJtgxqpNz39~D?qx1tr&4AAu>&3e=3$ywcmUvoXq?&Lp-jr5761g^u`q{#J86dp z696d6A!w4qsM~GnYk)*0oICCxl0Z&bWwAak?pqMUT{pYCWR9%SB-9WuiE@XeMIOf3 zyF#FO#jV$(eU(GHIHgzWH_y@zwkC!YsFoE6d{W6_hgaB90U|f6*hdo_KGCOOkDXn4 zx;-6n?vj7PQCsf0p=uepm-&mi=I&_T+uXhf>ahjSHn{Lpu_(hiin)BwL9A3{|_l;Z! z4e$H(_FJyTg)eBwE+(!2)Y2;+0p{IU+`AF*y&s3Da?P&4Ec=fx-(9NSy$@>vU4C(* zIjzD^KYZ{n`<=evi${p~_=g4@-95&zv|S_T0frGL;4;5ORS!RrThaE;fIFurnr!K^8xoM=ltlgyD%$ zW&{+80YjufvFI=(-OFG}Hu%GqI6-y`Sk5~B;R+!xFp1yWrzr=A1Jm6kyKQq@cOa^Kj1G%g|G!<-L$6H~UybP&wtEiY1pU+{u5zq!XhPytSLa?6#>;4Ojc7W1dWP88-kJ?aOeXOu!v{^R1r$>BOK#6 z#tvF}r**DG0Jiu=8Gus*t$b#qB?ZkltF+4*P4S8(yktumhX*w5felu8j~F5uk64u9 zQOzvcGoQ5o$sA6TR78~uN;db2iueaWTzW_qB!PrBAfp{5-5p9z3V=oYLYBWl#y?P# zRk5B0t4CF-6s-eO#`)BjfY`$yxKN%j#Nubk!XNhV1@15}9*m(Rqu6Sxy$aQn ze8rb*pVG!v3F}p{!U!>7vDkK2RwDwa#V^DFniOb-wY)VhOD-GRvx1AIYQOK|SEm4$ffo5!zy@|UiyS~3rO>TLkBbpS{2~^hQN}-V z6JP!RB6qiUTQ1C+>)ao7R$N5LnI4*Oogo|oaW4d8kO;h;)w)Q$m;rA~uIUgixxzpI z@I)M7AO%?5gDdOn?|vV`f?xPT1eb9E`cNEWkR+F1|IJ%~of~0G^~eu*c&T0raSO)y zZ%Itj@pUE~r3)`@$xSP-M!4jRKmouM;mAihk`aZB$`~WF_(dWvQ;mOAgUe;^4Sf9@ zMdqeez(;0MBfG#|f?z=w?|K9P9pz@jBw2DzrktNG_hib_c%Ac|#adKwEi*5=B7|m1 zW|y;B`svw5_Zx#Ei@=EM$|4NnqV!()%*oY!`QWvW<3EQ$U{9cDf2 zRGS3S%8_*ZjE$WkoMDTEn;)GS6AVTax!7_JQmBVI>Y~cqtj`|nwr?q%LyP4Z|9FSP zvb|`0oBG!8%QZ~HeVs47HLe3@Yo@Oo3&_+g;Y~vJ(U_gUjE}|H#~t`9M^vJ)SR2~` zXY|LpS8xv=yrmT{j4+8=zaJAs44Rq;E{MH1m%|0#t)+KgH?EOWgA?U~+*6;x0*e#@ z+~j30`U2GqU^eI2-Jh}o8>ai*ng2iuk1!HE*1gE8+oT7@dwUL1014{y-J(sARqorxD9 z(GR}zihmTt?srG?Z@OKaZ;O5Fe&aEa*80+}|11~}p0wi2Q+852K53B0$k1;|c_tp+ zD{#=tU_0-0ysstnz!^O-VQ(WzIWmNoEJTB4F>%f&U&4&Hp6%6$eXmHKx4K_qv~IDh zs2m_4|4>Ho1wMQZ>K&eZ_a*hqb3b)S4=-IWEiewza`+?J`URvtlm8DmxUaIjPly;RMjn%nA^c*iW3Z0`SjD5Hto5 z+CGob_T&~QNV)!j6dn)))o(0{?>CN*o-Qyl#;x4s2M-v*NLr7&`Yr?=r~hu~1hGf^ zx*`Sdtp-ud3CL%hE&wXP;UDZl{AMu5BG8&9Fw!b;`i$^X77ni9A`8-E9uBX~c2F{q z(2SVyDk_X6oRICHaKBdV7xWO!oWg?sq3*Vj%es)TzR=sk@b$*fQ9diQ;NlRR2keLt z;o1lyKR4vDq{+p#<#-Q_;*~M-N4gB~;-b^x;?C+N|%0s@{<5Tj9-qVC3~ zPS;*>F0_b?4B`+LqxE*Kr@}Eu$k9}S@vjmx9R+C}A!w`gP#27-Bt+^T-e4Z-u^5SO z8jY_S#j$4K%php-<~nU4$7LVs;vj+U964?whtUo-vdmNr8G|b%IA9o8e`H1 zIT8mw68Q>}J76w<3IYpk?h%U2BmoK~=RzgX&K%co?Xt=tA&4sUu)aV-0H#4Jyk;kP zGCF>e6@yX-hY~xk4xjXiAPT{GS}*kkZ198!D)l8H$IB)EsnVpZvVo!n8Cd`%OhGG3 z4lGg3Ay-i|T9M+MvLFDjrU+sP7~yAf;TD4vDsc`s!!9k1C57%KtFj*VYkZIq z={7SfWC73MGAsXdG9=kWQ{sUUB2ngevp2^PIExdFhSMbK zFf@Cz%p40D!(bzDG9Bb`It#Np&FUU;EgvP(H}&Fvynrp82N-gW{>HO1YtuZXQpwKq zA{a7|_7Z};Ob@#XBf{Yy>H%Zy^FG@%EUt4cvU6SkTrLAsXdoD&v~mIQLMQIybcY@Do*B6FXs3G5vEchG3@pK=6v-5ll-r zS2RgI%|#D_E+4N!w+}BpZb**{14u*$_52Z*!^hmXHF?+-ee}D-h zNh!t1N}G~O`EM5+Pew&;D!a5p%WOH}PVN-oPyPW3(o{{og-y>QMB7bI5u%Yq>j#i> z9^fJW=mJ4!MpE|-M*B=ln~+PXQ&71~36QaT@WUDeb5R-9og8&6Ahk+8wIJkAAjF^- z<{=mgbcSlx$ndlvu(b9>RSrp2NKIA71mG6`kg-A|U>mez5?u9FT_#q=Vpc!J*pA?y zO0*CbqZe+`R}VB;6O>P{uUIn?T@UJ53D8U9Yrb+6vL=8WwBiz`m0Ht`m)ulDUy%rA z$}tb2v~WTCENNVSRWF7W0R2=NX>_A(6oNp2)%FkoqCqS2;9l_+^sF^3u+>s_jmP3D zGUtI7n7}YN^=}UL*v!@c7S`tgwNy_L6n|kBSoI&|0An-O*7Vch_!9(k1kQ#4O6MUK z*bQY3wmerh30v0eUKUwT@d{G)9NZOWnaD6V7A!h8&)Tpkiy#&l;}OEMV0rUo=M+@` zG)8^0Vb|$lA&3BUfgbe19q0i_skUAJlQpGwcIA4u2x}xQ)xb6xgAoYwXy?*w<85hE zN^MbXYU4{7`~j@Usctz`Ec15n_V)cGwK27z7Um%yH1#A?)<(!SVFfTfOJY5d^KN5I z0q*M`yg?6ZQgY+VYAd(>F4qDj6=a1hQ_F*F#TJtc*JaUmMgw&VO#o5p0U1S6c44+P zYnK9VR}9O8QZlWH)-KeU9rM+LjrZfS9Rmdk6xwjNK+3@bA45ia`hE{t#Ld2wtB<$ ze#cgO1%h-<5OJ*&d>vMNO^N{jKtU_A;UNfBA{E$f8F-}}_#-1D8}&fgfMJ3uI4(z* zduLCB>#cb0&IF+KA2IV%2WDW-~E@xUPj02IpM9+;s9KGS^-afO8vJGAHz zU|5D{m<>bsDQ&nMy_aEi*yO69PGqnmev3khxQJUq4nkp7lDHu@fgS812#&!UoRN*L z_A9b>Q95hk_5g8W7+AabdM&tY_16-^Sa^w-eP;~;mQm3x;_dX1#nzZTqv9XpSOCf) zzeoTde&zP|*em*&kRxLe1zC#+w}J~9GZR@e)zg1L0)RVMfU_zF+CeMCfdnu@WJ>dr zQ#X_27zPs6A)X=f z2=x|d2bj0nmK#Eo8={QAGGm58Ll`Ot{-FjGpq}mdp7A-K^?9H9xt|q)1l+<11bUze zx}XjEpbpCAh|z@In3 z4mQA_ReGgaTAxokrCU0tWqO}qdZuOi#T1w5xH*tIpkn{w8yaLIejru($eb4!odH0d z0f3!};+^MYbN;~+>|m;?x~i@EsHSZ<$A9FckVm`65D2OnJK#@sk6P015C52^wS*)}ao1z!>nDxEmOM<$??R zK-lErbF=l3f0uf`7$K>e=K@{-Y))|bwUt{`#9#E4vDqVF`E=QJfl&-KwL%jdJR^t*8A;~Bv3sWpuDF5n zxRG=&vN3RboWt`sx^Z|V2b{$R_`v^R8XWK`{#p-T(8h&`b~l`w$8bsa;Ab8IxrN-n zO+3Jb6U>S8$l2JqN&p(_q{*WKUa3&Zmx#($n7$99M@mZ;iZ)W^yoUbU$QRiwuDfb+ ze0TitA6~&L@^E6^{DL3Q-fE!E^o6><5ZeRz9p&TfJ6GEX1VjvUxq2z|W*pFSk zEF!z{4Z>gXI}zfy%X59tF+Eh*FR7O5KMw05;G`k{ zFa#{pozrXLCUW94c)}+jA{khrAvC7lJLV#!-Z^xj9<%})VmvBla%Ojw>#xe%(J|w% zV&k`K=6VFk%U;}v+|v8}hJ8}y8_JrpWJ@?b?g3!#zry7?{WMZzHCp2}V&fs6;f!M* z0A_w!7|KI7N&$RSE2;oE9AQsvp`0N<@-H49vHdl*J;VzFd9)mNVO<1?{PV%Mku74j zTm@ESvQ_jU3rnCk5vq(BZNK^7#aA3_lF0i)i;LgZdf9)eCbC;8PTY;;-ue**)^ zXNZqqcL3tUzYhQk8a#+Fp~8g>3$FO*qM^iz6dPu+^W=xdjT}3A{0K6nNR3AS>=@z5 z1(7l(`fvrq4m_&z znD&YX!ePh^LR0m0;R3OYM=@PjmENhwHkHH8W>Y!nW@sVB*xK0*dDnM)YqgW!h* z!x}z}xFCgP{~B)+ka+2$U$Y=bzKl7u=FOZt6BSt4bHj%bMK8UWai{8=GdF7K6Kq~C zC#!3BY;8MtNZh(@_WaqU3NEN$ zehZSuAVaA2Mj=PI9kE6(^8gb@g{$%Ap>80C7}9S*2^Aqj$fbDDikT@#5pw`I(~3cX zY?BW*b7V%9Raj~DK{U>6a8M@YScbqmd;#FbJD6nQb0*#|HPN#WR+P7 zW|(58=%9iSjyWNTBIZOy8o108Pa$gRG~%2))oJHOCI*M%m;ktFC7_qV=qEzV1!+wT zDJ%*e4)~;!!w#>oqXGbTiLz)4CO{`0b=FZCTA`c?qU9)HionY+PKe5CtFAs(W`bvm znP#4M%n^L9Iml zk25ynsG~%&zKR$M)il-*2Vy$%ODyER3vavtj4R-*Vb&U~O*4J5M?CYylCQ8i1+4GD z1Q)x|vJ5J`Aj5_=E3a|%Mog3dm}uDykz%6yOA!=*4041M>t`>R_!9h5NnPv_+bv3< zEYh$r-)3;Y2rJ}pf;l6&GgAtZq3lL7bkj};UFCxi`FZlpAQ^Fo z9~uIKh1FNr?Da=7&v|n~J@0q6erX%^^V5+D?RE`Xx&i^KGWha~3~ukuH&bw%RKkxZTB74-$QTEOk?Z+T-RzOzc_+<>83BFxo3g1 zIC$b1?jaAai7O8F>?GCh>*FmRD`w@M`99I*r}Gze-w3RtWfbrJ@Cz?23=e(jsdu(| zimiv;<{m4_GKB3G;y!!hA?j`r@SK^y8Tt$fA3a6WM=V7?|H&&l>FwX|^!v$8jV4Ck zYczy2>;V|_*adC=cRQLO@CV}a5c!(IyD+IQGZQ4*Kcs>`rReWn6G(=Z9wRR$H1ByC zEFr}<_#*z%%76bG!yYsQ4>2q-fiq+v_=x3`6D0*%5d>2O6T&_dCIp49l7l}QvyDno ztbRgl;=71AC>7p|g|=InuIAwg1tPG4DB~i99{8vK9tKK`Eczirg6PD8Kv7he(9)AY zR)i6zagK#rBeSGvGAbsH3w~hPzivo4F9uAIx&fmZ6LUz!B+?-lq$8-@)|h8(3TRAp zq$OEoN5oVwLf1ptYhEauCjc^RgbY?GZDU9>Dod3SS|k9_n8r+wsRin48uNUiw@d0$ zL9%=p9tEdIuUUZ&d!WTUVt7hhB{NUUR81;(*gIA(Oqz#*r4xI(%gBh1Y1!Y|JmbuiYKQ)t2pNZ3YO?&1)v&scsQV%5f=rqxD*_@mkNDnHZ5P$t#I-~@Sw3<+iGTX zr(`|tWmteWj~SP+sSRFY&$?JUeNqkoh45FeY+J+K-YK`^tE;hst00Rq1*4(OW^+%w zwB<6lxW-v+f?DgLVeVlKR?rYFx`$n;au;UWqryS~(Bj=~s-Q$`Scb(7LA{NTd9IH1_T zY)U};O3Y*iZjn`|<^r=h&PL(?*nt@B&pDs5&H}o#ZIt?jALMu*JMMCiNhxS$hI%!H zZWx*+cWT5ESeKFpte4UQY2t=zq?F!|rB`FcF^qZ3vcSow88>P>5!$;6OSNdkOB`dX zHqoqJbgU~vpkI{X*-4&tQDrHnk@* znOY3s-OaXkS!=DITkC|6u_c10b(}JDlSs@l88&dfd+3U)TOudUV5}O-{J$q>CBgb@}#@|qBkLdo=qDoVv>PctSRq~Du2;fHWNM5 zbgeYJLPno;3(yIAe;8o7XHYFN>3P^h0!Gv|VD3(z*#Egx$a4Fochl_MqvMzB{yby_ z7ppogr`#sY84Q#0_s7b@;2S$NNW`i35Nvhn}2_Vu$wSH0=0o?b{#SDE*8-Jg-y zTKE5avS@F<^3cKTmVVT*r)ItnGT)?J%|?3FC{bmDPxm4Y-}d22F-0`@^F|ET|F6&J z(el{?4h2L3TO)?@dEc7VSA#aAd1t23--64ciuETf(f*i)ho=kaCTq98<9yHm_}+E3 z3M{Z;N`f6B;g5a<^q*Q$&|B~KQjdI=(u@=vx1p~qv8|sBBuN4qF#aq)l1raot&G1a z57zaqfkL@0TQOFwkl8f_*B3-M_G#EhMMQ0A(C9y; z*VjV(=(zVexGIPF>LZM%{4>r({3R?JlI$Z&C_mDYF*HQ!Hlhw~aL=ChJ^wT5l-?KZ zQ%XvYi9SCH&7ui-FBHHyMif{Bou8mItD)-kj){tl5nG8u)Q6Tf#J!P^*7xzOiHary zLbCN^Q7h5Y4UCswkZZ9hXE)N6?ugzq?U+)oetM;0ABSWKlhL!7$tgsgO6)#Ncsk0p zyxrM$DPB_o-md*RQYB%bCS_5&uIa@x&*#<4FkNN#w0sSC(~3GcKt# zs|2FXs9zIF>k$dA`ZPCHX&CjL$-f{Dqmn5t5_3wZnMxq6lavNMRD}`=Jy9tYy@6FW z=-)jF{Szr<&!Q(!(do+Z#*NAQ-;!_pPzy46uu_sT$$2oI$DXXNFcJwbJqEOkXR32wTxEtF)<@Ge(_7gt z-g=W)ohL~~S;P5x1mD=xq4X3(k933c)H{=@x1!P7Tp3XISRe1qD!B}M25JMBjHmmQ zk7}$MkO>FgseRAV8$!}Y=rbKpvz$*8vNNM+pLy2v@aC53J8Uv`bwLU@DHUsUji?`& zWqQPC-mUtQP)qzOmFHC>G2m%KN(AHv6lP;ni8KmwXZv$!h_if=K5Ue!`am<&uODc%g}|HgWm5>3pjKXaSV!W49e^^6Q@w zIeJ8yuZc~^@4d+|CEvkPj3J@KNt^~DaCx76k!PeeUinXx^EuK8$W05mVhUMNX3zgn zMk1tQ&viG-3f7;ewv81KZ5HTQ`g;mOMNPql1#qb##2YL{CKWQnB65({(F{>&DqLtk z`J4h}#*WT)*}Pk8nzFW;AsSPV_$7}vqeubr)~}2rO|W>o#y8-(ugN!a%>ks=md~qS zfE|#>js>0!P=?n?mpsogVk`=nDH%R}mpGL-_N?@~cWK-kaL54xWeox<2sb^Cx2&Q(ybaJMTd#9gE85*f2N(boQTX}ty z|3b2ahOcADOr>r~+LJ7!;lI#i11ldjdF5J=AZOCgXH7EhgC2k&@Z~4e#}IL|rmj)j zP*~yr_!2}e zg(RiIDldYn)!n{HrA++B8Ais&4wZY)sV9Pgkk1Tlxnobhp-G5jfz=vfirY;OLZQ39 zb;LnLi3lblJs5pZ31#WmZthRdpEqu9e4W^eA)c=OcHbFFCJN%GL}1`Pric$NWQc7p zI0ni)MP!bF)uP*zJYhbOHLP)8m7jeewELv$7ykM8`{Q#`je(Br_Q$;Y@F%8-Vk9|? zl0GB}jMK(XHT0PA_gHB3SUL3A#P#f`qnbN5? zWG&jHNv6a;*unnFp~0b{;q9SOvf(lQ;qMy5KOBZ9Egi<#q*gF^BJ1DWlQ z@g+0EI-StkZZ>T93+92np?)S8DAJ{$9!+o>H+o(<`gdsbs%4bJ6w0wQ3f9CDIbu)A zupoad=`fZs7fVh)b{$8MN;a_XFqURCcB5)6|3N=fd`}S>hO~|t7eseEh-B6U{xgV# z!xZrtL$+N*F&IP$p(Gp)g0Jjj#0vkZ-R>Gds507MB}dqQbx^UBmtrs!4xMU#ts3)R zr}%K@oH>s_2oo)ulH0a}yR@M~0CWyTM$}HQi6IfM!9SspKOp$ea%~Lff0k?S^T;?3 zr1U<>ks4R1Vh9O>r=YT1L?XJ8(ib#K$Z;iv7Di(&2%ouVP^ukn1c?}a zfN?1BKi%5e;{SAOYa@)z5M$`tQuoP}^ycQ~$*6;8nW!(Fq-o*Obu~19H%U1 zc=5&B_d@7k_+o8s1WOP_K0rX@LNe_#{lSzBasa{A@Eqx|oxbgkQ=@nO-TLutCep0l zO%fYXqw0sw7kzu)Q$tsW8qf?zrJzLx~rDME&dwVuqn9hoQ&aRfu@qo@%=!Pfz z5=3?hlCVUyd?V=XdPtQP;-8y}|XD^?0Pd8cbxu9sPs*jZQ2SU29X zZc{dl86&jNrZMgG1&kq7g?}a7qexb{z_587Qs2MJd=HW(^|5kJEa#-8)heQ6k z4w-RtfhoD~VpZdd$+sR>&EzH|J27opbpLKUUjJ$QF-3oS$7dV$e50#vTTwRh6g*zr z@CCX5o7QXv)Vx(nu@=|5Lw{$Do4M^{(3>9*e_5Nih|F$_=k1i|ZM9zQr1dvvP6LYA z_p5nyMNWu!A9i>0R_5DQUQp~eknXlL14MPOm>QV8{oX0-wt?sF`uBykfxQUU{W+5Z z$$>5fbwC&?*;E6IHO(g--6t#Dn|gRK)V903yZ2>&YjpEV^!`EFPZ*ol&P`{;Z>8W?(>8t8f-_cY5 zy;Hs=P}&kGQ0pw*`OKH?EHv;8-&X3Ee-;lvPr{ugX`M&PoTnz92LzsHj-J2zdY+qq znn}KNp#ZwkRa%mGQC59XF?vz8cTo-hTYLBKN3Fk~od1^KKx}sx)y<;^qUZzw0=-s1t7ss|wDxcTN{h0ajTld3@ZVJxY z5Y(f3TfDu5p4c%=v!CsFm;KnuxJ7Jl?H7}~^9zjYH01VWy5Nh>NZPyBa~V$Ny-5V9 zw7Cp7tL}6mwuzQ$_nDD=;|RL>WRK1MP@TyK#!a6#Ci5+--y2KqJIq!-SyyVw_BNjT zdUZjUC)K#R(ie?;#QNpS%6eM*QG&^wFhXQXjqe}(N$-3cwX=fW<1k~8bt;g{ zvIA1%sN+P}=mCPlSJp91da@bs)bWF>B$i$GF`O33=e@dsQEAB=X5nS!gaMZk9}92a z>-!sT3Aisdiqjz|YByLkdz9o)-t|-#NbPzuuF`!i%O*dVPSUJ4Udg}?kWh(CW%5G4 zXC}JsE4BN@xxv?_`h+5zQ!}USD9Ao8b%j|+KRN4VMXi^gecurz+j&61ri@B&CPM1aVV0)Nk0%4GjZBgLp-~4lINgJpM9sryzkm!F44a5Qfxt}Q^=ZXvf zXa~_dur>81g}C>>Wg}oRlS&AaxjNXxum2iviJ*;bbT^m7=j~N_vs}Mk)>;N~kSGq@ zf(ZiVh=C6hJ)XAva8~_ZTKt&LVOR?JW5f#c4_kI;2?7eHfOd+CQ6`z0y5EkFI`Z8qwFeQrr6_Lz{pJ1bO`Rq61vY}Y6hr37Y{yV;8%;rD{yp?(eGwb^riwbr zxa?s8)73_#SO+xdo!CiP!WSOp1BEAf7kacb57K%428IGn$=?fP+G*Z;JdsoQqrBC; zg5|kxxPMnLr+X@oCXYx=Aji|%Xd*g54@=Jap(l6WGWtPP3W-a`p*WwQGD5#YYheS- zC?KndkKUtP$qJ##Do~v4tMAyzEv>?O_CgR^mR#CgM6mRUfW0wa_{+;swgHt03IbFJ zV?i_{FJHHVvE)<+sNh5L^3F@cL8>K^^u`{=4{lF-q61-KdRG_&{pUZ&nYG0~OkVed7L)z76pkI2@&xkz)Yf|cL6L@=GFyW^X~i|U<*s$_UWXGDT)t(@fml5d|E*e zl-J_mS1{L9^#ciIE`!6R%||dI38ZVZ>LrTSrIXgCjGX43O83uVbLKlWkNVDBR|3yM z*{nZmO87((yTNRjGi+74IL-{jJ8C)Ib8OXVw8`vqP@m%%+>#RGT7xzzZX-&e?0|NB zz+59+2N98&Ax^G;KrfS1$%~k{u0<-{WqL4GLQQ>0R^0TxTWYe-Jz$D?QQY~DA zuRru_=hyQLUoVY(T$~kPdrl+S<0_Lw0NCk%&$2ej6}z>v!N(?!O=%O7xi;H;pH<|p zuCyMhOGe5%sl@29n!6WpD@YF=`mAFUfcp)H+O^z_Z3*s{CNPZ|yS~k$U`@=`IHr`Q zxA!__%p~PNkIVt`N>rP6Zg^JDH(ebDV!5 zD3XBTP+Xv8NRM#wGUrTEp4Z3K`P6=iR`F}+M4aTR2n0j1f0FzLZ2F7!HUB+5G^pS= zDO*Y(em2=LTd$^w9HkX(Tn(O?(=cPpDIj3qYVTQO=C$yV=;e0kB;Y_Uvt^;=&ctdH zB#$xlJo4mI-H-mzaWB!Ypg`Z*8XYmV^F&6ck^sKfn0|_Yd5sVtlVA_0(<5Nml#m4S zm_EHmgP<9uxt7Nx-f5T8`=K_`%aqkVJs-R1r%FL^bZ~rEQUUXasbJ(*`=cJCw%?i1 zmL=l7^RBxOO(ihOylyq2&uUh*%57SIn^n_KpBf)EB=&z1EV)1O>ds+GwV!3O*56@j z+%@O=&waj(NAhK=d549+5u9|{Q*)L#na@qBetEYPHw@HT<<>Y1)%`O3rKF5FrWu2kxjus6ETT2&q5iN)5|2ttyq`=D)h|d+ z_j%A;5#hHFIg2GD-u?=0!jR3OXg4r$GTHC?;hrjy=2(9HcBo-R9Bna%t_wx3AjCi@ zOGy|c;REr~hFaTFrA@W7>a|~4$db}@kk38jsiVVh3e|;VX}aRr=1@17JJy<0v?OF) zHae&^WMK~S;(qcHaq{>o;22xPLV|y9tJ``-55n){#!o3kOpG4@^2foo4`unDGRGdomY9}61 z9smVBX)MhlCHfm2{&_|@qozCUOj+GDTJ{VYFdKI3H{`D2N6T!L3|yRQW>+)IS)_Mk zzc)7W6))r|Lh0{Yh?Xs}6gE;H3?x}b2VPPE+MJB#gr2Y*d?cLH1$EC*{YRi4r{qPj zGH$3b?j!S#Rn-a9-f|42OQ_kJr@V|Q>MbJlf~5wc39E|9( zGJ0R<5c>HM%lSY#B!Z8%HJr?bKGS4R)dsVc5?U8)%nfPIiy#R42pzGJ?%EN{LN!iE zC5#s(fzURzt+UtPsp%2$gEmlG4$i)FZp_+<{>M-LbTZI{_mgph zPJcTCFEO6y&CO>G4d?X*f19i?KR?DbN?d+axUS>F`^*Quy~D%9gM)(u0|ULiy?Bbb zv$OMGNV&DO6(5E)Ha6lF<$nofT!s2|85ORK^ty!P`aRKQrR7!C?YWA?>gwtbA3ju6 zRFsvK{Yxn0ih}XRGOif7D6+bK2l`M{^!DxB{QUgWtgN%-{rTvR4CnhGw#l`*WDu;!Ig@lCsFIV~X z>(@R$KHlEmo}Qj~TG`pzIn>I^!NI}S*7m>C%ErdVcv@LsUmuSoKY8**S63JBB%i2j zoGMBkKa@Ha6TRl=UE>oty~)0cym`fR>{(E7#`Sac) zCY1D)XR6boD#Qw_a#)g$;|9ETSt;MOYzwhGi!lw}2>76szv!fsOOv5X(KOs=k3&uP*^lLjSq4)HY`2U=gR(qVWD&-;lZDcTYmRDKAVN}7Cu{j zr5ur7?5*xJ$>F6n()Cl8tJsv28P}+TWxVvO3*|XK+qck=P51{=exGTbxl4W@O91cU zS$p-vhkc1zY8n|3Jz$Jvb6RxXnKDcU9xsML9|8Ltf(|iVKp=nrYV! z?wTp$hR#P6$gUvCxAY1LT;SB?;nH^r95v^988c@d|VO z`k?R^r+Gl(8jsru>*5-_0!E??p+L$Ds;V93l0;KkcSYU1^LM-c`x~!1`FmXV{hcns zAt<)5djR3s*f+9fdg$kwIRKhP`HIf?d+&sh3H6b+ljkI@fuD6{I z{p5?;X8~y16Hq>2)-R2yo4Br8if3db0EKq={Usf80Tx1<4Hsp8U7ZJj%RYRjCQ>pd zm_XOBI~sgY5QeZt2-9`NT?@T+pz&#=Z`+S|X+blYiFM8sVE~_@BG%Ks-iJSh0OA9T zh^g5-@eOUt^PnDvnSuoCxe%y328tx4inXhG3(0TnB_{(#`KsK6mbfU>UX_IS`^Z6L zmI$E|F0oen(F8=4E4A8FcMYxw(+E1PLdK)ezx$mMT*=-Go`5wl8rnz*GE6wVf5=+$ zD04t0NRA&Cv~YDN(griYx71D$ENJmqNM#C@<4O{$0agON?cq-HjtIm=Aelv?_%ln? z-yFEDh8sRn&$!%LHFi@Nj2YKeENPPzhhOn19mI&?sVEk0bb#Rt2ENr zMnr%h_8!T6S-hyh^D5jG{$PFl8!3KlL8(xOuVdn}i08rJ8(FI^Z zDk5nJFN}-MYNeS-2PfeX&{n->dwu<_w>R8Ki|zylN03lupnA+CV4OYxnrg zY}99=IHIR2QSX*~P0h#|GBD`LV&12f1MLQ3o$z}q^4xvO2-K83r3804w;2f_8U`X4 zIs-p+powu^#Sji=+l1OO7JPd++@iCRP7olQsBtM`QDeO9Xs^C_@zb`=alp~f1x4<2 zc`LHre;XxH8l)R`i){_t4X2=r@o2Q5D@ScoWF#f{`V>)v?zgLbq*2H29@S&PwZ{q? z(gqz%^v7o%zMa&1-Tf17f~*^{RV6Q=W(X(NYh-k8*h1M!&EpPFB zoW;(9KoRbd(QkkI|oHz{icyo*%0 zL5s_SA3;xoq{%{AQ_c?UQyxf(WS@`Lc02oylNIos_6~muJL0D$54u5fll8bDByV|e z{RIglHsf|>KCRrwHNAmM)BotD1zZ3$hRvQpMOrq@K6$0zKFa217H zBplJ|4u!IhbjU+2EocJAB#pm3@_Nmfi!e9?Ne7IbykBA7LBktoUN9YY(Rrc&3D<5+ z_bDs6B?G0aocF${h8!=ki6Z(o9T7fnr2ICjC;v?Hp@<)dw{6pcx@CSo13mNUWL+>P!au5AqfI)BArPN9er6Hx^NxFA3Cf=x;Ke{d@Q*&Ed~9=>()PxT;qW^psp__ zfjcPp0YCuBkfZ4!SOlO?Po>ZHsY*=A@nGB^Jo{Ti{2NdQ&?G7_AT;GsguFjbV~E!o zj{rTrC?r&DDl$ODQX&Jf=B?5}1ayTzxh!~M^y`T!E&Vml1>%5#n{|h+dfx3yL#690 zW%?-jBZ2@7>=;AJzwSdNM_K^@FSrp|XbMm*$u~iSej#T);xS;Va`!|OWF`Pv2BdVD zz0YE)QzB=%0=o3$R!R`Dv`@mgO~>&*GZ8fw-|19ChOQ0FT?wsFZ-bqC-Z zI2?aOd~8YvMy46iv-|JE zFA?duCHSQvH;W+o$P(K69Z3BM?kf}vHj4#74Qte<_}qsdyZ{H?G-k(yfC1wkPrz|xL_n_!BlR*U3Bi)FLkjkOmlx{J`iEzBXtc&+EoE06vt#B%hGQdl_ktYk+2F=rXAV1YA4 zkR=ucZ$-VA#tmdzc$IiEmYqI%+X%i7nBLi-x|_AdwR3nU`=ZQC`0j~$bm;5H7#4eX$0k%K-Np zVVuFc+LvM<)ha&QRe%V%3SL*a*KzrWRL#9sXjiLDwtIgt26&-hcePD)YYeJR%In5* zuq0*Q7^@K^)#&BhOOp9#ydRclSmjVK%bK*bGq>Fzl`a>RR@7C8GjGP5inn9R37Nw8 zbqKsoKZyPy?eDK~+;k;wuJuwYBV#BH;jIkyuD;k}H9*14Q2``Du)~6Udf&pt-dbU) zvimk=95~Y2zl=FnF|4#`Xjsj&Fe>6>1ey5k2iJ>IRw?|?mN|Z@agU?!@>xB_Y|Vme z9nWvJW)xiNqAq^G?o$E9p8|4QQv|R@YeLHlYp&;Otbtd2yf5`hgprNO1t#OGq*HEg z^t+N+2lNw3Y9|PGMZYE*ladh3HGO^CuA*VGw?R*;?v-I3+LzS~1+y?kn2E!c{xsHP zA4jSM9L6S;MZht!2N)(ny%+-)IqA8{XLoENo zf4WeN?8n*iH5D0_ylehg&h(`}_Tz>SBn*H+gNYlsnjaYo61l=pT}W&Si2v*-5hj7N z@#~*GlJu_&B=T{~#w<@)^Gz-F*3#Jqm)MpmSx^`n%4CWFo01)C2kriTHdshKEQdJ9 zW9!Q#=Ou`5+NA5*ZDeFX@85>btfm9f_FBlcN$Qb^JQP%H30#SVJJ(=nn5hysAZfRNk{SJ`7<+2ANCn05pzl!bkPq{7mKbK9_tw%*d7+l89e4^N@0SK z==i3fNA7D3?GDxMlZ{*r4lTzSY|DO)Txx;|1^pcyy}Cb$Bg0N>Sg2GE9K;RWxEl6% z^|_IQctQ`STEf=x+siYLQ88i(rLmBzZ|o7Q!a0Zn?wFh8DF~e7x5Joke7Rloabutz zmU0rXpish^*mr1Dp_o7w@Xi;00(>Z-*h7 z%D{Amo6yU!qTzu^1pfNYON`x)`VUWmNrB;Sq6b5Q!I{5)458kSC`nKCs8_#_iaEHI z1QMbc*F~sq5=iaC#Zk~31wftjY`yU;9#U@1ooy1By#dTNU(I4z<{IW_YX#F$$d@ge?+~C_CJ(oJq^ic;{h5gbomj}JB^m3|9H}RVmVfQ6e%(;YBhD(^1V^_{0cdbS z?ys7;$v4vGM8?x&vc1dn)H;&yvgg;IC#`AV7M30Ga-pJTwIGFqG`X{;qru2`9)aof z-AQ4yeiRF}!`A!ofHjeZ)ra3#V;{YUZyWzmL$O~#YC}5tighCG`j_GE4X)V%A%h7FXB_Bd0cGj~-)(cHga}pz-eAIHSzk4aHiWly^XWhn23_S^(^$&k{u`&@X zwVd%&n`jb_Bx#*CtJ5xB=fnZR>xpr*RLfV(w5suG$0Pw&$Mi6OL7TYEW;7f3|+K z8@c=Y-NOS)xFdnqKK-5}*~tsYVw8QG>&gR z@w_6j)5fWvgza?Dz~NvoWJBi9*4OJF3phNaj0EU#mRKD@?f-<78?^~KqG$z7EG2~4 zl@eH(ULMm6bEqV7-c6<{3&-YxSj({Y#4zk?DWW#I^>($$*c@s9>*M{=POU=4cvi(M zy-nTsnz<2VlE*xqAyDy0($UoRidlwiUMCki_EXuD`(y@>1@rX!k?+P|i&71ATwcmx=vdp_jb6!&?YJa(| z;5>VJ=BgYf8+L@PS1ly_g@3jNHy^^difiOZ1(IvZE&+RNDMjoBx)c%klS1H=!T^f( zwUIVfw3|+3mo4v(2#-9YbC;0vx`WZn&aX^TL(wYP_1Tqm$t?xz=}~c&#A@NJ zxu;x8QnSPtECWH=N zi?`n=P^N@6&(&$mA6+pqqFFuhl-TlqR)(rn(G9Wlyk|aW^bM(>I3n#f|{v)wyGRl z8~3dVv`?u2++$!9^_@m+fia}ibE?mhaXbyaQ_f1lVFF{77?Tb zWZMwFDf_X{)_QW=>aE{ zZ6h-6CFHa0315p&JhzvAW>oXcW?rtg>eJTGH)A={QVrcLxkE(am{9bMm*!!4Cj80b z6*HRV(^hcPr?xrzkeM##2r84tV%7}u2bU-DnY=kMbzzY>}ZP8P#UrtfUl9DjbTZi3c3&6$zexq5r>%>J!ZM~Xp|q{ zxT{p#$wWv1D`QuS33@Y==yZq-$qF-NJ+^HJV)ZL|+z3tWrj)rIkT4&Z9I_NYQL*%v zgvBM~sWfqz80)_5E_oN>ibOZc4@d|&E@E26M*~>AldJ(I1dTC_`ZXY++||gF6| zq8I^fd0-BWju=`Np>5KBr$_yYZq^!ilSI|+VX?`nFfn0*Y$8Y8aa^LJGg-N609mbJFFZ@d=b`N4$jtl6vwF!WQr9_>%C9)wz@2H8Q z(!IhFc14z#CJZr?Xrqr}NdIS?>zw+DA*y16L54(ba>TE-&1-N$J2xzGL~89pSn`qa z*&hG^wG-K40MV)-KO7`@aL7Z;EjcOPmOYzjc>2lh;CBs2cI~uNWdlp|POsdjU@1#p zuAIYhiz-R6f#lfg4~loL6K0d94kK%xSe1(v@u9&~a%6f{(KH2|RUK-dmAhFc-BP4X zYNEx9l{L3KILl39?kGfS45=C}+%)?0bSS4sll#?)l-`jftTkeIXBw2#Ku}$UaV%0N z>PS(|CPdO_)~*J-a+w92{?NXfcaHE3U+xFhwgs|$aOW{XMFinprLAbv4NCYjR=jnw z)!FB$!i@25awnyoQ?pWB7t7cR*KrRyn3q}4=Hd5*BGfBWc_Tno#HZEX1LO)19SrV-q@vE^5Ukt^;u!TWJ}bvgSQA@w7Kc> z8*z(dPmfY>xyz3`NQrx=XFHgDMBPza&3m)n=M!-+j-75p=9y%m=16wrk)N$#tV9(1 zEkeC!jl>k$ndW?&qX;2KyQdXdLys7ab4bYNHLJy2oj-<}`^$+pXJ&m*7Q6AzPxA3uR&f?tWVA=Tycw>j|#BYl}5w_=N z_~wudz6t-lSDbzAQI~yttMB2L&fku1Eqc$$gn0(OytqF3RARp=!sa`D@*%5*+I!U@ z(q~5YGX0b>e3H81^^3iL(yYDt1JV0`7r}6!PvQ^wNp6R+yYV>^TC{FyOdq8&;(WgO zavbX69!x>2FRBQUWD`5`POWig#fH9XaeKa-o{6~B@4gRDJgZxlJ|CJS{5T(}w`u+4 z6u3OMw{Whp*}6^Ttgx8=?rz2n5c<$+Y4e`~gL!RznQdmq2<$6}~B%85nFNxD#jDFTT4=s)&p2!;R!sPB*%4(_0^WG%oe*+67=8~WkM0vni zhNxIQ6zW11mQxgD^kk|{<%L{2gE!EW+LUzDU8?mrDLqhJWZi}iQ93P{hk6RU$0V{X z3VkH3FE9d+XhaOiIDbWlyy^ zh$uon_3Oh=>)in&RtR%|3{?3-l!#9P9%;(~k7+Bcj=;IT}<+ z*Xu0pg4t9ky;n$zPYz)Z8|9r0W+SvYsIIg83 z^wWmfYlla0bEHoP2R0H&HUdQ2W3*Odbe>~3!pG=Sb!b}wn%ps_?lET1F-A=tmXk3y zfBdn*H+B|Xc1~S3#~=YxFpH?}O{+=`30(%qZ`|*6>2tsFrs^=9MW(&V3`d8`(1%E5 zM7VAQh3khZaEIc=v?IJS2EK1RDn1J_-yq5?$KJDl2&oCahYI&t3Z}TiBCKF-b4;oQ zp>m?*^8W!TD_V^!dEz1Eah23@)pz4+pT^a@$2ETF5!Qiau;Z#Hq46;}=-*7`#ToYLt0;u)jf!C%ySO4o{y zN4{BEO>pBaWzKK5R!`@(N!i{_FbQ;-xd3)gf*eks-u^V^;;19=>)Wqjm_3Rp3PWUA z@Pzpbq3`$;sc>v$P{ecK(K2BWGxwu2j)4(E?JWhhL<~(bfpF3kk!uY9=!1rfl_1ZJ zut14F(f7L}-U68iQ?ABB=quK>ry)A1+Z4e6NPccPZGrH3`Js&pS2s<5jLc z0_vv%wLv}yxCcFhpvEe}p9oR8EK?On8m4~t5^Q7b45!j}y54;x!XJ^l*MvVkFL+*B z;EIWK*N?bIKlIu^;q_&I*%f0d;nbE!S}jW#L6H)q=y`%Zz&IXvZJ{3oQssa3y;uTN z=^)e*Pv2?v{KE24+IAGjt7ebiQF0=X`0nT3R^70sIo^JwVnmP$cSQfmT<#o68L1rZ zv*vK!C)m4UsW=IQX0g%YRi9X@@hl;kGB@PTknt-^liJjWt5-v5@q;#lTI1a?+R#D^ z*LiVfA+4^t&68LYgCBF+(1>$)Q_ZTO_ELp zjXx~+rea3@HAV_)jN`PUjZ$P1f`T61@4x!A5bM&WU* z<*F!65{M_6*^(6;H%tjA#UL7==+7;MfQ`NmKCk1Pe@wHyHzgeEZyJXlfm<*CXjx*4 zo>VS1qp*$#=Zz9RoVyt@JvkeiNp2o1fqJFCIPvR6h>IC>uvzhbi1|K|pMg1UuGws= zf7!FrbT!31oV#PO3ML+GLb7W%thay@UHlppluX!rPssut@FKm{B4=(n(smA44|`S& z<=U8+3z&Tnuq=HY`?^IL1(A_8S&_0;Q^ z_M=}<0)9PzZ>5v)%YgM4SwY7uvHEDU9!7XLmz|FnEHNe(8q@0L+-qV2>B}HtUzqZmTjhn?Aey>+P3Y;#%=$w-U326 zge(XG%wB7U2&bnsTYdK8x%LPY00nMY?cA2^ z-3IT(7Vq&6>+;U(E9f0CP-@}U?1k_*8h+$Amdd8^17*kuZ0H1Ft$}2A6M(+jJ>IQf4$EIwuRsxYB10`s0wSI4fU@Q%uZ(&wE<;IA1fQ2+* z2n%3UzyR>0kkGj^aPIu+W9;sxQ1A#}>baIR62cdPNeuxOg zVH^N(9LSLz$^ih&!5q!u9D#6!ZkU4^ID@S%9a%XepehtwEruXS^MqUT6m0Xuesep2 za6E_gsIK!_uXUz2>jWx-KG*OfSBMPQD1$!kLQmeN@CQW~2o76G9;s0w4cS@PBlV8C~AzqC~!<{4)Sb3b>kmi3cw>UQVxb?@!pcItVrXN7Kq?#nIGlrWnL|31 z1t>`+2YHJn_XK}+l}GoKH+!XK`5aGo^$xYCmU$B%h?u75eE)2OWD01oc#Ci)SVH(& zs-;`XrCsW!pMiyczyX0cgMY~OWWxGo8VEssCPcC1uowFdcH*!w`Lw5Mv`_oBxA9vy z0t?6RnD6yJ2Y>-^>nH~C7C!W!KqqzLqjq|yc$%kyuqXd~(kFf@g?$(Z3-||;C8&%a zh!OPwu0NC~z{DAW(OBC z1mNMHhlUa-Qmkn4BF2mw4+`*A%*)1*B1e)eY4Rk>lqy%UY)SHA#Do1#Ff`H6zi(INYJu$x|-vi$RBO zExxs@@#IvID{sD(InyO}2#sM%)~w3962H(hmLa(I;1$E`#VdYrVK@KQvzKuYjx=`b zo~c==BA2^!vPvv;gAE@zidQPLM6l$ z;z0x=`PweUEV3k&QA#=GOB2c>i$AtpDGUEBp_tIyhrmHNB8w%uSf+7jqIukjO>IF) z9$7SX-Hl=%#GQ9M;`rc?Zv~0kGMq59$udzYN#$FM6tfGWjXL@$k_3{1fo#6*`5>8V zDyOEVRdL$sRG$WM1s;TOAr+n3U8>_G=k;met2q6s*E%~eq=Pz!P6#PZBM?(e3%m+D zEU~B&Xu$;s#o$S4VE%?=rl7Kkm9*1VTimBg>_LbaMxbh=s&?Y}ot}0!7^_RO+6B)K z4E+F)u16M|5+=nsGB3XQ>KhV)&TIkz2n;^J8J-N#yLP!F0@dA7Y(@WL=ArQ znMQ~~$R0{0F7@KTO+rsF3q(FU){?ix_30AI8@)tc6a&lv)N8-Jkh=o#M?U>@20$o< z>dkzCedq2J?z!(y^qE``g2(?ASt)*!b|D-?&le144W9E@0=>5!;18o1g&!DWHtsQG z0l+AR6c{MM393X%DL4ZG4w42P$PQYyTi@TP1wy2WaD?nDVGy#Ahp=enekRe*@qUrL z<%Q^fD;Xe8Y~T%eT;m$>=td0|NWn^sj)F!!BEP&x8%v?@JnC~_`)v0 ziHE+bz0EzzsNE;if1cxqJ#xjUx0yGM7f>OAi@{lOUIW`0)x`;@I@~DdrBJ6`E z)Lj$8|#h6-qA)065xSgq$4Pi2oqU! z003J$r7ZXup(jc)kbeIgq{5){rb9q2i`bc(0;oWbdAPtwVw?>bQ)0%JtiyE+VZ%B$ zDZ$mWCX~*k;OAn)L=O_@k0-PyAW;ZH=8%dIU@%T1NrDy!u!RzQ`lW1wiIQQmgcjRS zg8&4e25rnjnG6g^r9I3>nBQ22NP`cu%#}&hAPM8M}oSNa5d#!o4`=9 zJm^7%2&oe`rNwJTCqjyC zC?*A8YRDS+@rfOnA|F1ONLO>K+pda~flYdnVuNcl@3o_I3%Nl%#Ofec3i77#b1oI> zz=YoguQ_hjNCDU~Rnp$oHK#2}Ua?`3TPR~8)Of{20;Ar)^p<;yVw7;>TPy;dLqH2r z1Ui)4Am+Xjx`gy^Ea@P>Jk-y+o+U{m=y8l-ahIsE`7TNF3J-IHqZV^(2su2lkWyr0 zUxekJuYmt0-x2eQK%lUPD-w|iSHJ@l`la1K%L-tF&KRM5SfN;)b6t$IV1JizuxY!S z8VHX>Cp+)}k{!?xIs9P=ahS$9O39FX2x1|e$nQmL5C;nYKxXabUcK%`;xQviNr0Hf zI@U1_K%^$1t0e0PFRLjzugQvIz@m;1ED}cgq7OiR4UzQ{=#c1SuXdvd2-+cuhEUnc zSf+>xp5c#v(7=?d`11B%)(bLo+H*>rjhkf}<2cv&tfdB(A!$US9b1Gu@@RsPQ8Vbd z%vvKxMzRN#ToG%8l_444aEB{G3udsu9hHs)H!!We5U8z}oql$NKKx?7!Fijf#_YA% zG|T^5=J}Q+8G+*_QR|;p(JhYiS7~5 z{-oaV0Ka)~1P-JyP1ds6UX#L6q);*R!QqI6I7VDe z1OQ|_Tz364cvCA8TbKhM=CDN&0T7LP9^?<+z{fTOYmsF*)*Uk-04{Q&Z0$urZB4*A z+-IZnksa*K22c3U(G>I&QOpil$a@f2EfH{c>>y3Y<Ef<=*L*IXuOawytBrS~H<$Dfd(+c`E_jAWT&{6EeDM;=;!^c|C-M0(u z8G=-Q${dLfgrM-#j}roY0yIli1w1q?S%Eqq@GOeHag;y?LXbgt)%UhW^w^FpMEJeX z_tDw`+8XV>1vrp`aZ!ooQ4bMip88c_N)SjmDBnUPLO4uY`iLGBnVwCFV72HJ{bUo0 ztR4UqKrhfkF909YB_O%Upt;c?x-H;Oc!D+fgEe?U3OH5yA<-KF16^655sv=^f!sq= z9oId0pc8>$E0N%HNnxj~RgP8Gs#%{z9M6I^L;)(24O(0nR>b(N1P+wKH|&EmXkg_9 z;SmjhCpAh4WJ0jCKqgGo5tLl`v8;NCC%WLLRD=_xu4rFv9^c!#?=EPaU7}r_ zVH!3=B5;7Gb>bY6)JHT*EBpgBM$k2uP6Vb4&(WXHnWL#WB#C?l3keS3v6>gqgJ@BN zBtDcpZV}W)7!KluKU9M!pg@_qArdiDG#0}@_(L@wBsLxiuHjk-FhDE@hd54QEh>$j z;h8#CBrg)4$4taV`cy|6;71l&NV>!Wo}@p{5rPNyL>-_=*j0agxVp4ivUJ}|;GEhQl&u>vl z2<*ao*x^)W<;)OBB9wzEER`vcgC>Z=I`rXK?xkIrWg+e)(G33>xBVns62)~@O*{aB zMHJ;*-6cm_rUKgI5&b3gFoIMeN(Zb5KO&~v5XdvI*+KxqGXOv$^wm#*-hM%0>1k%e zsF0~V2T%f_L=b@&36)){<_t<_4N~U~vZfKaX7m^qF(B5I2*7$!o^39c_t-;I-T=IO z#?CQc!5OEFeP&iH!M5C)a>8d%`64}J0x(9W>_LbmmSOa0XY>Rnm8^#`jVE~?$v30| zL!^Q?000`8!+N6TNML4w!RP(iA64|7TbhV{B3(NUgLjrDg`TE$is6ZpVPE2e=K5Zb~H>N015NCg3DD-J4 zQw$wL-Oh(HCjcyfFSuXLG6V+}Dg$Yn%|VGQ{KKI!s)s2N8`Q!y z2gj)I~oI+=4pve>9UGyF{XwRGQ_WhUd)ONdQ0uv}XXxEs2m&jMC{+JB48<-)25`(S zz~IK#Yh8J)YiJ`kdLyec5ClBX+eHZ{{6jLeEWTjiqS{*`2yD%2Y(_BbL+Wgb2y0f< z=>qVAJ051Aa_l^oD%*wGX&BG@d<=Z0Vbvkgc^WVp({BBT~YC`Y%1YZROfUZZZUK z`X+Ef$OLN-6kJbTF3AD>L%v0Di7EduM%chV+}0cXLth-kILIGEH~_Bgz(3po9bA9{ zTrn1Bu@-MJ7k9B2fAJN603DbC5|ptSpD`Mzu^O*28@DkMFoATru^i7a9j7rIGeI5a zF%q<^9-HwU_c0qsffaax7h!?}fH4?fKoui0BR8@mU$G)v@gq+%C1-IYS8^rGK-{K; zc}i<~=FRlZEhu$TKrRV*f`brCFcDh>0Vu=D0DvIi14CGYDoBK0?Uf|ZfiCYdFZZ%9 z|1vNKvoH@cF&DEjA2Tv1vobF;Gt&Vglu8&hvor^DBzTc8_`x)1vo>!tH+Qo)OTs3j z#DX^HgGOiqi!vywUF^P>o;E0n_wEJPA7F#t62?xL%&8Y#rKh^6*jfu%{_ zF@huV!qs#v48O34lr&DDshYBB$tD&+9xsHv!atM)P1p1)ON0Qpf;lv$2W0R; zIJoaLz%N^SEk=NCS`GhobL?I4CdXwp0VZJNE_4B>>h)8Xc2vK{t>&t4@+!XymtjdI zl4!#}sGVUurAh47de~R(t^+*i!VgY%@|LBf(qdfaAO7YdT|=Z4v>-iD0u=CK(e5?n z2C!cILAZ`90F{TmPjD`q4{DTIIw~L-fd4J$rPwIJB#at6LITpbrIN~sT0cg&* zvfj4~oA$Z-HA}!Of8Sf)hDZ*BSTPjCh(5@Au(pB!H>d%%;R-bguQyz7c4h;Z7knx` z?1B`;C5Drzh9m!PeJiAguS7UxZKZAPc5}CrgvfgEbc?q(dBgb4HaKxBhyL*&azl7l zNcjH5!zB2me2?~q+pBalZ))`I-v;jBF8KrnIE1W6lym8nx3z*>`8YaawnjCzh9rSe*aEoVz(j+4&PL_?08BTsw`s-na;MK_-M2 zm>)q>47x^AHjoeb^MrFsd~f(3xO^SzgRpbePWm|`IF-*Yp6g_C*f@=`Gm!Pf%!9zfKS-#p-+G;+x6*xy%ztvtgyNs0yZ68E893oHvB^}RJ*kYM}l8Ew`Zntm~e)o&=D|#j?2{|h`Caj zI#FVKx~sYXxjRC_J01P2gXF_MR2jav^tG#dNND?BL@2`UTUh)ENW`9V9z}1{G?v=g*-*xDd*d<>=8SlYY^Y`fLA^ zl%_YIREfY+fy$O&0d!pnmaA8?3s3Iwu-3ssTB`s=W2I0Lzj5V~_4xWW?%af$(i!Za zjuZn6thgaC_$HhOMeGie^K`IOHiZt>dN@h)Y-i6c3jixtrT!QDMLdlrac)b=CNj@{{){=|xLKEXo9rOXNU%zfK3^IY7HUN0+pnL>5h!b=a zB1OFLWaCc4vnna3k_itA55o;P>=3uuCaldY4-e99x)X024#gFD@@c3g>>&SS4Cz?> zA`^L}GKLZ>TtuLQp{l6T)n*%}9(>qbCM}07C`-!AH(L`Ro(6kwQeNND@tCaYYpk zoeoi*j2MHEJ(gIph(&ynik@E@X`)4=PWP0~*4` zmXcCkm7i8$1)zgzoI%eZNzfs{AO_$G1ORqy?MGEf0FaC_%R&Ow&uJ4Pz?WjYz)+fh zW~J8KZ{q|}LJ@-`6sAN`Tom2j)Wr!5rLI8nh(@BKXP#Xap{d>8JO%%WR1W{$FkrGw zZKwku5ca{ET6}2efNtOd>EMJHZrB5AqPYN}PR~#0#R3p03}I z2A(i$3Ab*k;EJrI1r>uviGzkSY_W$2vg*4yn;KGx8&)0ed1Z$lYGFr(gwO2MqaCELDY7z}Sqxfb9DL4M=8UuIbK}AAWHA2-4r$m~=NUEVg6yC_ zyuoK1IVQ54at;OP1zQPU`A41Y$uFNH?PtSWPR%_(%JueBtokM;$apkT;7mu|m`R|} z>3yMK*Ad&jW`M3KU`KFgzLua*f!T2c%_Ibmf8?iu6|^8i80Z@H#fg3J3(EgII1|vl z3lH()*Xg7(j7ex}Cm;k$06B6%*2r)*G}K4}FW8X`=5RGFSX>CQlY;QA52#g3ujt$S{GlCwQXeAE%n;LaKRBjHr=~uX)2iprucN_Uv%! zyXN|`+0FR1QlT|z*A@tI2&N3h3%rP$Re-ZgoVfEM^Yj;}00z>t6!V_>94JLHxr^5b z;2r-+!%1P<8j}+2pd3tSL-obZZmO#|#~F$gFoFN0d1Rssiqh%pv=UD_c@%3RrKvq( zI@6dgBm~4LMhjd6hw#8^s$K1jRKKD`Jl+(iGSR5#76l_286hZyM4d0DcA~S|grgQ= zYV4eXblR&Gd#u4_9LpjT}_u*R#xiPp;aRxIhC^u zsh|^!>GCW9llrMUhIF|CGi^yoI!)VlH3PyZh6`8|K0VQvyXUhcZXC-Y$Tn26LsOB` zsHhV{9>ZRlU|pihOP%C?w7GYB?rcbFkm&zPbGlu8NX{#+nADx zyxo+8y=jyy+#!%V`9i&Z@dfi9Hz=T`NPfF`UjmBQBl}Hef2Zn&V)#N>r2z#r4;CsG-n=|P$&E_Z5{f`^V6OIai~K% zYJrAkG@ki`hFHyNWm^Q%6H>G`Y0V-e_#sAPU~5gNU{QJm!_s|Zv`*se5D+u6*p6&> zMUV~3Y3s8>HG`zGA{K2z&s&nP7O$)$dv5qK0hV^SA59v;UU^WWxWE?pMl)U7P0#M# zWI1+}qw4BtA7OFA{)#EWg8_Z7n%@(twuG*|%51ObT}!En6egWvl|LLS5szWTfr)cr z>YSJu*R#f1-M#OD0SRWd(Rh)%`xj1>dE<|j5yT!mbWS918(|m7Qs<=z=BVTFo}53!x)Unyzu#j zdSAL;$%Rj%&&kevLZ>uaC4ucfWUG5F%l`HLzA?bbt9ceBWhp(0!lZri-r%n&@C;e^ z^jY7Uiz8m24iJR%XG4FSim1UrN2vcu{0sP3-f3Pz_0l5hEp zq1-YM0^3RYJ~032j0o+_2=UCXV35mZCIA`7Bh(-~bif67ub>W%0jx+fCCl613L-?B~ApD&;55L23acG7af1e% z$OeZZDI|&!*sBN0u-3@X3=;wk?FtgRjtx_b5@iek1F#sTU?WoHA5_f~6A%~qY7fQi z5KS>CB#;t>>=*yKAQ?026%}z79nsimG4*Uw%82p6gf0Nl?jnTfAD}@PKT!{_Q6osP z(SXo%M28USK-@AxQ=oC3))A>ZE(DkA9EUI)GY%AyE|UU~7zWTH5MUkNi0#PHz!dNx zL~%CK(cJ2BXz1rrZb=>{A;OSR8t-up^RXJ;%_HGW68mo(4~zn=D*yxRA_5^i^dcc+ zY#}4j7-J3i(k~*{C7cSOIeIXsY_bM5GVF*1BrT2>VULnv5|k<=0D)m68A1ob1AAQZ zB}o#xun^_6Fzb5KP#~%haKssVD=XEJ{-!asgfi#Ka_7#n=SEPvrqaNCXcxbrB6c7= zIw2~D(I5Ypt}2`EDrXKXQABC#g%|qgD>KqBd1)*^Odl7~`touu`Kv7rOt1oQ7c!9{ z=2FY-@-EFWEnDIt9nLV5Lv)~q9xwp|39}D_4Jb!NF{zOse-1B^t_yat7@)u*R6tqY zA#yTPAtAHG^l}FI^66SJC|(I_EOL*A^H6@0@H&z)#jXv>kpNH-g1qcB`k@nd^T3X> zAz#BYFD*HBq6q4My^g^LcMCO_bJ&`5J)iRyVe=n%v6&X)0?r{kY9KqM@;yI;J6*#& z(F#0s!Vq{cu81V6R2H=#@>|BWUe z(1ZUV0Y`?x&9(_ajSNL;0u~WM7Rk~%Ny#x!j6=ICDF@=z5Mmj^0}eDaKR1)X3KM=N zf$ydul~i?*5HaPniBcp<5JE>zjV99|9v~LN133PPos_5yitPwAr3tCQ!gh}`*Tzwa%heK6Q*M7j%HQ0tx^B+ z5l$nuS!1*!UTn({;t#sv9<%`}&8Je6sR@gr9>N29deu*VRPKTlU78>hq=FX&36Ydl zIa`%Y)r~b@^ii!zM$;f1vVmF+Vh#A=6L!E92uFdq)tIWP81&&E^x+4_)mOm_SX;wC z-wZsPK)B|i5X9ie-1S@&Q9-fMUYW~56M_T20S>GLAynodsKI5nRZ0yE84|W02%=%h zwM#wp{6KUI4W(l3r4S5`a~3rkpdY11S@ z?3PW+r(h{b1q|{Z;NVgN5W4_(wgi`6b3<4^b43uh5C{R+g!XKc!&MCeR_AqcKejy= zqE=YNRk+F^oW&rbwq^6S%hbRh!XpO&U;!pn1ydKWR+o3t(RII5OnLTV*NRaYx3e5q zNgEVo0d)i?24N~DAyU>LS_W^0(T!Tgc@4r_g#n1BmwKlb)Vg*xzIMZo^a#{d9sr39 z4$f@RGko84eA~7$Eh22j#%};ea0V86@lXLa@gK|~LPj7C*XVxnH+lcPW`9+qf00!4 ziojUs!4kv?3)0kfPmgH#k$mlIa*<7Uc*h{9$9lB&bMqIb2ml?zBNv7@uy(N*TFisB z5rj``aI>&*`*J!CHH8TQ4^q{8U09LQ*8W&GR%IA0CN+*gmxnq)JR)x)pkOw;0EykR zTrcm6kAh6;L4_4JIp%S3#S(@Wvx}XKhH3RNl~}PHfN%c+97a$8t|b8fR*heijepOL zg#wN(!8m9ad>uIm@whehnA7+eN|UXJ?`aM4Av`F^AplYU6?u_uc8e#1gm;YQ8bQb` zq1!mCg%9|SA2(z(`LsA$-aI*(9zaLKgI6gc0;2bnAJikHmf0XcfgR{z2$CTj5VHK3*eab^I1Td)*lQOo%lKHelA8i|!$OtScAU!>I-^Yi zs6jjwAtT;W4&`}HO9Gz_LIBR8j6L8Uj0Nr_x*@E&p_{@Bn!^{uiHfh;q3!XOoy&S- z*mwIe+5jy)tN~>-!V+7nGC!J^&lvzj8USeEAIjh$q=8>0m6|`JrI!^fso<7=At~k< zUTylbvbY0RTC8uN&leB!LdNySu&nyTLoW#e2NTyS&Z& zywN+o)!Pp$){P06;)t9p>N%{yCthdZ72Rpu-figp3j#rEI~rmVG3w&v2|8y{s|$tdH5i zhCn=GK{3Fhql+Of;T(+^%Xl7ycbfSe?!g&wV449PI0c(L7my5*|4gumCD(KgJR zl%i)?WaqiNXuul6;~S*8GbFPZD6`YcsCxf_RMC|KYJLHtx?0x1yu%nh79E}1AzjSN zJc((G0n|+b}mHj4~Ahf?gl3(}SZ+F^TwA$nS+HakK`D9uFpafjO z8|;A`TtPO{;2D~y8J-#d+#ngw0UofStpUJVv2};>Nyy3PZ^9!SR$~ATnL5WkhswQ; z-JK?iKwZnT+rACUKOT#1or}p_ob6ps@^xPUzz1?+4r<^Hz9AP3f&`e6?G^ zK{5Z(;2-$(2mZkZ6k-`Uc zom)dfMT5z+zJj)%56d3Lof)#Fc1UN z5keYNfq0+xcoCw);iRihfvs^P1Z1;*7hmfGpPo|vOIMv#YoZI9gBK1xQOVxHz}Zn( z9&&YkLgZF+?_-qrqd)#bApij%TC#2d;BFJbK^`QzD~JumgBHMFBLqN=6hHTQxcoPw z%Dwi=C)V`RecbdwDPlc)qaDdoes^)5$(o-#03rsuApihGV^y%Ahic0d6tqx{RvIyL!n!sS;tSf~r>q6E2)|uvNquQLhnTcK|?#Y0e%b zl!T5zK?d*wC2aFf6Gn2L5|+yL@~KM5vcwmmGUj9d=@L zZZZ@EhcxW0^Nbn=%@XQA(IoVTH~4HL2TXnLiI@P--~^8jOo9kZ2DlDOY_S;KYTTc0 z3L5En))m1EJ;VPfy2ldD(lzO|kNWsxrHO5NVUiw-i&&?|@`miWM=3BzZlj3CWSzx0 zqHewRdYCS8$}-8Uw$oXMojiLGVh0xf%9ZWG2y=TLU_>%Wu7wd_W$wL&n74?c1VO3jZtPA~o_t2p(6gycfeX&y{dr-Xb;edp)!FGgB3l%x8r} z%Vfbaxy6C2y!0Lob<{+e%p1xk_IvZfNKA3)FNNfhMb={FEVfr<=e6^?;7YtUeL*iZ zwA51@E%!=s_=8h7I}HnR-G2XlEZxUhT_VuI&FlLX!zq_omB}v@-)tc?6cdfyV<-`>aeAN zvOT=pZAaDl>TC*LH%d5B1A@AJD^GpKtt-jg@$bdnyIGOEoa2t&oArD5lh0LoQJWLD z{&4LVm3;LhU2pLTtK{Z~y{FGBfB)*zU#{#Gk3QV%T@->LtwM~!2;<|*`Lg!FvZRkF z@8eAcYjeS##Ls{IVcyXMz=_;+B4g9zpb7H?z{0#PP%3MnSJrZjLXe?RE{q_}Y&ez) z4kd$-;UQyuIFk+fFNMZpK{#--k1=Izf2lj66HP=!a4v42r)+9-0P3kHy^gioxah1w{zDe|j|4eY`(=<$n!b1YI+^`}uPy^P8Y6;BYcrq!Vw2&yv7O+C_;fq#WrM8^u zl~&H=mERg5&}0d>f6$VX!z@t@5`hzL%s_6L45m5J(xm9CfKiF{%b(S~!^=&Jgpkkpp!qyNm(}t7z-#K7ra#uxieqoC9br zoyydr_~uS&ZRMhFq0gUn%F+kN$M9RWmC$)9KdYB=whx zZS4FIdorlPj;=S$!Y|lDh4B1UY+5DMX63@s_K=l*qjg_t;b+)Q!qu@dS*s>l3)|Jo zM6T>P=E1U1h%7e3cYAGMXJN$C^!W5dLZ#qoU%JheY$6-(a0fMNH4;UH>K^~BgDh-m z^An|B*RisV32mQaTWwvz4u9Om?s_}E-@Yig4O9OX#HevfwI z5(9w1N?vM`S(4)8tawmMaPgsfAwJ$p7`^73uwMdexgGyd%!twOKXzae4>({YKX?Z} z*a2OPtRWF)XoE7^F<%^&?6aiaSHvSC5Rzr@u0^f5a;Nf zLRw*x7VL#7?Yc9kdCe|y1}t8Ji`@{7)gq>&s?Ta_>@|mq3qF_h;QByCJXV7;ihFcYSCQ~RJ1_`KR|^)-~a$xprRn7hyxAIU<-SInq>Dbu(Rv^#F7KR z)x?4Iclu3;Jbb|z^q@q|a-CI!KU3$?47YI|ZozUdQs^j7?MVM(Ar5?`!xS9G0@@rc-ovhpn1PLO$uNqMp)j7 zDrfm{T&|bD6XFnCIKpK!p|!L(bMZk4?Mre@MxwVj?hrpA-39!G5Vd{tk*qw$z7Em8 z|ELInCw&mGbBxRyp7k1K{#MtH7uUl__7<*m46dFu{B=7QubI$2(cTpR4d; zMEudm#gDeene#mh{jwok+}9s-{mV>!L1&-y+Yi4>au5Fu5a53$)qi=kckI+G>E}2> zunU01ZOa#bob`Ud#d^{gYWe4O))!f|XF|6pU<=?2-#36oRe;%afH8G`Lv4Zz>D42j3 zhX)=~C@D6$dkF_@nv#RwwSTr(f<{;n5daLu;00g^I7oPcQI&$!k$%R<6_h{^#vlbz zNP~zMfe>Vcvxg~LXl^@*Zyd-$9#~+GPz<|JAZ7?+U-(aHI9Y4h7oz8eLGVuW5MwcT zhZI(aQ<#U-h9q22o|q+9Ra5oR7f4v$TGSpM!e`s zzUX+ss6t)Xfy4-gBT$M*kc?NSB1s5dOE?$M*cDXpN4GYOxLA$!c#S+_fh+-gy~vD> zwZKE%1>evy9X>9xxY)ToEuZ*drCWb1-==^Y@Dysf8QpgC#i>mrx9qpp$y$k;9RY zys?mD2a8<6el~ZHGiHx3iI3ViP27ls-uVA}97%vd`I9Ws1VAwYS!pjP$#>r&Yk~I_ zvIvp&D3gkpmXSh}-Ds2J@{iych~kKdn9!46SubFTfYULScn~&UfgSN6aA>J|e6^OX z2bK9GmHbGRQe>4Rh?RJW5mf*bj3t@4qL(Phmx$( zk9vqbj~S43X@&xTI+s~2nW=_-QDua12Y=}mP=G+a@PJFHc7+KZr#TX-8I`NaiLIHF zvMdEg+I4S)?U$q`@Z_S%4#41QtiofX6VHQ;MT;+ATZ!dI6f8S(;5; z>N)AjXFTbXV@e`rYJO#bri4HS))E$&U_1Irffx#ZRLXX&370*}gBuy7fSM4LDGVWl zsVL&5*k_$AN)}s?2ZS&NhIij745wa^uI=nDfNtJ{Ni51C-2tZJ^l zC7zY~qwFf8hee_(`Ur(Muk^~RLFB7a7Ez){2)QE`lTcLvtCp=Qe+7$$ZyBqU`iGaQ ztK?V=LGZA}QLn$cU@Cc(fSE-c+pz;1p354d%__3rsHbNbv1aI}D@z=1pbx> zG20bQps4gPt}*Gc5{Un^KB}__`-vv2t3|+-LMt3ZOK2^0Xfd;$ULgggWT6)6r~*5j z;Fhj#X|*Fus|qW$ztKco%NSn!YATbRof#Hia47LmiBM~^{fVxyN<7Z`Pd)oLe5z{D zX}7e2w=Jg?^QoO-aRif4Bg5d56dAR6IJE{_wdC2Za=WtYNrsPGGC#|Op$c|ODxqQF z1!l_&-pRRx`)HpVvTu91Kf6JUJ3~Kpa?tw3+u2qP&To}p}vO7zEm&?G#7`B z@Vva%loA=eUzWd&xxd$Ry(^c!9ci~u02Gh#2#a8?1e_F3RSm9C5CmWjpm4sj3KK6- zs$>9RK_CTS~|i7N*ti@4+v2LuHX&!Kn|{OOKI>7 zr_u~%kPt&44fjwEHViA>a1YuLXDz|Fr$zx%un1#_2`cOYF8sm=$^iV(2MIw7$#BCX z%o8wB2!&7wkuV9E@C#LyMZYi!5oyF5T#FsNi%Wc`O&nDH%Oq(K4%vVZK9CD@Py=u9 z4Y^Pd9H9RWvXBEkkPGMF5FT(2wa^2B01v7G0BgVxpRfa_pe7Wuy(#JfD$J9>pu*s1 z$46mQD)0|$kPxa+4I@z!Cb0wma07I30SaKv*Nn~Ctj*iZ&E3q+LIA&6B+m2@44AM8 zQGm|rtj_Dq&h6~Z@4U`tKnG?3&-HB2_YBYSOwaht&;6Xw^X$*?Yz0=J0p4uT*?a-i ze9#Nc&<$3LfB*o12LBKP1@Qy_U;_ZK z3F{z70FVmZP!JE25Y#Xs%hSsYN&t(X!lif#D%_RDTolKg%*))&7y&1tA_;WB)J^Tw zPYwUoQ7zR|P1S~QS@UoV!vGAsa0!S&)n5(PVJ+5UP1a>?)@O~@X|2|4&DL%0)^82h za4iWMT^zLVZXb;invf0!(E;i}3JhQYtiTN;-Ny;>2LCW7tl=84;mm1<5;@JFPoToT z(F-apuR`qjz9sJo!R>>6EQr)HT=hJ;-LTv$oi|h){D3qhRG~ZU-y+?N0tz_ zjLW)wNk}0O1YvC5WmwbU-#7m6fCW9eQ(8b;1cV_V-3Umxv><|%$jH$t(jl#MNF&V% zX%M7Kx+J7ze}32R{@=&-;Qk!jvpw6f?bvy~KkpYDmH@{ehZB>KkZF@pftJB6%aVv? zTr7a4nl$I%tk*o4$C0cR+^aP@R5RO?Ta{``aClJdkagkkKyY6)U|IWwyS$6Oz>25j&lbSk_qSuE ziuGZg)x+*6lw^4qKJnCQz;UH(pg6(m9={K%dGVI?$qxUXd&8dN1?i(~cq|d%*6s|8 zLuqv!8T{c{(F`eTg->US#1(OhJLV;?bhn*wmwlc96-@A^5E|AzK9F1pgITuPfm+?O@ zBv7Z3dyh@cUl-puQ)_|8pInB-#aEl1e)g-%W@^rPbZs!-@~izgN((17=PErX_SI2O zjHc`B%DC{j^tun3-JMm$50vLz3|R?XKB-Or-GUs61}ssC`>kaOGg{T5fyrx4Tl zh3U5I=x=%7{oVe}``KHt`?iMptqSJyPV%3Z)NNnRKe>i~z}P=$%s;KsmIBE;h}qrB zhr7GfyS+HfrI_a4(f6B^*JsnjZ~zC(;zSd|0LG@^|1YGBPr)2*IKHM3Mn-0}FNguHENeC zq-rue|CpX&^#Y|=O*GX^f%sW&;WTn)bitxi>o8qmJ3mwYvd-{-peG1^tIzr2=KRki z^A2y@SwfT9W6Sp7BUZbG#>#t0`GH)D$(4ZZP#VT+X5rD8CA%V7 zMYXU|WN_$n2b;=p9-4emjdv0UPrYGQq((_JBSd(Fd#m7-^YKZYF8XPN{7ApF`z;w7 z(KdLhA+IWtJSKZ&k~}UC^%a>2qi60#Ht_b=@u@HFCQqt9C8U^ApSw=h!RR3+M8{u{ zxJ*xLKX@@fU2z1c+EHzMSrOrX)ej5y13rPR8f&y&_qBZEorQZxiFc9ot}qJG){uu0fc3EEK4Hp7N|5*X33g3 z6T}7;{Ziexk?V_jdbtYDeV#7zCa};GDdHd(CY;Q&1%xJc`n>||0$+V(kXYr6&1;34 zc>}08|KD;FNnG(6hhZnaomTKNb}k@eh(LN{VO}#z28v~BL!K0@lVepg-JSKzTA6?n{C z8au^=ca)HoV7$o`D_=BO#}jFmPCp#0hiF~2y-N4foLQ1M-=0nxUuHN~fm|3KO_z)p zXS}-nIw2-Ehv%Ch+*rVxE0SD^5j2KYOw>*!DBU@7lV~fTh)2yC9*_$p9k_ksl;u{*6DLb= z)7upJs*FZ9V$ouq6d|7Zl<7JXKP14cg!co8D4V)o2<8}MY+sEBbZFoAFo5|dkTJ^X z?Br`5vg>0ksHeWs5R63zqJTuPG*_3|?N~7%PLmWWR!2Y#4itQZ8~A3}iiO%xLELd5 z*rTU|Ftg5{o?<-qPH-v@F1mxzX`V=F#)tn^l7BpmjFMaPV9wx`CH0ih$u^oO=6L~A zHN^}3zxA`#EQNR>rB5ihmHl|)bFfyh7ILuxY6CoH0viZM92?-j7Ri*TFVlYNVD$5s zehgMFWm5^aS&VJ47uy*(Pwo&xPn+-?96|HeM3uP?^b}dN$@o{imqx@gPQD}*C_V0% zz9qq{7jPxSaHU}oZthXCzdV?U8^ai7ekF~kT-0G{cZj=bV?oZo(qOOlNZyUds7f%? zkMS?g=&}_A2tj7u8>T ze`XpwDEQrDq85;s0R6vh#m7XYW*5zW+nRe1{Tt>@4Yw2BtF|kQFf33&>K*e$p{rI| z%X}quW4pC(l{2^|>^-w~*Lc=pxef_KF$oTRa}S>N&lN*-#U{lXTGPlXFqQ?zR%W9~MS&5++9lkW;FBjPkcZ+V~8a-qqlA6WDHtt}!V|$;wY%-ea5SA*`)MY2Ew;ji5g%=oUyV8+bfxSzzi(!+#- zjm+&w!A4WA=T*cLf|1B*?;l?(rg7gMJ6T|wQ+O^Re6DpAzQ2Ua9NZP2*ma~xJEt+- z-nR-~<{>JhgL^Xs!i@$yBaqQppOjO$6rgVm%HTSnW^@>C(L&PeaK8mokt}MOF2EZ> zPWLa>>%PCF67cD%Zz+hFC^|GpqI?Q;SJpfd^DRk-}bb1q&PruG+=rdGG=yCDc8ns1v zS!H-kXl&v4@PZ?sW|9>!NR@MT+zBKuJH&RH`kZ4|4YmbU;V~5}Fl10GakZ0ZBhOCa z^zjOke7;7xq#iCx(fG}cw#U<5rm+wODvmk2d4^YZzGc4ot+mS!uN7uHQqqGh2hX4l zv2t;Ib2guAAWw4W?^8YfElX5u-oV>6dNa8WNoFG-q)9ec`c~^RO5#9rlSL?IyQj9A z`<;3nwry{R?qw4Px2RVd+jBj08TA>}1!JcnlRWXAnG4$H+5E3rwm`#d( z`|dMct<`V)jlBP-yE(SF(DwUj@N#PxQYd+qDVs~q0Z|?M(lrH(nP=>}{W)u`C;h5J)Ob*aDEBEtQ-!i{D>h1&CH zcZPMc;Axrk81eM#swp6~kT0Bj4U&@$4WXW6p>kNj*CuE&U8FI2uZf6)o}PmKTLnWL zKs-LI&L`|CIm*W5xt*H437dlbhJt8aaobMD_q1N4+deJ&-Z8rV=k%~X7Vs7v>RCsx zIjs18K`~%o@x!fRAb}E+UMYxIDOgG=L`^BwL@CT!DcoP_Kag^!Qe>G@RI5_-uu{x| zQtZA`+^tePfpP-9aw4yCl9cj&W$8zg0drj56o2Lafs{AkI;gKmC8SQ8a@K-!_P+Ax z66G8Ml|1^vEVe)`txwLE!APLqFEC6VQ7f|o@rQ@k>%t^VVsi&F)Nybes-R9CNRg_r zcZOj^Qz5R*J(&+w>P=L?@hWLEKcdwN@iWY)K|^1lk%%!GgS~L=4v@ljOK26KnJ&FM zF}NNX%#aIl3WSJ>2fy|PBjGq6$H6qm!TL_B!^3JnGKJdx1d%APuqxPv8l{_CYUBp# zUxS1JDn6O1>d81rSjY#Ilos`4w?M97{FWaJ>P!3Tt~+t>U?cC)Q1k@&rJ+iCGen0P zCV_?)VgobuqCan;zH@9%x*?tbK!CY~dc#Nj5YS};%@cafSK8R3HK4OPL?3#Gr+>`H_g3Crl~SnHr`mpgv_&tZ9VO zqW&>crs;tV+)imC1)wGmwTS;|!PP(Nir3JJ2W!B}oAto-K*$?(g7AteeIu(3Jxta+ zTu1<+I~>|5_%Uks7pVA zbPF`Ox1rI4I}6&^JKFc8vylnZ;W+q#x~{0{Po98z7PoayA0C?GNqw>dU6br_h%{p%Z8Q*NOAsw!ZG)A_n*Q1`}gne|2%L0-QL|^ zV{XoFZ*OmIZmw@{?ymn{Utj;by!v->fjK+F{N1@b*}S^FzP$N+FGt_A(dSq9aP;4^ zzc>G-qAyP`&(6>Oi$woDxx9Cx&yOyS|C}5j9UmPXZJ+MXAN{&GI6B`x`VSSovxC_k z!EBBmZ>`*e(VO>T^!n!d!TG%zeZI1JG`sR|q2zY5eBoeq?%?O_-p~1i$(8lx`&nJC z_<1lhy+1v@KQ+BKIk`76u{|-lu`;srV|Z(5WOb!yz31MTURYT8FEBkj`*UfgduC>4 zVWM+tac*pJbaJtLYI}yuZ*UXafLYtmKWK&^UU1338R$*IOLt8?{_prooA#DW( z1-bW=lbfBLU7T5XFGuGmeJ+X5D2UHbO-)TsPL7X@kBW*44-dabqJxpa_eiu++E=;I zdhdYX#{rG!@4PQvtnLgow+vo(dq$SMsh=>lEVeER@cR(#5q+;ndwO~W+lQy?7W`F` zyOR?8%g=ko_Fz*|dPYHWgZELYW`3&1{o`|(LcH7mNYhSEPWQ&NrKP2wwY`~{nTd(X zJut1St9wsNYieq$si`R|E6XdYC@3h%%F4>f$Vf^`N<5Yn6B82<5_dZ8OZSV(KuzJ$CjslhOy%059~t5vy9)zJ9Qf3T(Ocok+LG~n zr6eBH!Mf7PVy%3YtX~t<;vl_R$Hl?=uLc?TeP_9{-^%7{?I*vO4&5L8HMp%0W~nw* zEVg)`?k*1f$Ah>qWhK7G$;(2Zml$!t={tOVE%vG&`cVwjVJ5qq=)7sx8%>HZ>$9Lm4chj_hxII zmPguJ{vNF;Phd*s)|qHDq=Dsgq*)q`_Qs$Y`K zSwgkRe!Ru|crO-yRrs$By&6hwSF#$G_QK$q`t(&t81|DV0#*^6Yc{MAJVoAUp3!l@+O4;Cx*+-VC#|1U!kvu8rO2eH72(hpWJ!S zVp82ExaVPY1R^m$Z4HY7PO;xsGS&}mw`LRhua7!fXiwCN`fXwa0qTyf_OA^@2;46Z z&aO8AJu|=GvsaRwR4RKc^6xr%lF0Gbhl$rd7cG9v zl9%g$k1&dx^XMy+8iKhHR!;yeFEw!-<0~GFovNiM6^pFHU--;$hK6VpJ;Qs4en9ih zZD|juE8KNjQ74+^}Uu#fwoICRU)ty7|;Emk#&G>NC?J|p?PAd+@pBhfFuCUm?g0D!t(Hf2$NuJbS^l7)C+p?e^<+W z{{&MGnfL{~qIkSBv`)3GA{zf}Wtw1RFlUkHWP2yNI2iv2xcr{lch1T?8CJ zY-x!d|7mWdFxM7`T^lp&NgiCCl_Q~8nY&LeV+6Ycc2gC{DYBZc9tZ*ugIGXGQdTv+ z0gcA}zhPe4{IT36e9tRI>X9n;a_WA50MN1`O3IDU;d&NsB$}sU6Ud(zrpz-q5QSIp zz9Kk_>`pr@wC)XaRkWildB?ri4A6|n?>vQajK!Tzm37NIy%Z)5bc@cXkW&Au=!>T( zO7pSA`~9qG&hH|!A5-jTbQrN=E+opTE~5$?5T5D`XOF%IgankB_VaK#GlOD`*yXr; z#;~PVun7UKP>IhSI5>nGl{V$v>ZeVl^wHMz{HQ%6$!7*j7+E!CpC9F{@2M-=6Jhnd z?$5+_PvWq}&Z~?zcetk#;=H7=@uA$kk{i|0#yvuK6K?%a+ez?{RX{ezes%vk)oA9I zUObD^L)Ap~lm{oGc&spNA0 zZvI*#HSN>|SI4r;9NkI$2}79bN71?(lj&K(P=uy3lLX;FXN^u=j6;})t-dV&WFcER z3cc~OTyYfdWF&HbE`4i8ugL~#8QVd44_hKw63LQ`)aybU9KuS(0=JQnrs&ByBf1WJO> zBk%fZt8m}gWUl_28RJOIr4n*9Q@#4xLL^o_gufN%pGURsrXVX+{^~*TB}c&}^pCz< z^y^t`hW^WV#7H2aPu)7DH7Sg;!ac5nG=zAmQSmYBP5CRun-zWGOT{lgNQ;PE2Iq*j zYw8ydV%3=8Yt&HcKEl07v=OJZ7W8raJMgO#Bcx-HM8k`SpMqF~gcV21PDO8z<6G9X7U05gWut?1nw?oZ0)$wLBIx_QDZ z;2Sgczx!UPt`UvB@ImWx%rO%R3E};zB0h_ET~iGB9Uidz7=G{y{*aCC)Zl~oHu+!Z z`wvtA$#F1(I^@2jT>dgxMNggFQ$4FL5Diz!*HbBeD+J`KK&lD5puqRPfwPpJCWhYR zss6!$t6L$GL6L;%6`9vD@l912W{mhIo|ie0aB56(gH;S80EwjV%`cWHeCK;a^}**; za8L=EB(?ArC!FNiD6$b1J&TIPl%NK};4^Frb7y*QinW)?HP-bsw%9ZZMer8bfZZ`u zBYVy3V*R)+UE?ixTW`2|mH&DN7+Q^toAG=C!ZL`DGKeP}W`4^WPdL*7y1%O5i|2Le zXLaXPxcMIjFzBA{XTscafzDoj;W-GfC@(RpX<@oYcqg#SVVQ0Ug(I75nFY5 zu)m00pAIFt4DJ6*(&y!gEf7`CMe?eIZ09s;u>%JI!d4Q-GqeB~#S?om!`Zbw9xD<{ zKmpra;{0QrV))w;SPW$vc_`ZXsbL8HTmr&71eT{akRPG}2DHGsfWV6v_3&vef_`Q~ z5?TMRqMioNlc-K2Wieu5HjR;X_EAq0r1KxsNi)Nz;lvm5gt?;do0-=I$FG+IiLo2t zG(HJ>J8)fGpAS$nq^M!&bPUH;Ohmn5%()?s0X%bz=*SIM5Em(2>S(qdOY81l#T9jd zP9jT)$xcaHGn6&V@r89S0_+#Wp9}-+RG&mQ3y#o(dHp=8D(v~B= z`H4hsDM?`(X)(98@nuSna$2uLS}+_!Qw*;6i6cRN$|?QS@+1qG%Ah&P;3CN^NJ-ag zNIyoW(;|T&i~uY=KJACYr_1f6n+I7_bJ?`A>46T8L7X|=4w)BoDN9WxgPgD$<&3Sg z$nke<0Xx}LxH;k5PCxA;%U>oXMdUD8B7;}JG*rfzD}TZDw1&QHoaQ_-%iI94^TWKX znVH!B()5$YT(UfWcMI5h2R^=KMj0w2vnY?=C|}am$+YO#q<70tmS@5njo6s&_$Crdrg;i=@Sc>Nfm6r$?o?0m?lG)N3xq?;s0{f9l z0Wm0xMxxMJh2({b;8TzLwy@$RQlYoL#jRGw4|IieymL74vIBUmf{($x&AP963KZ}P z-_I09WAI2`OYm=6JxY`))ed}=>|2`TSbDwo7CD%E_3|^BASiAMOSZ2-J+g=>uPFC< ze$20;I39RyP;reTZ;jE{Z_mD>-+a#9Ep2ur(fFYk&Ai(t?vidsmBX#o^x}oZ&UA5unnlG1y zvKYtOr!yq_R1oYAFxsyA2(K=4vSxAc%cJ>hhMO#v`6|-CW$JXAK<{K6EnxlP{k~o6^X7X`tVAsMI4EhjC0xs%;(60bXH*G5zy7o26 z_6_6qwIR@gQ~Pd9`#xR!_I%p`-S`F+1`X}@2*yOV7Hck`Vn_cQ4V z5F$XdVFCI>*MY^`LBRW6I=5ApqIUQp>WRqv>2Rq}fy6ioghB>zQ6$ze{7#4e4*6O!<0%-5DqW7n8r zWSmKqcuGMCJ^&rYPfu$WX=zrNXhsfOfkL91(NPA7mT&k#qbektzPWv9uw!p9{hMVU zB^0}*px3A>V7Mpnc7SqD%_^K=*8*Y{NH~jd5uR@tq5YQob@;OrNu}XHrv#CmL_v#j zo??BEQs2;0c><9f|J#)q| zdcTShzZ!lrj70+MUyn3q)}KY!sjG=^WR7Zn9kUo3^M6QUB~c~q^a?Ahl}{CW_?YNo zjL-_fk!>>8WIK8pIr?E})bwVI-4ln|LMewf0I8lCxRv5WCD5bvRZ3a>2VT>dwJpgZeGErvn@WeZf&EeAG5#9 z#!hFkuvbTt{!RP1P=f_0u|aqTE93SDbAgawYz#m1vSxM5?6hRxC*zuIKap z3`Pv$$X3s$ubBT^9ZA_xJaqWowx+SP!Ns_Vqy>`I;ELt$u_haPbDLwAo1A8=yYvI{ z(w^>WaAO7{8rXod^tx+yup9rB8qsfS=|y&lRxrl$r&IPO&cCg5s%?<;wmZ>c&|x)> z8hl)8!%$;kwskYswNuP>Se)^92>(_T(Mn;=y-U1FA-VOwy(H(ZC$D{Q$A6c@Y$sG> z72ACW8wphW-i>Zwsn+-qpS_zHyH_-_R>#iU9$#9`qCsNqn*xP$8Ky@N@B$C*TbC=dnthf!gS*#PX4p%t@$XIl>&i z8``Y!;aFI6-st#15Qgt{wTVXs?dLa<1M!y5JdU0Cije0>H}ivsU68DXyE(nl}l{7Zfb~ z#W|ti&`&AJPc(ZJ6WP_X<2K^_FIJOc_v=Mb#nGl9?P~`7wubu= z!oQA@LuXnpRx{1{+^4S-d)rw3XQ6yd0O3pltu*S)!V7a-OwMZXZ8{x@%6bkVUNZv6^3ipYmUWzh*jyq3A)Yor zMQ@evQo$zquLq^|RiUy)QmA-$v`?-PsQjFCs>a?eyjBO7l!eZL>lbr|Z69-YnrlGl zYKHMQu5MaK8~|Zp_MUG$`2&%3qoFO8U8ALK+WEko!hlQinj&8;`MR>`#S~#Nzo>nn zS)ZVdQLOsi_E7cy)W^fRL zzG8Szn8f{V9LtjOn!P4vgHl;N{m&*vNQ8Aza0fMKCQNHa!q#H|YZb4d5*?QI5U~GA zO9aC!WC#QqT4bvNTz2+ItIJ{nz`l;8KddCB*}b3XDAGNxtlewx_e7tRb}c`Aqcj+6 z)|Oshs`uhgte$k#uvd#E7UbuvfVFJv&s9Nb-d4a$bby-sGXjUHtMfMF?9|Hk-mEYw zpUqF2_*cK~1_u75X39rgCzUm^Moe!KC4XZuNh{6S*sS)rWRj=1UCMA~SkI$t^@}uoQ_Rma;8!5LF>jZ={?k7z@bf?9-h5%nY`A=-7|r` z);y7Os^R6!wZ5^&w%q8#idHDsl%I!ZrfXDvFLTz8Sj%lce!(*o zaq!}yilGrtv=5e{6P1qSLTcGXN&I_084vvV(XNdgslI+@!>e%J#_hCV?>9FzNeX99D1IASozwrCQTy9G zlf{3OzIS8uvpwW1voH+jd0(XN>kafsN_}$LmHnJsCw)g?po)b=gxO8{FKIS`>i&n$ zI2o7hUwN%%6XjybMKU-K@09C~oK|ly?197zEfu8|`q0GNCkq{@7#3-ZGgF za?%^3_ZA<}rRLLfYYli&44v>|XO6PHIz?loekV&&vB<>;3_bY#HV-{NE_{^mXi(N6 z8J%0lu;LT@p6IC1qiu&jTx^y>!!-`4qYZD%S*v&HP0gv{THS@Xvtzu=M;LQA-H1eZ zL;FR=>AyXfM`B|w&~Fejw$1f11?9Foc#-hZ4or}`s})plw57P^b9B4}k~vg>25hr8 zm2IW+#=^e7KV|*)TJHXu;%BD?I62PG87J^GdB5R%Dzxgiod75;l&%PpN;doq@w4ot8B$Y&*lMGe7NEoK4mCYK0v z&{xRo1WI>6AKv?W9TZ3{sCMHsetHxcn=IX#h=LSqOtmp6H4xVUOerEidHPJ$x5ZhD zBD_>8wXp$GR#%iLEfvl4q$|j0Hr!hY8)(GwXGS?Uh6Y>ElAwYWMGtw!S7)Gz8^D`cUW2WRRU}+lEdo3%s$;|Zq$ZF9j&1A>eQ4in z5Umi5k_uVH5z|74+MvVUqQgVbsAP0R0U8rohmPt&M^B++HqfzW=r|l@rT9ceZ?riz zR3CdFS#RK@%>Zg61g`}we2f&zy-z?r^NE&Y9LLJ=5K2byx=!{tOt3p5!ej{K0c!b| zXWxxl73|a$J)`@IdHX$+2OSCqzxelk?NM=zR`I9<#H+~hj}>ZgzgkQUmdp3m%Bx!I zsaiVs`#6PpbwIuBAsmPf8xlZn1q#fslg}Q* ziKi$5UKDM7&)=3FVduKBbj1=7KOy$8PPC*k7dBG|mhpDD@GQbp09&vF;tZF4F7;?u z?a>?#5TYvP@heoKK>pWR5h|()!#$)7YHl4ZC>2wIcy>VF3k{4)bskRpzr_u_9j7Z>q73N#Z#FroB&`@E*ksrnz2RQ(Roj~2+UWZF23 z!=^^V4-MRFJpEX!%=2};-s$nnEGkBBqsh zCX-=JqJHwY^Z1}AS(A+HxE8@W5Cv((fqEiBa6Ch+L%d7o{e(!24y`FQKLEjR(;3y% zGyXg&sqi9Cb-Mp8tW8TOD0jHDN=7|YZ@55!J4;+_lLSPqD_&o%Bl_a`i;SG^NtPGW z*0wJ~P%`&bT^?(p9JZ3mzmd;=Fe@@7S(bIec(!HAbFtg_HQQGu&_&&$UV3DQ+F4iRQt=QbPWPLIt9%n zZ-nntHowK6kEVZOA_yl?RX>nbq@sTH)Qg5*e7x_#S{`HIkJLyDIE2?@*0+9!>%q*6 z7(@TIpHeQ&KkN;#e^V8^q8X z*D+I3__e2CxBmwV`oOqGbS72ZG{~(J3JQb*{cZx2%8Lv22Mb;? zv~(*$FZm)c^ro5RK|ES3giE_w z`Ameyg9?j<6jBe)Gw=5h1K;bhfX(;*OqHyfCQ_U3pPN*=>1mX|xGXcj@`nksFT0N! zUMnm^LIq7iB@bR8^Z|%HJMP3Ao=ekZ?X{(~7?X8%vm%Mo#j^u5T)S1IJ>KZR>{#LAcKPbC{AzKvcyxYks>CWiBpzyJ z3FsTKdc8DI52T6JqvKeZXU8RGCJ%WLNh<*LK$|31)iwQFxGEsLd4R9)QFW^Mj;+;po4E)h3Urx@U$jcV zzsBCTnplNxkA|9dW-%qK=fkwj$HbUs)}J0)QQTQ6+?i{-R=h}zT+?0G_%;pnjcad1 z-lHJWmqT}{HlHtFdaT_4R?VsvJ(j+(+TgP_gRBeQ6pyiNniZ{B{k9OBL1{IH2e?6v z8tDx0EN(5pa*bQHewMl_U?PG|q1w^

^sN==&50vZH&vAVaVS)lE!m-ZS)Yx4ha1R}OuuTM9#vW70{eh#bk0GLlSb`QK ze^GI3xVinZ06*7OY>9Eo#fq<3gmn9=hxGPqu`OJI;!=c#mDg&JzM73I>XimA(Ft6a z1V+L_Lbe)7{xX4U40^{6>mfnW?Kt+Q$u(P>=&(D9zuhVQ`0H1>GX);-jCxBB^(#Ae zWzZQZ{DO@t+Ra>ImW$wV#59<>s4<+4j^z}0Usk> zn^IgqlNdknXR8SWqwb zUC^aX8LAO}BS+zBM?a+wtMZ*UDB=9nG@G-OH~V&PrQJ004})_L0t}(Q^uu50hV?AK zQry#wBGS@I(=upaS*tWTpmg1_aO7;@2ZVY732c!lk>*nj22SJ@>%B}Zlk)Gm8^-k% z6N}3SK<)^k&n~II^_eS)8itpI`MVnlxK!(jg(LNhwzBWUX^EwW~U z8RqgB<~td%#~@C#LByG_R#_OY4fp%=tjyi^cY>WYAE!)n1sj+F;?HwUDLo%^o@<*& z&{}{ysG;VUT0&yN*|#ayK|m-1Y!U z!s4J;aeosGA*9O(Z-XjXH>zEO+=8UFyuU4QAO4qLfA)dK!QxSU{hp%KRd}FG7HdnBEosetC?gr2|;h3vn zF66v4#Rp>cy1yjPxWeTQQOL*FrQ-=UN?`%^kY-JY4Kuj*({*V7Mb+c&>^NL1H?Zr^ z&@E5kF={M|*k5+Wo5kEMI6h2^8K#Bu^|i}>;=CNIrKu3*$NVxzH*n1%$R`ZypZ?B2 zh1vg3K`JN(rU=l{`roF-UB$@YdZVx~LEb^a34ZlQB#%A+#d2MbezMt^3w(6}(iX`6 z^l4|Wz~RUHfS{G2-`SBX&_FKSciEcntC`+}Ua1tp4opoN|ukJ_|20 znbTR3dX#))JwW4_h^QXVQsFm&+tlyi-7Bz~XdpzuZ3u z4L()+YtU4WiRVU*kQCAT>P8U;hto_2?bvd^ZjUbQ2mW_s{8{@LMQZ- z=Qo>WQi^V+>puzk%|-d~ctuEHs#iWnyEo>Sl+#&@@n1V)A*`=8>u*J4saJ+_1ze{Z zw#j9j5BHCcd7At_A)qu^; z*2*d*#CnGRT)9r4p0AN=CHi$9^>hpl$z>vzf3i*_gX9bQF{B)2BZ9vRZNZkLF5xqd z6mYf-L|99mSjIfCd%1>5;q-EN5es$ijC$D?ND`<}N4Tbt`mCO2Dg)8hWUZp^FBd2F zYiym6Oq248%`*iy3CRtm#oNw#o$#9}Ci>SUdu%)@1t%cdXr(V6CRIfeV9AUq)y%zM zS@Br2>zK%yzub!QtS`qWz0>AuVbHVP= z<&$+yqksxwrLxu{#m9;l3!q~D=~BWkdC$p0D;C57i_~@1kVn0&YE*SM8ZFu%vaF({ z=E!vk#Qx0c_}CUJZb-?Gb%RO#Q%Qr0R3($zn|c;>_uG2q8}1}!YacUqP8oGfg$bm@ zW7=m1+2!ytvc+uO{;n%g1b2s^L59I4XmALc;K33k3A22=`|rP7wN-u8C+|Vm+w$~%Uss?@t~APX zk~C0IonwuJ@ZxJ)w5|r7N`jKqEuAOBd4VSRQd~_FFpTIobc~7H6FV>slyFvRJ%0ri zl(fc`#Isb)6Eqr)A04ewj@p;TwxI8b1yJ5t`e^Zt2X}n%4p({3^hva5Fq^Tg&=V|`>9C$m zHtHkE6flXd7g<&9lu?jPU$w08T|(mLavZd@PR}TY7^yvaCEr@`NwQuc#>*o*moE7d zOo*dh%19|42e9NtWoAlbmI@-C>(wVrs`+g99+@9#HWCvi$ydT<`Y0J4lUn-6)Qmx7 zF~xH-GFP3KRAK=|?llyR*>IXgrCwmR^iCkbT;fE!r-k10%}*8#bolWX$1hQ!J87{f zbhc-!q^Kk?fEZ;?JOyJgFAL7hy=TcQLAF?FVpk!@#wM)e^lI7+kan<(ay*bnTRgd3 z`tSA>F|;8Q_e4PV5(Gqu_$GiI=bOt=Jz@l+o}_@BV+GvdN%(nnt8l0gt2R!J{=Ym* z)pJmy$zKe)K9eOSE?=3qLKA2Mo~X_>zaWMlv4U57*zO(WTI8>6yv$prPR>7d_&jDV zcHbBlBnZVeDjqsB4M%%4_LeNO4UiybU2P1fZvb+?e7~RwY}e)}WYyTl+p;C9$mM=thsa54`x@%g|s? zqY}o>&sWJ#(Oihd^!I5Gv?UAa;$x%VrYMl9sv)JN&-JT8^xb1pIw@kjvS5uG`QZj3 z_crDO5Pv)z{0AS?&GFb2!jm|OdV(HuVG0)iYeW0`Sy}owT}4D3J>|cN7*P4gJ;(8w7R)1jdY;hyu$Z^(2?sRCl6Y2F!)XByx|0@KvM~r zrEs6}sU#*vx?YL<^Kd8S`EI^IGQmYw1f=pfrjS-~=l<#ObBrbar{NW=T~P1W2;$Zf zyhV$+G%L!#Y4s@b%o{no21^4m1eA|0c#gTlM2qvW)N&!5EbsMG2?6xZy|B7KA!WCz*IZfQ zDdiJu1;P&xGpB}#yj=qPCPlIf2bK3FJw=R#jWk)=FWNTQ5BxQK<0^KF(IT4%{Vz>{ z6Ht^-dmwL+ijq4m_BZoQK3>nfA z))x8s=B<}v<-u|ElLif;5S#H)Wm7whA>t}w$p1SfTIuo(9eEDX0=v+0wCI%nr;keLnu>UHas&1=;Bufadey?sHpNq%;zVI`?Mk6piI9y^~%;t zx7ReZe%d0cSEp81?71|xx|#Ym&)!BzO%yBzxF-0CJmvJGFz^E*6X3P$C_v?31_t!J zw5{2C-(m+kCh!$_wcjK99F7+S+JZW^AQzUH{W4b5kfAz!eNJcD?pT__YN_Zz>KBj$mtB(hs;9QAz@1C3 z%^QyQY>7fJLa-*+^78I3fy`zbDbbB2_$FS)c8KpK%LI+g75#A1V*;bL)=-eKI?AK( z83BB^1ZvVQsnW}_nk#S`Mb^S16>}?O36)zT)X8KrI5Bh@0P%E1l-v+Cl^2~JkVGX? z%s)&90v9U`C$o)I1@EJ~rK0JF@jTP>qL%aGGVqa<^9BMa@5=bN83cqGcMmM=ERJO2|;RQ-0d2OzEZmHj4 zC5ibZdKrm-3yCi}B340x@NZ;U5lni%T&4zzgRsx)bOYtjZZ9bkGh_SSTY$&4hNDD5Ri7D=?sWZcVSQO2YZ z9gY^pWM#*MX7tvIxyqX4yOsHowG^|h^;;Vy=C|zMZFQ^g{H+wc5lAN(Bh}fP_@2vN z6;arSBcSs`>AS=I)&=3?H7!?JG^r?{f;_i5ND8bVycHo^C>Nhj#?k`xK&|$`W$`4b z_M~BX$6Wo6o5f4G+DnSXTZzR(4&+*d#HhmJ3#w-DIPkHn_6ue4kE!-gVF|!xVR2wq zK&Naar)&#nMt79;{zRjK4zNwy*4};5kCr+WC%s#ir+!{0m^qY(M2a0pyY5%Hktpb| ztm?n6w0X@O6jm>i8g1Av8#!3V~w?Q!0&z=8&eaP!Wt9G8l6!Sw{rwdizF&J zj?S-1v_8f|9?plrER|}I-Y}n@zY7M9B{a$rsUbNn1;RZ2A~0hfg!Re4UEvb6!lQ> zqfiQo%Ua%^n*RBV{0x?Dm;5d*LL@C*A`8aUEzimt1)!1__coKkwUwGHf&Q(sz-P^Qm%F@)Ef~><(u}AOaAcA5Lb8BrJg}7aHC8TsJ`PRB~BA zNW#&KT3<@w{IY6N69y)$b44$KI)6PK4OO7j$mS^Z)~wk!&g7@XlwddH5G7Qdx!uNG7ck7l7&kuxMz?N0>fyBkt8MH5SqhnW2J$ovjGt27Xp{TOLn5P$)TI`M*dSs zaCiZG1Kf`KRI*`3u|dwo{6{V9NA%8dz~X9cI?3^HQ~yB;7$rL&Hc_TA);rSwZglpt zVZQ95`Lv}2p^}373DXycZ+N0kHHaxICbjWp!q@m;)K=*H`fSzkd>Wrk!jZ~># zal}Gn@#8Jyrf_I7dPU>j z9MSaGn)@HkDMyn0?Iq{kuw(TVpfLaP*LSY{BUe$WC@_H)KN%eXd+9^WGP1_2YqO}V zXJoA=_udX3(G{1sBkuoJ91)={1u-6l17I;QXd~lF7!`Da+VV@7=r?Z5DeeeRT7l|| z6*WH_f#^<^HO^BNGiv+KpUjA&!`@2tP4_t(KJ;(yADfElYFyFf!{HOP05~sjZf6H` z8=R9qTRDP`F0YF*`jY%_a`50G-naE{A%L@Cy!W6i2hi1!a%j7uqgCN*Ut=kk{Z{)% zBTjN=qCmb|F2&!Jp4+<84JJFbSCmm&{x?FF#77>qy=yo6M=6@3`5Ik-kGZ{-d6kW< zW|iZO8^X7r3bt?@A7j1nTEgYE^P^k?9=$u~VE5=U#Mb6%~V`Nz%$s|J48)LG$ zp`7NyP=_TPg8)mOEbtS&H>ITWZ0z=X*m`w9FCMuL<{S{fWw9-v=~8QLSQ_~&caA5I z^jDthR(yBXjhah~=98fS@v>)|O6S}ki;!!jY- zs1J7SIhcazpCUxV=+&~ewOZiPNh9*=H@5oxI*@WQZJ;*VCv7|-9nw!av_3lRKwTao zJrN&Wai8ayNOGu<0pTZI1|Q=28n!t$sZ;}O(^jcf54p6u+OoR3-aE8b21d6iE~IG5 zzi_`J@1$%2LX$Df7Fm|y2=kvp7Wbbl5JHw{zb)FsElE4AXn$MMc5)u`a6&q5SbQym z z>NW}>!yib>ZzliInN}%?v^)Oe10@wSq4^=S9vY$!as|rMw{*w%`3EZx+lqi9_3q#P zxQ&XnAsIxZM!P4!%BNH5@X^ZM7Y_ChBpeIGQjA~f&YJ5=)_Tk`6b)tp@g7z(8U?(! z>7fSUa3L9d|j#YLAB}e{Eun`SQh4aLH4xjd;j}wJpKh*y8 z@3-gSD7c#`7i<_r@odbM^@xB*4v7~=ptywb`NJJSL*!wR=&XNb8sK`xAQ6>dg@a6h zhKC|VR3i--&-QNYOmA6FZ+vxhyjS=U{b^IS5Xl)gQe1;Dr@YJ10I<-cx7e zJL~*=+e_H)a5Xf563`GPW(jGGMA{0F$88=G!;V?RQjofX$wUnkvav4sD6IM+bdewA zM6t_$b$M5M~9!0%-P6xXZSsow~a=}aD+neHX z|DZx>8?$=v5-_5=;=@{;nb$2lI4-o(mo@{~&z!U8exS9v`O9A%rx5nK|m;q-BlE@wj1uE&J3KbRCT2ZPw zJXT{_|Jx0{$Y^_MpqbMe<#SEG1RH#B9m8zUo8_oityQY@iai2Rxm>{!(&A~EU5hPT zuoFcr{=vn#-F_keZRQ78(=Mm+VG0q=71KVy)d8J5dvJ+@EoDeqM1+SGTrN%D<5Y%Y zwKAzoOcT@i=5Wjqu~1V;G(tRQ*v8ifl2H(LrqYOUV%gn`2*?2_JibxeAtnUmD-y=z ztZUS9iJ*}dcf^Q#31w*#tbBJQFDHyu&XFn#{FO7!-E2pf-2eV)RRBl7iEYg9~sMC)rbqcct&sn^ubUQ9y8bU5X0ih1Uon zuJ=j>n&Q!lohJNG0P(QjYmP{%O0E--1EV3wMb1mgOP7B_5qAxEf(?y?XorT$Y zs<0+9;w|0ZWW1&FW?%RItN=Kvm;8e~ebd7A=S+8quQBqIn6W*(fbJ=CztB9<6yG>% zWf(ynTe&yaiV=xdWz!-t53!J%y=X`|f%kC)3C{p>?awKF111+~?#R1E1Kx4s_BZ?j z;=bLsUuV<7++Y>Ao~p%%>LTCkSwpCAr77a|L~{d|)>7DoHADX|O{UyNWmNJ*{En7$ zl4y5Rocpg{HlzNplbv4~T8uyZGcqH0v}G@TpMr0El%0ba0DX_;^4h8kwK$JUB$)h1 zA&aXL2Z1c=BST|cUu7Upt)+any$slV#>B=2~R) zk3xp&QUkAM$DW(dJ16BRZ(FJweQ#S2u@3iouImd1`?#1ze7p?jzBuNTq)=5)zD-TQ z@(PRhV^#ld;8grRu-@#!*D#p9So8~XWaM9@tXe3 z4!mdmy%&O2@OKvs7^C9O$XFn#%;l|v-=4&F_>ZT|aX-%Gxd&ZnS1Q*Hbi)F@;l ztG!8V9yZt&nhyZpfv29sP{KP5ju}`&MT-nsPgsgp{xzPzQCgHlU5UYsebGPHruTMd zZ_Fz0QC$?vqTRdAKeSa7p^MqYzBws1fUv>{id&+DdZ>9JyhKR!lzsErz1gdVFNZ5 zv4XN3rY>X5uBz?^BFkz||*ksH2+)eXfsfk|+irQK+nG7_~s8ykMru_LdmMQir&a#LeRVbGb zX@ZsX!$XP2KmdL-x3BMFMV8Smd0`v-d4qBr>s+W)=lo=5`8&yS$z;*2%GVkd=@%7_ zqvNY|Vjo)hM6C%tty!&RR!Rg_$E5FIUsouM4f z2C^LQ7P0&-H23z*xwC8Zf)ifo%vaCBjZ@$~Dzn8Q__5CXj^qc_py(pW!J0^1KX;t8 z2_uM!V{7lrl3mg5$vbZAdkCkU(q=F{P*`2k#m-Ts{uuzN1tV@K`xm;}s z2HyiRW{!XHy$btGj%%7Y>-T68?;2wPWq9Nq;Y{)hDYF+M$eqi*zI6)ObO4}-VR4(# zY7S8n<)ZH*Y?rk^l>?~@RSfMG=j-lFaZ%-&(OgD6Bq?=@lI)3d#O8QV9hyw1%?=80 zm~k$P)S*^cOj}Q%Q!kBTBC(3;5F1>g4C5BOjl4`J%``DBIoqcfaE(a{!@keB*_K~V*4g}S zd&Na4Q~|@#Y*CbI(C&M$bp<>X(B$YoKZ1iwvJoEW@PNK|xiZ0Urxd!;1$v85i+Psm z9%ogt+b4wYpSDHug`}i$kEFgK(-dm=z)hXi4ziF$g+x1eo&JFN$P`QFOxivp;VlvMqUbIX@gUwZQeyTkE}_ck2le4{TWCH-4&=ndH~4 zu@cWT2SVqUHyafg*tZhn-vdZJrpMjVgkY?W=@RI_BX-$+wh|R0; zMq9LgHt_s(8y&y5n^~&h(s{eGX}jr2sW6)7Qu1A%XXL2oiK&MyG{mqq zKH@vpo$%XB0Po$C^IakLj#4AwWR?Xy&sb+g?tu5;X1}o(%RG>R(iv_fe05F%j*d%p zkx6@x{{4bC5utE&tJ^XObpu>;qqaBi*bb9S4WYFRkv!2=VY;J}s&6FOz({_MrNCI1 zAus6q=d4O}t{>>etdMIy^4Ge2A4ac2p zH_2w#p$rxm&X6ICv)Y2R4G!4#NCd^Ce@VvWW2$)uoCs>7WHvs@;DYOU!50@(L^@wh z+%`bY%)0Sphrk=V6axFYzq;xd-0ltec!AiIeQALc7h8Vqe3 zPixeZA2f46etV#GT1ODZ$x_G3uAnZ~V`h*h;@zgq8LN0uZLpE2GiF3#(wEL(R$P%c zyVG-I(0ptpcArJ9nx$IgVV;K|#lm1}i;S?V1Z>@CFhNeCBF6ZEN*KoW1|MF3<;lZ5 zN@)tF-wl1^3{B1=u$l{GB}bGryn)NjW_Zfj!_PK>uNUTqTivG865Wm{W}E3^`t{kf9^~V>*Ic+5uTHTI>5duhOP=(vbA6i1eJMMG54%k>Mo)*+vwmc8-6G z(107kkc_>W1&XsH+7-GtEACuB2|wHjFtrovb!IY;+E8C-s31l%pCmS71H;3c+)mXA6#U9Whmg^L1&jZ(%V@E(-~%EX`y>0 zHeO1O-jdU`Z0*NvOBiZjbQGo|1DRF1G4wg)Z@HA0R1yUh6;;(pu~?V(sAptJY$L=< zv$CA-aNLP7Qf=w{vXp;<26N}sBlQ7~Z5r`JiU#=|YuQgmnD6dLW@oO6P%82CTJd^b@AHvFjQ^#Pn<}R(lyDXuC$>L?Z z?9&DP()x8}sQydlpNIB>faup-o?~vn}S~_bF| z?!!1Xr2d(XW~+kv++ic*7hMTS=z*W)4^jZ)Lzs>N=#^5=d(Wx&-=-y6M1sCq>a`!K z^^kgz=xIYpozRrpT%wLNhstD&k4?+24(Jj((Rx7;4YMV|~a zdT$d?CchB)tBiMs>-E~8=f~mXXU#9NYJ}_XIBbON0X3{6nZ!K4A0u^IVm-?eb(WxI ziO?($1(b@E!$nx2CWaRgs!gA$#z8jI}~9H}H73E`wM;ZJ%p@*8Kb70t$8dmBFoSO0qIZil`E zq!O!FEn!vJ`+j}38SA~y--();esjG;rIvki-N#V2S+jQpIlv4Z3Ti$2HtLrxUulGM ztljehAtbpqIAWG&K{LO@m++r+R|CTZ8dn**(Th#knFbe7s=as58$f0THR0k2` z^Gpp1oz9ebjb}~nf7&)9(!)wE+(mDtOuJ*{JK)~6%9OEML6vQ@tW7XVrbzt81x6L6 z-u|)9B7&|`f;HcE_;Sz10A;;9R2F5`1z)@nxr8FAj5foNf1}-ynH(Tz*-4-{z!cky zw9tD-*|#*TH(^zgXd8t1v)qnE>HBZ9#V~&a_O5{^p!D@HYaLK1DiX`Bno56#(L`<7 zIA)-Jd0;({i$GQqnN00U-TuAliN;f%sBrzX@R0MWhRcZT>s_(|7|qHa*%~Eatb}5p zj;02PMKg?DQuZwvUeEzIEyvsbY-o$U98O7fh*>C$le>#O03)Z_N7|tyFCM}y zET!%&BXTIk&Xpm0u=+h^NvlMM>9D6Th1OH91Q3*A6nrWB${>+h0ws*!qc9F!zj=H2 z+5GWu*b;qGDU%GMpQI%`h+O$|_vo)dyaGk3UCJ+EQP;?{6<+5=$XL&%80K;m%=jYS z2Xt*#KqjVHLt9jret@|(YKA4wX$h`29kH$~}vWgECO>_r8i-7haXa#i>t>`7>l@TR38q#IZmZXBrmp_B|Tw4oS5xU)wm zvrDZB0|^h2ecrQG+^2ARIU~oYvd@%ng!~$`LdQgW6GD7UO&qoJ<2}u{RR~rF;ALrw z-+Qz-Rup8rbeI2r=mClCLIh9&*yeN~1vvmwwHa}-KN$_2Xq!3TL~99D*BG6o2)>Ay z=oXP$KoEw;{CKv1<)ipiLP-^I2((05hLI@jV-AJWKENp1A2u*}Xs5V|wn{VCZO;*K zKtkvZ+u-q680!%5xZeC&^y9If6;6uO4qE7T>3+mqzTc(9c`DP|Ti-Ru&V4B+!_tbr z%>iyKvzUv4OZmQYFWLpGA8CI^sk?&@KRwc^$y3nVAhlVMkA-0umQs>6PM-h?738iJ zBd$FMe){e>R}I|sBYsqu(p2sJnf!PvJ;>%e>-S=?%Zq4N(y)B}I2bQw(`BDWGbd5Il|G1&^*qt$j>Xs{< z<1iI=r>RQA`J;~borM15hMvxsO!PgTD{*3^k288QfJZ8ddp*WVTt}Lfw54CdUj>A*O$TAh5lfEnd zNcQ@F4^z=&oX~t>pVdLmG3;xc8!|2v!Judy>Y*etA7o5Osnr-ZgK9>@qo!mqwSG;< zzf2LKkf)y%4FvpX=ixFaJyET3Dbj<_|Ni1MUGU7CdID9zX1)lW7|VzczmBG%LyWm( zj1kx%6?%UzbgP(bx|lq>qL2q;2dh>kNIW2ajWz+lN2x?^g)Gxlc$*g}pUf=jImf4C z1k;e<16ZO;b}pmCF+tg-bF5m08F+3O|5o>nD3;UJbQ!%z#-&Z17$N{fwp~Sj0ZAvy zd7-;}Gy$~@J!I`FPBhd35kd$ioLn}}H>f|^v#pV-boG{L$rO>^{gszA5 zUSgYEglEz#*dya258jz$@=6SLl|l^p5s)Yq88<@oy$@# zz}97HEX}u5SdrgMm2S26&&P-`8CP^0jJDr9i9e0UFYQ@N;+->Ns4*Yx1N5gAFUg z-XyRM1HE$BtBa$>_G`GR5@^R39E0cU9xuCoj-!&pIN6QE-r|$An74yEzXt}z`gpN= za&`K#%7)?k1yA3C(IBuekaI}}Q6IA_GK}L**xN`$o_K7ZWnDa?ccK5DADiI`n4FWM z=}y!bkVtgUq&di0a(&$|fc@HzE+O!Elq3gwAMc}nc)eU_z$Jv?+~j$u)HQPOMdB^M zV`w_?&{F^t-5_j)+WltcmP$D-NC4FsoSa~Uidbfe+$l?ydda+-Cp(xqxL@RO9;CI$ z!L3rwI@jylxyd$N2hBXUy#Kg~T(Rx+TPsz39P=BX(D%tIBEgWElKARf@Pd{2;qh{p zV)Y!K&ho1tpJf4*j2z~2q(|d}(zVC2slrF?DaYru-iJ=g#|9=Ee@lT>$NO_(#WKmc z*q$YBJdCr(1vvN-wPTK3-pYJcxDq6!QrS5*{P1U;1Ir-rgLeK^%KPAQQ<2Cxz`L-< zpCO5!YTyMKbU>77?wlt8@-q2f7>H9C0yp!jkw)QTVPks6J@K2B+A4njca9gHv6prB zg$^T%YacHXeT0EvV&s{v#nsIjqQlNgis0>3Omf6OK#6xC#=%SoQI(B;g0_X(+#xZp zcEiCm@51ONw4-;X;8YQ5lF{e@lr>P|;a_b*Ja$HuBVII8058Z2nE~0Mp@K=IY;5T; zRYrZL%#yzn{aq467(fr1xUri~tI9R;&0!HzW*ocG_t+!{zVd7CJSB$j>VRoAHR`DQ zG_Eyy_45fhzP4Q&rpH|HH>__|VN|8a;G>r_qOu%Uc zJI(~DQ4$ih&ThF*)J1 zChXC;X{umnpVZVJw?jsnE#s091VJobttq3Q|iWw985jRRE#P z>jJBWF^IpYqYHmp?=Y6}uCb*qQeBGBeXi-KN?T79TR+ic$F;5!e#;@|-a8a@s?RFJ zq;4^OW7v&zl=N0|!uVDINs)e;9xWGs*Bc#+LUagF&aK1z7Z=f5jDl_xQ3W7z2B+rB zV_^Zzth6|K;l)giYWhWHz;@D{Cy?cf)WXbSTK6^oeDou7RqbC4* z{?-1v(>jhfW+96Km2cHxf5q4Th#vE*M{hraxuqW|OMCU~av7`vIeB_{b3|@ z^BuV&yc!uBtb*Y&Oy`4Rjr4jM0FcI}kIqbp+~9rkM>bSkKK+^ zSSU4l@MLrujKEw3Tw>o7mC@+;l-C5z9~c!ec|=F-E-?YHTbLC{?3Iqjoz5>``X0bt zBa5e-MSt8-B7X3|5B=&D{wQ(C|GoEv{0kIX-Iau$FMxq%ZJp*4kPv@^58wQ>s@qqX zz>8Ob+GsiYnVIj@sjY_<7V;iXH7v*mmkN(Yx)O{ z@_Jme86o;eX2}y}eJ*dOT3fasrtWC2Jiy#9C3|V2`c7J0%3!R~%@$x6I~Ux^a8+0y z&AZ)gz29DUcC(oQ&85FI!8+d0R&BPoLoVUfg47pTbdzEVq$~gl3gnjfyJfT^9qwIc z&1WGM?7J?68OPZ~lBq5^zhBXdgeGu>;;@UPXCX4^*PdN}_iy3bd8T1?yRUn20-dTh zgX0-0>;?2t%VHTK^OQT(kW0JAUekn2o{Ddx{N(OWV?xWG2Jips0etUQ(B9mnO<%lB zZUd)?u?tQ*T9@$SseIXDtsHGyK<@7jWRTN{jnLtH-aH{j=P4qeZC?Ep!JSzY$ch_8 zlG;A4@-fF4TwP=wI879}np94Hib|WwvCWBl-5iWozn=jQ0^G_B0X{yh4c#ppVjY&t zdwwKOYY#{Nax* zi@6TLy9D59@#>>PX~P)60+z3+bfmtOnc4aP#LLmX(t#~y&~b9~Q70l}d_o?|18cn? zsy{-q_{2TIT7)V=?hv0YztDtxacT#j$Y0?|bU1mIC`J&RQ%fC&=m_jF9XVOh*mq^M z`RM3qpnDmbu?!d$;Iy6vTk;;G=V5b6jE(@?N@r$nA6Bcoaq)v+4&Y~bJP7yH>a z?&?F_%}VG1Gnn%VFZLi>T7`tD#MW&bU*oI8XsiiK3p5K2kSW9SP9sL?Qn=>8w!IuOu>KM>st zu;78iq7rY_imC{Yp^^n`!QX>(kd?w;!NE?;YmqCg4ze}U4fiGq^H@C5kVGps2Zlr( zl|-|saFWtci4Q3{$KkE-Fww)YPs84QiwYDN;{Hd1&)bEjcI5%uMSHP(0Csg2Sap#n zBT?7+&?i+f9Sz;TYQ|qXJ^Vr=p-(?FN=IY|b#*5)c4aZIX8p(wJU@P^{UEThTT_tO67bBch zIC5~NtVyJdPoaTkeDuS<*hPLD?QYeDS>k{%$}8$O@3QeB=8zxB#1a>D!s28c26Y6l zt&wch2x*P*#_@^&_>iO2mjOTCZI`4LRUi?%l$X_Af70C36^{pfA@@r`|KfJl_DqD4lTaLN$b z9yBq+KdUpYC`?ph-LXVLB=^j~X}S%Ss~caXBqm)oggYLMhmVK3v(#&~l*IdGj9n&F ziQYI76>60uZye5^pRZL@6dqr)$yPqJT7m+jUhzxG71XBFY@x?Wux%n2rMF7&yV?0_Se($zOxbpdsiEl@%%d?xif#+52Ochx{0ik zsjgD+t+>kmsBtHaOJ422_fh58Q`e;EyHO?2M)ly=M1iT2YE}fkD#SM$6Caj`CT5xG z-2z?6#aeo(*&wMcj*rbwkkPu!BqPWoqE9*cQ5$NdRfmxs+FKn1t;6UpiCQV)TxCwU zlUNZzd-3ro&2v?T<#j!I^oZ4Rjn#JvxOuNv`0M0rKUpt3Ht5ARl-4!y<|i5k`c+{z z*3^MR57Zl;-uZ!%9TLzE>9J%E8@nlL>WQ0Ngqs}ND{ytIe>|Z+lcVn|H~5KFlIAv4 zY&6Kct}{t!#^j?}X2&92=-L%DaQ@_;7-Agc z?Ut{IBZsSyN1FPA=LMq?^)-!dkdCWW%BpwBbJT4+cDS1s8w_(ZCxU1E&@6gO$y%Tw zjM(5r%iXCexreG~&-QePA#1PS`BV2LMbGV2XBK6%zC-h1m1XaVek;U!J2XWhZT9x|+EioVWnEc_HBBf3Z;SAG}KKr{;9&nWxE zS>6Np`JZbG(jum%qyA(zC0axPN*Y=ER@D2}I1oMA>dnuaogvO(iXm=re)E`8=~)3% zHv}8Gd!RbHcX|q6AQ5t^;D#?wmz<7n8hH<}@Es(D&i2Ga|734Bms% z>fi)Lv;R}$UD9Q7Jp>N^#8LHmWBhZ%{%1egK}25d!x^loZIF%=j+x#$)7zhE+RRg5 zwrhQDoeVW)qlzaVg zk9d3~w)D>Ug8q%B8enf3tn%@3qxDgzPB_*YoLsj(o3}a)P(t-4ORw!Nbg3 z{c}@&^5k(H#8Pr;L$TXVp_{vb23 z!c}fb!56w;$VDE6*pdpk+f`lV=uHB+eSp4?whPUpW2@(5>n_t&|K_%5Mj?`5v@2%R z#zizfyJ2lCRcbLsGilDoUWZ!*dKd&3?r8EcyU+{_)Ev(niK1;08gjiDu z#&D9aqI#mLx_(hL!|Li;v-6p%dOcBh{3T?sHz|Bo8`+1LYuedsB$IPZ{MA~O>sobC z2#*H$cky*lD?qgo^Vi1A*?g+_8_yR_Tbj=?Lq3sB}$wX zo*=Nk%V=}|$|p;#VeQTGu+1K`_1EcBZ)IWeyXfTD=*V8Mti9C(vJH30q)OfhM(c=L zz%=46lp%oAyr!_w>8ds=L9Z=sJ>fBp|G`8?4u}yANBt zUtNkWlEFW>%OuR!-eJ!}XGrqK_LSYg<$(Q_qU8e1?<#Kl`nfYmQslchv*?;xycbyh zlb-xL-6l94ZyLAE{~c)s_aKM3xQ2oq0sAoR%}aBb+Uc0HI5L8Mu6P4M`;FoqnG0M;ALu^a#=l}O8zyT7q01?IgvSEWX|+@a4%sR&NL(7I&h7E=3$dkJ$}g5w^K zYM$N{O^2zW+=af7|9`SIUj4QDnU!DB^k>s|fHWJTc0A;bM|eq`cvNC?Sz~rZoH7jh zdxcDgdToxy>~RB;zrb|5xG&~?KSV~fxF2-AnD!1A-p>|%c|zMfC(3n9FMYR4_Fa1W z2154JI_>WFE#d}*k9q2Wx6X@N7qS1bR?OGzHc8_sW9a8l$to4z)!4riDD~->=9Qww zsaWxy+x%&H8fwP&-2$I?NElweCCUUCPiZI5aIoGa)#A+@X(9y6JQBBU_h+}jZvm-G zeDeds%Oi!<^SkXkD#$)U@_zI8-MR-h$O>>FgQ-M&`vgQ0qLYt~iR6BHT>LxJ{l-fRHTdJ>L+Lw`7Cc{G@H7CYj0Z-r0I~?PAi6=%*!??)_}emn z5sNpS`uQOQ_s*2-?nmgK&YumZDYO+=c)V?(@hhC)Ex6;_AS6E27r6bk42}^m*vJFt zeh7Dg8vzd9#krT^9J{&e|Bo9Qm(gf`S2haczueIHOq$-T`ybI0Fm3)a2wc7Hj38A= zO1hcDpv1-1Z?auqJW|i)GYlnPcHVkbDC)CwcjUOFRU#XW%Vd)EN~c0Kn;RuC>qM_c zwTSs*SycnS!T1x6?7r;x)od#52qsgKhP5oauT2K=A1*fA+`c_MC^H!+3ZU*L z2ncC>3HD;Xg7?{KH9(zz0K(#YXBzHm(bO#SLdwhLr~DL46_flGQ<=>+?i`nE4gRMa zT5i5Z#Fyxyb+`6?kC&JA(to+3akq3J=Hl6@;`jBsp8sDrbdOivAF=&dcl(B4ToY*D zKmhA0q@kN;41o3(Cwj-xE6a8V)G5@wId1-+GRTDb9UQb)^3R0^+UPh|?%k#uE9WZ}X% zwc*vS%8MJC00|7Is8?kzy5pTl0hQ&)?UL_;3}{|<`1LRB`DjYrCsxw(L!VV*S@IwXXH*-o$W$@ zNvm&bc}asIFl!ni{pXlDl6Rfb0ma9K{20^YVQ-w07P%}&CcNQ+1ru;{VpF2M#ivq{ zPIHv0{lDGNuULndp1RR8S<~XtP?hO$e!+BPxrn#isj&^0-%(2BYMGR(R>G(` zkqNvY_-*NSi#Tn@cG&!dCw52xU+M`%%V?&RwN3A7S7S$p5B}B(9Ky*POL97BA6*>e zj~7%n4eqy5R()Rnw!EStKgv*jt$mbb_L_A^`r-v~TKM0HQ=|VNPO-rgpum_AFNo+# z2cedvfX0e;Vtwb6Qv=7CziirDCGhtT#-ZzHNH7}HbL3gg0+-w6OOmfrvfb8~2#z+Z zvG(A`y|5DP4Sbmrl%MclhSFJ=XY*{z`(n_=&X( z)?}U!N=(C^iSN7_@FrPDgsOB>gY?a5w3fzl13aQ4kZCcrY=*%Ui-K{SrS$4H!>pb2 zslgStO!dN(ivWHXb8JQy5sWd-hzz=PTRLX005yHF>8$dF!*z)hHJxGIq>qJ1aw>Vl z235K_edoH|*Nao1UVOj9E{uG5Cn}4)H@RbP82OcvCdE+~az0ns30VltCIJMzW`ZjO z6w7Dq-U;OGj9@|g*uL0@{`^2RQYEzg_);>@4BtV>{ScW9AoWUVFFyKguXL05C1k(- zBT+c>R)wRIKeK)*T1K@(;1Is%Ll`PyrGp|@piYvVemUtcSp|_NowS(cGV1Ial~;j_ z>48L*971fW#!tFwy+l<4qcs|iflKilMAd>{PgKXRQfc&Ck$o1lb&>=1E0_&x)!#bl z6+P+K{13+N`Yp=n?-%{eG(B{ebV^D}gS3>ibhnBK2sp#QFqD7_f`pW$A|MSS-7!i^ zcY~mUl+NM%Jp1gu&py|=uJaGvKd$?;)_Sk^OZ#5A**ouhAHwdvcfVI*yWws5@uHMk zX}e^L+sAq&%%ZmV-UlByAKQfsi^kr2m5;8^HV?uqTQ~20e7fP|-)r1+=j2`$hS%4L z{HawppG9>7-Fr2<}A1Nk}Y^ho+z0lEWELmQiMEN$J5 zgAM}YvW6BIp9itOw_E1@_Q2kiue#K*1wNjTIJ_F6ve)_U z`;n)DK`CkWD(D%>G48LqGj)Po58ok8{N4Af44)eH#YO{sJjt3^JVg5xuoBOo+PQGT zt@}0j9;PORyYlc`59qr;e3^6QDsabo(5(1j+J|sA5s&M1?B>JQpRe4+W535M>tGf3 z2}IAOC3IZ=^!GZjX~z5Zcd_9^I^XIXQ(DU7V8bD?x0|`Ja6uHkJ1kc4UvZwKW+5A) zG({Dnnh-pLVK!1VE?`*jgwGeS{Kh37Qn-3)vp|>#jb<;PhMpRv5ZI9Co!dofUT97* z>uCr)hqMM1JRIjW+YXnLOwBWUD?bTXJ+5%LjkF%0odOSN${wyf*Cd8S{$znhMcv=l zV3?b%f~nT{-1k5y=3gsqaG71+gR| zz$duyVxf1lzHn#3Q$!lWc6y{;w)XpnLkW_6K(&i{BJT(Egoxu!RaCvzGAF^ywUfju z1*@Qh=l^{4PM^>Cj%05YL|S}B?On(n=J0lSs2r=BXI{(*GdW<|jUl%}!Q`S(nR74g zIC=A69J#7kUr(2<+aLd^?pGxRZ_oEjH^`6v;6eG?xscse#STD0@sek%WM8fBjKM(U zVdKPre%>940%Uwd9+8^em(WonAh`PF!v2}=<@J-w6qDLDYJ>JDW`TLdLEwi>_@9fV zF6Gmjx7kPD9#6+8US{-2Z%U+m9A5NU{PWSl{^$(@PJluT2@S$9+p2acy2|`%Ub_7Q zUeLNklziUN@b3h`M@tM>Me9#+(}MC_7LF_bFgypblB&NdnEhI+TuoT!aNDL1n|SE~ z`@YJIir1Eet&+LRl`euj`0nqQYBv{gO=M;;bF* z80#j0pcH@wimM5G#A0Eeb`HI*DrNJWc)X?!U_zpJP~XAWY2qjobs( z=|D|0R#tNeaE}M4Kdkxozw6e}FC#zo*oyQhPH5>G^yonViX+%902NjkY&Y7{#j$qJMz@Na#dKZEUaO{^pgGWhFrkLyObL+m;9C&7|i$*}x zgLKiHG2urrX-=^B5%#ZmhW$BRj;2m7>%a@8fme0|>E^0mO4Doy(xRMLqvca_Xmx=j z-S=dJRz96!8nFE6-e>rhH>|jeRW;n7<32(;=M;pL)z`@&Kk;dpJ0{z%lGMti1BAKRe5Xut| z(@^TxrojXsNhfPcjzJ8+@)%0YV6#$TORPBRz$nden1vuLF?*l`g6fn`o+BIiN{d_A zA6c?fSn)Nq5R7T0MbHzL;h!;j0OQcK=jeR2(c(OOX}@!s)yQJ!^)uoOH1QB7Rd4gk zU~6LJr_x=(7!z;?pgo5g)=~QgqZ>iw$Kj)Ajblp_cmEY>3%5o+5r{z}jk8_Z=|e!I zpN&anIvCGj?pBrJMMzSKUYI;A*eXh_nkoA`{JM`0?$v|_VuC}E!B)y>0Vu0$%I)iy z@T~^Z87goT%-@QL)lb@FCNp~l{#d7mi4DQRi=#ek+!aO?F{S%0!?Ranv*e+V$$Ctb zQg}anWm#YoNV*l3VY>4VBnNYd(cLyD`JBv7eBrEsc~9Cq%g? z*1*{;FJdmp4pbvE=c#IoMqO7oV1#k7fIzav)I{a89B|xR(}_(L-CWb$+^4^d-^+65 z267hAN4H6eVMFYYNO72YVN978^4HfSz3|%L##mj#%f(;T zux2?9DY=xLktC1q*?-(Mn-TUjw9w#w_+ykk8b{<67#r>w>+U#Z<7*~0gSF?j|0TC1 z^~eD*b~uGPo~1cl7#dLNU_-7$sj6vSS#QC|4uOCpk-r0Z($e{dB{jRZr=f3yxF@Gm z97*gQNYfYI{vrzBvyL2E`m2ScGIF4XEr0cso)666Nuv1+m6MorVn1}^_~*n);mpPE zd_&BcTiKb%$eGvPna|&uKhjy?xwBxdvrwh8aGSHpsI%yzv)G~Y&413~6fP3%E|Ov{ zQf-otlw4%&U2ajVnl<*KQAA8WE((<{iiafNwy4bYbWMx^uGw1vBYFn2Z;B3H#_%qK!MEK! zBHcZ)>7;q^WL<1rZHy=_!UkXG9x`N$vjqCr&_^2#`{2j7^;jXXXBab^B=;wg9wGin zhfH`_ZfrO}?CEGAgO~Bco1z^t;lMpKa_irFWOJaDJeS2a^kQ@K0s_6zo^Z2%ud-b4axsJrqahy>V=SO! z*#_lb#@LZoSXa6kw7W$$Mu*Ns(J@Lm*zaTpc>~MQVMr){JIF9_y?oT?^K*A1Bs8EO z{v-u7XDO~2``v~}FLWd1Zw%b$Z0Pf$?^y7bsblOI zyWcl4zgR@f>z3${Jm|Q;-?aaMbK_!wI5hI9-`v0b|I@jr`CraG;osl?qVBJ*p?kvB zCE@bVHFE#=TDku(=l3 z|FP{iHrCeHuVMR@wYAITmEF~)-Q|_-`L)fZ`M--@gvElDm6heCg=^b>ZT|Z;UB9rf z@IUqXwdvXEnVG5S>1)9L-&DiaT7B~ zU1RoyiUh)YenL4Vp%`+_(i4h+A0;9eMZ|xLAPpZIuRZ&wvWBMjZ{NRvUshILT2l7z z-Mj64=dFB|--YxC1$^Uq_JeO9b{3>`<)YhjabI#1zvRZZB`*tdo)@O2rM-CZA~`wvnz~PkeSyVdv%?~v zhrYfx@6l-VwRs=)G&3UNS!meP;3qM`!NCt6JPZg3xF3|K8dfD6*(e*?ARAFH9a8nr z)$aV>-D$^rxt4LEe&OEU-l_NBgm{GiH)-$S;BZaa+uGV%SXlfwX@6v>nPF5&P*+)3 zSNtO*`A1lQz`;tOp*mrt^}8EjWMrgkV07oso&TxbD=8_-%gbMD_fk?);{T=H3kwSi z3J6|n_uSmvoSd8-930oM{k3Y(%*@Qdz(7w=PeV&jL;XK&djcs50SqPpz!?noKb?D0 z0Qf(sd&vJz-T(h}?m0E$S#@iQ2L8XC`%fifZ&fiQY@%?DQ%raE`*J}Hzt z^i@V&&g@TpP9Q*UMuz|S={QhGD36SoKAo0d(`k%~`FoR41Kea>T_PO_17G7>9W~*m+ zqcve(>!}Xq(L5RVUxYek2qrbXc*8>c=erPMpyMv7X-=gY2AsR4Md{wVWu*m!YK*K! zySo)t<%GfAG7`qYmHhg}@`_}R%tj=|-$bXfoGf~u{c76B<=;vGGCYV1uPuB~J7M8- zP-kSY(p@(ny!WB*yT7d;sqmZMrA-Mhg2b8|72X``>{+Z=s8{5fS?0*zsQA%#MN#Cd zH>_L%f?ZEoM-Zm>DIFbTQrSnH@0{~MR6#W@dnq3E6{WrOvC=oyp|8ODX@pasp94?Q z!@re~AoJDrp^16c1`=bw`0hH%i%Om2&K9XL70iSbp4ImEv6|x*7&6dZu>X6!YjfyZ z2@MiWG%Pt}E~U$wDx!pKp|BsD&Rz2%)%50`&<=J-8 z7*BJbt&NquzKqB57=r7=wOLq2xIE~Y@yGv0xljlk_Y{t$9_`RXI#-X$-XvVH^(>{X ziQId8qBDQfT=fjWwX~VoKy~`K8wKad(?(jULWLlqVKp3o`E=CcbgB%$f>D6JWa1cd z^)bMyso0IAc*@ER#&F(IbWQz)=w4<0J%f#;aE=e^*I=y5U<17QQ{=+e*!QY>VFa7w zOeP9fOc#yaCdflsvn-hlIXn&(*69&qca3N2-~d1v<@A^onjIpkvO17Y7h81yU3p4;Sw9ztlYpx5AQyy=5JVhz;IpgE+dLP=17;uH z7X7WE41pS{os442S# zfXT`gKv$w1h1(sT`%1Y1^i|je?PVP59&clXt^LNH=AuPoH-xL5ce$FZq+s;Rz|axa zBe8};WBs~b>ll5I-tz9S?&Il61s^;L^rXG8oPVl6=A)|%v!b=OVKCykNr6khU}Im( zK~5Z-$oe^jCN)iP^({(LJtmd&VQU$wmBu194zqK@;0+7!^p|Ij#Z%{foTZS2>dj$${H8KDNDdgc97+OdwSnlYU{HqYp zV9RsaYjr{kY#TbG$S(03GyEfROct>3ul;oCOCyxn#WIfVl;~c@+>Bmh1f{Agn;&CD zP~7yOV?ZJPI9h(Diw0B%QqfV1w%7)f{2;(;TP^?5hTUAB=JR4h+&A6OwhS6VM%JYh zp+I{0*{KFTIm27X=QqvAI6r z|E=?RH+7i$>FiKLwr=7+`jVx`*0KKe+uJnG2AA8=<7fp4b%HM$MCF1Dd)+T?{3sEW zyC|*$IlGZsl?r&*ur6HouxdYRr(sVA7XNe2>n0r;n78 zbgwWO0HC3=od+;U_W zwv4(aN$3%V{VVoPi!8DY9^NU7>?sLJ+zKC_Mk#THBGf`}Jka*4)js&G{XqK8-O8hDU5&cGY7p?s{%As4Srgofv9 z(E*g@jq&ei;w#VM%Mn3vC+xv*BNKtUAho-v(RVMp@BVvrw@s78QWjWix97(Nl=lX! zl|%;c3sB;rhj)mEaX7gLLFZfK%8nc&DN;p9=-oV$i)GjXhN2t);5YE_+M>TyCDEuN z;pdMpVoX+Zitli8EJGxmWh7Vko9;{B&yYbXnVZR`nJG@10Y{*J$U9fdW__gr@(q#i zp5Sm%AWuh36F$*8C`{@>P$igIffG56r}$Gve#nPh$5L)NlI+k^oa6mT)slZQz8r{( zVJwOv;>5}kGGE@;!M>EV_#0yFk!I~xXF>LWyn2~*av2#~ny6c!IF1vrO@W=e;i$`8 znVDS71zy^mQ;X{&sRgKCXj!N8suQg2fp+U$s12_!GB=Q7S3I1&DfsgAl^;W@7YOc= z=W)oH6qK17*Ka7@lorKAeP15wz(hR?y+3g$U5z+pI_>`4yw=zlvX<`JCu}st@r|$h3q2m3qlH0M=M7Ug!EGi-*AI`KG zM5@L4YsU1nGVAPY>I|l`m_Nax)tOOGagTzhGWqi%o`Hzk-q#V;@g2^;`});-j(lp zKQrD^kz{RH=Wk`^Guou_Jpg$I!iIsjTtY_NgVNnz1xgo40X=Wa!eC--;{9K5KN07s zr04N`y*8+!Ur~8_LItF=h34K=D&Ab8za-VeWXrHpJLd(DnTmNH5P6_ruFLswWS;4* zx2UGVdl$v92k)3}h(pH3gKdN;AC-i?5ej9NpaI9y?-rniN;#_`o_J`JW1*}bl|Dhc zfRd!-k6;OCMP$jeES*_&31OjbNi$Hq~fStez+{Or6m z@r~NUx{{~OLLbyC8ij=F^@N=--eH)_Z#)2dE<@296!aZyk z0p<_7%!N`Uptv`rOBYBATjbebIgMf^T}5>jUlmBN^qT^;!7KzOp2oF@?DAe*uZLX$$w}O=jU(^ALU zQDh4M9GA7^Pd}PueKg-Ix6rS$8miQ8sTRwka*c-xh<`dlL7Yjcp4ir`hSh(t(ffMK zk9nPRPn@!^J>_L=rT1lx?@*n;Z7r))>3t+X>;pUzu5l%;Hs1UczK6!E|74L1Z4bJ zwREr1XRb27qIGDFYGMZp2?Wk#Aa!%KWT_2qJ~hoPE&X0kPG$Yl3B1S+AO=z$@>C6? zCk11|1N(DrhnHiguxeh zb~_o_7t;CmOBSNl68<}cQ9YIDWrUU+Va_4L96WgcdrdUS4GZ=OG44% zZ%q&`$p4pfKi{Q%)uqbXt*+FqY1e)2-0Ng_OTCACR>AzmVKRecdP+U!zFjduCsjq$ zjjIp_>1QWTf&|`oirBSpOee7jTv6 zSp^}lBGPtmU^M6pQR)LH_HiUO$q)*9Y_A?ObYqnJDOLL^S4e?1pH|hUbt6NK<%+eM zmsGT&Fy?z5uAVJM2`#Nt{kOx^5@vA82xz--E5HfqdD@tn-I$bBH!xSeW`1DOcZ7?p&;tMg#zbf(WKSz{rlMcu zM)iP*;}BUR%`)k}DrJ9_S%&ZDRgtk@!&M>rW5iUWB>7{P^R*JfNRM4IrGYVo#Awsg z(R)MveUDlv2U};9M&8cj8Hqq;K_E~y*(ZG@BmxP`8AL36GP?{vv%_;6emnJT;*V$% zj2ILi`KCWx1Tq2r04Spg&{1ALBwNxjhu>Q-(yvsX8(W44C>N-75@7V?fX6HuwEC-D z#IPIvH^uugx0714SSKv*Pg)vM*()L$KRYl-jO!mv^gt&~7EorQU)66{DMwU)NI*VF z0D-8$It1{&YsjrnzCY>q3(dh>S3`}9!`GKe|^X1)-nuujYCH{nOO4>!Uh*KMC89oh9kPM}9gvo9kzZwBL&#U@kz zhvx22-+jCjdiedR7}fsy7UaQ$*icy7e)4Cw+7mUcCdR0&ZE& zV*S_Tvi91m_galq+SvCybE~_R_bVfj)fC%cs`(!td&3lUqy7wd_Je_qwRdr=DADza z=UcuD8xW^`u-aNe#9puBp|Q!~=BU#6^Bv)Thu{9jP+ZPY_4}Z`F9FubW01P*O=NuhH{wO*;sv|$X{BTH4!(z4P;igVx{0U2wp`?H|n?l$%IZ=qrc^R zetu0l^&sqN+n*p;enL%F#1>A%d^R4c{M;6M8~o*u@w1-^&;EouAieJ*JKulP;W*Y? zqP?&`W7Ym+oOL#N_{){@!sO-&Y-MX+8ObL;KEZOv@%HzFkLOW*rv)k(;bUiR0jDX+ zF!%Ny@PipW!}F-IqvsTtPGje!Kh6n@XYneR_0KNJs8(v)PT}SIc1suOgp2NH?lqLZ z0|;Y(^MCwR{@dzow89>rbBE*V^%!mD+rKjISF3SX!auHtDE~En{6p-t0F^iwxPN|` z^H0C}AMk%W_nH~TE9%()IQNVutD5n2qW0YxCfr(-1SQ|1v(>lHCCF7Re2std=%oqs z7EA9)-Z03NvYiUoc~n3xZBIs;Df4EbVt=YluBeTbk6K4Gysa_o#D=eUKC z+q3-a&Z5|x^;mRrz)aXSayU@;E(l7lgn6=2ximz7eq*$p@x=Q-&b|MK3n9Wse|GCr4+{iQ<$RRo^6g7&TDgr4#=Bj?LM#_SyOSRrk_A2s`F$IanAYA~C=1A3 zA4<5{*pvWZhL)|v;vyTa;>N1qPDK94x&I5^dK=%;HvA~A{UsTMxFdEaF+?Q9M5ULa^5D85x-k*3uqMnCUd@v~+szUmkVN}}iOx3~!fNT)TexENs z^&Oeithl(@zf>rSHk^2i{gErN6Q@w6R|%U>5hEheZ{1{zkqtIjkQLs|6)l{s9n=p} zv*MC6l=&fCT}JckBDG2G-EL}uLa4!Ut2{Aig-n`9q!jdISq(IHoA7ApS3c)ufir7B zeDo@#MELba)CDr@$mSFsvdS1_uu8;X8J+>k@`tRVbFFa57!Gk-Zz)51cd8my=JC!$ik##bXD)A0lBmB(KQbiSDY%yCnV+Z0hg*m(Qr~zHo#)~704n}j zAW|UyStP*uJi-^MO7_ekY9kAsSO%Mtc+?~75Me!6S8VUca%0atAWMhveiH7Wg zj9qeH+N#hIT60U-IevbM^X>!{4)fR|6aZVd6TOZNCo$oKxV)zlVDTps&}4sFINRW! z70_1hkok{1c{wUVOx&41COCDwAZ|hZJ0=l>1>w-Jscj5FsLlI%0N-_Of0VgEUm7|O zS@Jfroy#&$;CWg@w{%;dNOW_lWL)gB#nN2vGm&ua z@KLCPa-ZP7T|F4R{bwlY*_ji8XP*zB*g6P{iqzWsbwHiqj8Ms{N~kUQiVyn~}0=%g)Id*1YpgkA#?Q{kRoOv9MWRcggf$IGN990f_ZC(lLlMWDp+;X^K2 zRSc6@AhKDyFrd?PZFI&nBhig3q+^a6XirHBu3BRT)AqAAOC$#wxFGC)QfG8aD{a#{ zl9<~d7=)^!Sc81}2ICH%ck+#T{)F`xxdt1j!>9(hh%vMpd{JzM+^W68Px)ZSg1*EPB&vN3%?YS4b|U8B3g& z0@2V>1tp)-TFS^I>9ojCP*T@<*qHabhu27lNGByoknb2gfK9wF&7&!GL?DDr;;1er zDz1vQgQIOsODSk`_;^ZdjY;wwS$TkwkTLw|1-?u7#NE6{kMvc3BD;7uMH;7zMs|DU zNBVk|kPl;43EmSgCFx%hyzW(~dDgNYb#$@urc|h6ye+G!A1Ra?!|terA|8lo68#~| zcDh%=(XF@sW=YN4x)1z48(&|~pvRauOEWz@SbszK%F`-;4d!+gRfUj8X}n|@n7lQu z@FA(+XN1}Ih1gW{G*tClhV}Pjzrf0kiamuGQWlDRnL4IW447lt?o=J#j7&ZB{X%MA zqd=cE32k2=t*XLogV>uq@!_P*i<_Stg!1SP)De#04R#)o@r3$QUe>H*J>E7P^$}{X z#cBVR1t$@5?T?Tx*AMU0h6^?d;J zodDJ95*sw5FK&b2I}&J6;*jSIB{SI!ru(L96WHEs$v*so;o%C$+H@CN+YjR}Oh(bh zh$P-qi5ES4*1J0XxhLj2M2CV1k?E$JHWvBMzmU1l6rX!c&>__6!cti2zV}By7mMc~ z+(bg#3%X7ESr!2`MN0(_x?8Ea99b*<4@3Iw{oe=9hNUpJVvON6qNbdrcHt}5LK+z$ z4S#RA{`5s}M)1qxuKk_cf5OI5#iy!uikXeOAF z{KjDbaRd2J);>E2DV0IQX}rOq1kdMBa)+aJi^x)j?ll7J;-u65a6hK%p)do-d6fTQ zLY0E${XXI-riVmgtOXsg??7}z+mp&aSAi=07eRf`H`|B)0Lvl=8~-kkJ7alP%uW=2 z+KuPmv#bLzOEnW;D+aVZY2yr}%&UxDJd2=gYXH+o&$f^T*9XuqT%`hx`>%)f0?}ON z#kE_H9SF_+4ko{&WdEA!j)l-Zc9cVK0d`V-VfH@T$4?IaM*1FY#)vr5zjy37tfLHz z|7+id^8Z(=1P4tqc_RvQU_4C)(WpGJH!JXln~9ewj1Y&X90h z6{DhtAOXlVwrfs&TDJDyQ)Xfu7{S&R5Sx}SBz8O>X1>(<+$P&o>70v)8-w4eA(}&A zC4!$<^rcHk#k5-}j2-LW&z4g-;z0N)#HaSpLtn_q;z*5l)2d=~@6*kr`8bgS|G=5L=!#P*fU0d?re;aL*2+z zi9Uk}XKUtEbejvy+qU+Io8u&CHSFfK95itQ55Y%{0#C$=41RZ+8c1j>ku}-kZj?rA zFy4wbCQ3-Cvwq)TGtm>h++#nl9lfpX577=}?ThOF&?|s`sIKbDszPeo+2Eqx1%S=v zK1MgT>QxajRm5a>^?Hu?Qv7Z=WYt0k5g!PVHV0zCjJKl3F^M`!M|l(rFyb5+jJdKF;##lz!3lY&L2`}Kngq*j}=Gah>v0( zXT-XM)QFCEsrdG}nychP;v^xcB5|ORTFa0}@0LN$5;1#VW7?G>iOcouXRwlNAz115e|6B7b3%;_nDg@Og5k@#3SB#uk`#@pKN##ckBb~+=ii2558g*dcY zsNnJ1Ff@G7%(~O8m6BooPIL-?%aDLgNV6t0=TrruR{ssI-6$>Q}Sjvxm#2D-B*dWbhkd2J` zysI0tT^@rf60RLla48YUfJb`5vx+d`oH#!e6uxJ4;|$Kph#~Vtfn@MtEj;8N9_oe% zkD!SB@Q5@#@nd7eJ3MKRF*w2)G=itd!IPihk$%QVIuj~#u9&aJq@uly0wz?vU+H7M zGQ^lbC()J{vG)XU;wcyb0PH6K7dCtOt2+)`D3uh*XM-3%tCa{2Lvdt)tc>CO{bPUk z?_yAc%YxAo_-~>c-^5P7-Gq*d(~V2;j!VjnOKFW0r0JT4nEF7_C#qzYC9 z%;Xqf-N%jJ-WXTj7+0SeJ-jlCW+Vy~fOI6@=|)E1@kJm|pDwbbct1<#)nFaBN0uO{ z<==N(h>VFg@Jym6OwdUr-K5C~-c)9iRBO`wuQ93HBuuN6q7+XS0{rpBB0?rD{!ZAv z!{38WGDqC;FE#yTFwy0R{!9%T$$&^1;Dn;@>gI^&HDjGp3N`5nDDS|!;9We; z5zPYitXv?Bt-~_)x5Z-_go|8kxE$Q&2wf&Jb&1l!%Dv?A{C--agG;gs>M{B>a-9t^ z$X|#lR?tq2uqwMJ7qXBHJA3Dm%^yQ%Ys+HWm}DEfFkE_@#8^QQBTn(?#@zTz+y272 z%QLjYSOx)JN zFfI^oIOLNr)7)5o@;S}OYVmFjW~)c>^P}b5D95W22l{`ud-oA|Hg4<#N{>7gIn42R zW0^>KspO?Ym$9rHiU^wmY5#U-RDT8jZ-upRi3DrIuWU;)id)Pf9lAlnO23@A-^gyS zW=9n*=;;_`9OYT704G@^@Z{#vr8^U2S4aHT;+E~Z=t#J`R~2q8t%)vgp@HGGkJ0@t z)_FwIi~KT?YuKdapwIUYzgC*nSS=1Zj~_@+hz@LhkD7JCamu-<6&LZ^&+xggsgKTR zJaVSLs)Z98vdf8Tc$?Np?-AHHSNGFqEmjuMEr4#$18x41i>>Se9 z-D=(UQ&8AXAc2?Bp8iuw1@5|o8@`JhCT&~(#kfFjT$ktw+mv&n^rD;5OH;;`=nU-` zT#rYN2XVQF{h=EnL&zg;5m5(?SF>*W>E`y3Z?Tx$Q?e}T^DK~*hxQ;@#|C>EZGK15 zZ^!xXJlDpV^5M)X6I#}`HQVe@H9W!v4cz30o5q!58cV{}cMOd@e4Ji#FVxx$VA;0prJIgc3oB5!7TMhj^$hp-emCV_oQ`uGp9>6*eK6&jj@3Wt zc0u;O<~oBGSRl^#7Oxp@kJYlOson27yT+UDCH5}3N<4I>syM%|^(($( zakKN*9-)SBKMql&mPqt1V%CNJpiz6biNZ8Zn~V&B`KgIWV4j{W_Si7O)en0ujvjRJ z`NTR_JP}40`@v|gwE7R175{n4Jm@Xz6x^{`Eeuv3TRa?7-os;e&;ly!PQafKY{NT#h+Z15uGi@NxqrdS_y+zsO+OrB(K_>owz>U`S~Ny*V!ZlDE(U#ckKNubYU+b#wC zI6e^Lg@-qwJNLvNROtLj2mxrHKVbT?|8sFW>-qNUUN0ce8SvbHHmXHzKa1)@TWSl32j}!SIT%VI27`)%Csf|#@XM6wf5Bt@f{zNvANN9#2}i^k6IeBC4iw)cen~pd zz>vLxsj{>+LXe_<8kXz{dYo`_1o;tu#v>$$yj<^B?flyeerV~Qhy!!~fSI(LbKv1| zp0Dl@p>#4|={3;;{jUsnUfrd_r80rpGos!Yrrq;Oo4OweQXym0vA{Z_Ufr)Ge6KsD zV%js|KVd03yX}BGgaJGPC2l$c1ejmo94&nPX{WTLJfQaFNAj=~) zh8r`nG5iP~YDAb*u+Z+T4tNiD_t40p{qB+TGMUE##J%D=VC)IGk>H)R8g_iP~jZgWBsb4 z#G0`6p)6=zRudOam@YRf6u|2}Trae1@vv(h3vPp-8-F~*$h8)Ng9vQsi|<>%%IG)n&`(nkc&eQD{D^TiwpR{0Q=vIc#8`k1CwLa?y1@4J2V0a5C#C0Q7MH1jEnnrM zzo}Xwn5sjRdDx?=U;9So#s#Eosh4dZf4o!ih(|(Awqwm3pP4X1U5yQK078~B7 z{1ybT)>>x)%TD=0PFZXN{AS9D|e9$wYFs9d7u`now z`^`vZ(8l<;cR_z`1HiAbJ`F(v3P7Fsxm0_L7jF8E1jR_YslOR5hYrdd&Nn~#b@=y1 zT>xM$AG}~&uPEh+vd)P09yey%%A55X4_45Ynzp|H^+Shi=An9oU&v&M5g#z zqsACg`Fm#T0AmzOy`WjW_0xU~yNE_~=h&SuWv;AIeE9{#eg+YyLn6fgaqj7MVc7v) zWoh$RR{AZcsKq+I0$o}2pA<^h#VNFL!F9N)1oOXZuVa8$a8-K3c4Hw0B|6nmao-Lz zqan)5O{vhC_{W%jVV#?TOTx*j(BFAk+QfiUoCriPkeWBuN1DgW^JTi_M(5L!X4InS zLcPxN10>RUODu!D-L}kcMlF-s4P_kB=Awcd=kxBOW6eca03>N)lB9Pr+EmSZ8dgn3 z{E{tAoXX6P+~`8EG=Db6NkurLNL|I>=HB+B_w^+F`Bk^Jc7tnkqctBtU`i?ZPzfD$ z{;10qHX*|e1d`Vb+z=MhgG=tw3FKrjzl@880OJ@cd z;=R>o@p?s%Dq1VhYsHy`bAPKZ?y*0NyTbM+UJ>eH9Xx5-01bKFygH_xT#;4Cr=N42 zQihsaYDBI)v!(p~N4?UUW}M?aKR&Z%MMDU0kCeK!+IW6>Kl~tmbK|Bdm&my>$%}aA zqb@f;6XGH9YEV4MZI+1InD@loi7LG!q6Xr{w4Ws&Y!A-o3`N<0IGhUg@=zE1ZLtak zi9Q)Q{C-$0%AKTlk0xF>-*Z@GOlR!38f#9!xh8MyzPIc$n*TrqC>JQ7YeK{;{hW2T z{TreWV_c=MYbrv+NRDpVdrYY5TFotKmPtsw>FQPA4df(PZ$H&ObfkOs8u$`K{?>N_(1T6mlR&ca$LM z-{0NCqt`9n#cvbzMfp*I%!2a`J;vGtW`VA3-XG#a4|DPj9 z;C9c+UBMm~;*Zu80AU=OTTjmgdf9 zDp4wtc-r`5a(@Iynh~<5-Oi7A6S%_*EgfM&3hK@}^|KVTU*9lGL4*2{aSmnqTT|N- zuwE*yBfJ)wUUa+mp@dN`L3$8;_h;Yfz3K?r0bK)%K%8Dx4R2{FRG3e2xZO#B;$r*G zGr%#v$uQZafYps-fsvJFKkDI;Rd2k(Ln5iXj&S>@ZYIve`hm)>=^7@gtfr|XvOMc4 zFQUnXq&Z(2`0euAEEhnrWp@h==v|ps!`?Z1m=ellAwuw(K?$1>QLIsblsVgYtKM=>jPFI^4Rli%^wKJ>P?`uZo4G z;%OgzgM^Nu^rb7SOkd^!57PBY8D zyQAh&iD_2v-}f_?5=>venJW4TBMvZOVw&d^MuZTNpSbQBp7%492=#>VrFJU4SJ0(* zrQ)*#m^v;oLa=`MyFTTpU@i$W?6o=39fZZ&6atTI=Du*3-N5XQ;(=%$xVOxQJ1S% zwp<)VWWK`E6)4Ksg?bs>77et#x^HkJaPBx>u)*8>@Zn7xnoVa~Spm$@PlKpz@We^z zz=9}C*F&4kL`UX-{dbfv(1}RLKM9Og=6VT7vagX&^s_f^M)T9srItsS@HTa$!>&e_; zy}Wz;E`(DpH41^4fw9BE7kAodXEsksum%q(t?_7zw!B!u6u$$XALlhPsjTt4G83<} zV}OwPKQ(Cw!m2F_f+_$Q2B0#n=h6dW5fb`VM8l8FSRLnIVs6cJQ26!d7iYQOs@M{J zSTxKe)?E630nI=%zvE2KqJ&k_JLJ{IcEOFJf@}DrA3XqoFk-=Q#vY(xTXl&RW&zWR z6CEkr*6+s!K5#yZ#m_14Uy~`PZ;XO~o8C+|)<@oyY`cUQ)p&tCZVrai7&@j65X3KT z_L9Q}t>|tKc9#*C^p?B4-khe133zx-Xs>q+4}fSF1fX=x-d$KRFA6%O0D!Oqpa+31 zdrZL>2btLaV76s@JLZ{k^u5jyGq(wB0D>b!&0fHyof#gg`17Lp8X9`8C#6-O@}1fDM3`FHIZok0LU1O0W8qND9Bs=1)%&n&QO%VTUkPFDTQaJ)JJPBQJvg z&W`BFDx3rkq{H>thzz;}5VS%#?1MF&Vgy1Xgz*h+xdfzPV>S}bH>83|qypJ#S`&^V zIa;3w9)KL_!VfitXL$hxw4+{tWVDGSzY*Lo2IENx1VQkFK_G-oR6#eSitSxh52%() z7{GVA1P#0a2`D7y6%#*H!xL4*K8R17wPG)J;UdO_Ai{-QIK?fZ0DEzv07fCwwV+8T z24gseP{0Hg$O1ahgE5F7B7MP?j87#vnoo}6luSV}aD!t^0TYs>ozZ1ozGFz@WlV5K z49sFJHU$FI7jfz3UfLx~Oy!?#;eH+CN%Z4C2IS$)WK3~DY=~k^oIu}{T5pv904f1M z4Cq3XttFQcq-%5_MT+AJexOT?;4`G7Qji$g45k*w=7)UoJ4fR0O8;h!}wu=!8lrVV0y~ej)pqA^S)G_)L*Z7=VdcW4Yx85}-pp z#6$GuCovJuAecidxL7NggD0dyJ2)iLO=N1SW_Fh6MlgWhSwb7W=4XxnsDZ+xQUc;t zP7;UCSnkP$5*&iKnS{h8CtCESKm0>Hv?hy|A>mv@$8Cfh$l4&pP>xpULmX*dA}H{j zLR}QbdWI2u3R44wffvaH1NdA^ zr~r=H1!tziKdb_1E-IrEPB<9ZM!-Ti000%7Lo?}UA66uGY8ZX0NLaw;h>q%|_Gp6Y zX;W(isuG0}BB2s;3!k=60Z5}uRNf>wC`+IMEeK~=Xv05L)wtTt zl<)v7NDM6W2uzp)H^@UeOv7wE#02=lI?Tf{_+}CzD=S`Srh*6(P);*^=YtC7sm^P^ z@~pJtsXPvBP1GSQ++iN>p=5rQ9Q*>i#)NlO0<~pj9OlI|{DU`Stj4Y?OjH9QJb@HY zLpdCdFPOs@Oo29NLrj?Fjy~aOa!t)%(?)s)w3h0$%51!Dx&@1~h>8elPfjulSBH`IayEW&rn^ zullYp`<`$5wlDm~@Asl__sXyRvTp`t0*dH@1>A4@u45CFFa7#20SoZ^7BB*P?*J!o z0xvKFkFO5o?MyV}Lq?!t4XZFJpMx=+#wFJ@4u>U$RAs6x>AF})!vLeGTcj8|JG&1-`rTH?l zB)6|6U$XjUvL+jF{a$he3vErfC0rJRT$V8+@jz@mF6HemOIUzQC4pT$!9S=29LI4f zE*j&N=^dMc8a_nyPA>pdFHERyvZCfO+rUBrPw+_J-@TXe~T70^LChyqLufG?c?LnU5r<_ZDl7W3SRu0`6jS1dFB$rW16 zZ8X;{KF=)Pitcq&phD-igu@l*2zjtqjKM$XgE%(~h73R|%!5Dp!#$)K zO!z`OWWjo{K*9llFO);so^9IJ^V;6?OKXKb=RyRKQ|cC`H2*8LwyBCSMa}sqe*)+l zPfEgGRnJud5N?DTqlFy&gG^rZdS=iAH~|&-u1nPLKM-5WvI9LJgEP|e=OS}5!*pxt zvo06_PkkzqwyuxbZNGeROuT4}iouN5=#3_H#ck_Jz;Z2gWmpixKRg~(XKQd6bIb^nSx4DYfuz)!cez_!(JYhvOfZY=iSh*MM^=;~UOG_%+1o`j>yZlq4?r*t;^d_Zg{UQFyB)bfTb z{DV2LHeqLoOOG{KANG}2hw0ksQ~>ZU=JpZoHmWkkubPCg66+gtHa725a0c!nL@jP0 zL-0a3!lw7JimIAIHd_}3eKtefHa1gqBx$dyckh&ahxbyLE4m7Uy0WXg;`ME5*Do+^ zOB}$ET7VWXOjyLiKe&Q?w>JD0cuwCphT=vE@QE|vtbZ%TE%L5_=QmGNbI>*g$9gQt zCM{zfm@+hUP1J@rhs81cgJpLAxP$M8VS}y;Qnyl2fB@xd&pyQ!PHBt7xOPhUO!T(m z(zia*7)>xhQa?mQmjyTcLk_d6N@4?%-#7EebOB5u35Y{&LXSh-0s zuH!dilg(1L&oYE^( zTwxaWS%`x;nwu6}!-NUT9ss1Ujoa1`AT&%o^htE9S9HWbsNJkHdaWDEbW6ICC-zia z0bCfuKQD!JM3iREIj6t>xTkB>vA={p%<;|Dv4=z0QUBaV{E|dB#peFQ!eu+8G`bhQ zHrpb0HEYG&=E9Ipb5dmbC*iuc!!~6z#W?8l&GB-x-b=fBV5dMGRC2W0!kUR9!cvImD~H@bvUjm_j+9b2``iBxS)bpmDVK4aBVgDCoFS zq{2V6L&=x<$y=wvue@Z}L#D>eV zM4`LJHH2`}2mH3f9Klz2#25Th5I~#br>`T$%AJAgHQlh^I-TG7yTim(S9Nsjm^Q~m z5d?l&u){y}aom^x*W7Pix7+;9uX{^Sx}}deQpo((J^a^GWxFR)*w2o@YY^_?l2NRH zAW-a5BzonS$?7*^=BK>w<9$+yJ3QFSrW1v~p}`gi-gnph?%O>J)<^-0L<;yqINXCd z$O3^q1QlFEJG6r}$ofP4fIKk0n1Ta7d_x#W$>mFu3&aKl62%t5A*}yH?c4tOyI$Rg zZq!eCQ@pJum_AXUn(rMyKmZUpkYGWB2N5PD*kDWpg%2S{9LUh2M2izZ5@g>|bfg9Ed6Y}I3x{3fAaI4mCU=@C(h_uoNMWKg(9zrHnx|FF! zRLVd_w6TT%3Bd)lY9(npaKOKRTfv4EJC>W|LZuc~!dmB_SR4#d#1Y4GE;;BRLyo<*Ry3bESm4ToTr=Nbn5e)zp z%&`Ih0tM2Cj)6i+$Djy2D6=C5NlbIAEh^!Hpf_rn1*`(RqC(9(@yyd86Oluaxgo~_ zG%P_0x&j_}t^nyp6wp8e1+WN(G)U?ur7Ti~iewIlbfOSwNr61rrkaW{*oGJ?syOBw z3;;j|7J;|~z)LX2ENB(4a79zkT_fVnw}Dour4|;pBJH0Pc}-T?+W4%^&*d&PtWxWy zy(k7~;ISm67B4UZjjAL?R>*44BiF8I5z2HqH~!(r-GBVyM>h_%u_j4@3Q1=|03M+K zXAS_`ahIQd+ARbC0})iPATrIIZP`1eC?yPt5U>!#fr8Uwt5*Jz=i!e*wyRm%p7l{& zN>8RXWs4|i2A*aP*w$Qv0@wnLE@BS%J#>}gIVqnDQdc<+pePy&Zi*qw18uO$fFM!O z89<-~=J}Ecqf?OwiWC4aW}1Pti7la#Lv9chWl)KTO>hO8Vg|50^rh^%>E4QL$4X8P zXqi_ox9^B@fd?8I`M&4|G|sqK=Rap&uW=S12TAA#=L^*vA6Up-w;}NHg@`ALX{UvP zVy$8yQifP%s0HhGum@$7u~MNM)F_Os3A~b`_1$@I&fz})aqI8&B0p>I8jCmohzxk% zL89l!LGV_IK$9=)c<-vGe)yy&e{a4laK%*zfxyV79d@p%!k}0IkRzOYzL}Wy-k1AD znNE~5R%-hB?;n7>7n3(2ZO?H8G+y=u5(9T+Yboj>Ko@RC0PXDzfrF~x;>yxJ|3w6V z8-z<7aI-IrfMOOwV2UUHfea6>ux=f+ivY)Ezyr$AdI)5I%lgv5#wh^}W&iEv^0qpDqkqZ<7IJI~KQ@pZ)CT?+AOoR&zQAWWdiUm+Hf`$p0 zf*!#TriNoAV-cn0Mhr$KiClb$7wy=Tr<6j9m8ir82EvM3q)jO!@Jb&45s4=}o&}7S zf@2&RcSJ)W3X%^w00g)28zRbajsuJ&BkP#RJ^fCUW68oV@CT7YRKj)u_(YtRVvT=v zqm;FD&?3#!NR^54lN&JswzO4Ag)pIqfNUc#q4h`|auQRawB`Ru`OKy$KsOO#LM65^ z5GvGy79!k8SN;(SX^xXw(WHzn7Zb$4DD!zVB!G6B!2lyZgi(%~Au>(Y%M3cxmbfG* zSZq*7Ti=2lGdJoDLVWi`85&RoRK zc2ZQN`z+}*b9&Q(JS8d*;X<1NNsHltWCLFLf>gl@mZ*Ydr{_}Y&(5l-$lVYgy3pi2 z5yHd76|kpG^(jcx#m`!fRjO^kP2Xyl{5BxLIvL(Y;Fw4#(PO3y~fjU+ZAUU30zp}RzL;w^Y-MP6i=YTJiYU@y7YWv3q+>He;{JWe;91ZOD;1< zo?K%G3zxF+AaGJ4BiA2t8O4tL@;VPaW;@;)wt@BIBxXQlgi0hB|L6yE>l|H1BXOd7 z=ChOwvSQs{8336zbfI_YY2rS$pE<7c2vm@e3;5Chk2b)Hu;%*^4tPbJnO5?qC1T=x zhMBwup@1{0d}08E$G2~dGN@0jYV_VX!md`bAfUp5gsiy|ObCv!s`?OFSh||N7BR3R zB5XjTn$QV}(KAY*Y#e!EyzQ2@z0LbsR`1o?I_5EMw0)4P`q2)86qcNH?G;j(``7&j zWv8JX?TF_#Q71l}JyRTUeD66dismA^ZAn_#DMJtl;mxB3L1ct0#21!6G{c(+@`tFK z)Ea*_K@8wBT|hQ^XjlTrGY<4rJC&R=ujNx<_X}}BfYz1RgQRt35U+d*=I3_!XCa>N zd*6H@7(FBLEC9hSNbu7(S1_^LLv1o&J-=4}7`Za!XAm{enhOUNmc|k?3Yu13$3{;G z&0W0pvm3+&3mhu(!dq{Nn_b3?=bqXZ&3612zKG^rCz~<$G+916at9kWe{7Na5V$hq(I&0X+3; zAOrc&pZ@i?|NZfw|N7Tp4Dr|h{{b)n<&XdTZ~k_my96)+|4;0Ys`;GH0hNvD#;N@h zsT1C=2M)pxXw44XEU{9+E97SVL=X4>v~T%nV+F>*5h7s)S+E6N@C9Ko24&C%9U%p0 z@CI=(2U)NNRj>t_K}H}!2ZeA3?Enqd;H3m_@T_mxB=8_Y!5id39<(9uJct4jX$0Ob z+z4U`XzdUrEujcvruO0GM6e1;u;cPfIrxte7NHH@@D1TG4&`tT=@1SZVGJ6f4)t&k z`OppTFb~}@6M||N`mhk|Fb~oI4fLP}&@KW|4+5QR-v&Yq!T<<>z!mi230TMq5$SA3 zF4hX-1e$L1a!nxE*h0g8v%94`gu`X|Wb<@fLA07i$p^#sCm>@fU$H z7-x|eeNh(w0NI@34}@_UbCD1Ks1FbNuMwH>5wUO8B!V62%nXwc=5*lgQi&j1iq=kn z$h0s7ykZ+vaRj%q#L_T1V38T&5gv _bMn=TR0hfq4?49^>&3@Bj_&U=gA*2_LW; zPtV3Au^<#+4)VbXHt`Jc3+Zq}0t|vp{Ad%1j6((@{r*9V(oxeOa@tIgGTxCNP0|+c z@g!C99uXlL;DH%bav6(|4fNm+8Id5bFZ*DP6~h8DH**;$GdS(B7yaM|laV-S(H{Y_4`eYkmvA(9@*uS@ zAr0ahhT$Q3)7%sQ{5nh^2Cfn?Qdk6G8@ytCbQ8Le(l@~ZIF<7khx0vgkr?w49x_2b zWpO6;U>2d18cCDurc*1e6BevM2ciHL{K2&NGApBN4&H7r2g1<=%I>IP>e6#DpTjX} z!#(ly7UQ!+X^|KI1HmO>50$&{NW#1^Fm*1JvEdh@eoAe(>R%QKF44e;2|FNQ9e7<4r;MKAyGOPZ%gsa zI;$;5&CL^GXLJZ+HgVw|Xlj3q^hg=B_D0e%IP^(n@k5^!5aIw^G*dqN;2-b6IcZT# z{}VvFbWp`?`(o}*p{oV5upq*76V%}!&H)VDbg_^$P8VZN>C{e{6cD5|8q88Yi*OD0 zGfP+0KLeCdsS^#sbnV2{+$8cBJW?P|&W~_G9dH5fD%DaI_3>%@iH^h zL>nbVP4y=KUGzo0)LE;u=z0~loZ#*LWgwXDM-NI1cNMHI)w(buSUYuCiFFo#Fd7s= zKJ|e5u=ExMHC0u$Gz*ngrS(-|b>wn`AS9t1E};@QL0B}hTf^#G$uJ_s6+}6;Lj@5Y zFo93+pgD2zUFQ{E3zA|VuT>+@UVSYK-tI;f;2Zv-9xCAyq*7o9c3Pe6SMB0pJ2YYO z6WN%d7>V-_)W8V&AQvTeRV~&LpB0HP_VzS3(8S16=gSq zJ-32o@zZ7BGaugp5M(wu^8gLfKv~`ORD0IInsv8Gs$SF64c=}F7GS3SA!+@{6@*1A zoc5;w2$nghRz9tEX7_>_$dxknfDO=~U2#@y4Ygt?R%fT}XSok*UrXd*2Nl9W;WW^X z{xzoR)~4=uIr8>B_cl25kxKveEIacve=%p}HE~mSb(zBB8aHTt%>rQu8+Z)>xX_PC zc91exa~=00q_!zKS2;hIG8KVDhnE@q6d-T*bPacBdG>IhmtH5ZcNa?q-p(AvKp;es z);4T+QEGG5a7oK`7e^OFr8FK8;do`z2uqcDnH5!4H(uqp_82!&Vb|9rQW-`-Ai~j) zR)L$m_o2Yo9mRKihp~L|vv}bl8T>$fgRyH-R2Wfrew7e@S(kp%Ha)+fAFg5KzR@E8 zD?t;41r!5#dheIGRCX?cmpC0bCZ*IJ%(8`bF>nWW87H`cEtrCH(i%-TJvkB`@U>|H zz$tO}pmeo_p^AEgElK6HfDO2T5%@h3K~L*6itCXN9u^M(H5hLgapM<u2_MPYP| zRWSn0^B<^TLjH1JW;6KUIEhbKB*FC}Rya8Mm>v;ff%X)Nw^k+f6CS&GhX>h|FZfXF zSBd&Ej|QL}KyV=b4R&JlQHyMn`K^+*GKJwHlQ(mdyd^Dml;br zdJEZ^!#HXYm6hfApS}QBR=^;zZRCUi0DRPsfRs|Z*;O-?m)F9VDYKlHQJ6#2ikA_K z(EtyWF&^KUOHUb|6<0u^x#}9A8oWX?41xo!ncM!g6bm|I5BicVLZKs*p@Z?9Kbe?S zGI{R+kV#pPH#(J3S%=eZm9=yIZ~&HxR3XSz8TQ$hxizIbm{K4HpcT;J z9<0GCn+c)MBC5l3s&!GOQ4*qo@t95Wq76BRzj~)JSgc`g0~R?S-U}jPRRbV^{3_uU zR?e-PIw``y71*V&0l*a6VGN>R8pZ+i4&ry20p7@>jjX*w6xh@v(inFCzQFgCcB}H+!k0q2 z0iX*0!A!fx_!h<|iQpfAU<@*#0cgC&ZT!Y@JjZo>$8CHE#^4dOHpqp1$cenjjr_=q zycdyt$(dZp6+usrT*;e!$OGXY|9Hxm{1L`r2Y9^8z5L5-JOgAL%*njWZ(Pi0+|1Sd z%h7zz-JHkU{LQ^w2Pz!6>r4f>0au6xB!)I}4M4M9p{+;!DBsk?QC!81fyD{pR>G$c z#^BK*J<=t8(kZ>tE&b9lJ<~OP(>cAAva&Dp)()%@Mzy#eU_ zw`*O*T0k7Uf*-PgDJH->Z+Bz`ec1V@*z0-#s2fzSyRWs|U<;gB4}2D1I8;5U=r-W4o-ph2)=*#Y6GM|3jSdfq(C%G z8?{xNwcT&PRrujI)#6R^4@guOhj(2)v%F*S!I^o&A$*zHg4PNBn`;TA|KT2xy(z3W z>7pP2G;kG`I_7zYuNDedvh%Ld0U!2y=77GJg;+i%=*vY=^@7eAB+AO$xC5fINVYW%}eim&Sr@gZ8 zJ4x!{D#EAU-m5;kqJa2j3GwGd1MDYzMR5{nL5L&2cLta%<9=K_-y}0ZA2~l5X_kFA zQ}j#U^pBtPn+f%aee!$f0gwS#Qo;4bBIN<|$2J@0Z@+bN|1ozTVKbi|U8Y2l-r{Ex znZwffLrVG6sNo?Zh+J2{6)Ot}<{!r4x!|Jfzv`+uVeGfRYyiT;KMw#38a#+Fp~8g> z3%>ZLV@!jF6f0UZSYu2hKO8%H{0K6n$dMoa0gVAfGNsB)@Ze=qX%c11JZRA5QHfJz zqcJru`uusYfkdE0eF~jeG%3TQN}DER>a^j*7g4KPy$V1eL9AT6T21vYtf&EA7lKlT z3P6!cmu8iH3pcLZxpaMMt-J7HM5K5XX55%Fuwaid2McBf&l%3bB=e*}W5=-Iojv<1 zglhTe(98%ib1vw)>(tK;P5qMvAce1R_sq!(VUWtTcI~W5DVSv%I(psc9FzkN-?uOn z?~*=F)PujU-&FL)p-kBn2$L$kLXJJV_U#Rgf7ZMC_+QE7Q!*|;GEqEum=>QTsfP{Z zKj>9b#vb}}{>=L=_qRG4cT|ky4Qf#T93zGgUxaf^K^v?ij1W&8gU&>$v{Ho+qx2(2 zK~?ZW3K6a714VZOafhNoBV-d6M4X|5mRd=qNMnsQ#^oJn;PFM;c=i3r(Ro06lngx4 z&HzGGki>{F71S(eSNob*lCU+ufJ7VW!l;sH-r6TUYvrA5pcEraW zXxzbvqdM_~UwFrDDHo}6nOanr*%5=9m3v&sV)$O6up2xSvXLFSBNP%GXf z6oCiEKBVWNc&+eFSp9r~VgbtkPD?GJIcByfa*cXw*rh=30uMBbSgPbleQ3%lw;@eA zs;H!)`WC!p$@`P4$j$N11OT{tkP7AeSr8QB^wSSGYm%AI69wtxTS1|ulh7(HhLvo! zZw)X?i`MA79T}UrBCW+Dk9^#3$9#jqL0`}_h(Qb+^f0l;dVnm+Z*3FS zK2&Vy0w|wwQ3)qRm`!)xa+%y0$~~%_vtTWwhY39KAR=?Q9Q~mN8f@U)w?{ks%p=c{ zb4G7hm0x5pX>R<(Pv`&t_`{C^0C1qq#s(FVPRI|?GlxN0%;U*HzXm%jLwMVrRGMK0 zGx>2~M7P!@pWse>@loAgm)@Uk+qij#59tg%%=m5iA9g5yQ}Z1?PWjMQdXFXeT8htQ z(b{nUMfy;1Q%s2-XoF1#2Z@3XSpY0BPs6W=f{-!O7^Dq6*)CDWD~c1^5f*NQj5`YW zg)%x(omCWYf)uO>^5~*G&M;4VBKaG6SOSkkP){Ztxn3Hw$3Z`E4`{t(VW?X8Js4Ic zbJ=l~)4bsW7U)oPL%@eGi137Bw4((8*qSSJ$buAjXdk2)!YW9VrwSUy7%fs-jpCq; zU)UjT8<3(Gy?DX@xnwXi8%$wIp7$ffC}xBmp@~h*$dMHaO@?^699Haj6+BXehS+gc z7A6)J9TWr%*=Pqlu2F@83(&_J<0L56 z(w3E>=s7nUFQCp#sP*coN?B?*IkYGi%T%dTpXwB(iUuM??Fvj&DASxoZ+hL@LzAAg z(>P94azDLjsjA8qb{@o?(v&L6R^W}W%%h7WGlC+ZidXEo6)P^K%T+m;Rh1;7B`+}y zlX4nXvG$a#FKjF>&6*UpMsubByCCclwY;S_8MLS8@18OjoEFO1?_VpmDR`lwMd zhfUXM%UMUXrd76iq^(udY7og5Q?$x@!8yX>k3^acM%7^iXpf5*-bSUbbNQ?G0!tD^ zObV9&f;lW6I(1r}I`*;KWo%20no{K!stPR<24wg21!Zg^Zpdx#-Qt-ys-E{P&TSra zN5ai z4av)5R^29Xij}Ga@c8B%R1|v!w?JVr0CX$N3#VuS#AwkJ7HBstR_Cr2?y*&5%u&*6 z%e1HMFi2SP4iN^XwR|u#w@i#t6|dN~yri-(tqe?~ITgs;sRBO2G7ZrgZvwwquO@tq z=BUCKFBy)@hWqAZk06GtIbpIN;_N6WpH<41!*V+PyiP#3)4>1aGIl0F#jv!Zsm1I6 zM1(K#fHX@QQ58Fxd`k>xxXaop>053thl6>`dko!Ct)w9d+2cCpRq>=X-_yY&99mXG>tktH#j2@tox z5t41p1^e9DMJ;-etmK)<=elR~?@r@AR8_B9;#a1)Q>^XkcLx056~RCxE|Ce2bA00! zX)|2joHINlrWrVKC|Da_aEMRY;umK%QK(%JjNd!F`4%}`tgwqpY{KXMCix!!2fjCS zhc(WfrtU~wu2Yz2SLS`D`Jb(x6r58;=TJ2|(GgMrUR0tISonIcz0MGm)0fEUes@ap zJCmBIA?i|p?N|vs;O=3)C|rLk+Ra{&I9#F_Vmj&f3i*xiADiZ6}M4TgG z_K&E3>UsOL-d?%3C=qXV3_O~yhW9b(2W{@87yQm{9|^)o(uc&&ha{G-59aS^^PA^B z+PgQ(?mb`0(|;Wl)k#F@(JcJjB7J#mUwZ3BvhtDep=NAAVdbCSyxXT*^WN?LRCj*h zo*(}zELiW*$6w*(J7oD9Z2nG-EL~5BBvaUPkHc%J{fToQ@0+(bLrlT{4f2o<(;x)F zCw}Nx6{m0skbr;`rhYHReq`i+wPa*)2NHUqDK|qd_g7+fr+54Jft>e!3{ee)@B~so z4dp<374(22w|5OVK@X^SUcq?kVq{wt5_uqEjAMT>=YcMicR<*GotJS3u>$`vC}4De zFvx_4Cxa1)N)wn(*yj<06+$0jJ&(a~g~NdowOIT&gkUI!T=5V@Fg6ju5I^t_C8C7n z)`VAq1)8u2ZYo zfNn^KPEi2nH;G-hgl{o}Rwac7wTFK2VUXts^jCc>^NA~ye^vJXg1Wbgyw{4p*NSC$ zh6~{f86 zXpOg65Ch-~=KuuQ){W!X5S+jk{U(rY6_AQ}hwYb#6u5^?H;S^S2G~U&wTB+5SaFAV zk71~Y`iPC~kOfGTHEnp1RZ#`i(FY|tSqW*43n_sOIfe2F68VLJ*n@2G=!4OSh}F1} zJV`Vj2}u9oZ6v9ZPGN~f36SMzO6T}e=?GYRxK-{5kB@Tyit2)qHTR0JXpi;ie}2c3 zNLdh%FbSJrkYGua-@%lA<&@7wg;sb7HL-<1Vv*%>l~<>cT}5c$Sr{dF3@0;Q8Jh0QI~<1mD7fp)pnUV_j`L8V|{6sNdO6&pb6qw zn7F8v)s&XawU+jUeSH8kmGF+95}A@QnOT>anpv5+xs`h9kqCL3r5O}(zzL%{oSFa! zz)4D;xm>BKVXMhu&zA?2&=Phah(I!%hEbb*cbi+colDW33(dOtM@m5po3_T2J2>n`ROUy$%=Q$pS!u71j?5Nx}L>pexm6J4*Hc8k%SO8DJoKVqRK4BHEcGikuBloP%ece$b@T#G)9+oNnfvaAr7t zU=o})RaBJ-pKS8$9$r*;~f9D!tngP%F7 zJv-`(9@?cGnU9!ArpPG+2|5XvP@H9#sMNCmsH)efCo!dvngZi{Z zq@6LKo_eYb5eW%uo|+H|y$Vom8d-08a&ek+ZcwK+aR+%Ih@mK_v)VYAs+G4YZ}@l> z!1qNh2zYTAtmdhc#9AY%iiZW)s?G|nAu*}bx~JOOlViA(9m%WYnh?bquEu4r)?%zd zma7K=pFonXo3gIZ2M;Xgu7o(Qc$t@*+OST+t!KHf1+fR=nxJSnu{L6^3>j7f`;LJ? z64IKm(1@+s%Bk^6uU`47>zM)g8mxqwu{5%=FIh_-n+JjLZplcgvihzki?Z_ywA)Ig z+_i0iU1ArH?oOkwV27ZU0b)H@vjCEp21kQ0Pw5k$qA0opnam9bq5mc$eL7} zGjpq(m796+%A56CwvJ$`pKG@LN)(&O6#+{Ur3(@*BPnqExDOY(d#0(j>a(%?wYJN= z+!4BJIl6}7yCKmsf#VL2JG}T;ynpJtxOcYzu(v!{w9QMt7KXb(p}SbYyB{&V9YkWN zo4P&wu*f^V#;b`#8;Rwszoha1ys8cYnd_blKa13;UtnyM3@5qO!Zc4_p`h z+noQ~yUj|lH|ae0XT8{Kz+R}p3!Jc2fy*F zupg{{3{1ZxES@NA!aY1pJiMGPiniquz#9k>5c!mHbIBQENw#8%0~CL6*zOpQ9sw^r=NRUyG}%Ed*@P!87&(sPVu zte*%h!t(mFfBcgU{KkV!X~&ViS5aSdjFTSGX@!-<^6STdoWN-urh-h!muwMnoUEg( z$foFD$Ck&CyvC6{$@P2xtbt0jn5@bdp~+jE5>qN47p$iqamRG_$Tf_^Y8wJO2WWw%?8oR#GHr5EX#2V%At(Q zlq|X8%)MRd%h!y~@Px%J3dPLB%`eQBsfB~i9L}a(&i0JPY%IR%jLz9igQoS)Uwq4) z#>|dP#?LItrA*4xEVQVczx-^?uoepBfDhZSHfcA^|GW_ajm(wGheqO%dc2`$9C61x z&iIVJ_}i`L3(-nzXmgMch2R9i&<+!pcp1%!iC_n@49_vy5qS#EB%8}8z0kVc(3afN zgluTr;0py&0Ow%;3K%WKcyR;{)y*L-sqm0wSY6LWZPd}6&{^!zbzvH)p&G2=8n96i zvOycRVGvP}4ftRVr0^TTAxXiU)T+#755Ny@U=YOcKfpBAb8!Jozy@iM2G5EJi_O@L z?bweE*^w>TjU5M!J;OmQwZQkdN-szp*k1z(0px*Bd-|>y!j4%c} zFx~f!-}%k|+!>JE`t9HU?cDsW+yGAC`7PiDj^NXM;0cc3I-t^W@g-q0Ccj}OXrd-; z;wAtP3hWSRzzq&_QYQs*CwQ&fN{zd{{oBEf5E3&ng)jy$4&yN{<1k<3mp5MQ-Frj^s(M35Fjc)sAB-sztX z>Ip9Y>Z4xZrEcoW?cie_7xik)*wIt-~|6LH(%p05Hs9kQ#NdF z;_HkMOzqTAE!9x0b^giOSo!SG?%7QYsM>)vRs`!#12qL9HB@6YSOWmKZVkXsf zz=XOa_%H}WK+`sz5Qluj)1J?xEX@oJ*8Q%$*s(dC!w;VmI-^rM90LHT zqdKeu0ApSdWq#(slIFE@5OY54?e4~~CJN<{58LqDH$B*2?eF}q(E7gbL~ZhcoE_++ zKJ4Q@@Z-4vKtJ|_KfbZyNZ|?}4gmfGK)J3ExsCAx>CaVX()LTv)E@1Wne>Ck>U3fM zL)(BuNW?=v1VlnaL?M6pHKOpUCpV# zzpJl`l8^MQFZ;8<`=oCXm&<~UZ~MTB`<)&8tnd4TU-*-6`VCzB#ZSJ+FYU>n`__;A zys!MvFV;vc{kBW}cDeN0DaFhV#Zf%|9eTf-UqC?r{V*8*N}v8bTK@H~`^-Q8^4%Z( z@Bg{+Z<|gG5DmsO08r52L4*kvE@XI6Ai;(aB~C2(km5y*4hLrBc+p}QW`ktYH}n6)EkqufCl- zZYuw9u*Ml;r3dus)vssY-u-*{@#W8_U*G#+O z1{-wnK?oz1a6$?zwD3Xr7F%@jMHpk0aYhf-X5;-ZSB(BOPaiC%W6m2Tt zg%Ade?<+COypK#X)0_`YHQQ{DO*i9A4^BDl3*m(V%5sgVJ^7qT&p*ZLlc+%n4YaUB zvnsSpMp0T6wMQXMw980OtF%#&F4alXO(%VdQ=CA(Nz_q2^>ZlyL{Y_b)u2peja0;7 zB}~>?U1hZ-T3yOjS6hMF)zMym`W0AJr5cu`V{c_NSwM@WG+0TUMUmNCBUmMZvaH26 z+iSVqHY{zuH7i`P$OX4sWz+4*Tt?Y#7u`nP?NVNK>$Ue@eDl?JUw-@b_g{bm7IBUKR{B(o{sOIc~aG=JXbYS7KAi@nt{PwqXHy!eWd;`us3~Uyv8Wiw8=s|0fgE9| z-~kLDNF^2P2!jsdAP-RxB@C``1MmP~igt`43eyWILjaKC9CYwO6vj{x51^wMPnd%}JOLCYy6}lHoM8>= zN5vfOu!jKHz&eB>geM#W9RvyE7|VD@pQO==P;BEA3o?q|bxi@^kX;zm;fjI~(TGS? z;t~ni#22zrif=q*A`4OoS!AIHbg)MPhgifTCUIb-7)MgJp*a8);2fq9%L@Ksg|KWO z9ACgj{+-O%&re9`f^$5994S;`NQPO= zV*=qHPbf$M(gDbWMByI+EJ!G@@r8c~@oNVEF-A3h^38%669D2QXDrW|5OoGH1@`zt zLPEigmH_}3-~b9f0iaKQmh+zo2`B)lSrB#p000L~=tA#F%zTD(oDxN+6wbi{;Dw=vXnO*C_KW0}Dssd%F0QiDGq?Ho~7T_9d+h#Xc z=v4rKRjd^)h&hIVkPXOU90_#-I&hGMcorlZzAS`1mWWrq0)Vdo@GD>i+cG)eV-Vmt zhcT+TRD-}X1&{q|SS7nogH-k)fgLRW064IYRXhL#vH%B{KwA*e1`@KSovdmz0FEyL zuNB=e2oL@-1pqA8AdN-iZug4XzWx;ezYT6u4^oU{D3-B~4cHIlvDKcmAT|bp#WuoH z0BQs?D|7gU1=IQzeBi?sQ}Dz+1|gLKz``H<@CPl&T97LIgKRN1Ml`KkkO^?(m}*U` zDXhV?y4p1)`Q2}SD^d<)q~HNOvxY%JF^_+MgPjrZhFB3R#Blf*0ActC27E$c{`$88 z7}hX{Jq%(I7sM3$00$VVU=47z%o@Qkh!cAB6Bt`qD>UBlKRVn_9J3PuP!LBy`T>q= z4!Ouj?n#nm%w!v<4y3>f#*?T2`;RaHAjJk@v5Q}<-xyyw!%cp2Fvfgf090Wgm0WW{ z+MF&}JcxAwaDg~z`V;Y1fxPC;iZ954Bc|XW9Z^85FPWkbZ5TurnSRO~%rS>33}PMk zWeV^DJm8=fn88h%MmOFH*RD+g9RrTAggfGCP>Y(>Q|QJ&_)!gD8zclka2hu(7zrjunAiVZ9u=|%x?ItRxkwrkcS-P32i|*h><6v95t!8eTpy4!Go|gkRLPuhd=m%#iW#j zrlB~8RLl_ygQS9?r6#Lc4f0-}kgx&B@P-PK0=!Y!oaX%?hpjvE^PmqM+w6N~LLNX5 zv38>$Gw+A5Tan!D{sij<5&A(wz;#$2@J_CTBuf?xM4un(xkxOPv* zuVeEc1pSpf$odf{&Vp>+cRbbc|2O{knT~yA9sAfL;}}^P$EK{Js3e5Qh(bg<&cQik zZ?Z$m$V!A9qZ~q~j3n9FWL1dHbw1zkwSK?b_5SDlbN)Ny_If?X;||7gnRgQK2nVEY zVN2)IdD4lU{%;6y0n70D3N8#;1(qj4ju~O{`fy8qp4qpLkgyy(*{oe?7&+^(O8@Uo zJvJSEcBlb|JV{zcINIFck*u0e0ElOzYxk49n61c$IMWR;qWpvbPk?GY_Dxwa{-Jq{ zNHL@mAX0n6G7$fDR0X=tW~;zCNdf?$lIFCd%-7PqV{KpQDmOA#tx zZMTtRN2BE0>6$j=0zc#~MG;s5+2w!*EAifrL^KTwc$}4VMB#01C5tM1&dMWnS&H=J z5m+u`L$zLfPVAjZu*|G69svqM!&OQdwkH|Qn+z?cdd~f~RpMSGN@lo$#!Jh@hM)y5 zNW9a+yel#{(aATaGxpIyp-Gw$#{BNDn#mVHH#CrlDEMrb|!x(0Xm3jsl zM~X(nU70S(5F;kwCPq^5D}@qGY86NV-CYjQG%211uE;QC2Ex?$8GEm$be8f5kr}EF z;~v_lxKg9w{rEx@1)5r`xmclHBVqTb#JeuJc(172<_r%pL^q(5U~X(Y zB^76gFc z>%|b#5_>PBdU(#F$h<$!slPa=-_24^uo50_OLWvMOtTj*O*t1IO@1+GMgR&gxum=> z5>AgWe;skYCEJ15Kc zzLtFvmXrj`{(Q@UYReDpmV<+qLsOQ+8h|2wg+cp>A)It!(EEav-$iMK9N+_9B*{IdgIM^Kw>2jSd%L)C?2Gjjv3t-HZC9PEy zNcWymKWpgP8(Z1$2E<(0i;_jg{57<31i)Gt;v-CoY=8|K1wGV3Xy-7<+Jbx;?G`yk zRmw{*g7Gpk&>!~p4i7Imo_P#H!2+nnph~zCzh)p}n2uH}t63-bULufiH@%3DyoTA% zXdA0tA`}z4T^W4IjgAGEZ`X`JGl$))yX^PQ(;jiFuPuHP4CFUNP z7+?!~Y3vZ1=um(_0HTLbKn4H+`FnsFzzID95oz>?&Q|~XM>{z_`A4U#=`Y8$<3qY# z{oio)$({^i1y@K_RsyF zyZb*^Y1?B*>+Ap4`u{G>&=%^BzxA9@Khnk@(*^@*9UU~X7wwHMJwB1HT>po*-rAhq znb}-lSzlROSy@?LUS9g~V|`(fZd$L;Ez%upx?oM`tLOfgUH$#rx5>%LFaM=hFOPm+ z>hE2DTRZ-?eExOTyC1zHV|1wcKTXV?(C$y)YP_@qpyoT zzb>LSKchAmeSVcoeN{kh%Ij_YZ?gJTLqo$rT{>N@E*UE(^~d_OdtGj{qg7UnR+V;E zRnzflS~U;t83U~xM5nAz%AqG^kRPSd!_P?vU&z4=yvsNV#oh&SM!8Ft@99~ z6;?xA3Dl$^k+YBB-!G`GelE0mDqN%ebalMeuIK&1)mIKej2_ep-5*6I3OTlbc!PX%oRo&Ehq{E}P zoTi^I7e@SEUA`Q~vm$B0XzsF7LXvv1Qko$5B8rz^O>VU;L-EL~EKzD!{E5!pN$)gM ze7t+K|6LCeOYLpW_eD4`g>F~Br^%g8j5?($1As@-y|wMX*VbQ>;R3##-T$$xyHEM} zvi?n6eV$U9bmY7PC$}wt%N!tTXf4uhq7p260_& z`{Sn#+V@l*bTJzmugW(U)jF=-hxj^%jFJ=iy5vW?5y3m`NFLRd+rv74HX5@~A2ceVhEB7} z6pkd85tyO*_MH!>jhKIpj(ApYeq@9t{u+0>Ur;!HZeA1l$(pyaiDG`*`1i;qyP=W~ zzMVqBu4>^mjf9Zpnm^MqQM7_-s+EYkDoZa{vNrfaJU#|rYAh> z!5P}jMQcfMmY+emv#7$jlc;m6{l2+tRXvHJ-{P4czM9Um^Z&c4^`%y5N!X|7F_xW5 z-3Tpa9>p(1Wp$5MqdJApZWs@5M(kgnG5b5*a_i;E_?uf##DPk7N8Ha7?&Or+G7+wS zq1Bw@Z~xXl6YdQANzmwg-sq5Y^85IYe&C<(x$99$99afIYycskkGEHp-NOZoT=HU2 zvgV1pUM4O)bueV$RFZU`%ZRrGLf!@FXTAx7&{rx}zPq%m{)|oJXF>^i%M8QMKNySX zDe2y2XgxXnNyH{_12lp-89>jH%q>e#Wm9^^;l=J#GVnWWnxqJ)r;Ha}h-cD7qm^bC z*uk>z)r)5#m!}}NV23@r2oC6#cJb&BRZ)7E>mgEgcnF_)?3s`~9KQNxta4cqTa2B4 zE!Rce#5O_p4)tEN_HHWk?J^H238(J3o0cp47&LRBq5>dEWj@{d0R+7z59^dD_Zjp}^}%r%XG+}h@B(Vp$Xt6b_ss2z znqH}to=a)z6N8@8`iE_{7nOw}sV186y9piunVE(oYR{D|vIc1o3Pt+2%IC{~ZQG2_=t=m2Kdb)&~^tlV`<{20h-%?YJ_+IHk z_KZ^F;Xe(0YZ7`jL`Ue)*Gd;&%$ zhUJL*yEYd7+rIp%LOU4CE0h47AtqjpRg02fEwP}72tC4rq?!aN3MScaqcCWpDgaR4 zD0^GT#97iC?c+q?uZ!l265dCFF4CGQq;q@Eajew=rAHM%VfK133|u1wO_)x&TLzY0 zMWkLx(%m34)^6hs{<*Ll0$qu}Bk-sBcNrqQ#_6FecouB%MD)N|4y^q2hf}+Z4`@11 zOI|+oy3uOt*ma~{*YSP8{@pUvpRynVkMOo?y5lHzulUKg3Y~3B9hshARI^b`*pxGH8YuA`m3ft0Oqa@{l#1CZz8on z(dPVK)EKs(!(jAht>ydOpD+I;)~6E?YR~bswREd~z4J)Tx4DUrt%t!%Dc(p>N-foee_!)Ogq`ILMB4!cAG0%9$*3pT zNqnEzSg*u4wJ^oAl%n2s*Gjty4^_$;7zo0QXCy4D@aDe5yWJ&@KsYH+e;@%6f@t0g{iCe>7IHDa=H{{&dgB zFTWwpqRBz{Q;?^%86m;ZPCLmn9WJQ(x<0MY3qnzrt^z-8iHhwooTS%+@QMq};2%0E z9B0(XRPw6&i=Se!NbfjlEI2W+V|_I$boi-o0N{x9cK^v|YAw^J5%~=25z)n9ha### zyP*-i-3%8IeTt|uHg}0R_Fc^wY;heuJ=%ch(AMyc#?V&Ux8d(_TGXHP5uS@SGn$`j zYgAvJJiG&>pvOiW&r}IiZ$Ld<1nnrM8hwe$*|VhrkVCw#8i2EFdYTMSV>F>@EX`n? zK=mMhzt!-sj*=*KXS_w0(hHiK?HoUgQW>Q@52{q55<-7(KFDd;Rwt*l$H+ zDC}RUKCZ_*Oq#?pEP5UYiW0$@lUbW~*y-&x{wp(z`2fA8#ca&IhM_R^>>f}AXk$zl zwZajIti|}CDAouUsI*K9lQV_@?}BL{b`zxvY^D{XTWLgH{Ri4c>@dwQhr`@o??G0v zLZdM38ecD~PxUSCpA%*}Ijp8r?8b<;FX0eS1iUNs>|AJHHqQBVu&YrRbQgR<&E%=O ziDQ|G)1rwB6mT;(^^7)!q(W)7=KugN7K+S~4k4F#sFmPPw}gG0!*{785ykL(X7~G- z#2#$3|E(j?sO*1>W%=t^zXUk9cB|2-yaa|&noB528re`B3f~E4(u`3Ni-BA)=1PgV z+7k00yE-RE*aMF?F%k7TS6Ozhdhy)9yWur`59`p#NqYHPCQ=qb=#lchFLO^t0x6Ar zV32i3qeYCr7#dv({f=W1>jO=tu%c3s4YUBZy!oK{C}ukb;F1RNTS_=b56*rfZow@E zEQ;mAIg~lZSA@n_n#Zr*Lb^*M9bnehn%3Y8*2@{z>!a2`%dD$=nHD5~AJpiX?2tK) zd+WC%7m03vWAAYSBpQ!+*fY{B`C?n3N_8F70$@HYW_bUUtuG*Or#KJ*VE4G7^~k&8 z4iSYpNsHik03HAQAZfcYerhq^9(n~pUy**rF8k`D!mo>)6YN&xK+HSLtb>&dC8V$A zW|EYG7!@x0o7w+M0w(Q#zBrE-p1wZIK85oK&-wjHVVhU~FSQ!3m|vMBb11z*in%e7 zrpOq}Vs~l3(kZq4(ua{tH)t@6I~^A1WuWEFn44vD6XZ)~+{dtf zpd{2th1rH>^Dbn#F5!AToG6)@XZoF17o4b)*LNI{iUI7mWQezN!}7m`1oe9*5a=ZV zmVF?V<4QI&DJk?T9q-F-Q_WN~(@YFY$s-c4coM@9xkV}jKP2m;oZPb4xrJArM2clb z^xwFpb+gMep7$`Y?$OQ%{%4op%C%?lWz0E5x)HH{z6kjuwOB}E*Jd0HDiFU@PJQzAufx0 z=q>1(m;AMG>q?PN1N{w%eKadGw)kszM&A3}L%tGtLs8Omq2(|i+Lb~jQr@+SJW_9- z9vJR73-2Tsu<&CumsB@oO60YXTvyeeuHLxSug1?$KwnLutcnIv;c}RwvDJbvkP-#$ zvW@y8ff41Cu&`U+D(kCuUO#$w#x;SSzE!8=cV#mWe6>SnbLf zIr+iTEPdKh#r-4US_`n=WM#=}vD}+y5A&X%*(nEKknz&4$liTkdRwL>Pge6b0nAj+ z_?dVw1_sr;bqpIcGwMTLytgCP|l0_=7CiFpd>qyPsi|V<7mxq&ehH)?1 z&!SDAgSi3siF0-7?sYur)r?Qln6K6THrj{Ep|$F}m(ll_fZhjB`PynI@pY`*pQxPwv9txYa2P%Lc$cfJu4v-W^rd2!%CSe5hOcL_CcIYUNnjY+r3LHFAkJ zUOgX^#uWgOM)m}-*-@cWb*xdQuj7{*ly9}fokypxHSQx>1Sj#S0`Vb#^^KprHl8%s z=MCx{0UweXz#P!r669-ey-!<{M)(`czd{cwU`QSC^9*D9SrOrL$e)uLS01-AeXF@I z{it)n5faGeeF+JtfB*!PC8d3!t$pxY`|#g(YFj%B2}dD2#=|=%s@g}cb$tESFE&VmjRt zPTf)w-7@lBAyoL?6b4r+OY)O$6`dY#OT@o#{@DWLQ%u;OypO`}lNsB|&aafUU3}boaifF2&)5GKSRDX_TB|Kv6L4>Z4MdlS~qy()+N_MB1Pysa_3jr{>7C;Y?Z&N4lQ?((`|d({&{oda}i=hnKe`OJC!AIBx7*&kD%bawF}%2-FU4=jp!-B zVGs(L?Ki;oFz~f`!Km=rah~zPV42a$gfX9*algcI3` z_I?(6mI{+R==8K2Uu_w+7W!ayQmxU^==TjSKYKwc#YGhN#s4}reADI4_Wdcj!C2Np z($IvB!eo5MMAC^+;%Q_amc7sOYe3Dlz;4hz738UBEbFtZvohm_CtpACO+LFm$t*Nh zQP8~l=?w&pgaA)0;yy9d4_RJB{s~}jp+cXzuP4;8k!P`VW7sf1k<~`e>@Rq%b+}{cx5xwB(mGr>YDH=pirpEeF%AmtzFW9u&4(2y>R7 zoxI>YLLULk9Ok|wybN;rVzD|&Kj?)DFD2@gMbv)e+WMZRx0=Pq8EyRoqWpDa+XD)k z7l~YE&|ND&S&8|(dQ`C1v9-?0CYWoD)UR4;e`{1yINvf{TF&Xi@P?A!N{k|s zb9RojwTu7_7JOHQVWHf08!b;Ff><^b*?v^|Z&4Kmd-RaFh^eo_o9DAOG@X{h=Na<@ zp!0eI>CZNOroVUUZK^7A*7#3fiu|%su=1+*hro4ZGh66t$4|%eTeqxNU+7JNlDGJh zS9cge(7BPY%pd;>@0uzoPRsAujBTJFt_gIm@hVM?Zqa*p^^;*zySr?wk~9Tr8x$+q zPv+ywN#x!z+xBP0ZL8s(+p{~6)T#R1ZE^OH{pq1MdT2LWI0nfnUW_Q*-t+YRiMq69 z`e@ZVa!zq(SM9zI_pO{jEkD%N5*^%)TwA0ernZ~wtG{5+ns$+d1vXI zKC<9=+%S3ewVv|9Fyg+_ngMO2qIN4)>Ci}NdW?V$gby0R7O<12sWv)bW^1C2n1Abwme#YA#7uoFe z+fay|M_*_^@f@=dMPy)j{`if*dxZzeX&_+?=S>%SCjm~z;$aNJb6mHh4F3Oi^@3@V zkZxodWln@4Mc~fyw+m_F1PqJ4zx(R0$NL;r@8+g3JI~?xGg@M{BTG;tmwh#>{r+^f zi{;XHWMW>}OY~P>Vii+1j>Q@?6miAW@n7C>Z15OLD|iqx+n;fpK}DDOOZ8Mk(E5B3 zGui(gr=O!BMiVcr%W1yz=6ls=Z|Ci`NbS`WAn7wA5Mv+nF%X-?oI z>iV4t9viD>ukzbOdeH<w9C1<#a!^F*I>ZXP=P-C>2}}M z_WI1L%W=BTes6aC+!~z7eg_a3Nn%+;#{ZJ`op-vbqmgXn3e6#67aEIT)J~xd|X1;c}A1wxc zkL?EHW@mdjIc}BJn>Lx-uVW|lj1$eqB7$m+*kib=47iS&a3!7zYmAgi;p!C)f%9_6 z7H~v;d2(9pY;-zD1>L<<)_9>JFZ5M)$fB|s8aJdq*3LGJmv(I6q) zC&6j9Vq0%hZbQ?Ig4mkydT`-XYP9buYPGHJ^_?U54q7Gi=-iEwU_FWvc9H+w^z@?W z5vPj7zd0C=HAa%H69RENwyj&%AA6U3+0!*9MgXWRpdyNZFT#_7zJC8f{AwyFA;?1q?U zeS&J+<;}3t4f*;ZukCr}-g}|0w~gPP{A`oH3R;fEWO#ym!e_V+ zNjw_s>;V#?Q~Ocwnhd=73^Y+BvN!4hT6Xm7a*>}C%1h7zu{&SH%o2}-{ITH|u&t&b z(WP`>`$5RbpXKKvg=<+UyPnNw@BXm9-}#t?m?XoIYVH#>?y%_ ziM}qy=ohwTCqOX}3Izjgvv7mk+w3wxu@BV1bV7Ju|0B7Z=Ox*OkBc!?JDN6+Na^)d z7ZSHn{l0~R_kPppl6_tb!@>Np21bS$_7H=>e09c!E9hl|fCC)-&#^0VOPNJf0>rmf z2?8pp$&Nq?<2a`8NUZrW+J3|B!=ltZ%Z$fN#=QV*F-gp=%qqzSocV>+81v)zKc}kunh9ub!*efV^eNQTzz-Cn42Rx z736+h?CY(VYYpEbdtWL&*#vCbD(p&CUa@kp-()t_SZ8Baukq8 zDLd`DJ#I5(_SUrc>(r*8VV$X+9m8@8xP@VCD~H8}ScNz**IA31*%}9YI6JGn^F?A+ z@>zJ;{p;&@Pj#BPfh-x*zz-}5FIeBd4D|V+4=E}KoUo9{hSKxk?9fhss~=utZS&Au zs8{R32*ealQS$4bw;P-5v46g}Htu)vyrmQw$v;)+6Li)SdHA;r$NQ zzZpz)4}6SD+O_<8`x=*OA0+lz*7#T;6$XTgnwqNOQskAOkIsA`1n;JQTSvlFsG=r^ zF}~c@94DtCe&foMlt0$frs%o{qJ-YQBVIsntU1mDQrw(EdVbxs1TYjEf=sqr=y$#INgS zF=%FrNkp1+lud#zYkX7fsUW4zoL-l`*f#0RU1j^CeYNj%p3ztCUmL{=Sw~aSVoXQ~ zABHIvEXeN$mbIio#c-N~{L4p2%L zGOv8ebU}A#R#31^E_S!f|IWw`Cw*LZb08IwjScjO z|I#kESE2A;wqWNR!|&oxXLYuxbE8`P9$(+ik#7Hb)9g>> z0gA%WibYC)20b^L{v{;(u(JMbAoWJu?`GmoxoQV(9k=lJ%W=h%l?9&gatbgg#7RJk zUWD34i&0(@Bk5xyR|f8!{C+FlMs}^fczq^Lcn{tB`&HqMIl}Ml62>44Idp@u*~|%N zZlrJ(`|?g_%fH{myUio3DUv_FKK}ab_3o4EJqYVaI4;fn)gL>ohbWfyNyos5CZb(` zQI0OcAectPrk-GvWOVj!V?R~`M%rxLqH1xr&9<7aVD?>XN7(%b*!9O))D+pfr{JXz z2~??sIO^;=uL7E?<=IHMn~p$XqE#GU6CH6zZ57<^hGw8{NVvh#LaXeQmYlB=Vy`WV zjAVX7hf>u7j9M?GxATR8FU@9>=v;L=f|i(;D&^F5aP9G7Pp90V_UY=LJBI?pJ|srX z$NlsGWkjpi6m$1qOReD)r10Ve~pBvy4HL2ia&J_C-}T76Liep;0Aw2mz9Jvv=j5vH7C0c3B51!{F}4=kSZqf-REU2qt*WX4_~M#g&-vcvAEE zcdkr;ce?IucKyR;$Q}sRHR}{ydg4@2S^q^^gkttI~ z@42$xkKZ_Y++^k5o`saWw;pY{&e8`G<+_nVVy48uxvFOq`ua{p`=tz{yE=XTd)-$B zC|3Q1vAYPtjgI?4CN>#nSY^FynnpAd4%BxKF}!Q`1wsj&YP+4#OHk9ED28;Rv|}d> z?elv*jbGXb>N-a!%-hDKAwa3#9f=8TNl@b-a%Ms97Ue*c2GuBb1=qN1#Ls16-)gG= zqz|O5n|)S;6`^#gr$0Zs-(kboL3@2ougQ7@ zW6uELWFptwwm+rUx~a@6poM;fl`p^c;Q(XIc^nJBTF{@w4#jUL@>1AWE0BU2v!0eU=~lpLVtUI~<0LQ~HlxZ70t< zLin2*`%$8!3E{y!XWB$Q99;gY^9Z;STrVJ z%pqpXF>~xn`PkK0W7pn|IgO27|1swLYwQMW+=YAGRdU>MjG*NO(JsEE@0jf(Gkz;( z+$-j?;Q<3*a1nnnf;W`G5NmUu8)>MlLGp@Pd_rnF8ueUw>4T1C-LwS`s4@i?oMa%J0p+N~JrTS4nb`4#W_)Ha zY6ZSN_sO&?>RKI4R3=V4rR5&%61o?Dv-qQK%g1Au3+)o-9DXXC-$}{hRb>YwP$5fF z28qRsm^(OO+BKRydrFDpYwE9YJQ*fC5hY2EiEPPPiWv4w8P2pCSkw7%s^)4Eu8wtw zk<;bbQx;p`5|uasD~rMVxDfZM?R}LyzPlqNP>>(th+ZHuK+ zT1^_;@+UdYOl1XMA+2sHwGH?bgvZefB zC2(k-rU}ekPMDs2XPWMMjo|o^gu?$^be`Lt{`G2d`NZbmF9fsGv~K0gTNB1K?wQ|- z6kl(=GvW&o-K|3H`y1SRe8y$_*!jl2x)*g_KUia#8fQA1u9T%u7rx7qYLQplw~DWn zVceSD&qrLInnA`+e=VQO2F`c-Okb059%a@0^KQtuHBEjMrP4ATi^AIk=`5BS#Be(DTG@J-jeD%^&8?2{@U6h?9W|BDmu*ivU;8cNlr<@@ zzIgLr_oyW4iY0HicPvE4^P!OkNoI-7m&**AboiBtM0UTuRB82l(b{w&tYSGaC(%og z1d?I$0v-oi|F|1Ty668RsM!<5r_#cz6`61&R8cIfc9}+!az9CQO~KVY5+{Ajfm=ho z?(ujL(JSs!b7`p{d#Vi)rAm~-kP27M)UMdXuG$tVUxWj8<8w*EE6M((l%z%9=j@Ki zdX-SmOy_w*Bm$*w=DTF!H@%eWc%6Xs6c}MH@I>Upz3&*^GQF_ekW##v%Zd*35+6-W@=O`G!d7tKC7M#c6-;Op?Pzj6?BnW9s+_3az#-)Tc<@Yov<4q&{A8*PQYc=CGl5>(Two4A_x!gseeV#)1AJF& zNM0JYIhHIAA5hEKfAW6s*mg$P?vQdCO0MCKc9-}418+udC2gaW+c32lFBH6e>xvFB$pAoF0m1qB3vGaw$kJMo9!G= zNL-71e}+;OL^gYV-$nn~CSn&K+4&1O2UT3YdpU9^HYMs3!0@m#Ru{E)P#4sIIWu~b z0~10L-;TGwPqkUz&V~mn(snN-BQBU`b76j7ruhqp1f|%&m|^+#NeKT#{$GpT_ieO z?GTrFMb-pp$#nY4jYk5PQAFB+uEc6`z{-Au*V}3 zp1YjOk=G@q*5KCuys1m_1mQM?c*iy-rb%RpH#CD5-QM7HLCG;Y#{r7 z7W=lsZ_<4|*~|ChuvgaIqVI^rO7WTz&uveu$AHXjVi40+q=EZzHwV{YkAE zyEP2y-NNA*>BIhK$FVKBJJ_%X*q!T1AqtU)Nz~uTUim9=`TZc=Kx_WsS3$r97U&pr zmp;oM`bO`;(^1zV8efda$tppw_-IwpP>kcIb&Cb1)7Sr*-pijqQ#5`nzKkGLs&Y&m zdlm!Qo`180lO2>0kti#CC@7MGSdJ2A6GNu4yP|i*Oz~U_o*SsZr+q0* z2J!OVDP?^S`N?98YO-)0qws}1HH*dy$`eg?mG-E{85aDRjo{G||2VR5JL2xFXW|0P zzb{|s0(=V$xY2M3-(4jHF0dB<;E~i4@#57C4i)(&dCqYjC5+n*7}GzL+T&S!-K$ z_1)k#GhN#6PyfE$xd8_Fo3E#1Qc~W4!6LnXA=s?9QM~_xLB)R0v4%gn*c4d~k9v43 z9~eZtQs_|t^L^<`cbqY?x z>n{sBCTWiAd`g9%Gp{t(pvZu*c3)kvDROHFbP9MI3dZu%4$w%>YoKCgO^E1C*5K6w zGhw#Z6L;r~+)?=61l^+p@s#;X&zy}mPNb)C4B?QlTnaqW~5(?LK16IpriyZ{}^BikADUmQ77D zFdToZP>EH`MzM2ap@OmJv}MaP-DIAIu4jJvVVys}=xtRTn$6{UWNcXn+MgyVyD>?`XdI-dQjB7*t~rP_ABg1}@-_jV z5cvTr-HqQL{8exnK34)5Fq!XUSJb3UqNh3!pDUTJLHuf2%Q`IAs-}4zQ%Ih1j?t}GLcv_!#Ze_B}(E9gx zzWp3vFGmkWG6dz_y|FoL+-Tkq5}n8lxa_G?^=}N;y_XU_iZ`YgW|4yV5f{})FR&+i z>#HE4y+M)X%;@3puT!7C@Wm*E3~>6IepGXKbLO{+@A*Y_K>NJHsZaNA^~NZ)+Ha=- zH&I}M;a7hjjky?_=Az1nZ9A*^4;VYPgsaKb{vR?g4f}sN=UIFB16IDxa*J9C@J=B! z{~@RDhL7Uw!5uC_Ex`h8so=N!c!+VN#tY;-o{#^|ZpX8FCn%pt7_}?+wz$1ojJxnw zXLqLQ)baralXf;t?q`sBX;Lzm}}g!D5nkU{6p*!2h>8?l>5M~ix(ifw5lg>{eg z{{?CZFn1;T4c*-@lh01IR)Hm4;O29}?hEA+A0_{<}kwwQIX3%g&h7|&!K z0~b__B04e8(_%*gf_lZx!rrI8XDMu4EP((r;yj8$^L$@(%pBYpGpd@F&M>Ip*DtN| z9>!l3xQxX4Rs^Qk^)hm%a3uM25l+7mlqlu;g_J;-fY_sqWRd~~9}W*+nYE2!o8Bpw zsuWMpZ<;btCJvqT-;=~BgA6c@aApK4?`1>fBc8leCc_IMSLGK)eM%A56UjwV1y33e zQrIIm7=c=n(~W-`R*7qvl2O%*2(>8e12sq~v>wMl8GyH)3{pes4ju%g;dIGho^Z<0 z*;YsKYb+pX<5{STW$5P`&jeRBFYv2;Aj>PyF0Y_$l{T5gpT-1*cmefuM5VHoQN2r`>k!aa5`^J(6jAYhZf1jFH|10A;77%DFYXJ-Hm5 z^(pH;$9+Dy!ZVJccw@GrmH>eCXa>n-^ zBuauFRXJN+>O=7Z!0xeOx*a_ch3r4CF=c!n$3rncJDdMg#Q*BXA9p)BX!gM=Kbj7+AgX^T$7u%f*RW?lSWVyjKQ4p|0LffpL{|r~eCf$-l&M1!>Il?x3l1 zS^kG+p9l1)r0*8{-E?WQ+~L7yrN^rHI+~xf{9s=MPRTb4PC^1=zaZ*wX!F(gTkOz| zM$P#zH(kRP+yMsTYhvzFo8q5ROHEmW&fM5cJ*_X{1?SCsoqWh-bd|eG$XuiM*Svf% z#s^K1k-1_dbSLqiqteh1OVwTOTv}N})ZUV2^UY1ll@aYbCq|1HfxiP+R{^Wb2aXfau^Q1t-f~it1S?4BH z;?$YV{gbVKukCM$ZVc8o2dSkuj#=ny%WR43~ zg5<9{1e;V=2#{&ZF|%AR@=J2;HpjQK8(5GGK?O67KEW!ToZ|ijgN~!O>G8nvQB`T0d)%A$sv23ipiE@5Nl7QBi* zL4GifSzWj%N+?5CLpGETwpv!2(f7RH1l4Rl`!AG4@g8A2EhWTJt}&KFIYF6a^<0dwb-Z#7^B76JmO598GTY zHdO9l5<1R)n_9}B=QccBVj$QvUq5ehVqg~WGfk&Wtg1?(z?G!~H5p^{H3q|#c;0SjdpBhvfYU~?n zRDxN3ZypKRH60ilqd|Nd!v_0FT5g4nQ${@CF5MP!<*k{sY)=hZpiRNW7Ph?Soo4^E zNSI=JYmN!39MKo#IShrNNJ_WnO3#@}agcC2%OYNh;$o;daV!WGPZ>2Wd>V{{P#K}} zP3BaOdBoKpJG#B#08Wg~l=ZqKcpTiOcS zaY~dLZcHq4^vX-!v@^|b-00GCG_t!w(A$VIcb25@>tooA5t_UwbH;J6332Ul-Mh`de! zFvWR3&2GkdqA zH1g_-P~`Mr96s^kd)8Ya(dxGoptm{r%|FBp7jq|?bp*h}Bi*7W6B|*&`q1Yog#`Ig znj7PEg~e^J*t=c^Eab1p_#5-a0fu})#>(e%nZP7T>wS^Gy)s-{KyOB_VLKVMaydH2 z>qZ$)d&Nli*fW_wsSyFzrgWF|cWdS2Pd6Fa=Xr!x+_LarQRV3c%iIvdes}PU6}qxY zab1m2x&2Uk&9KSK%w$YAw&NS$b#8tyyf#t>sk3oyv{8otkZU0US!ZZcN6Z za%2q($~)p)g!ceY1^%Sbt*M>nENLZNV5Qog$I zS=HT2MzUq)*1H$4CTlKllsZ=zzso4|G?uV-lXSCeGvwfG2QLbF97}i@WPHEj+oRvh zGjQbPv58ZZU{jo^##~LdNxAxau+FlE1>a3u{J>J!lCKr#-DlYyTrAzlUqF zUtOn{Pi1Lpx;o?gCVRnWXLI?Pwc9WMZF+e6T9qwmH;d0#*Y9mSlU21| z=yO=%GwT^`=4@p?t*9T^bs8mUC~?Y}sTT+Zi-&sLpfk-ugl+5E;EgC9t{z=Hs2*biOJg}b#9+AHNrW_H{ z7*l3)80uW&IRiHpmF$s#$wDi_Zy6&1xbot5Tjwrk7cY5acLh?d99^tHd^i^-)h@D* z92m0~N-sPVwCy4nOGp!UUOq4QKp%lJeE`$e5IazWJjhEMUWl7S1Db)77xFSos5K*X z5-PG^r@M{3j(1$-cmH^n(+ln;UcM>-!20TA!g%ghyq=R^P+JKo0ZNlG*gjx*7xLDV zzJ;axD3eR3%NlaMdgzgvX431LL&XdwmSmBuK9$j5TWOS+L( zSf_Xet{-T%$2 z&GRO@(K45t_b~L^=!I>aw{g~AcSDOWEI5utS%>odfI- z@{7B|UU&7*y)JLUgiX@{z~$<|MAB*QCYMDonM5B?b+mf(iTan0P4G(_CZaA}nBy5b z&jYG>%(V+c#oM+xk0~$fc)%yoKC}otb>klg`M&CLKFX~1vS^3hq)u!BIKi$u=rQ(k z;1D2b|IKZpIcJ|tcT}i>Z&Adh>$N~%r(&XbUteT`DT-kvLzDZRpMo92PqxBotkY?H zk~7{U9S`|U=EBA!?I-LGRoLq1eh4q_5OvdWu`+LT^%XOX0PMn0{odh8?^`ELH3be` zKmXCB;K#LeB^+RX`%>)UVQ?ypqfbT@<+H8WTi08)xueMI0kn1invjJ%P)u7-TubR!mCdPyqPV7Q=rU{iD=miYc4I0r$`vs5QqTT_Ihw!S%fXpO`nyGtr{y?R46kEoyU#;k( zH6dkx_rtUvYKC0ytRf@}_%|y(L^AZz4~2#)fJ)f?grXDX8h>RB#e4O>_A)g0vG}&* zpzS|}3AM7hxtF5B|HaX!IaI9w+f3u(jpf zGj~;V9MCs#@Wmw49J9=BF!k?*b^GDh2o9SICEtt2)z)RRZr@!B$CPj8q8ni^9t*r$ zWvrwUto{1V(a}RD1xl(0Gy2c-E{(svg$umXSd>taZ_w8hn!`uj+g!HEX8P$QIhk6Z zk{&$%G1QNmDc zm*ruh>uEpZof4x&^Vgu~1+#6GZCk5>6Y3F%#Q47)3GrdLA}kTU5IIpI6hd4M%?JMz zO0~{8QFiEKjiNFAbIjO8^8AQ@taI*Y63(*bT_HN#oaH&jG*ogy5NN%d* z@rsePTykEL?=b{;!*EO^%0tLU^!p@9UMY!IHi|?n#YQ!ih2g69Qmp{MZ)1`BapdGz z*B24@Kl3fAwpuwdvMz_1B-;tW5;2oD;3!$$FX|cMQdkR!(pdWo!4Cyx=g1>ZQV*9; z#=3_~A6`#HDICo2Ce-t1eY_vU2_bs@Do}&GINk!oXE2OWr-+*!fU#aC%ZT}!mV>VL zj17zJ!uj@Qqw>BN6zXXxc$Jh`DS#&EKY?NQx=ar( zLzvNPvXgU-|8#WlZKHD*UtcrZ@~+iGxE2b41>prYJ(~i_n+;>IVI)^j$h-72dzyAW z*#ciR-i=G<$6#ukB3f&HbmauUo-Z;mA!w<`5G;qKV%SAx+loUSMKZw_d3eu!#I@OR zvU+*h@Lub>bXohL09xZUEu*1$OR?LbIDS~g;(#JnM0EHGL|pk2Z6^Op!^3j)t6Dz)B&t+y|=31DiDP&9-6`0USn1CB^v!VO%@>!P|YSHH<{95dP zCj9C(>dSfqc@Ix9>UpEETtf2A5K71V){qSAOg}ktH%SvEvM_9P__PAq0PE+k!wDDq zEU#o0F+L>oM#RS?!hfgcG~O3id!9~Q*Xk>qAQoO&Mx!>1hU!qrQdDSfP6LHjV06#J ze$kV%#Jc7$F<6_-ZRG@sJ{9K#5dmP~&Q%{$p>p$VA-SNgsg+vUCD&`kru;OBKWY%y5dyep;VMUPwB2(!Cbv@EYWC^I5N_oEdJ2&wtNXakABD1^pO3lX3DPCss zXgP3Xc`$I zxGE{|N?Qe8C|Qf)9J({~H-*-)N)sbJexRWO<6p;LCSewFCcmMKNA#$0Oe;pl(*kqW z2RM%GPES)mkKs8^IvyyhFU2sDCbk5!kD=Z8>~~R!c)THS%%;DBO@{?1BJV0&l;Tq$ z0V5vRSOb$k41DvO1YxK|(sLs~UKAO1VZFJUj9D)5&IZM-Z-U^*(kG#i*CCFkS=1sQ z2dj4p88vYklm>5j&^Cb9Qry_z+Yc(LXCxstAl|GM#DcFRmE`N zM{mRb%;LR1Vvqze@cK%e+2GEc1l$<OfdjBnf?CI@wL?wvr_$+FJ_w>f-M8}QT?eXg4%|!ZC8Jp3p3C^D{!*k4>d48 zVc^&%0mNUG=H#Q%AVe{oY66IUZ=%&Sy{>R0PYJ7A*$;unYEvePnVz&>ws~&v_}G>a z8AAC3F(4s-M0;Yx5t9YXY7@uER+3*|ybL;yKJBWqT4cPsA!7Vn@a^@FfFVqR^t!*7 zoFOtPUrZ}F7%=P%%z0p)4^?2M)*Iz5-b^c)xt~LQC579n(i-GjzxTA=G`~!(jyCB{ zw^UVSz&RT{iWDxDpAhpb@{L&8A2NMb)e>8Ms@DnC&0gHnS@C@s<`&q*L*#^IeS(f~ z+IvIx!N+gOl-P{&{x*ej#PYAsC3rrvZqYKQ)P9@^Bm&ACj`O^+3frrJ>%6h4edr-;q>f1h#V`+VCV=mYBd$0I&$mVa`%6rmSqZu_K*Cs&V03&c(TqY$J}i(T>4Y`wnf>?dKc-+-+Rn!zbu4z-hKXMog&$m@2l8J95! zY%B)a$?|4pP9p00ew)lGmqR|Q%fu#{Ul5e2AGkc0)Jf)-{l7$$24JM-Ye{$Gc*E*DmB{tNi-Qd0J+=^#OYFni{34<9g`71(0a&a8qnp2&H-lZ?8XTJ zV7k%Kra&?Gcpk!(>{7sUS2zrUe`wKguxr$@vBI$1Dlm+apg`nrWH~=444*k-3pu*@ zofn;Jnqj49&O(L2aSug>m7ZPM&h4)Xe?GcH80EK8_zie z9~W6EH>Ax-WFcPhHg33Ba?>Gl`Z3P1VJ9eH@Qo9N zx(=ah?|5|&WC=__4VPk0xk64@;G=Y1#6g?$m=*Zh8ulSC+&DlfhavWlh}p1O3x4K? zv&a3@E%PL(n=H1E1(sVLZ7Y=X6s*F0mV?=Qg@Ld7`424^ojZY$-s~@zY6`cr%fX)` zE|pvyJXDUl3Le60ZrgG~lw8O-3hm+s1(6f7GfnYHZSOW!V{e+{tZj^#UWPU8P&7g`dN=PZ9&B}5AMfV zMNd}t)G0Pth-G($5)X;|m|kr`9V;;PQ$^ipSUs8kn?n3hO1C7!#EZINVr9gMms{dk zLGMrKwA6B+5|^MnUzny8koi=P>P7vMzX!dwDlWby)e{|!U@>BHzG_xbo%nPhkpMDF z58%bmKCV}D{iuVktBjSRtURjxLIY)Z_NxVqDk6bmlT(MFUTf!6Eul<}S@!X)7SEqs zi|ZNViN3t!ridhchEsFVIZd_nS89+8m+jltoVGa ztf9D2VQZ-?Ygu8dHYH-YMjNh1r^&&WEe$3MUW7YBLg>Xb<#TK69w-jt@XF;>*!9xK^|sOV)CZ^6 z0_VZU4XerRNLVUd)(y|s{j?F^rx1S=j;i1I>haPshe*iNO3Ry{tr$+bLZ@4oF<@(~4gx8a#F61wYLQtOB;)40}Yv6>i>H?ad}c_0 zTA+Iq_MdL2_-;R@Ce75ex1Z8pAsY6F8}*t*2GDXL4!upWbh90m#mKSdY_cXbV?&sh6A{A)~_Em z99T=n&O%H^8rmSDs`rDFN;I4f67CK0D~Gcy^kDiKM%OLkCFXi>kiC@`ZC3KTft-5v zX#v(k(HJ(hoGlAIK1Y3M}jDR`g(eWSM8eAJ-m(d~LRRj<@ zfQ>Bm;ReOe8p9$nwu`qp_DwlBMj7PfxdKb>s{ni(gS4!)%nagU6r#H)!+m~>$WuCR zrdm?`9%t{Xd@aA=4jAcG?lTuHWRr;u^a2pj8X}?$)A#w`l^avFi}04biL@oZw-_XT5Wb z{?kTXJ==?F|$h);{YjrT6P%t6T_JM%*k+$}U`}UcDc4sJVHvnht zzGFk86WLgStgG0Pz&(`cy3FWof(LF>c3ro1Hdus9r28~M@vQ(Id{A6oXb1H}4_#n8 zS$hvddoP!1JIh0_kYukwU>`!tw1@nmk1G&#cAfoK1EV$6RP%y)aF#U2pJccgUJ#Ia zyYdaCyS0WAP%ptSxE+c~hZ`dK|Jv0^00`MZ^QCNn*2!gb$sb?5a+zHob=z?a6&591-MAf-I1d=^d zZGDJ`DbHs$td86&KiEh3jrAdb+ixRLM7_hrG zh*;T1T-aB?3XlSJ5Y57u^Q2Y^gH}pARw|`d9-+7o@RgR1)#46ct=>Fwx{$mEQCHnIn?^VjMIaN$yn3GVg>73B_D=Sz0bG=MTY3hts|c#i|W| zwz7d!)LNDnB=&WEjjeOD#%z^KdMmGk(1`(3lC>uE6My(C{)xrtOy6Uu^)C#VTl4DgTP%XKu{cofY+Uz+p01w)DP#?~W8J zkAgOj_N4btrO!*V2rr@ukInbbJ7bOjD~O*JO+Rb9I$unDxt#e@Cv$-EIn>l5?=&UC;N5wo%u3rJ`A74M4k^c9x%l~y7eNvyFFG%~gql~In=ON@ z3oPC|jg>~JqW#26SI^RRNkndXS$eJspzO%kw=kUEO z4?Z!Yxkmwpbcdqh{NHvpB|Gw>v?dngQ zCarofI|8)bqzA z1#zfudTHD>7q~}e^EmXpR{PD*31_j3Rm@{_+t47V8Q?(a@a{r|N!z>1+lJ?v-_ef` zmj#<#^7MS~uUhPAq;zysg&VdoIA|(Od&EWPKXdlBHlSz+2d#TwEv{PrtaO=HZE+3! z#CpGJJu3PdC{Qgx${5S#cZL2T#g&>C)TMf%v`nW=>B%`{YA_Y_%*@Cm^vAk` zSYjiCtyJxWStNP9fTD2VvkQ#`pkg)z9_7#yjCUVw>Kyr6`<)MmD`qMxQ;A{bggn1Ne&fRtg%9NQZWEl_ zAKuEnyhb$1xp%1D*07g5Nd$Bj2ZPoO`xepHsJ8lvM?*YOWcB(PhGD2=fo`(3vktj~ z&hB*|q&5AX`z*g{TfU6K8yz7YVMwH^WxW`$QyFE)hy+nPH=pv4|D-qG@)8ji7xjsB z^cD4u4Y(#S2koCuNv9y@rlhd|xjn)^G;jfQ`v?-~H0tRCUoy!_rX0Aus`o2+$hLU? zw^Bc^za>6(dt$(`ok087p{h{iM$t|F9#?8Y5Z(8ubGr^mk1v?AxjC+Guug5E*h@-n zndA4lBLyo;C($}oK6mC{TDgY?B^Mx>f@0xcj%Fz~Eo|DD-FOVanweDk8IqU>^s^+% z3<-b2kLiwUb`k7!#5)N~%h=e6CA`Q5F(eoB=k6xpO?dwN^@c<$-03ePL%#|ZkB3}b zK{a$;V!9|E1D|%zIoYdSm{n3s>HEYUZh7Nve>&uZ8^M3mtnub7O)&ySM@y*+a$cMV8M^^V z=wb?3zBCU^c)1I`LbHAkg=B6h@P^x0W54t|m+bD)@%OH`<~sFLr`>iJ;9wl4ks&8m z0TKfs78v0cHPXT_pmOL`MFOwLM%&{(1PcY3bQo2Ni4;*4U!$o}|IDQ_e0L&7$Em`T z(LAPHD4=_gsV~8?&}_?n`h_rgNNJc4)jDre!#<^0Mu2ppMI%*Up`O{*aG5hT&*>BU zT~VCH#|*<(K2!QYmKIJ2?)ZF!`nUZ}*0#;tDT}koRLd32{lrMr=N?vQbk1xwK!>yj zu5xFLqoUQ{!U?T>^DM(}OI#V%CXHSSrnNGbi6@L|7PRV>o_J-dqXXwqpF(BZRQ}ZX z)6ro|d6z@pI~ZfMehFK=U|B-bIZZ6i_<3=m*o9K&IjWlMsi{!qb-Fuo_*I~N5v{=F zlKt4`Bq5=j0o6Ppj91MPwTit_?p-04;W_}mS?V@JYDT|4#>Cs>p~i{g z&^JXf)w`Q{Pla$xBuGt__NOa&JM;M z1G9NdT+QmNaQPnA^%4S8fIGTdAhH+5u}V;lBq&9sm}zn`vrcEw&sKK3C!W^-Y#eS_ z$B_e3E_*Ya2g+OrracF0t;KLwl*w>Mgc18z*MEP;>Zqf;6iV7zodw3u*C%2T@l$HF zU4_g`tG}I&aB0Y^tW1`(HCZt8VJ_le40m_xrxF~dN4dW}@DlmG3YqcJ6m?e9B38_x zHpkB1rY6x-HiEAF6mBTK|GSToIf{DClrKMejEa>@aRiBA;mNb6FA3N@kC?0OFm$p` zU0Ci?^~gy~r2=nJvfeTCb=4fXz9d^4gPKiu!gx?aP5vsZbqcMeRn!1VF-mnA5H_{p#KwmikI(6Tye zHjdrDvGQaNRXxo_y58(dznFf71!t;%(6PvWbol%vH;SKHC(nDN z$TNE7nS`)xA5wzbdTgdSY>W8zMTd0l81C=9K2#27-2jcT*yFv#Zg>{D^*Xr1+wa+D zzxPc6KZ_|Rs(nIIxW?f-cf!jxK%~S+E;D zIvmZ%gjUy!LYNGeJ|RFuPVlS5k;tNxVET=v87>dMs1gOkc8TP6g&9Ol{l1B;ktu2V z#BUTwk3ho5Ad!59yfqwTC938er=iCcm;u0l*TuEE5^S zT_1<^xN0%f?DXia63IqV@|!<2+q}nAO#$-Z?!sboy^^`UfN8u@c*fn!~o*qDd2mNw%?3jBJ3uWPBJbT%YX|21*>85w^R1pc}aj zmY59=mMJ@gL=p4Da@e!C7@sBCKKrG=J;nTJSNb7-IfPLR_ZW&UOCt2c(A-Cra5ODt zjKw{@)Yq?+h;M{QfSmvAPt?$WWNWk$NlTd2mvl%=`s$iw6zivHV zvIQ8Ddu10rAJYSs-O^3$eYIImKO0f6Hp;lNPX_GgV4+}Gz%t18Df-B>Gla7}7PEcb z__KIHuWp5p#7HK^@?^zwxGD0q4YGcYp>kvEMcVd1%XK=jO7FetmbI zeZrc@g`KCYm_z*XBY|C>Fni$vS)mj9qrU0w7d3C?8I(mC`3JQ}gJf1PoZR>cmN{|#3#75K)W7Q6Q+&lAE_!iS6zi|( zzCtHS;TmrX3KIi)$P*~}W?FuA#cPe8z0J*1OR_IDP^rf1_5S{-XTub;dKbvbMX=F)JY+U*k$z{Hw9mYi$|6)2Mu>6sfrtFW3~Xs@c!B-p`#;tDAPH zoAb}XG^v#sGsL~u=`KrN6@Tfg4Z1O|k>4kNSovED? zo={-ry+?WTw*aE}ICnX9{v-(ymYR{(y*asKiySP&C+sDh= z1p?}t9NT!lzH41ApC9Wix9l)<(C#hIeZ7DgU={J{;QQ7={T~xV=PpNyUU}ytTgQ=l zH|c4or-RyA!1MTMz4^0}4U?+7xW-4ETE~N~CP=rSaW`cqF^H-HT+p3!V}Ehd0ng~N z4XD~N=|MO)?@82B;r4NF^vE6v(*>$2ZeU(<B%*8P#h8Zw@Jm zyj}+FjZn1>xCR;+Qw_5uIR+b@53i`Wj`K4m&#yJOm6hJC>W8 z_9N|TZKmObp`DHI4VHB7Zyl5~z z9_zGGG0k8#hBUJYvj!$ts}m}ENbp8TsUu)%Gm~LX7p7Aa8k5oOz4Ytt&5}*b)UAm4 z+1T>gZ9^xn1Qv$y={|?4T-<8W4l72yq5iZUiFL#r8&^}A1^#t6o^>j?Kagmgex6X> zVdZ0)azd|a*3_KoBG=kj4CR8Kq>ri`rW_3SC|OIUxq)n**es~D;B$}?*WAp@NukH- zHyu+z;TgxH0qY^WJ}4MH8NVud!MkHN)na6|yztHMTIxz$6|UycghgSqQTqgFzzkV1 zAtYP}68!-Zhr+btMzGtBovK5gsP7&X)X#qnxX%Tly5o+YEUjh|%fmpf(6w?LtO4h> zp@g-O$~B~2o!ku?>G%{VHTmxO+_%H!hrmU#yLnGKn%^jZKcO`HJv0C~%?Tat1qy&F z7k@YzEf`9`vP}!1hc3o|^VL?L*gS=h-+y=m&RVX}G%M1}LBoZ?(Oux6L^xIz9LF5a zQjKA5EKA6}L9Ds)%w>Ztaf6r}`&0J@_3;KR{w5vwCUlaR!DW*+5i1>lVbZs|`{Xa>gm#*6G3cE#Uu=ic$u-0^nV zal^-O24j;??gSn0kUio0yY2k5t6g@Z6L({){+nIRy_f2;69ND29Ljdq%a$D`mdDRt zSj*TZ1=d5}e}0}g@RZ%g{13X*YI7x$Km(ifp`b{^)m;wIxq*SaXl;`R$WqfT{KFpZ z!>+1>u58qy#KV!Q!?DT3iJym-@WYwOLt!xLg3Hkl^CPZqxYE0WrpcrA#NWU0kC74l zE&SixF30FUf3Ied{w3m3kmtEVMwfeeo;>ibQ2{92XaF}Mpe1h&FrlG#zagt3wqq$_ zeN`iC3_HiFAz(5rXgwkb3L{oL$^NOFDyTjus6{MvEe*b#{EN2r*GL}hGzpcII>B09 zyoO@Bas9yhKF>ASazl0cymCx{VD@_yG?_u{9wzoVTY74wCBcGm(@eZf~Qg&0@B-kcsr@m`_q|GPWNFp0(DO1LMId?y2k+UxHcpW0MghP8ZXK>|qDz^rfm(`aSK?Ymr<+*b4 zho*m?0)8n)D5w>T26XiVbbYfHJj%=pY~?y@m^TwF2v_fkNmP#tE^q?u1D);{MSSH-|OivgXkRCRl);$ z=|lgkJ5!m5mA?-;h)0`OOFw9*mji>7A0LEhANRYSGNoo$wSLSe!4|cimeU{eejy%< z2oN*d_p`t52ME9bG<-(GX}D|z)-!IKrDP~lKcdnsFq}c!)#O4hzn5mVl#}Tc6X!8? z=vAXdo{nIuA7mjITr8dOY;|m@0Z2lc@gN8&81qYK^RUVu8$L^(rRg)^m5JaMg=j|Jn_))h|U0 zn&@crnS<-Z85~J%o$Zm87yrkuu3)*Y8aK}oxczx^zWS?D#!vGCZfz%pf+KhW8^uIR z?!3S0tC9r~pA(3ktEf%p0|*6GWbyvl)x#FyYSF>j%^M0NdiwvdtN8|~F_$+KDIDtw z2OzfX?#eXoA8VAMuH$?v^!8M>DvU2A`BjeXC@*8GvC4ngIAvDpOwv{nXU}1eL01fDZSj}P&9Fn^dTuSO2g(@XGUz| z+$NQ3;@XEtZ0bIClw#_+;It71EZF2N_AMpmEAx9@_T%T?1ib)D|>}s-Wl(gd~^8f zkiXh?*HYP%y>d|YN@nu#upqQxV=GhLp_RfQf{}V3wqRgpJ9J6;0wB}qnSQfkMNx3)p>?R$lTP7j ztZB5FPv{$7X6m;UDCSVB;hN~IX&nCzA2N)T|J2ATupTfC(EyHGuHWUJ4Dkf#%67Nd zW?ACeV68NR#0_;m-VC_-T&$X3cY;D5K4^IX-Ft=BX7C+(Wkb*ep%3OPUFeHbq3DDm zLfI@}YJGW{gC+EOwA#+Aj;Zh;IF_h?m6M6GlMz@WuxP1XKB>!^sUV8|FuvC5aGnxt zGR0d|X-qmat9ok;?V3SoN_T`qCIhOjyPR03rFcnuH`Sn9FMcZ=b+V=pM*>Nzg|L$F z3|kSfpaD462&0&Izflnlt5WT#w3C`{5y<)hMOu4^WoC7t0XItGKUF#+o8=Omychsz z-FVKTbeR3q`7lkoNNT}Q@*Nd`Y`RWDZ~*~8B4&s?BKLie*9J?9sWoM>?}&y=Z7Sf# zhE>@}4NyT(9eUD3)CmRSm!OiX-h@kP(vcYJo_$WAXJly_R@Z)?@)0l$kccOYU}Tl2 z=2QK{pK+^^tuXibb3qaJcedmgxhZ~F2*8j~Ivm{xE(fjfV&Z%)Hl|udoVKvWB)QE7 zmOGKdmcopX3>ls>7$j1tU{%&>CWHY%k0XZ0uoO~Q-{X&WXNDO~6 z$|quM7&QnDhI4!h%479_>etR{k-QD}V(g(xim;J;xiXsu+;{lU9@O=fyPO~@V} zB++F{-oj%fU%VO7LEqE`unJ*mc$dlMzaJzUw#LQ~QP3}gUb$J?*O^-E2&}!_9;}Y;B(}3N>Q7^3utsr%&+mjvqn-El$W{$E zpV>f`y4gkRM;8c2Hj`!Eb|a+a0&w4G4}cKba{7ri{V7UJRBhUW;_V-P6gKx#bz6st z15xxgFX6NlBq}aJ6vkm1d9?D5SkyQn343@ACAfs#?g=;{UD#;UgRCkTK01j_*s|2( z$-OU7a`94$HmU2VxB>42)=q#H?b}kW+fQx;vJni_qq}TQAgcwk=^t%3>*anU>frNy zG602zGAE52ig^U8F$O7S*qqU?`>>{-yC7bSUP25&rZ(v>$T0rXOvLq|Zzp!+U*Ge# zSAcZLfcP^^{*QFv8+?UM+Or;s5RO!ek9N>D_@F+vcEU%wZ2~y_n`e$kQUE+3tGGHE znyU*iyO5`SgtK~}BYIi>1PPIgMOMKW;R$KAZ=qGqgNOBPW|1LA<2Iz2sFQi|WRfAz z5HK!)K1xz>jCC2|&7k{g`KbFxa)9~G5V~Lf4qw{xR0yeH9>`-?L2KdJEm)Z>+YQfM z|Cpj5f?4%0%wC%8?^Gy_SDtL;ZYXOg)dM_Q)W3EA<=p}lPI*XcDUl`qC`<%9I5pLp>fdW7edhlEUmR@;z@s(f!;TXS%54BPrBA7&s*!y@v z<>~pT-kfoh@#fC%e%2fZ0!fVuuK_-9lqBe={q$j2hts zW*_x19+H`=(Kq+Ml0E#PqkTJ~C7t~7`x<3nJ3u6HBZ7q$mFlywI3U@DI3rwg=lPBp zpc9tp$iKQg{kgGVEbAg^iwYp_D{e5AeI?8hN?i?!8UIB?O^zme5>EDD;>eq5U9Zks z8RYErjUU&`ZJW&>dMkZ(n)L1vHCeo5|DLN$a_PqW1I53qYwOsAl~>jOML zQ~TMMrU#iDOZ-Fzg$q;4>%cKG_Q)yabz@*5mqvXVdLdC;l0B`+hX<d>C3^C&n@o@MKsG( z@XGC3#tyx&(DMToY{>DDV9Qa-vwrMVQ0P%4iDA^v4@>UnAxZXbi=xa$(X*ikgwwNy zy|;7&vGFQWR123Hb`-h+gWS+*F(dp$tBRMhg;r2~rX!JMvdk7?!G`F})kH7tqIrhD zNsVGz2`bslqr}RCm_r7dQey2S2W>cG5=`X6P6ns}N|tCLGKM9*ywS9%AvA80%+n~W z$cdvE&P#Wmci6z-J1lobQM&kr*bgbaJVQPlOf0^M3Jsv65!=zyCnIF>pYDoJu}?A2W=h%&|%O*wRFv??>RNf+H~INI|@ z4Nwy5pdB3u1KDWzl6mj|Lh|Tl)v7K=k^l4^g6&Mb-g%+kO)~Cv0CaB7b@Wr4Xa`M_V7J<6gknw%J&a7N(Y>{ZCdJN&u)klbA6xd) z=!{q0j75j_bdV9zmwr_Lu6a1Fd4yQgJU-O?XIJBDolJ=SB>tZE@1v;gSSh88uUxuMlq z+Gx+U(SxQ?%(Ov4+L*5=fo_q*w;0GC)Vem16BzA!CETqW5`G7UmKHas5wcoyeK$1TCoG<&8x5f{KbpHc$OPhTE7>x)hWsY+Ny>6 zq1E~t3-csn)MVD&>8K&HZlJqckX6`=5tA1-&tJZd#Kvm|nKNRFMCyq>i(wVQG~lh2 z*k0IX*LZ>bGE@cBY4XyY+Q4H1%Sc6()(-gMq?T?09SUs@o=#=f)`f!6SeRm9At2^t zl!8*-SKd6X+f32GFeWG(A(uhKbHm6iOcZT&_u**o>ZpcsZ70#lU^oNdM7!f~TtGj{ z=LST)uo!&w((+jh%p%8UI7-UU@Uyc~8mBj=0W3N#%jj$6a*j4Siv_E%opi>LQO=`L z!cwGHbF_O1IvLQo;JIgw_8>h9_aae0ZjxImnrKU`egou48uHZHHPkfiqc`T5z|8RB&NAE|wO zj5wYFn+8ZKRvM_GjzA z(ClBoRv%Ya9~Ty$W@c_@W)Q0xi20~r>+5T4YpefZw3nBc|4Y)IpPxs%+4s{^7gJOB z7sJCR6XW}1qx+*He@2FHh6e9?dl8+T*PWfW9UbQ#9Z%!l5B;HtJ_AID z(jffD)Z9OIdunQGe0&@UZx0U-4GawQ_V#umih`v)H-dUM?@;S6SJFT*%qOz&{dtFgwU2$oBVO~Qaa!Y~qx63Qb zN=r+Ni;Mreyq%Sm<=gZrDf`2l>TuI?@1!ruu3x-AefpG=@*ycH>0M$766Mw^H`b`s z&@Qvo$~Arp4@bOpUkZK~6B82^6%`Q?@h&tF>1GE71^N5?`}+ENdwX9yIo;XHUK+l< zR#$%%7xem%n>}r2uq7es=_!3wmuTeAuO0kn^hfOcY$ma9gkF~h+k*{i-P z)_^(#N-TrnrJz5r$o~P_oTo|uJD_d)56~8=ATUq1{a=9g4#m5N#j`(-`C3|@Qupb{ zzc}J${sG!8{dh<~yC^1@{{IYU=Y$gLE}2C5*6-m7ZY-g_0bsj4b!wrZ7DTjk34cmDrd*L621H*#`L zl6PM3=j-_>#;}8*no;2a?G(si!~X-&ezsB^$?@}jX^2WMeOZbEudGv$rk}r=SsjAr zuJWD#3(zhNRHSn&%Oc{HE69HM!i^)#vC(ZE$HQ4RC2j#8bIuRk{SVOg_J0^*a|?@s zV(Hxf2Waz`Al5*GB`F#LZY7Dzo%~=#l{q43)pzxE1xu$nZ{^?zqBQcq+jFl9fx55% z1GKfj6ha9}`hhz%#ozuvK>OMq%Af(o1KQ&xI)`uW91?NA&W`WgjV~ZE_40W?>Qtpx zSM=jWjo2K?e}J|}o!u6Rt4H1KCt?R($3gHYqLXEhdg$4FwJXtW8mgV9d2f>1WC%5j zPbCAL)k-Uj)<92ak1gFB4`_S()=>YT=Lf5o+1Y{kTw4(1oP3L-6=*g^yVi_1YmI}q z`D*-p$k?G{Dk!TdyK4Dghd*X4T!d_kZqdvQjB#jcN!(+l;Q;kZXbSsh-C_!PKT`?Ot=>qhqHDzv1w zXan||-2WqvZ=HAT!oK#`r(jJHx%Cv80xlqi9v8rPlb2E;xDJCRh!aqS8SEau?O~mI z-LxLGboH8|;G4F5!PA|zy}GXHc8_1b#%8uTQy>zu3T*q}mm6}bI>|P&A3XbNFSizw zN&XJD-e3Q9wDz>n|9JUd-LsQ_9G`vWrwb|meM`{)*xUbJvyknRZPf9>A~4|9UW0b)5- z$&dkNu*DYJ#3h(BH@#45#r`f^5OWx;PGKpV7ra1QxB4%L;$f9D6`G`&Sb~mUnT`TI!`S;tXj!MCU)k@JXg0N_ak0c*ti&(__^ z>Muv-H9GVa>rzsN&bibgevJJ%Ja;A{9guF0zz)R;2m3$YM`cbd=J2-!q;$K5lk}6B zyDwnaE)ZHEF>H7Wi1!T(Ojx~bGC~MoEdns2`@=e=M*2ZF>6@z8vy@)&{@O=s?*H;W zEcX7PEeSE9mlWqSxuyXa=Gq5HruyeaQdA*QF(v&q9WD8WxQCi%vEVf7*?*9V+eZT%^`E~cwik-P&As7Q< z`f)i1pgtHzgh+;x29C%cMI!hPH?Z*c@=7K%`lM-g1Vi+eIVI{U zjS+^wcP_G49~*?rOxa_v-lq%+d-{@wNZ)E(8eH}`4&BsFfg6{yH#IPYUAPZz1YC}W z|MT%ib+5n9xkOfcd4;3uwi}cT^~(oBE3&?*zJrD)xVh5BdV;^J7~65=KUQ zo`0cfV{1+@KBe3&FQVTpik0)jTiSUbrW37LpHG z@q7k~p1_7+FS26!pb{}5l_jwHoAxn(YKKQbT`Z1g(;mi&{|eqwrK|)Jwl{*9e8NeF ziJDt42KL5WprJ^XhpsUi@4b>U`#G5)0}v%70O&V=Ndj={vQP=Ur42B>c6x^Yn*Aw# z%w#aI+sGI9P|^NJ?(U2A4y&CoA8`A?hgr5i(e^ZCo3}q9GRbG`&a#qw>u9l$uAy+D zN#P9;b$dUdvREW_jol3i(b<#8z|y;W3vDEu%0Ua6*R_v6MPj4tevR(@K}s9M(nC3e z3DqHtc3_g@6v{KCmjz7-L^WhIHUxs-N)~^nVEAlaCW28TH19pT_ApvvmbnFkk;cwCdx_LBM=Xl&~qf8Q2w5cy6LCwBuyp&xwG<_qwSM;li2`#{69OT^SPS0EUMD0os?*cJ0w_59B{=qi>2L zdkwT-rE6E8ivk|c;pBrp z)|>$OyPFLV@hQnJ=Jo?VwuT0OVAkJ(C*)S?Gn31>dcSBWhcd$~<$r*7R(w@^d<71a zXB<;JtegBx7fhx1#rS`Wwv*oLG7?J};L8c|)62-Y#Yc)G4>606mD^+~`-$3SDcc%6 z(V94tv!{ud&T61HNCfB~%@W0*X^E7` z!pp|vFSC+g?Z-3nz)hE|fDH zcoSv6lBWDN+HqXbWG6Xs$I4+;!C{WK#>l-9M&?s73Wsg=5X}X zvXak!Zsldv<;zq43|uy!lX>Wfzt!89p&pDWnjJcGQr1f?egwYYi=r5Ofpw7FOWBoJ zEU}8^22t})Dm$aHdYffzc2->nkKJ39JF$q+a;g|#l+xwa zo97WXX1URi zh&ki?iNa12DxVc_Hs<^p$zPQ#Jd4O{>Ub2eoEHSkFTS0_G)Nc*hgDqW_L~cw$mP}E zEhLFY{LGH^&Me&O$YjjUMZ3IgaxAud1B%=rsss|R-HHYe?l^T6aa+L21zukMepc`- zcl&qo+uf3XbC9qN!b9THPtS@t1qyjOOQU^Du>O*_EgT9yNZxXHqI09ZOUSMnU#25Z z4cZ_KOChMJ1WU&&ajf3qnkeP|TFUZ8Ts0nHNDS~f7Kk$CyJ#aSWniy1icPc`en%Hs zFufw!Dh2vQj{HOeE%<-GcokB`AKWSWZ!4zWCBN%##g$>sqmu-TL4o&8e5qMgsUOp8 zan)DtFN89JUaN}{Syv6p-$HXhNmOcXmyxrQt+4Ps52P)HGY-MAV@ zEbo|k2Oc&5D$wF~=V~=}usYMIfV`Y(!tNqS8i>LGh(~A5)Yqyne`?-L)W6878?k5rbQ=C1)SYpZ zdLw~mg1XJG4J)_baC=bGFgNh$HZmzRFjTXee}Kp#>uIW-r`^S8Z!8*r1U3qL)Y5k~ z9tt!ZL<9x<03O=p3=?IV9?4Rc;xf;hiYl9wJ>DP%TLhR}K2rf+8$`+g(EO6*?ngFV ziwsJSCaQ1E3M4H;xvlOxEeexOSEt~xej*OB`j2p8+iIt$&+C(`>Rl%5lh9sFJfNO_ zic=&R1+nLid`rxqCX>nbL!7BS1u79H9-Z8|#Qx?LUfPf?ngPX_OUe*wf`RpOU$>Ug;~7qc~{m`R45S;{vHdyF{DV+gv0TFK~5;u8i21| zy@wxrkN)HAsThaZvuum~^(db)%mWU$mJwa2yPIA1v~ry2rUqrJg=`5JmhG370IOd%3u z8NvhFl2${~Aw#lxL-O52ifcp4S3^jaVKv2JwAHXi$gq~s&?9)!vlG~K2FYEP5hJUi z%#(rLTZ5ceem~Q~|L*nh6hYwM0t(Cbz)T5)^b7UuS)vc^?_jG)q~mIDJ88 zx2q^JkvCl&(|XxG>HW7oYi%}~qZCCt^?sIeh-{X_QX$r}Yu|I$K5jNUZ7(Jh?p>-5h^lFn+$w!&y*fQnA>mO}f<-_eUlr?Z@I)d`)+s}1IfYI!>c@oMpY_jkB&V<(% zU)Z*&7@TColQwbJ;zsw=`)v5r6Y{N#PjVtWymnx5L(&!C%d;b;;DSkf=X#je`W`E_ zqaNJr-?Bl$F0OZf9J_N?Oz4h05VMD^`0Qra9e_n-?!U5%vs`t(kSD zxuka^NzLCVTJaIMK9PZ_qYclXug4;r9tF>8MA&&ZzKVljD-EQ@K}Rprj!fmg_p)t= zB%KhZeg~g!orWI&tousK&*P3DDaA+-i-VUj+i&$cNT5Fi-8UyZ?;!4 zd(`@8kLix~Zn}?;PeEk}5;r(?6NY@3;_O2DXvgzy*U>?t_xGZtGm^~{u>J1I^vQGH zA5il1$YSD>B4Y6Y$UU(W<-V`it4D!dTY57G`AKjAQ8>(Rxi(CK=?FP8pV0{em0?mwNj?~U*& z1u^Qz8@+F1j{@HI{hY76A`-p+qQVevyH8{NZ##KqZ2Iq`8#Xx%`LaR%=RSkeNBGIc z`MB2^Pv0*9gxtUb+T?7|2E+^)OHTP>|I41bD)L_)qYu9U$4~;RQo!1!;kGK%jcWor z+h|8Sne#f%jxo)doQBoQ9>RTpPp?2J^cu=!yl+qfwH_48d9$5Z#)gu9cS%!)dVQbr zL5l_4<3Xh5efQI*k&W80S9v1aL9||TFZdREX`j(}YwMPX`9rbqmaTe2|6LQX1QxAz z===-XiI+XK=#8(H51R_)Ayx^~qM4dYwtU{i!mLBL`ryQNu#~cj%A^W8O10duBgSg^ z^Tu=QlLgx!=52d9~uU=Bbu$)6VyV z6S1@L``2}-1Q#fDSN+hDaA8B`PFME$){~e-fIkI_A>fqHRZ{h`|BcLmx`!d`Qgow5oEFR0V(q`aKa9(rM zWE3TggfImzbGR4*6Dgx?zCv#+H+o6>%hGcsI^S+ZB;#{tg`x7Yg7-x$=(G}VLW3-3 zD&x9>5COje`-`Ohyd{LBSBa$Zd+d=ovOGd6M=~g4#84~_&_9@bTbx*A))R(5#cXC6 zV2IHT`bU+`D*lq2UDoWKbhpvrpiX@m->Z689Dws?lYbQgoQJx1x zFVn{fiJv4-hkb+iPP-CrM{>U50|EV)V}ub&mwYe)G4N0dIN6BhFz;t{&2nPU6i{5$ zKF}iY40v7S_q{Fiz^_2!{j5Ky(oNn~ky*0#)v4jvfn+5LG5)47J7&v&eBYB_eCdw_ zbp%9-n8zZK{S>CMMUW04_9)CQSqD)B9X5zT=GiL%R$HvI)NqozwEUZd?YLle=%!|O zET^CE^t}-Y+fk!&j;q&h`a~;H>_I+oL-AK(f@G`|_|A|ztu5wT0OkhP80pvVfY5}G zDgUIR_)J_z_H}$rrN|c?fpesVbPTD;8{jW-`=9f~*#we3$%JRjB?vIuw`jL_M2kWLfa5PX1tR#Xg=?Q{q02al710@Mh zAXysmW7(WH3HbLb-fYo9)#{Ye=!HbWhUzdEQzMA8|e1}wctB}K;ZVu6sOn$GJ1-_T*QLM4Ar&8lHy(lFO3fXo4iXRNj1 zmCO?V3y$QHJcrG}N2zWRC%Ob;5QRuhK2QoK&;Sgy?^hsQPLjp(X832<^&d=}GtI6J z)GSZ5XyHph;IgEfknR%G$MMnppUsc?@rv2y1`z{G8RrLsMKLN8)@Z`fa8Asq3?A!uqVh}HnEd6Ay#@5 zGZS*wQh>aGnYAM8BcT`}m*1tz$FEkdHg&{qt_4xIb>wc#Dn>a^0ji-4*EiZ*x23pveX5KeU{;2eQD~C zCA$9l-Tmdq%1!Sn7v9#xdu-k7v}`6{9jke@&i3%wCL0$fbJ4^7I+e47f3V&MNWwER>-Y{L?GJEd&lu5pf_eoECSM>x;W>DDGbvcwJb6rzJ*_t8!sE9ndg=3Sj)`+e0UgItFa*#CHPM5 z?v5pMV~oYg##Af?{j%1h#>`UYnwV{eiYsK=~BHz_T6>JY*n04 zhq?7$3hDN%9!Q21PEOdxj3=qfK+3o(?J)7J4_TA&4n~$f$MgvM7(EAI0I1}2|1+fhn=*pe8 zPP@bFd#>B#2fzlbY}3oYt7^6WU$L(HBI_c?e|2#cRDMlpX)lmAl|1^ z0cxe0u}az!GnXzOuXgioWtcs5Z+s)|a({iSP|_wz5bXNp6cj82BiMG|Uy-rJzD}mu z@YN3(H2wTzu3XxX%I{%2QTsV7<8^KP3^lbYC;7OH)@%LmAwRjCe!7NB?9~?j&A-0C z4l~qiP4x~4z0Z1G@lQg|Vxbr1u|l_qRz=912J0LuYNNc8%gDf z{PRuqE1s8jkjKt~@LMB1X0oJHuNSJj7@^6XC+!Ia;P5$sbxoCzh5jH{1wp1pbf~7o z$m;9{TRg~E{i{sxsK%&>ydm(VGD0%Onu&Vsiwiobu!X3W-yh^w95{Pj`b!n|X_fGg z_|UDjVg_zyq4T8b$<8EXO4E?AF;Xpo>!AnhM~{5?2@e(lG>#9bPNCjQpifcg zV}3jyFlC@5Vx3M^!Y}7a=+fv0~4P|(52xT=y@Qg*m564nTz$~HBiy9S8P&e-$YR)Ak z!gEuKxU2h^%P;DZ=Y67vQHCd@F|LX48O9u;qYi%RkBvt?oJO7U;yDiMSxb>hdFqI2 zP0<4k!zs=}tmP(*dn_C~fKeQ4vecN*)y#$s33A~8B&+Y*NK#&xC-;b#Q@T_;+j*1L zW5Kb+^s(e~Yf$kh&TsJrPcG#!(t*hhFM8xx}dhY{}+1mK7qa1l0(^OIa(E`v}=d?h_r^9;I~>nRS~8j+me^Nr66RNlP$f9MK|z zfyHpq{$i0VpXS)4aPvatI^$8gJBxZ3i~0mh2DD3tJWEDWOZU~6j7^qIoR=Q>{}0f< zSX5(x){vQ4uhgPa{s(C9Ea_YlQC^h5)p68;u{!*V>UX1lRI_<*jH#XSm7RqW zUiOdBZXV zi4t??aVdu+%|$abX$Bs{a@hW8{4>Q3V*DHQXq;(iW}!>tIFb}W9y{|pU3s<$qF{qq zXEPSSXDT2i)*&S#Uujx)zWK2Er!|v5y%D5$)6J zhJ1#yIO4V2E6V}RbZAsP`O=P~?xX$vY+5K}Xq}!0a2kZt~X+0m>Fsl10Ie(@5rB%M{ ztw}K)LI0B1N<>SdybZCA#vHQ54yaME+EAC?l(PBQWBrrGrqE15ToT5+^2Qyzb}Y>M zlEq3RVla6;LSWJ6*Vg*%`TCNs?G5hFRf-gtFu37uGZdKRROgrMmNN&8j{x zzq9>E@cD=~zWS;>wT7VKjegIkZrw?1P*+X(z;?^uig?{BA1C9* zg;SYLFn0a;tr6X}v(YPQtmy`NC}lxicbg{0Zb^6?*7~_fYaQ=K^T>W?K6=HZfvXxo zf|YY32ppDfZE^BCd|9+>)r~)0s*5m)$gUbRY;YI1;aPRz4zcj%gM z5K*=v^4{dSj#EZ=N358wwunfDeT-$@kPb-y;z<5}HbSoTwY>Czg5KuV(wBnqUJ^Fg z4jx*?uL>%C;a|QZU176uLGi7h!l+tHBZg0N-EKe8Mr(O1zj7qXT8o<}|76sAu!#z&ib_7YTg? zmA#9V1D(2~o(nC-XIi$sEVxA^11SCtfnv^XajlCx-3EnAx}dn#BMKWII%S;HL&a&w z@CPoj8;+4HEACo#Pb)s^(QUJ6FnM{$|LU>0sUvj>N#Y3&5V5>AH*Nj$_d9H&#R-7F zyqED1$PkWEW{TA#p?_l$i>vM^*_SYK7Uey7;o`h?NIa0!7T@2LTIbe2;v6Jxo<$kE7d&9JAz5#&$ zt)UxFw%9jIG;sA8-FF^xksNYA5Q~tx>af^!KRR{KwQ;Y|*wxY_?qJ1{oqV=z2lSI3 z28MZvP40LWc&zqAjaH^(5S!iW1wB9A5`TWfXt-x1BHWo_U}V1MOoqp)%T> z|NDod=H(+PUqV+uWtZveulcx{is$qebVu2|M}^Cqk8U?5n3?Z;?~gtB_;K3%=kB-g z0Gv&UWP}-n3vJs*_~@nJQNEonlj>0gO!Az~<$!Q}bNP6!!tEC!sU-w(J&H9q^SILR zk=3!t#>LtqAl8P*AApu%=|?;#NKl_Uct#7-*HdQW@{SkBO^2h)>IhKwy<~G>kUWYA zggUkp`5F+^JEYur$Jc+$wuv8aOd%D%HtnH=p6-f|HXvpL{cr z!6jjcY>eh?KJ@f7eH3f&iMt{5A>ZXXOW^XoRpQIe9A^1g%KZmprju-+_csk#G9f^~@Lj#tk7ms4bUlv2 zfWRk($X*Ph4aCB%9`5IwPro}I|fKgcG}q~eI(M4O_x z9-W(poqrVx(42v-Q(y>@tX{CAd&l2s_I|YU;xuJrf=^=f8y+CqW7D;ATR@oBXSwa! z%s^#s*W274Dx4K8R`C)f#_$nOnGG{q{`zw9!48mG!QvOeD28L?pg-+I6S$Jk9W{T- zs$9x>&{H&=f7;@@A$fm3J!+jFNMs9xMD1ggS&2Usv!ZXo*5+8(-8eU>3OM_TW(9CN zcW*D8(W&QoQgD66&gVZc#b#*R?& zxpx-5?0mWkz@$pFLHw>K8>(P(xP<5ae}MKaKBF4fQ_j%@CKu1dPej)&*2KB@d4QK-yjH-~! zyE3xOv@c9cn9@o@#81k8=#UV;p0C!%sG7W&Z@yf zGQYWZUGvyd1piD+WanOl9vRfF9@O3I@itbAB`lxKEbUjeq=J;<)ZEZbc8@1|37GFy zIQ3l(&WMrRY)uLjdH>~2#z$07M^3<1Z;DtTVuPvwJWo{NKcm>^My1{Q0%SS+qR{#ncCntRT6RlPa>~jA5XJMqT#b3jIPY9XQ4S05MMz z>fQ809M+AOBF%kD+1IkvpObK6q%ZABL9QG$)|%ajuLd|GL#pRfm7_B+VYhy*5Iq4J zNV45dqH8`P9FeYRT39kEC6pHBRX-6$|4~RNsiUp~jtYv5q^$`Yew6ia6s!fk=U~Cb z`(c@fF(l#z0E1BF1ZtvtNt5HnF&rh!$(BOJ94t5g8}hPKew|2(Zz@-(aZ5#DQEc-m zF^YpAdT<7Lq#Hj0uYmvSdlCx|o$<$c&AStc&td{vb4QtaSKw7Gn<~+gJaw*&RMrom zjN_H2BvZHV!bqHG3PNy%FUqkl^G$Xkw@0;V%4Zyq_Y(rrT_jmcu|M;5=;;DsWLL99 z{_k#OHbP!~iEm3CXB{RzHQR&eA{b7PPIO(BYD%b8q24PnzG8wwJA7`&==x64^^+-> zi*Jrs)`=b^ru^;T0lw~_nLGK1mck3y6!B(ADdifLUy_50+)lep@6+O)Z?d`+KWP%4 zb0BN+e52jjAEf<^FSXzf)eIddma$GOU zi9O=7GIOf~#~nYD=e|N8_ZO>TZ^Q&{c9)u2*Sy;e*5F{IuG1@nepGs6*LpTX+rIUL zgZN-2tIWjUgt{Z0oY3|x?HyJw2^`O&?}7GOVxr#U zH9*8&H8+Y)s)kn3FtN;z@oI(0DlFppg!0KVx#wDnZ&Y`*sk?Y>W5h-ZJWW)eTW~c@ z{9w0ww^uqP3N7jlsQF>Kf0F>^VwA)XS#1CmHVP*grG#-NKZ8Sm=G-}T9qFdMdwZw= zC+KcxbZ44cI?brWVw*{;MyF8flRyx#K?uM_zB=CXrkFnrYj;S}-Cz1`*(06tRI}26 zoId#eXVMi1`tpBYk*10z>=8s1loT;syj9hLLHyQHyv zq`lqpp!#8&q7O2<5#5Oqy-pRW-ePa}9j981APa^=SPmF=OGG_KjZ!$9C^tdUHN^q- zcM5b89tb)P+x&c!cGGjVznffOa)uMWEG7p7vRlSiFBavw2kjYRWsZ(gZZ$+QjAID= zDr}C#`Fwg4`~C$TTEsnCEM@y__dGAT;BkHw8z7`i-fKEUs478oH2m~hWBfPBH&0bn zrAdxAywZN{F}u(RbmYld3X%CZgl3>k_B_)o0Jrj2vdIj8sztz5F75Ubn!?q`8Ohen z`Z%_H2ynh6KSQTi(P+{dT%bSu(aUjJ<3Uy9LD@XpHCpx_a&~}!VAPrIuFw6ka@+k) z+w?0Ger!an0id)7Wwelym24=Cn&b&e5)(-VWNu_r(Wgf$+{FrurGQ23#FvI1MVl#U zZTv8|%O}5KM_i$$4w2g2iwG79SV_iy^el}u_O9%>iq)*@3Pzr0jYMM@-W@5s5hWpO zH);PugIuHB)0Q&GIt~L7WPu8<5yaIN?%1=eF=Fl&Yxq4I*8L4)Hr`w%E-{2}sqa&v zvW8(92sOn)m2C+3HAH1Q%1Q~#poPlK^;LyNfFh?_IEGscmARw1cp%D(V5%zi zolX0Z7F(6eSe?KnE`}|R7wZU(Vl=%Xuu_Z+6i&JnDfJ z{cc89^GhIyAx-&Fqq8CW$oBpTO*8xZAs9ff5Xy?R+#z!}0xOa3d zbX^LvypsxCVk$n6IrDPt1Yoz7Yg|;)%RC5m;$~3>B&s`CNJ8B;U!!8*>ok(U(ia;H+TQX#u~&OOAYR!#)JFNk#V_(#LxS6m{>nOWxF~-{v=EMxp$L*B zwYx3MAGK~q;b|p($)mPKqA9r7-Q-7QuTWxFdw1#X zv#mtQ@F&PD4zU6lzC#Od2Yx|$-qY{MjeDrxO{}SPqMiA^OXm$AikC0s!SK<=`ti=J zD~X|9r9Jwvh}LK94xWOp?T>Xr*c=9 z+<<6ol(-lveBenqA5_7i%9GNqQzOKX5I=)K;O;QV6)GvcUkRzEimzrj(>nO)7&XdW zl{3S1H7qQ|ma?@SI8s$KEntz9stIhW!Uo_+0=#c;N;g%}{PHn)zgLp1x}1)hdn!tF z5n>erX1$AdpodJe22>U`RMVqM*wD~2C#tI`xDaMoPiW*p&4`WAsEg1@5RxqrGa4o| z9&a3WaqY;3V9corLhU#iaKI`a!X;?NdVqid> zC&3bZ9w~Q)QDqPs1Y-u((0Msu9fQhkpL}}~Q&*7T{F1=EV{2b$-Rfu1hqR!Ke)yEL zET>9keJtIuK+%#y3W%q2h;Q6OvY0vFX@>Jjo^4dLGTWv{%^SC`;N=4yV>jXe)u#jvS+ZyQSz5AlW`w7eY$_p=deUi|X$lvmWB3BThz-ILyKZGIYH{KpS z*@OiTTxkh`y%tr^;wGK8b3XlHlnOdC?6%AhPC6>7UVWIxY{CgXq=Jnwocy6~`NdT9 zg1b;a&j9(inb-I|bWX|^oYqYK@Iqwz+%Hlxy+V~o8r|^E)e(*7=+`YKwakdDjGjKW z8fv)*M{2p;3^g!5(Qan_7y8EbRhG`978HYEs0*I3E#>D6s&?s1`fHWy`%r z8J$)gDCV9Q$}X{bpSa(cx)UMmHnnni=hM5C*zR;{cx zqvIUcZd9W}+WomMJoomUC@(def$$ZuPm}E3shPmB_JGHxFHvQ_C^X^o0m7#zL|xTd zUV3Z_SehEuYB~bJE0iIX+~bkfR@UF(_W_uvXhK=3c1{Li9$7h?-`*0Jwhw=!_{FIe z#A%|QXN8|4b-3sRN?Qcc#Mq{X9%2VH(B@-oYd*C$m(5&6vaZ6vQQ$k zH#Q7HLsLn%T?Nd&5g zewbl9N`PiSa1A21yWacpJ;(w@AT$b)DGo%n5Aazx=e9LOwdz#%kIKmnKg62ao41)> zE!ticz8X6>VJD?SbFV}tVg^(U490Fy@a1SRGqov5znGJoDl$rR|L@RkxHKl+p&zVC z`7iW)NF;uZA*!>y@I2BK&1>1cB&gKR=P=4OavjQ{W~KHA48R(q1Z9y#+c#j@6&R2; zAd3T5nXz(0hk}8SwMQ$#Bi~ffCk_omDl7c!PtE2OrssaSY%*VKV#}qSekNFAwKEf5 z-v3wsO~UE9f>BWsJ}69*jxwYlros&w$3(5X!pLoF?a>b_-HTKWjC`@=t(}8iUsy0x zzy`v69cYkImHywl!hXe`Z!QS<)<-3cM@Yt}jrK9?go=z0QQv&keQjLb*sU!Y+Zt9GUgD2m@ zaITs6DENW<8yu;Ne@mD%2Zy)2p*f<9Q!QKp$$;y*nLYwWPq@N$!;sg&S9EEE+IAR8 zQASvuA%_6jea<3sl~#Da96UUjRG!AU$)NHZOWsXow$)(NE;GVu{8W_l>p?k;3+wwZ zCWSM{l`I6wG59jLUyyi^q4+Q^!Vql;Q6QE-^8eKV8(>+>Wa2dOI z<>g!T#E=t5N{WP_1rddhgZG7%f+MLW7(x6)T*-b>Ul^aRnro1y#^>?B@HqtSC8hPB z&l{zRQI*piKKaAfqoYdRGO6vDHmjmsttMr1$7Ft>`aWjxN3`pZTZM{l5zrXxkZReB`Dl2jYQ^lzczA zN;7QZfgfstPB`EgOV4ljI(lL?i1l7ZnR$cwO<8Rcvfp$g;=68@iszfhPx+(iGoIpO zU2jK+d^>1~N#)qbmo^n;rsFq@lttofBBMJqokTzb6?83n`}^CO_AYOoX5o6iQ}MP# zChx*lp^P>RS0`VhO?;0oc1t&z#JH_Ppzu|ujNFvy~L%`qrU)#oo~V>2J8?0N(^4~>GVf;^92{mCKA>_-yG-?FW{+thv(!f@- zv3uds>!PgU4k{YV^PgY%0*Ew=NXkj<0p&_lej`C^*Jf{WmCx;U*NHFZ;?NQBWZ#D2 zjkSVdKJ43>sCAP4Mty`&9{f8*iBMCJY#3~BU5=IE*SBx#!`<>#>4>D#FXwK{ZLuVG zbz3MRcsnEW=`MI{q4xJ0gV*x=^*hg=5Wu`7gZ3h7RqA;_Y#K0tIC>iBCm;sEbu^(o zf~$7U;~AB)`!Vo#g)8;(;*tOH6O1x8;Sk0L4QMbHgHf4e{zk-lM~1#i9tTwy!XN}6 zLw;IfvI+Co5ybws@WSZcj%@Cub(rEpeV_vS=o1KpTM!}FV~ahVMRCL?2%2GQJA^Ox zuoeVkJ?;&Xiz^W1-2%~EGjqu|ApJ@D({B0)&ykn0th4C%~NYQvlYvQ{XLeY6=%CoPphhTP*0Evf&{N$Q=_l<3fwDD87Bd_>3*=ZSvH^+3 zeANJl+35PS9cH)v61N;2MzXTsj6r0HkMkq8$2vAr62Y1Y@%1hj4D=8M7#5N3Z`YaN zJ$0q2gkex}G5hluAg9}LenTRQc|eJXK!LyWhk#(ns~wd9HiVdm;c2k}hd+*!aDuIc zB}D8Zg8Qj1uKRm(1q17W5^lz~5bKLlMlzd8N6`c(@wx&y=zx3;qE2HvA7(^}ip-Q4 zBi)6)ed-X7~Z!oBz!h=y{7cv zD2kBC{Y_WlmvCg$1X+6js9P7~Vz2lv1K5ijjGURgZ$N9OmoN2GFpp~ZT2KJrSJC;c zcmiC4!*XS^UVzbnlbtxJ1w|+@Z*jv^Z+oFRsw)Eu~dMT_@|1@*uB^x5Yvcti; zDS~LK`a6cP8%~ohWJi4;(QA3vvvJ}2-Dwj!+f>=)5m7+QM(L8}>eY;?rEdqNPkS%o zHItx}C)Dx%lAZjT!e}Yf%3~?7gx5w^^H5Ld2SLsU*ZHVl1EACa&wc$>S? z>5o6ZqTC25I`)OkGqm2cZBQa#)j?f(q7?bW?M{%G1@|z_{i|LB;?Dbz1&-fI69A0B zrKOb4fW1{mf2zM}y~a;GFQmsTxVne|DruFpnpyyl2TM}LUx$esm>ZnE!UOBagM#2v zwfmB96Fw)kv9qFcSUu^XMYN6^SLI8|Wd-!opPY3utDBgx8%Is470_zVQm}{v^%@g- z^I(s=AT08Lghn&?=eEhD90pXX{rae**FO`IUetYjwL#?=WK)3YPa^e& z*J##YapS38;nWeG76c@@=8^i=#%Vkgj0bqJ#Qc0%J1jQKd?kLO>9mu|-tABbkWt8O zJH!{Buj)RbR^skg7nSH*mHcs{CJ#xGcgW;u_6@V$l0<=~V-Ui<0rR6!+nY+J56yi1 zgl~fyUt5R{m_BSv*U=#{n8$e`#c-QcV zR{D(@JW(ce3!JmU*ErQrW+fuK$na$(8RQY+^5U!A_60PQ4NTB+q-wC~d@2J56`9mr zvD$S*tM?)no?DIEhcC{ftSF~cZCf;WSIP0OcH?suw9&S)5}vm&&BFUdLw`ASE0dsp z^TK3e%Tu>A4ET!BK!qbuo?p(~HN4(+!aZ7055LdH7evb?_Y6A*r#gy*}>7?*fniFhcoLgP7I z^ME<(2RMdB01X`aR67}JT0m50or|zlqZi(!Aq_(4E8RDLy<)5B0GSDw;c<~n;>@Wc z(Z>TRrjB|J)}%HeL*3MK=47H%$mV#G2i!P3*ltprxS|%fIvRQU@mG0c_nxw<931>t z_H>T546RexE{;gFU{LqOk7)2I*k8%ig0Se%Msyy1Uw3%{Pi6@iV9o`2ZG}>wPxA!j z=Np?v+r*ZadhV}-oE<@mo7ZEGC%?Ie`HG)#&2!7TpJNNan+=*B;P8$H*5lX3vMIlx zI!g#<9$xz<((3HV&pLN?$ ze558Cf>vAvj1 z_qnOr!^Js!uNFh)DRC(;^{bh2z7V3ZZXzD#X_CLmwf&RbDhP7fzFW4_?2UO7O{J+v_Yr-HpqGW7zDbMf&93mR{>eOV@d@j^!-zS zoYE$_VmJ9SfC6<0O$^ZKraJG!jy9*{*PI!e)xJ+*Nwp#OS2b!T_~HKD z2**_t|K~1|AP-q%*hvL_Y&TFZkoAp}H20B(lc1g~o#`$yl_?%TDUVt!o&kyIEuJgO z6S0{Oo!WV#%F7fZZM}E9Ns0!bRM7&<*9CIx7kUv_k&%RUKmf+m1~yX?%x{{v`0UOh|N$meheV3Q-xmyhzA$Txb9n9ticBxs^BUkY>$z2@J)!Z)7(X$y%k zJ{#fG-bD7DC88Gi@bcY=uyEyO0~My}G}+ zwJdn`HhGV`0SB(V=U;oxy7{aLxvgCLe7{C>_$lk`>Z1pRyp%%o-^8z*c2@j?9~SsQ z^RS87&M2N+=Rex40xL2PF{PV!3{)v$ntPm^2UkyV7$o9$trHpRT2kuDF*@R zV+%Le?WPDwms=(jv&cQNyg9P^CbCXAs(caiybH78CaSwRGSduC9T?T}%wp?DPxj;Z zL%i07e6tsQHiTmr++z0^y^n8VdxhdI(|m38!vz+?tR*@B7J$O(-toXb2MIf)>zkqj zr~;KyvQmfD1lduVFx{a^0v<^sElIC#lVBc6Nl?5*XtL^UvWSOA4GdGI&rSy`m-Q}UXccnTRyvKH>bn&p}zW#!W zMJ5_Z-GIWT&`Y$*pC0y|+-;B^9%nk6Po28)hs6WdXplv9m(_in-_p`k1Soiup7{-G zTMtcIGx*e$n&V+0en_T@iUky|r0)UvhagER(6Rvy({b1`V+!&aTT5P$Wq-I!4znbY zA}cj-K}Q3c@V68?8(42Il_8(2bi3xono)~Nk?VM}q$NUp&x>2E9sobU2|JS$%< zfzxcTJVgsMm#}_WW5=77eOxNsx}{23X8AFn0~rP)BD?AJX)Ey3qvqx-zP5(y(!Jvp z!Q)w~Y{{s?%uJ%1NNy8NE;frXFsNQnH`^sEdfgzOqF93{1JP~K48UAA0(qReDQ@qq zYRLr~?rPgS>NJg18@sWHR%&4em=kaD*gTUW$a9$Q%i2=k`=l4CM-Yo`5}tap^5he3 znl;O}nJV22s8M`3H~5Z6@t{W5Dq@iO=%4!Xwvq9^dc(7cb;TM%Do7e5rs5Dx$_B+Y5kK7h_)#F22~G%E>$EHgFuvS>jf-l_!hl65*I z8~JMY;Bt?qm$U;grQ9fqdjL;xIqCaL>sQ82rLJEHUHf2L$bB0i03!okH}wSebA&zt zAjupk$q)~VKG+gRqmzh!7)FFTBY-3iK_JnM+)TIY0}daZ_u*u&}5-(J!Z(`#F~P%k08Sa1xDcMxQy&6)okSG5s&^J+@6c zJ~{@18~OoTfKC;C@(^9w`vNOZ=$c_h`8DX#DAD zP#kZ{_jpO1m`)CVQTzxo-+5&63lFIqKSy$h-e~M2^)BXo{bW1rbd&d{hZ`Wx!#~ZF zD9fAE2-*yAV(R&cj`ZSbHLRzL-a7y$TR_N{Oz_RLr7*{#(3`c@7k>(Vp($~x>vw7J z@?la!a8J^)kezj-`rKCA$?h!vl#*z)xhxB2@>XL)nC4$Xdci?|%si$I`VM>128xl_j zKd!eWp71s%cA!uD5|>+0aE%u(07H6#$|T^~Olp2o%GnGi(p%E$odT z7VvxsPoN)4U_b!FIU@MBhLdUR9tykpN(QZ4o;Mw@aKfXrF#zE5h01Vz^Al?T4?W&b zH8NJx*lzU5@JcUvp2!Tr}J4rBzYm%rPuwEB1n92!M)eH@z~ zqMM}S_kQjNV++^9yM2#;*GUWWZkRkizh1o;KW0h#qD;f+g(mbYA-geK8ZVB$h;2b9Sv%gL z#!ooV@o&94UTrHhR_oxpZug?el)zi$vABrCb2@ax=(y{2!qDxE_JCVYV7<)+k@;;kfs8!KJ*GqsL*`*0c!#pwR}uzIBX-7Z=*(L$ zq;b4hewwdCZ?;R9d{JF?*8S(G6v*S;ZiON7e2jav&QOvTJ(R!xjA|eSaUB_^?9T*B z>guKuZ&Pup$}_^36Vfcw0`ggQ-Z)v!sS)fmr=L8vqnJwAMa#(Dt|B6rpQv^~^`+E9kt*%2gVIikckzt6pi7mVe5UVB z_rRO(!IE9&?;8w+l==Qs`NSru&1$p`4dl~ zhivk^WiALO7)=(QQg-ZS9ryauFs5l#9kGz=p&+p`*8PF{R{{BA#a63fO`C-0LtXW^ z$T7-R`tJ9RiWr1q{>%-WTir!kuAl7dvvm?bO^6yboEu^F4mkD}VU4F*u9||l%*ZDd z9h8{jF8Sx6ha%sNG`)h)C#WxvIB@p-`_+q*6Q{qjEU1=${rRqR%*9BelB8j3_Z8(1 z~atbB$jur>?Mv1G%RDuoQ?bM^Ht5r2e?| z9?{`rxcdBU)h&{}QGc`lV>BD-`u(j*B3wktl-;fV$HBMFtoOfLijWnMQ^n+jM-`R? z!|J`xldp0}_KG6JJuQmA=%Z)6t1rFttd1JxA5^2y;X1BZ`&D;yoPnr08TqSXJA#QK zO+mUOk}370XmJ&j^zcs{${zf9|7E)zu9w- znG{m7q!`{m{9RA!dv4H>_9|Uu82m`?|3O4D9E5=c4@VJ}yp}DSQwHSKAggF{$Y*ln2iOs~jA!wewl(Qh(s~p5l zmb{D0RQ}=3Z0{f9gm>?)=<(MV$uAA?qbLjmguA40*>=W)nXQ6}5sOr!xWgfD0?i?c z*Rs6XC!xOjRODkfT??{2uB6F^6xDjeHGl+$O#31H1?C|%901vIZSYSxwBHv7h_A9& zV=*Y`Z*x40kGIQ95ZACj~398*@%DKu2vD zR9&@WmzLhVZ#5F%zz~f)?%ajKG@w&vu|`k0FZo7^AT7E5_r~h2n)xrR97av+^IALA zMk4l<(UDRKiMdW&{7;$N`z1otb_L|(p;?Ms%G?J1$cs*iX+ecHH@`*dS33|paW@al z2G-DVHPZemlKn@?29=bM}>&LDWngS<@h{3TJ%iGtX{;DXzq-a{zvMi;365+tj}@q};XE+j zs-TjyC9F^0UbEz8)XmfUUSaZm-=jw{O+;gWF9`pLySrlX1UgG!Igi12-14$a&$Y2Z zVE?V6_CnL@_e>9}Xeo4QblB={9@jCp+J4b&LW3S-xT<{>iP6}O97-c1E9t|BuTdt6 z`a<+AE~5^1ODkQAoFxI6H8fY?(o}+-=4!gCPsJ1}y*cWg`|qoy_3&~26$sE@b^V47 z2T1?^0oivj>hu~qMPjN9FzfgrBEFoJWh{7U@A8aR!W z{z{}aXnREbmKMz#JFuOYRPBst8X2~{cEp?yOjCq;Z2z%GU{ z0|o*d74eZ`TkPBS8+mvOLU#k zFdyfiyXx2!@!by2QPS5I6FKBM1?N#gv{|MyJ)()W9L{ofCc^wiMw}x@AtJuDEf#oQ zt5hJD6Q-B*fj!NsnAN;*HsMSXzZcCdVg=$Q3U;D?8?D<9xcx9#`9qJJ2iXHlxs0ox z1Y5pdEmTu3FBGy(i^QK^NBUd2pnROwDm1hl`nl)>&ZkDoI>-r2ua+p>Dwy4STT8EH zDDJV{>b1+1!CUFdLZ7pax0Edu*KUJ8?uT*MkIqyM3XX^;bEWSQncFH0WWDB{vgzMG zPw}gviXaF4&HAXGJ%81#KN)@OK5(|M9jZ4wskTyDX!PyCv`M<3GK~`w$QLtLm&UT{ zl85)WOuKtOIvgwWrO@Z}R>upla&pCyd(s`K|2gus=Ip})*U|eWH#;QLi+V!ezfJ-V z*!VvjP`A!?^gojR_TakheKP*z`|(xN3mW%t&c0XFm)^86JWJG|cNCG0?&)glzvjNa zzkFBpAUilQQatN>`?~%WY|TNp`T8wxaG9J$Ny25@g4b^M_1*8Fle<5NSGR#Sows;g z_gpZORIS0vi;o#ziZK4YVRoT zx-(d=q|wJ1;_<80(@Z{SQ~ooh zyE=7RkZvxR{?>f4lP+LU|O`<(#9tA!1#o!@%dmY=5k1QgFZ9|IfjRi(S>0ugnbMnb<-!aH*>Sqz>p6Q zo-GM3Ll6HO5<1NoL_8Eqxg8pz5J^=ZJ|q{Y{RM#@pB9EaK&QVGX4M#xZ|?EsI>M$b z)DmX0AsAV_7ll0&CD-8VI`6yo+0x5DERluO3nMB`Ka^|FujwW*`$oHEQA&%{sQV^r zMS-f6)VW+ic`z+H=>~!?ZR)cZ?KkB4Mn1;wr{9=MR9mxM*ig*n5bZBg7dWZ(CTYa) zy~wf`q5CXRhYI0G!r|}3-!F#yUJb>Mm&Wi;2U(s4z3qvMDaD8xfQ&6hlYWUb6-?BkG-kb;#-PqEwCgvJ=gbjZ@!|(!PBp2^zs-vb~Hl+NTPuYc~n-ALt0n_SO z=ZA{K)cD1mO7+U7oQZn)_B5Ot@`#WY{YjY+QOYUhz9x_Q5LqLX6e#Uiq zv^1d`0byE(NSYein}e2|4fI4!{cKFE0`JB=7TMfeQYP?09P_5Zrby1?eioT%9@0oY zpJDhhS%DB+0s697uZLMbD_K=UZrrZH{cvt(ME+fA{%%Clj);P|NSrWMu^w*$bUM!v z-;;&=IEy*_rsMITthdEceA?iY!Y7TZau;4)5~kr|=JPh)tll7}VX4&9utfPC{&{$bKY5upxvqm@ zG9Pg%>zx@7ZGLKGVW3hLmVTL}t+LCzQb=T}f>KFoMv(=1 zq-}pm)pA;)qjO5?R<999vP@R*_aVl7}i9@&l{t6Kj=TqZXJv;FB|F zK3fIXa#``a_$jQ67Pe@ciqC1D)y3{wIg+@SU>tKEoea^ki|!1sF0?haNx{llBtL>uN*Pu;Mm7-hNO|gui& z15rrDDV{(AQU@6K!VI^?5kU*WM;ooB7=feWY@kkP;O#)a_2J`Qp5hGC7Gqb|GexN5 z#^c3JfxFE>FW!H3*g%>jiEuV+a*Jy6sBH2YZSr}E9`D~2miI2wu&D8_pjoLw)~G)6 zuoQ~`Z3~Vg;DplWk1lD3wkZh$odJ(dv1QCq`r>hkX_5A!AUP=J-*^@P587=Wmh35( zj%K3`MZpa}G6E_HfMQRdg7E=1bQ;e^Qxt4yd#`eP|NHjmqUrFIZtvLD6WkpA^5Bo696zf#S`oT z%b()G0Dzn+T-+{j9T*qH3mTjPPrb#%W$R^OMdt|EMp z0Dd=~6XszT7}|wf0|!vWW5Xr89ag~Br+AZAxOr3HuW%f;_8xYMtaqc0pp60C?l#A( zw(iWXkahs~DF#>GP}JB^%+XLBXgJ|$D1K__MHkYS=;8FL;mon&?4#iq@#v{X!yJxC z6lRE#(&&+rDqu)-SEzAU_0b3tXtZwi$2XPHoA;wl?Oh6^B#Eau1OR~fDwtgZw{{9F z55>K&#oO@j2IPTQ$G~#&?*Wc@NmJmQJX|pT5FMPrI&*M!sGbWOfa-|*X4JxoqFOGq zA}Vv@fHEj?#G<{5L@*E6fMQHw8cYYq8JfbU0^@Xp(JUlEaQ{z}tKb=9lsWrxP{25t zw)gwS`1(T>t`S~}1`453-7aX7Ub&uXyfp4^TDq<9Jd5O?dbt10KlSh_!hh=FfH9C0 z<^hic?(>!~0O03M&45!19WwI?dY zCSnk%BZ`3!$}|+D>qIyXet~m_xyQqS3C2sF>OP*rujT0hX!J0H#*YZ6WmF@VJTv#w zGcE7t+^QEeJ4)wTXz{%XMe2xNoe{!#iDZEQ#`yoFz02>3Gk=~yLYVmaLzLs6?Q7E7Tc}bg|Ft^tTf*&{d~0?Aw6T?TQfWE zJ)gZg_91FwE#LQX;SguW|3l#>Rn^A03IFKQ!P>8*$Er0G#QG#oLa|BtX-xIG$=4;- z+J)>S6jOMI&*~BD8h{$^T%EE9ntvE?zT%uA65rT=HPd?x2Pytq>{wf^hSP~}ZfCD0 zx7L7vZ6M!l%-h1zsW+k2TU<5kvv+H>EO2&TS5Dk5ZqqbK?E3A84efC_R^=8><`xP2 zM$Yk;`SJv#!{&=$Te3A$jXu9U2eu^CehYNMHMq8n)ix=fN?)IBDAr7C)odGy|DNjD zA&%YnHNIhWQe%yaFKE`r@4xF&v+MOQK-;foSI7}l2=FgJJ7+ggZ7+OcFNS(A=wvS; zb}y1^KLvL$*kkbFlP(2DCd*2((uy{z=dIb3gH?W#>=I zuRlPVePs31Scg;exIN6Tr=b(4C?Ao{CA%}{Pt2n;_8#j zmF*;zbzGyF#D(2Q1_!?jM~UQ5>ri|+)~7})_pjH>-Pdbp*Iv2TtN1s8>(_IdH{lXD zIO#XzGdHn6ZqCkc#`tbOIoy7UyG{Rkn>l%#{pU6p?=GMFu2B81_~YI4gf2&bg-)@z zB=NRRv7p}Mr)*!hCMa);-#pAyDMd|=@%|?id^bypaf($VflKg-+{zL3W_A$31NiEX zdr=EQbAycic_5(0UWelCfkE__B#Q{V$#rn&Dc~oIJVA;dl-fD3 zy-=A4vAG;8H(Z=49u38#S3}V_vlxh>k{|(n8#8(N)>N&;_;zMb6TnNWRAh@^C>Mkr z|LCPNg;wuzV8zIyFPHHuK%u`;NA%miY8h&=7USOAG!f4YNwNzpSGaz=$7O8FUu@iX zu>;5Bd5Ym*jP#w${m@n6bVhp9_>}vpMLvI?t@iEKs%w;%H|D+%$5mg5+g=JmyYF@G z_NesZ7728=x#A#}TMW$(m`1L;0LEllIy$Bd{$JQWlUz4L6s;}8#pNi7m4Sed}<<_0(+7{s4b?qT6U}l5F=%PcYlrWGXs5v$pB@!SsCx*s-JE@02VT>6PsZgfcTd}YsloN!~Nuc z88Dp{HZhXT= zD6wLCT2@6R!eaD57zU@$mi`GNoeriZz13jqKV z3R2Z&ut;+4qMt;7FB<3)K*?EYm~I780ULYxJDsH81x2?vgW?%L|9*iJr-T(YjUXk> zZ-&Ix0F6V~(t#dE1-%06eYsMxbH6!HgR(s5tjN^w65s_AmEABQMy%r!y^J&|*m;)c zR3=_fFOrJLBt%$24h)l(M+x2BL!d?hanmA`p{!j;_*3{%Y~*@Pvt-AYDqdjPIRaYz zv_VOK|E1#C0N(nWfwty3qrhYm+U~VPSolk@8Y(t`6?{^wg#yrTPL`TN_5U2ez8Yi< z0pv=es}g|Y5@H+;D4{N95PkR;K*KMpcuL~^-!Y*OLd>N+E%anmO(wBHb)`0}p2 z31m`bM>nr=c3Vkj=dwiOgFB{m>P678$eB1CguEQ-GAFw@)v{I5COz$rglb4p(~lDJ zOeAE;S4oqY-*rKr|Kv2h^EE4M<*8%iGuPV71|@LoaY)QS&hEf|g>RFI0UW=BD9?M0 zPNHL+sw@L#q?A0M@_PUTAXwMG8_iM}?WLSbyt=6(bv-nYIns)OdmTFX@@hG4R0Ygm znLh5o6wcel8%j@!Ov%ay6Ad&ERu~E@;2!y#(|cs|0^M``gEa{MU^5SRQ3$v%__@yHj7DsSZ{GR>pf!5uCr}g(VlMg#VV>=iJV6;ff`y8Y7^wHqD zKBB_367}R>>S?faan@s8Tb27;ht^(&o`hEZ04QYJAA_UJzNkbs!4}zFR`j4QIxc@@ zsjIpB`{-%GXJuXo)amp3$83mGk{9I;(-8BRQ{1O^y4)d+!B=Cn(W|cgc8*UY&o?Uy z{J&7xp~*M*R1Y~K!lc`wbT_gu7d4~n12`CCakK}}JI{icy*F_D+#NPfqjNb5mp>TX zTJnlJ#6ZM$sKYKhYxv?^;DPK!O=0~;xEEirJGOSYhU|?u?34M{_7OXt3ms1`wP7Yl zmdsvD-P(6e{&?+rtv^1wb)lP{{^u9_m`%^3 zY`nLq5bi_rrsqke-rJmh9%DA9e=~QzcV8hqrov1w3YmTORsB5YO2rf8bbJm?5T1*J zoo6*>#xN^Mv!z|r>$Y8=KWl1U>*#N8dYOIClC=GG#ri1XSug|-yQ7sO&tUrb0UN*jHN?|+<|TJ(*p}TfQ~zxd;Fe8m<7o;9?hCGh#MS+js#GW43obJkY{1OS&_s&lEkBI z$B0MgLh^s(o}a+5EO{na3L>+#TqSN^I5rx&@D@ua|AEH)2aVP!iouN=E%bMg!De=N}@9gv4_b3~!Mz zAPrRD3G-tC!p?utmZ1Q}FqFc>xb=ZZqte2oed4PXY-EA-%_vIvvX)|URvf)RK!{^A zx{E@nU<;FzySVyI7(=Fb@ZXleaKN(_ZU0RMP$r~eMXbtzp>z}J>KMAGDCcS~?}j3! z#}nq3CGS}!??n{HlSbf1TIF>l@Aoh$HHP}R4Bg2rq!?KtSY>D&8v{UlivnPICQUh< z0rCJslsjM;;(0th{eN-aJH-7J;{M|4;h%ATe~-Aky89RL`}7~;_X=@y{9nrNzh&RY z%gd*W6U4>l-<#{J=W%)QU%2nnv$}A0cKD3`{#idg{YUma`DYwG9vwaI?mq2LAhw&1 zj*k98eh>Ec_xE;pclUOG|AYJfIehkg7x#Z(JOjTQ8|&-qkIO612Jr9o)u;7R#8S$y zU%%GY{=4tHurTxU=g%Sd;^WNB{QUg0_4_a~a^KyJnDIx9et7C}Ky)fR>%TKIGt<-m z@V(>XPjaX+`5~;G`D?y7JM6@9pBd4=H{k;A3zIv}cu5arm2QnY`AzE|Zs&yMeY zCI3K`|6_LcQ{0>NtmNM@(N*8esvAn5Dc|a6(6_$y+3~Hasw(=Lms^>YTbcQ9(6_j_ zIKLn-H#hfL^Uci6{PN|?v*7!=G108X`MANK z3W^Hqk6%-WYAT)2w}Br9)=ydm>c_W#*!N+u~`O_Db0GTaY$e-(yoM zu>EPL?t*u>-|W1!?YO2Mfnm#wk$osL*Lryxx$0o!7>7Okn^Oukc`LFNy-xY8pVUUI zvi|{C(S^@Rsqc?zC@cJF7#--%+KW=Ube_T88*R}87Z986Mejbt!zX`n^KMcSos&P6 zaunSbRo)TGH_Vcg1xA0{xtwvd|Itw|lwo zeNTF^KR@~pev4^6z*2qFvGs10`gZ%f-=xI-HQDOjjC>c;ft`OUzDa;LeyTzmE+D}% zjIxV2&deQ3@Y`0NOHVG~b)Gc!m)V)Sdp?d&%soc-BA@oA?+o4%hV3QQp;Q%E0a6C zc=0^fA~Zqe3dO=|)yWP~Cz8yMfV>_iVi*Pwu@ndZ)+Pl&bMH~CYZ_`J9jfRtnDTz{ z61pk8{W+eG*Re`-2g584yYA~+v*1ntXA^&L~{FtP7%my`; zM8@De?P2T1@~^9J@a!U$r}Om>Q6B=vUc{r|>zT{fBSEqAnvrnH&GAIi07Tm?QrH+* zok0k?%a@>HMF*EkjSvrJl;yoa8US|JIpbCBkSdpX$w6&Dbs5HF+MonwxK;|TObEcX zi*3LO?=#2}3mw=m3g5sc%DBQ9)R%wNRTq)a4In!`Ri!1%)M*!Y@zX(;k*GfdZ2pw5 zMG~v|gsuWl<8kxOtoq<*8U{sMi0@4K_J{ss)XJ})RY0_OISJc@-Y!FaM|7^*@DS2X zdXWW5Tshv^(1TZq)|-C96PRP>)W#<6PZ<3~U93;&Ruz+b<%43~rk?Qv$$Ha3V`e7R zT>wsLPxE^~XPLj7%64xmDH9fD{R6p*)dQ@#hiE6q^xE*5>nNnDSNJ3wv$Dn3wuBhb zK2cA_WUvx-^XQbzIZb1R?7W{20Ilqy6V4r(3;wvBa&-7+;rFn8J?9}QrRNxYro68d z#){*;7bd`TXQkzH^U+DJp^V+*ZO9nejN8t6DoxhzTP6KTYOUUMb@P1`IkLWd>hCq! z`Uk;ThLUk;t`!E=5>gcRix>r6R7lyuhS#S*SS~D337fe^rzh z?>TwDO%WxutX8%CiHT+A@uz8Sw%tb63913Oqj3^$eoD*CR(~r58pljl+U8YX$4qGW5u>)__rnI& z(@b!!>DCVQ5s3s~)(T^)!wu*PBtzaG{}{{$9?k&(cHqG-*iyh8O1Wv9$%h!?&mW(P zW~^>^tP1XBK2n#UF=hA1^@5Z)v3_{w6BhaO7OZIiLY~`Hn8zMPN9XT5mfL(*!hYLBBIuyi| z5&#e+RqLD2>?UgCCR-e|vw`BVfG64&#Prh-Ef52dho^9Z_mGG81qo?99^_iguJISo zr`sI>caLZGu=uV;EbT*n6S9}+I`i2A=m@lS54BATeb*dn?e2({p!B9+sRl*4UPif* zfd>$;jF#YwWbP~E6eJ?=If3^6-i8|84BbZn=WN$#dBgJ&0YuUQM`!_Xesq1JgM&t& zt>12}9YE;P8rlMtklnBlyjzBka=)3Ps8q+JWF1?1u2B1Zz6m8`!&^uLw<&1L1+V+ zktU~bV6_yywR|}|sLFX**ZvrjNw`01QDUHY4CnyEJbBq#EcS&@rp=KLi)_`4oXluZ zO~Uag5mBwAVaaa|IE(SPiM3zoY6CQoAIwmhY_tV$qJ>$)f$}jFOEf?YG?WFrxV#w2 z!5En`Xy9v63v>FBXXW=4^hXf9?dq^E2#x{ZULoK(yo#>(i*e!+%m~s1tD#UCgJhe% zP}FH%CIN#aHv@o~o-Hcj2mrgy48+&%J3VA0Wov}lgXB5&`a6#w&fCP$t0ZeXE|{Iq zpAG$ZMuYk9Aqyb}8T|%1F5o18+(T%kbQ8Ud=OqqQG2RUm;UcJT$w zBQ>_1%5FaZ3CU!p*av?ud9m1Jb=w5~7R;o9_jxbc2@-zNl#)b}_6LTPJBPQDhZH_+ z6xEzYKARS2keP~~9xW)E7nV@8|D{C4Eu@U9{5AHY26h`GVdPSb#9UJ2QWi^KW}lvO zn@EOFI_FnRnuUn0rSfb)GC~4Jbk96w%DHth!4 zr`MSxwzRB@SwxqF9k%o{@%hNf(lnb(b^JF!kdw1 z*;-^vUiJ`B2sq_BE8q?{WO+y|i$+wiL>+Jgg2KcNOP!TU9|PPxc+l?O0=*-16Z-Oz zmU99{D<~N&{sgeM)^k*}R8 zA57hMFkJr|H~h7QU3K-&>Ydd)i^YmwBZBDBgCHWp>Z{izl8_(>qO4AkD612zi%6nH z^zIuG$v%G1J#)`JbN>F!nRDi}>%6b)SbJX&zugExG%&qvWRbu-`qawGmPD?AUZm2H7vo(?qxhH|yl`g| zG`3M9t${?@?6BR4oGPVoDe>`YdQAD!qpC^cPcvw>X@;`q*XKHrL~{>cnHikyGm%cA zq8Tlb&rhYW4Qsh0+M@HW(b}&CHQE~2Th35iHNWBkYQRIM@MH#!UVb&+>dk>K%m3}P z#dI=9Py(8Xbj^0~@JH~7&e%tP+EIc5rZ>qtuH9b*H4A&qOQ!ZGOO5eVg|CgT$qx#S zAhKRX@6<<44_-Ds{L}s@4MqJksLq4d*#+{6NNqn~kLYYId|9WR){d$7aALR1>+(UYVL+fN{09-nJj{5VZqXwGfEqnu#~$*i9%x|?WREO# zg^cp52hP}84SWnAuI>*{4O>E*iWrQ7R8X!KD?_6gSXB(Othih;dPz(O^> zB3%8#T>UiJpuMqz1ND#K_gZ+7N3;JyuL0mmq%34L%9RfmnoYRTMKD<=m|YPpu5n+D z0UO5wyQl&C!U2b_0mtP5=c@r1u0f+N@`uF~(I|?_Yg867=)XK@Aqi8~czKn(p&KmJH&(l4mdA2;5c;5f_{HH;%I_aeK7IctV9xq7or`VYl>Hq(0Y zxJF=wBV7Ld?rHszoP4ZE@_zjxh?kZDF5$BHdegtgjbCuKe!;YGeD40{$IgJIi0lCZ zih;2#3F+_N_jY}FEjd&&&clfU$xeY6kTj>hqobZ$*`g`=qL7)}-GHF(TiM+&{l<#M zy1zVn(LKhjWlwJ1Z1YZe-1X5bHtW_ANk$l!YGI{;nC_^r@Tk**w&e?T``ARIV{WtK z3oLP>(`#O-nC-Em z@v~=I-sC{ySWOjBMSc2*(Kt4hUjWW%L<*vrLwsZ|@-BSa-7{AAZLhOS{gYxaE|LfW zx>B+(P499I(LEmDUImn7!<68RCpARX0NclZCf2w<75|w*X|i$LZX!D>y}>>0#yLa9 zKw01dlRc(b2%@?fV1MiHT-@&5%|G1{Qf$aw5U>}lKic(fcbbE8#_S!!4GSxUGm2Z# zv>lBHcU#`ypK)|*(f!)`M2hk9Apkh_F1~w~_Uk8j0J}gotN;s^jh)GIvdwwCpriS@ zWpAn8iS3aToSfKD6fnORCF`jUe}f77pu z;C0vtfj|6D5#*!PjPAs7n9IsS!pd!@Z)*Vyn*nREoNtjUV32GV=3&>7(|lqQ{2PF( z7f(Bdgbj9y&>?9Sj#~HwjRe2VQAF+@hWmvuB$)2+H8Z?I?Rda1fFSp$VKi}> zVFPTI4Sru)n()#Z3nG16Sua|-EgSRzK?aJQZ7Kd>93ak*6~7##0_niEvVTg&feW%> z+^^su#N?UeR+qungy)vH^BQH{oPpM|gF4(@$}ykk2O3JvMhn1O{A6nS0x6kyL#!;U zysHdExdkpi>|Uwm*_|+h2dTr4U(jG5e@UUuM&lsA0hGE&(39e4HI+M0U10@qO4(r0 z@uNMR{5^2@)~649_Fzea_n}Gwu{(*b+ z7J!>LB@JgKw&u#ohTbiufJF0`z$-p1mt}xY~bo|{_zQZO^3@bs-Aa$q~ z5KzS!Ew1`4wZk24na_Den^I=qWB(OdpJM{&adk)c&3{q$p8H9|xyEYce9ug1mds2M zN-j&+-@uiKi&uIVcQY^cqt8#Af5`>^0yiw@&|Uie`uxY~H&FNB8Gd|Xe7TU$w~lnD zhW3|3{hylJi*ad2$!`~X8SQ*B{|RWn@uU;FjfK4k`VUG!dFuG*@jZomug|+lf97AW zb(zCWNm}rLZ~j#>m;WjKt~D2eAServdq_TLGyG!u-XHa%KcDYxYVuxEe?L;Bzk4+etq?SabI+S#VX3UKvxQk1gxP`nWdZw1(xduncSMuV0NoAU3wBaonXIyhc=&s zljuW~TOTWslbLRQ$mnI3rt;A4>|sMPk2(~}fuBE|952!qA%|2oCRtbW8^5Y~PY3y2_xa(x$bq2c1X566x~7CmY;)>+U{dYq|A=f889gmfL5cmr33fq<;&E zVIglJu=Irpot@vxHPQVc;K2un-VA(^`sXi}LqIj-@l_3}u5)ZaM!c2D>ophg-VoksuNL3@1d;a@@Zy!xsr* zLcdp?V}7s!vWAw#^Zr9{ti%;23v+0Oj{sGhU-&5feqZ6_#4(>w;!D-d5~b$Ha+KdN zP^}J4{&uSd_$|YqPdKQf+`DC=b!Y37-HzI5)vrgFOYirSydj!r_Pxa)@$^fZ9o>V^ z*YN`k>$wrk@A=vtKPPFNq|tt)Iq3aSp&qE!G1sv3jx!@*qjQ3r`)eQb>Beh&fHxm& z(3Y&oGY0ZL{_AOXs!6G_D-q33=1&__aBY?63y#+_>-=*>rI*M9M{}V zRrfNY`xMbzEEovM+TANBy_c07Oz{d6OUMy`%Jjhuis=@&%W*<+Mj{owJ3c~CiGtW9 zR5XIlp39Z-65IbC-zP}Dy7rJR!R1UvPSfrQt-j^@+y(ww2Ppwu>}#%qYxfS;p-MgQ zdh#2k@&TVd$6QALpFIFjchn+wr3VFI&{|1gfa;NeaNTt=5gSYmnWlg}U3As8auM{> zA*N*Ktr&=I$NB6B*f$SO~!0JKLy64}owQ5=ZpJ z+D8Z^Y2%XxnJnU55PFDlZ$5zFaVG!hUGVcBFvE)ATM?y@085SZA1W$F3{Nbg@@qVF zp%&ztSR#U|abR5f`AF9DDap(&1IR2JCbqeltCkJNL} zUoKI@2A;m5{aPC$JBc(fRXIw(=+wHG$L z?KG=xcb&3~y)bYcAR;4L!#Dkl5*hom#{33uAv$pJ?|Z5vsz1Xn!Q0N08{ss#+p5~6i`Wpt9M z6lA>uZJZQ(;-Q}~S8Lbyj`ypJA(;za4!(lG=S+Aj-gand^vrO=c7My~MT;EGXRePYy5 z>+Cs2+ki9=8sZvSQ23-USM66s$w>(rKXV7%p+|)HdY<|@tCe>ppK5ttol7Zmw~=yk zkYl-Bi|%ZdwB>2p^THPfQK;_S(b@MJvx)c@9qfKa<|n8%h2b{?&|TF#&xe|M6oMlK zC|`(gkh!mgwKA^zC1k%}>~jujqW@bD8m^R~P}SGg_3;jV)-g@|&>U4PZX2+muDq;; zYimlhO80*E{c1j?ibRq+ily3k=PHDuWZQJ~db7me6wUI%b9ym_2@5-Gd@%Tq|2S?- zeQ4=%(C|W`(Y=TNA&Se6Kfu1_mFq0u;xdFaq(gFkAsyG1+hF4qYscbkFTc{(Oa650 z`I)d(%B=L9D1IaDCmpL!n&$n)|qd1RV}C)G*vId%zg^ z_X{o0!+@k|@6dOhTjC<&ZQo5VS|%xA&qQD9ekhEXzE^Q1=X#|YPxHI(i>4Y5E~cCR z_d!pSR;@3|;@*EXq--rx$Js|i=bu%%k-Z)Nenw3C-=9S>y=i~X@@%MUT~Yhu*=sFj zC87daEx>H$!FNR3_sET#+R=4Cze=)O%y!W5|G>1_U;h3Ub)G2mdPrr)-vm?o>s%Xt zB(wP6h~WpDN7^|n(oOQXTM;eAoIROoAH8xqa|&9ozI=o=GwseiJM!xWm^6_XQBC&j zl>2#iJ0$S2ez8=;K3?1hctqC2siCv{CkF|K{ISM?dlLPM zHHFX`!cl!&#(E@<4b&@_77;uR5T6*G4LP0ZD^IKWoks_Ws7yg7`c>-5Uuh~R=KHZ?Oghtuui&8HRZ8}Bd=3Njbp)W1l8_T+C^n6;T*W{M zV9V^DEJt1MGY-;yOppfJ>1rfrCAX9f`Wnmb--FKO8clgVVo_z3qatVm#V2C0!lHUb z8!g!$Hxj`&{A~JbL{$w`M~k)wYkh8%jAPuFF|WomZr{cUALR?q-UwJ9E!ewJ&^6pO z4l5Oa7Pb#XZ5VfTY2NT)5L}EaRKS4?$mME`A9ap(3!03SjVEou8YG}EF46)Jy}8t5 zSwS64v;FG7`=3RP*M^Rb9vjswpz$94&3jO?6+!b$V>L`{8B}I6YNBP&PTZ&2&0cbRH@a9{~%_A*X_ln%8jg zs8=RjlD{ySVD18&T1Y3b0d5JJ&2pJ0WXG$p0r|ZXAK3!|i;(+AK#8Cvui{VadmTYF zoyW^i%fg&-Ch(!R_E!xHT0NZYQPO;BEQ`hDWm#53EHzmtIr8PCd0ugN_O&9MjE3X* zFDNc9TXwj{N5{?fu5P^A8jz8NQWH65@~_?7i5s^Qy|X{6i5cR&xg6nx^bmznOMoGs zLg*+i=13@3G}(+z(IX|Gq)Ou9draN5&=)pinqC|>5L{S6-l5WS1 zp3kPoP-EyH=?F15;h)Dv5GfwGe7asME`t1~3bcYDR^TF;&l{`nIcpF$YnV8Td17OD z4p2M78V$^v%*`6q&KiHc#(izgT4pVT=FInJt@Le8H0Nv}bKOlZFx;R+HjrJp?G5fZ zhk-fUfjRw&*t5%ITTz^fH&`4S?-%)Ww;nxQ)G0XypVz$v$#GRUm z8WqO}p3mQdECgN4zCsHjiVOFzWnbHcFwceXu!RSS3lUEi9-hztSdUkPFBstI9g7#D z&lh4K_G;M)F)G#`R@Mo~*az7O9xZv$LMXNUsF$WJ33emN2{$bU!HP@SDCpbhf3x%)KJAJkY`24bHworf0S<%3|XI?#J z^l8DUDPy;fihhbF5@tny2W80&0kDKwPQ*`*bbVs$c6fJ=b4ItvE{+QWRG!{eE%xpp zzruzuf|FVpjq%`E8=P5hVv3am=nMPJl{l^f;LVj}nWM=NDA5Z+l&D>j44B{v(}lF) zWHRKEWFawBDj-i3&!fc7xi}Ad3Ra8T8Aeb2aKw(sbw#U?5PWhNhWx|zP#AxThipk~ zq84&eT7ToVm!@#p8iv}L=iG~UvF{K+j52u>^^!&~~;PC4l z$7VD#xkFKwH@yEi6+iclQO-nNNBUQ2uk85f*^`R%#P2_CjX9(ofqS`i5CFGJ!ScBC z!Q36nR>{Kv{oiHZ@oNo3q+Camlh+j*9?%G3|qWx^tC?J9s>L zgWch!=yW2HOvl0y{z@FAzYV*+FwnlL- zamX7>f4+W|dorT%X<2=$JB1B&>!@2Px>SP4jn8aVZE!7fWho9rR$B$>J#$~^mVB}^ zp*GTN5n-MXLFZ(>Vc@o5Xt2Wn&24)h=MV0UMFJMHlWKN3@#xoMhd;Mbx$~8PD@7~C+QS2gn{isZG%q(JTJv7Pezb>|bsX$OfAcLG z+)80HM%LX4Q`#y0H2#L%-^_W-Vs#}26I*4l_r#1!GR(j5+xB$eUShGKCC8SQnfI9V zcGIAXBKcD;J1BD{c^g##sm0R2%gevhAYjEAD#HWihWq3y`I)lpoe27?H^jCUL4Pmr zmu~OF!c2FcI{6Gj!8pw~0ur~`c5c(|3BIwI@_Ol2crZauwWjB{c)tI>!Vg#AaXlVN zwJfQT<=zkB!(O|?5*@=;%;CRRlGD=Hy}>>p?frxx&u8?z(LtMWGl$j^_k7)UXzAlE zkV^?{KLE;yZN0v$T1Rm6AbJ^`=RYn0MmYcwP{wl)_VbYT9!on@H#N+QHo0x;-_Zqa zAh+SskOA~Q3oi8A;a=b&>rWgVhM~10H7QpuVHhB=?aJAvz;!PeYDnyd4CJb}X&=!p zw62K9I8GekBDNr;z7x3614@<+CWogdeEJ+fk>HvCj#bP9;wxVq0I~MvdRzC`plv6x z?@%-%=@FE|yuFsM$#+e(PwCk%n$;1x;G|7=f1NW`W9y|b^i7U*2>+eH6U*KBpjfl5 zq$trOG>-2Qb^mRUPpXB90k4PO=apMft(GHE2C*n>f?80^%E`|CR!1J1riAiv4Pxf8}r_;ne>cO2F@dE5$ z|M&3q1sV2t)$2bays^WH_lo0r@xU4GVxU?v*hHoI_#oFxqIurVe^YmUg$1>p zClE75yyKkc4$ba(rjjBuBa)qZfblB;+jbn21D_oOjy1J}{qhON`x1fSGquS6n4waGbzTeHdsh^4ZFAF8`KpdwO`9|f%8?{tEbHMdO zo+9MBJzcXJWhL&eYwbDB#<}Hk$k)(Q|47&}Qu6Ml_Q!*Ab0|XrKD4tzQ2+7UyN|z} z;T{)!BE@>gJ|2eJSd}aCLvO|j#bygRGz!HoCPrRoIfi9CFUnmQaIWIQaYVc8vHm8; zWq|PU={q}}3xDo?ynH)kMppSkHJxUIpMY6ST{7UjND~`Q5Ip0Mj77!hasf}R3 zJ*Jok0Q^Zk6dUv!3dEgef%M{-&=xhv=4itI!F`VfhO_zfTpPhw#FpFq zHyi!8PlUz`9GY}I4qnOh42J1ahKdoRjmQvvpXKQ2mCHF%K{{QA zfR!sM-Rx8ppzggaIGnoCXYPb7eK^5q?CR?B*XiM;T%&K*1naT~IMQ>)4ytv2o3iz6 zCQC{jS-z5BM&rF|+CNn`4%3jDDS%FfGNP%4mTb|Qom>qBnS*fvij0VKPh_4%=n?5o zx~$Mbmpx>!J^m$z8yV?xJQU0|3WTiq07nh^?y*&qd)isOn!n9BuMsgy0#P}9UV2ua zD3+J>_c0X3N~-MGGzUaYrK|4?&T#3-LqXO^wuco2cqRR^Lpc=|wllHQ`Cu9Kp zV&uEpYy*YLIt|rgBVh~{J*F6U7Ae^{!lJmPg+$NxX%+mN+03hB@eZiQ*uJZ+Se9ez z;a$`a&0weSczLH%rTm@ca~UyrAYgP@y}oPsq*~I{l?b0^TUc4+{y;{h5o8#DvaX9p zYqZ){+;n@n((fEewMlR@D@04tS-nZ-k#xKr>`#9a8e+1~AUQ+o77GTAfMnx z^rXO5exq{r&19HH$N1DmpLbG%*zU7FI%MFl#xW5`?K$KCiudczH!D_}>O|H8D_ia6 zt(63xaLo1BH1F<&^}GzbwGld>&HY}KUwpH^XbEtnB1Nrws}^7?4&ardZmt{g#fjD;ml z%~?H`JanWuTL%UxKym*p9s)l8Pcylf){Qye{sJSQ(pNGGpng8et$=N&-lP%9xt}5z zLZ9P^jE|x4zzHE&JF?0UAek;cT2(pGa7i*i9?pP_(I_r8e~)Z@~8k%NSoLfe~pe( z3#&_sdt1y@34V^1JtzYp9P+F8UV>p+@u8c3o;aYNlejei&t+}}<`M+?a)=!Ax4L!0 z+!+-k4DZ)u)AI8)CUi^u@Zdk9kUEd&h#~c0pP(>t>N``}XVx1uBA>O#Ts8&R+VvH! zibq^u1X`rD4`~I0vF46-nU&P+JQ;Sz#TqV8IR5B8dtVwWYL@eK@@!KopcIS70-135 zF}8auamF~ZBA$)`MJQ(cVMWGGS-h?n9t*$ws_`}E>ZctLN$#UD%(3W!vjbNp%T>}9 z0u;+l%@!H>uzEa1Y?8(Y*H`Y_A+KUEFik!2rcAS>Fk+$bx`hLyu!^WMg%eFuvT7B$81hsJ>5hk4Y#t8vBlM<2gY{U6dVhx z<+WO&nKbS0I~m38yq3L+b!6+tr)pyHCt%HxW1QiJF3+nAh4{Sg4fO|t!1yp9zB_K% zxB5ETH(!plc;*I>&`oG)5Ek0Qp?N1_v}s{;6IRbLl^)*whCM@6tjKV`{bt&Gq4H>= zWP%tY;VU0_{@=?=K%I1Klf=BVkB;0$107<8nPsQjl`P?${>JOhHI?UKR_M+>=6f2m z)KjO^_?*pxN(VY$T!q4RfX?vr2J28InFbpz#XXHHEG;61pdJ$Mxcg;ID+@N5RvIk% z*8Vg47ly&%M%t?(0$@K4*n2N`zZm`1*LLVd@9kV#aR6cy0ElxK&@|yUdM~i?Pj%@I zLufH|H&Ora;tS|E#WHSL7}ul+tuxE3;?zG}`cJ)05156C{7X4-EgjPcQKBEB;WMHS zmIP!fk@Y0$Z{x4px^@E`MHk!_1n-2=U3`0xPf>UVQhwaqw#VSk#C|OdqmXfyr=UO- zOo8NY1y^T0yaQ~SU9%un@|AZ!zQ@>YbUZ#V21g$KRW%uZ* z@0Gc~;R_={}vDY@UhkY5AW|CeXlF8}_by{IuHFp|7Y z4D$h^V9;*&@E(j+7|x2J#{SHCeQ-=E7^XQk z{d8?mh)fYlv+)`H2R<$Fk5eksnJ+0pAHlCL>4u)gss(WaE=mnObQI83YxE>W8v8!# zFmRm{Xhvv#l08q0E1s46di6fhSEUNMrJ)%*wibGvCxovMe%+BZ$)q>TKk|3TdTtXE zwZ`?GBET#JUA18ll52%(3j272%W$PnQKdx7fveu04C%;(wC{!7@ZbqpL6c*}G%!*d z>!!{8uy6s>3df@q_jygjP!q#2e=w4AT^1F$LlBV7`D$3u_qoPn=?ULo7X$-?2f4!( z#L-r}5a@nPP%>~eFj>7(?3u13cysTLz86^C0IaP65>cUIcPr%(bLI#HGZx344I5Gt z;}R-+rf+#_4jA$a^FvWRsOmd9A>{)R2qi7ZM^!_j$2+cF7{NWJ&hM7Tx z&&q=%cJs`|{!Jx7@giQU*$PzcWi>z{SO}89ut^kvgs{5m3hsk*!hw`OE`^}tHu}6; z`nUMMd-{5LJr%M1AapJ&a&l&W8bkmgb(As<829?M(R5*%Hc^88ow8^FK@b4d2Ty!! z$5RsjV$I{KcX~FCMiT*V?k&}czp<+wJtsX_2c)O~k`db~IxK1DV`0t*5-lBpr}FUhvEIM%#1dL%W5rH~boTHKGkM3cis zy>jo`AH6m%K{7|W3bXNC*GRGoSG?Tzw&jkA zJ!;S~QBujn&u1&hL42;g+!Vb6wksA~^%NFEvE{QHo>ASMppd)n2VveBIU1#F*PUpO z%VHp0Uql);AlW@efDKCe+8Bn$J4IJU1pWw+^Rx6o4SM&pX}mU<7OPzQ-r`mim5QeO z=K`lK!E9zbhZ7(hFVdq2Wv=2?h`zO@)rMRoJwZt_W;Q+5%1_b-@vQc-@(TTi`C>1Y zDxL=>dU*8*D)2H5`UFK*x4eH_G!4c@qPYyvf>6!X;VZ)x8{G=p_tA17dyOQV( z7J#077gP|#f@$y3cDw;w*5ikx>90UVK?xs25K(4=-jx6ySG_C6?^lm~TL;$)E6OXU z2_n~cIL>Wgn(=-(*tRqyiXd4K=O0FH#6J$YW`_F%bme0c;8%KK5xv?yR66+}dM^Un zf^aS5!WFRp5AGYV90}l#z<#~PegBhMUaS3fS-V1e@O@KimFHmD!CgYA_X|*Z?Z18K zW$n6_^pE-d4Lj*gB~sn0m-J6(>7Pm{+LbB{@{PRi8(ID*k6(E+Y^>y6#cx~fzhXcu z*cUIPSYen@vPTjCjW|s-K|Zu9=j)m_1_)=VKjx7+5w1UxmN`|bKh=^sGpIi^lR3A$ zcY3L#s}*-{b;uQA%j++5kyL+?Df9bj{cojuL0lk4P*?k(J1WWVdTe4Yb&vKi``#7X?=!MLx?r0*W>@w7h&?D{llEFU_Nr>KY~E$9Fz z9;2lT`{|IRgvDGbKtZkHtmLO}dyfM3861)3W?w0T(ud&tM2BGFKW<5_noZR9*=(|C zf#{vmKH=OXu1Xl~(1G0cyt;RT9_f6&4@&U|;=6Tb0#cl1rqqp6OpSb}U7zSecDIYZcTHi!8)&U zmBFKg`wSs(H+kcplL49DDt~A)7Z5RB6rJ9wG?uw<;+IR4@A2+3&G)*=En>--H`FR` zTSfVd0aRnW<*$wD@1R`!+aRy8pwODz(mD@*WQ z`l#r67TmA4`|%r^5^j?Y+&2kjo&`4{XF}ahk2PYz*MapnYT{)##7%Y;HEBrCYRMF& z3E#a@EtIP**|z6pFItEnP9Z8d#S7P5gRf>U$LwWVXT|n>?*+TZ5NbE8bp=K+0$JXT zz6NM))Y0|6l6fb$dMbPMJiXuai2(ATp8VHnGHm1Tb8Mcc6h?KPml`fSKr}j~kmo`N z{|v)ADk_RU27>=$KoppPnWN}Ay>OOi{ zR}uf~ZY7L`P369i@|T>phoqJ}e)I8rcg@BKHpKjY5INVoDgy3pCgY^Q1=+%VX{l_V zHE$I5g`h;*!n3qLnQ^a`^`0pkU-iZp=vsUPGZ|Uln*8Or@XKpH+;HnKJH|<;^E~O6 zoL-cTZ>j;j(x_cg^^3+sGyRVAyi?s|G~-H=B*Onu6Z#e<>REqy<;g_`=%LA8(DOe> zf_E7h9CaTsf*BLc3Lg!!Vwwuoe+Q49rQba_kx!t-QAsH{Y+~+53vDwxTbR1gIziuE%a>}Kbi4u)jWB1?1 zpcU^lamcWG`4MJP2i30n@5Vohxq6QQce)KdGU!JG@^2^wg*V2dWq7Ze-aYE@iwK$i z&2ipppg<W5arwg}wJXp8~ml8wM}kV2Sj+Ou8t zk|EbY(xYrQ{WN+JhuQWVgh3_%NZh$=Ixv*PBjJmGGn6utD(W=o0k!rrja3L3CHS1W zWE5(XsqEO1^)%W;Zs+?cTBNo={_|lKzSu|NVg=+Z({%mvb`c7r6vM$ES%58??oN%) z1_wCAHB(bu{dxN%z^U`W@#ciY+MQe7)O5mEyFou!G8t%IqsOOgv;$1WS?oj+sjuY7 zzuhpSMm4Q|ir0?W>tM&Li32kjn2yKo4QMB$T}K$kIVk}Bjxa*?lXs|k%9|t12hT!} zyEqAs;`S~}ErKyw!-+11kzu3L&?Q|UR{Y%DS zv@CIIf&TAI8;Mu@F(m*{^4tT*fME!ughPQ3xyX8o{+@j{)HVVjlk;NjQphD6&!05LmV1}={#WR51@A2)WdKCu>_|t8 z`vJO9g=@yGvE5$8NHU0pPvQJv9*Cd7_kLFKN)$*1 zWR7nc7&G2hkh5@#V<61h?F!@A>>+quWVotZ%AMusCBw!b_Nz2{slMvEPq}HTO}}{XJK-aCpZ!x2`)^ssubf4(qvI+F|GnzEs^Fr_aMArv z#nG1`{n9Ycw22$pyC;+Tt&a8GdRi~P3=fnK-wwLxjM3DvWBYtIbN9}bdm-r<7Mh9v z{#TlUNgNB)5p5YOh*3BrIX%pHG?W%o;dodwet<4TeVWXaO>ZSA^~N+&&F*@SJXl)xIEbI;mc_n{S9GY->39SOM2 z(*1ToSd~5`E-IIXlmRtV)*_G>AaYPhctc82A_L3q4IyO%<;sWYX@YwmI?~tqN@AR~ zjYc8QI2H>h&&@3FFFIg&u4ghT$W(wQpn`%k^2>j4lP(4%V}G;g&s!j0=Q~J{ty~YG z#$o|mu{alJ)|c{RiEyuI9M>8(yu-I;(uEe!2xIN?K!7MwBUG^$&F`x0>xy`*yF5l_>(G@;3^ZB8v`lPHi+Y8a*sxD{Q}Fmf~zYroA~Pf zw{rQg%3*i4AG#?ObuFs@H7?2||Bk`Swv?(Kt8 zIE2k*-%`3J`fqfpX^ z_xJpa(v(I{Z0a;xzFq2;lWQ)QXciS!-P7s(^f8mAu^xhD!;*J79!v}4uLr-e`8oCu z+9@=h@7=sjN9BuJANZAtlWc4PGn?$_rzGFYBuP~2p_+yWX;`DP#n^jIC(Y&+`_A9Vn;sd>= zk-nod&N#)=-ag1opJIhDdN~YXfM*7!9O}9zQzVT8!`80ur))3hbXXc~>h~6sEJ`^KBa-E*H`Rk!WvNRM`eOX^ z&Y3FfyuTyxZ7<&+#^D}i@6$H*YcpUO&D_;ej_)%mjUGI>=B?~lj%&#f$tu*b(AxGP zhO-Qxp}-Zh%vs27FDH7{;Q=b>>!#6}zN6W%H)W1z$psN+^p*Elt{9HW8k0-|#dxuUt3p#n- zaq0l+SHYz>qlF1F|2B&i8UEsX|;R9b{TP+JG=~J5bL8$ zH!9>WvS&p^~)arnP^I#6fOa>BdeLgGO5V2&K$v&||*B}%%F&t%Pl z))v_uA@wZ~F4Hx@k|6Uryk`I35!ufyNH_l2V{Ci;9Rp-H03gF!r?Wz?OSS>zIk?Ag z)0dW}ly={bYJwj&`i9>9NIGfb6%+)g(_=EsVcnLd_-n*Wf=K*PDB-B!+k9W5?b5@N zLdnWXBw`wb1!-q9r=&0Zthw-DI2Bqd%WyIp(R0jiYeeo ziXRF89w%o3a~f?R?|^f&(^Xo~PaNdb>cScEv<)0RU=kVoZjMj0CF`?e+TArW^ft5} zDP<20e`?MyZ`DI?8L~&4&Jt4l@6!*#P0kHnsJI;GO*!FK`lE= z#Y%l?bpJLj`1eG_W@WkAOk%Q+F0oOT%8FNpkq;zKdnm~9kBpZ9lND=_WWFaWf2=U+ z#`t%PH#QEam?d*ROVHR-eqoBG4ZtY3%7xKkUD8$9&rt{-Qdnn@574EEmSw;1#^Pw{7z$o+4h$OQGG4vYUhlEibwnRUgPoy5E;f zq*Te+rP}CYyP{*gOi=G^5;pb}zbmgX83!{H{<1eM3p-S$QYSK)MbRM>9x51 z^#8^3*wvp`^KBk6=5^iIxw$X>;aIB$FH9Q!L0bkpRcY3n%M(}5mZZZ2a(71j1?YpD zIQZrDzIy9fH*3fC{S+2sx*xX~mrFD|OA(zGNy}IK%7{mV)~fW#lU&)PD{@ld4gR4| zgKU&0k0pT!s}O&LryE50a5ZW6D?VQ|rACRa9bzA@FT63C!GHp{;z z#+gv7p}nRtlCSw?MsDGhN||w01*Kwk4}l~8XtXlBWg|OuHU`W9@DB()RuHCCK%^*G z37umom@HU7=`e>F-Sh>lp`^D~IpW{)8IiFHPFen(b@*^9GF7=7rS#&u z28v{?ixy5PenuU|Y{XSwxGRDj%RC*+lj{oQDK%4ma+@~}P;Kk1948@raPyE!64E00 zOOfx-6PtJ#xGw1_Icn- z`ZebHuOy!^*|-}i-3bfTw)}7I$~L{#R61^TMKaD-C*RA~%9E_e72*b%Ci?&=2Je*U zgqz-`Ka*Au_YrgJk2LlmeVKD!WzaBhwa74TnBNj$IVaV?{ri5xXcyGy#eq@+W- z1d;9*kZzbWp8x&a&%Mq$`^CJQwfBozv#xzz-{1FR!x_t{$wr9e*I^K}JE>FO2{kBF zw^)D}q9lp+9hoq8cd6oS3hWsO$$c$k5IzhPPo=rCO(0YVCr2kImwG3U3n%YHCvh(V zF~mRIH`>W5u--XV(1jtBDOJ!ZQP4Gb7$;lMrQpK#8@XGslUvJ$bIpZYkB0MiC--3u z*TD;SdqEszy`#+Up!WbPih)iW$r=~0pyl)iU*m(36XHF&&|aRyj-eNBgBSj#7m<)R zsq_Db`%?I*X3 z-x`JA6f=hd``VK)7uG!vPi@IH5LES_WtKnx`t9E36x325G)#`c@zyPx!dWUaGTRFy zOw%dVIV80{q%6rTSunJMJhV~Bxn$dp9IHZu5LpBh6|*=K z?>>v97|9`)MZ0Z?=k+;2>TRTQU6h`&qOFAvZ8o7(iFD3X6yZ!9Zevqll7B^lJ9Z`| z`W!f7nX3>Gttcne{S>pIN&2TpUyRQfg(i4ojLwgzEt4NVOljx0YPhT0uzOt3oA=rL zOg*6}!J51ngx+4sUv{u(gve$+xP3(~>m3(NX)^uI^z4l3<@TqE8iwNfxbHKm7c=%b z_WtZHS>^3?>&BG3#w4;GyJ*B#)|+VY%6`=)_4_wgz=2x+Fp|IiW*1 zNobkEFNb7khN}tjb@Z52Rx*!H#KGz+V<9@vs^`kTsG{uzN7SocEVC+vqBXvs38CTZ>ZzammSR(wO1x8YPNe{7ob* z{dUro6qFJ6GH5rbRG-slc3|COV83ZPlLcw7 zYg-nk`1Bqa1*cbK(x}3CVPb~7fG>>fHWg$%*X*Wr0bdm zNkCBiG-5=0lhz_2LPqrK2#wPYk_azS&%839A~3TZy|EJ?TSr-q{e#KfZ>g+xU#?3y zv-vHI1o&MMm5uedscmH`t^HJ)N2{2fE6~?D2&xV`x;;D#GrW6AR%j=MtK{c+Y#<#( zAS0Te{2q|MAVJCd;;G*hy#rdgUw3h0m|SRQ}PUTa!S#|Q2DQ!qGNW|A@L> z#$&R#d2&Oncc=G>N|!CzSU_6}q0jX6ea=%zCv-il2kZHmhwoTcnv_^~c<~Yao)KPY z4kqi}G)k@m#!Z`EaBCd=IeViK5jBOO;!q&4`{TvJq(DoXEsf|g=JV?{2@F%@>K>Bk zz2r0*(14&@Ozr2DMm+Ls?&*X2VUjIR3z30ll3kM$J+%2+hBKyEI0SSAG9w3&@s(fa zJls}lT1GZ+xpVy#O0g7c{S=$Al)C+tu(F}6S;TnR%8OWCg9S5zd3aN&^f8iV<-Rzl zUyH&smq<33DD_v!F_7P~Qq=H4k9uGP4y_;Ww^nGDrAU9BVZ2S3e5=WVtqWE+^;fs( znbKj{`9lsk_-nX>H7Sg1%X~4`RnHBvvd%oFOe%Sd+ZelZN6^@**JfCOZ9s zx@tq+p->>7=yq=`D3xh#&`7o~40mxiuq;bDz~glL2!zP_5l$oOdJBm$!4$zqJx>t} zwp;6qVb^JT@ZvacD1r0C>=Uh%{9Y=Q`SvaD6E=DD3_nCXWYRSEi;@PuJf1-DWYL=v z?G}#sLe)}wm(6AKV=%3Z-$06Z=>Nuj$H}tQ3iq|8eqArbg#Iq23N_dF!cRV_=xz5A zCFUtT;xh(9z8s%63RS--i-C?pdTaIk2hv2{?qO8y8-4nsq1;%k-*$hM>U{UaPj#dg zu{3TYn|!51HP@{6_g76|guzHSlw6Q5*7L`q}c-&}QZxN?Vz3Ind9^ih%6P{YK20$=TnZ_Dgr9i(Z1LyLJM#D@`Lq zUxH_l6&0BmPxaqzbObV3?^Y%LczRbFy<%>Dm?cMV)hs|`e=CE%{FYn&jPWghI168?< z*}?CN*g~~MWb@NR#@U&%I(6&2)ncp$J{HiahQxo3UP&&9aXSydleT7KH;XSea$(C! z4-S4%CO0#n8lGN+akw-) zB^qJvo#Y?HmVy4#*uEZ-zk8I!DwbTDy>zKK)t^3^ofNb(=d8@OVObAa4yZs`YI>f1 z5$sYIvmO@kmgd1eHF!=~#$dUbr!efg_ieyo;-Mm~z&x8o_?us(1`Cdht~z($oMlrI zm}gE>$`}OhGJT9nrs_6N6Sz>|nwQaYPp*{s=7#we-KxB5}Qu9QrC#X;>L77cs=JZde=Pv z6UYCmsqG@d;~ZbVLhVo&|CRfv{F2WO5}s@Z+}34Kv9r^NHXhO2$8RfmE@qb^CCtu6 z$(#JW1D8^d@-`VJRMKS>-lv{*y!5P1)x)H`q{nHJ_u;vH_Sp`I&co?z~8kA)Y{23eC8Yv4}rrlYBhFU z*8;>f{b1&587GUsTen{jg*bj^kb4HgcP{m%kYQ6NaDn_l@x2@f`~u2;>&NyS6jCZ^ zQ5Zxw*-i)k!5i|%ZxLDop^T(qB38`w;U72x8GERP`Ejkkz}D)xU)cE~=vC>jpZ?=r&C?^`C=m(W%?wS{grURYrCGXw~|aiZ(tp3>wEn7h3hQ* zGo9>q)v?fAlZ$&>EFy@SC_Pc9L@rXHEXyu=h$iQecwwI^e|5Cdqx4VNj?l%@4g%MP zt}8y~-aDj?&l+<9ubWoSpIZ}BdUhm#%8Ja}r}pWmw{c<>oeISbkKFThx>}CG)Dnk- z1c(6@A$sSR4py(TGNGG%64g+<^>MYJ(gK-p8me*YD0_|@=JcH@Nb1H}mL>LZ?nCkc z6}|Ka4kTytJR?V#ChtzOpX|>oDOal&Im9{0nD}PA+@=!DjdEcSF~b^Um&#=o$XZnj zS-_5hIyAh@Nck**3Y%X&khNYZQmD}-A0p&Fy@ z?`HFFsJS3`_}o#(es^P-?k$HAF9KuQl;t z-yBJ%ICGm%2)rwMG1oLW{q*cxn?=!xx!c^f9bOZvahAK;_0Qa-7c8}up#)ESN}Gz~ zn_|q}YnNDznYj6p#>XYa4oic=yH>dsFRuQKZN~?EDbKG=VAgT&7hUX4CvU-Qee3OC zy;$B)-U`G1>GSxxLGJW#lT(b3)CqDb9d{b-pr_V>;zMuzMxHtySXKr*oi8V8C7MhR zAJi;*g?Hus_|C$(Gxii_yjlLHk@1}D-CXJ%2{gHmC0)TU@{y5?IJ8vh1XGavg|^Fz zkP?opW_;PL5ypo`b&Y_-$SbmShEU4B2k4}R_TJnF+ys1uNvVJ?!FSw&4ZY2AWsx(` zP5wWWfihD`$vpw@$J2{n1+KBG29tl_v7TuUeUCa#`{nupeBm-0m!K9B$rZ;e_~%Vg zCwB0GjUvE0J1!!75Mcyu=3TP<8E^INujc-w1eAAdQY_vrSJlKkf~rF=LASzV!Hi2n zB-&ZuF-b4nLb0nUBty^Ctma0iGy0d53fX?Szn;11ZYAUUz=ql5-U;=TPZpJGy` zW1&zaS3i{i86+Y`4tfcJ9fB5Ln#hl9$K@bs=W55M=J zWGXe(r>SGq4`l?e$9kwg4I02tQYt(+g#Yq<%ZT1rCB6c^dMQ1-PHqtX>aHcW{CcWH z0q)ZFK5R+;hV?#n>V9@f-fWwmrqkZ< z`;3Kyq|Gw}n4SDLK_-vL{Me^8xs!tKH3G{?(Vl5wG#iP#^LtMUYKuxMCOPb<2||q> z!P*zj?t(75K~CA1o`ynh#%!oy6Zv4T_rc}f!2zFfQj;E9LjtpeLiD!%^O8dOfA4kDNL`)L*!85CH|7WPCwZ1a7Xp;y>KF1B$V zvl5x#Z;bHD-$CQfe%of@qoiRoW^QwrwiTD*pWzWwzGA8Yu3K!LJADz8g%L%p==rkn z!#?lhhR>cs!MCgLFNB`>u|lqc{2Sy$CLmF$hKQ$6qD($S(KZr68r{?av5VdjowG&c z{rqUF5%D|-J&YN`Q6I`1?U#NMK}YF~m{FMU!!~V?Vx@fM^G=yqKAP_;MtUZcj6Etw zJ?g2JhwmHQbrr%aDKWvuqJ)7T0w3JwLvFdBjXEv%|wpvCk4WrBSh z*qcnEH|?-98-j=;qVPlfvoU;IK1zX)Nskhx;F*L$nM7?!SmX?)=opTA0k#?9>%@z% zzdnBb9sG4l*y&?bvXoyCd9QnEK~U&)vcq&lyf=6aj-SU4?nK~7E`wL#FiJGAItG=g z#OjD5U_k?`01BqK3^_sKQf7g#mvQCV(KWP6#MNXn%C^dAw|i>MUCEgvAabXc*SUbH%Fm3&%C%G z1XWyATwF3xT((=B&w*oe%wD%L}**J1OU;%p^M8*14TsohlCH&70vCq zR8@H6hXwdlh3_@edXv)z8;K}5l&EL33>6#iRl|P{RK6H^>t@cb;IQ8tI2g6PJz+h|4N!& zZvK@tqw^<-F<5^kB_#t|RpkNz(D5<^K$cP(mG%{v4(*nbr(|*6d~+3&PgNl}KZKEJ z*KqfTlH#Vw1;@!yHpOpIA`svbPVm?vw2v8Mq!LC~Nt7BzkWvjCsZ`q!5SMus0GS0; z<1qRgqPx$HhyJk?SINJeqwmaW3}>2sg=yGir5uMW8xk%8X~&{%ib>5Qb8TEg^>@EJcpy!WDBGXxd?Tl^qC{7mh&5#o zw)yO|-F#|;DXN}*>U0a}vjr+SqKhwj1GRX=B$@b>!w#q z-%9=@LMY?V?iR3){56&K!cinn>opPm}V$EI8!g{ER;!JeC z-nrK(rPaKIrK6isKMwsUgxcGPg}rh2RNsrSOzYH#wFJy}JM6uCMDxRIuNTJJ8#v#k zrPL>++iw=ucLM$~vC$WKs~?@#=c?4Np)`=^j%xB9>c!aZSDxuNE9rZFF<}0w*GX*9 zg4)fxdEjVzz<{f-U~ll+t^d9IkIv>F$f3S8vF=7L)6Cn%WZm8>rTVeGj_kc39;HJ* ziN->REP?jng}vb=*vJak$lC3&FalQ?IkHna@@H>&Gi+oJHhMHavc)xe1{*!F7`;jx zxhx&MqZzr~8wKfM0^DPFN@Ez|U{rgRt{R4TbQU50I1%?aiSjt9 zKPkyQDWyCqbN5rNUqH-gQgL`vd4KX1KI)e$_b)Z&U&g*4SZAnQcxrdQNhDuC--uL3OTRf0mbjK3a0F z!(;v-&3yLw{D|Is(9sLERfbx+8D6^EUqYeV-g%ZWUoL~KmT@AMiDEFD`3O!C z1g+W>uPEc?!zna#WpvjmbF^wh`7ztu2~NlGHQ&orn5(u930X6V^Z@*G1VK^{slvgs5&`g%VB>W;(HpA`igKc8bO~rB0smlo{finy z$<2r5>}GTuYWf=*2Pu{8sZu&y1Yuh&`kQX|>mDOSn1(RvbRr=`*hwWph1YLjdBc!r z(K14XBHuby&K>9L)0}|YgAn^S}I-$Q$sfy7* z29b#Zj{^9Hpo6G#q98c_cIIx~x4q%}z42$jNIOhZ1?xK?PbrD38-=N^0^3}!r;>z4 zj%)yjn8yJ6&kXk(z|rOZJ3_Dz*!;a}{d>n#fcCqwGKju<5k$hV-XL*g|6~9hnTGsF zXI4j-<$rGv{-Ed%G5^+|xnx{5W&mRuD9X%TH&RZ6BXZO+73wJReid&Fzh4DxTS-7# zf4jzi~c38S9tT~gY6M%(+b}*v|z9J6JDjN(t4ydEYpq7_Y1i)h(0!1XjQLC0q z+l9v~EbW%0KYX~fl3-NS-hC_VN6KOOGCmau*4s`RmqFxC2qd;)CAVGCj9>M8Vw@a; zY55Br@c?u^Lop#x`uDnW^eUYYu*9RZrYdN(E@*QjZ6&--;;l)kAbM*XWHqC%>RN~ZV?gIWQAtkeN} zOL194f$pz57d&IZ2EoTHe}4N4iU7vdAqj`Q5}ZIKAPR&9E@A+zb1( z5`wXi-Iyf0@GNY48nlnuJ@X;M+6E~vOJ#X_C<@2ns_Z2OP5YDk8P9IW0b-XABcPA5 z47&(2V0_)|FK&+pxWu*PL*18=kS@Qz(+Y8o`*HhM;-T_p*tV5>ghDHD#)A?6&kS4K z(nQ6Qv>fn|a#g6TEuTJfw)4L08U>maK z`;=(*5d&{Wu9_6Vj-rz`P;9B8=}R;G(G13E;lXWS4kaS_$Gre0V4|hG8Cp!wCM)!ioM$|3q76Pb& z7xzXF07rsqN}y?PHg%_!lmm2FNA60^^kOoY(yN|UONqyi>dUP~KRXVBtm4b!2TDNb z1oou4rrPqfZ$kgO<)nxDSI5H1k1|=~kc_Vu$GX_>w?#2=GQI4@K00{mj!|~1!*eV3 z@ytAkr#Y4z%PF*rX0MKw?VrX9`cKV^wdcvLSwfq`_Q7`59#eKySJ6Bqi z$}39!GF*)Ofgv_&bq6LZ97vUy^8_lroDFkPeh;ybcspIs0ho#}c9`V-eHHH49wT}} zu~|_zKoXbH&*v7D4L6XNW@02_P*myVBqQ#?RX_aFYOD3=Jsk7N^+WDxp-!IJj&9NY zPFh{032eZ$-3&$KVhi++GIR^<3wHuS7DTT9m6m~w$gL#qe6v{nf`lQ(eBF!D1a3;x5l?B?cbK_;SBK8 zP?*sDarQU%>{qX+A}g?4Fh}WaY10dq8Rr^{TIwvBzn$Myum8SbY3*^Nvy83L(8Xe9 z8}6pN&Z^Nk_|D4y>y7TVtVYvBo|R*no8I1gjqh_CR!%K9dWQiT&1)>yF2ip6r}-K! zf8JTUE!^l|{`)=t)2Q7HZZ|dBZZ@pH+}#)eIGXL4tTx{G?uJ-sh{r_fmk;f&Aw*8I z6RIzRo{sT-_)@crdebIQym=Ati)J?yt8K9IUK@tHG0ka^EF-aTr7N3ME}4R#;GQJG zIk$AK+w4n)q*=)OF-$7yc8n*hMq$?=L*k_*_Vt&yrfhOr1N5J%XuROTt~Lxw7YNpZ z;@4Fkg+7qzsI2Egs6#yK%qpp8o^YCoWtbV86jUA38wMOg9GF*ef-|S%?ruLIaZ=hI zLMA7N;{RW`?f@eQ{=xF(bi2Kif0OK<&vK)^E;? zB6JsQBYdt$tGrTDq`a*-$Ha^~e*C1+tQ)yI=5YeReVP75#Zi1x)!g)<&dlI@E3*3z zFoU!X#M)M%w2bkS_8b*M!y*NcBqCra+er&}bx6=LSTbyf&HQ=q^nF1bJ$dBM5Nt)8 zLu<(<&x`dyb;wcP^XeTCM9r|BboL$J)5h;%npi31Exfccc>i{pt{m~4Y2+x9*h_23 zv~~aMnySAOnOOAjGIm3IyjY|%+z2nGuc}k;-Y%&(jRAAHTkxPN!o;l6a3zSJ<=(cR z%I(_*ElgJQe%wUi#!ZWbUhp|x$JA#&Uz0}#uD{Ce?Nrj%c6GM?;l42nh9F3k4Gw4P zKit>jPbE@LyfX`Lq8N?)zOq3A|I=cX2X-*8{@)hs4eIs+ZL$7Oi1q&J?DFOsO|hO` zUEW_DUtV5b{JYN4^6LFRdi5MFucA&*Q70#NCnu=0b=1+y$;rv_@$u2c85&|eJU_cX zI6y|?lQ-8ud* zwRL}ge{b*4Kdbd0*1EI3{m*ON-B|nQwXUsAZLe)DFZ~B=U0Ry^e*&#&o%KI1>pz8c zV&s29tOFCHXo$7HzyHUNAJxD5@_OoTT3YVvvSzD4qgrH9jl!r}PE;lR--@Rl9UW++ zwW;kJnrUtNUfbB%fEHQX8Yd?ho$MGD6RlfluUz_8sa#2= z*zjexMnptJNJvOPKmZzO_3`mRE395#rb(Y|Jv=;IU0tj^EI)t#Y-eX@WAl$=wY0Rn zH8n-OR@hNjPck(!Gc$Yt{=KQGsgaQpT46QQ)kQgsB0YX5;)m6eq*WuBG^Z;KTTu`)3+{r?av?LUf@l9KYjAyyI+lK-|?@$vDYP$&uq z2Zf1=0)XFGSa^7NxVX3w2m}WQ2OAq33Jw!BN0*|G%u=i`(xQ;^i}(+^9B?7OzN;=s`H0ah3t3d`)dkb1wHbuqdDeEZ0hN`vRC?>^prN-)w!GII<{1?(S9{|`o-{qe0 zso76w<(!cc*KZ3`<^G)!wDwOelj{Ed#EP+@k=CvEox?xk^*dbai{&&JX>L5(8Wfh| zO`>*n-1=P=n*Nf{&HnFTM<8nHz{RPPM*L^Sl}5mg-Rh5p!HidJt#>z&kphcCO8=*ug=-OF=MCC{m@Ir9QPN}|*Q4cGgV%9v+%wl>Rb-2p zV_(uGw>v$2CYb$6$1a&Afz#(QPw9zx9NzQ5!xP`gM=O1ssWv~@3j&Y?hf*ZYn?+mc z?&muN886?gbZ7jtSTno{X1555t_4}`^|Hx|awA2kHXUN|))~VfFQkUjxEpbI3v(09 zIV_Qj!Cm0jb-NtcqK2sD-O^fO+>%mReJ?4JPudCw`FU@5IlpwW;#m0N;*Uqt6i_jn z*Nn+>?$-hiNk|eQF^zT@c&y&C9%tV*uc`;nxhP?SDyiIOD|^mLrH?TVPXtfphU?qq zX35_O+LvS9;90vrW$ie6W8GL?#5X*-f2u|4D?4~-)S9tLkt3X!i{JnLpm9<%Xv4vQ zmAfx7uJd-TD~P2Ju%l-Ag1PE-=?w7ljz)kWkH)^0hL=!pRRBnAz{C+c$MW@NS*v|K z*g)KF_fmYi)+vg8r@3a3(-;$3hYWPEClvkZ+&&;RLRfn_5uIq=x?7?c0q+qtczJVk zIGXGPKqjqGcb8igU+zH6(mn#smy(22C*KserKsK_xEC{<~R&` z1-?FpL+@ag+Ev7hb5y_UC|{SGAB1KQI2GnJ zGa%r|e->+?d^aNo5eV;y=J)3UQDz7h`PrctG8>e}Q1}t?6YZduf@r*Tnf%_BbV}?# ziW*Ob1+14agqQ`j3M`JroE)iH?Rl*Uh#SB{NOFNS8{lucmen zN0)_1V^SUnoV|(QskX(Uf!k#ClrHjvkD;~{oe)hvFbymw$ju>&6d}e2RN91a!dBo{ z&Qc&v$q1HZgwk3p8?_~c;{K#DU4NmusKLdEQ2J?!p`)@wY!{Zr^csB=^?M~8JMpo~ z=QP(sfqc0(QEG*2w9T36DyeXMM|A8X74nW)sGlx~F}yfPxzzEXG7Rm6mN0DW%C}HW z4QQ(;e11UB9&i8jz(Ku+=qrt>#?!Y-q}e$SDYyfrXP*t|pMR@-+ou_QqP2~hBm-1Q zx#eGQcI}8QQ=ACNT03@WYd1Zu>r+0kh_u()ntxhf-)Lt3=A-Jax?oQF3((`us-P8P z_3Ey7R~Iownh&9RG7oxN2{6LhTj*s z54%I=_+wsQ_K2KX+W^fp1mAy$f8W@5fb&7FXEl0C{43p*jtI4YW$YRN{Tjm$C5ElT zrkrs^^i_Gim9nTV`Q+Fkc0tz5In<(WgF=mzHfQ=TpFY_v4Zy|F!zejNIfPh_Kx6nL z-_vMz)2FjIl_LnOC@AqdgD{ClfCxiPVfsRO3`%s#pSK@C+vfb7aW4zk+tiyr&kTd} z6a?n~Q$Lg$v6TEVcJs8HvQ{wSZ|cfC4Je3#?j)-FD?gq9gH$i(vJj>~m@Yhbs)Tfg zLZ0T}2n3jA)AC@obG9kU$tr%zKmQDzvx zDUqbN1tTqXbi08Wqm9qat<~?(;l#n8cTYr`(+CnS>tjuPknJf@@`5w!4NN}=B}oLm z)03y!(TuN~ed*5-j|TO4;7NmNo0yG_lCMG0>8RU%b*PBB%~n+H!HH7`wf<4W!>D!c z3K#5;V026t|4psm9KWukP+~+HMVK4qgCLQnPs;RSx4!gAs6dHJ+dM)|DJr6Gu^snS z#O`ycOZQ|!PwiVzUUl7_(Zz~>yeDr5Jv#Ej)iuPV*E~V*5%^Ft_mSMMNCPkl+(6!I z|47e)+{lTmzTkFx4t?X9b*;7GE8syLp})mt_5?!%HcEgm3a%c9c08Ubb0*;f9|-+2 zag(3!Z7r2vy<5J&9BsS57)9Nnh#5M%rMoYrRiDVbb&$b`mcg#V55NJ+Z18!!okK75 zLj=7CK$tHD33*gJBv(YPj;vOC@#Uk?-H1GS2=FT}ylXEUUtfY&#K$w0k3baoMg>nP z3NMY!=Cs~dG**yuOchDt_gu(N8sbNJD0kH@?VIZwzzh${l@D8&k79lijzyE#Zh?tF zA9H&TIN1#2m=ayMj~D^Qd{zTUfQF5PE{Oi`lmOgTZep3>!Uo?O3D-z?r}GpZ2oPK? z;~SBEDev|5(foq_K|}(*hn5sX>*&{xC4Y^Y6#c~VroUEc_*7~94fnkYIFVJk|3cUz zz{o(;yQ#;yBMZYD`5`hs;G3;ST^;|iU{K{Y)A{c&Xp8l}0DckYXa4KeqqA3_U&Ipt zv;mIK%i#SQ91x6STLr?VoW{sxaAE!ta<%cfN;5o%(Ji;?HTT);sJ>7Oe-!~oHQ}>B ztZ3Y=OoD`N|MVbpBM56>QrN(_!&(CDE+?dcA>2kfe5xVR#wR>ORsF*|rv(Ub@23Jg zRJRq-z~RTdRPow%mK~B)9s6KN;zIoh4uRIa9CfxDPqHm*;H~J3WYl7~-=@ry)zO25 z5MM>~vW29NgS_C7V?IJo1pNGx_!9~udMy+q_K}IDi1J~w(H}F1BG!NbNMtxUM8hA3 zX&cKE9jo^(_TuDAt824iz6m^n#t{ifYWv!+Vey^;am0B*-G+Q1p_%fi@5trTX;WSHEegy6VES?}bJ2?xkv%ycsh-(jFx`(M^sE^#!uhY`=+*hj;lU(A+YNC&xFtOc^^)NK@vk?99e$&KA355!nzD4jKc#ukG>10WM#K zgi}I3GH@TlMk+xV1Cfq)4+CSeIcBkftFw8ov$>ntpuf{)Uu5mRprQq&Y2F%~_Gi7? z$+~o5z#M~(j)7U4B9V;n=bf1l1s0|2T$$Be_0GhK#+bKMB;@RvM_N$ql{jutyd)m2 zdL@p_7;)$!tj;EPDk-;YC*>(emJL;bO9$u+9Ku>@h%Py{NET=;;$_&ObZN)Q9wTNu zMBgIGTqMY%*ue@lTNp7=Xh}s)0m0_xBRt9k>1k(7zi_z{qJ09#b2kKY8$m~-3WA$_ zL$!0P6>{D*6_;L9LTnN^&^x**MbEDDkW~8fN4V~lINTlJP-J{TNHN)FG55#P9Ezf- zCMs`AY;5EQS@RONUEq1R5&UD9LpH%??E^# zd0e3UCJ|av0M9)Wys%r=qg}pST)N&=dKW@f^$|#?%-k<7qD}ewb%54wtc2SL6lw^? zvZ*+^DErf&-ak-5N?pz;3H-dmz#h|F(W-WNX5!%gfsHO>5JTM_=ww}U z)KDna+@p3W^S5yz?ckG2SSx$=gb0a83h$R|N^pDG{T0mas=7+XwD~Ehp`G9m0TXK{ z=6B1{983}XRD=E^s6C7i0BZRNv7oi}$?#vrsaIO`47;$sf!f5L51!}J8#dT)ZSbcI zzg=n9=%!XZPW`5xs^@)(LsJPLQsD>1@I&+J;}u}OpIAye*XEN}L;fdOS&VBN$Un8x zJJrdwihS5T zij`&WIgW+O#Ddv0_oX%ud~Y6_YaS_Sra<6O95zqtv`j%;e!8{Hes7r;ZJEDmnMF~z zEJ9n?|1_`av~JHeZ>6>l&pCLhV8CqNMjbZ)8Eie*Y1>i6l1hF2DU`+)QOI3|5x`N} zAo_}C%T_iYa)pFXd+~!iJ`;N5+VOQf(EVqzQlxcIHFwa=chKE-AZR)n#X6aFJJIwD zTUsYab0>)ywl^QPofo8X3c{t^^|Z7jsj}_duB?v;E0YQ_Gr7epgGp5o1SgXNY-{Bl#j6Q5I9Y3F@&`m zH@95hM0*Z&^>vhR3=$J5cC)^7N$Mp`=_PD|0&Ra9Km1Ab=PJ*IHfW-#AO;9{4>FZm zv^qqmnp?KFm#8osndVBPKHKZDhyzag1i=8QXd(MFcH;xX917g^$|Vav;{gwmNzpX5 zuAIHnpZYr)Ffz?6{C2BTEnd?HLe~xJr=sffVNC(e1O3SZS@Kj7IM^7rKRN{lhm_zS zMSJg3X+GbUjE=z`Uk}!w+N#VEoFQPN4ntHW1ASqA*?;QowF}r0aLSO9nE9s4o2(Nf zuy$rYrV)tiPuQ}Okp^c$MR8y6bv^b1aqO%FC(rjSKf;W5=fM?*#juM5}iHLE_C{oL(!gUeZP_J=HR7-uZ(pc8qxX{;$=ic5% zV-g^*f{N6ie`?U1WIsz7Fx&vVg(9?3n#-U#v6eRuz8l|d9vMy>!Djf$fq=)m7D?$1 zW7-barw#A0;JG8e;~izZyI*giweTa2mfi2 zaccQ#5f1IhB$$iB<)WSMuflPK&*ItU_Z$v`^t(e^W?9P@am(kmx#5)_04D$FPvs@v zRdW94@JlbkG8J%&4Pk=KB$YlrQ+u_5@G9wfBj?EcVEDS+$bfT4GCmI+e>jIfeZ9ew z6`V!*0|wLp-tCrCS4UsTmDgDXmbLVjcNV5OtTwShbMm>rPgF|OTGyk5*BDgRFeM3^ z_~0ov1kVmO20Q&?wMHRT4VWOD1uw!Sua!<7 z2B_jR*EmM)@?byRt3iVO#F4%2vhBphRZP&*31TVXV0QBQ_rl#;Kf`X;*yIj@&YzL> zfiPPSz0FH2_|KQ{pSNEw7WX*B$3^$H1Oldf=nfME4hO{+ut$$xCng{Bz(K&;Z_h)= zqQ4mpjiSou|*;nG#nQRphw<;`; z>crv639Z2)J>jWx#X;#0fs(^tG(s@CW4DmFzV z_JK^$oc|1*;51eI$o3INfJnD7y-D%ncBR$w-;r(i(N!Pe#SdXH0{RQPXBU(&k47Xh zfed)AcB%{NnW^>3OY19@jB{M{f=MO7f)Mx^e9~Bcmfv|+n}w6LTynQC%=qjoS?wzO z%T-mzRg!h-fihh6evC!pnz-$fBBm^pj|bOi_x#|x8uLco`gpJPYUE%$jkg3`^}8nH zGS`43pPm|ltY~hY8b$#ZKTy|hOS^-p3oq2(S|t3L-Zo$e3KYHDw;KNSisLsuHMHa! zj~`?0?k>gmHi-SE|I5jLS**}UQC;oJ&javjpGg-UuCzluF^bq4%=8~&lF-VYQoJ^m ziejS1xWegPS4iO2djvb;?N&@-{dR~8&fa{PF79!UMfGM|C0j-&o7wn@>5Dv)Gaonh6>& z(`yT$OHMMM`R)nEg7{dvetuS6vhGnNIpuR4`_UxX!xn z&F6!Kz@M98=rGq}%V37yv&qjmNN=SFG(^_v(DkkHIl-$LH`VPMY97}gWGHOrN+d?d z9H)5J1FVn^?4#6yjtq-fhA3W`t7*DPz=TpW7K2!^Fy@zCYiaM7&YQ_YN~TpZ6` zhDBo(kDH!w^)GePkSO`ILZq>M8-75c_vecm$PZiyQdKSHl-^$GQcVcoaQ!=?CuMJCQZ4!LAxv-z7;%jJmydOh#$)C1 zKuRoGDA~9ae~w!1{FMA$}m2rzN3krbnUw zhqM_(i(eW`MHbpeWP7C?IN#_yr6xZ)Ps+oKjVuAhyf`ojG`Y$fLAcei9#BK z0bo#AHO`a6lJ|Hhz4ClogZ1JU!HYvoP4p>>FES{LDLy$+Or^c;0zAqay!`_UyHL`5 z*$a)ILLPLEM|!%OKrk7kL@tjAKMf%f%X~e^<-^tbROoKgmS20Sd1ox(-T-Dn6`-~WHp4CsaPSha3o0SNe;b3S;acY4=zE#$THy@wk*7H z3ORDLmBDH=Vo!U=>}0mg#rb9{*WiBvqd;80Md?4F=FT|Y)U0!qosWRjvW=89ek~0V z#dNB(GK4XVP)kEKj5ZBz3M3KQfQLGW!GwX7VH;Gl+BXMOFR(T?mH%RetJ&CTGP3e( zvL-uNnigUJW!Md$mqi;+`LDm+4iN4T;^JcMwDRz zmC|-1{7hD9UjqS9go1PqiNrI&=33@v3AQ$^tV_@OLiZ6MZVIE@kjT>8>H06Hq|It~ zw6Ft@n9dozZEkvB^xR&eHM-Ju@5xl=hX^dB3vFTzci-!&?^;W^1|pyN)H`4nvG=Xr zoh^dP+Qa(YZy^CN##mMfT5s*Mzt#G0Y#=a^5({kY9u?|@X>6#7N zRfTR%DEZJ;Mwfa!j;5@M6MW|`6UGbWI+sE8_h&$}dN!VJ6{uUoSdVNVq^1UTR!|*U zNlW(3mi-F_>^HYDYkJeg=C6}6yyotlR(ubMgfn;40Rs&?Pp-qs+CfxkG?UXli>$I%aH0ay|TVrh5j+s$TWY4-Q?oz?3%u5KE@| z9dtT%EajjnO^zM1g46N1>1SWx)1?mecye9OXPJ}QT=ec(0Vm{r z$aPGKcEX!{tZZ*P;*srkpIA3xTQPuk7ti=k>s`&@ERZYpxjC>Ejr4BvQ)jp3iH>;!>7i7i$Gy`>U;ld3lN|Q{&Pu@X_mm8DcDtuX{V!$z zX}(8Ul(~n#pm(2q>L*dd2&I0eKdM*`k{}x zKKbqY>)#zJ^P~&_n4(M1zP|oV_PXZljywnjdwB>8P?Z*VKirEyi`zJkdq9uqxTT0d zs+hTuK$Do#zr`qy4f!(CV~L?-KH4LY3ZQ|INUr5tz`|=ljk`dZ^Ecq*J*c>?SStz3 zn2+kSzPt-S5)71vJFgXFLA9H~BK$xj+(D&)n}k6NserJNJ3<{yyXDI@0o)HOsDOtc z0G1O%!fQbYd_no6JgP%NqA)kz83>TLFaMt_L;vGJjxoPovx|vHE?Votm-|8r3_}Op zLol2_>}v`Rum~he!-U9yWRS2nL_Rd5LU*&m?g+byAiLGL!=}qa39LX1jKM7vzm*6x zTq;Bc@V*QH!6;FG zRJccEGd|e71B69OBtj`%L^u3JKrD*Px-_(y1O2H54tYjsR6bN>65B(xWPCqagosQW z$3E1#XDibLM1jkrhMpH~ee{@EG^oa&zHiH;} zhB>}c{Kr#-Lt^X>^qUA5aE3qG$Nzg1$B!UKj5J3~+(?e3MUP0a1z?Ec_&!^_#SkRF zK#4;e+X8xXh*Wt7eXPin(gbdJhj+M!HxP&kzy)@I2Vvj=!~4io%f@tE$e+kLdKxo_ z8A@WK2@$M9A0!l7u(z2!sW^ZGC0K%1(1#}g09+`CGpK@Vum+(tNlyH~B~!?r2!IU4 zMuM<_A!&w=EJt(%K!*6DF!~0Rb4V-Uf@f$3x3bEUY6nap0ev_GfnWlQlCkL%NMI~V zwT#S`s6mEE7iB;My3|O!6uKEp1#kGN9>4*R`jNQP(uVd;X5)C%J~P7Bk!RM>_Q#1gHU!+Ntr*IXkh zfCqkX2RHx#MaTz&z=l^?h)xQDCin*>V1V;P&-7H!^<>ZXbWiof06D;b_oUDIv`_ey z&->KR{lw4tq|&9jfpTX@T1NYdVnOTf>uxmC*V%+1W$v=%P_(OIpEPA z_0b;%(jXPmAtllxHPRzR(j-;VC1uhkbQd?*fM3~Yp_0lf| zQ#rr{yZVPzD2O*Wg#Rf>18X3M4=~ZvG?1HE#fKPxMKHS-MI~v-1=_St0Km=g&qP&J{$$ifz0XHI)C_z8_GFWJ=mG|iR7j=IP36@0^i=)K&vldeswZ1u`H4DQE?M@Elwq2eGtN2Vg(~(#)3;P?c9aS>{UFsr_PT3v)&ztv2!9b4Y?33Fvawu%RtoZ6Ok**DCWm6Q!@J3v+0w!P)s ze&kh$eN6gWT8D^OgP7U=Yr?=qTAZC*ECGSKIIg6tO3S_6T;0{o)yA?l%9eoHr=5pu zj9aRuIRCkA$gDMy(l9`WXaQSjIoEBizCDP)U0%}NUEUQ#o@h%8c}oB=fCx*5J6+tt zCETY>NjrgD*^pD6Kwddh-qB53rWIGEb%}M1wSh<%W*}ODa9hAl-^x2(ETIcyEMN1* z+}H(R&E4GEHHipVHnzgli{;*`^k_tYl3#MP@MPJ74-iGxE6KIe88;BF=tf(E~^<`g% zd|YN75G}a2H!~p^HYpk2K<9m45{_OW4iZZ%2n!GkWbhpYreZSO#@`Ja6j2c-Mkgn( zU;q2HVFt$GhfqDWy_9A6IWAsf0*fXVsAWY*E-`)w~q9^#N7m$edz5Z)g@Oyl15p+^SZ7TKz2nFv~N249Tj6Po1> zc0pP`$&fgJ>mmpgXqZ|M%u*g?K}Kaewi8}+h!aSiWzOXP^;H25V01p`hEULf(10O1 zhAlqFUoPPW_U0@(E!8CFuWDv`_GEv4X4{nvLNtI&QHIYe)-JB)FD~L?ZV~9TTmO;T z=Qc8DbzWyWwrI``iRt|U4hevCN!)t2ey=aVHYS|U*f~b(~69_Jl53K`cfDULA&T8<5WI zsO}(d?SRPkMxo^{Y|zH;#%&1I%K-gZ2E~PN*p6-OrU@P>1#hT_UpNCt@P-Ro37pXx zp79x=5gLIY8lyp)ff#^N0Ec`yhf^r5si~T)+3FXOTm`4-_l|G*e(DB4WrHZ>7Z`yE zV}{BlTMQ>@|E38;AO?NdhE3>GB+!SI;2XaI0KgF(!Z92GKpe$k9RJ4=h*|iCI52`L zxGK!i9IH|+Y5@UfSzU%efk!xMAAc1Fck&_^@(eeK=>>!7<{b-f@;?W3B7TW?$b~B~ zhzl^&kr=iu7?KM2^RTAxlCFsY--!Skq=GOY1X3Uda-ijr@lp_nanOYuz#t9sCQjl|5waE$ zXyt`Kqi4A7RUedAPv^1jb~-lTKwyN1Q3n0KZdi|XU8jkD0K6jV2bKULAtE4xFd}8` z@+E4b62%34xCSyXtZBHSEE0$<>Y@)N(^5|s!P9nDSL*rBb^rMGc8l(cL6DDQK1LB!mZ=X8g7hwr+V@B~ljhf{cZPauV1Xik$5CSsbRV@jrF zYNic>CV`M9YGQ?b7>En_2hZUqXX+rVLU4;#GupAA2l|G8_@y86jK6AgZ5T|+ z=Kc=yZ@){I5C?JahjKW4aR3Ktz=DYO;Y7H{M*XW-Y>cP_k-eb|5f+<)~ExRiN72J624hB6^y=n)(q9|c_2Xxp4W{;Y~%5mwhmU~5&z{mck00=S)01yPAfK0)J3KueL zSP;lRA`T}~tk{r&90nFQa&(AMW5ZAz~h)P%<0Kh70wCK*HAw&ENq4X(Ki=X)DiE8yK)~s5$a;?~JM?xI^v_h2Fbz;x6 z4AZJj$hK|4w{X**s0EYRAP!ySw&mN`=FOifr~l0WFzqnn!*G)_b-MWR#5{aN6{tAi z1mw(`H*>z~FGs>9@5n~v>{spSy?`~R=BjhSBWCmDAq%A9Z0oJLb+1+_xO3;mz%|nd z#m5T86V04i81DQzbl}2-^&>W27%_3tNSkHd8}ja~;l+PnOfo>1WH5~p3iKra?(%cx z&j%U!AJCg5ZX~?nI66hb0oc|SK~z*gGtY1_AcGA$sMIdI_ybIYyX0aD4&0eW-(U7+ zHXc?WTJ@0&#=x}9A}<8;M+c~J7@vn9zR1yUG)1#XLYi#%;6eiO$XO)MMDin%MH;zK zDnqGN)`l^HH=}D%M(Lz^jT8e@JdbF=f&U+YywG8jor%a$jViU%L_$okb0h#hvKdun z6S?qAGX%VOC!Wt;fB`{6kdnq$Ol~%2RD?cd=%G?()xwpt(Slh3Ujzb%oi0*YpO}hL zRAx%`NRf~f_OR(@o;PXn$tM&U;LI~Fl=>>Ha7m*H05hax&ONkdC8&3oVmhd%>i@2##S3k{&#HBAzVRTdlMI1`F_W`0%B$MW79Cs? z6~B0s%`Qs3De=b?>A^>;6Il?63vnhrHPs1m;|UP&WC1`G=)mjp%3+JW6?(^D2}!a5 zpp-%&fHVtm&sr6{)7(E-tq{_8D-;ADd>E)V;DIM}h(7&DLy##uV#TY@ERWqdS6rAq zPdt!d78gqhh!IE(PsS~*#^V6Lltpi!Nk{)KmOR< zIQ1@P%#e(*5J@ovA_fAUx2(HQ_~DcUIQ3|wO+DWrq3wUN7bKY|6}b?}@Y;(%enpHc zzdY{&3#@)eE!ai5_7yPITpN6|#X9{_L=4Ps!Ad<3C^DDvO{iWK7+ zT`(X72P6!qT&IG<$X))xhQACxN1bHYc?%Z?$z<3?sc41eS! zAN?2x2?R;LJurA{Hr2u54p^w!Eb_e(1<3?s9`B@!(w^v4D`kAP|0lA}4tk z$&`SSBT9%v9FlOSyva@r-V(t?7V!*Q%(9zUVOT0!@s4X0#TxHug)VdEOLeL+Bx;n+ zJZKTVj+j7>xA9~rlev**R*jmmD*z}iHjx$3Now9a=u>pTiiEJjhbimMI@#IFc5-Br zFgeB>MPh&wjvJ45f}Ul-M4lX7%Yp0rwA;-ZhPS|+8E<*b3*4SMM7XlaQc+Vv05G@*KF%%4g+r2I4MSJI zDM7~+0RQlg>mDJ7s10Kf7T6Fkp4PxFh6{ojdtSNGx4sn_!TZ*`6BYSEFY(21QZ~#H zArHC3RZNLZMSR^Wtm(uzoXQp)VgXi(@Woc{N{ksyQ5pA^AY6D!aU-mf4!rlCKYlEE zx$GMcn_AOj|lXiidi?Bkr& z7{j&ZFrzig=w_PYAF`MT2~GiwXtd%7tHWvpD<;qt7bBLUo~jE^#y`*pZ7sqB1D^6mfs)<~rXw&U>DAwNJbWA$Yq4 z7Ltf=Okn65Z^#l@0gio0-Pf zu~oRFz94|LteuISN6Y6yKk8)Mn@Oi}O*<{*BihTumuP8W@R z7~=6lZ25>n?~#n0AYYG|`BQ4%BF>-P#=sAL+ut67xF-Y;|KJDq|KSgQsLml+kOeyG z0gO6#a{viCbnU%agk20p95y-#LPkz}^ixKpuz!;VlF$z*72UU;ttppk*7&v4$kb!#p6v)G0-xY2N+; zAi#B50RCJ<5M4v~12%X959A5pX^*mD3`1zs;c*6zVMbkCo(2Mk^hw_bJpX|237iUk zAY>Q-BqUJ=UgQAA7}}n;M`!y83%V2#Hu_4duhfA zBm+J013e@|!m%N6ID$E_0yMEgIcUNuw8P?Ag&i`X2j<~ppg^m|gCzLh3Ho6bVxh~) zVnak)#~`BiJY7RP!XgMEWVir4{KGeh9VP}!IK~bL1e75$h+T}sKcGWQv?FkU!z(1jD}Vz4 zT){b9g*^^pL7HM$EP@EuLKHfeWi^~Y(qdC>Bg8@4L5c*aF&(mn(H?w4LoUP$bioGr zU@i2*KbV8%QDkStK|XMUF6hEG-~${0fF@+uGjd>BO=Z_*MF2cPTj7jzWh2`SWIlFd zez{;tMBB7g+p%>M9Tr4_;NNDP!at}3Q4WU@yux&}f>b7iDP+StsKYQUK|xFaF0cbU z2ty5KAvAU%Vs0B$7=Tdq;i5$aT$$NQf@PzzWM0MOM&O&i#s2}n`5Oe%)CE2Qa45n* z=tEo{Ni0!JMD!#o5A4*UZ`kbpiQBNP0? z71iQxDyB%f=T3}(iNph2(wfe3rMbCe&ROPDP26&Jgw-X45@g+HhEZ`G$3l#uGqhM{ z-~j1q=Vlm!J?H{HT-PQjj%fXZ0-nJ?6b3<%gJ&j$1V~>K{DTrO0E(ulimoV&wy2A~ z=!#;19AE&9)~Jo%XpGJ%j_xRr<|vK!D3GS;378Etxc@+l%IJ>0yE#{3)OYs-O-kp%$v49x9?Hs-i9`qc*CeJ}RUZDk8iDGc-b^ zLh2lB&KO)Or*^8Rek!Pjs;DL^CU9v*++OaX!tV86m~zn;@Bt`Pz(VL5n*M{DW`;dT zgqt1#fl>r6j6;6Z>7C}Oh?1y@UMZI9D6&#%mM&|MHmkF$=nANZGOWOhLMxOyQF1k@ zvPP?tVym~_D7c2JjgD)NZs~t^#QL@0`<Ke~dgu{+t$x1AvIT11;t$ya`+y>dY-Gm#$;Ty_fS`Ns^ ziq9v2LX-i>6x^%Uw#5TD0Tw)BZLh8zemL<>AZeLe;jKyKuk%SRF zO4JPU%op_@CqAa{nx*STyrY21BR%rS?ut(VAV)&XNi%SUA^d}#n(xG*?<`s`{X#_~ zj^O*kuSqP6+YsE}%IyYsY(ZEgMrtHSdT&k25(0%nVG_g!Ji{|ouv%=wKbRN;mx}|x z?gn4)Q;a~X1uZw41eXNDzi2Q7Pya9MUZ(z9gi#`;QZl7eLgkMHu=e;>LNrkD!iDwC z=?tH5dot`DCZti^= zKa64)b4v}kWD)l)PGo?IEW;!2r%BY@+pKZ&;_v;kryElZ9mmdr<|F`g!8UCMF8o6# z^syGpv9^(}Bb&qm*ab77-%E-_2Xsl<;jkJuvgt#Ldag7Xa+d^ z!xeb4A8+x(a`EVf1OeDZJP>0KcSNF5N@WhQ^ZBd?6NH3PsD)xEkxX*zbXo<%)Zw0m zKKui#3iGS{aeoH#Tmjh=(*Gwchr|>DZvB$+E59=p;RKuVYu8MzBIV$7klv@5^Enf9 zC>t|Kn#3Z&#BWYBM*yT`y0SE)(BEV0lmvE(X?$^gx4h7khCrdk+%P z0&z<8M&M^mH}XkCH6-K2%3?vwzHH34syCUV1+cISZv`A&pHPo9K^HY{7Bt(qv%yGeO|7T6n`h91daMiD4)9WbJ~3GF`_TPa_of#0e(8-!~qhV0XWbZ0C)g9 z?7|W}K`@|$eK0^aL_>NLL>BNvDKr5q=z{_}1bpXW$eQ0Xpz>MVH-7VoemnMbA9hD@ zfkMCaM3`|H9REO6^S6&jw`Bu|#bMmt5yTr{b5yUm% z!h7E~LU}Vm&_Xc;xK<>BI@UOw+&DxVc}Z8q3dn|17kNV{@+hCRS&K5qE;v>M-Rdbs zCcq^Ce84)S!UJ4@EO^5}0KgfDLkM7bL6k#?vH~}Jc?lyFXNR*^bi+SvxtbRVn=?0_ z6SqQ)fO;4M8sqpv0OF7zc%Bz`8w1DO)!h~n1P+h`IuQgEgu@$tgUAF>IUoe26NEk_ zLP2Z-St-Pbz8yqdI&SZQ)xt$T`~xz6dVUZ0F~fSRGlT(L32V(1^rTw+0O@6j zwO>0?lX`+@dqO;+a&J39IJLPG`I}>WRPlLKSReNBgZ6RXpj(49)Ez-!LOR6B1Jr}D zyTiv%J3n9o07!a4Q2IhFdk8eUl|_OxEHqbW0(LGusAKytG8fh5TF4fpaO=#HBbYe6oeM#L5 z;QvAsJb^E`gRzNKmS@2}lmZi^f{I&ucqv;|jNuoZMFEf=py<7g6TNYlJJT102DBQg z8@K!>kKs=}@AtmqSNB#BT^V4m%A`Rxi1#$CXF=>c02~51+e16le@M|2+mTGUAW=?o0je8&Hdnj|dotA-$5%XGI$PLpF5( z>op8 zsT5ycMVM7FvkgbL!~ zS+fCBFZ}!GmvLjqk0(}jEVnCVwsZ}SNH(ulfU=kc!U*K2gI3FzMKV4;b#+I(kRR`b zJ=>-zK6)(BT4X>fuYcoc2Nyovr{u=1qauIWHbAX;$wsgSZ30jr6_r8zRqk{<_v|cR z6L%|HeEEraMCH*sVBf!1=HbVe55TzU?|Hi?ZTnDO3)BM<2qO>~JTvV+yz&DoK?M&i zDZKffA`e3N94MfxDio_>!VNiOtUm1;#4a@uM-(Wmc^)w^H5mdCBZ9d~?Eh;)pJt>n z#E~BC&?gCXEN=i5x;X5qX#PQ`$0Lz+>O&cC{O`EzGC+p20;Lm4g+KyH0l_A#oQ%uQ zVoWK=Bw^x_OxQrkLkVY|LE)(f6f@+^Iq5`cN&LP{F3;t%qh%gtqEiuoj5fkE%qL@wr;hYJ|bN^7lAy-ZZl zSZ{I^REi?KRjV!d040)VB6+Hve}>W3SUN?8kyKfo1mJ{a=79uJ(MV&G*=9*xwpON& ztti)Sp>hBeJ}N2f)ua?V0^D_VOjc1^pA@ONd62PS%M`G@&RT8b<^Q)PTiF%p+klhO zgAY;I^e?GX{;7uGhvjp3)_y5|D4rGYvqOvl?Yp*1ia~}6;D85)xThdO;bRqGlNvy= z8%&OwIEk^%w%--RN-?ho#t0+~1UmND=8#(&ncb3Qwu#bDo+&0N-|9(P>e*=im}o-{ zIA)$=&UNdBKn5}4YD3{2+fHs}MtW+Nv>2+3Kz;f^F;CX6+rxjXGF#brADM@l6Z$gY zk3e21J7~S%{TJ<+)wY|Y0)lW#7R3^9-14rf22*GzPs|jr1q3AI0mFwb-E{C4H@Wf4 z8N)!aQdo~Ys?7EDSo7ly(Ymv~Vi?U1+o56II+oo6k z@dxjJb6f*_>{kP5g zaKx|D0(p$3FC5TF42%bp1S;@+KUrW)h-b8QF^_))0Zb^Gfs~u*;vfC!R0TnJHvgTD zY>dg;)~M7K1E2*A2Y6sgUI@bm+9-YMtBdj;M!^sQz&5UM25)Sl7)R`oh##R{@McKE z#`KLDZpsU_N)yA9NO6iu9G(@gSVM$J5L`M8VIF$*42jgl6aN555z$zYBl1a$=wl2D z#3G3{+GKqCqT)#Ih(|0QZ;lS!BNw~nMG#hCT(^*f!v9$E1I0)njg8#m_5fJ3t^}YM zTbn~4TVlXK#NaJ^tVtd}0!o#5@{@nWA;AO*LZN_S6oz3*0q*gSUpSJM1zDpFBl#4I zt$>stX;l~w&`C^Yaec7LrE5+}viH^UAVC-xANX*KF`~p2iunOEnR&~mh;o#}Y{>|q z^$2bfL^OXWjWD@a!vC$aXvsXc*ix~p#Q5>R!{^fgQhDy_mM;>h72KfrH1n}BOs4B6r zPJtrcyg37HG z6c9irz$VF~3Y%pks zVy+VzKsXe`0}P9_xbQV@Qu?M04G{Jz2W2RKLy6=ho46v;1#wP2G7Vn9xV+fmo0%C?*?)26LusH0Pxj9cNtrIKb`XG%ES*RC@AZ6sszTdW!^7 zSMTu9#Dq0WPWWNfHswlL@<^f|eQ7ppyTm9a2_TQv;4eyc6$VkqKkQNJWrwiYCarX? zq4JQwnl>qf;^ej8ePnKTTi4r+sMN$g$Y)|Xd;;OdKi(mvbrZ4OeDpR>G@uL=@!KZ> za@CTb&Bl!H+SdRNcAqgCibey> z1#~Fp3`tjdn3=xypZKZK`v3Nc;0i?&Y-2my8~68h72Cy+JN49oDMy#hes;U-JSi_ckh zP?Td7uHZx)cCT`@zdr3aF@ThGw(Xl#TVJTnH}P3--G>`7_Th#;KbP>2QD77ls^CQB zvR}d8Pj&q)k@rTWt|j2^-oVQ9qU!e!@P>X(nY=EuG~pl8VHYIJ6*>V6@=yPkj{7ta zCM;kx!cY8QA_4^D3;((%`I>J7BM$}HZvo$_0Yhp4enBzBp%dn>o;raOE|7or4}#7Q z{cs}4&*?^#_k_pK_EDx69#S+I$;vBFnhMJ0FMwM`UV+N zO$bZE$c*p|W9<)}O>x*z_S}$}JfI&Gqp<|S45l#TD3Aj7uzC8>{JL=3eBuO{0qU-< zB<#)IKC#vm(cusk-rF22AcB6agWApc7nS0y`lJ!0~d#u@uwKBiIfYE20b+ z@gOzs8KJS~+{Ye^hzznz6DDF4y3qzJVIVE1Akz^dKWmyo@*~I(2_2H-f-wcZ?G@`W zo(fC32!DvVyQ6yHWw=Cc+KKax6Ka8PC!w*is+{ z03Bcl07w8I5<$-HGV50IBc9R^E8+mqBK1BGA`dYz39m3!ryAks3ID+zgzFKI0%9u!n&2OlfC1n$KIL;h>9aoV^FHSj1LOb$@UuVt z^FQ-*KLOM~pK?IyQ$P9hKdCMS475QJv_T9+0M64OQX#u0Q4Vx;M|reIee_3xG)RSX zNQtyajr2%~v=IiV5sPb+j!DYQWQR6zUF1T;bh9)M5l z(@zoAKoxaSB~(xy6+#;|QvGvM8#F|<5`?m#!v5hLW|Sq!;0DdWMcwpFdh;?fGXyxZ zI8~DwYXSw5(^V&8@s!ajSu-`SQZN-TQ~779<_1ksA^`-lRL{f%r~tS~feMBI0RKv% z9pXR=hJh|wHCI~`C590yxo{#D;51baE2lFNsTEh3&^kc~1K2?^!U5@swQkA)NB?2U zh!P#}K^kh)E{&5FS>ox?ku(dUIdRQaqmv~Cc3?e%9;pm|W}u_~VIMSPU9)K^rSn?> zkr<6}IR`>Cs*XA(7GOhDV;#gL4;FhIA-giuVITH03D#pfVgyDp>az79PEuu47F=%? zFkN$bU{hvzU>vfm>`WG$KoZ|16U|s65KE9R4Pq*lFkqLqV`=tgb0}vaW<jyMm!E zfA(bWH6lkM1Huqr2ZB%R}u9 zaUc%i8}OkU!fPU8@l&oKyLe$}<@Qs8*3EKm0VGZgNz*jh5icXwcK!Bm#}zWJKpeQ? zaG^jL;s6QG033orAUuE_c3}ygAQ;erAx?o6vH%G@p&v#!3;3ZFnt&Db0SZW0YS+aH z&aGkaZ*}9TbqP^$4dNk`AqWpq09eEikS}+|wPxW_bt4F5p~3^e;S8wZa0}uP@}W~s z_b#O1ACkZzh+!AZlNbi#8gSuz#S~l^fXe{Sd@BllL9pKf0Q?rw`2Va9cbnF1y>(-g zhj5?57h(Yb{?{NfK^+9*1J)rG9^e9G!5frKAgW=X0H7R5VIWw68|pN+WMYDk>k0tpGqDI#VDvAsuYgU5)rwE&v!v7Fe5@mNfVn1GAE(&Ecx8aJaZy7kP^t z*&qy7Nz%b`$yi{pAsR&D0*zn{*%lK#jD^_Nq*n}B5i&yY5@ZcZ#;h3w3AO9-n1FS(Buoe^2!9oDw z0qUWS0e}qP0V4;(hk;m#8=`cPq!hBNlxI1lYPlTMcOd+v7Hou28SiLsSBq`-k>|NO z8{-3@AfKTi8+^fgL*N>y0Rsra6VO3O6aXGNw+!H66AA(t99ST%A%eddd?m$K|KW$r z8L!US3p4KN5bu*TCM{wvox3=me_4bJR)3|Uh5wlwke~-(x^kERA8?@wp1>E};hILd z6=1ptU{0>2~weZCD>$g0LK)=12Q_ZHd-F5au|)_Cpdr*e5PATT6gW2FthrR zz8ET6xLw^fZ_=O|CU+XLKp=brNAF4?4gnnU!5c<*qW|~!Oa?%l6@wTAx~Vn#iGBH` z4FU{Fu_q7!EyUnCyV{Y3`L7w9tiJkDz!^e@;O`dJXZgCXQ5LYt_92h~o>{^GwkmA; z?`adeo)>#?dG%O+Q!#{LbS~Se{hG9$)&Mp`c3A>`1K|(W0Dt3=$N(2<=TW6SC9>lq z2LGWREcdlxJF^>G{eW*CmLUUhA^XUokCPEo+f%5(9#{>K$D5zZ`@LCj1?C}_apH;#hrQjKXn#8@Q5v<$ z^;RUnxc}i4@H@ZHH@2PonARC5s*NM+Zfj-r!2idQxAE?=>x8(2gACfENIq4o zd?Hv@RmQJ6VxT|>d}wQ&#a~vw7u-{-RxvUm!c~02nR~nQG7x)tBve4gm#e@H9KOM} zv`ss0=bKD&AiJ{Rr-PilDco*Fm;h>tquyGR|FX&YQgD&>JS;?hEvm&&%A*wY$Q1 zSJ2Po2f#rw_#vnaz0eSS!vV;@=RucI!kxb$n4sFpS5wtn9KIv@Q%Jlou;7)6VYWJ5 z&bPdz1$G$OSpYTS3r5}n-{^2R15C$O-2*CyjdD!DS-ZS3S=N+;s zI^RK_KBhe>!2J&B;N($0x4(j0Lonanq;pK7O3nrcrD8b@wx!AQD zZN|_sXpr6Kn~o1>Koy|)u8IDUgra04D6ui zFP@&!{Lc~Gq>+8ik-qJ1Y2<-o>Hocc?&-en+2HE4e(Jxc8SEbF!F~+dfDXw1=Yd(V z3qQ&eT+Mgf?HT_dlwRihKJq0W@26f3Mo|(ZpAG)L4cI{NeIA|7p4bmx(t+Nq*}n1H z{_&YU^I6~PDPQUvUKuz)@}V^BXW#S7zVr=0@wr^>6}-DqKltT+-=9M6TmSf_{`I3? zN^C*$3js?2-|2Cm@Oj_Zo7?({+>1|N`14)$k^lRjUiqJX>*b;A?cNQZKM)Eb@0))5 zL0|U~-}fn<;}_5rvf&-nVHoNa){mb1$J_e>f{nm|1PdBGh%jM6H*(w@v^B4pLW6At z1qxKiAwfEnYykKOG9&{z4F5u!Jc%-;%9S5SmShPtW=xkdYuY?X^QKOjId}S8+4JW| zApd}!7bs)Tj}Q0uy_@rI!ozDuj+x{i6wzKY zGk*>}y7cMP!IJiDTDA7JtP3KWXRGZR+JkQ6?x_1E@8Fw@n{^)+eth;ni8cv=UqZ?P z#Hv-l>fC<<4oF~u2LEz)U1!;C$6!L;4b;dy@~FYq8h!-g#~KRd_7{DZ$@dkAA$q8o zh+dhP5>fxG_)jV+;WCb72TDcNj5gkgV~#qWlptpdHV7m^4+;d4L~E__M<8NoxFLES zs@EBcTS+-3iNHZAoRv4(hhGT#oivL%M(ik4fMlMDW}0d$*5hVB1{vg#Z7fsQT3!qi z2q6?s#NlFCwx?xaRBAOSR)rcGsBuN9G{7w9D6ytWW=2YBrIua_Q=6B)31@>ty2eaw z3AItkMPrD{r;~nycBoaYx|*n1uSWIiaWA?r>TQ8|!?3ewb~hi>AaPi|iO8stVHcoM>7zN+qf@|D!4 zOeoTb7EPSeAld42%P~()b=4}Dg@DZM)61 zqB62vuGMzmP4&!y)x7mY-4$uj8e-g=(RO7c7WaE^W1G0Fiwm{3O|`DX$bSH*EYj-$Ek=L~POpinUx=*dU-nh4OS6+AKy6=wZ=3;g3`9Z9K zifY(-o{sv^9@pM)>?AWkBJ?0T|GZUD)2$ir+Haqx?_mKS{6aV@8=gRd>os=r(h|)o z^=wN&J^UuOFTcvSH*7ig`tL8G_h5k^zJb6+4e^*48%Twxjln5(Epgxbj#j^AYA&Am_`T+a*$7C zBUC2$#)QR@j*M)iO|-}rE(Xtp%9sZ-faW|#Er75pg8a(Ea zS$UbqJPPs0V`&nKv?F9En`ld+Oc9P5Jf$yx84^ftMUplnRg%7Aq~OgGl(1u_>}YvL zXmawFP}!v-dkM^Jno^irA?C5%;Drn2sgk2pCJPbgNp3mwnd{WaCZ8nAmyuGN^zKb`^P$`yFt0(QMU3K?WsDyP?WWC5AFnW;C)kUp+yQy1q3fG+;wx@GN z7f|mCS(xSZDSM?zA;if~rxJvZh9K_l^Mg!VFs!A@T>`UxaODnfgZgsW9eOYUN@>(@q_9Fa@rCbWw2;15exBq42ZEr&> z+PC`Fv{`lRaEl9Gh8@=@dsS|dFa*oCkgyHXH78Wjxn0HS)`szwZ#<*+-SFzyT;tt| zQI(4)C3(TQ2O-~()(X%1Y74lIn{O0v=u_|3b-xr2R)2Le(KQ%+-B(l-0oyj}Ap{5| zh2ER=rU4ZYQ9*hYRGOf4sR}3^)X+l@Rge~{RO!71q<2Iq(u;I32vVeE=Uwmj{rf-I zYtKn?kh57cYbMWg-9 zymFO<2Cf^OoZ;u684=*GmFrcy961`t46;qS94aH=+dl+=6I_4XXT?~C5Hdg5&N^s}63=|XjhW%Mp= zKrZRC3FI+}WauLqv_HuCMxct^hB>KeU%{kCWr)DKO=R=UPxrOT76ZR4D*HKsZ!I~N zO01}C82*SaIH_nBPjI0Sn_JzNF_e~s`CE`ui;2i+y}xA`DO&5oA4Oem8*b~zti5uO z>m6}K^ZNd|->Qj*@_pno_<4;rg{b7IW>tb~3e&@%89AP{vovl#Mqb}27o_WhBzEJi z{TJCb8b-4NqfPwtfDL5G2*GYo@XmC0dGJK(@O^Q9Z*!CN*wC8cMt_eR8>~YSlHCt% zNKouUAdVB^UU79GUQC;4Twr<_6r@5Nm%ei3L;88!0%Bj|0t7Cu8W*kq0PmMb_}h4T z#viN({rY48jdE#O<%Xa2X=NTD6hluf7DUWf<#&#|y@GyIe-c9nv0H=%B3DqsH&J{n z+y}s2&q^YWLdq#XNh0_DAXs@?iJrS3^gweQY`AHCCw}{EG4@6R_XQs{j}Mu&_O*cP zx0ks!El_{UV=s4|KAg|}zJIKPlr@U@aItoy{cJS$y^&@PY}by!x#k*nJow@2sJ#91 z*M~5TP24#PhLpSoPC$_eqh_W)5M)pkXwNhvUZrQE{<+y_*Pcv_r=H@6$Kp@QyRnEzcCx`AGQ zud&V$WpvVLblXG3{u|zS)!@4fIR98Ap)r8kWfqE zP;2#2Tl-Kubf`mNs8b*D3njZSQyY=*1OkQPD7W#n+!e4QJiyFDy`UG^hNR(fBPZyQ z0(!7KfUXn=y<_h$4+$5f^$t3rCDtH(Q+vl!7*1mW3grQ3K_aq+BXZRv^3@~mV@Zn& z2@yr7q;K$~C6LHU;mB&)$eRF)xgneZ9oaaIYVM1q*^F%WMs)~Bk*Y`06b6{tF@=vo z=@r6wA#}0|urh#74*|OzgD)b%+`Q06fKC?=*8zZk7zj@#<(4bmco?^`n{(V|j1aB6 zk{wLd%T4|BtC>2V^m>asy^IDF#BTE_OA_!F-gA_Nju!wBj$+>}5#3Z6U$ZXAQjyLxBV$Np=GKTV09_k2r1kFf}#AmHFK zXYeZ=oDu-IEui0)qPPPnxAcf-2>7cP6R3_3MWZ85X`@nNo_EIZXb_UbD=F77a8e`J z!Gid|lSwD*@t=F*Ur=JO2PAr^WIYVDt%8Hs75W`T!n;hli3GT_0X!BWJ`KAuP9+5a zZb9fKQ9<1saRv@4fBRxDPpt{E$@Cvn=xp4Cvt7dU!(R78)v;pta0%Kdc*7X@(GvAO zo)l03Z7xwa8o^sA0Fw%MJ`P-j^p7!43DZb>^ff7ZE2Y82%{(>Dk~Lw0JS;#z%vK@T zES3BR&T|4E1R%WL8hP=!L6$J^g$l1KleDQ+m-?+V2XCZxe#e+MTo`%J|LjS7&EFyCO=r zjIcKxuq90CA9I30O+nyiR`WjC^O?-cRK}}5d+cW=I;tE7DjSwh*tq^Iwolni+t`~L z*GZ^y;)HVy!*T>7uoXF2M&DSds0xgpeO46Bv!hCG%F9ozD)13~?e{GI9aUk_r`%Z4WFz0t zh-aDTe{Yp4{1vc8X#+(W|Fu|u7Ad1Bm3jVavC0+a7yrj%EpaR^7cD8%EUuI*sb?#$ zjVNiRDsCDmX)i8nqbh9|Ep71)oIRD|*JF6zSvtI3I!aYGE?PFBS@y%RY$~E`rnqc& zpo~~px=2OzSHG-2D@%_f>kj|2Rs3aV;LG0jm*4-F#d;D^epXz5K2T1CSP7rL81a|@ zS`}nY6%>&blqD6^gB28mtTK4`BV=j2+&dj)B?Eg5b8`t}NhNz)CFk7|4(cl2^Gd#* z;%iP-LZ($Ma$qC9z#C5h1qINWW?7tKwM=uFbY%5izcRVO>Idv)_o-`?W=kLXm8H8C zK8mZ+G%Yf%ta*4)bDx$_`*^nInPlx^zE>~_7CTfMhwJvOf1a=c!9w$8A*9(B(8A(AfCi4L9C5Ohu- z;fIMz(}@vl2oU3pPh(8>Ys8#0(qX8~zpKb|qmTs_^*g_IBFsFC0)6j9zbYA12`-p>{ zVqro3>2K7$f=RyO#oBL`c5p;}<(2Q`&h~WP@N^aG8Wmwu5&x?0{FPS{7$3uNOM<&B z;6x1a1~ni$)Or1)bD#aIT2zOIGo9&N_Y;6--4(vLM9FK}BXPm%QbFzD3U-INgnE2cS@Ph5UBy4L%?*vw%FO0rHm!us0P9 zD~Lo(+JRi{aDEO!f4GNrMC2E`1g{!LVviDX|6^k$}i4Uzh5A~G}iBAuWats4Yz7;}#H59;Mx?l6j@F$Luui7IQLw($e zRA$=Ylw;6u3S=%=*mv*YnU>*s4wh5#k*=1}bq+fE`R)`XwT&w{#sZ#(r=2bxp4%PH z(WhF$vK&AFWwqFJMb_jFR?gFawGx){C2p)DO*25(iKqTJ-c5=kz(zGdr>MAqxIu># zc%LIv;|1}of>)OYj}pIY&41TIR4RRjrMl8R!NWhc41L!_PhLG!NmQG3&NtrHGV zx~CSfdt==$V{qaAz~A`5x6h}%qNg;=rfi32$d+cfNq*);xAO*2PXIyg_kv0}*~%;i zgC)a*je^qSIJ)Xt-`Hc)mZ6mhn(YcGs+ILK61IGoYzy--dc0c=4}S{KedloxcKgBY zMt-Hxcvo?N3<>q3nG{x;pNyUdFoCb3L{XYraG9i%hX9-00dFF~T@J%PfanxFY|(6f zh;{K0N_QN+`0p|>3APdX!m&?T7P?ja=8vuAdL^TW0sp8=V004r~fw{i1XD%UMEK2FFO5a}q@YJOz ztE4ZMvg5$NdFEd(2Msd^r*&|vwXzOvMtL-_{=c=TI94(|)l~)jYHT86ynCY<_kofo zOmcx91J#jOICY}>ruT90QqOT@{q+Lf8bEU!59H(F-z;MAc;b~ZNr!{R==BI)&@PQl zxZ>e0bWDK@>qmV+Xv}8B2w{_TYZG%tTY!ZxV#rN+po{oGhBMkF;TWsst>71`IhmW0 z3!AaJi<9W+pMB8_vO7#OTTWM7A@4VvUu-vGskz6yoAkDCUcp@eAO%MEX=JPS{wDUz zPTmzQ5m2q4_dC~{n7*R@^qQ$0^F@aScz}S7zGpFl1!s`(i5D}HnqVy6v;MPy@<>uo z;aI~hVBtJuF*un0m-$5D4Ugv=elJ+Mu+WX@g+ybrO)L(zuLpL)L(1_66;NqbC?A}T z9}7N8gN{I`;qax8nOkYsnK(Y+DG9VZH~#PwXa!^cjCfNK^d|0%!574L0EL}FWBg6R z0q-cB@As_SBLa;G9H804AVlH-<=r&=%_H`y=pU%7AC+}QZ9{{j6y~Hrdxg_JcXj(z*PS)E# z2^W}zyFRRIJio=gVd<7IXd+sFy9t-k{Jes zG_3TLp8?2o0hjZJ4|L6h3+0&$jntJNS<4n~7eBKu=3|4ZaQ`ri@b3U{r)~A#{fmbt zgp27L=R55ez|vJL96|V}PpUVj(PT(QZJ3acn7A84E1;WaJZ{y^y@V2Im>$nnbFQXh zLfUPwY9vxo49R`w|23G%jU5V(A7*Aqxg&8^T!2izouMdHHIX;QAe*g0SQe25o)-o3 z;srE6y)Al3{mM+&s0^PoL>QR9@oVaZ~K0X_vQb9I0Hso9UzJAOY&nScwV z6nb#RmtMntuj_4j3M4CEu<_>sj|=U`yHYEDX7(TApMCwuSiXBVNm;*j@=q?B`Rx)< zC&J?kJpzCiVpq5y7qWm*kAH?MMOb#F^0bq4N4Y}C(UNvlXIzElN)UlWdydCU?g!mp zAph}M;UcS$J3Yk9jZeGC3N4Pd6p{@YIJFB6j4Iq-^AT_M~L}x!Q zuW~@9GJUfI+!XgR;?{Q!2q2K^PB(DdE{_fnTh7}Q6aIdna{r6)^QwM=kY(a#{D)^A zj6FJi{S@rtPswlwM!&0W=bU?z0Wq)fXM*(R4=^F=ew_~8U1ZT+Nz4E-CCKTYCn@&8 z?)k3}h?%KGZkw}di1an4cehXG&`~OeCNJ+vs&T(Dwmc5A|2E#6ZvG{@Po1Ay)H=<- zbG-JxN5bB80Hs=MS-E{9xe|HeXKf)?8Vq>kWNXeNqC!P{;V4c=567go9ydY zTvGSXv9x;9*Xc|1@js`EuS|ZP zJ3l^m!I3iiyLM8`T)1}88~MBSuzOv&_3?f5e={IffAMDM=9K^2k-H}sZ^x9F-?@L& zlF2wI*EM?QF=^^``4|0oMlgp99dzkA_jc-?SC{R^rPopr^LuY|YNSfKU&9^cY}w8Z zJ2tHt@jishAJ(u{wDIs?!-9r;d7u2MOjaVCm%iD`!n@Pe-pfRnZ?Y?N z{(ab|SygnBYX3x!NEx*nlpU_UAu;w=l0Ryss^6XpcCrbwHGoiDr^-RUB??5L7GVNw zCyIzrz2Kw-g?rD4JL(rXvQ!QsNAG!wK5-{I{XxbO1RshAXq1qt)< zThT^)ceUPI=EhrGlRpZ80yNgd0eYtN<7~v8%^<$Yv%6>@hJssylXGNv3A5$<#@)*LY46E6+AL|f$ez|D6IxkqAVPC4WAOc z)u$hykY^)cenjFgYjv%BDfFT7@juMc(SQ7@mSi^`e3DtSTF!t0wgSPXkif7QyhsK#G&tft<<|?d>36FDxB%ZwRRF!-G^oPj6|2HbB1~7pC z{Vytcb#+C!ytur)yt+95Kb+*{zyBOWOY;2e;+*(#dVY0wM06#Iq9l=)yg2zESMvDe zVQdl|25BD|xziaJBpWa&7HuxpDshPc$PpfA8 z+FJjywK=o6J+*Q+)i6IZH#0LcH8n-VBL^qHZBDGOe*5)nbZvQPZE0*}X>fI6V0p1` z<#e?B??CnL*x-3*=T7JNaeXsk#N)Kr_pHP2wDIX>?XB#p24UKiRwKY{$RfiP;L`rg{q;s%f ztgmo{h)PxzloLuH6N;dO0BtnwMrq9mx z^v4XGGEE9E6z^V2BG(lkt|KL{1O&GPgbq2m&)L|BVB{1B=OrUUs(xOIZZ66slxRypb(_>K)Ob?pf*TS z4?RspB}cOqf~Yt(YYNBz7nPj&te2~qp;;^XltB_QJ;(NTsJ-0cYXqlOUFl4LG(5nAJL?sWm^Y4b15K+m?o@uTB3zf94k_2fL9E=WWVs6X-Xoxboxe=Qx z^I@IE*S+^!flQ8WhTCnY$S(%I`MiyFd$Yn<-4z4P^}iQ!LDby3Ee&pYLHct{7v(*F z+NlAAH0?KNm z47$^6?t4ay&I&l@O~HCxkYFv|!AF>REp~3(FDqOy*WMBO$(V`QzyK`VX-dz-7V3gjYrvDem_Ey9u8YO9`FkEikyG?-X^ z1w6T4IPW3NRTD^UmUA%5s&r*wlVX$Xu%2rF?biA`H70j}jEG8Zq`OZ#2xah8kaTAJ z2bIk5*>~6=Il9-Fo*icBkRO8nIcfjUMD!N5EGX~J#HZw!#ajjG(rAZw#A0O>wMwGn zc2QwL@pf^sBX1~EX%9hkr?jMrO04Ai(@!}$A;dk|B*}lG*%i&8l7$BN z&y??|_G-QxI+f{s8(|g&@{093vX%k|NvJu3o%S1DV@zLXFc#_sQw!1gE#%gYi>0;( zESqLj4nmnGMIo0RaGEKrY3mM%P^oL}OcV1qiAtd>H;J(Q51wu&zP0PwhXb?M+Mfpc zXSJPQ6M6G0NT7M5ib8`lx)XXs{BY>j2bM#h?8kb_Wb{VPyggI~dSJ5dPeX;h+}!W} zlrO0GBA}NoB!?Zh|AR_qK8`jYQ94OKc&{LocXOQc#=X)RJF&9kNPEJs8pV>7!^fR6 z)~`@QfHNwK*pcwoyqhY0^?z#7l&dtm*HUbT8<7D#2m*)MH8`pV&BEqX-agZXW z#4DRRxN`$+sV(=gBTP-oXyQq1&C%3o%B9B-QvC6c*5B8!PRYVP?EW4fRm0);1+p-Q z`S69>?NYJEdnYGKTfW~?2V?5b)~K<-O)}i9{mA`(h?bB%1xgo}3tcGem6F9#y5WMD zI3g9q2NdDXs4bo%*)VzM1FCV7B_9A!Dzlp%VoLylh)VKM(%SOVsc(ZUP=ay?;d)Uy3~4N=U@Q-N-6kFB-8i^Ia0l_dt4FG4 zjNJc1k*BU9l-1oL!fzAD^PwS32#uriNx}PE9}5$4#F0JTeaSk$L?B3wJ(Eff^C93vdA|NNgUE1Ssb+ z0oV>4xfHaIag9xm4kEp8+=RRck_J%RN9!MzR0Y4KM9x|6P9Hv))Blq?b`d8alBm2i zd?NunR3NQ%M{_0VP2>?vpJl|-1}=>Uq9Q2AtD z0x@Gj6H>@0c+7T|zVFr>DkColyupw{c%Smdmj1kzt1%w&!Y*e>aq%KWwmZf*F=Bpg zj%k@!mp-$?9mE$1Gb|?cu1q8YQta;irUXb*EE(t2dzm4C-b1RIu>Pkn^^{&B%!r{9 z?H%r$L7Uonb}LPIvs9tZ&WlxBMYQ?)-g~o7&x3W03U$S?M*7Ghwxx4M3-RA0Mj#_!VtVT#TQ0 zE(4=!z^%0dfvh&hLOK3o=eN|T=MC1()z8=00?%jv$tAT(v3~K>{m6Yq*Huea=F|q3 zw+JMk#!+%YDF0}NoQit1>C~173(?SD^eDIQ9sFMJI-X#=mhy$0yz=1>F@#csH7BL3 zt2yrlH&yd#H$^2<8|lvlo$c+JlrImPN|Wa5-O*$}4Y}(|JIlDC(}UEN`hBgm%n>9j zFRNNQDqCu;TwwHtx6Uc~_pfVW6<;}_hLx`aPK^Y`&V~Y2r1H||mT4Z{A-KAD?(ATE zh(D16!e!k^cKyZMt#pR%VMkfRb6ji*LIc~8Zxu=|e#%9rjzruFK+Xj`y?+up6!f|h zD+4u9;O-jJGj#u;a=9oi^DHjrWw~A@-d4oIq>Wv(`vLkhh#1x8TEmhZj=4g8QdSw? zlH!<4-QaK119{#Pm*^VeOgicQ-4{qvPPwD=>ZZ?69_%qJ=R|9p_0vDx{mh$r(OUsZ z4Y@3&-hYE`-wJhg4)Qj&S7mocg}SsnnLafRfsKqs8$*=A>w2L?9Tct)>7uzns?Zw8 z#Y)JUPB7(k@@wktMI>zfB^=mO8cQVWh!L?7Ef z5;SQSj*S3-fjrB|0DBS>pf7Bj>|w-PoR0Vh7d?tX*FU)P_ew#`>dRSgPqREs!xwe& zeIaaT&lP#76AHkGy=I=$8LQNwt&8?b+Gw%VYg`xDFhc2QpYPPy7ssSUt%|2@^z9Qu zWPW2x+N#JX%Uee$ryGy(t-b3#VL|~Gab_lDige0~Ou>qvY(ORm>Y&>uJw$_}bE1!1|*ocAf*A9_Jm!h+Pi zxSt|v+A4w+Wzox$!Iwe^k};Bq26WUkI)-qHjt~wlP|`FG(F9d$mVtqC2CZs-M6C^C z7E1+MM#;p5^s9N8gmD%XMwl8}MCFi&>Cx=-yqlm1WY6(@)d!X67T~a^GQ*M;W8nT+ zd6Lg$9~9u^6u?WYnsNmd^u+a;7UYWnAtgz0NE$0O^iOrJ&_aEi36gz8%!+KxnsLlJ zOH4xuqWeVWGlQmv2*)Oj zOE#1|*a4d3nZd^dl7iwb;L~HyAW7#FJy@?aqCXTqWN7)Wfg=zJ`9nef5lPcpA1$uI zIS;{rNMbf*6K;ja@OH5CYntq%nl052NkC&5nVr z_fTtvEB_GE=ks9?Ktci$^pBA=I3$S#YjXWTym~kqkZ#fGrHJ<(rw>J{~*3TD8*z( zZ|i=nan$X{a;y&$3`{Z?N z?}wnb&`53DVooj!(KRyb6+pqhr-GKv#sr>!w?zoM!b^icsrjUqr3Ta#Ii6Go> zN*`41kO}g=^Uud&+sB$g*mgoB-Ao!&Dr+@0!^Mx)SQbwG;=qo+b5rYcn&d%PD-z4& zi0GL4sQVEcUWeuXi7llx67%IWaE0uXnZK|%UQEqe_Tf@p%97Lv{k6;HrOM$e{uFAL zGZ&ika695=#0!mo9PAbpVLUc}9kO0O$qhHb9*qa-|H~z1%iAg9_V>wqRv)p*TVTD7 zg%@+*h@jXXgWYFKVbRQIbIh;fCE=8#X~lX!bIdf0z)lolsXDOgqWSx*S^N4xWjN*j z67|bx1r>xzZ5dxK5gtge!e`=B(^N{dPx0qB5z1`cH~k&`Cq!;pXkr2#G0fXs>}ZOX zC0JucA;qs^R?(Y5^+2#iykuOwSZYzbLn?w#GRs$zp+PbzB7^py^%*T-;tDacFpXX+ zUQsNl^t~JF%Voj}F{4DkD=rDPPo1NaTnxOv#3r;&_hrpjXm#NFKIq0*Dxdsk8Hbet zo(hyoss*D|C9a|+X>2U2NJz+13Y9+a6bbtIEOSmywB}6(#1vc?UqLfiK^-aPJ&>~} zT1nr`Vc|`tr&(@nSAJ@eKjCZ7Ay+{Lznb0JOO9|qMSiJ!|zq}mHtATpO&H5mxI;)*8sU?le zmO!Ng=uvZhWEvuRw$jb9mN_s#@ovr8c1C+bO>ku6N2gK=QPzYo3QD8{RJsYG-y}cC zjjvBbE@vw?H?`X}R%$hC`8qN-TOS3KhUt-^n_(9H%@oVcYLiXz*%Uzv5Nd!vnGg}( za~Itw)?9tJZZoZ|z?TdE56DhSzavIJy;BIiMiOFCB7BFYMz-zDsBK`j#gH5~MBV&7 zuGByesA73J>4Z2Od|Ieg7GzO|h z)4GJUxtOT|^fL#^-BR}1LfFO4THkni`Bb%{!Wj5_9)vO?2;tGi-_j*`QNLc& z6R%j!k0kN=<%rknmUHU1_58XPm-K*|emptGG~Hdz-P1u$-cty%it+Lz^wO)~;c{32 z!_glv-=ApKpX}csKSbh!BT1R-&%Ed-&Qr1S19|fOpN9JL(+9Hr2a4wgGKL1ea118W z3|7$$Xh)J!Ep>JxN#e8zYdHqnE(YVxNMp2QewwmJia-`i5TG&YuNEBvX0IOR`J}7K zr=j5BIB1v;7+H}YSu-11_aE6zA0dj3yK^J^7bAF%(LeH|M`okP{-dWH zBaT2)B%Zu=3D$}k1>GB4-=*x1LY^BTyr}7Yn(N1-+{qY7r#`-$j2b4*9^UEgixD5H z;uzw{7~r}b&*S)Zt#u&B>|3$+H{r_xq1JEl&J9#Z&|8jyLc;DhZ0WaJ?V;Q9^_Fyv z3Fl*hh6>lz11~HBFI@WoOrM>6r`=$eW<;0MP*3f6o)b0DBpyy}hJdE`a{K|^K+rcV z1t~mtBeMy$FAOzB^jOmXwsXwa%$iBWaRWkAZ=W}WVaN=EsrNA@PiUsjJjQ;#9jenW zlZ>n9mYe)8t&?Fyy^8Fb((BUNn~JG#Nzj=B`EX^L{@}#hrabG7f7NyOvVpC$HF)gv zk=+OMutP*^2d6fC82iOVXC?{yLuc;0{yX;iX1nWVKF=h+x;9tOl=N=Uf=;x^CEciT zz;IE9&DGBL5wY2imowvgoTP{}Lmq^0YddM&4{+s=R6-AL@Lq3g<6OYxT>V~8t;CNJ z&Z#Mq@|-mib0+Lu>-?>Y=G@`(LG1+=@#!ZaJ#}SWo0oIRdmq1(v>Nar5|&_dGqaxJ z?SDDvI3AXqQqzO*6aVg6u0xkzwJh)4!#QxU;G0N5%P)TFEJE*p#p$#!adzDONp0@4 zJT$y$S}DPO)n0S?T_$FA&~gc+53)F!INY1rDOh2@M(Wx8u?;_jgjus@E^NPBkbbes z$wklJ*9p0L(YiAmb-twhLJ-=zc4Kl)?rKq&nE%RLy=93btt>YAIsZ(z$?Sc%T|DVu zp$dzbWhvcU?RTBlBOALCzx4K*4faVuain!*eKdsY^G-}Zd&K9?YbgTpKak5q1MfB* zk~bdIY&`n1tiQkUL3jPuK^N$tMmhPH(ABJWy4wI2c8r5sp~g~Pu=7UNf7RPgeqnC) zejPQk6>$HT$18R*?M(m)G*NGSZu=#&pT2^jv9=&}!e~y#k5MjH-~E|eAG1@ruYR?+ z#Rc2W8riFU#hwEL(55u2!#J1M#83#L9PpC9;1wCm3Xvf5^W4KF?R_ZQ5*XTP9r=Cr zV*NcyFR2@KV(4x}3_>JVoNOFgRY9|bh4!;d$K2-@5a~FMdD(cimj=UU!1mj(vs$3Z zNXJRuI^)OQ^$;E-PF&&T2=W{Y_!0jB58>fYj<*Mz$p`cM2NTijZ0*0Lc=4dh*{zqm z6ae-CmE_zo+jlXBSSI+D^R7&&*utwbRJJaZ6H;e?nc34DOKs!%)dp zP#(E{dgLO~@a)X?VnK`oESu-^&(bOVqe|z3|S|HzNKRVkO6%ZaZq$Ad5D zvrbA(jt?IZa4sNlKq2h;sXSpSYUKETP)R74a*Cd%A}El2&je!et-_R6;zd`A{;FyW z=e_q}*2in=@dAtyr$U`;JuC#r(zU{+Xi$oz-Q=8bf}n1coX^XnvqP&fj1kP1ciJ-J zt_V{&mBHzEn?V-6vUug9KgGTGg1{=`%aQS@GTY%yl{CY>XMo96oqxZfolmWi zCxWJc&rRQkw|!tm(f#*O*CwwrbIjAT`&^q$ZyvG+k@usGE&dSatoJ^^MD9qKwMCVG zs*8A5xcwu7x%t?hL5tAwd|wzE@=8WVqZd0GalD7faark(=B9vNh&wbkk5*k#a(+JA z8u`0_0Wn5)(Cy77;i8{Qcto|vQ5#$}mhgaRDb-0nytwlJ_m{8W#^6Qm>A~b+yg4Nf zxSZ9*1=tXqkG(v%!g1d@j{4-!wL8nJ8K^|oLeSS)U&d2D084hQJ@y^U|HczMfQx_1 z5#G(D?;PD8UBm8-C3)`_7C~<74^vIPD$?wV6Wxu9LWt*Bv6%m)uhJ08QjS%wJ=%%w zSAJNw~!$2BOiWE+C6g2Th$j8+kYRq_cD4zg#bwt-{^2 ze50SIpd_VtmySTy+0Chq`u7%h|AA)p$a$W842q9=1y83T^XuuiyCDNl>eaY8Zg;Ed zurcI4eISJx3edFZ%@AUdxZU)GFQR55=zfMa{2?e@J;D-|s$gUtOBQF8`LOj*rNKSl z$%1FEGA0L~Xh3%L0tMZ|n4@!sw za~hMicn#S##48HAgdrC-L5B4pCRM}LTF?PisZd{MgI(5eRU^NDqxg(IhW^VR`xp>c z3RYQ6wZZxpA>ioFW{oJj^4F~Tbzg}RHMXClIr>Q^KdQ3tvF}wHUC`SmQE!iAaCAOT zTPq6cI(4cEZWa#sLLisFr8!P@UQ=@y^zn7x-_qIrXi!@x&+AqLvu(ekeUsnSlacBu zE&uQvuH$N1PfNyS*S*~I4P25vLbPSqU~nqY)1{B>v8*SllB0gEt1lqRE9lo-828oK z8|sHWdXIj3w1o`i+3TPG33`(Jpgw)u~D#A1AU@;BOi1{d2Q zo-Vdlo%<3&_on9T$Zz9*pul7fjxrr<|QIc4VIbQ=T+~XP2LyM)!l4Bmm=B zC;KrEg@hgwBdJZwg~#+TlUI>D_wjKKqp5)rEYu&BOHa+aWZ+6(8Uh()eot@7B9W{T z%`*11=_WgyiAVb^FD8JA6-5foN#q#U3whYgW8Q;^d9~|GJ!~HY8^cH2Le@yP)yZjV zDrnx0b&;QVhrl}ZpsyfZ^ zAUmmv>MePPrbBVSs`E)7zaVYX)8vFFHbd%SMSnF-dZf&&<<&{>u4oD-exL<8&E})g zF}M{g(T^bmLLCtLc}hGy>b;^odI2Wxq^Z)lFd-N!&{kcEXOc${kf((QDJy`vUs1}8 zR;#>Cu5m1>iI6L+ee}Nb(C4;$zDlVpM4ko5BO#W+IV+PSUrdIW!=e;!ieea}f*46> zK(hbF;VxqqJa)1a53byzc|l9;MJy2ZEB%1L(iLv=%VPC7Yp_Q?F3&EXS#Hp})3fO? z|L!|JGq@FSm*X0QLgRbR5#%Plx^K`&zWpp0JdCfac%J!s6ci|N zri5~x2?WRS@r`Ci)pX#$=YtBAgHX-}T<=$b&U=pfU~GF#DT$gY+J$aR=MS+s33^ z+bOCZWFW|^AwJGgp3Wyl_A27Ob+QyZqzQB@?UsP+U@TXhu@;MpRF>qBL{IthzpfhZ z72&SdA@_f-rJ5Riy=g(4JO!a{?CSMRH=pbFeOyknk}UTgsux7h8mh8*G4Opp$@fry zT_|R}8k|S1@s0U;>uwb5KcOl?cC7=WEsv_ySH?M+e_?MP&B|V%KD*~o6i2W5(A$`o z60dTjXVBS`ba-Y^?!dIY%)yBe8NGWCeeu%kiC2a7JT|kwknr^~`$^DEUczgy&a%h5 z^ZIO4qII{s1YS4=*feJzJxOfM=d9gtGR{29#bYr6sT_ z!y}EA3xTKz@ca$~n{RLA`=g`@v(}UK1~a>76G6BLk;ib^A8MDa6(3aL;pAH0AFe#w zW{dXaIh((c#k%Lh+jap=`E%N9O5`2$yN#UQpI!A^+Kk%x1ce|2x4*pceRQwD%fIsa zvh=F`)ZIyg&&>^6xtqZjGk?lYnzs)aet%`o#M}ICp>hZ&Ajl4`^~5}Cs?c{4ANmR= zrfT{i3%3-fWfliMQ(x@4nXmT-u{vmeEmJ&VVSzn`DRts<_A^3Rm2Jve&u0I+zVsCf6LWb17$1u`(oxjFNW zXsBFO`&L48A2scpoAtr!C^sq`?AFKjueqBg_oy!9PsLi_73IIvy7^PCqd^S2%qNXF zqM;NHEdFN}%xiy;bHIMS%zbDnzv$EjbhDN@& z2Q_d!UAdC7vW^)SmsuCTvxJ&>cg&re|3o2ho_qINI;p_zZ??z=4!g>=l=YpJpSY{2 zig$=E-}<*oHeTH(TY5)3N|93@PB}&zq=XLN40-0Pq*udZw%ct~s`_|NWgeAL@6c>G zr24hFQhE)9(bP=Af=^X*t>t@4(6$ebWjlHIt=jY87Gw8#h60cchzI_`jh|l#jC3XLr_1*#1eKjmT#&)P*y#&?+j)M&=6+I9qPm8$vOI~qn~P4 zul1KfQp8a}a9?KYxuWw>@5Pe@J*(Id1j?jEy<$!(PkGRfUma}Z{QgDjOg0s#aU!9qwVcMr7`ZW=l z^hnc9Cd;VdUo^dm{_zUJ;NO}MJ9%AoE!}lz-5%|Mg^Td91S&~4^&S34@=cn3>GW?d zuD`t)X=4~9wpdlK4UKS&Zm)%Z_KzUJ2`Sk;A}DKof11F&+52a9@SnU`2`|}e422Jl zTp9tP!jgHUguS!~kRE(==st4w{n02*xVb;oYZHowIqjd~s!Qp8ikt1heI%3aW3<(u zq%BA}SwMz;6cPaH84txR1gUcaIsAEVtK4Ih(?BeS`xP(M{E!e6+0cdCxZoDmLjcFt zt?lrX;*mmtKb|yzC-B2q^~Cv@$SZAvzt%)ea|AC3BnPAWqM;ulF~-~_Sq>6&nNE~q zh{)yuOEsX)Cmz>)OD6@u{$n5_Syc=|xgp8u?@ll#J-#*nsH28TqD3G8647Z-p+>Kd zxTh0jO!gWt$!r{Oul3RB^g!KLGF$ei52GJmPoa2^qM)7!`}3fky+eYQ#A$^CUp_`z zFiu(uOj_NZv{sq4{DqQPLfLps+JzX}+D_W%PdW-r+P*S$`eA6_J^AXdq21o3%U?ry zVF?dr@+Bt;M-(cVTur~mOt*huGjUSZR;6WPW1W=Yk1(}NNQ?*|| zV*eOeBu#l{Onwge>74Y_C3>p3cCw`Vr{j;GWdf70_ye454Mp%UQT#K4Ve2+YO;^07(|7@g02~3+#Bd#OEBH&>PSv0Lz5bFC`V{QO)Q0Zs8}j2Pty?jeE|wb3nLV;t0s)t~HUA<1=bvJabi z&sZpUTSKpfd?)gwx1q5FFMi5dn?9L$q^xx0j5cO+NBtkXXJaE~gU5c1l_i9FqX$~d zelYTuRFb*j!rW6rbwL1)0fnzUIsf21uIBsdZJcI}a(2bnAU%|(D+T4+d>5w9@^0Q^ z)Ph{xXwbyn9hH21=|okR+1lmzSY(7aRyTl%-lY$mMWee+QjBGT*pQ?S>S0gH=-xIZ={eLhE`YrY7jtk+iw#Eh6DzW?zzySRzA6{heP4zqPFxG19^ zBSscM7IM%fS_uoy5K0R7!SpEl!{Irt(#OIkvErAOIh@P25l^qgS6G==B#0~PuDq+9 zXb$5DGrh$HTPuR3|D&h#rvDlcPl4|t!X$2=tVpO<=snHExvcaq(HMC&829;kN)Rzm zJO8}B_vxyxLx^<+xaTwjl_gWJfGUqn07syZ$2*lUkC zmbN)I?L(G+-1lDzVS()gZ#tdW^7*}Y&=3i+RtSykBPo3CMB}@o$G_$<__BF_E0V{k zn-2{bZ)WU9RtoO)GVNC1Pi7z6xQ54)Ki`c_bCis7!oaphLhWTa!fR{P!u70hFC3=6 zY@-dg2|7iave<=*E7pwbo3V9{cQbeVwNjsx0-`LA!KY5M$IjIS^w9g%PbP!Kotm%6 zUV{bFHIBFX7q;+BE*~;J2N$f9Uq^39L;eb)lNZ*vboWMFQI^L6XyK8)_5EM?{ewv> z{JzWT0z_K?0>{NY=h^tX?p)dSsvYLMl}W#SpIQgAwb=7pGU9jF^Su>veACOlK56tk zI~rUVZ4Rs+=@OAq*NxZsllOS)ji~#w?B3=k%?B@!wJ##zLYoj5QS3ScMbJ#5M@b0Ji0;6H@4C4F=*+nYSpXB`T5X6?QiOZTMIdg zM4jQ$mqWEtcPHj>MkLwmF$()lQkze3mmAcSC$B;_fj#Myjs>bGQ3I9E4EC0Jl6Mi2R>OUR&*y1T?Usx0%XvroTfE2WOT)<-~XeSDK z2dN3HKnC;)rrltc4qN@v;@6_)6=v?6zc}x_fVyYCf8XWOBkP?=i$?&Of?%p(7ElO` zbVE>drNs1CkY-_sqp*z}nF}(+6+vOD7Z5p6xcd#+utB3BOKxPp5M1$R!t2fUjWx~_ zzsd5;RZsUwBvqaDYn9Z!JfpvzpDkk{KA6)YESqqkaB(gjI`3I=0Ui2T1BEjHxoKCU zLkcXJiUtAG7bVy+3otF6^#%O_{#s8Io6MWt&4blmcyG+#E!qAlevGJ5mGjmgfuR&B zyKkiq)dlDXndgs7D-ZJnWvJeR7&X7!j%BME2|gdFa?qj+gQWrr`5Dcoq!tf7sH#f- z9{{yLO25~RV0TiCL9-u=hbsE9jB)OZ!D_P}ioh04X$5S_#*A6U&7rM-Lk$0h`A6hn zLW2w)K3w(h@nef&C(~?otX0Pj1t@dw?D;e3&^B{Q7Tr_y!?B`Ohi3iR^=qRn3uHNT z1;8Y%n6`42joKjW&cS7trRguNLKyZ~^7+T_`9FXB4gdggZ5joIp3V_42!S3T0IT#V ztnhCQ0Bds%dWwfJ;zXUl=PPV8G6nto`uFqi&yw_Sr_DDUX9QAaU|0wy=$lGa9Ad`? zl(^&0ZZaw8)rCuCxKeR3l~PJSseD+9Db8ra5(rzUxJ5R~Yym)B)o}1oDdq@Z5CZdT z0>B#o=wQ$nf&uUfHwq~e4Mza_2O0v#9OH>c0*tUEl~r1KWlTz%_K*Kh12Tx(hDU|@ z)0kv_=@AKc91;X36H*euOl9sQr%iNn)FDjagyRo6dWPeTG-Jdh7mV0&qk{{HQb)u+ zwG^R+GVr(n00G)m6NVVrNMn!<^uR&{Dg2qntW}l@nt;FA zS<|gFbvh`?Rr)#n9d3(aDfC*wkxm9 zeq_QSi3sD)I#kqY@WB*gXmLx>@;jP*8`mU&CdZ`FQ7^+t>@ok!DXZ*}mS!OE5CUd| z1@LMZJB4seI2WaGz&vxbfgOjixA zQ&UjBSC8#c3nP)i5f#JqvN+|Ho2sQhD?BuWJTr5tG~a!@9eUn=FAI_z>ljN3Z>5iJ z`oORg_m5eYucWx`8M$(dDjbbq@07UY{)GvOea_UB&8Uhwn>l0I?u z6;I#6C0G?B#opO3DE`gY-$^@7D445|3Z=!0JMjjMat!}6)NNGq$?@yI|4{%YlZ-!> z@xNr)A{Cm0UYD9hzVaL+u$ZUDg0tWzwm$qUkADef&_3ai3TYiLJDYDtz-PV z2nt5h298XE5=J{A3}XlrEv*7-|B9XhHMqeY@-QPMXcNS!!ayD7@F*T+i8_k#5F)6f zgzl3e0CtBNC{nSCS?X8?W&{8lm||22>|qh52gaUdqyv;tojZ78n~QN!bYe6j`es58 zECsU0RV|(xFQ63{39Tf)G=v<5C!KThdo00#WylCjAR^R2PRRB3Gt#158415 ziTFsO95HaTcnB@5fk!K1U?kz$$ONSDgg~+qhFbqhhZX=Jifs_U58d!w0ypVMUDm9P zbMj3ACQ-LvP$5l1%;Xr`2FKdT#0>VZ#wu1}4SUEeaVDhV?ij(sVO*k>-qfF#>Olhl zEMpY_h`}8fxyxQ^lASvY02M0e4q;5900F2C7T|=;M!J)eahwSll+lfBB;!Y;v|NUrJY*&YbKo+W%H-!qn*{+X@M1#6n8XAOVuc4`aD43y zDOvsrMfmNH0J=Da6Hp0^VZ3mnJ{_Bu{E&}+YzhFWc%D<#2AT*m#eBGOYMh`Nr%DtH zVwAue06Y*hD_GB$t^=t}I=PYq_(2t_=!5_LtocML?s1A5xy3M$_0zeotW+)tLw5i$ zhQp|nm;GGlQl%P`9N=O??6^cr4HB$j>C>eiJ>4>Cq62TxLmS$lhc^uBE}HJo3nMYY zMkc{cx{@|!oJ}eY{R-2+vi37S#7aAEQ38xG><%QL-b(}P)$=hkCeVn+`cx1N5~>xD z0@&Rt8Y;QcGM8VZX@*6XC*5Xr6s)?&@ z8`+ttqnZXWLlcV&NFIzt4;!IE4j%t}-w|Kwv`bNHb_1N^)_Mh=@+2ml#=@{e+*ZQY zCGc)Ha^8<9gBxQIfB?q8jsI#GkjN!5lJ{j|IOdYY0=}`0CzFG!(o@7>F#sOIyJ9Ef z_{1`W2@0O!4}9RGAI_Lok^d+O`uQ=*ZpLp#EGy?ZTNc2oeX@$9>=f={g&kMD2v{71 z2Lo(*wRnzcZ)Ku`Hnc&rY0hKgj$s3hB!CK+NWhyjO&`)ka}}?M2R5X3jd;Am&Rp(t zgdyyd0U+3Jv&BePq;gDDLs`{7+41m}tUpT}BMurNz)pLr>0y6HOSWJ|V~C8}CL8+D zr?xdwa!^vD~&K{OYv~D4&2k% zXG5Fb+FJ^rAvOt2Zv-lW#^kmG-fcuj%Wwuq+-9$tM+`X0!x<56H`y)muxQB~>rzN3 z&S7e958U34{YgA0go{^mq$$R%3di-F@|fUSc)Hf#?vR}khfZ$dHt%1@Qeh8TY+@6% zphseso$7k8{N6h$!7U~vjB1x$D6}~Q7Vcc=snew89?`)X91_t-mz$3=D5Jede)F-@ zq*Q;nhC0-7jXz8V#T_rY(evCAcuuk%m%yq=lHwo;N&W3qf7Z8MqJnAoqaTw_Ml8tv z$5I|65E{WB*&{!bm&gB<*#h_b---T`5)?L#t8D7Y<*s?m13u9&IZ_PdG3hnjlIwrm z-7Dg&5U;6Q^0vR7!f$B#%#WV*yGi46=Y%JVA-uKy=-X-RMi|PSj1NOQ; zk7bCL!!J^T`rf|#AffzC+^+KE?{oPd@j&N!A#A1~f~B?oeOJBQ{Fcb$N6{BUh7-Ql zKQh2c$@M+}&QR`khWNo>{0&{)y#y6JOgm5l@kK=<%$oTfpy=^_V+yc{;APKe$ka0!{u%N!+KOs5fTq09D^ma*+WE5&Cy{AYKbY(!z(Zv zEYO1~Y~1CIUn`2CM|42axx+4q-Amllu*?A@M&d5^MlT|TBr3#tjX^kU!zE$_IIO}D zvf&^3z)0)?M%2qNJfJ9gpO%CJA1VYVgaa$`9xVPL1Yt}LR8Rx9PD}*BgOETl0^={T zV<6_>{3-v$2Ydq>5Q;{aLN@qAHk85|GGiVc*D;{N2pWU{1Y0#eVaMD9yxl`L`knz= z;VUWx6{wCdfDcV*)gf2`Q>ny8e#JUUko zMx10yuA~h)CLn1|D`cNR6u{P9rtM`S;DM$qdShIY9u*9Y`rQOl@rD!dB%%@*e+mU3c^mQ3YTf&c_G>0tMO4e2NX`^aF^7Xg`d@ zDhy=hbtfP`P-evOM+p!^JiPw{ z(HLcidW@EE0y(e(qp<=xh(apB15Tc(imvErrl>-cKn1Y_O~wRL-sOTaXl&Z(m3pTY zF=zaYz(};fWGjr!!Re#8Y@PNfo$xgoz z^@j)a!ehiIvo>pKv;jVBgDu#?Hr&Gsk;1q!*|mPvnT8Jl41k1W1vT14qk?O;4k~H- zQ#`W79p>R4N+`Q}6R*93af;S0_(x&B{F_8_f}p({v~;wiR4Dz2h%vXT?fCHqi>aH&9wyx{GF6^?d2D}04#;)z&F7B%C?AC7X_O9=yt_ILS zv3Tk4{w@>{C>S1X!Yb_YcF^B?ghD=q4lv}@veL&w{q?H13 zUEM#t2paqYngPH#NbN(whX@pbk0=2B*025EFaGAQ{_d~+g1{Rz0RRWE01q$$7q9^z zZ~^}>0xvKFH}C)}umeZ11PAaG00YE4!URw76l~Q6>@Nqr0SEA}2#+uc+wTX5a0#cd z3Y#zpudoZ3@Cm~$b_6%zq)rkp)y50@5X3}Ht_#p^o0ROc?1DKgD3&O zCg8(EWCOG|Mqqlv8&t6sUojSEu@-MJ7k9B2e=!(`u^5jr8JDpck8vXe1H@Fq8Hcg) z9ReQAK^xC89oMlP-!UHN@fLeR4ReGaq~%(+r49!Y1Kbo6T*L&dUw-^B5Kpc_)Pqk% zpAArNN7RBi)J_vWaTF^A{K~Hm$S^4DuL!)s67Ya2pE4?^vMR4KE4OkgBf%RWfh*54 zE!Q$C!?G;fvM%p34@^M?6$2dbvM{gI9YjGBXn+T|a40V`3!^YIGjj|-^D;-XG~X`` zU+hX~CTDu)AP3SWYLi0bz%T#<_s+*-WJe<(6gZ#(07U;EC$t_%&;mJ3nn9%R`nK=+ zm~L3iE)w8?KmRj82ed#BG(i`1K=Z&G@PI)tG($HuKqIt5JG4Yk^b{m&BSiE>PjnP) zl@BO^188Ttn(M^+EX(yVMe%4WC6q4g!3i9vLGs6Aj8i%nSt@kH7|4SeY(hGe0!Ih{ zEtG?!c`oPzfasELM!2n4@N-5lwM0WSQ$O`WJ2g~KH4aqtJWWADQ?)_wKy75f4s`TK zBk10Wbl)aSNKT%8iU59gGa$JkD)cZem`r~>1~$($m1v0oq{2M-gFo1V%xy$1z{43N ziVHACEsTTOUIW|aGkqwvRzJ2>KQ>iIwq#4RRSW;a6i{|$`!g{|0Si)ds)f$8x25EjAz+)VcT@&FoL4X#FL2zzFVE)6!*{nLyLo@Va z={9yOZ}wDcHgiw3b3gY$TlFtY0S-j>V{ddu`ZH*Ybx6CWXvZz{(FBt^X&XSPlv3&Y zpmZzsz(^Fr*I5Oe>IVlr#&75L<*>KV&4*)4cSd8ke;YJ_2RL;QLr zbZD2gSvRk)ns!F$=|l7>0Q~8CcdSH#OhAsMG^Uh(sK8@&#u!j}m6uqG8|;c}xtD)AMkjhf+jwOsK}liuL6RO1i$(#zzQq?5bT}XSID43u=WQG{6psqx|IirAA&}IGde*#x|id+ zRv$r06@!73`Jz8Ij_de8tGV+2rFge$>D7eFvaCKYiIOk*xlxJs?j)=e`jzV^XVki_ z3$(7o__ss#5fn?r40O0J^b@EF6bS#cvD>PIW9z%O?WgZ(wtrLO7(;!P02TcCXQXfW zUc0Om`l@Dmw>LVa7yN+-yL9hBVU@eNA3Re7L6%_wg9miGlPjBRshi{Iyi=~_Vy@=u zcD;X7$fUswP{&N_2P^zTl>)qfL^~NiyHjvG!u#{N`}fUH^bRB)JHUa#D?C&;7#{q< zKwrFpjx~69x;svoOnh(nj_<#V{D_&GD-42%m1TaA!#~)9%eS_`dz;KJ1}l6S z``26PZ;U;{pZ#V-{z6ZJn<)SKWB2hu-yyg${s4!K7_vffJ{C7=3zee58- zzy!RsIgf7Q-}T~$->iRz;}^W-OLp!PG#m`gEiiQM3(L@JzT6)>3%)JTT42W;#5$M$ zJNJDnQT-r5W6IA51U$yh#{Pc5{F{gUQQUsF@4i-xe?Z47E>!&51AW_11>6(#=Cfw! zYx?Im;#tc?P2Y4*?=kRB<+d`ZMh(a*nrgApfIyqIxCx{VQ@ObHnwOP5VC|74n(^UckjX&&L_ z?pG4cIzi*WatIHQsa3CLrJRuLY=gCJ;}&~%D+DcLKG-h#Sa@-$SLy4gDq-u4c?%DP!<8Q3LB=76R zv-?lLiX7187*bNOu9<&K8PLH8A+#t!$hIr4JMmIu55uN31nm-c*nxwn4tys?KIT2L@(jA`J3N187X(m@`04)VjBd$?g^ zq6s6cQZGiXOXr^!tL)NC0jXrHLg6mlkTVj^>qWeWO0on(m6Vi|KqlFP`n6if_<_X!d!Q&V-(MVHjV~Kz2q0THc zc2>`ktF@LomCNG0B9>}dZs z;zJaXHSb!{>mX$O_LUG$1aOeyL&5mLkAL`s9|r&c2(B>=!WG05=U^28AV3ez!6SwI z=tsdk0RW;IE)XacRvTCaF9}%Lof)K$0q*( zPy{`uLLOTPlDrIZ4SUU{epOUV4~}6BLJT4m!=MCZpz)7xSdx?oyW(B4xR@<|5eE+h zmMdXm6pYo4f^g%>YVh!bH8QV_bX<%a=lDSw`I1J~`%lce#|<60fSE2N!aZtH1T827 z9xgyg`^=yZQxIVlq%vYD6(aym9OD#&Km{;92^oF-qZHtDC#p_qmsBcdm0yHqn(oUEe}7MUW3rVF&`hF}Q?H^FJA{*(!w?1ZPE z(g$zC9Hv`;iPV(Ib!Eo9YC*Dk*NTkO2?Y^A2^yn~e^gGdg`G`av4s-uw1ky5`6`B7 zX)$-)LOf?vR`NPC(A&^8E(_&|XEg#^04UX+h&Aj&NNR}}1R@v1=)htGFsswfb}^<^ z$yNu`)!vzvl@HWs+bYZ3mw3#loY8DSM4OT1Vr01%5iM!KX3o*8_GU9K+CnVXm6bDn|(!yUlRY?^{&$O?l>Va zh(Y**Ac~R4Ka}BJ1;@p|CJ`^0$Xi~V2)CvbmI)l%@g}ee_jq>DC1{QdfaW?^zi%vY zNuJB!t2TJLsTIT^XyJ<+4n_wMfx&`tycHIA1h;t6E!xi8UJJ+aVwBx*dSP^xJlhc*;~0Aw1R;p=gv4Y`9yvBMNU}Vr2k$Dv5>6YE8|%9r z>;kw)wh0=g;++tWxFUR}h@Tsh;&bUW&8O9i95z{tNg##*5Fy2xAdl@a>nKcV`wtTu~^tvcz#rlJ3&*A+xB5W@zDpfA$B zzKE>rIvEIG2GcJIa#`UllPM63620n>vX~{FJ-d1%fDSaZm5c2wlM>i>#egx65r#sb z;%b92$3Lv$YjryYyp8GcU4C4)WA`)JFk#y+Jn_HmsZ4 z?YrtF4k1tsL`t=8i7!Oq6nVE@;_X09%iF>qO3y33_}(<;o5^hDV0{a2@RZv{(1xwJ zRgt5KDc*$?|KP^Nah{NuH{{}S$vDL3Jst{EA;V;Kwil0=%MDF?9Jkf%|SOKZ^i1430D4BXuVUK?B033-*@== zE&hH(pYYL>y#WUD!F5sb#In2sB0Y0`*_Y2S+2fA(61IIUZSwZXZu(c3RbJgS@A=Ok z-^A>fvildp_bS3(q)}r883s{^Oq7KJ5K-Lqu`i^=Wcw1R`^xM4h{voXkMcB5D4-w_ ziVOWru9x61nD9Le`3gKKT1;Ob63`7Y6uiR8ZrT(GyPA~w4WAVhI@j&hIb}PNa zFYY*w2SklEKCD-A5Chfk&%W^5Dlqnv?+3Gw?CdWD3V{$B;VZJHAFOW))eQ(oivYFA z0OM@qXmBPL5b}6HSpo`Tx{wETun^-y{-}r!OUVaJM+3;f0>lC$I6)4X(01%lmGH2) z^pN*vg6MRw!g{LT1Tp=_Fx7VOc}kI?e6Xbyk(30$K#ZZUzM>RFi4rSOJ1&u)GSQwk zQSM^m2!3JwYHALkf^N!Y5K-|IJxHEbQKbJ`(UM4t%Pau^DnJeXVCFP}1xnBsC5{fA z@GGG3rh3uwWWwXvt9KAV3(*D{mr?lKu?NeL70(dskb}#Pp$`f{zzB;Y4!|A|j2pXg z98wrxD4AKt~(%3kr)6NlXfS^wBKnhE30)r|ib&@Lut|GPSB1@|$C2j=3jm!8# zz=|d#1fU!KL0pisBn5CWzHuwU(a!&#ax)~WjJT-7)Br0}qbA=<86}b{?T8e(K_27* z8>D3Z$Wr3;g3F9Szy?7OQZFNF?jOV;F6FWbmom4Satfa^(}V(eenG7kNXf==m$cH! z2(vK3ayM474cI^jhG0|#C=nlX-FCnpk3oL~Obs$Z8~CcrxC|L6^CK}LI{Es(Zqmv+VFEj$j61v25X1623*rC(0UvS`iJq~P>XFNUvk-*f3j&EE zAnG3$^gSUhITx!w5AZ(qjR*hQM5p=^d78yPUjjf^O+eQ#HWRA|mPQ0j5Fxl=9{2$s z8go36QV2ORJyBr|DB=SkVjnehL*sKR>QW`{GDJr+C#GN>7&0{v;UP(rCQ0!%ZPG=N zG@|}t6%qmhbU+MVAssTbfR0q%e)1SL>B~^z6edCiROn@jwAVOvygW1y0aN2l6E)Fh zCZRGORaSwY(X6GAswc{ zTfa3f4dgt1^bZmO5Fp|i))iPCHEiA$-s1HNpYjMUhA;c{V?@zej}cl4FmM)$XW6x459nesE@Sr)(-txlik2v{Q0c&EY&D2vSruus(>r-m zYfrFN)l|R;p-un&3L?VcX0cYmbT%b<79r1r7v=zMe*)U@wTlSXZuS-6`t@j)_HhgJ zZQpat>`_ut0TqV81?s`@_V&#Bb~*nR)1p)NK$Rz;0AwAjbmc>B+mUSp)NM7eX?@K+ zGbtbI78OhZAF8i&v(__*^$v@b7ZbNLc3?Dc!8&a)Ci68_7kBfZ1xwp@X{`=!Pml?G zlTt4i70>}9)`fSClzLCHLqk`>q>?4k%4~N>bzh@-C(?0Cc5Nd!cEJ|_7dAPvcYE`J z2)ws~gRD~6Ieccy+-?w$+mucr00OfWW$RT^%sfTmybLn$@S?Oop z=KF+Jd5KnEn;43pm{22Fa*MROkl{SDmlQHei*byLiPej_=t-m0_R4k(mDr3O*mYqT za%EG3x$TD`O#r6BADAJNPGJ)whmN-xk%LWq^KylM0(f|VmTb>(*8`JlqJ@j9f!peV z9n6sXj*@eX0=xktrh&`iK$1Opio-I9nR1Bbm6aB927~T`LRL*cnI=S8~ zR0*KDj#c?@xYp;qmJ`3o6Q@&TQ^QoVfYd&DiCLI+!#RzUHj1bBIKu#RkmLZMb{gB6 zZ{OMC;yLZ+*%!I!JaFM`#iMKy*qfh~fs5Ig1)0ahQe~xi;{E_4;6VipLT+22p}otF zfftXO`O4k?$*u*9XO3#R{9rYFXt%?nh0 z8T@v-ludb%1sY|8+7`v&hyFo-6QWjiA*z&mwwPLkof=qZ+NN(BGrGAYI~tq^I;;O7 zn4o32q$5oLQ~{wEB3xm)tj+qN_luh0)tbK+ZRqTxqZ)06mQUe&WIg(-LAs}JYosR_ zug?qx-0~mJL8Tdjb~Rzf0K1?&!VI9H9R7h1sFoGX!5*fed(SSS8E>M=QFmy%UYD0M z&exB1I<9$|uIt)~fm(hku@C$KB9cLG4I&AAQx->?v^jzeSfLM6+aOK>9^T*!o&g+Y zDE?&o328eD7bvk)cWe)s-T>LEL)wMcTg}QjVF8d8K!=AH;uYOPEJ=&#x+Nr(Tt^L}u9ojv?vJZL0Pb&t*0V42$zAwTo?J<^Bebv1k080GCQ`~S2 zVtz!x%5`AV?cK}8oXiD%-}M~O`Q6X!d+-viw$qu}2M9nKLx&n}p z(j{KvA->}8{o*lR%R7Cm*Np&XeHq--BgC46)19Q3+^_x{uLPXuz8f6F`#H-7s{fcM zj^_>z7rm=`$9X)seY&ze-Avd0ssun9AYvZMlp}i69-aH-yWJx`01VLC6u=;IuDcDm zz!|vP#w4EO1JK{n? zM^*)ZweMjXhG4K++y#UAC4gramO|4Wkj90~#zPsP=eq49-|a8l*TTRb(XA{VbnEW^ z>HBx^SF-RIlI+XAL{8)eWq#)=@S`alxQi+1?FZCpg#w%bbZj6lcvKoYKb41Gq`O|8 zzrMD6tHI&b%iFEBt8#woPBU;2F)^qbT10RqP*cf5As zIEXM|LLP5;D15jB%ON{a9$LJJ5g|i|89RDR=tGGE03`oQmQ?UYfytFDTe^G+697t; zF>BhiIrFB@ohEbg)EVPnjGsh#rusJvfC^gP?2)5|qU4xq@Zd@NLh{TrbM&@tGU>Cb?6^H*EB3geQ@uy%%sJ%p6dl9lX;dd3b zWm|nFeeew$)g-l&ANU{ufEYrN#Kk{4umnvqBrO9?N!ZlV9aK=N^6a-Pd4~I55~`55i<78I%Yac!(8F?nmI389k_4N;h7J8=0?}saA$K zCL;>~AF?D$IwXOR&MFX8FiSTiu4GLtB#~oENvmvAqhUtk2!l6q)dPZiNE~wv4u?)k zX{ChOINv{tE$Nt-{aLBtB<>V*M3r4W1jQYPT;b_tr?#pPn6rtgA)2h&dKj)hsi`3# z+)&^qh$XEs4l5;X0Zu>tctZnAf8e79N%{W(QW7cWuoQs^+6HB)rR)iCR9w(R0G}nt zXd-~O>aNRfq3|gQACs_-2C9BL@Z!!Tq`itz6m}efg+cQ!#P7hevZU)^2@AF`U=82I z>$~S*6|6}jU=s~Z6=0Lh7-KBMO$8>QK@TS-O8&?- z{b0|7 z7qokokB(8jrXk(V(o81=L>7nOQ4#r1mfq^=C#4SG>ul+-7XK#2uAw(wj2k*|fdSP< zgnQJY2wG4EJX`<(lD)!!E>J;r^kE7jtYSOv>fTx+unh7L!AMFthA|}N!4#@cE#Lc2 z_}Vi*`8~vZqq&7UaABI#v~MEulOGMYWIvMluP8$#N)dT-L;%+3O=oCXTsE}^YrsPt z(-;FulHtT^lq4+pAd6Wdx5EFMSVvrxGM6QQ7sfQIu_Z0U%?sHRLm5(SOH*KnJE)Mu zE=6P_36kLtofJfw;O{+0MB*SNbV$A^ag8o%BO^=lfohP46lgS33yhJoM`|*Sj(p7< z!4pS09^{XZ8Aw6$=#V{zMwIibn!!W@p+r(hmf$I*PLg<{O@8rZx&(k9$is~lcuR5W z>7_BD*GblV@;jjvB`H19gJMt#l{olJBKj!DXDTR=w!9@RE%Z&<;PN)dWJxmBSPJrV zVqMq+QaRtrvvVG1nYd|YHtAOxQIRS?8^My6SlLSQaWkCaB8 zjYhG{2axi?LNDsAh6?|Np0cs0AMq&}eCdmyZ}2BTM+s6O!ZJ)WQ5`}P`cj3(lqZWc zrbfBv0&Xno13Y8Ixfp=apdRX`fZ^zCJnF-gegtVs(+>|8k%(2D6s4}5*FamEznL;j zs}AET#BzyIqB>3hrXbHL28V&X#6hTR9gb=41G zYem??rj~W9eMwDwY1wui;1%St#hw}`05evSvb>c|Y~2#q#msedrG1DgL8~f6RMnYE zZPIC7id90k)^-2Wg&kNg`df7gpc{)C;r3dPm%a3MysybFTY`I-;aaY^2|0o^HDj94 zVqp%;y=Q$r_1vsR*FD|DNp)HBT3wo#QUdq`c~~*G?x9B)BOtGXy$43{VK!c!+AL@D zBPwACXf#mx7Z!lf+^MnmG%KCeei3=%S*94AE5^`u7dqfWnL!_MaghoM@FPn+c*lQ< zaZ%7a81;%c#1|21eE$`-5qn9=lF6@hTU@69_D{wgoRe&%_XS@|p(ZsZJ4w!vaWa3YOhi2Y#IRwF@Z;7%o^A+Jjl^W!m=FDv zGSl?T;!FQ?UzKb_99HJdQKPDb>HHBpqd2foK4_=YWaW1%x;|x%i{2RNfb1c9)jJtA zP#6tEN0XMw3ONF1;4o=bRoc>OrnPBHj4(a#S=fgBG)#?6lmKti)$b{SJ)A+8MG1`yFS8AlYZ&J;z($tuk)9i-sMnhdrX3xi%=F&uhuZ?eu z`Pq%y1|_!vI$|S7X50$Fw1N!oAYfyS*gNU3e~~Ryh%cI)*xh%&!IRcwto7m-mp5Yi z&CGwZlD$lAvq$8+;W_pi-GEd$>Lk8Zm0YtgC)Ms(ATg+_?KLMKbdz`>Vu`aYONl0cpnq!K8J|_a@=)mbKSKducyeF%kqa@ z#vQo!$PTb{g>b9<(M&gurd8Z-{l1&xFt&KuS@Y#%FyZfr9=l6~9vGqzthnEnyG1;6 zAS*b&+?TF9iPar!tb2{&-qgHXY~FXA6aF=d(*)*6?_k4QcT*JBEZx(dkRAMDni<(+ zmOA2elEQwQP!}TSZ$k5$|GqWCR<RmOfLkqX%$59#0x-lazNmwdWKf4#+lBoTdo zF?|LIerwlu7ZC+dV+YvueU(>$c9(#`2OAAogAr&%#iw=A&v!4c5R&W;p+P6m<+1 zm54W&ZTQz{`qynlHW0gD5!-hlao0I9_=X1<8RW-eoVaOz=tQgF615->6PQA(IC?&% z35fHGqPB>G!G?U{hD#P=(L{UwB7okvK6m(6S?Gmd=!xfOjG?G4q_`5aKn^zWNX|%j z87E%T7;n}1Zn79_v!ND77J!*7%5;ESyYX9RBzw~T|km0X_6<2k}0W@D|wP$Ad)P3lA3c1C+P-Jl?6RS zP2y-d30Y7J*?H*rkq}u6@NfncBr=1@k%NI_8kdx?<&l4JjdigCZvg)aRcV!1iIrKY zm0QV`T1k~%d6lKm4(?zIRv8M2a3F}#1qWA<4RVkc!IPdwjCl8uFX2T0uue$Xl<;Rl zJ-3&s_>^!3lB@v(Z}16`fS8G?n2X7njp>+=$(U~dnTweV?f?vlxd=~l2#630YxyZ{ z$(Fu2e&jfpbjgQ7DOB<}dbx#&e`%3~=t+aQ7=3Z6-jqPZn+`4Dk=D-G$8rwNr>XH$Xcnl;e_k+q$AnIy7#7_=Fj zAX`OfWiP-6s07{@daY@I31R>gt+Id;} z$Q}vGpeNriRAy6u% zZ`z>d=?m^442fW)x{0IBd7)mKp?&D5omiLusitjFdO$U(gTtov;ihmZrBte$nQ2FO zkfnIKr8&B%R@0{&I;4Lpm=KwrMtZ0(v3zjOwC}ikpZKRoCa6d0L-c zim5)TfMF`8oLUaP2zi7bVyJ$bE{<*6UKuRHN|OnI^V zilTK9m2UB`0Q;i0Ik5i%HCZ~G#mTN*`mPvCt<;%$5j&k7TCu&lu{r@+x?rm}TUi|o zTn8!`AuF=J`35C>Ab4=6bkGRxxvvm`W-?$wzyfg zM~k+%84Sd^wocoywWy@cal z$+qDLwY3VjkjuJqyQ?+3Y<&Bxilbwh+q1rEjDCw7fIGCHi?nmlo4w!;&YHOG+P2ba zRgXKjkvoi6Ter5m5+jO2(AyrH`?sCzxx4ARcbcqpAWfNIo~LUnjq8>?`gBrTwN}f# zE(W{DC%eCDF4{xA>|wpTi@n)u{dpi-`^kuMj)2rrEj_o0{)is@-V} z`Z~Y9rNBQ1w1L69aH_w#nXJM~yv5710_?J@ySxW1xz0Q3gf4!a;nUx{Jj33$QZW#JicYP<+Fv>%mbA!mdll zBTTm?EXDv(dPFvYDi8 zo>Xe3q^qD&{1H&IIVT z$&0?~jK#=&Uc4H+&b+a-3(tPs#f$dI)-1Nz44>N!rvi%^!aU5Dy2|y_$~_Frul&QZ z+{YsTDGt2QYa!3$NzcA%&lJt5Flwd6z@Yt%d*=JJa(vDNEwMaI$?QDM=JL)b%|Z>m z6Cc|aFuVxp>e8wTqjRdV;r#!`s+_|BJ;xsH$^+f0K5ff*E7We0(g?cJxtY`lVzBre zr4HH%W4W&U9M$FAkL2qSUz#g0yKqx`gOl5S2)(f*fJyV$)kCe<1^v+T9MQcw)&+a8 zW9y)m2@EYt(=WKu_|?%MebqaC$9cWb=90pHooGb;YJ;uPh5e|SX|Re6unsCsPYuUmtp*4# z;}1@*zKAOVJch5p7dZ6<1LbUtkUQKn`cMMPlJa z9hBJ`i{we(#Sp*`d{7d}@C;E7A1ol=YQX4?-sr&%>5(q!lRoKmaNIbq+~aKFQtjN3 z%+o;*)d@B0q#^?vXC4)FZG1Wlj; z)6M~JzyZ{*@C(oI&VKL--|!JH@eYsh6L0Yi|L_;z@HK$uufZW6A}m`pA|;YbDY7D@ zpbii~60hJ5FA^gpF(Z5q&kk_iz%KK3G3+H_>?`9$p6~`g5A;DV^g~bdMQ`*$p9P74 z?cvV!P4EBo+`bN#aP(78^;K{6SC92suk~Bc^FZ!Rq0vcfYr;qxnullDi0&gG!s}K9J zFZ;8P`mO)^w2%9^e*x5<@r>{L6c6#g|NFf!{ESch#qaDKU*Ch_E5Pz5CP6I5LK4WL zEX+a@(qIcEp#}d?1OR|CBw;Nq!7?qg-#3dMwG8;?)X+=bw6GIZuPZAfCF(d&H6|f~6GiDjL3IL?p0?<&)zajwg0cr?<)VYckBZ%M_W5lqprNWZBZ?%a<*V8FK*B=1rVAb?)TZQ>2KGJ{$hI$Ek=dcq~eKtReKJ zf;S4BK8-rnB~+^gTPo^wcfTm+kDsSf8c{AjxrN-gIHpV1V&kfOX zUcI?B<=3#QrUnpuvTe4wZ>ptjcgycB*_3SoAOc%84jD_C6VMRByiFF>WqswX;WGbd z6|dEL9JKd$@VyxwV-()}dGr}UcSfCBx7qh&<9D4;f42Mkp6grP&yu(KYGx@88*X%P z;lR3xxTlsPv`_{f7XU!P9A&ilgC0>DGD9Czh*%{b;!0XCJrYao$%$ih@xckrOmy+Z zu14IfJ^k|QtiP#n6iUY(ZDh?y*MO8QE2sVoFF*j!_-9Fk-DObQVcRzNAPK>PySuee z+*;hBcyWR|#a%*yB)Al}Qi^MEDO#ks6}RG2prsUApinmVbHDrU&g{&)Gs)K^pECdJ zI*;@Capq$}3Ej5!oM^w$-hIjo9hc-_d(l0BpcB(cCsBDeL0%O_Ss)1Sme_Tk){@w> zchMSm?$$#O9QPV4WN(LlwY}gt^{tT4zH<_gtSAxIQW$f0pqRl)9-%|2h^SNd5>J7^p*LXKbQEmF) zx-D1vy*n2xdwtYO#mTj{a6qlTS9xLufahWu`Gu?TZ&la z%hCzLa9kWUw?ad^REpuCk;sCxj0GRU=eOG#7#^m&akxpVx=M=wTFk|8i&%Kp{omJJNc$76-gdui}A6ZNaq?XoexuXD~W7wD5FnZqv@tPX6X61 ziuw7=g!;8_jf3AQaUa8PJq)lqe=+iWZyC4x`y&&Js@tPY-2bEF``ab+WlG1zQfns4 z>~4vI)2mRgLHtJwuTPR+Ex3byjl+D5ah-o%y;ENfy(&zE2fNyT$TIsiBmH^9V#N|~ z({ah@wTSh?dhJ9YDs*PdzkH_G^57u1UDmgWgm^7zcW;B`CZz`P@p3FRP%1EBAn?_F z%-B=w+atFhE`L(1mV31bP$`OWf5?ukp3(jjVgvpA`{ywd0MdnFU0D;#=wV@U>PF%7 zZ)4Eh$btXOz`%)6AeDqXzN26i^#T+JV^p3PE(l^Ke-BbO`SdSohe-rLhetF_LOr4j z7cR9S^axUJr&^NEGC|`2{w}YGBwW79z)6MnHeoY(I^^i3DdX2YxWf4!|%(Je=Aj{ zP8T5crSR!vJeT=5n(1KIv!c+6iqYBNsmO@(cRH(FFR*xLqiKDMf7EKp+qKMINf`2x zULWnVqT<1`hb1(N+$y2XbICp;qRfORsLrC3mU0?ZX*#$X6y6zDsu)!pl(`z!g&5U3W^#$5lqJqE zl8xkwpOr#B%W8bdHMCb`Jn;gNguIQ91S4g~brG^1EbwW17=;xO!MnvyBP{oU{&8DT z8M`0Pcg2oYN>CGuW4^N1{f6#}8}SU~u)3N4MMr0ATN9c|=j zJ8NrreRu9+fDha0qHF_D4~lGK5W9p$b()0Kd;S?W|CY7X#X=${BC-ylmHWVW0vqP0 z^8u~z8b6yq_wbL-Py5~b2Y&)x*U+UGpSb;}t#fgOHoXx<*Rn(3SUkyev4bnXtjv=i zr^3~80d!8>!>XcDlxSmFo+_53$8H>;tvAm#ER7}o;CK&&eYLxd!;G_H>j zxKpZK5TQ3ngy;)|ZkCNwnH%_Gi8+`5%gPAg_%eG?#u1QlJL$q$#53NA%MkXS@YRP@ zG_{mMkjpV+e%PEnz<)@Bvo`5$EDU&FoNSK{%1sC&43%b&RaMRApDhVz3p^ZYi4T!` z!p|@|SO^7CEDQ~>=7JMU>#H1Ay2LL$w=f)90v9#mjDg%gc>VN6$^)|8pD1}=DaG<xw=}l{w&h-8r#J_$!$&Y@Ovbn0kEY&7Y?C zOmv*eGDEIEPwhAOpQd!q($u?tU}I=vc|R;di|G%5S~%4PHQ6)wr_^!n(X`AByigd* zwI9U<9Byfe+czfqIY%F6sK-jc0kEe9Y*P8b4TS$N;PJEJ{I{Oy{m3-knu{F37dcda z{-@a>J?Y$1IrhAncrI!)ZlhF4Ct;# zhzW!Hof61xgL-sj#yb$9L9v1mVCZ(tG&Ahg1y1+{&g*FL(UKByXY${{_PQD{-Yh&Y zpMX&l=;BN?@sXEcL5|2U$=d`(4ucuo;J8$R^>fgj!tjN7mAb=9Qnm|3wH&eu{t8Rp7+Nmo1g2GaTe?iG9H@ zPdJC;Dm(<28*&Mb+UCcHHl#z@c80b%zXkm zW*oU~OdVYueD-eQdjy2wBZ){tm;uab7Bre5GfIl(+rbYAlCP;AHlG}}B#-t8N^pjO zs@_5v1fy*i5h24VTu~@jxE;bn81fQHeMHax;=cU*bVpUuTOmj^n!cnMvVtOHONWmIL7hr zs4fp1uXG2Kn_vJ&#nJ!-@hk8MSVBZlf{|R`;(A{r_XHd^o~Sm_y3m&Br3tu*X_rJ0 z03U z-@wpBJyh$nlI9FHV3vM7l3H6x2FG|5yl5|*8W;821TLDNIJz&!UP^#b9P1O*I0eAi z1}E=q6F8{J0aAe``vm^8lR@_&;zxII@GpK6RC~mFSM5Hi^-N<_KkASl@oMEsb=P#f z8t|L|m!VQM4G9Yw6<`1meG7Bz+o@ba$dSlfd5X`#Yjs6bTRI z)S!~cK_anA0N%+jo zBp3?_BLgOr12w{Aa7@5))Qi+#3*giesn+%h8`ANm+lgi{gs|Ye(iK5XMxxLx!f-Z9 zyBIOBo;aV^_9bEx>-V6s_CqP)=UneFjj zBh}yLX>atcumCThZQ_p*gd?ok5Q0U!t>V9eisx1UAcaksG4%mrZ5IY|9!UAtCwD1*Vp-Eo%O5)~9JdBj*efrOF(qq?Gc^)R|J*M%6OLYki zxADNg)pfvpQ+U}*`tYi4Y^@Qhq_MlnytB}}tIqsmk9qf$dC#VK@40#3gE_jGbb!I)lYqsbti_PF#jvHtNFC3eo5g67 z#hB>E$S9bqxN2<5Vrp}vyUt?z!D5!svXT{Mcv0y%oD{cUikBRk!;Ldn}FRx?ZfS5?=tRYgvtD}9SR_DGBir))W2}TC5YzL1b zF#X`s9?{}o;9c%W@lnJ!HVliX?-Sk%uTbLU6}JCHOJpSuQ7=wnKa^q1hEau>LJErk zY|CJR57F5qd13>Q*de#Fxh&IAJI4;XsEd>nVL6;*?6u{e-VG4IOS}0BV1#-?;taui z@y@%+g`3010z| zAtF(ml+U|`K`<3hq&7;xzY_ku!`@=r!ICk~kQrh5&jCtwSj8MGgu>8)AvVYz9jqK3 zt#D1b5urCAqo6g%dPg@;Bn8Ztws6`SW;nb$5O9@7M9w&7a@De_#E+LgVcJW!dk4enYeDr`JEO zE`Fjl_Opv0KTpv_`}*nW>BHgt@wYQH$bN8eaJ2V7Cj0p{nq`03-ah|&a~`j54*$J^UGTVKC^T{&M~JX=^fU0yz2S~&f(aI~?o z_hWu<@yqVn%*piR(ZtNo`oL~Kns?vW*g(VXYin!&1>Cn*TL;%S7XKr$|A%6qo1NMC zyoMIohbQMoM@NSShtT|be{X+F@9;#&bVpZrZ+m5HYirZ|d~?rWQ|CZaa|_yGub-Q! zZyl&_=_#72D(n~!?Sosin$6UV|KBXT%wq-Urb>IJ=JkIx_PV2^PF|4id|ztvU#iHrQ^=DcNP{wl9}!1pBQxPJOTjE>F605 z7|>ihH8nLQB_$ad83_pqT4pCCB>WG{j*pLviwg#Wad2=zAP^7;#K!)Q%KpDhc8vco z%Wi=>Q2qa9*>CM8{vVbdOGxQ>>ta0}w}_N0(*D?n zjFhbTwl(#?S@sQQC`l{EBUXC%Yb;U1ykFsrmR-i*mYQv6tbC;d^S1gvKN38(VhKKt zV#>CDcQ5Ai`(kh6f3fU1U7wk9g8%)x!k}jMyTxEG4#Qzp+m6KF&1UvEq2PWW@z^cC z6HD#*AC{f6<7@Z>#SL>PTl&g&I7e1?Nj%qD`)=S<-U=(kuW+@!B#Fbyy<~yP`;Yq}|Cka-RG^{uEZ0m}PE^JT6HT`{oR{7(e0wV73Sj zm*xBq%O0?HLRkdo{Z?7@hSwDzvzE%)qh@}ox+Z+>k)|f@WeLJufd^H5O8pr2lUpI} zAMY7zh|qvn@}+1@9?zhq_*?DQr7rfjyVHMo?T>gx zDiuayZ>t;8!q$)OtEG>X-KW7-{p38ePI9;=2Y+7ocj)L<1fASvqI|dEn%@U^fnvit zCtf+huxK?~nB@xQBrpI!~-wEB>p8vc}D)H3)nr=0Ea zdo?W0qb3rdG-Rzb2>4M>&?DxP^#z$=I7p{qQ+-osZooI}emaxtr zy;c`sn#f!E_FtXdm$UhFU4DhuemuBi8{@r8MMP|3UnP2YjB{sxh`T)Sn zGV_4s5V=9D_vk{QbZfUMsjXkY64&;gup3*h(N=>gu@aq|dg<)G$d0{)c5RCg9*A zOHIAN-S zvA{eX)oMTmebVP_^dVjfR62T~=$iq?6671+eUr`!?KYN(epQE;jYK@9+vnuJ@a9#+%^HD*)!Ex`@I`HqS%{BY#pF;hVO?oMj^n#fQKsmdaWq?r(8`C)w zL@9BTOng~VWKap0{*FOp0ObHKrm8jsXqdF)ErvH330!%>lKto@8rqFq=fWn|?{qSH z-_W}68G^)ZKD9qjE>MR7wRC4P-6&5Ws^pI~5*trMQNNQ=F@$fv<^re!A6j1?u9#UZ zjbsjlh8D?-Fem#BVb-fVaK>;=?t)*La8fzWz)ywkF5gh+Dr!8f!Q+47y;n4mJ<|gu`T-Odct&P<{zVZ0O66#_QJP*Ek!|49*Nlre5z9PeWst(DIh1UtBJCSEe%gBZ7IrO`8??-P}0# zwVWTblOZvUqB$5x+$=oSxpW8D8lWnTkqQhe#l*9|QF$7(oa|(>LwrpgE7y%8Hqc_B zy6wPh66iU5WA}6wC%CO#+QYGu5dEY_`Lp#P55O8wMdn!(K0u|!g(Kbl;e%p_Jo$8Cd6ZutQA1k@SG{8*){T-l_jOg$ z7L;}UGfmy^4tbTIL{V3mbXYr?4F%rM0Wd#?GC+kfjzUx+Jr(b6|q=25k z48;}aCk&(yUr1&G00Fwmev`Q;bEi$=|7Mf2)eD(RkqF} zMvu=%>a*D>NCqT3Mql55CTWP%5ha@o>)fe%xO;ss&;Sxn4c zK%F4q`ZfV37v`!LA!90}8b#z^;X7iOW0ICTZAgpAD{H%b?Wx2=&1qM_gas079J_Zu?{t0c< zhy7vkXDue&yuj}Igo$H^X95LQrVxw<1CS7c6K0r3jw>~*e+m}mKO4fIP~tT&cg#7rK1z4Y9h_|#@fIKjCK}Sb zl5+6|zL1g7Cy|Oh<~(5Xd}H7LRffd`5WrQY&$p=0bFD8lOKjf%`sr}ApDJX9J9HyR zH*v)vIVeWmB>AhO)BSM@FAqP!)X|L_AxQJq*F?ieG?69K2X#`4-o(3`NQm|($+ zY&jiMgv}+)J8Fzgs?oxU6kqi(#V(lVKAxWreA0i#g>mpdRL* zSq+8YteZd4tIipRu^F{xSaGv~=$vJLwt1^bcAh$0U}uip=aBf5Xk~$ z6U#_EN&8q8>F)Bx7Y2TtOC*WP%D#ox2N!JN^5oJ489v??%nuZ39~OLYF|Uy<1i!(F zgE<`bXJqkYbKe&J4rUuO&GcN3o}$ScH`PrZ%Ri%GLK}v0Flawb!6sYKbMm4;x5cMv z@Af+j?t_c|RlS>)EcT-;Y_-9PgW_;x6|Skj3q2@?gp{nNz2j2M|3l&-Ap9OM{yvWT zLo-WmpzbSt(Gnfgcid|qZdmgF&Oha^wvinbz-dM*R(`<4W8&^t2Xo@nO3|fW2@Rio z;Nr~(p!lb31uS?uSLVy0A)MCL0vo#swdzvs&eAiM+}PPb*7$OX!QwRg5@WN9QS}Oa zTDc5cp3?b>2q|FsWyPDjil}cql_f>48hLTNj1-Tld45JjU`SaGdxc?qMLdg@Yrxr3AzBsc+-rQcB*XcT0{SGCY4Fqc$#nN?Rxy-SF% zyodsTLaG7Ib+Pc#nBr+8XH{ex+ly(Mh&1O~YRtSG{ zb)9>2jSFvG*In)59fL+N7C69Gq|1IizINxXZfm@@Cok(yNcpi@{lWXt02t;VZSfUZ z1O40DE3@q1dG)>3sFPI`5g$W(71oj&5r1}FI7!XrS{=^E#=jD8_RMPWCmN3O8t%p! zwe!H-Flb9^ew!-HcdSt`pPM$+1(UCE{}C^URl4bvq>OqL^J8Ti;h>%+{MGw7$xREAdGPpSI$Js_%$-V!kIhy#Nko5?)ldv4>`O)pRg_ zY+2Itj)P%Qdl7v%YR3*}r=DmHooN5ct4_DsbKM0Kp)ih zbfWjzyzlo!w_Iv_ZF6Urd5w}%5PaDchNi{e6Lteape%TJ#MtW$|d`M-oN3CFJ>En==R*%m8(Ba=6{mE{!i{77_t^KnA zJ&WOQn!{GzedhTe#ll)%_`z^Hi19m!c_bj8CY(CD+T!n8I5a=|7cl&*#sCQR`NEwA zy*~=yr&yYge7#lFzKPKb0+u{#b^)MWmawiL@%aejk8uI*ZJJ}5^h_l9fM)=E(3`PC zo6e4!_L#HQdB31HnjNdqj@0gsl#_AHwGPiysxCwmpdVb$35lQ|&!HRDmmDqYuH6X< zvco67@@hkT>`JPdq*?27U#HI}0F?a>{8#{i$&8fJPYUI?)Sq_vZcH^#c5INe^7fB) zA2}~3LYD8F*18)v?kB$zOy8`v?bK4Fo8n+bP3+%{WfhERuH>B)H2eCh$hN zlkM|E%8YYQ!XT%UA22rC`|r)Y3pyIkCbz<7!BY%AZqunI#>MVaC1(@EwkR?WFRY%q zUs^MP{4)aDbV;BjzXEhs)PFcAWFO>*xiC+*== z59?p9?!E|l%*su5HOVYSVswf#L&Q>vj+oy`SVE)-XLT(bC}dGcx6ix$pZOo=1?wnK ze2_*tb6eT@Zx-`9+Jg=rOENvhF6Z;FYvzo4CY3B9{dj$tLI95P1x?EpX{Y(2H}j!| zPWtCdhDnRjo0D&*s21`*EV&X%^3Ffpe-5gH2wV{SfD&(_sNQTWzkSHdWLRJ_;Me7S2_T#+OM-Bqh^A(NI)WgHn~C~|wLF@2x4NYn!j(CJO_3<9AL<%k zsZsv2Yu#r};KxRMlZwvC@Ij|S>&Spd2*Ef~S< zHqm-&e4Xr8_P32w!c8ol&2!mx)1CJLx)@k<_5D+u?3)voY?#)<|8c)RqJSTu#P5rj z0ag{55!={Lc0pTnue8ZDs<5y~Ff;yItxqj@)d~aCh-(P|W4e1>mRn5I;VhoJXXkrt zp3Pj($$|;KcHVCbCPPRSg@BDjwmClM+dI-*A7r2GzwkVeXI#LogZ!x3#S)qdB;2w2 zzKQdbV22Pe3foJo+cPK%FseULEZWMpTz?e-QGNn><~42ieZ`%t!n~Nc0sw@`5j#|E zc<3CsKQfZNB|T!d+BNxpoU%pbp9;2mvMknfWbSE`kq6rJBL2Gl6&`W?D(`q~@?^&>j*`bSky1n54m&S5-%_GxT!AscCui6~o!=KX zN0ZxwAHII|e7EEIJ=f~opXhv}9`Y|96Px9uU*)&!`s4BG^hw4aL1I6Y3xD|NtfLc* zxFl27-vdjvPd`uRZMa;-T3l#E%$fF{?rmMnKR*|HAByPzfi<^ywCzk%w2v!(5m5D$ zI?^8e$n*gthocA`u4zUT7%`S?rAYgG7kc+qwL^tC0^rPt$c zp!}uwQwR~`HQwtv`FDF0b-$foU1{|FNn-r7Z?$-=1L5!e9`g9>cJYtfzdx`@-#1^I zR3pd8U!1DHxH0oSZx7o~iu@J!^7?HPSIZu? zD!wvYTmGzi`74HaU-9}iE7|LsIxOuuOH?7LpD ze)#+HPwYDgfCQ>qLI)sVw9g<~k%tq~i0OXm-%*OE5HOD6{<%AnB=m21oBDrPc0TmF z_NRS~ECI{j7#f2^tvpeWt)bjz7L81)ryPZkU+3a!u_2fa*yTAVp zp>HYQ=YF@Ztx?wLN%-3fFYE#O+*nSpEt`q}Z6*m+4Q5%$mR!~e9ZYsj zmxEkFyvo5G7G56)z&>gqzxlMNF1!zUsUOZZ?f?Zs^;NYjFD^{`n^Oor?J{u#W)+#R z2sA!0#RdI5EOx5?`LqlZ!QQ0Cma=gyS3yefU9m^xj&Pi_OoneLr`nDv4VylmqtIHT z>9R~vfVNSP4sELdo@cX%bs1g)9}GU?>T?gQI=s$1o-}5Oj-W&zA2#-o7VaT0JP{ z>)%1Vdu@!hjUV{?mMfo>0P`p#di(|v4d;fin5KZWTTGqa#Zs0lr@3a#s}FRwl)1lJ zTPpSJ5x8bPB+#p6QJyCOVdymgg)FjkWcfgWD8WjjXr);=ZIZ<7NUlH^Y=q9v6oAMU z=r*s|vnvr{CP%t)S5gw6p ztHa+ksZ3r^qNz%iC0L(NsgtHVZ=$jFL}1WMofSZ!jKPOg>zF%uJq;@(xqRprynHtq zC^92}5(JG324ECZc@VkoFg*oqm(elZmR6qDi63?QwuvmCoTh&ekvz{Ep~Ssj7+ma6 zR`SYm&hoS0S@HvWP{ld6%@4KbbD02oop`?MIpXmZ#8t#v{8i_O7pOM>_Gt?g--x=G+^oj$T9b%KKHx^Hq zImNtvHEZKQ!vRV{dX4c?hUSDG9V8U&tR(Dyqn-20N_?(0iR7j`WPL|UVr_H2y7c&j z^2gl#j^4@U-Fr$A5@`VJK?ld$y_0E)G!ak2WKSh~)+9f*T(vp(sBQ*!wkl=RW@rxq@mYC2xVD^iZlOA~bsMkVGrz^+n>FoWDu zQ=0nO7O#P%mTjAIPI>x=+ptb~hw1bzimG@95kV5V(#Jh|hHquUk*1U!^^G}Sv5!2G zSJRD4o@UuMmx@)~Xqb$gDe$@>&m6sn9hyjUHt3urt~+NogM8J;uAst;x1%AXEv%*? zI*Rs?zFV7b1qn7sFTZ#8gk63qp%PG6*4EegtGw`@@xfVs3U}UJN6DaIH$5AwKU6BS z;6k=oq#`6`kf)+ z?k+WqYpW>gBDKq`)3|#(&|x$TWp`V`H<(Y~%&|P;(y&=o@lFtMw)(ySx;t(nO`kPV zq{Kg**(gh!0nWTx2~cj_TzpNlrdhF?i|+1)d}W`8drFpJlc=U%7jx@TqMo_;tOtSe5fRfq>i(>d(8sn|0D?t%xmm--kV6 z`S4e3qba-PJB5I6sd}0(2V7y%k|6@4e>t)2Pxqs!eQ;0P)*Ovk3r?0N4h0d z>1Ho{kgsGP6x2ycj{Y<2-buS@XKC}-wL-A&lAN{=k%1aINNtb;xKu*a{q<3M5>{b& zIiaE`Ag4t49{XxXYmBmBShU6VZ%S$hLdQoi7V~`*HI*di{bEi^t2mY&IUAPDNRxJ% zj4`J0m$6eNZxf)@a(ib7y`bl1s1xQvLU4y%n;@LJN#-cJF+lLaE&*o0YZN1JOm^3faU#p-OIaeZ8*ns4(AnzQShnX3Q$;bz( zxxD`jVS+4|KqDS&Z!;1Vep0sR! zE~)A0eBP$5z)+`$qlTZTVu2EuacBN`H!=J#pzK48ZafrL*#QrDS7y1R|9j1sM(~=T zWy;3$w6kW z$xWU0UYmQDQp%JQ9c{FF+lavP+qW9FBt8$<{n*vQoFyzo@{?mOWrT*p8DD*i#pl3M z5v1Y7?~fI7)xG>xME`Z$QL^?eQIo=U6YFAzwJJ`%Re?3-K42U}68Y0Tn>}nt>2>{F z_LGY$gMc%!Tz^g;QrPjN!8h*DL?0(Y{5P3ll<{)HTCPw63uo%HCW?>aUy1(6kQH%G z)T?cvf=`-NjlPGM{awNaI0@V{T%@V;4skI4oC>tsgpSRNygXI4BI^Cw85$NT)X=JY zx^kIEct4c(BxvNzKTg$T?2n{AkB3{djMqkyb<>2g7|JocoQ6+8J66OdD(NM3m#L~^ zd~$nI{aKLr%TrB1x}*;?VmK66 z2-Gij5Cj2|jN-@&f_ZKbnAHNdr#&B}Urc}KsJwY!B|+c^>&$%H-(m0q|0A^- zGtRrvIDKhRVi`Ugeb|eB1kd(6YaygRH!yC#dnS5-TB(m$Dc)HDqf!o*^`3#Z;8Su9 z5}BLxT2~gIpIn(4VKdtHn0+J4S|HFh_$GJ-5tQ>>t{(?J3$n^VR+B`be*w2MOpbg= zo_$C`WJpnINd5{SdI3}N8&Zu?lD8OANgP6(#LD(VnhQhdle+fRkkZ-EOY&h*2jJWl zrb|Aw`8G(D}u=xrvDTJ?Y8^aId_v z3_|dr6lE3^5s<++5};`Dh-=FTI-}^mFygU4;(0al8vC;s`DbtT&pv1+N9nVlp{jdg z%wZ0eM|aH4`&j?d&mk?UA>^@U`yj?{YEx#!d?;>^FesQ!C6AWN%>>RN1LoQov_Bbq zkuj{7IE-{3e$*-*eOWM?u&TRj(omw|SmwT3X6bOX zCNRVq;S~gDS{Y6l>w1!it0f46@{Q(7jXE;RlVJnM4dsvH6`o$n@VJjtUBz``@|8(s zyWJ_!TeS0dso^;zpIu<_qZ3mmIFL%YL>mBM3~rkFVDSc*${J7*fXTmt-f1F!#FE2c zm!lfeSalotVi)%WPb69*9&$s@Y_CyqU-nNuHl7*hT*b{AXvbB`LuDq9S}GW@VZ<;5*O0cbOoj~6*G_gcySX$!% zl~@&_@tVxMgY2_wnlG#drxoP~ZBlVDz+K~i^=$FX!z8_ z$k?bqJ0E$eiDP!rlGSCDpj+q?O{pZB4$)pzGBc7XThQ1vu+5A!w{44t!m=fuKAz~#);r*m%LTwxrV9Ait%S1!O-I*L}QMM97+ zw%MrRTR{NeU}-A-)#s02UdI~Aau_xZ#$EXd`Hf;^*)BUf#P_^;<$C&RLk{q0%Z&5= zOgk2RPcXbhbGPgTT!9HJ*mB@%`Ge_@@3Qqw0)c(fp(|ENCL7K#io$SPCr!jIjZ=nK z3q+TqC~*7zbZA!MO@rQLc$mNok(M5-PCtz*P*Fq&Q&|A1_cf+mU8YeKrf<#-_q3K4 z+>wsj2&kNJiR@Z{z?v)2sE!0?!;D~Xz=amBQB|)M_L$vFuBCRx`S^qVEM*$Q@tPRc z16z$p*G-gmUgknZTEo^A!%gu{O=|p&3JF&~GvG#xX8Xyl99XR0KQkX@*ihV=B}l}L zVjmq!dOu7tMgGt`xybk7e0@=W7A|P2K&I8_VYzrD=R2eMQd(fcj zHg~(lMGrQ-STPI~MbFPUzgr4Z-ml!XT7OpFO6oT^pI`3-TDyAG^)Kp9r(q=c$K6DK zy|GN#(XtegwMrc}%bA5m*db#&EFP7=zFe~aelMtHgP(ff648%fi%Hx*aO`SZfs>({ z;oE5*OyJ2VLeqt#hp(}l(935#3O0avQD~M#6tBT^(&Su>9+wZ{s3=Zd+7l{S(dY`Afs&;x9z>rjnkGK7{cAS+XDa)4M!QD6)(IwZD?&(s+%iq!uB4ds zb!;3tcdX|u!eus^k_YlKIX>rl*FeC*AURvXbH~`qkxl0yUDr6Td7H6lzf1cocNwmJ z2O`1?#|UhjmXkQ%kvO@MIDL~iOPv&r_M!neVa_;)&dkd&!qw5ujcwf*$#HVe4+F^d zCO_;pJsi2J*a23o0TNWJtv2T0pFbhnPJm(B`#jdmHu@ni;aV#Byb5oz3MWVdglP0}b=-+YWqqshe#hZe)P(J&evTTOA2Kar?2^ zij9ytPriLA-|LBpd+iu!Xi5<(gnZRG^_WynVQ!k_(1GJ|@n#7Hf|5{1GgI2xAe~Ed zzK=!Op}my&vNe0c|uo`&*$6LGogTb2M=iK{)NBWY13}@HiE*7BBH-4xGKA5 zgeqJJ9PyJ1Mna8Fal8;g);Si#<-a3rz|SY$zgOuGiQ*cRO@0elo#o_m(6M!lxG3WE zNM{zOfuW$(uP>)h&qfZij&ZKx^r6hS`2#dotGPwDxy4myB|_j*JzAq#MD#W+@|bv> zkyd_y5u}=Kbw8YQ;SPM6(UIh(xa30ga(~#T@D0k#@5Hiu>3i&VueaQ>`r8PDoJ*c; zcsWU2_iBFcZ9aN>_eqjIT9^KDgeE$2R2MLc`A|>aH2o9zQWdtZ_XFE!W6^uZ??PkR zTK4Is2qiB2a2WswtJ-+_HiO3ng9SO`t`OtC z9wXKY+->EJz%1x_Zqc`$l%@!mI&@Ir=4DmgFGmue=SMEM;yy+J;9G?#`kM@>;FaQw z%R-fM*$ z?67wS1-@Gk z`ikuQmfjWMF(vRC-mv$WDF@;?5o1v8g9GI>RG^Ktr$L4idok zs-YQ=R%6RvS%Xn^7o-DUJ#+f}75#BtnSpR>pzBR=uWGur$$HWK*eC1KGj$;Uzlsk( zzH=dbrrSe1SgId=q1f5)9-_X61xMlra$~ZF;0jin77q4l^1=DMBq!=&6FaAE8#^Djth!8O1 zb^qP{xN^|hBDk9@IZ8<8WsoRj9>--+?|$p^X%P4H0RRwKTnsU8G#+tVx;kmd(2E{+ z+j}MNn?$-Q@15cQYQxNbd0|3$LiqK1p7MaZe)G?9>XEc&?_V)Oc3kNO4W18DTDf>1 zGviqr@L>YyDvuLgX4m#x#*1tYk#s!@G)=Q*(p(du5+(3gH!WhO#!!J<_@>1ui9|O4 z(0>2hm$vjb%rPXCm6i%2`-3k8xe^OW41~^aF++;q#53ZljiyE^a#CPo$&ZobrfEyv?t7DS4t=5ou`k4uGh`X> zJz7ZO9dNvaZVgd@8X+0ePp2_pimZsr)QlXlVbd=K!+omTy*ZOUS!pwkKg1(2#&@;rC znPZhEc0Rcr(Ezz&GV29zsRCTNVezDX;PEJCzNr!FqJr%idl~LK66D zHm0&oXk%{MY7rWSKD6q$tSS2&%Fm+9q-!HJ^7XYyJ$DJPgCM_`Rm`Ve@v?m!*F+w|PaE z4KLsr;k{MxwtZP!uQUxruFI&?senmPp29{?g7GR(2w|G7m4x?$R z-sGgfV3`Ibu*@8;-f<6hxga|x3s}lFO}^`%%fCi?8_x**yhP%Hb@_$`675Wg7of|M zh>FT|$D|n}Z;b0z(2-VXOx5l95HmH-l5BRvApnm{plcj3o5x6un}aA}R7RV3AlmP9 zAqi3%X27u{rEGFuEZ=Unl2l*3P`SS35@>Az@?P!(2k<0l`<^K<87*I7FBh#(FY8XS(elJc-liY%5OW zuf_$m(dKGDqfX+e86Ab+Ek|2v?c>!#EQ!C(y&N`O>UBFT~*4}n_R&i)W8QcywMIoU9@m>TuyUrLIU+o zr>&M9i=dnamVO3ytAh1xOJo2WTFww85edOe=?YNL=H-`4K?O9v+JYy&b#k)Mi3WFd z+1*;jK%nTxJ?_yBP^>bppPegUS8I|SY|0#pP-9iqfGvlyR=J&pYgchsTgl~s7|e_p zJkRTf>Rs~NdqJiu{WvqmHp+(IRS8re;|V* z;7COX7llzLBH*4isV6QrIo=811Uca#u0lc)4)^*ux$#A5NM!#I##m6-Bo)ZdsGPbj zYpTk%57|OExKZGTlwuqG*hVQ>V7moVSRo5gANzVNwUJvc014|n*u8)0rb z%&}LKz{n8VQnAHYjI``741ktnDF9QvpRhDXU`2Il~)G-=R~;~XV*c|(v2 zK}9!|4C3m3_^Ba5Kz+q{-=wIxdCbSk61M$o8OHI9CRd0y+ zKyZbvUtt^0xWYpc>~hC?(tKE}iCVSdKVb}X7CaXoa)!x|xzl|es&H^?#og*A@7>%D z!GQnL5eqllgxwX0x@oVzK*dYF-VX_IzdiW!4l4hSaW$!t(O~?Zejw;z&n1FkTY|XitE;PrUD2f_RRsAM($i zdfIslurxZVCq4sw8l^C-kFfJ1nU2LT!##UWkMHH0Fp2rx9A zP2e5`BAN?+98L*^X6+c+K@(FKu119pV{Sp~2i*&d1>{5eE5gn|`h0X3|{ zzyW|Vtiu;zwB~Jo@8n#58 zEd-vm;v8udEY^e_9z{I-!w`C;@JY!w5Z6Sl;6@n0G_V8!00KTNgf{R(L!?5m0h=hK z7i31JWKJe!R;FcMCT3=)W^Vr`XLhD%ekN#!rW#zr_nAX2h$d!E!XYGrB%r2iz9wwO zrfkmUY>L8KnuMs48Y-9?KB^fUhLTWmT6iS|u<2zwN=ZFr#a}uBMOwr#?uB6@reenA zOx7e?hUHmaXH#aUb}}V*cBfG$rRKGi4S?rOUV!#|vhPKJw$^Vd$iEzyma?lRhbwMyZreDV08H2dDv)R;iY5DVI9w zm1b#|hN+k~X$M?_w0z!}im3{$=An7hLZY8F>Y6qx1<(cE&{bsU!5LEM!#^mfjk*kS z2mmU~LqGI`J;+Z*C__Aa0Sh#0CJ7@k8Y41Zs6URy2B^UjWU8iaDyMd;r+zA^b}FWZ zDyf#LsdDP5o~o*@s-}{`rU(NSuqvyD${ielExl=U;cAICq)VLQL&zQ7&7Ixh-GQj6 zWi81w9R;w#tG$jZ6}&1H-0QuvTN6CMt(sxq#hy_3szZ>T>7@bc zsUGVYPA)nT2FM>x1SnGU!#+0aUjAlRNa9#rX%X}Q$cC)Qjx5QRtjV6N$PR%T3<1iv ztjoS^%C0QT&MeJ>EERkotk!JJQbEMrz!Ctgn+oiP0;E#iCrCu!LQo%rUSEV5Yw$=L zP5jvUAO)~J1;#q-!@6E&c&yHLt;?z`%X+QYnk?9kt=aYf6`biMgzeduED?l?4hX@| z25g+dTiqt3(RPIYNn`*HVAE!85iJJ7y@Z|?1s-zb)ncv2LL6mqZQGh{**-4h%B)B@+#FGKhtAbKlyurK8toI#m{M@_9!6sP(=QTT?7lA49%-f#V~ ztp~Sk|K9Hqti}F<>m(fNXHb!fyzpYzilF$S(2k4gqYK0}eE?{XQ<;EN{pPFz6bvoO1C+An-!0V>>b^ zv##z9SCIJ(73>E8tP?Zw9&c_Y7G%tVaN8CEiixZi zzp&6|sNc0#-g1N)HiM=X?VK%cA<6!OT{GDDE4^vW>R zUGF(}M1n48gR(OoF@P+LgAH~>><$I6A*nqB;bf5VGb3?7qwqFQ^Fiw@4iE$_P_rP9 zEgJ1W5RfcGE95x;qb?7YP2^}7>}ZevD4w>}?igf8X!1~i0I*T$NRxD8nDjoQbV|20 z?^^ZD<|~@av`TYz*Amb-FLXFJbo5d$L|dIi^YTRqDxn%Gq82q<#SAHxZ2lSq66kSY(<~L_lF8~SJy1i?7+!7b`GAk1l}?tgPd^; zSb?R0GJu0UtV1%W%NAHeJj6paMASk+fjq=R(td+*)o4YCGUbHhODxe)3>aCB_8XS8 zX`eJ6r*v17w=~D^ALoDwCpOH2b#0HePUH6C>9#oY_GQ4Bi~+zEL_-=p!54r-cYnY; zG=mga0W`Eje>A{0Py=))gct0CDNI2wf-{6dgL}p_D1vK|=fEw%pAIv$O*SVeFIiBaap4WLFs6ij>IiLr+p!2z(54xe#c`d96EeLv_ z|M{WY`5uHyAsqI5KQEFedGE=015LD9L|WuA#3=j}0D!M{`7H2Sp30`I?*Yt*4=zBgG2DIU6LqvM)QcH@mYxJG3*q z8bmv_SG%=0`?O!XwkLZf5X3NOd$w;ovqwVR=mDiSHhe!erl0?4F83;@gGI3&Tkyfk zI-H<>gTvf?gL$ODI?yAmCqzB~fD*@!UV$@m^{dfyvk$zBt(oP@WHv4 zY>_*(SwptyqG(C)TSCmc2xtQ}XaomngEMSF7bI3DMZ*dHI{*ayz!&^NFlJ*Wyqu{_ zF|7JF{zHa9e8fj}cv}U<&pg`0Jj$m%+k1S>w>`(7!7xObBc%M>r~Md6Ive0Tk*E7@ z`}_<`_7*RBWr!Tf?Ssjo+^A=RH5^+)h=MyL(FD-L9{~SAJRCkhjGQO{fQ2Rmtv7^B z9=w=$5C$j$Qg6hW--H1G+ZTxa*z%Pht zLLwN#80>w{(x;BN9p)Z9%}`9D0G>;J9R!&R{##q95X+Y3KHgb_H9U_pZi5hgsN z=1f9|32UKCSL>m{g$*kjl$7WYnJ{elAn7rZWJw`Q9sp3ea%BTG4OqsMIg@5hn*dzG zyt$L-&YV4g24(qEXwew|ViZ+c^cpe%BD8gT!h-**0svC(DVt)&S-ci8L&aO^MV~1t zsq$U1DdL}qrElTJm0OenF>*GRiZNzuZm)mu<^~o#m~dgkhl{dxioP}3%3 zWy=RIUe>HR^JavO%%vNK(Q@a@WDq5aBoL&?lCMvuq)8MqPujI@-o`!qW$mL$cL!|> z;LAVb#~%Y2gDoCBYh7f9W$6bTK5u1iDh|G#d(BwnVl6#kte6D3^8P97zMg%1_kp#$ zcl=(ZWXhiLD`c3TKj!`Y1wwoBJHJPa|g9LOPt0i^`M#h4o6`oOp+M2!DY#u*O-k-hoovk$->5!^Aq9`mCm9dj!2 z49JJ@;K(D^LW0mF33=0rJ`J~{GB_*e;*iGnY~0dIn-H)ohovkr#*(<$!sp91*=+N} zw%)_>Jso}I@5nkYyHm4T(wPW9Jr5$|kVNnx=s_n(ifzK)I>Zt;M{9!=E-l@}t;$qWLC)CswNBoGUH! z%%$4-#~PlAF8a;I+PiqYj5~ISCfm#?ZBpgIJDGwtN|#GHmy3j;rjN za5kE!oz=!o1`Ig$R4EpWi=yqjC1#s3rMqJqYLEZkxa7(}OQ+WUo>q`S16OVm(H>lm z>1?4jCxL zXGJN_KT2Rg3DT&58~R6b<}{h}A!L0W>!3g`agM6>E`GV%)zz5fnqNT)Y*Knp0DA&M z+x$;31AJZuCkPZ;kb@CQsev(YQ3GrNB^>|QMh=k}A{+*We8G{-9?%d)DNd1!RkY$2 zu}DQVWRZ(q^kNma_{AxfK^&qHqZh-7#dslNNx^g63W+B<8dhnJyOE(!>L?c*wr+_@ zvUBtoy4Rj)SwAZ zj*^t6{A4IiiOFH4qa2q=B`HBEN=|MhWe>SuqF7iw7anhy{Ojd~@)(yrvaXMflnDmL zaTo2W$QZ_u15iNmk9HW7n%gO+Fe6Ey7f=!s-Sp-+!5L0*j+30=R6{w@nND?v^PKDS zCe>=;&ULm^oRdgRA=>4TTS6|Ea{MJQ{|UfgLI#Gz{M(HmvdJsX|r zSHD_Qu#PpQVpZuX%b^Lfmei~sjn^S0v5B3!QH4H@BT$8P)P3pIFa<@5AD4>Npe%ry z4BH6>jKd4TE|y?gT~8Bts4+0H6I2*y0=4z6&K%nv$l^w_otuE=9S#^*+r!@j2YANHU8!a{dtkHDQW70?us*dr zJnrVz!bUB!u`q0t^0v*zjATUhin6d~{%j^}`3EXkoaLG{xiK(ikBn=KQUQlqq+@<* zOleVLvD$N29{n*-A-vsSH7d!JtMgkl4A|gmStbZnpiuPEOk4;uCe8Q9mqC0256Y3w#m)c8ZKO74h9RkwE9udQ}$ zSOB{3*Gfb`9D zeH=d}4DCDPdEl5Ucv14)>TT!R03a4!P;LuRmXv_E=vK74(Z+7>xclAluJo8gwh1zy zloIz0X}`1EY+ME$CkIEk%Yzc_+`wFb+0G%xbEpVe;3X(gZRY7#qJVq+qZt;z_`)rw z@$GP2*dCX(fFm-Ir{A>GCkHj0|DC@H6PeD}7O&UIYx4=>{I>=utQc653*)4~=zRYs zyG$O<7^chn-C`!`Bh*EVk0V>8C}(!opWSk>*No;dEc^@yzwQm+9O-QbO2nI&SjTJm z?V3}1aOVE;y0ev}A-hDSL93dP`n_I3b~ejpKJ&!edG!Qu{Y;juw#rLT28>u>d!p5W3a1~+rj>jHnhHlPe*^*rB^w?hiv;wO#t_% z`&NP!xy1P6VUNri4MJBrWtJ0i{%MAoi*H1dr=rke9e`@oWMfaE-|}aM1vX&~9SZnyHBF z<_M9n3}NT;BI^T1(CL~Gq&!d3oNrg=zzU@=G`zjG-DP$_?Le5`{|+iHi^1%9vV;*JrMwQ2+Ddw4vrxnq`?=^a2Wp?D+xt$zerL3 zOi|51YL$ZF{=)185zG(!Zw3EP3ulqkYB2_{&+-y+5oKZmpkNDj;T>`1N0ReVG0JPyB>Om8q$sc_SAUlK!Ptge(k`5jr3hgb-N^V!~&lSHB3t12V z$#Eimi2xDfB8yHKJ+U4W=;3SvRQf>^2{dOu;yoA@~1Cz$u>+6j4Pg<&G*h z&nf||r8I&0$c*noupwX3|H86`xX>KQ@)iwHC7NL!@WCCd!7bm?6G_A##cw9Mz&NB~ z0Sw8o^ir@?Qkwv??gX>HT1rUDA=7G1A*=8S6*DIvG8P4~B9~_nRWCB55)8c$Diy65 z$zdE4MkWx;+zbE!FhQzv>ol<{H8pBAJI*EHjSfOc>cWi83PBsQ^ESa!HzTqvA=4Iv zQ_uKP{cOM<87d|ez&NmBh};W^j8Hl$iaLvrqnxlcq3fgugc!gRz&MR7Ju3wl6C4{; zmmbq60qP6Y6D7aH9(hhBrocF~fh9bkG;0k%6G}flkU#(H5IYeJA;WAz4k6h_@GC=Y zLH(&g&C@{%Ble7j{U)dq?U5FSC<=^29%O<7Jv2Xw(}Duh*Q~SYNOTU=WhQ5g$COVz zTa-M-@+Z;Le|WRzgwud*bb_AD9>;`7|6w24E+*tass=4cs|iE}QbbFUMES&hx^qwp zfuwM9JmIK3sq{ScG$<$Yd$v@9IMN=6Aq$R!1!h7G4+%}FNllHEO{oz(=}i@DY!9o8 zPQB4i?FvsHv`U2vLKSX3kI*Q|fge=oD`=vyPEt`BiBa3_Na@ZcLq@G;EdNw={ty&5 zKVm1v(KmmSQ|ahR+pkXvXh;{W;SvZv<{^S=0`mVk6O25^DvJ`y&bb>mQ9Ms`6X~O5Gs#!lZPNH=Qr#1eZP)G`FHbZOJwsrdM zbV@gMPh&I=$JI}tmCp=d6x?$hZjUC+PO8w(U9}BVcS8vcgC(s|1h+HC4$M0T)K*!P zTl>{pebu|dwT6WCh6*;zF2Ec9VIJHw)@XuRA$IIi7MqH+RUMTeoe&%Q@W3dwE4B4j zF*U+867GU#~Pn8yBwbtke)j0ps003|_fpoMc$j>yfmRxIgQsT8@y|yKj zZTqRYt`%LOtZ*K`*R8H{5adg)xr0V!nyQ9BfQi79iD zYH$m~Vx9N+Ow@Hd>Sx2MdexR_x%XEm7ioc&MvJCgIVTE&<{zMACJf*g+_=bva&UQ_Z5UA_eKA=!iE@|yjOyO?*gj9IN|{Wc4DCtNMUJW2BfN8 zWq7vS7g^w!Fyt45H&26Y^Rj5EHa+-u!i)#wx;8IHpbfevM9A<9oLK*Glc(zID6Mvjo(6miH3lAMgX|MIN-rlfg%JtvU-{k0IZf; zShPAEE=O#LZg*4sh1kD#e1r+I;%Ze*e)R*(1D&qdZt3}J1=YA#u}~Z zTdmppt?@gq=X$CSd%XQyu1Iwtg@ zr>{F=Hk+2s8J+*1Vx2i!HR1U>g$;3^6s#tJx{TSzkXb>MIgS4r$=H|>3vj_V)4r_i zAGkqT2O|~~!3KtbYFUEB`Z2>b{8>LB3kbCovfu{*z?N}YmwA~cC^mjCcrejhY)^cq z@VB!vd4J`MlLPi`$2>hlxxN;lE{QN04P&7`k|v(hkBxj=mgs?wqv#H~9qwU~dCi@r zam0}n*i3xOSL&Xz8r}68OHnBlU3SsXI-2b%K+4lrh98QqMMsl*-U_)&V~KO z{Cp}!om$DP)J=V*6mm|FUDb0_(X9_g$^72U{EZhY3ZB*;I+r`{SkqIvQgPf>b+N-vYuU^QJSBtU3+KzCK66W&d(`QKpDWn9@ZflkY)?4As*tP z8o2ulq@f+?fg3cFTN5A$>QtARM^CDXt(I(%=cc033|^1Kyz-q`(TG zp&kEV;uLbh3!b19_~C8=zzg=l6s8~-(qb)=zEl<<397&h-rx;ZVHMus14bSexWN@( zp%q$z@mInOsvrrD00to7Fc2UI5V}mF^XQRY(oJ^hrM2k|cgA3I;&+&&y4>nbT9d;( zrMtdUWBt*u9Wfk#42B~n{GbQ{U<+6c3;qELWP%!o5*nsqCA1+Uw`}mgWC4x<@hu+! zHsBSsfBRv98jgeVw_p3;KqVF+{I$Oo#(z7g_-aXiR1)5TRbO>y70vXuq&RKCD0~QUV2pn;B3itt&>1oS*ESX$^-ds&cd7p- za6sm5fkAA&1g6j!EFe@j};0@A(3?r2c$&qU?EUP1c{&xHMnu0jWb(x0gX2t5cCB- zpbW&Fcib z0Urbf?34pJvW*G>23|nzpile?@+ANdvCt<;)}K*gq%HyzGJ%*@7RN|LX;U7g+L5Bj1;7WgGXNt zc;JFRdFF-`Z)h>epk{pWCF!7pYO0Aza!4YDDE=7ZbexRxYPSEb{2GtC;+AC1znRV( z>OS3!sgqE4^8^dBGb_bC%1mK}Gx4;*G(Ee>&O!*%7WTolcX;cQf9*E9mqyv)b{&K;+WN;^}yOfi@FrM*P zXAIbg2Ry9N1%WgpgislXAHabRZ%(P(jpy1V_ejDzat3c z6{`r4PMi>rr_ck7gMh;l4nP(MD8UU(%%Umd5C~Y<%_1_0MFq6{Ug7&d~=`# zy+}CC!^R1@v6%~0;3LX`B48rZ5XxjGLk;uH8g>6pnzy26LAdD_korWVJt3(}fwI?!`D5@gE=`Lfc*bweiI zNnHtoQmfK%rOl%y0K&494Zs0k)UXB|+#*kU{uE#MY(fVVLR5hamKAV&gC!4w09lYD z2LqXbF^WL~y^40A2Q5xQCB#*1in!8`Pm%6-RNk+iDJXLU+~8fPr;jVHH=s z5MeL5p2tO=d_WpUe1{t%tCPgmbFqzmtWQSZQ+=)PAQ;Ho-UK2B2QhfX^>eUrwCX8e z>es9O6QIXpbl?2WxVHR-=0Okgz#J>|*nHG(N^{vJJg#f=s(N zkH%odHF$9jMjGGyju0(@5^kLkp={vj^g}+qSV1&)rxWS{6WQ%<04QP@oJE@a=$G%D zOQ_=t<|X1}tnh_v46K#`&B6a&6m()fu_*TJyX(Kv~5< zbrJz)#N%FYpe{iUPy}*=+1%)!5D#A73QQvaEdv>28Fh|#^K5;|Fz%&?f*x?lwASFm zPP)>2d|Uq(8o;CD)z#xNao{{2BGq2;-g8rh`K%fvKzK)%S#A)NbJ(4rx0Jfo7WagB zwip@6yX$jvdAIbtIRCzA;2GmM$QhlYF1r02kL~aXO7PGUpL{lrA5!F#W#W}*aO~@{ zfo#)f^A;JwE}r5KX!I8CYPV-l&;78|6XMJSVSpmSs1{?O_x0?j%kv@abN&Hc;l5Xl z015b+`y##m{sX?^AI|@H6y$i(mShB|Xa;CASx0N{7Z(DMd0Zr37|{ga@D%cJQv)G- zKecj#(*aAg0tEqYn*{(V_8{$Nf^flrJTZH}QF{!iNc4#xBtIhJs2s4+QMD*)(pjR!NzH&T39Qhs<+ zMkr@U*b@anOGoeqRAv!nhA(c=0vTve8(2$j5C|cMH}V#1vqpxScwC&)cR%-c^hYu$ z;#!YER`?ZYbcp{kOGjvU$b-ZObw9{xvX~n~s1QX+9Qj6wJMlbS#1l@)SWVyt-BoT` z_)SEBFRTDlGDi-?fC2S(Z=5KN%Y$5N^ojBpip55Ulc9U22xyIActV#L{iTD8mxltl zhqP#M>WFddsByW-ab|cPI7A;2s1rO;PjO&{-Xn--ajA_OI!=N_{aC6g$kO;Ah zd~uC!G=JKtG4}@<$z)bEmUMQQ8ao&|uqY6=c#D8&S0JeqxTtdr84;F7Ntk945g-J^ zm~txT21Ni$dIgYzzzS*BJ{Vwk3CWXJ<%#jWs(XpPV`X)W~UH|^^*N)Ts6rG9UuUV04b~2dOgXLSxI>fsZb9& zlovBhZ^#%2v`nE9ju@FT=J<+F*O4MQl7dNb?pPNjnR9N55HL^_%eaWdsDUv#lPtCd z_2dQwk$&sPmI$es-2|7YC6|JBF{G#}l~V{7)kk~jl))E4Q5l$qd6}?jd(==Dxtjk6 zl^hu)vN@aHDTLrjgtB>+>9w2yka^VSX^_cSlG%QYFb+8&hRG?7=Xns#`4`X0M>i;u ziJ|`)A_IqdX?T43Kz_NAfZ3g}Np%W(P2%~H3>p#TXe66PlY1C_NCk6EjHwZqNiuFqtOEM66I^C__-JQ8AmTT z8Fq03RTe00j3Kw1r`qqm6=De(Uf zU@%%)X)cMl6G2c)O~8|bMF>WaH)}znj@o{ZDiM-;XOtRWp>hf6kPh`l2h>?POL;2-sH?8WtJLPJx(2Ly7AnJpe}wU$mV=th+LWF8l~amrhxI;ZW$LaBfd z1~3iSfTY#v77*|Tt&nCtp#-G_2cyQ5Re&#nFb>4fsP)>VN$RjE3Ysfgsi5*uFM5iH z5D5WFu%c+Ntf^bk+ORsxuzN8P*=iHqdJxL64yH;~DTtD*#1n%R2TM?*w3`0|A+VDu zo3a*r9$;!0V)}caLUe?YsfduKV#TbAL5_C_t#aD4()zQw2BZR^4D8?p=Bct5v6TbE zt_d-dAaTx>fdCLoxS)kri+A@509soYT&qC!XJf}23CS90F|wx3+NL-9raW6@ zZR>0fi?m0f4DApFSXs9bkp%Pc1{=Gchh?|}p#Ue_y1H1pb(XLGwy(SfBbq=*wQz6( z8!D>!Dg??_X}hqT>nowEwr=~m0H6%<@CCrLC8G6w*`{hcApndh2uNkP2H*y?a0{9k zyRwV52vxhZce?-wBf}&PnR*B^`n#2DwhgD92n(v$$`cC9Y{okmdBy)i{}2kRI=crU z0OA#W_E>%01qa$|xU@Q!ZE+VD$4r4G@7&XyR*qFT=qMd zBy3A)(d zS%>gDj`I7g^sBietiRG$swFAG0#N`<`U)y}5fQ*d3CzO)0FZ<5y}A0uD_q6=2E=J7 z#4Z>jkMIlWAP!=SgGxLjOpLZpEW(}ZvwLitRP4hCA*hwqq(`#^P0)6&YXIHD3ZJ!> zWo*WOY?W#3oNK&>AVO9$_zRO8ymSnMcASxJ>Y52Um3+Lmw5$KZ))v6@*a~Lwbru1u zvg*hL;RE%g!vYn{mUqVcE6Mpu$3Yat90-E23&t>2w=B&+xmCTqpPwNK6qN`ka$}eSyrd$$8kxCye7q?9 zo%Aeu^emwO49SWjAls%B9otSId&^9~3ZuZt;Ou<4+;ih>!Tf59n}J`EV3dt(%!P5b zpRCLYi@fqI#r7PY`24o0{KrYK3QW5b9mrTvi_mGY7Ph?7(yP#Mp}2IxxW&8})Tu|7 zGYMd2vq|j1mg}i_T)fT<#Y9b9(VWoZyOpc(z^>egef$5?0#UV59j-CWcNF}q4UN10 zdCnV5Y>!LPKOMi$ddDF=)NE_i^X$2PoDdJ_QmR{B1K|cjK-C4|1E}y>HC)#Pg}5_4 z7d6e!i17$`fX;}32gankFB;fly~JdV(ZoAsqm0&*ZOUwI5YeYT)>~!@yw?N)kiIZK zot?B+oq$-auUd`1g)!KL9SH+lrakS`W!u=73)#(_*3cHkG9A+4Y!FAlq#4#-mnqr= zu>pjT3*bB4-_+N;9H!(vrT|OWtbz!wjTo02*0Np4j-AZ4?SqnC%Fo=#iJ40gXatlCEvUY@69B2M@V(cppbN-t;b(;546Se-KHVQ)-4XTQ*j?fRZq@{T+Z}!2^qt^z zTLRLz%B>s`4j>Q*;06(%;{ad=ydXh;PprpqUew_&yQzE9 z-4zE)0O|+PASIaVgCpwL*j1&zUyo75XrAT;3)BaDjP7pV)3m89V z^Gz0hEf;|O7y$3#*SQ$EXY9w0v&pWrta;je6b@SC&fZNC5P3?K6b9`y)r*$JTlF|2Y}?(-}F+K%A!pXdnR^y;qBkuK>Czm796@d@$Z?WFZzukl}xKOPT%JgzZhAMl&1 z7$~pwYtQuQ4$5z@;<5hhx*Y8=ZLtoJuItM82Z7hVaQT-K_E~)~f?x7vs~Aat_{cui ztPXLmuGUjOi*(<^2yuFFkoTAG1;$_u6~6hJ;`coP@^K;Zpl|g5^BBS)2j}v@vh(nv0F_5%eik51`tq4GtJgt7oC6FpaT46Pq`;A%qf4}ra#+3{q)NZ z>+kOP@E-Y9jUk!7>D-SHyI%hax}fj&pGLd?{22}q00a&sSkT}>gaBTs@kGbrLx>R} zQi_BqQ6fZeLwjVqE3g)hkyK|3nDv07sA@I0C+|W!u*6 zTet_ic+zF8m@d3=_3q`{*Du_#WB(q_3S@B7g$-L$w1`n-OOG!lJ`$I%7G%s2C1>XB z(qzn;H*eC-e&p-YP%PHL64>ZY#`y5^g8t8Cm<0}E&p=d7F5xrGlWe$*6RU&iq2 za#7s*bLfD@7BBofF-!l(7c)NUoYG^hbmum8hrF3QdGirLiyp1h^y#2OS3jpcyuR@J zacxJB9@d9hLE`9vKLQKntCQuF!^;r^8+6dXz^MDjFz2p2DZ4}riG;iJH1lYrk~&-| zJrOY@@uBtDtBJJteu@t^=<>r&M%id|Yrh9`3#$o1265wn9D@{6sVwm7#TZ}kDrHC} zo9rt>;;O5VA(JpP1P=~N{HUWx%CSt#lTHK^B{AtpQAM2GYmq0^ZNiDPu4iY~e`OG`-{CY@n0^~~6o zG?fWWnmSz*)Y(ckRa*S0&FxgLQmxgiTetQ0urd-{&XaG;WwKk@avg40IvfQS)AS%Q z=SyTGDzjb>L)w%*XIq3eDr>I|xW<8B!?r7J&4mhGg&S@w1tXEf%M^zzCXnH^NLl9| zZDvhKUEvsY7vC)<0%Es`I+P6!&3@nex1fXjs(G)Q^~xD5tt?)6I-i67>Ns7J zTdp~wla>u*ul&GAlqr^pXN8X^w2sP=S#FslVu;ncb@X@f%+vFU2wO*NI zmzhnov}a$87Va4fmQ!>(Nw>3S0#Eq|830mH1{{0VNk%XLwy-9ic&f=_AS|%ChaHLs z^5dI(x+w#x!2edd$mNz>QhDgvN`9&d_Q_))XQWB|IT{?-P!sUO7k_;6%QydgO(-FM zBymz!IqXaIB^zcnJ4c&l(+ArbuKnNY-zm8fXA9xr2J5a6jWj&r3*dl;KtAw}W=O#b z&}fHIM9_|BSm6)#7==K*un$vAAs6|$!cnFdJ&P@%dCgk@3SD@W6F#K{|L_<9c%hAg zP(c3#JDkElqR;>!22qGZBw`Vbc*G#$z#{2jViTSCL?}j4ic_TG6KUZIEM`%QTjXLF zy~ssQsDTq-Bx4!P*u^l8v5b3YLmS=r#y0F>4@)RQ9qo9>B`l!>NA!RiJb*+%22zkh z?BgE?c}PSCv5<*mNJIhwbv$djRKX2{=x~Qwp&c&g7A{(n%b^oBh%S{q z01!`tq+lJp7|0dC!4H0XgF@ACr9gT(1pwp&5Cb8FI}8F$VZxH4LW3ABgE!d0T2v{6 zD;zrzhY*mxO;n&G7-dIi+0tP)vyw9mrktx>tepHK98c0Yee1G@`AL1;3@JVw2*BdxRot@fa>-t>&EnwI#aJ&7WVU zyO!%>x4JglE?=@+HL(^a5C7OldH>OmeJB6`AjpO_%qkF3xWfPfnE*Zh0Dz4G0H6XT z=s*to%7zlRVtHH6D8}Fc0Xx*VNzojgby!o6+lS8vY@>%#(xQ~K(m9as7NrI0k{Atx z0UMGkASyACk`NFO1c8Zkr;ZLm_#$1>d-=W3b*^(==l`A9^L(EBW>%8Z$Xa`)QyX>q z>CwG`3`#qmA1vDreo38^ z*^;;_B>%Pd#TVLwdXM$;@JyLKQdj#td5C8R3CGV;hn>hEOW*{=cCy>GcTDAKRx)iA zqm;AED7?fhdnU-5OHt_|>_PdvN$?9Jws5V>-5hE~r~o0qWX-y2p=GA}oC9W_wrui0 zZ0?KNs~>xz=;`SaX08L-s>!)@ax-L|9lVmN=-zrPBDga>?Htq`_+u*|#Om`}@xSt| zh#kM*R?7cf%{0wj`k;u+^HsM4p7kpF`14sW^(dWKmE}l8L9LfTsWQXXgS(-Bn@6an zgS!q|-ViaAmCHBzzJAfXN{?aH`^9W4+y5iSH8slm53Gv1?Gm~FYR!65=8;aHX#ew! zwrt^VNQ%+KdA~B|7D+8WtsZoje~zYNkCEn!VQE(XcaGspPkse=pDzdG8QW|)8gAkr zI|g2gx7>5LYaZdGKFo8R`zy&=(==#+{APNwjaHG5n~Dr*XtUW?iISQf=Lp_yHQEeu zQJ`SjnN1uH{~iBNemUqe2yc4Tm#GXR2p^wxVXnM!(pn4BRj1cDmF=>&v!DNL{zdNC z9M)<|{zth_!qSEK*Sr?76G04Hgy#K2z{%jTQQ<3mQU5xmTlaH_7fVc>XXB5Q4n9Uj zELjmb&u9L%9DgN7>_kPKFEJ5!nYvxOHjxWe@$fb=wucW^ zD(@>iyhw~b<))b_=bvItl8*hMJpNMVB2l*Rz5Kvy#qd{3g)Kql56ycY;!l6vCf@E) zrB~~Ipw@!ukaFzMh*kT~sN>lnRPh` zr8ow3J=^SP4DNc8ukom+%Ok1FeL}-+Q^V&%!;VT`Wv$Wn~Ey>_%^d{j6lUI|j@*-`fS zJ@zl2{mHXBjS@Ovg5H*Vqb`YN`IyhLR2pwo9V3K`4?F?Zm~mk4lpB^9=XEe2 zGn$V%#WWam9{?++Ve;6L?)Q)>YUu%Dalu9;Lf7Q6;Hoxa@X-1IKV3CMIW0zHB;E^P zT2D8K9wG5|#r)aq`mHy#YJCIL1Mwt)1uWxd>9NKD2^S&8%@TUV0&_#?MS}r89L6>a zY(l_@2PgkCGx#H+eO709F`*9-hOaJ$0pU0#5X*;;X?1%*HFn*5&(TJfU3V53r~2^>qJKSJhZ)FvM1n?~IQ27ZK8ESIW?@u%oC6=DaH zZSauwtaxW;tZOi2NlOppidm$K4r{FXMMMlo%e1M^^)lK+1=p*5J4_W<$N8(jw?D_Q zt>#4W56w2kU*3S(?#4$4$GZnpYcXII$xzyg_a*Di&?kk8DGA)<~RI_=ieOVSVP4`@!wt!E~$NII=c&TLP3HE z@wOSsrk2pm0dNoyr!>gVcY>L_UFnoY{g44Gz7Dl@qWn(+@UXn0N!A@LOhA(XkJw>I z#LwsxzzK#ic^88`i8deuJc(E><1{Fg#}W{;jHP}Y%{&z&_BfroJ`9NSv4^@gCSSNu zwXGB0U0P<70XaOdTz2}fcD{&ZzKd6nF5l^}7d?JYHf1;X*y#xHS%2SgAu4tWwF;ez z#!kIGx)z>1DZZSpCPQJ#P%f@qZ{i-mZDHk4!=Sb(ZCPM;_h?A6Ao4skpYNBC^(BWj zVr&R8#?_dy0cw(K6z~Wp(%y7dOON!MHh_XOKTF28pu85x)!4D7rI308!6$pRuf;mc z8tTd)O)eG}HDY1>4ij|((JunL5rj-KsFW}|Dy{N|y-j~a1q5X?Rb(^6LpD2U6D<=L zeiARf4)!>SS0UyLH=jYju~7XEv;nl{2|07qtL1BxW`M6?<14}F5nG_Ta=B>scf{P@ zv-zTm@(ydr%n>R|hGUT(w!~w*lVP{Zu&^p@*VJL>SM(r)Yn;e{1w`K1SR%fWq8I@v zr+iY|kr~@PnrD`nTM9|nBCv3tl<=PTXe|gmV~VmpMi~z_3dZ!r5t627qj#-Yir=~s z;$PHXU&bICwI`3d7$cXMMFxczA^T+zcU*ilJenWY>m?@W#5K1-J-_rUnLFO$){rjG zJd_vtbo|9KyOiMM?Q!}=3?$I*8YsgGH>M5`?*g6%gUesqbLY-dN@iW9Yi#i zMTs(F4^gpffpeSKP!Evt*AEWq_F>ie|M2;=Bm8p@cDZEF=x$ ztra~mSZab0Jy^yB!Zd9-u(rG~I-@@lJlL~oLGMM({xWpmB(7P1=9^-Y+n;B4Qo^1F zx?aVYmZy9*PbUjHr`u#)fYLvFwk~LbGk~p-$e#F`tBkj7*{tRwwsd^1m*+WUcz_6u%tn0D87$RMjW{TE_>PQ89`m1Vq3urtIV8?#-ToGOhzGoSGLwXZEaz+w+VkS6xTGPB&HI!qR zm%XXBmqfOWW=te4F|NS4DItb)H^wa(I(5NUp=e~A79$=(y=P&t%m`B!^EtHeIY#=N zFv5zCV+6AxKGnE)u@7V&lP`XvFGYMNFMLRBc8()`$^>d3=+;W!9Fe=g6@_@;K6tWJp-` zk{13}u0%vT_4{YxT0CKW~q6WyeIFfX37Aq+BA{#LoPRYWw#m;GWb)eU(ElQ+c@`VvFTA_2gcWOzb*JcP_)Pd=Pxh1s<3dN z6t(P(#ROp?HBWSn1P|{iAIer8$ooWVtQ}BvN$CHsYrT+|5<8U93{Y=7U=!8mvL6Uq zC+nd)R8cg;cpbXULBNG97V7ppNb+Km61+{$Y*v)XCI_X6w);n>6V9d zuR?mXAw7qYUJFR?9i$Ht=}Q~*oHNKzG{|2$D8Mi%&@N~>%L*A46rB2xOE(V7+vl7f z6h0gjk;)Ug5EMlWLUrFHk%^01fhaP=9=2jUxc0%5BtCddU}FHl<>%1e_a^^l4>D(d7762u?p(*q4Ejh7a7@-;d!KEeF+3r6)c4AG-vARr?Yp_eNo-- zqC_2fDu!V$oY%>s&A7ks-QHKch6Q>b{doE_MeN#>1pIji-%0r_4}A3J8_rdV0#n}$ z;2$l}NafZq3*fnj)Xh^(z883Jvdp6D>0nu);IB`%Z87HB?uj>z_Wa`X%aOt}U%VIE zlLdoB=9iT?nad~-3yf`JEA6{Mjug=fUiD&=L&dx4R|5sNh2PY>d|Ni|W9v@#G9}|y`h=+%l zM@MHzM^^_2C;R)vqm`?@-^a(tM@L5o2M7E6`+IwPSKHgf?a|Y%t=-+-ot>Snt*xv7 z{ySY;`}_Cr<)1m?TJwMZ{kOKZwz|6d`}gndrT^8!!otPO%)V|I3S zW@hGEU_3Q7_3PKKpFe+2PEJltOpK3@6UW9*uaD7D;uvadY>YTEayl}6I^2IaJbX4V zaM9a)(%XADG;li9b=u!?+TDHF-F@ECd4~Uf-rD-_`el+#x8W+9?3>FMn3Y;SMJOOz|TwPsF{P>Dk!ALA6Cl-?sivZ#W;HsSM>LbHdDg3G!a#CJ= zSeHuB<>locukD~ECB?l2i7QlCRR`j1&(GJ_*T=`_$lc?_$>zw$_QX=_$i(DWN9*XJ+L@w4 zy1l)Jhli`HtFyDSgM)*eot>?%t(BFPg@uKwsj0ECv7w=%zP`S;wzj6Grn;^E=p=H}+&;^O4w;sr6B837BO^UM{f!$p=;-L+a5(LCQBzYFenrXfk4Q}$Vf>^ zNk~Y*U@#E`A_4#>2y}fXz=!|{#->$``;La)q%ia4?MlSJ@91P})f99lGCy#i?Wy_D zoyzs_1)KKg!rs^Xre&nJekXzB#2ovwwQG3?z@l0xLT_!!a2^6p!LCzRI{HED^*x)u zx{u=}Mjv!?bn5S!-4LZ9%(5H|v{l*vc)_mwrDCeqb-c``|4ZdegYWOY9NmUbbIrjA z8%1I9`g)2fyNrg&!S-6ls(ZwowWNxy^R;*2hKwris)_r(8I2= z;%ixM#B<5NFFuKeCExz~Wozc{RZDeWbHmO89!<$<@U8KAAzFKu@xriczm4jTSn#&= zS-^&MrQF*SU)Oa8@sOV^$%$p_XIHZKlzFgB#k3KinEa$|CQk4DavS_Pq;Qd zmKMvoe=KbhLxe^BBr=ve)s8(W&21=_Sw~`6I#em~O?$Mguer_KYI=CfH$O|U%P$lG zuI^xHfQ6M8R4BlH>&vVLs`876pS>!r2>xC9*JhRwktVfb%GHn--a;Ljs{53v+T%av zJFTh9GxJ5{hxY9eWa&7DC^F9Mk;af$j|A;$A2w_!Zcj5k54=f~w4_x~L8Xywq6(_o zE;2p$dpTa|%@@%f;z8dbd|6_8Y=>}A=hmN!+H?j=iYm(jE;X#u>YwuaeOi2#bzz!e z-Jb`=1S=K>DC)y&f84tB_6W)3IQt;N#=qgnf;A|~NUUvh=5WljVe5;XN4aJJ!a`Hn zf57}<^3kuxePU&KoWl(LNs!|VeU*y%<^#-hO6%6i?=&BV>-9xD8_r433)7gO0@pim zkyd)OK-IvVmIwKfL~4f(nW_p_y#n09SWmL1_xV=if>m>xKZ()VYIiAj8j0{kqRkrk zWworz19ZyB&XZd2vker})$HQ(W5e;Kf!B@{ZLilvu1JvOKV`-J^*Ivv{E#Hf%0tUnf=@srm!B4*8W`>d@T+5-c-D z-fUD1h6A%7G(u`hLJe9wTso7eMu)!h-e{O1dNgj=u5OZ@2QFdlt1EyW5`r=79TP{Ga`|XsiEZT zS>lL;V}(=lA#4Hd9CBi?+nWvv>}lK__X2V$_pkSr>GN-L?czmHAR#C{DdyMBr}ov- zH#MY8Uc%9Z9VpkvUoBn<+5?5W!m--DI9dRTNAqiH_nExgPcKkFs8ZmR04HyM+Ky<1 zyErW^>@IUXfS|%kr8%Uxb9Gy$BR;+C9?4kZtb4w2aOkY8!#nmi{ME|ckQ0$#Q>9)x zvxQO(vU#51Kdi!hN88+eF2tq^q2!kr8d{4BV{|FcuNGAgpOO!zrC{UpT{j4QM=w_&v^Y(7OLb>fj zuUZ`349z0tY7>mb-cRyAEVIn8*8K0Fx1a7|)_VG)jyb^u*j(gvM`?>eRR@M!e7L9( zntXtLV%_)QQsvmv;X{fq2$cfPaWRxxjTq1$G$z&MaYQ+Zk6N9T-qZz2 zk&Oifrouu}x5^32ERV{Gy@rqeGX)-4qdADd_RqTI;Eea}>6h_PxlrR+H0mk)9$uZo zcm{1>@q=SwH`c6ZD_k$=$Ud=7zM z|AGeAF?THo783nVe#l69V;j~i&$9{MA&EY=R@VC5niDo^_$oTr?4>IauWs2Cziph* zYq~qZ-zhSuZQ|HEiu!ckO@aKgT0F}G$WiSBjbibuf1HYp9~1k0BWK@Z2*3LsraFQ& z#NV)cu3WdjtNwfP{lOU>In3(tm2^sNLA|U?oaI+V<>TkMOU-|{KZvv+kfE4PMpL<% z3VKu~W0DoSb+dp($fdh9~(A+l*~E^zR} z##qD{j@IxHMSpS)F8eaKmGVY(^gDIXi{6LcH{PGe-yybb6%jpm=2%d)*|{qH9^toX zQ9r0VWd!PX_FkFTJ97Dzc0&PN0+RU#P<#@Pfb{;f=8gT$ks4ZvGe|Rg&E~UCdLR9- z;%R1o=+Cb$p!;XhRLbMCs$aFp06*_E-HL}?r7~TJSoI3)Z}rqfW=mO_njtS{Qn13U zfrcW3;639AE(=;(K|>vd-!&|}>mvRYcGMn)5PPc8^=|Hg`4vir7*=UVc@+~xiXC{7 z`dmy6Z0(yA#S8}8t2+_lyQv)4-!fH9Sl$T-I7|Gq-8kCF6&lgBj@0IibAgbRU(`Ep zp_hL%peWcr-i^UGcaSkOTCS-XnX~Yh1&=i$@-614h8)Tz*W^WP`Q(Ka9JF$w77`ZY z45Mb~IDxJO1CsCDb1;MI7^ZX;)(I6(dQ~Y2c#$tPX$^ILwGN-Av_QAncBbOsnq<}& zzw4=)BOm2x5b~T3M#Rx_pU|G;XhZfv-C|U#nF5jrv=I(LB+)^k-9cb+ipYNfT#usU zdSvix#@yY3D-Pf%9qQGG>JAbb&jK{u)E;@RX!x4Jm3L`BlLE%q3`&A~x|HHuXE)|X zKb8^b7%qgJ5JJ8WLiolbP}EJh=Ul$jog*M}6^hj~KJ_5>B3uAaO^GA}x)%cyC(-iE zSYH3AJbHk^7mLlpzG%cI1!LWb&hSJ&xC2jIt(k5^x^A@R|x- z6t^0l%kpCfEQMkTjtnETV=~DTmdQVZlgBJUygUgug$9xY1Mr@~o`m61fZ?f{;nx-N z`4Q9QYVv{;6a*4`Pt$I=;W}vqgpOFTt-nbB;K109e0zrxtV*?GMEfhvi)7F9*q3Hp z3Ow%n5#6lUR+AbnFSX;J|#A{}q6GobPYp zMs~9UMNtn>NrO`RnS6=~dQ4h&PwhP>M_ycL@m#GtE8j|YKfUviJbGWoJB{aY`fAif z+!FxzID7RmZW6g(O@m3xunhLT-y3ctU{}h|&y9k%kWt!0-K8{Mdfa+zHI})jB{oE6 zbIE6M=dsO>zs*#=&FmvMk3DVXNlLVKdb+g#q1Nlc4zge|SNY!8myI6g8JVv_-U~Rs zUo&-CMZRmf_1fq0iwd_asq1vAJ@ktP_3e=?jz)*Hg!dyK@1%dt=r{Iz^yhuX6+k5!y;bUT#2UL44uUrjnj|&Jk|mi80|Acix5jrSVO? zaV#Rg3leOJAw^V28UJd?f_I^42n5N(Y!;Y*)mxJNgf)H2^j*Qd0=crnr}sXDmX$s! zt6UE5m?~D>C_Z=&grlHY*FS88vF(#W`{|G0n%ML1!JYg{W8C@LpHw_ktq3l_eJXpW zw!tAS_OWJ!wqmjL!OM@DO&?p{RZ8xa_m@@7^?evPt6Wk61VTw1TtB`!(+_^47Ft%h zT_#U>=RlTOzC=-ebXNB4KMt8*sJ(r8OvWdc+E4Yjs&<}KL%vrYZ&Z>~exi6^wRIa3 zj3D)wtDJc93|#&Z^1dcQj{9J`f;zG4AIoQMR*r-aC@VbP&M3>;p_0cxilsRd_P3f- z{z)QHrN~(>b9g97h zU!I7$AILu8~Cdw+@Ll8mw_e;w={T8GN9fER`i}u^@D{_!9$9a9gOex^;^>8o8 z5e`(2(3Xour_wi`NH;3DHWtrlpMLSFHKXxfwDwzbZFyMr+^WH*zrOyQ4Ppch_9bCJ zd@%umi=sty!4-CCU4dqH`G&f%=1KW$AwWei4hmU>UgD`} zh`_g1P}2{qrp~bXtaRiY6z~^-uZTU`?Y^nFODl&5uC0aF+2*t6wu_mzlNpfz24 zPil?-M~Me};wir2iL7|43p^wV4_EkpCHS2_{QH^5cjj++ewG@lU5eP^@2uh9xfR;a z1xX5Z<>SIy!Sb0i7Z^bGJnQZ&VEwj2*+0PDKdKizUeQ=LLUS-e zDY@GJgRKweS@c*qH4~8?JM= z;(YLd&Au(R-j10Ovh$H8>oH#Hp_}@n6LeoJ3t>*sN0mt&oHq5`#GJ~zIb#=W17=Ob zvg{nRV&#Hd@XuWFZ0zIYdwpD9t&)|M(#c~6mlO9c2aUFv-U$NN!JRSJ2=$hsLA`pc zRIhGCu0H!HgZ@vQurbpX1}LssnhTydLVMmg2^)0OrXFHFj_A6?O zefSJY$^~~Ufsu}m-rpLah%fa%CDxpKt@CpiWQfx=xyb01&L{i*@iU`d)AoaEVT03ewx+|Ar+(?*e8W^jQbQ5o4j&Yr9*%(XiqSNnAQHO})03g` z%XztznUjbGI)jC2n_02w*T`J}>;SyQeEMxO$Jp#qj2qP1TFhWukbF0NgM&a!`q@D} zDoF>#DZnpTu0J&v^CRFNlHv1d6yK_8ro@tJW*2!4`qgYJ?-?wKZZ8vBmW3i&OBCQa z%@lIEzh#C9Y_&HP<>ANnv_(dcH%7FV5-a?+D}%75i9=hABGEm$oBg*pN$7wUhWDRr z|AX!g=J9^~<_prUKp?wyg-GKOA zO42;pKX`a_Oy@WR~disiT+I6m~D8#5O&HVTDcj%vl8jE8gl+<_}`4)VS@Kr ziSkL|_U=Lov|A5;8?lC*pKMlcQX;mE^rc>OXPmd%okcHPtomG$i0_l_{p=C@kND{% zbN=!R&6OMRGH3V#Wq4}KxnFv9EDkyb=n#*U)d4CFHEh~cEw22TXY@D@Z0*iYHv+ebuxu*T4QgS{?U6!u9;aOEB+xVn~6zkQ+ChADDh!} zhD7M0gGmw1+ZgNUwW0V}lQVtF?|W{hXe$Tj*&cJD?)Q#^x$5sNww`>^>3=u(_NT}A z*8stS$}owl`R42V)A!m=hw{h@xozqfmOO+nZVOWJY>)Sy`Z8>k7+INo>}p?xg?=J` zSG+!&t*o*2;kE@%;0`_VyAPTPy%h3lJary@u6cyqJ+z7M%_YiNS;R;dPm8cy?6 z@ci!t_FKQ!jcNo5t(uY00akTK@$5zzT=kz*qF4#hj9UaHUZCsxqFijTs(nOFA)&cm z;Z&0W(8I015A8FKi$xDH|6vb`5m?4ae@bv+w++6JP4?U-$Gl2l)DzR@dE;cleK*WK zt)2Y!otipxjpj z0G5L9xhB5+Ke9Zj3LH4hh@k|vJn8Ja)!Lezab~@IgBQ@A#mK_@Dr!w*)}15K3;FHp#lav1jfS zFmcI?LpEr8ym-}T&SUo1G_CFuJLCPJ1w^aF;mdzxr@+y&i0(skh+oyl-Fg0qspIAAz!J)XQP>ol449FOar`72_}berS~ zkDiF73NGeU9@z@+NZ0jbs#I-E;IfUS)``wGp#gJeM;xE>#-o24Y34A^3;&pS_ zo@u~hJy4(*Xb(SG5^CEfhbAA&LhPvdU^s1L7gb+yb_)RO`QJPYcR922xMR{7PW0r!S}wc#yKmC`m-9l1IX7t zR~6tQdyl@aN`gYunhMBs)_um7EIW=wZJ zlPM&r05lHz%7t7H#ar(pU0*V>ax=+twJb63xOR)Zb4gQmddTtjgp8Jk`!4sbk1s6M zoVa<4zAyUHCE?DWGV{o4C%EEif-S#4EH-7AQt}J)MQ1U-pFjz)8NDnCNat_(t)&xM zlWg_g;l!w?h~lL&)lY30IBPUj&DTA%HHk-ao*-s^j~vvC>Y_9Hs>jRl+PosRkWcqS zXGoiPaGSf4gqQQx7gsGHYa+auTCqn9TM1^#vUirdxiXLuyZfMRvrtlycR0i#mNIy^ z{UI1dHJRTLe#31}>_g`eX#|L+AAyo%xW^S!+>yf=Q*sd_o0l+FRUq(T`YkzpZa7oHydd5t<^V(o;s@pXI(7n5ELy)1CF<6T)a<`6!#GzN6p_ zMhHQB8;$)cqy2NrpuU>Mu`<~CS|FEXR^P3t>npze#3SP<=XFM@|Lu20hyO);(R@Tm z=s6qz_j$7-USF`o7L;tu{p%YAg=l)#`(OR>$DgV@|58|$_C|``$;ZX*@U>CS9?A*P zjlecT$im-WnRv8RZ+e^0ozH6V#wIy(A-r@gY%jh%YWpDUTc^56<(d?T=lqo5Cw$}a z=q*WeauM+WfA>M^LzVZm+G@(V&*v!Gj@vD6J`a8ZO4dXXx*xr_z9XDr$7w>fsCqgNN#O53PlLqn-Xw7Pa9zpZAN$#UPdc$EHQc7|S>z{PgNuh#e&#Q*wn zUmK5e{0AOT=KbjYAcKTAx50mImYrBdUe#u~X{oMX9Ns2n?%A0BX5YRoJ)~01W;&YS zqJvf&rd>L~-BPqs>Ax|;r-Xeo5uQ;Y^sdJ$;1F?bITB#217*ZZKDMB4C$T#2(VDM| z;X4(d-FTh%LaP3yak7J!)mGLB@US8yqGw>@tSskPqORZNsSydzb0rkU{OReeThw&m ze6C-i$kuyJiNL8fWKZMGSO2*-hYWnp^t{Vy)HKd6HyV+7j9seOcxt5&^AwhBB92yW ze~>$GY41AvI2AT^Sm`q{1`DqCY3VcjP`6-_NG8E3xa)s2JOtuW-MlBfk4&xZ6h*=c z&Sm|AhwGQMa{}w=LCMU1-+qe+-RY6l-+v{@_TAp}z6kpbM>iC9RZ054R^cHPdN>oA zl--wZ>UQr0KDPgc|H!6)@WZ4kbpXxb`^{DJ21P$EmMvI)RB#*~A4yOfb3@WWwIctj z_sqrM3C|@6LdaOtYy$fsiNsTfzWU!^w|q*@3A9Sjt#k!y->YLubr_MY4{YmXx@7Cb z@D8`>TgNcJWW5+T_cI^ms@~$y>EYPNo`u#9_%|#p$h!`4gw5~1H9Si@pC<;FTSe~C zyUUz&_{F$+O3zon(Q3Rsc|6A~aqD0GWu{71*uv}9L(PR2TgdZXJ=K+}9_;R3)ehaN z@{7}^#{v??@CXq@h@3k_W0yzkvdPwpyauLIo zg&%z{KuIqR3eW6N{X#=pLmQxC)335Oqw*H^MrpS!{WqWZe{CBc5>vGW8ZyGH7h-Il zc*aeYajV8+8Pv>1j9@~I+oBXlcsmm*p1A|jcT2FF4$Hx@$-ZiL8)VPQBj zWE#}g9u)DRb^gZ>g$r4@S;EGRSOId-R>3#!i64dM?W?aIpwoS`6(W1ChV0()U7j^FjOD>bv7ADQzZ@C3L&-p~&63g16;gH3B-szG0Eo zq&M&w6)_mc2}bek^T@c01yz@7M^jBBpSUlI0E@XiuUL5Bo-MC-pxfc%Cg&O~_t;E0 zMhB(Z2<7xeNAa_uxiAJmntXVd;>r(}J6-Pxa&*Bj0IeL$x>gZSb!>2U&nd*MP`yuE z-g7_$Bm@o_!36pKc-RPy#Y0SkvHyXhIZmML_9$$6PeNf2@kL!vVnu-XYp;_g||Zxwp854GQt z_TlQZZlN9+uR}Q8qv=Pw)hNDM?siZ3@j`n*5BTE(cR^@1t+)VeSQ49V7P^|gzvgcL zXNmq=wf;J@{(7hWF9H1xvHgwd{a*|Fo9g(^cCKVZ7RsL2Bd_SIk;5(I`u8fYC zShL!+nCtqt(pbT_ED)=cE?-jAbL*ZGw;s&hzPD_BgBQK&hXZdm2S%KLXT@sa?ov550+Ss*qlJUh68h5;I+{1*LJ%0D?+96*c9C0bCVRPJckI2l+z@NL zx(z9ceZAA~qGSEt5Cf%pMsW46?h8>P6|*J9fQv#7ydF#oCc_-dU46&z1hq7)+4uFc z(8HmXjusOml3V;S*WqvVk7RzXBoAcb4bq25N!3GFR2`hiCH^V_ViXjFA~2~TNkpye zjW{enD7c#R*zB$x8X}))n02q%iWw7TiE*&J_TKzJW?^hyL5B238=l60?~Y{fOS}Lm z{2d@4!bSp}nD)Y1_LE?qjc<8n+qT6@wEvF8`KiJf)OjZB{wgH+ex+q0LkYmjoyJGa z*`yM8QOHG7D)T}C-}*c1Cd*E@{0Bz;6~>7Ymj-XSa%|>6@$35&Yeyx@G+WMhFtc`Sh}pb_IwAY*gw zGv&ssnwLC$HW89N!NWe8Df5*yVqA7a>Pm2ux22}+*4VbCpo_1fkvfmD`M6x*Sed+e z=DL6=yh&P^bj#0(_Zi|zqK2q>AsE4{+Bs=WHu3fTxa8{OBYg{X{RCt<3~Cu4X%ugz zZedqx_BiLK%jtxxB9BeIh0DdH`rKruC6M;D+3za_qn_qT?fA3H@#8u+ewb;X{#|5? zg_p1qx@h7}>8IM~Fad(HMu&x;q#E&&-dze*DAgt*JHW&e9kaj;GsiUMI} zXLX*n@z1UGxoteNrO#&Gk*1rzX#`=^lhqb?*6RL{&!d5&)`fgLLt!1$~4Y4J0hXMyaf%QtDkl(WsETi z%k1disG+8%TvXVvXIp!=fXyKMH)oyB^+6dYj?MzPtz#U`N0wJ@t8(O4;%1*s*J$i6 z^nn)ZJ7;Mat>?C2o~p7V40EKBi(59S}o^*k$E!{EF#{$7(z2tiu`TCBED9QZWmgo{}&8B&R_y2TxDjyah=q=2Wk(GwMr

Xr0uz5gGu*sj$4_mc0?5!pP(4j7?eB$y~L{efB}aovjr%(fC9_%L%nT z38z}mvdQX#Kp-rfXCUtdqN6vbiYClFcO^~+*ZRW@Bs zz!+=kvU?)!vWUnxn0FR*FEVhyey8iFz@#i%ZjF3;1XE5-*>Jb`nE{Wr!$Z9Yq}fv?P7!S-^b#Z!oD*_EWNSXi@hFmKWD~RiGk26 zS?g{r14-{nbRH2>yb@@QUzI9BSaE@bNK|FMywf;}IL#br*u@ zz46kkzlLyBzPls2bHita`i+lggaUv^O(a0V*`3{scM{AK=rv(XrI^&LoM}21;{R`8 z<)C4?O9HvSZ^ebnz-Ue|>LDEH-R(&wzy9bcp5X;bLnYmKbK!;k85*Y){?2i7P~$Zz0Dc^a4vs7o9kn=N1M;Kz%rzN_ zZKk2^T|EfgKd>wGnx)yC7CAgp#OB^00m*>WrNK)E3!ZUZ>2T)1Z`TQi_ez!9X zpYJhpyXf#X*9~s&`vu@0h$BB*f76}+75BY9oI+Lh;qQ^h(rMJKPO1w>PrQRZy`rGY zijHpFPh~vhTlkg16~E=3AoK1{&&Ln)eRu2vK(<&+z=(H_NMWwjKVsjKRiNF!Ckqb{ z(n#Be)$d(Lv0|G%BO=bsm_!ZC+;BL(*|g3Y^FB#m6rMu3x4wN+G5&~UI#)hSxW zUfGq}3A>{qie!}%Oh?3-X~Y#spB3!TSkk7FFIL~y3W;xL5mkmUme9X#JAGSns@XPG z+Jj~S3$gK>=Dpd7P$qxM&+-&;UZ;6pSaRa>c)o-)wL2{oO^6OI4GryDc0(Q}VzAaj z=xC#y&YwXb@4GLo`C=6KTit?P zZw~*fuG)Fc1&XrU!vrOM3CbM&E7oau@v1S-ih!}nx@Kd?5e@D8vbw{Bw=eC7B_M=llQab^}T4j3+5*3K)4k=Oj!R{}{b zBxly$XShcR$aPTcA_$3%>1HC@;)Gec5w4TXJ4uK< zz%(CO^^;P_ctR^^5r+3G+2h1MIxD+%L+sR#b1Q?r@mLpMq(&XwDuybZtthi!m;GXv?t1A{4w~) zVC>7l!WSheawgKl?BV-T4qRr$$-SAXGT(+Y)e-&%%c$lpAXu(Qi|fYtI#k)B=5sCc z5DhEt*0B>KKCf}-&S*0i_OON+UH(2& zZD)Gras4-Ud+s$)ASuF3v^a%1<^YlwjnW7VW6z29pNXz~AOHllha;e&fRCj#FMUF^O`3GBsE9p6__x zQVsx<0p9KWGb#KlbPsN6D_57&uCW|A_e+y^GPK(mC%6$9_>G?eklVc;VjJT)E)zMu z2USU_c5ZJdq8gHdr{E41E2TopC-pG`AK%9N@WCGo59&8f2oam~fbQwaeZ)OAu$dPS zE87{)-{8HO@oq~mAcCY zA9L7i`Hj{(3!`#EIrn>nkoRvSy_Lpyj3u|MlwO)-Hl>hKQVZHlxq5y z>23l4DIae3v6{09#^z|PTtoh@Sdhs50_XHp{Xfox+v6%znV8NyQ$joKOfr>Ot>(3% zK|7MBM8wa5b*}a!U6s3xrr1PA036mwL0LVUS~}$Zn0D9ZfNkz`6N;$X8zK`{U#aYf zfDX%SJC<0bRfR+lV`qCUY*qxjn3$~5mSXOjC)_CSZm#ncQr`P6MV04fA3jwNQbkQC zS%|?+pUo0+{qqL!O!Bq5JO^V#D&x^U5=}E_wB0Jw(0iwc48OKfa<7LMHtWv#c-7Hz zwy%T`CPQZH2er=6vc81}tZ`R4>nWj3wYc;j6j%r?3BDIy`TX2~qm`4Kw};mDQbn<2 zPMd<%YBkf6ze#}kNQ^l^c=}>KqVa$3$wNY1@?Eq8_v{J^g6W@cxM?~Bhxj;tev-8O z7S9D)s`u*6b%^+i6`#h48YMr9#vC*Crw2O$c@mv;+xebPaaI{px8MO4IdEOQZmlzCPpIo>&)$PSO7N%sf{T60bbL#m?^10 zWL2i(l;I3v?6ljz(%8dDEwBz;Z7hw(k@zYPUX><-bhw0WS)9!FdChH4sSnzF$@DAL z+$l<#MpvJrk(ivw@;ZHpk?#Q^s-kB!Kw$3Gi~zdSCl} z+2vqnBBSXdT+u$l>C}M@+c=o(Rqr80ePu$T==n*Rw+C^h%}qn-*Ek&)4Bua8%R`5f zKd`pUR|pg435cWwj?{Jga_zfXWrvVQATm9bWmS!5A0Wk>Gvc2F@<(&PG>J#b%j`w^ zf&*k2xE~y?&5S?{gvgE_&a%CGb4Q;clYo(co5}?k{NIp>G5+ zeDWGYGU&4QUd0*yeg5uc#j34qYvIcdvg2p1o8n_i<^KtZI7ew>$DvOn+IPnfn0UV; zW0z8jIkJFARowpb1_MI!iJccY39gya`6vGh;Qd#BC($E6x-=3m@M1~ccGeN0{okEI z;;O&nPrD5amAXxSAjqYu0QegF(@#M>pKiSj8`~%DF7C?=^nE6YqC7R^>`2$+ez48G zaY{egrY8Sjv9tnUYq+I$P&-=xlHZ0*wy5)Y^3_@P-sKPVTLV;Vj0wV5sQEX4+fUy? zuT1VO!)MQdk#^`CPHS1{d@~jx#B9buqCmzMd~3}q_jt- zBep0aekr5K!*u@nMC@F17%64OirctH0--E=W)XlGmd*7vpQta^d!SR@J-p93Tzvop zICn`KEs>Be|9eQtZM^J^fp?b+bI(W>vYaiCGV%}_QjGAK9;-8-eOSdJhRyhaD!T=0 zB6#LFM!3R2xP}`UM5NHut#a8#Lxm#76R8e>C1ZG+r*r=%EH+S2^B#52Ss+YjAM;Tx z({?2@_)}7*M)><=aRe|2P%}aLn4U|MRE^KFlrQmnqNGf^pbQ|XQh z5T%V^3KVAlduBG*+PldZNq!1~GOqE2=uvd!GfqT=(xSpv=Pe(CKoTTX36BI*hhJBO zN^pd`@^pE*6GN`Ly^;Y9sxZV6P7~WHvTMiv**mIQM3k+B zXAeQ1&=XG^K{K1p?>l$J5F`ChJ651XMubg$HcXviQjlX%cLS%%kRLH~CHcH;hRIOl>zzn4Xw$37GkoQi<8?1wG78m{a$iOSob; zYwy-1&ej}?^>)Bw)K) zW_u{`_`K}#KLIppIhv*%o@XeJ?m{05z-M{k{N)ZBf{wc7j&}v0%$Er$3FwJgl|&M{ zN_6JUyJlq$*6;u0>&AEAmoulHUDuxKQrhl)SpLIGcLQ~Q!;G%XZ04!KlAz~@QqRM3 z{qha+Q+oN!P_Ky%dKKXI`BR_NQeTO8CLN{E>Kva*Jh?Z|sSo7V)8;OWWr|YR2v3NF^nyN=jp%kI!s943L)U*~H+ef}KEN22T+uyi;j#B;1 z$H;3ZX-{)*G)3HEX@+Ivh`$vm^YvD;ky=G3PffR=QV)P9QsK{+x90=)aSAhAs-yWl zseSO3I5{zp+0>f&{KT8JT$02zqtb=^+6Dha3kwmQ89aQn?VP@h)*NmzH3xcFSIhh7MJXT#DRI=2kCw{D)-VV^dlt4++Z&!QrEdXmy8qW0$qk zT~RYVOsp1YhvFe7cBd$jt3|}Ma~}oPKoj3ZH;lU3No(bCMN(kraeZ#O(qgo+)wE2` zMl1+d!)`j~A?sG=PS+ZVyJEPt>ATx-=u#Mzs0bES)f+pl+OT7s3{;uA=hwIy)boC_ zcNya)0qL>GU*0O_zQSl^egU@nF;=8@6LD+iulk#dy<)UG&qDWdFO$4quTQxR_9t;Zl5JODegos&;>Ek*9loaIC*Lg z&5ju(nb-Hj-Mfy`$d$^1HIHeZ1!MOvP3#ZW5+91{hNBP1Y=3*6n1-Jhxa(z%D=s#0 zz3`-b!Ezd_6TFy3f$vhB(pIhryNSlIQgy4gXiLFM5E}@!b}*8vOL1W)+&*hne$hCn zOVe+fr`hEzO+DQ$ae74*Z%d>_hm?^V4EfOa_xzF6i}kmpebJFD005F40MWF7l#V`- z)pv{UJEG*}Av0Z|&N5ugQ4CJ9h>#lke3v9<6Eu1RQZQBph0yZOvLtG+AFYNPMCxVk%~d| z58LpIzGs?o(?Go~<7EWv&u6a(e(nBy#-;dCmbsUT_^zn8TeI&x{b$`%c{!PN>1EzJ zhke#v+8%+La6}NG8WRTg#)t%fb-@_+2rxP36p;?TMb#tZ9xl#auzAE_+=4J@Yvj!L zdpmGy0y(p~h@ig!%d|+LqKR+z-r7lGkKXkNO6pYq$F@X`qDFtg!QcCIKNSC zOnGG zS%x&lz!W!`^lyH)>@ST>aPYgaQs9E1u2BF`MKM!DAN`@b9okpZLej7s|3@3i+MQ zm%?!RY2v#q1m8x3SG8Mriyk+$B)!rT>(pV9{Er*8-@e_z{;I`66?G*2uU%DlT$U8y zBXQN8(A?Jc{!cH_RsF|{+Yz{_okl5bVo=@~tIqHCZb_!cDlSX#yQXAtN8;Y9%1hoxHyEXT1$HDzGY0mxON;C8kwDIH}gi~GY zMbmwCK5*mo$DpyaRqD+W4$U69f7%?0>W=CE6%|}(e3U0`BoUMHcGvF7EUjHgYnzZ& zp9sHdAt!{~S|k^YKfaybrMUuLNxL3Ta%+DayhwPZ7cee+`ng||`0wu3sAfoj@xMh; z<89+97-l#xq6ff=q=s~i6V#;WJ4)WE129QV{No-~6z6+}#Vn0Ce_t)S1Ro63AH!le zLLYkbXL4dA!ya#bkdYw{-F8 z#zAh;b#^;-BeNv!i1Y^FPmOXFotCCr)6jPdG(G+hSN-b!!mOPlXz`i;Mocv*(#=p| zB)Ez?KX`O-bumU|@&0jV6r-ww>*PB}JEn}#rp-v@`&B&|s#%^kZ7+^TKbXR7D=A7qyrSC@G-P|`1d2_<9J$P4gUG2KK-cjN{BS|7|OoNL!|mv4`xh;si! zLAj*q`JdJ0Ka~58-+UL+62urnLyMI2Z|}_ zdwpreC5;)p6r@tZXa^c1)b1G-n6(YDLhNJF)n+p_lXoX4+T#Z%m%W&(Y{wC-)nDeR8DpcL~o8K*KW~5Lhn)#c=QT=)>Pjana`%{BBLZ-;; zH!^n?iUv4a`cdYO%0sjKuWk{A^C+~S8@@79+xUO?U~qse${*oT(h>|1wIjSeE~vXP z{b5G_k7l*3${dBY?|C_Mqx6Q?U1jC}K)suVkMoskVzt`>9LQBQ*g8ukzj}8kvj^Kl z)!N~(9};#Nl6%8IW|dp6Bk4T6sMl8Vd$p9$PUh=#Q|x~89{*p_VtHAs9pbkgs+I}# zV(x6B3Uw#s(npuw6xG5;fsZr)F22<1FQR1k1U3q;=vDk9&rx@?3OAE$C0;x)ffk=%PH<(&5VGX=pm@EVg9 zdpNwWk*@_Sdzb13PD1Ev)7ZR*#q}FX9JxMW^=c2Q9W$mqVJ5Nd`2Ax%Oy^T0g^ZoW z<+0QI%>~`%k<;B{e|6w6;U#%&gk7m$BUHIa)qZ7Z|5S&4iRVd}b|n@WbkTJ2LsBeO zkA;Xd6?k<8X6BGvbx|15m|)y_4R$mK+2|oiOzqgNV|o@fP)h0?qloqD#XlXys9qb9 z;8C~26SIJ>%C9(cLl$!3rY<6ZyT>y6hC{!E=+%MpyI!2(I-2Q4#2llmcV6I#!h*=f zd1!o|&{?mW$XF_fn)wJfWEUc0Pm=E8Q<9wL3tj35n8fcV#W_Uqgc9h+p&^$=ahPrG zQo3~A_tr3>^o=(HFT(WIxTFJ~?XR1#6y-Qlp@FpBcP%bVc0-l`w(d^bG<|KMxRdkMW%#j1RI(s!9q^b0Y!)#^aeZ*4y2NV6hj zHk%o3Pt&l7)vdckZ!(d0-Y4Jr&d37$6f3a|2f?o`WQbhrP*q{O*jT+pKkI~-Q=)>V;ZsFVot z+^jCI#B`-P&}qZ7l1j|5#x9 z7&n!rM#nT`@zN*S;|A&vV@k7FzL$Z2yc+-0^sD2ydV+46Fw8#v=slo&Wa8J5@vwrF z>6T|@*sFfDm9k|f>~IOgFrMTpW#$sjPOBoDH%e_R(>iok6WzJiW>$eD)e-8|SUP&l z3>C;Bm_#xdmW2sl(Dz9Q|9mj|%Axh`ucT!2lCZVqT}+~lq3VbkhbW?xEBZOL#4s905NPjhQaj&n^34Z1YQ~kVNCRw+tls*iJ!f0 z%kgR@FUnX$3YvI1aG8Sl8KzmwVe)OM++u?H_(L| zV>0CLmy0DIY(+^j|G z&;gjz@eDBaf+5k-<_+Yu$K(Y1V=BIA>I@h9zxrf&J5f9!B1Og~cboY|%4?MdB26EN z!!{$z9%1N1F6Jf>~0-RG36pEjbz8m)$Nq&j`K5H+jSo0X z+9s-jJ9eCfL|~*xN}q<7%f<(|H4(GhK>gFFnitN}w8p7{7TF;404BHsr8#`OIYJva z#%MXe;1L|)$teL|b!xU{7p}Q2-gnY`ZdGKu+uSjB<)vD*8xE{iUi{Bwgr`=R>!e|% z_JAIUbJvcg(Y4c124Xq^w-MrDPUU$Qu~X5vv5>Nm)4=GG%6RiLp%w+1^E6Vfib}zW zDQg4b>719yX!MXU!oN^qk}mosJDS)P=B`yc`x=qpV-c^B$gi}lAtS~co>bd+A2?2Q zxKD@)pUgTZeti6 zPyacVlgF2_-mj0S8K=>HRv3{6*P{nqSGb4J@OUI+ z#e_VkD5p5T^n*nGuzKj|_I=*T*_Zct3u*VfWt5($=1jo3o7R|Sivi#cY3|1!EU(Js z3bzV9;BUuFMMQK+NgQuX#{8UR?PFucF>%V#m zg;Q;$oHpUfq?W22Nj*M9Irh*1*ABHwX#_q$-+51+D8NcbmOY*US8Nu-xsy z)7v)|mvBG5XXd1sUrsSeR!SJY<}fme^|JY&8t<#sJ+w4`KZF09grj&Gm7HjBa)!Nr zhJ%fUBd3Praz@jBMstlui>HR#_N+^OMxa&c&*=Y;0nuoDeQFGnH#wH${&r8lQ1m81FW&BcY2@5o%yO%--Fl5BFGvM361xd<+Mr=Iy%qI(=a;vXXa@LQOPOu z+tZ@GfQ7yvjasA5fM)BE%H)*M5nK7DoyK2_G(0$?8$}DN14e<)-*Bwgy}n#F~nMK?00Z- zY8BH3j8=t{;2|v4zash}I4OXmUqI5t;+Tmht=6HB?0y-SV^qlN9zp%dlTD!*LzA9q z#ldOoK{NI7)Eoxv&>;_vV+nVehwb|x!Lv96eR3dAhI8MJsOQgdxcAx%tU_-389D! z18CN)(NZ>B(0rq(f8atR#MWW-D{S0ib;ejQ(^oP}u~xxtJVU0KLe&Vv)KSDWgk;o1 z!$;99OP!oyNE#4^I^CD6aTP{x59{dUYT@~0Yp?$rMWeOHU`C-CAi-+p;ip;V*L&=z zs7t}W7gckM;XPIrXW_f-Bj|R)I7Xl7$t*sK;AjG=hGLjE0I~&ugOn0b!*F`qk%eHG zCqe}gp$roMnUWnh76wcpxYdft^g!Gi%`Zp%pQ^2}H}P^1e9@ZxSbQFN&`(s5acYos z)JZ9*WkOMFgT|iwAXwld?<@Zh)v}QOE-Iu@h~v4=TQ0$;JgpCuw7L@XPVnxS^^ zx*{fY*GmUtB7dI74=K7*G;&4(Mkcc&7D_gWaBZPDa%N%*aNUChwf?sixwm$I0BFDq?CD>mOJN9 zkp`!JR>O9#CrEXe992`QkkM=AZxiVMgW17lon#6W=%%b!2VzkP2iNg1j{?*;Zg3?G zd>+jOvxCR8zRhTb6E~(P{;p7I9Cw=558<-YIVw zWepL{O7LOHML!fHTID{qE1T2hHroLw+OZJR17b+dj&GpNP!&Svc^WUg^=F36;D{sO^ry0HF7`e7R;x$ zv6jvW*fD;nf@}!1t~`HtzuK*(^!dz(ZwIAwU5Vp4?A}-sgla|rj?1-(ECj*4)Oqx; zl>yO4V)j#AHIxhm3NKMA(&;4`uoFG8E8j!ifxIgAV9#x0Z76wZ;&}gqtOtVY8zhoy0@NmU(Hmz|AF16^g+Blfbue>t8?W4r_zI5@Rx79b1NEDXD3@bY=M~ReS52=tSoI$wZTcv1{Fw2 zMT;uH)Sd#0qF0FGyQ539VSf_C`mDcptIezhpi3=f>Ci__M2yM5tYR|e-Rb_{UH6_lZ^A-M37m2yY2+`*6~X;Ot)$KN`0TB`A99nLx3m4lj^1{ z56^@-_F}?h(jm)pPj$V$3qsWUSGRI z^KA{T4DVoYO<}MQL3v%5IXCT@&iEO(gIwl_6Y~qb9E{~Y{QIZt$zaX_9rYXI{1k2Q z!t0)p>;t~nPk%>Y7G1g**{PQn6(96m>V2JEISpP0b9}z$oNZfd>f*GXxe}#Ado+cO z^^mTkvR0pTuR2k$?c86Y?}7Tor{5}F`@6#P&GUO3bVW07{Wb@*`w3wFM06AF`}yLP zMTeXv*LUlX56^zYp^LQLxnSs}9a*laFaK?Qo5fvZS~+4kn~1nZuWswIuwmgl$E9-wS<)^+pm#J_6qIy#K*K6y6=<9m{Jo{-2zU3>a^qO*+9m_dOt;|2jJt>0i zSeC~sPI&HZ{inVcY~Aza^WLK;uniDH^1o*lb2$cIVwnotXEpj3mnN?HQ_4Fdc{V7} zg#y*KXYV_f<-b%n6n=jG+MEdLO{(uTFeq9`a750g`Tsq1#% zeO=>Hd#T{-ZmC$W^_kqDfJ)WRV=OzCdCUE)%<+Q~J)TGZ9-e>L9LclL2%D+;xIJFV zC>tyLVztl+wlL_N%*aN1jOTNM~-#f3?ro zEQM*Jxh(+&@|kd{(Se72*zp*L#QTG@mJzu|LiRR1A&$K$MovEzbHK_f2^}wpsWjPy z=_y@YlF!X<|AA{}nVICS9%B+Z@i*i1QA@}YKn220eD0Nvw^=) z5BlB^E8QClS7ocL$E>@I#mL~+r}q}+DTOT_dN8__IW`5( zdf^PB&Cfr%c`O8*VgzcehhB2jK9H`OxHa4JF;P<0vWl)8N25CFR1J$03-5|8t9+7I zx9jBfgOHzPi+peu8qN7IKt#N8yy@j^^`lW0Pv0i3a%a=qBMejmnhYQ+WiD8o`-edp z(1;B6?68;r+2_k7tCiLt;?1?4sYS?#E9JC$RWC)ITcQi%BzmtO#`E@>tw^o1ljulhq&9Bca^HB=Xn%T6kKHri+5^!alKIW5gLsKCPQ<{}uL$ zh>WD0s$&3oV%Z-@P#8~c*~!3-H&lPd_VM{oM^Lq{6yDe$@__$ZYVsW-P-1Q)Pb*j4 zq~|`kOU*}ReB)m`gxAUMjT=-F)1?OfrKKd?BcVLYg(D>8W}ue z8DXu{$y)ZkYxB~pEpg9~id#SArr>&uX5#DS3ho<8TeCPByp+$YpEh$H3$x&lPk*~* zYZB{fP6zS8m|nSv3e5Lr6@1>+dmI$pH|NzZVbqwdt^EP_mu6kWIxVTgeEpt$t9{0# zx(c%9ly4ZO?_coiCyjuj8n zqIvC1578|Pb_*<=J69yuIn`!+IBURdV!=b-M-^$anrl&`$0&AJCr&{a4%|$JggYy+ z7*|&kIW}aU+y_*Q5xp(xo952X`p0ncwBFP|C%MX6`vE8eJBW>*#GZ8Zt3-zqw%hAu z&OK|%@p7eE3zvMO;QS{$u$MSmy~XCBW^%q-etty zjLD(au8%GGCaJudByPT`MuYRaP1syWT)A;&z~Km z+#W;Fcft%R*L3RR1e})AM=rW#e~0;enxI@S#`HxGA6f3c%J@4}Nr8b$zouOy`=P)3 z1+W$KgzTFOeZM~xU-m)Qp~kxAI9pa$>QL6f&RWR5)n9|FRQ@{FXqbnm=dVBma`S~dv;=e`LR`L~Z(bmNOb+u?1p5??Zx>mKTNHx&7KDU^T4Z#&ReztWxTgcfm zB1;YWA$d3)aTQDWt?boq07;EM$)C0BitDH<<&oT%F4Of!Ml6o zh1YFwxRt-Nj{P_7^!D7A0=d6B9Q68Ahsb!rP$SugvD$B|KYdkq`TiWocd>KTmk|_p z^%JjnR66>TZysX0C0`v3sP(Wv@j#enPr|wIZ?P&@l;tYH^hxynZbh_9R>)ibmlXH) zCLg?(H6`&^BoR9DrgnZ!H5)*G%S--(_Ad7Ii=NlNLY1>nv>=usT(f<7*2}FIK~-BW z2e(7@LqQoAVe>w(SuL44TAsf=3LQ^_xpph?>%F|?9K!o9EUrI{ax+Y}B4X@mC^PDr zPiJULC$p-hmbw5W_n8Y)4?~`fk<1LEY`JUH65*g1Za=Hbaw+pG3TC<;+V&ulT$+TQ z)&w!@_2a?|6%%c%igWa0d%6vOBgx2A|8@v$u5j(HRlw%s2) zKk1@Z5x=Mh|GKU5`YgWd0j$=7ed;nUi6!1VibT&M48hFNO`s{lX{0a-SI{=ic5C(}7e zQT<$@=`f;?GEOj8E_(U8|?Iq9AUElPRr` zuHYa-tDt>vi0TozJ()%ZM6`p2Xqu3pdQ%9ckp5YrP)AT+qU9G%(*oY)J?Oky%0gX| z>E3zYNV=f9NiYF>6T8WutIYpCn7_D_zx*~|6h{_VANRwhVCzl6PG!N~V8M1Pr72K& zEL`|YzwpeZ@N9?aqO$PsVBz^&LgB?jlKaV^6@4s8PClp94H*Fo8Nx2T!BWm+X@{^- zks?MbEQ4zil?eF$Z$>VF#?yq#s+BI>8%hZPPx0zHM^I$|$idUlVCc$^sD&CJxMaF- zCJ^`3w86m=m4>{L-+AMebj5%!0Zs7?Q>tH8YA{r4v|DPNQyPvZOT-sgxRyQmTrgom zZZcG6vs?CZ!$~^GzHW`sYg0su*4lW`$5>iyT+LP4d6JEh_w+ zuK*{P!Vs0YR=tZQR8>}0RS#9YqXdT|swz~7SP|8qT&tU7t6Qt8TkjA(LlCu5)^v*0 zwC`4Tz64=EV_9Nr2C8a?bBacGYZxhO$E)($*>apr$roTCKapbL6rv3iN?{Q3YCZJt z5w$dit_uwjUIi2IU;qP+N~X)f(ug5T(fpO^RqwMKN)(6E025&ADAV8~MPklh|3y9d z-?z!LiLr*%fACT<5rE;lp@R>a2A#aEU5p8xRpJKeb+%>_2;s^X)Ve!NLWN1DPT#U%G zfwcZN{65tn`1omSUhYSwN3Gr8Kbk*`FR0FNH!1D+Y-ep|&r3-@kOSH|#UxplY})gLX=_PSPM8aXW4w{4T{e3%VadYuHJ_ z(d8b8rPOYMqU@et>?eEn+QpdiF>bPe6QR>4_i>ToN}*<;TMx99r|B; zY=V04=Jh$%^!{tZ;Mn`Z-$wY9Lv3AlG0Z+`TI{Z{S5ue_l&x@=1RJ$Fn{r@W^kXBC(s6%AqoM!qB_;p%O80 zCLCP3KlGkzxVU|&mSgyn`*79Qq2`+52DRa~{o%@m;V)ue%Q(JvyMOI<|JoJ*be<~aCWC?hRTKs7cY4f@wgnFD-eEbGm z%IGo9oG{L+J|1k%D0l?b#C`3y&R2&`bg4}UcuX9|PILrKh}I5^A51h;O-geP%Nk9- zcb}Bt1UsRNlkNeM2%>|pBk4R-I^v@!k12iismYotqx=!Q1HzQ4(TIuo^r|6|q*N$c zwhuAh`Fdgc(RG_BxL*P?qt-B3@O;M3Y$h{h=HB?s?#CIGlWB+A89$qE#nRvG6TbOy zqJpShy*L>$|1pHA&xX{pMAUxEPx2`psa1iFAG%}D`DlNVQEluS)bu1ApVBLXzo1yPEjIg_HI^kcfLUA`It z%5l`cFf^_B&ko3yznt0x>?dF5 z>D-g4FJLtGr7Vnfi_A0tYsV^Q0UcaojlYgA9Y=j$PeY&tX7@6sC6;A9?G#2=x$4&W zY}bU4nNQzjx(;UQcy2HiY_N4~h)M%EU{#0~j6*>8yeZYG0kOk1sSYNYyUPzl*10?p zwxi2B^^i>y=#tc`)6$xxhK#p2#LEQii>0Z+voOC+k*#JuxT%hlk<63MDQji@|4FS% zSXL~K#s>}#hd~21n7k2`VMl}?zzW4rDKecS$SS_ko@cjobeSJc6;Tg%_NJcoW_oYC zE5t)SkD zg?eFGx|VhdX@I`O{h`r)U}YaKaWJ(+vF%N+WJ2r<$F)@Ewzo2^-QE8YvOn0dpU`nQ zu5kbycI4-0(d7S8ymaPT`wKM}ed6G9mS@r&-N8_`Y8--9V{FktklUAz-SU0($s&a6|YLeKeBRB7H?Ct zmZO!5K~&AjbnRFIB)Z7`}>yK|w{Qy}?Vv;N%U^?zPpGEP@W#a4?K#Y@~8 zE&%++Ywk<2qT=kt;*6qVv7Afkmn}}?mr3u>f#GvuQ_?Lw(PJ92zle`H094AA(%-lw zaO~1>?82Gwn*{bpNcvCN&odDuq{rmq1@y15Hf2i()2p4c*TQV(_wsUh-Z56Q{=d*% z_+p%u_2miHvX@b1#sT}5jbDO*F; zODVSifag_Ad;a&cF0{mB%I{aQ(&L*(Zx|(?E?AbX_b1cb&Llnx%@-o$Fb}*30Of`` zN@aJa-)p{DZ>=vU`=GFr`{<4&CuZJRAWg7!$&T zr}%#^H`lCj!4y4|DKbM)O#7y^)cPFrM@G( z5PT%wu~XG1(RM(!d)QV30RI=YNg7Tnc7(f$c-++>+l#|zKB8J1$s`ADuW&1k8bC2; z^AK9#vJ{N&AUgm9I*iA@LJ2`jQsnB9uI)bhk%qsw^o0sHkUY#?`YD6GY_i+Zf&x`f zII=$bZIe8Ym8y`H=IrX12{#WFGXf~3-zD?H?6w-^0!u~|!oBx=TXsSQNh36mW%xKX z(!!sa>Pn`i-Bmr7)6RW;N{F9~wn9ijqw8N=TQYdpin+!7p>FM-)#-Npz9P3d;c$Vkdg zuQ1kt?37j}>oHqdF9#bNb*WkK>2D|QU^+}%o+t=UoUb!7hvG5m2u*8d!b+)X<_0PRzF401cY&O4jl*$qyiywb1y3W7(QLOIu907i_G!R zMM?bGE@l36%Mh4C?hA)M%~9^G0<~B<7bk>}yOfEWZlMW4vP4g1_E6$(U*oqZ3%3%B z*14M?8VDoy(fly3w(>XE+%A^j$qsai3N9SkP7C)I^)kD*Z?RJ>={QI?_Z@Q>GjU>= z{QPDwz;JsqB6b^$r8%<#NKfE}^xQbA$QY;0`W}Se>4C%cTXP3j(T7i+r2}P={&2kX z4_^Gov85L)k+1d0Y+*Egcw>u`G7@NNz4 z3yJ^)0PH{GzM{Eo`z>t3Lq%M)k7AJqt`G#ycLC%O>JyEF$QX3DHxd#*Tc%Z7O4j5} zb~<4m_oAjVM!bH!1K(I7y8&iUR_akxAi8Cp$44Ur>rpWr7l5W0Q4zLLtV$acF9wRp zJIMQ=YNhwdH%XIHT}CR$O6i2Qk|nwOt!pzdqELsT@eX3^tRN|Jg()=6`YZ%+J))59 zfm44$N7GZwhyZvr*SnQa!Bd|vF!9v*r*h={0{Z&l)-q|i`=!XB@dPe!pvA4Y7iob4#T%fdPzpJD&NJuCymQWZ z?@#+}XLe?HcJIBe|L<7ywOW(}_KuohJTk`Dg+H@`_kb(UR?A3UIIk5I1$95FO5jq` z&8!q<<0he^)l@ltVzU93y70so71S(6aekX^?%|X|_t(F!+vUrb;&?5y&{jhClOV)Z zsd!Ci(#~l9rg(RFrlEVQkDM=?71wfhZRxp-d zryiyk&rS0Os;->l^E~O16d-e6XAmj9TwY8H?)Jcvc?(465{Bt(UlAL4n~D_wHLx;f ztJf#Hih0#nK{u>Xt2iXRx|~H;p}*p2TJ<+|cLYHB%LI!%|7x;Ie5E>2?$qF6Lq8g+ zMhaS?vdKGH&bKpaFF0_qm%D#4A7j)}!RG3y9ca2-ZPeND+7;z&ac{alX4KVQK=S=wgWNl8D?|yObRsLXE%QT`L&yO(Y^VRn(>FFDmUMzK#MawSOw7RVUmzVB@A0W*P?zp9PtB1H!S*p}d zqz}$}ksgz`kbcD$;&VV4)}tb!`ld2noSkoj#ly*3`7VR=gkqET4)GK9p2Zw-jcN(k zRGrTWRgOei(Li|Io1GJe*j8Tx52&+)y4l8(+CJ7ZP?|&r^Q`yRXGIL4_?ulS!0=<` zyEIpr4>Et_)b361HXZY`Eo`jU>m!a1VJW9XL$oMHAYjUBpN>&!l0Yg-b}AJ_rk1x} zDk}ltS0vOqD}`pQBYXKmJQM9@nK5=oB#`ftjjU=18Hw3r*dMLO6@4md$i^82wg&aA z8yeRS9VGz-@0R^2m0{FB0_K8ez4dax|4`<5yO2arsa;qGLHJ{FB|rMqsuvyA!DHnH zh~kGeEl$ns-O&%5{|~i#it&G;Rv*#W>cjoRJ?h_IG`RX-ZS~>rEm~XsbN}c5_AeS- zMQf{%w?F>_uKrJI_4d~->eu1#|LCf}fBk1&U;p|KvU-1cf_7H_ULb#;AW;`{sH54( z?~AA}Ur<}ck5f~qxrG0qrX!}0y$z_3>ZndWU1+$I*uB$mrP6&=A^C z?eFjJ>;2T*+xw~KV|RD=e;L)W)_%04TCq}=Fct6C?`+&|Fx4>9+R)Nk-GXYAN7XtDURe;9=e^g9BU&V)al?|;` zO^u~>%T<=2tGxQEGTN)Ehw~@fi)&i)Tf6g%KBlzvhW|%lEk&=AQZ%w!Q&@#|RtpOX ztMV$Vax3%m^7FFuOOmS7)6X9hfAcf%vj2^;8XFt`Z(vp&rVq#*#!ovSWR(W`NIk~w1Phpjil@LWih9ba6VPc|{)LUYb2QVf# zT3r2K<|-LEISB~~8eILK*ed>isZ|Ib?tisa988@56I=!UU#L}ctLWI_|9@&VrlSpB z_BrQ2)avmfAcca#>tyTyO|7zNwx2xZLA5z;Pjxn|{lBQywI;F#G_^YVxuO|OtzzKP zYyF2>effv`qCxdQogpho@&@|iYCkzkzHLv zwTiTR(bQ^>_vzP}z-yP}xkP>o_TMK0Ew7Agivqr_ zY!0KLW#rGu+v}sHhL>|6`|tk<-s8l63l0vxAKS&~DJc#`{rd&HEe>r8uK5;@k!DXH zfhT^n6A4q}WCC0rtC#vy*l?BxQn{^_#nN>BvG!#FVSSA{=0fbn^L8EWCGZ(h?s#Fu zaF!?CE=({bOPNl550#d;XG~nL)7VebV6WRxADB^31(B$59b_69IUZyg`st}*nfM(a z=QpNo!4!Sw!h!VyT1rVr{IvtfE z*z1qV6P^top{doW+KSXYLAbx?hipgZ0qM$~W)W42JP*<1gnZLg_2*8(POu z+^3C=m^gqkQ7gbT4VddVS>d=^&?WC60GMMyXR}X zGjb5hLv;jJw+d_iaHiAGBEyAER4G+s>+@S9%_ zUwm9^eu`(t`?Fsn5U+k##yf~*F5zLxT?a+~OG{+8eEMopOMZG zcH@?Q_^bZQk5%0J$_fsw7R5^rHBC3}dc(Z)6sQTtZO(P5EuILbVbc7HlsyXnd`--6 zTVkDqS#(O8k0|J7BT?d_=c#LhJwU7r3P!s$!s^{{feG#T={G+gu6DxjAKr{tx6_F$ zL83?!dNdXI@6WW=`Nae0VC&Utf^nvFPiQk+VimW>W-cS38Cfa6YS6koCbDWQeXz}`D%*)Vitbb1yrAutf zy2rS)xJr#>2emo+k6_TAKx4bs^?!!Lq73&zsbM&#$Oy{mQV0)aSk(Lg^)Q@_vWo*d zSaulO(qmjC-7`vfzk&cn1rh6G1ncfZLLqe+^4!)@&qpdk%7zE!QPR5@?EZTgv>GuY zdYIu6(AF?$l+B57^+1VhYyhvf6}WpsH5!v6tm5ea!~8(#@PYPXiagLLtiuFa!&>tW>V?X-%ThTF8HaIGq7m55T7Djlxj3C%I9~P zo@=hZKaxA9^Y&Si%g8p(6UmhDL>n3msWD-IUQFo3_pGaRbzuPDsoW3?F-Dy#6R;HE zFrrMAhaCLy);^Vk-XmU4xw@9L4FuUq2-j)1Wv_Xn4c7LET%WGSl$ns$A4&^E3ch|g zi0|NBGH<&9{bzjSq zlp4rF8K)Hqz>EgcIEGZp3{y+R=~GX}@KS(@*7yv|R#BdKHE`y)=|`8u38UaMz2hDlCCbpCdbirf$6k_oW0ESr<--U zf2P*@R19Pxtx94imxSkRWEJMybDST`Qha$|VgK}2mrZ0!u%I8LIv>E2kbT!oEz3gR zu)*=P3i@1PP^`I{Mp0_|9jI5Q%_AVm@}>RL%~BLFtAsc!ciM;N!@}cI+5kR3D}Ec6 zcVc8gWiO9QJLl$x^q==acMW<0oAmunzp95VtQ<35z_1gCY3oebMGLBpkMiGiEp8|K zerdN{urV%uG(U9={cd!+1I28Rt95?TxfLz`rw<_S{`TFH<)nUhZqGxLAH}rQEwu_D zNDxafwP0&a9Qg@2>*0!JUIco2K5)_08rl7M8?1O{l>k98bahRQ>GSn$hTV6CEYF~!o$K*)R$JVyu?^xY+4u$CrGg3$pC(kLq$Cf zmq0q25M&dHom@(K;r@+gUQI^28uSDh|0zgS=+ijPw+Xd_%u+lNC=hR3F9x2Qnxcod zi@TK?4VNDvuw@-2_&pH??-?M}rQId{tEW_IrgdcbW?_CpvEywKp4zu5ifMhduH=N+ zgMM=?UM+SZZ+R_0$R zfzMChN)W6M=WR%ASHn033P$efJUz5`aJ_Fqi#+o4LQcRiSDF#x3mBBIS_o$N?u3$s zZuk9==VF!JFeB0Ylb4AuKhxD=-#(!nD-Hz5Ep2c|zCCvn@3);5v*VFD6vct#vTGk- z4viCRwB`vLz%YbkOJqjqthBXZ38okd>*!xTG zf;#K@%z?NL@?9XWO}O(LusMP7P+TJeeFsJx{tt10ycNFvd@af4&baIZo^l;w<%xRF z+f`tzZ)!r}noUaI#>7|ZGsn@^9rOs%|9q-pvj(3!mnaTsr@BN%Bss(eWV?TS+tnRx z3VJqZPALD!$?UD1_brx!ABr#(S)oN&3K3P4;f#Oy&QJN~T0#7)Ct%%s%_^tw7YAxI zry*E|0dE&SbxMw;TrZl}hY5uTWK^c!fW?BJ3@IE!0lx`>zvDk%oH`Q*u692!OSMtrJNSPhKewU^uHcW&o5Zp(tc&7gp#oN#UtMY4JH zH2ZKy$_VE5aMEmvuPREX>gs+`>TgFdf>>c8wy<@Nw(adTY?4!z z9f@_X9*1cYhg}ihXp*Eg6wZ>Hw4o8F$z;6&hAB=QeM`=c$UW#R?9pJE3Q{IaT&Vr zvu!7tya%x4znH##!E@&?s6v$!b4>3YN8$V4_Dx;l>*LG-M}}A=)`Ag%CuOeUQug24 ztk^Gkc)$%Fg^0cw@ zPJwSc0eA{jdB#$?kmtD_d4+F$%?Msui60m8D+-auB?8t8YPsm;u(3o{fz4dGtpSB? zb%lE?rfj^&JF3QU*q0O&2vgQE+*&x)VHdhr&)NG2H?D!vY z$WO`_6{Gm(ad!-h-iBut)Rjq_R*fFBicb}*f2bmSTe7JL;6q|@dJqifRp~nwQaM#Q zeJCV<@8^1wY&TW9zK|Hw3L1O;-14MI@T=L&1*bZ`{JKv>C83OIXWSV{}yc^IQ^Tf_g6xh8(a8-(T>cdB$U!UdFguB^Fa7wL34QR~6nWAof z?5=tIP?B5i=tD|i1;<>0JSv~2?8Lajh#^GzIj@0OU_7e2IXqZV7J zoHN&}U9+x1f8kglYcMJd6Y5;w`?r-_rs-pS$HYQnP#EAB4p21k^_^z(j$^YFZVqnF z8^Ay?XwWk`hs01FjIY;a7ue-c(B;(Ie#=@dg;hG!zL^EK2*$yh2i zl@M%=UvC7ntRc$^gVgtaXx#kJeE*@9rngO|x5KQrE3mhxp!Y*>Z{KF`$NSy^n!cgW zA2N=y;!>eUJ59sAebe_JvQpo-wY@Kt3HFP9LqPGN!t4W>$jj!Q(AN2VCTg>LN2VuB z=3}7Q$3xtny@HQFdOw~ubRXS+d>vSeZ&mXN0KDY+S%{x7|xV>b@Jy0*kpPG#YXpNyg zRzspPzIjCv)j<8imgoP*P@h{&8YXC_Ch!`@QyNE}B#tAcv)CD7m^n6)jg!$q?>cd& zD!HfZ&#Kj3rjmoELzrRPLw`b39$W*6@y*^_C>AJcP*bl5vsd_1sl zD-ZC(7`EbQQBZqH;q>17>B_#(`&$!fva?NtmEeJ?!+}s%)d|VzNlM&VC+^u)bXuYD zGdh(JKiJlQHx0K-87};6ST+pMnhSE8`zJeflsJbMJQujz;s18V>29`_b}nXXCO@Ga zx}ArUG<9$`-;GzpCre_*T@4}v4817BcxXF7e|pNb#)=jYj>sLVNCfN*v1XJ4I_NF1J1J|>{06R<5*w0hAr-QPdA)zpgLw2s?M z>9K}I#tRGQee=(Cqck68)Jj+)2u>9wggx2DDlS~Z-@^O4W9YiaK|pe=4O>f`gbZ#7 zS$=`)LpIPNdD1G2d@-BOx9juoJn|c#v|-ffd=?SF`(T#B@*Ae>bV$Us48NaTNT?S7 z{!P*zmnDo(9tL;K%WT?u$^V(baYx@R={Z5vgPgb3<4VTNq4UMzr@;|sILxeni;~_# z=PQSvH1JGd8A*%GHN63#+yd@*vr69MM5c(qporA2$A1Zu5 zz=|!Ww1zYpj z%8oIJrpXCTbCO|Y{CgdzoD5as-B)MP{E({yh}A zIR6%MvVDPw-#rB>0(i8~XTBa?H=e6ao|BuMXFi@q(tiUHor8eO`vXOkd>3H-GwF+q z1ea3+`i*jnpE!>@qShB6{l@r>pI2@$z{?$w0uqVd2P?kBEjoa^k;U-CL<^4!@Gj5_ zZ@cB?PaP!f+}Y{ZORN-Rjhvb{>SE7={p(Ztv-fY$1JlnrORSOd?W_vRj|9Jzb$`9R zyaa^ppKEohwzMSEkEedU4sO1BpL|TDaABPC+y8RgT<5u=)RnfvWs1&W$Q3{j34Vs+ zP)KRfp8NH}{Z};|VAKLeFn5E-K6O(j^gnUv4d6DW-ZW|arglFtw!EcLSTrZRnmE7V zQ)mkaoeoUlATP!3E5!(#<8Yq4l}tHFn!9qFS%-Mee6qSu_ zym{mPr&{6XT=DIbl6{X)cc1^>>eAo&Ux7nPq?$@tTUstYwEP|~xo5-wi&^$l3ID#m z&qfew;|lat zav_xt2WH}CfJ{yi7O5`};FfM>_g zs_DJ8^uzRt1XQ(~EJyPVPmP)_`a>}9eJfI0HTkkJ1IW+SJDr8Pd}WB-w&DqLa2zf< zMwJK;ri%ofbDGTu9VGl{6VsF>gcdcq8#CO203KQ_{yPaUpePsu$-n%gmn|MKSxBXt zZ}NMQvCl`&gwE^+<+9P~DnS<**nGC#hr4vqFWrOuMz8(vlEvDZ(feaIfi7O~>Fy>t zWd*e3U&i(ZL#BrY6Bya#ni0O=P`MM`W{*)L2NC3=KdD@CCA1nnjSEKqLqTE9S8Tat zBsYWbd1t#5oMZ%>A=pZc0;J?hRL_$TP)m*^Z=GzidhknF#sTvAhJq)diNtW za*n=KNInn+7|>UzC!;=KP^Y6Ko{Gwc9pEJ{PAKCi`gqKMo+x078R(Ow6H5wI$dIjw zN@$S{8ome?D+k}+4ucUvXwbX52b^GBwchBO9D2)i!w`BKSC8RTO5|Cpxp9dHfF8cX z2z%bhrIm5$!W9{-mE$QKJ1(mgLd6ESEv0r8)<9(V5@1>Z0~mo}iVumbfW zBvDS$oMhf!j`h3E9pv-EsE*H)G)!)cGTbc4!2<+qYB&}aU;xQM%3SLKDWnfgA4QbK zM+BJb<4ab&h!?cLsDSzHvVqGf?E5^cPYg4TYb>-sczqVpRI~z;g9Zf#NQ?h{t7iD~ zLE-$P|E~p#(Nak9o6;|Sj55t>HFS1~j7PXGSC?wU@iuKqvpvu zelTBi_eKdSNW@<84`~Fz%6x+R;WG}1SNHSs-!U+ zEoOK7MTWb|cDKp$aP;k=dLLqT*`rO0#*M4fTp~bV?1-=M)aPB^s-ofW;CZ5$Fq#L z&$W_8tgIt6FnOcO5W*|zQrgV&bP|1g*0yAQ{uKJ7Z&fOUU8-t2PM$2)8zD3X2n`Cj z1ffPNo?e*w>dV}&lJhh-;=`t%qYB87~?Zj<3e)b z2AL#dAuS=rcr9z3vmwSkA4ZeKv6NP8Pdlqj&9xC>{j#-4YZZWgwFqBUo9X*gg6qF^ z+JH2kL`yNlSzB+L^OUt?tzL^ofY|# zZedgOt5`X_@7OGUjCg$2c$2`0IHlZF@~pf*alIL59Tog9m8c2vmtSnymE#8GvON?l z61R?2kBW>&Y$AgTpMJKKn7AUw6at6y`-U4a-!AB8tejPHc>8}gEpB`9I&qbTWxPyU zhceSKXoWxa_VZ=iU^)l7zrybL#92)=Y(w^o+|&091|j8UyB|{V+)d`h{a6sbJT}G5 z0nCMacIB$tEflY$%c|vh9}PY*j?Eg5%f?(+$W$Ibcu8Br1X)yjq(|ZaKFgn)XUbi9 zoTWZ}naPf9Y7%VRYr&yb+N@{kg zHgUIS!Bpe#O~eVVQmzZPCBin9qGBds z)wB1y7)5(5B<>f?2It8e%ZfQwz4KX;hau*4_eyM3W|k?5unKbziGa;Sogd$9d2FAC zV)Z%8&DI;Kk6`QzG7f(F_&aOu!@<>G0F}3^t?pBBQe&>nH?fkmuuY#G2g3VSswhMq zSFh9IZS*U$Z@-&6EJEC414)Gm(?W2lnQjH+DIQ+K0VyrYUXG*&jLr;4Ld#w1O8nFGRvg+5vFGLjH;tm9OO5>zU*P9`RpU^(F6~=6h43Y#1 z-eS>EAv})2@fw4_xK*EnM;;UKqY4rLN6`&=@Mp_CS-Tq6G0i{$J6Qgl=nhL%kOtH_6%zr?A(V^=WsHE#j|cCMhx{531y6+SkK@53@n92? zDicv#>Jg%7^mHPYb|NBbBF;bq6;nBpK&pY(R+C)9py)#fK+=}FFjp+`js}8sGGl8Z z(_k|67f_o9)0MG+rWWW{s2YF`#Eu6fN(w(|l=>qz4vq|CDvdDlh-L8~_b(ieo)}ZF z1B-@D)n-oBRZi7+pu-_kjmuL_`%}%ordq(C{};9Tv|bdvuK{k*0*^e8ZvPLp`n0DJ zoI3(}fj4{?CoL{H9M>w{h&u(2gqXwBY`}n5mFkS|)Pr1}B->7osXU2`(n<`Po@~^Z z?3kW#nV6QrP~#vOas-^G~m390lQoRB058r_a_JH0gAb@ae4~zJ+kIoGiC9Z0?2SS1ZF5KQmRpzyEH~tWo++k*v@C{d**D< zM8!Haw6in}v;lYirQ5iUSf;{^OGQg+U}WE909TIpE{9l;3_=iHKGPkfhImZG`h~^Z zfx}pXVgpPd9Mf}hTJy>(BdA23mRdnQO=xE;wUyv|r)B-ZdL731vxwFhlhpY>ynH@E zOasPe%;g^mes|kyNpUp}QTpn4z@#H2aU&g7!3VmFdD;a2SUQx8w_g;W9}PC?3A4LC zLp>BO(y7jppX+vq)wR*+#nu8ae4ihT3?fpa1&~1gFvy$Q$wO>iy<InUmubDG4V2L0Hc1=^KG3PU~Zr!l@0SiTw%rq)T;A_~^^X8NNBS>zr+R;j2AL$MocIS=_@Wsi#$V_0`?8p;ykH^2%v_nt%0Tk1GRX@YfKd?IyA>n5s<6mVM zZ&e%h915LpeJR=dWP8#cOxk5NlHD#ZJMjTT%}; z8#N8(7lZ?#w*sN6Et1an#cp&-{9ui1c|B1>903RiokSPpy?D~}<%^F@AsMwkJeoNJ zDrSXooPjVV+aMQt5%0g2k+flI_@yd$!D)2B5gem}Fllo&8A2GZ@vIOmawK|$7j^cD z;+V11n0+W(J9}zY$(Qi9sLo3={C!hG51Dz^{o1Wmq!DPSVL*=H!HgVtYm9CSOLl|v z04Kh`%~!dajMMDBula2BR&r4ZW^J|5X9@2j`N)|qi>;K^=_Mk7;>emfjkyi&*3D?d-of_w-?HZx2=gM*h*|*tHD<)1 z<@Wj3N%_WFyJ;D=qKnL$5>M+^h2i}T8?K1$ zJuyJ!T0;5xP9Ju*`F0FtzH$7Hm&_{5?KhxG-ldND^sC>@J>q5Dy54}#?m)yY?9iI6 zdbfT1>o>C89XbRtr6s$c&CrY}BfGV^^y-%AI170r>sM=rm}Q=uEmRZIa)}0kbWPqk z*vL4xmp&)4o>kJLP{<_{Yu@k;-^%DQ}h1{#6r9EjKtMW^M zW_WSy)qWZ1Kq~sXq1}Ogu~l5Es1#<{4+D9gi`TFBSB>q86|*ReysDZ?N6gsk%^?8b zg|$Y^dO+uLxFqn?gwdrb51kj!bP#{y z%fgX>8nKap$Jd^2a$ea`d`fCNh=^*NsyN^U;+ESi#NH#`9tBH&rQc;8NDt-ttN^eA znBQTVh`fyF|8BdA6F>$=S;H2;FlscS;wE?)y0z6BEG)1aNB#;eAEEV-DgAq zTB#FNEnLLSl1JmEtRTSyMBU*OnK2ZYoG~x_N1B>s5x0tYF%C-AJE4%Hf6+!MCZ-Wq z$-EB^g#?b}v+>kNQ7-GTcBL5LAmZv6itJfLh;TasDb_H?mQQ|C*5%OAiSx*Y_>uXg z6mt9`%eHw39E6PZlf+EckJr78O)m{chk^s4v1b0jh*pq87?!_3gq;xqL`Jzy#QIJU zQND+Ky`=jK<2>5TOL<1zcf;P#?=sBpy!jDlU}((8 z+yJoC7_l?p*jZNCIbqm&rEv+RE+POBH{(JHG``>ZT;Ojwnz_bGhUz&hd}(IgxHu_JLaBmf%A0x$Km?gy_)U)%FjjwmU(ML z^gtNo0dY#1c78+vxJ^brnLH}d52UG+3NL`8eJGy;f-(nul%iAbrS|50_RpymUyPDs#p zTnvqrD_}j1{t2QwDpRapwF&lxtE7^9{EGLRfly6HUr#H}K$ho($yV2u5xaNOQ7oJe zN_`aj63yr`5lO$x2p=Gk+a*!R8xG}+2rrEY9Vk+vLdY9?dBz=#-HplVATV5wlByB1F{|R zvYn`+gBhWCx3PC;+2I;qSmm~3aeYt6s(q8M*f4Lb#+`7JjhgANRgFz8FoEVwScZ1) z_Tzix-8ecsQ6abBD6|c05`*dm$071^1gM z>p!OMg)c4|%`(6Ktp6iG?5Cz{OL_1nvD65N4AY>v4HxhW`XSPI8{>|Q^??3$--)sB ziD&>6IKc|?L}@zoX}UaVFnS=49uYDIZhZ?h<*i88ArEs7U$2>Y^PF!v91VfrPH->o zI_CZeP_YwnhJ(_7MZ63oioIz>Kv;gnFFm1CN3-GqbZFl1H3G|z^J?o$(bu~oKl?(c z75Gom8`JVP?F_sf-GO-=e$x_uiD5rUC4sm=h@JW&jN|gD{dU^l_3TelQ=jk!U>%r( z$AlR>ALiU6x_{;8Kv83+z)wg_L52s-KL@?;IHrsarh<>(B_8#|Ps@P!PB$-@R~cFC z9==TcirV>Ao)iTU>{^A0D)vX z1?WPz3m-R9Z=yIO?ouE6A<+L&t1e;Hz`-aS3SpNcSeRlIA;+^q%6H6TiI{{=D)W1U zg5HN9qWKAA`D7-ce!WXwYSrgh*~d$S<2AcZ1jA$S#PM~_q;|EPcA?O#Jrc`C2*CB^ z7uRy_Gf#fA)s`14uctpsWk@fL8zj&UOGiENEBn$;!&V-h0Fu=G*{(tURURb;tnQ!toSXwe(h@(H7M z8QFo6YCd!`M&dtmp1kC)fjB$1KH;%;?f@w${X1>Y^Vk-X4q{FLY z@KWoVS8<;Bw`6W=sDx%GhOLHHhZ?=3r0pPo_OU-}`np^NHbA(eB3VvL&DZ)B|Ay^B z7WY*3Ym`ZQkyU}z_fik~oW88%&AfpHpXZ|8FrUw&PY!b{pSMd&ERY5?Ue2>DFWhmI zBHm|!0ok^%;B;Gs*``^J$>T;9sY8cH&zrJR6Eyb!EkpopHBITOii^ojw9MB#Je8s}TvbV$8*JFPr! z7*<`TgN{Jx2$NFP!pR{YV(BmVm6jH3`;6EyOz}tIr}QedRAq9ih~D2D4bQ|2k+2kU zfZpJ2`BZ!_bI&eLkcSduD(5o+4&>!{?lwW+!H5O0+n*{tKJTt!Wl_|c!05ZeE3(EBBH5~hq6FeQ zLPPzA(Grit10l)7W+MmpNdVMdh)eNCD-#FCssi@Bjl}j-gRep7Sr0|fXMw}eyiD*d z%LIs(0}&@_g`?!80rM|QXb5hNo+P2G<<4cMn)QgV)?e>5NGphf?XYmSQsRFiQ;B3s zFyNPp5pNa@16nE4j3G;Lfr7H-vbKPTzae=I? zEx>^#?Ur=l{^uOG_6RB2QxIVyBi*F>WbW%Tb``-$su(0ka_2l?6va43j;!RU7G&jm zYR$@Dm0qtu!c4zXipf_?lwzVK9OI35z_#MWmDWlCbR+`cJ`P0mGI?iCvQ`oO9G@Z= zx5gm#3|sXYg-ua%i;8rk@$gK_Pe82n;tyr)VkDC{x!&TG|gt5^yQsq z9z+EF899m@)3j`OqX2z%WZx1*K5oXG3T z$f$uSa-I##1vBRJabi5#{ zPT)yz`XZ@)TlLzIQ~LU|OI*-CZ5q^6HtubBWhB|T^Lr-}YWOh2gTt1f1JQE|@gGv+ zPgw0D1B(R5{3kO>>!x$gGm#f!C$vNx;@fUlB9^dVUA&TBF2G}yWfG~ei9q6g^S%cRk z%k$eKrso60#gsMx{^stXBu956>&=&sU97&-m|!Dg)DRK2td?I@uzSpFnv6Jt9#5ln z!icId4Vk-DCZV2{7i1uF-0L2hvd)VbslvSif5z~SwJjzvW{VTZm;OsSV?WQDS%1JF zU`kKT-)sWlmiG(;E|CU+AGM5doJ=M&{66y#ooVVD#;%{+Mq3%2s?g?$>;n5xYf<1J82PXhtZq z!enHf^JgAMCvoM=@azjgSZA6Z(KN8x7}}rM=>%@99pQvQwiv{v!S>ZZwVbRQD#2Eo zquyEZke{85z~QluRL}Bf^HSMOxULh)?)|GMooQwA+RRZ|Y3sFT>ILi7vxwN?sPX|O zCHJ7fF7OKPIj6ur39409xlafu9#p@iY{{fOFs?MW|YIdVe>i}REMy!ynP0Y+q}Rmch>##{*uXB12% z*chR)fPcHQ_}i(%BwrRUr-ICz#`&NJ1()%X(VDvIR4S@s1C*r;Bc%YtHSewcR3fAc zLEJ@3lD0z}1Cbln6s?nV4CV9~&j8iA%G{YHPYtZVY~{?BrliuN6Zk4De$y^2VyP`U&MPd@pjG%XP!s@Q<%}2DE8`)jrfaiE)RJb%(p~((Nfvg zCReh8@exRi9VNAqqe#5K?6gEtoPn>AjE`4HOQq5oJP_g0&vC-PGc`3OowOV<`#;VxCqNYbZefLdD42yjPoQ4Ex%V9!) zDP0^eYF@=s?JJA>L&SHKsQ_W@M@HgPwi3l(O^TP>8{u)cpwok>Q|;%vI0t|3Y?Zb4 zpR}^{SE)3go3{M^W}0NIg|4y5MT7Q>9Ssgb0gAi^s=SB;cu<7ch_Z~}@E7O^cq>9? zB2u`oP?;B1DlyBdoledus1^8cgfWIx?{M1D?a;yr+#OIr6;{v_ZlSA~%|&ZPR;8GX zuhONcdI2o5zKIvnP$Cvo6p6xk0|4+xVNmKRis?maIaJtty>$ADS9!bpcD-C1S?Q?6 z^up`aQKOw28q-rObh$BbPqXghRKeMPX0UJh@WAfp4;0o@)`lxJ=&9iUQ*P)BlTV}v zP!1|sg*ypXzq#1usip+_m@?`uNrpt3xp8dCSZpivTrJc8@Pt+sg+; zQL|Yj?vIgnLp8qhigI`u@}dMB1JlZQg9Z{}@Khv6*cDaag!F?7FhvY-T`B=r z8ab*ijh-u=z!6fa2w|vlxFAPD{KJ_&r+_f?FwaMId+4XhB-1XJ<_08N3 zUG)tg>uC@Sd>>Ehm?OT@ftn8Mn=iOqZt7be>uZf7ii}i#1Y2@O6^GJKqBT7Bj&N*l zQaOGV8f3&_=MM$i6W?VF6W)55!;$h1ND>TT)jNTk)GHw!cJDY-XB`XexO&S`b%h^K zv&I_wytp#ds^S{q{SZg6Bqx}XtN-FO1JXFa%r!{PJMe*LX!V#hU*)&O%bRmY4)g?;nNfa4=6Dm=B%33=g~2E`6R^ z?Zj01x%w5>-dtPT3IKquK@bHxE9^{H9A_Tqa2X~WiKKul$-vZ=@do%Bl_{=jLP51* z;$VBfns9Q599E?nX#=^-{qz3V$X9@Sf`U0~Trh&~AdG-F6WBUu91QnwNx zmH($4&3bN!H^4Cwsc;)9SDS&p1hPSc__ED5Of_E5fMOclYfAPnG*L%UtEH}~7+<){ zB86+sTAP^4o0L}5vK;WiAP}=H0J6zbbhVbaf5(q2g#7%lpUNd zFv$Q0hceT{!i5f+))(O+P1l;Ln2CG_J1!RK%@EU{x?VN;qAqF(X0H5juJUs36X;o& z9yD(V+6n$uwf6iLO{xxFKy=sgtB#BLZBzs-g7`5*p4~XL9IDl*8PqDPuqf(Ph}l#` zX1e2Q>#O3y38HG@c<|TjcF*_e%SHq!g#_09*a6?ckLk)RP&TO>_oxtd0nMUKoe>3_ zS~xK)p`ER+YB-~>?F=w30Dr`1-s(ACb)1a{gyiV@tt(6d-6*w9`SJGUQZylUiQvQE z7EP#!axMDd#0uzRy&Gx`$RB#9Gt$X6LM4rfzfXVjSI~a?C(7=E>M173D*gu!K~eZ3 zvAY{dj)x{(NZI_g5y7yLA3EA4^z0_{Qzo4Wj$qS@i@!pkuax9$QGC{@Gi~!hg#icAf@x6_Yq8jCv4kke zj|aLQg>es8ax_emSb{<_QSoiH2~*ynSMPLH!x%+@Z>7H>uC{b#hZPdfWJ|Q)V8Vbh*9_Xoq9x)9HB(E9@w#RZOcf?8DJR z(+c7LgRj2~YAf6WckP7W5D4xrrMNpZ0gAg7D@95R#T{BC5Zv8e3bbg8OVQ%AP$*s? zxH}XpIoW&v-}l3rbIwZgHIrF0D>LhPe(S!X%R+azQ*{mv@}0k^Eq!4t%+a#v(eOQ3 zUQan}R@xSOF883wdDy7zcnYa-zd&ca$Di{L&z8Poz94ZK?K0%jUj;{z__-g8uHVR638~DNB-(dWW)v(t(#TB<2+*mqVG7=|y`$va$#`$pB;kBug$Rv4#-$Dp#cTBp-1T zQngX!g$t1?8OU#G&C_K}NCYOH2fDh&Eh*W*`3iT$bm=~HdEp8-VBdF9M(d9B0Im>W z^s*luCebK~)7mdc4I||O$<#jwnIJ@7w?f^3&;0sG@j4m29`XhS7(Q8BrnR}*BK_Y#_A<0;;Ia2R5ps7+#k zMWPHF9H#i0z5}|8U?9YN0x?o3I=~qpV6vU1DN@KpM$<040rl%O&@L}Mb@P2pbH8+< zL5mIq>Qh(Vsxv@WDAVqG|GlE)%_-m?o|0e?AYB6!+oWH}1W3t+5a*f|t}goq0(9TY z^wg!EQa;!*_I*UH*V?guiOD9{V(Q@0~{adtA_5xgRTTWcNhj( z;hy*7W-tT10Af(Y1FjNBBO(*lBYP<$>lOG6zJ}htAHxs(Qs_ub8jxMnqSp8oZGaz# z0DnD^iz9HKrjl2#hO1WRN>qdiAOie;-og95{hvLjutZr?x*%~35u%tyP`5tm$zK@5 zh&qN|iXa79E}*s29aLAbTm&=g!<4Nc_47^i;@q7Q`oc!_BeCSG4FlT7q&HhIKUIXf zRAB1+dj9s5Nlbj$diT#%&~p1N0wQ}14vQmM1M#D)+RPx?)*M|qX{tlTC)B-MUQ%E0 zW#24}{E;5;*f^CN#N>Mb#hnEe-2^Riqs~_`vF0NL*v)5NU_vcUFP>ll5I7{9hL!ce z9BhLBP^&`L{gG&DHO^koRwWT28FV?k!9<+=L`MB9*4o&!Oo2dZaz*fpjJ*lDdT3-l zQA@z$sOH1z2}r$EC7JWL-ynGdguG(Yx^xZ2Om117G&1}3gi5l!~KDWqUR=N>zjKQTwLIDgWHCHldHq(xUfPgZ+zTx#xG=g+s_vdQWFuqaCXE--M5SUjKc9|7Qv_0iOH%)!D z9qxhp=R-D{-2DI#AslLmE-g{`3O|5Hz3iJP_c(9i<-0+S?k^--z~@5G$zwdMO1~nE zM~>MwEX)jk%6-4z;U#$CC9Dfe{B$HPG^VMFd8^qfFx5Xu?mjufYP72UV&LjJ->x5r?Kr$oTsWDSf>~A(}8P?e% z4f8A2>DLCI$0riK)}B)l$hY^R2a+d@&7&;K$>*Eme&crI2MJYVl9SXJu~6Kk0OY)j zA2KBU<4dX9Qkso2Dg%s`P<`YEIYqnhryi0~>H3AITp7Wa$T_4_hxgQqZ+gD~Mf>5X zxADp&wRN@Ibk4k<9}9&)djQi%`-L>TT=W<#SBW;53gD+eW$EW%RtkK$-678i*%n#% zQ~TItllnq%h<>>zz_93cpKsBgvYhhAWekDvZBmPU=Du3W)&nn=hjaoUZr>liV|T*M zH5GB|7#mGyR$I0e@`Ol{YE30d|8^wFpY>kK(WGb^Jj}t+wn(rmzst`6~Y#8p^SU`xhpWv6`URcewpFUMm^!q#HeOF%)&RQZQELTG@MflO6# z(ETi)%sT8TN|qwI5+ZS)-1oT2j{uPske+(NYJHQx4jMw@E z`X@s=9-QRC z`h!>MoAx+0QKQEnIlGw9TpwH#9H+sIgw1ePO5wENu)acYc~arIgN_ZQ0V^&SOBA6W zP#&UGNWzz|BJgy$^@=Q?F6;R`s{+Fq5|~*%$)ON&hF&r5DHdxYS1Ml6PQqA=-W;ap z!UCXLF}*}9NOSEUub)b%EPAo*vaQfh-aHL!EhE)z;s(sn{IqAJs3P4flvQ~y&l;b(|bFU$-Ari7*nT{ z*1?5vtCFYsTB>}X5rbhsDDdVcQs}j#!OuJQrs|hbIK#ay?_tnzUQri!lBLC@+Ak3e zV15O1-MCEHK(2q*XP7oJh1O!OxWCKNCKETg?WRxQVqJ^AveL{aL#)v>fbX_i!xDi~ zLcR(ua!{~W>(n;62D0Bq@?I|KUVPMVpVCnMmBC4`G#n}apInv@Atm~vZFqDd6N(AJ z4EHl2ZvQv<>@;Knv(U4byvfarOaVw-&MHVc&qaUT;<6r7!Q(SxJ6W1hNi8tWBm`Sc zC+Ams^JTeEzJrE}*>wK(Wd+Z~p1K4E!?q-5rC$D?;$-RvkAe%&jYHdg&H)sm9kT+7 zc5x#6=Gf1jL%0tr9G`@3pvr#|WFLB#;76T3)f0EF*ZC06tC_p_yZO4QA>Y~gMF)ZX zZeMdRgNwW8($eg#0$yNoxO<(pWquqn<>?9Ktvq?emUooN-WgeR^L`Qv|v;seVdM z7k_iFcosnL!QlB!_BSf|0OZ*DkJr_EP9HN{Uz6jThRWUm6N^sY@8F>x0rezOhX^zW zcxkV^DEZdw1?xX{^`W~}7J2U;;%~@M*Bgt$2CP0;3;f_+1bKUx$NRb5A->4A@n_JB zFsK!-VN|$`M=f7a>GUcJLsH>m5sv#qDMN3M>G`FL+PBz&lh~nlq%)Iue_`=V$gte^ zKmX9>IhJ!vrjKV$v>9MU5S5c}-qZ*FT?D-q9jYjD(tZ2ee7E~GQ`Ntd%!Ci868|>9 zuK5CkOlLerdH4e-?PISj{YS^7*`@%sKMI3STX4+gaU7DKT|$X1Ts@oXQrdsAeG~X6 zsr^8%yFW@yG7j6MokU)*5#Oxg)7IXsxvp#qJnj;++Vm0xSmB{;dYJ}#Zt?3cy`s2f zdpU}FJ#1K<32Olzy8szh;FF|vYC)VQF8kFzinaVWFOJUWwLwpQg8Gk32X?+i0O`+* z8H$jYdi8)(SF-vZjtp3Ny+FKuJvIYa%q$Bj@oe*CG z*4H41yOZbZf>}XMvBybMhV|5yuuSeJ*x|e7*zO2?AvPj+5{fAbAs2pl@ju!meC|^W zzO#P`Ng$!KKGABj&wFGvd>+lPTtVP2?^}ZJPbrMf2v9nu6eMR9r6gd#pY#wGoUI~> zGUj!DAu_QBD&IqpsTy@*9R4oSbKT{bS7pR4qBg4`#F&JwsDZFNnQ?0E!K41{(Tc83 zk4oa~pi__NfRK7FhMue%*P?`>anDZBFpK8g&|3KES7E*jVIdI_v1wreAei4;1STT-{HrjN5S8+UsK7LY z{sbcEwtnm(ph5aH_MA<8+*i6(biyPGWF<7nc&{Ynu1v)Uf5za+ z$^nA%iK=*}!Mqz)=)CxU^nwG>Ux%b5vsN7Oo}hF#rd0PCyK$XK9>!Xd zNCL2O3MG3Rk*bUwd`5+#64|H;PE(nf(WGK&GX!c)&p^LU5kt@wjz-03VWsCYYQII2 zipYn{44bpoIL57572w0~2mr%TYi@&vJ)$lHhAhLES`#x`97ZaiF{!ab^m)90KdwPA z8?|3fE9M&NTzKhxZ)krMtz$-VWB}OAM7ir-&1l6moo9qtoAd(>4cxC_YGBe;=!G1VtV#CdQgIGXXD3krbw5L9@cWZ+FUOj7r!cFA!`}R=l4zh;YimTvR^Y5hDEc`afG_-t+_Km!g7Rj=>ksOi$jxVBM zKr+Bc+|Fc{*~0h@$>kd|A8TjI7e-%+Wt*Tp;#7ac5!JB!#?}&t+?Z>OlSk8 z4?;}w_ix7!vo^jY%p*RgG=H74)qyTZj{PDYz&@dZ6<~1iYWLa`g&@=pA$kn)0{4-v z0l^t?n$F(5)^cOIes5bUx9;DrsB0}U78@KOjGzUVIMa|~&X+`@=I)nx>})(XGo8gc z18obNlNA|t2=xl4o^6s|{tJbVbIjOQ46?nF`_&Gd;BeT(WL z<}?oUq;f(98{4KEF&C2i(R~7u*lmVgOSx_hg)a*}GW8=F)y+h|AIg$wspRf6kYjtC&11!o4f`pCIU1Xfu@+ZvPG z8gm*84LK`@pnybl5pc#YexWt~&rLj1GGU<=XObCeD*+3>(Gs9Wd`L6s5Qh;UNn4BX zaodsz7SR7&*qeUIG;PUqlAuXu5WRoO)3$gP(-a=5RJz*~v9{E$tW>#$lTZ6^HJb4AzoP7G(zBW`;;*h5Khkw`IlOW+h8y zqtgAeqqE;+(_~}4xGC_@scOrqx&3eM+&{O?KPS;A_#bIZVie)~ZKl=`GZvLdVP@@_ zHyIsS?_DJ$U$C-_n`}=?rk(jG9NZ+F-6Z_YO5`IaahijH{FA^7NhGGp7gB{V|KhW@ zVutoq7U>cZ|B|Qg<5g(#_Fm*k?1D;=9L8ya-&7}O)~uT6^SeqT$V}vcYan{RNTbro zEAhmMM)h~sP=`D4k2#F#%%W%WZvC@?R1!gI^G%}dX;L{smTMeeVA%8b9* z2v8QYu1pA?X5ae><_|4Y9}N^gR*6>xUKRp#RO87N<|IH%zD^%nDpy}LB)rE*@i_p^ zPMOZFkLddWoBXN~VW09#oh>n1H8UAbfwc8l)f|3>w=@;DfAw8`Vcv#_twx2p#eboT zHPJcjtBYLk$g21p0EeR-lqOR2J!L>T1GCHqI`c2LK3aiI@4USnQ8zGwdoeNdO62=W zjhkrjsqI#R{CZ03{FpG+7N6p6j7UYW-x!klp z+Gs-N&dQq_LpD&4J=rWkG()H@^L1OUdApsl!bFI|eVanK5s}wryNFDO)Q7MBzDim* z5iv#TM=-nsw#XQMIK4s3dNNyW|~bPxalQJV4fqCWpxpGB?+gq z=%b5ZmQ~K6o?*Vvvrt>U@A`RXE)YRa2^?eas^FMaxsnOX^$WZ2Xh}za+F^uVk}Uho zO!lMrx^Fm`rfv;!Op*UwUx$x*VfSROeweun7@qc?cH zsq~j`V!aUYe*MYRm1_Sw(@g9qe54YJDFH>lN%}~adzqzs7?gn+f<2VY#U4O7Erbxz z7g7$iBL7kxCzQyZLTmrcDh36kW!+4Q3K^+*zrazpAe2AKbV8_QLcUBc=P4%jl34);P?w_}%#aTKID zN+!NXA<8xZTxXMq8GSXF7TrfsZd3)00|Ugi*O+dK&r!WhHzC~8aN44f4?M*TukirP zR*W_U9Gfg;kdhT*j8zWSsTbvB7JW>+R%)tSYqyWj627%zJ%jx`u_8-rUrjsH`Zwd5 z+pS_DB@M+(dxcjGq#=9&eS*;n7uC+fGAW^qeh&nj#XBSlbHt&v0Sv4b!8+J$*zB3K zDdK9(a1t9qJJ(>ZhZR1+s+BJaI&s$r7R}jWZh!t~Oz6WB5Ci^SYL#~$T>wQ8(n$xX z3L+Jv$a%!m?1gM$j3__*2V7FPs5t;7Z#c%e8KI5^h+FITX2%oulLWxCsWi60v>0uN z2d`hJ$#W2)pU;N~qp4L&_ptlFuB(_I4b%IWBk(B&xQzY}wc5ZWb;s=Jjzg>Ny4W5_ zAW^&A=7lV&ij_FYwb+J}{JP(Eu}}(pJiH~Kc4g5t&yxïSfw&$^_);tq_6PY6+ za>$!es`8Uk1>*)o?5g`KU_ck~mxz`!WY7?mD*nGETv^eWv_`jhkaBs1sKp_tL4%*O zI+0xa<=(3aeVn2U=k=pykgtyHZeE*VG*DGqxDj@Y`OQD<4d-07oV#2?f!Y8pR+1}u2ltFXv(T#_ zBwqTBAnvb{EpLlLE&rBz=|yC-q#McG5J|^7?HOl2VGXU!ic2=#j=e1Q-&UG#lcKC- z?v>ho;hBM-f?-*vJO-!~XIDpb5Z=D4X*O?5Dv|JB zxnYR)!_$vr3c1^jzmy5`EA70)TvX>Nd6Tfm%Q7(gKu`N(S&4K4YTG9pmX4#2&aX7; zq7Tm^8)&+donr6RpSYPk4Q}$te~d8V`~IAPLj>^p5|l0>tM`B@P~B?gIazL&M?c86 zvGq9u89(=jo;g<5W8^gd!L=K(@mF~E#fEgwB$y$fme5zhNM%y>u#bS$vQF#CR6kAN zWkhEXHLEWIzC6@Lqj9tz@Zf_l`8ECfcr(;0SVQsMj2CkwS1rKIZ&R+FkAB&GEZr-@ zWZOn!ozwS%UBcI=1nSn+b&cQ{k2fWz*W))Q_hm2P)FUsSj+yDFt zzI4Yu2~ZK29yN7jxY;W%50W{kBZ8>EvsbbtT$Ee>Ay?dH*-Clx-tO_GKreQp@7Z9a zi^sW_?=NFtIU>PXo=zs73o;PZd1*XceMd}1w zqHxGNaj|Pe@%7;;&x_pIcFi$NGZo3Pp9fvC-hZ5(yp=O75#i9Ft@4#pDY&}T~Lpy{_v<&Uwrc7-_u_WNtgDV z&Ke*l4l0FVB=LT6iH7^UystD_fp9tZT>IQ~9np?^)3l>RKX*n$LUpw(*N#QlUmPiB zWfy{p;+G6}^GwERnN(M6#{Z;?g-=7NWO}N_fOM3-Z>p=YCs-|-E9J|&D3U*iIlZ2^ zG5dsjMm8IzB9mo}8MF2KYnCb8ShUytWhf1g!UO7s(%*gyUw-or&8C6a`l1dpQxgK%+^);>w9Lz#*XA#C$+`V}!|iWZ zqr~x7zvDt#u->tV1lgPaUqE z%mx0;HoYDJXY6x7M-q~hI6tyP`z$SqKmlGVZwX_f3BaprQ!UL4Al_H?V)=C+Mb9Mz z+?3C0+Ytu>bfwkq4M~d>FuP_RCx~aZyDU3nx3@356H)Vsk1R}Rt@8~0!V(mJIDSD)fw z3muTg(2a!Jn&7g7RTu~BwIC6?z}l~rXx{t#+jUug_R%}950i26e-U15qiH*DH+hU_ zVi_o^Mlf}1=;CJ?a=U&-p#&GnP8>V?{++7>v9{`#F=vA{PH2%I>Hww7&j5}Q2Mqs4 zD7yXDM7p-N8Q1sih)LBug9g)}-Qk?>{z2vaUkC->3*u6Y{JZk_1VL zX1@?U9`gUDfQu6M7_u?Btq6<`^Kf|aes$1KlEcNBDoFPU9QTGK&n;+)Jv6j0h=L{X z_?(h>mm|5^#3VFu;e{97VBm%i!l>6xd)@E5Pr#EKh+Ta^ja4XgUL5~MoG{9eem&G_ z3nv0@{g>)Jp7D9SH#H2MuvjKtKV37D1p*#!`cYBw2ik;6M;hqv2P!d+ePK^MB zuzVPS7MgzY0K zq9Rp?f@%H2rLm$4eWLPBM51pXv6WQuyJ4P^RB;hRp`s`=Uq3JEn_yKR2f(mg=x%gV zC0o%hq{M`(j4Lt;m#RV8xY{p-H#0ggE1Z5f64e+@`ZjjLp1*Y-(oP-heiP+y?cA#x zU85S8*&6x1GLGrShh;ZzLy~K981n0evhya)3qU>G6tf^1S2+}~z7r2_iQ}P+*sM%c zvPr-RNpLMn@WfR-GScreNmN5d(k3U-G$di1h0Aj#+;b(X|4PJWi3i>qlD*dbtebS| zm&7ual;Iv{A(=AkortR#OIDSVrI(C;Y=S!5&~M5WcAX%m`uhER`~`JDl|<}qYsxbz z20k?i4_9!4eT)t5EqqZq{gBk1!;bfR=yh>(HOhA2Gwxz z)4%$lOOrklm874YVLyUc!;K(uNO#9$FnJ1j*^=&|nyUMp>N9}#t#PWY>8rB8G4)xI z_uen$@G?EBvI=0C^HULr?wRPB4gUpwzv46-f6+*ZEak!MhA1P$wya{QOjQ%9LL%X7>y48YH)Us)ese1aPhW3(2q7iFV;RC+8lMV$B;StJLYJaTr z*?e&qMl3w1a(cq@8msamM)DrEG9dm1|DsVmdsY4ix6qyuoD)+YFBZihsp$HrSvT2* z1q<0%UkgKaQy(3QIq`}JxQfb^im=t4mmG-DqAQ_U#x+d=r*wfVjU2`MV!pdbnw&5? zb*dwORz@>FHd!Cy!R0g7M{>9luccuF6 z@ldk@rI_+j+|u%=rLG}m;_3)@_dxCTQbV)yH;chvT1%p{%T3;uIp374-xYf#mrCE| zbLEuysi!#Yg+DPBe7f+_(@X2r#Sx z2d8*ui=W~ri|eIz-5YSN_Hr)ws?ciddUV`oHgn-AF*^*@f|ds%L@lQnAZx72|6hMi zLlAsZL{tEUw1*IPozd~e)ZF6&9|Ung?u6rj+L<$uhg*JRJubsR0~5g)7M?F`8ed|Q za9NgYU8rkF_DgHIYQAh$*ji()CV|MtM5K!NbBg3Cv6&#`ixn7)1nA|1iGpH+q0M%V&2M9y9njRO zc{67cV?1_?J5P(JMvJ#&i?2*e8x-%uSWDnROE5ue2tlhOOKZ4eEBpgq)+yG@p4RxK z)>m+B(Vpg1jka|2|29#r+H%L*-p01&EVUJzw-xfVmyb1!3T-lu%{BSlgwflCWljG{56_;tYg(i0 zw`12_Y}bNJS6DBO-$BL%#}&ve?8#pGr~b0i1p_ucUCx{Uc4hK$j@9_n(E%W%9`a*M62(sJ4Tb< zwPl1lk+3{X3An2aBP31A>CTxY(qM*ITaeDK5t4-fXWa;m;aHIOO!5hFQmT+r`Yj=xV9&WBqYLy+1=^XCt9E%_Xbg5H%o)SM;jic6x zA9_d`px{YC3Jg8GBW4u<0C*udM8FFHKlG3g0>}b7KX+#3L5OaPK2`76#^aA?7mr1D z{y01wJ0=|OlchwL#ILIVQxaFQCjFHJ#O%d80EiMW6Aw3Zkezk(%5(ytV3%q9*rdhL(!enP^z zSPDEt44X2knKldjo!9W&f^WvErsPZ6kYW7vuaPNUnHs*_*>`_tonGo##3kA}&q5u3 zTl38}S`7OIlDzseN6q(>%VFBPCdKz?`q{)>A#yG_e;x-p?7=thr8OTOKYQLfg?`#7 zyJjKl=u7E-UaE6JM9tg>xy6>{-k1cnI`>P9RIWY<7U}~ z?@#OgpJ|4bqj$N5U4M!f{`|(DTdP^g%|5rjm0s+_g!Jda40AL{}x>s&+|BF9K!?G1@qqkB39Y9bJ>2I zuB+#dp5FMC2?l)*3=*u58B^+o69kl&8Q2TaZ&CfvMLeghRGGKXl`G;bVh-CEJ;jkse zxcu);+@k`aqb$9n+2cb}k0Z^7Bdn>Ta-XGZ|iV-2C>&DuYf?#CQ@$H^_nR%gfi zE5|63lk145mZe!qdmvBm8HSB!c)p;tUXh zvtO{YNB6UtT&xkLrkf8ok@bwxPOP0PO=hJ6ehDJM-dFvL_`F=N6*neZcYde$0 zfC}Bq6$n0bgT``_@Zgk~j0Xa8!#}Vho`gE(vRuD*y#_NAEDE9>TtcxB8rN6X*g*E> zIA8PCt5*UL2`j<_UE&{;*8n)diWTuO;0g`9?Vl103qt-E79~-kg}Yvc5(C0qZ=#+- zVpnex1t2L&;G0RJC2k0&V?FKxP2R~B6m%C^cvE(A)5ZZoPvrxbX6gj!znt7Q3EW`{ z0e;l~C0Zc7nk4#is+W;?o5OT(v3lG1>ZbV>WT@~#Gl_8Dig>vP4-@z=8^!cmkkE!1 z^UdT#A4zq;S@l%N%f;_6SHu`Z%)kDEp+IYbgf9S?yQ`PS0Ek_{Wb_bT4=fCig8%ir zE=#t7*W(0i7mqQAW4u$#ZGOsDF^cplh99sdfrNLqHt_X`@TO9@SAEUF%&%>&JSp$v z&9;kFnGj4cQKk4q42cC&lzx2kJ5Kr=Bsu%*?Zd)21ax~!x-XguU9bXoTy zONVn`Sygx^h4Bh`o`Pgvs~ygakza4mhuHmO)M_V(PNU~YJ=`S5RY~m*X#uUdzOJvj z#eoE3=4th2VfobwhDBgnGT~zzyFZIpj&CNQAmXdM+0&&doF@x+teE<82tcF96+Y#) zJD{MG<*maJdPDv|UTD>HqmT-liTny^r zyoDH^7F`1DPhkMUD7QX*U{NunAmy)323(?;@LZ4zX3+o{OPVeVKHs?OGXNJo2Aswb zb4{7#CtETMCr~L0&)da5F)qkOQZ?1@-Qj6J#M8?|g-g%yOa)Nc=)oTD5*?vPOpHMS z%hfjBgW}#;Ur@i41?eex$Tp?8W}7^bA-LCAt*CK6M>-6NwiF zc|Q3pY~XYUp|c>$Op8KbYkCU{V%y_uox}(x=g3blzz!DLP@IWxdeXwniDofE+EZxtGA*o_sy#o}LV6N&sL9 z(I{7MZkkzhWegCW#|8ryWw7YN;5S2f*3np2q_#Wxq6?;coqw4FZ?UeJU#Cggn}k7J z(u-NvLmHvdrqv7c@HdqXzloeB&qehDPNTm^YaT|wHUin4y=4mi*zd*8|JV!c zdcB+H7wR~}Ls6_#Km!06No2g=PxM%6+diMAqOK7kQaIG?cU8Y2Q^Pt=>QgaPQ;m`7yod0TS#I)xD07UT6lEvxc)1O zZktz$L%e&odkwO^ee1uSDS^Sl*hw?plccgexoPYUj2u?-w|^Uruw*o3N+)hF&oMgE z9ZKL}cHh~CEfKu8Cylj~F2>GjiuBp7pS{BY11wvG$oUV68pa z@`5ON&Q5F7Mt3aI~_K;|eh@x7rucQo|BF(@Im^CgW|X;oAO-28AZx1m1vRBTp;l zXE$ePp2e0Mfj^Wb+K^yW#U=^B#Y$M0Ak}i`4!{;k3Z|`(b8;H9XWLU^1>YtH!4dG! zc{%JP`XgbTMc4qh9}3KZ#CKMuOc94TAQip(IF4~>tt>7ti{zLY_h!arc32SPSHia* z0>C*pMChr*$PM#_)aU>QfP0Ea4#O(@tA}s)Q^P&eE zd)$U)IOl*pS{!()tvKjeAmlXklr*#F@@wuf&P78dUf#iKI{ z6-#2NRN}Ce#i@FJi@impC0IlEOlBBhZ*A1EelEL{ zoogL7QU!$Ey~Mn_Zt1O2bVWbZ6)SW_X1E5V%0Uw4vSK3ovLkupbn{N{e3*OWRQ?Q}+Q$0AO1KQK_h6 z2(Jl=;wYN*k=ND-?e)9@+)(vgv&4%Rgyi^CM|`{feiFj_U_*#{(NExzNV*sjH@9fW zBO4Sy!#>rybsJ5F9F7#L?cwG^*;eW2))b=e00P_)-*NZhe0?ZuV%I#34r~nL3l}lC zK|P3RvWPsl*olzo^(_I`JCTdiaL7sMi^;2}7unO*?An!zOi0}enA=*M&#ofF@Tr5s zHUV6~ij8Sy{yYRfep|WUXezFmt&Bs0>tq#v-~UUkT5Qnm_zlTDx}%aJEjHPn_>X7>d8AcXZ1KGHAA9-e zku_woEmGk>;T&{ftVOsZ^B-#U@ggA+!wR=8#3m%jtL(|kJ&nIDliB~FR$uNLM8*T< z&%hsEBZzRLS>;PeqOGQ^>27gF0R`io<$dfwy|W_Zs`W5=EEE}kMAdP$l5DH#zdZS{ z^I=uz5w8~yMtU$p|{}1;$345_&xK)v2X@2hFm~sT0;Rfy0S}0k2vLpa% z!+-|VVv#$(GZmIspI!Yhx2@#>gr)WkQDkxwVR7>#Hgp8;(ydQZcGSsFnXIrLV4bi+ zo1C<(vA01N`Oi++9~2pTqaaRBwC zs;Av7t-KE%P&8Em9*-mHiTtA;WipH%CK{$nSLRI0i;c!fUt58~9UJ55@vjYrJkGaMb%8`YM zQ3c~$R^Wf#1zf{)nT+&t!#<=gbvc#Ry1_{R02<6iUn_Fk!EyKudSuOEIAJ{qIHuMI z9EbUK{s%=Uq0;YrOmB#iB8RM!(xHNOJ;o{=2cfQ{8mFXI-EC%q6R;bhTiL9(tfal! z3je>!x#XDtN6tk(piqBNs8bYb4TYLTp?;xIKT)V3DAWiF^&N$(L!rV@C{q+l289wq zJ^trF{d@S2u>0=;^>F)t19tE3uI}zG{@q;v&)EHYgC=(W{=GRvU0&W^U89fx0J~RL z7Z?B2bGA!^0ou$xKG``vKDyf5N59Z!?$*{83T@?XY#=u_P>;Xw z?xr74m#=mgQ4f=-yNSF1yoc|uCs3zj*CzvKXTMN;;}0j@_b1-he^$2Fes8ZVU!#H0 z({TJKPM+9#?Zj-;NSqNuLRi_H`LdMn(^PBu|$1;H9c&1(^qRzTFzt zBJ{ntAFb|=w)A&(eQRrLYiw*<>PcAo7CF(G{;TD~WUJe0L-tt1`^N^J#Rl(|hKA{S z$C3Jgul3DnkQep&^}kP$#|mt;uKOQaw;V80<2U>{b-31d^YgQd3fj3Ei-}L39iKlA zeDWNscKu%MF;L}<$_sqRqkoLHL4^}M2GgK|0i(q}Jq6L-1##U4F)hUn-B}UCQFdt0 zx4OEz5`7eYDk&)`EG*2=&(F=t$V$)7k1I_|N{WezNeatEle=hd7me*6eUR++f8OJ- za_(sG*F>el$1%eoKS#R|jpt@*mt<;}1P6wM`Q`fi2YC5}x_Sh7xp}*~y>oSSO|r>$ zbaZ_4<_$_t9L2$WB*BX!h1`%4KjL7cFfh>iZ5IGw;9V;B{tH_2l?ZB)2y7M)Y__(s zL&Lk~*6+;B%nS_;bai$ANA4;;e-4Aeo;`aeCnqN*EiEoCE-EC-&(F`p!-Hma+1c5d znVA_F8R_ZiX{f0vDJjXx$w^5`iHV89;QyoO;^N}||M6T92!w%w@&6>}4hRn7CH#NO zxt}oiUK3)6|3}VM`^q_vCuzL<{~_n*tBY|b;E8`7q`#>9f0uJxYX5ZjZ6!>Nw$#1) zCV7tkKRGvwjK^}^gg2o(DgS})>zDOZBOPu;XP&92%8!C)wnTjGB71Q~I;D&?@0<2! zN!z4DG|_S{1Xxe@NfBeDCN}ThJqTdR)4wwc3B> zT>J2d=D#+W;ub7>WogFm_R73<5+h61JATm^fCpLOe*MrT&`|8`>NGUXV6n&#G{@wut%qhxq)c8`Kj<1Ph*ex7f z*}PxavigmdwUsHwytegl%4|~TFi*M~`u!WvN#`XuZJi&ZrCT`Rf))T|47nqyH(ngX z%dY-Y5?j%>%A%RuPb|Xw((1+GB~XEJoQ$kS}9|+jG2sk95U7f$46~ zaY=X%xnoJ+;+(yb*s%EO5fb>EK%wHa|EQBK(&=(ab?8N-H%E8gdCyJ5c;<*8Q|DJN zsrz)XSLTkto9153DK~t_jRt9VX*{X9UUa%o_wm$v!IwXCJC#rITWE+@{IhT*>a*`^ zkgp%Fg7&2W?jovZ?s`2=Vr6bgmMONy+vkbs&@(|d6%A>W%SF6#>H*CIPrcZScQ1) zVsdWh4ijy^G#t13o&?q}PY=p$akE{@d>B*=oIJ-7d&Y28lF2U@dO9R<^B#B0?E7_N z@CgdVLaZt12CH0AUf!Yl+Y}S@tI_!!M=wIt+*$89_}-LiBgek zWFh>a1rPkFizC0yl0Y`O&cj3>b>C{-{kNFkTcXhv?2x6%aP8)cFwX^`fT{zmzwD!e zXqYg0dj>eA&!TnXO0XoE5um;?`q5S+2I|U~z$i9CPpe{yb~l_rw4gaE7)k#T5F4P| z%Um%$#9hrC_dd(bUwnRurvMOPTm-;c!5ylR)lH%aJ&FuSUA=^~Nh^z|sKE^BNaIyU z)D`Sg#(Gybd5fa7-=C)z5tehw(13XGHv<5z7Tc7PSfVQ+EDXFzVZa(@F<6Oykta$D zn~&e;yhZ=gs#HVy zzX+HQ!=1m0r`m@S=FY}dDy4(;a=G+ks3*9{s&KX4J(3x>HC3d65K$goWSLM9>LBM*s&G7N6+u@O^!c9sgM*xDwAnvJ^wD z$&x*l@^{7ERUP);XU&g`d7~ssG&_D6;O18Kq;J|~7}l>O7OnB0#=$6k;cW88dRS)j z4W5M^PKuhviQ}Vv48}zvF+TV+EoKueq&|4XZHw`Xms~p~4`jx)xp8}>oRA#H zWXD$yvXDtESD8S76VhOYgO9A&2n%tVOiuHXoh%S2Lx%s#=z%j^HOxZ=FO0r6wDUoZ z@C<2aB9TazFq+j&X#KJo0B-(^oW--~^TKsSdJbHdV*&^GCIQf8Uh1F=&FQ}$I?;Y< zGkj(nVz zAf{MHKGcy}g&exm(3aPyGu*p?dAKH4h6$Fn4eKo9xz4Co2pal~iC2FcnzE+P7}}8z z;CaCtg_uGe*bz?vgh3y(pu!y1Q4Dy+qZ?f~1wL3I5Hj!s7FQ6)KD^-UO-K9T)tt5_ zP5s|%*N4;s$+mO4z43D&GSWXXT?H~B4QbrK+z|h+5DM5~2UH?kA1@IGItEe*e53#X zt(XTP0U(TZ2*ev}1;9CG*(--b{OA@ox}&IVK$(nl)E1wK#uKvbjw3kLT#iW-TD=TD zd0e+<#?Ll@=kkH9LLLGsMmYwOt6de7u>f$#cpqz!59|avNYA?^C0=Se(>Utk1Rel{ zN4%y_jp82<_o}mwb%j764&?TF$|H0Nb-=9b0H8tk1Y(DNoZpEbM@ZGF&T*?N{?0Qo!X`?7a+C-9 zK2C_obptPY#YcQ!*IFP40BXQ>J~VmxQ40US4;J_j z{=g4$k^<%+4jKk2E;AW8^;`e|cXHQU2=Q#`w}MA>e#SC!ez$w3v;tV9MO@@XU?fIl zWJYMDMr`Cp1%Z04bb9|#1p|m?035b9T2xOJGWeI@>%NGsJ=X{xVA?LFK zzBC25QUeA93t-R%v#<}P;BVUyaQ8rP06+%&01H+?3k#=)ZMchWxQ6pFJ|j?a!Z?h? zSd7Lfj5W|veaJ=S^g8I|TmZ06?(|OaG*18k3qBVC?eGeYn1q(tfTYuel9mt^a0n0> zfm8?~=W{t=@dN@f4)lNz=g@2dL2Sl`Rs)f2`oL^3p@O{lkNB~ElM{@`Sda!;a>>Yt z0+CgY1pu2fQYD2_DYa53)lxX%4`N_&G|-JP=wp}2V;>2U;D|$7rwCFwg`e1q0J)OV zRp5kJiUoICMR(8$0FzZ&mqm{Ru?p`X5B5})u_cb<*my^o z5JR8{t#(^bnU1`5l~uWyRw9tz*cSqJT*)PWU+IvLHG%>WUDH)v(^n8MkPm{$mIK9j zaJhJuNf2tF2+kl4eL#|Ud0%?Tm!cUZe%X^K2;VGWSIU;w` z1d6bH&@ck06P3~Fo&;K*(wQ#UxnbaBWAoW}#R;DGiD{H65Raz_xnNu22%VC|o(0;W zF~Xsd1B3C|VGD|crumJonV}O3p$2gTihu~U#Re++i|O`IAnKtwS{{ChGKMFgC8`iE zbE23Sm*1(MN@;usk(q`d4gWc#FR7k+d7wEur5`G#aCj{G!Y@5aqJ2>?4~m>c>V&Gs z1D%8m80w_);ZPsrk5oFP>jwbIvMki1Ce|{ic1owvGN;+HEqS$~Eb6C5dJxMQ2Qm7Z zpJ_B~+NL=ArjY+aDvnwyqVlMcI;oNpsgx=yrqZYR8K^0Wo&sS3hoA_UU{@Vrs2aMS zR;s9~njLQ{5L|MnXwoLII;&tJt8;2Fno6XADyEdlpMPMcDQ2qascEUYs>XU7H!3zY znyb3ntj6iAf7*Bw@CS;}1e+;e!b+o13Yx`wtlsK2$tpg}`lVpHsc&hn*{ZAjc?erz zS9q1KX*#Zm)2-iHuTT}P1GKFYx~u2w0#R{g9-r``e%W=u`K4cZ>y*Rv~KN&M($7tVqgyDAY3+kYGAvx zUi-C78=&Ob1S0?q(qLq2`+^+1xTq^3;kt4y2RtjV52hdxR`3sGptqL`ZkgM){|dOJ zJ2UHA0cR^_yo;4=%Rfh(y7d}9V@G{(ClDuC5O${%SMU!{paIr4=j#E~iUt}` zxcmFQ^*g}t`vkW;EQyM|Y{)&8cX_~*3i?10=g@BjA$wl23Wc!29NfVk{J|g`!XiAv zBwWHKe8MQ4!YaJNEZo8_{K7CC!!kU>9qb4%Ith~?x}!kDJlw+|yb1{{EDOxQE2uls zH+|Q^Qw+WW3&4F4 zW*$Js-8;r?oV^HKyz@%LsjE8_Xo38If&9?CaW{7evA5pYxnaAzhfB!c;-ZMq0s#MT zq2&g(rkl9OOUH0~qgIH8TIdC@8@m87yR{o@a{REH8?vD+%3^yWC<_2DU}=WzB0+4G zku1rKOS7n?43Rszm2117e6zXhiGKUHz3U&1un3C40|1c5UAM|4)5^dy#IUS)NQ6ps zI}i8p4SDOyJ3G7)i_O_w$RY9wil7Dpu?*7C$c}uaxh!pp+sy6BwY=QRgIvzPyv^<5 zvtU?zUysx9IyYPI?@mwB*3jm{f%*edY=lm}I{Lc>;&^ar} zq}(1HH0-@Rj;XKX*4MY#E!09Z}x=GPwX3?5k$_Jg%^|73gKu9;hd?Ej>tRpSN zC2i88iPFr9(HC9N@@&xM0ji213DL388Vxu6%qtPC)11cBeB09Rtj{jZ(&FK(r4SwB zOwK;7)Hm(QPTjFk9mq*d&{RFu+{_-I3mr)y4V+lkB7M4HoxC}XZeOj0yDZRMz0!Ma z8|%se&@rmcY1PSm*Zo}AbG?#d4a$UF)qUO0jV&G1TCLCF0p_XFAu892eXNVE%a{$> zkFD20Z5``s0necYObVcIZPN;21KltW_@EAZfzGeI+0)tCnETnHebztC+qF@lXaHS> zV5Wl|*%M=5FwhR$Fa}a!2SW(ah;7@uh}*cU+ZA2YyPekJ;i8A2$Qu7p3K?tN`I->I zuy$=*+tNLn)SY;Feci_0+uF??z@3<+;I8dG-Uy)%$KVa}kPfm)+v&~O(LGp8-J18^ z)4pxi@tqxrtjN&S41R{Q15`0OaWMpu5BVSrVZaLbpbA7Y-~pa~>n&6V9@RlD)F&<- z0t?Op@dBbtx~na&K2s3;aLWLY3^q>E=pEu!IpQ99b?>d<3!dW2VFZeBu>+CD!dv2f zF*X%m5bmH2>4&PEu z8>c)FquLBdiloDu5O<&s;q~9p-R6lt-5_qchRx`qozmFt-luL8cuvd|T3e)W=?W;I z8w%=C@&&;l3Zc%e{88Zc>E|Zy%aP94+%f3_!30b?39?R!w2rF00s#)L5UyYi)UfM_ zI_kKL;$9Bv+Ai$d?iX`8%me|flPHPH{$#$MC{3*uFJJ@~5EDy)4c747);`D0F66_G z@83@B39c2!4ge!?t>q4h1CMCwjwtK?9n@eAu2Api-Rq@p;9DN-b^hr3P8;Fw>H?wU z9#HTE5sBy?@w{p4QGyE8{-X{*@(|zc72oA8@A6-68~^_f09y_61b^;rcJPOi@LACU zXkZ92Ap_N54Rnz5vqSRrCGty2<`(bhO`qMik?{mE(pb;Sg-Sh!t(*p_tAg%Xn!LU00l9@1f8%6@2U_Bj|$y?*hrrh0DW>;lhF%3Ta>% zQR2jf4k1#+m@%P6jU6>|^cZp?NRcHsJ~TPeh$2Ni5Mq+X3_?ScDQ(iccr&Cxf;xTv z6uIKx3ZO+3K0&rCghUCM47Hf(${IDJRjppdnpNvot{H_A?V6D1R+3>)<}`b-Y+9Ub z&$?AxvuYegY7jzTCJmFpwQl=%9Sc|R!moonYS`7w&O`|qr&z}>GZicRU1^Y?Onk(MLjUPvT zb+=pGS5cF-{W-eX=US^{z1|T5UAqWzNy8NvZSC>52PW^j9KDxbzhqD}Vq_w!sp#$B z$DjY8`n1ihW_ND7&;%^4JhlL=3PFriL!>o>UVug#Cd8XeL7)87?c01?9P%by;M!?G|i~T zLJ!&kHrXhok<+3gWlNTSjsZZ1WY)pQon*iQV2p9-p+}rB46@^#dgSru34`W9M;~@n zk?2w0P$A<25If0a$VR87w%US}#R^rQFcpbgkGwt1)c?da3ezUsg!7jR{CnKmQNBIQx8Yvdrwab? zF`)|b>VxmyQ|f!7w6i)zouvvthz56rF~|#c`srsKqYIiN9)A8Y2Zn;!k;R}p{wV>W z4_07bAX@ROqnBMKtw4(kD2l}z;9lpyf8}Cl%koT;yo?Z#A_g4E@dl{CZXNG#7Dxyi zq~VMX7%z9ayWmX(Xchk_!~+Zkf!?*w5sr(L;2hf+0~x%bj`Y=l9mNR49LOP#2mpY5 z=0hJsXz>po^6-84@jzng;FB*{qZ&2vUlNsgld}O1Ms#CY2Din)kRULDQe>M?EN}=# zG(jQDkcK8ILd7bQ5hEL{N-6%q4>tb8AN+7u3d|vnr4(cp@o<_4?(rdEG^`*3Ap-z3 zXOPY%WPR-eAbxxk3yetMei9K5Dwa4&N@}EuKtW>}v6w}hZIXAr6HJ}Zpol*_@*qr* zMl^0PMo)e+fU|Q;3cN5&FQB6vUI4%f%s~#Z8RQl4s38C_V2@M)pcv;chzk3bSKMbi2k1fM#v4i|td8Peb*v46Uu|}M`(-D)n$0}CqkAW=NkT9r9 z21)-yG^CM)D;gLuEe=_Z!xDnT$iXLcFd_?XyyX>1`HWCblaRf;Vy~`651o|*Fo&T?}yeoJzf!(jgj z+lg$Z+u-;4_d%9D=6IuZ-XL!HOdFGs4&o zuB0iI@rRdLTs)X-T@})Ym{gF*D$mNoS(Narq>tWHim*alQH?v3-00~sIg8u9+Lnv6 z=}u>PMkw1+g$!>_BF1@~f1C9COduA!kg7xsk%SPLPe@~;o_1`(!dwJL1^0WV4tP=tOFpAOh)W_uS85R7Z z*f~m@*hIA#f&o7}-~AzJ{p)LHeMN(xzLTH7?G-`o+{1>z->1KmlfLDGKJ<_S`SCf1 zXo^n2DT&CR8hgJ8q=@(vKLD&eSF=Bd3qXW`HBUnb&I=>(%0SSoz|ShcNA-|$P1y|Uf zh~TPnqroY(BpVFBBt)JbaJSZALrt?CCm^!>F2%2+--8;iCOv5^aFDuj%kD~}tpazkOLn@>|LzKKb zq@CE4Jup;_|5^yEGs8iwKP23`IaHAlxPt~`h!&WVBU1?BFvUldz(~ZwJzP0ioW&zt zh#t|dgaE|76G1RU5;f!!HUtVA_!Fg(h%!LFgrE;<5I9$SKUkzYU!*-+)Il<1w1pUf z&PzEq2LPQ8L^gx8rgjqYhNzBLQ0>(6lU+cDK#>SIXu*jX$+9#{qpVAI z^hAiG%R*C0w7d(=QwUUwhO(PWX{-vY#1Fju2^zo%BOo`ybj7oL$HffIrToMTyvEG~ zqZCt2hIG47^dC2*h#FuW&tyE%ygzrm&BR~ zkr9!IkHQ8dqD{3ct5!&ddZ-6;SU~^?fn=Bmd+-M6G&SO6INiiY$~?)+8>K%`zk^T# zZ0p4GG|wAEFi}(zJNN~yg2GHd13yHFNQzGB1jjm&;nIV2v%g$ zk@G7sum^sihZRf(eK?47C)J5F@;8BA}r8#Iwf>nLgRJGMy#noIL z)hA#qT2P05ssYXXwl>8K7)Xp=5j(D#kEsaAI~6s*@&JVr26^a$KMmADO^7t@p;ah^ zZw1$I71wbk*K#%2b4Ay5Ro8W8*LHQ+cZJt@mDhQt*LodSLD;`ZDA!4N2Jo=ge+Afp z{nu6a)pP(n`pl9A8^?q&ou8D58K?$qa76!TJvQJH2W6PjDg}TmB~Fe-OQfnr5iCGh}MD5&%LOR8PHvJ!?lcmgmG27g!#1!YhN zg;1nyO0o@Gv30c}U`5Jh``Y30{=k$7M0MWgoa@2y~#HL(E%{fdEc> zNrj*TYJkAh-7?$MT;2`Rv8_c_yFDocfGtomAayq`)iEgh7c6DokFf(}@U@88sE=d_ zU$se3pe%^*U(K}Tlrmxfuv*ivg6+E;%fBYb`%T?03HD@2$-PNXxw5A z)8D&{VBQ$Kg+&O{$%L~_zF?TmM^>q_p;(OsWs0a#Ewsu!_GDki3Ndtq@_2!~$OZn?Vrk}JV5X$4alvG++GTFs zXoluM-eW<=3J93GQWy^juvy{l<#Vn~Lgq(uPLZB;Sc#YdS7f6=h?nUZ@MrfeGP>@i8yjTVjj_9KnK-U}_FldkWxQPj~2C|%L zZ`$eI%xViI>z2L>T$~AxfajP1PP@ix1cvFD?hvgl<}zSpg}~{zuB5o0%%A>WgVt(= zc9YiN2u_CRt2XIEH0!Zh<8kYRB3y{|qK2kb?7+TCdwyof{?e_EY^>-_oDg4@R_)b3 zFn_CR%W#5T=!O5IU5LVZ!-WvaYB6NhEPO_paU%EZ?2{-%LM=pm;|u4x!E@0m!|I4u>!UJxvu)| z$)zA-#rKqXod;u>;CrdK~`$ftM0Pd8ckLR($4QW3vYyI<_>L(p3Yqj zKZx5qGKaowzs~H_UT_t$XsxhshCpR)E(k_6NZleg`+mZ&^re&Vi zY|{oAC`gJ)G3H0G>4I2B7@zMCMQsn2<-;6t8V?D|Dy373kX*oU8}&i?-na(e5)i1e zIHiasum=BYkU=GX9T|UY1drt&m+PX)MD@M_uy*Gshw@)ei4zcIFW-`#yb1qA^E9t; zg=_K*=WtYW>@_cn?90Ur03&9Y0cSRJHK&S9c zUq|yE>;G2uRo97WOBV?E4ri!UNndYTuXQfmu~PVkeITE{y=PNbk_+gN_toydWr!<) z43Q)C7$0FR@CSLIgi1c^EPK` ze|eZU2@f|2Er^gZ2KY%&^e+qL8h{0LxQA}2gH%ul%+ZK>sTTmamwefmegS}g37CN? zn1XnfLXZM6sF;V6n2CZWmS+)HAOwwOh>Z$om7gRvpJhttZ<%-bSL32jdG1^|yqvFh zJ1^&yFa>bfhje%ajh%vh(1@MsnaweXpc$GmD4L^58UVP0eMnA&Xr_X&nyVTs&g_IE zH+yFHdYdfqE#LNgk9iR{2`Yc2IiEG*rF*)sdr-8AdQb+AM2Hgb+>96;00<#MLLC19 zP#nf_9LNCxSXc*GXoq&t2DKg}JMtX$@mTjkEZF3;FL?LNpWzlgTfo^F#+c#~+J=OKImke=mL`s>M_?NNq&I0reHgLD{&@hP8zIG+S82yXQu z{{aXmu22CeXz*Y`G@TwHY)HpiH4F_WQmkn4BF2mwH*)Og@gvBPB1e+MxZ>Z6k|J^Z z!=VzRhC&)%j*K~zCPxWIq}Q zW%TRlBp#T8&P52>{CeRVgUupA`V?WEs5kFYdt)D+d3wOiA@H z&O*JAO}NOT$%u;|s#&9h_%i0qnm2PMdD3v_f>tq44PCHwXw;omukPs+jiN&>0H{Ff zEXhRHn|1GY9eOlLe_9RNz}KLKs{XuQ31*_f7$zwa;LQe|7+r zBU^A)J&T`Bv!|G1S1&OtgINpK{yzTv`uDGA4;(RXngvLjZ|n_7AW$^%fQTYZ0Puos zOi*+nfCU<8;b#AV^vWy!$ig9q-=xz~3SOA#1v=e$0l*68kYmC@ufP*QK^WMR3IKNe zGetpR&;>v->KN2bIO?Ia-+i(4;)+UySVPToNJ=>+l~sb&pJ^IWMPdJi37W>`mKdfc zCP`{25(fkjO5==#6O!4RmtVelnU)^4(~dvx+}X}L;*25ESS+5C&J;Bm`kWQ{By&X< z-OytL02827P8edGBThk5+*6Ddt?)BmMOa#ySslIX;sHiwWMYIxBv5AAsIkgAE0Usi zR;N>7h8bsTymF>%RKQ}?gd&OXkOVVp;#QHcJ2mU7&J#Z`mm$QMYhtKD|~feWJo7)TtuIJ^ZNTQz){JYVM_?+_bg2a zzohWO(R$RvA&Q{EgfmGk%dEqfF|5+YAx#^wN&|yjk}JE6f|36gop2(7MWQ@8GR!f{ zY$RxNNMsNOb4XjT#u@kQE1dXsOw!N=nfXT_&`7h)QWq5+($i4;?9|5@9diNz$7sE^ z)*y>K^G8`Y;D7)ZRj^4XZBoPn9Up-GHrxSYnblTZ9aeS1Qy&)fM|^wa_uqPBbc7;` z;3ADQxkLt&;JG&LIM8(R3{tfKjB`2WmwSC=+#*rXzyk~1+le8an|}J{pb2+S73tkQ z`QDHF1h`bP<3xMyk#|(VABrR^jV3H-gu6z>7jJt>c%vRF=gW7*zynBN#6%~XSb)(4 z*g3yF_m{2r%{Tpk1O7MQv{U5kS9N(X@(t^5u+Z%vq>%s8&ajbt{O`m68|)#ipsqn= z0GfY&t$Ph2zylu8gNr~Q6P<97MPfmXFBq_b7JSKiwy_O=bVGyNP=+jqLlxz5OnxQQ z-}>%jyy2M;07m#7GcI;K6vmE*HS|yaKoX8t9HbTK16TnsSdcV4U=J8UgCSUD5&FbJ zh)#UsMzBN+tPxCoH_RUvRoFtJnJ@_zlLjsphd(Xaa923AVo2t3g@agO9;t&OMfmW5 zG^oU7)PN%%^Jow(l>kNnaKbA!u;(lG&3 ztYc?r3|28IX~}i6vm;5!1>&612{Z|_ofqn5@^bhQGT@^ew4g;f@F53hsxl9Aq`*Zi zfHoyk1QjpaCPYt%C44vm0N$X*A3Hfhee%+l!;}*~^Tx;<-~y7-$b}*h!GlDmGjJhw z-z7^DhHj_>9owM7$b#s^7$h(YqtjPKYJd%E@F=22eH)h2@d_u@gIr>WhdBv(&ySAj zr6=Tw3N)d##4#aa!DOjbxfoWl#uSt~bz=WCQKmBCQ6w0_DC$w;3NtL3Vjum$6aZxL z!>AmStW@pQUjdsDM}Bb`S^&V&Do~S_K83N39qUK>dXWp5VivO~MU*@_z*J`80S*X& z+0dpoxstYXqN+g{urr3d&@zSgtZHC?qgHBIgh?pu-!EX1hxRfJ}4Fd7U*43dOOwF zN=~~T2}d{pD1&f-gP_lZ9s@99gzAZLA{d|pDy=JED}Cl0DIp(%zY*11vNtn|#Mp1^ zIT0oxWlfmqFKiBRJ@tZ=yZm!+M>79;kTBT8zN#dGXGOrkOl*Ro6NyEA1}tMLeP$ae z0DuQ`yp09B*0&9oYKI$g19(PK6E8r>5E9X#tA1Cu5$1?wD>4sq8H5aO)GS0d@LWA$ zga;Y8$U~~(wi%N-KiK6fN1^rPzBzUy4|daWKH*($0C6N zIQ*dxee}b?CRSx<9T0R_hCNsPg)409_G-RIqD${ zVWTt7k0o}G?>XdnVxqhgfxuAc32kW;yo#!%v=A9h$Am7lA}ly1x+6{%ENNrj2BAfw zvkPR{mU`o>F$E@+77bh+*&@VJ>FwG)Lrilf$_U{a%)6#&h(;lSv%UzvN>>s3WK-fk zrwNwok?n#|!F3uhcC!zTRa3$7Um^r2!WE%~rgx>7acyY8CF zIz^~phq%z_)z3uW0|p>n>Q27*I1$w;%rTF7n1eg?-frtdKX}gUJ1JYp7{nxo{H1$$ z+J@hV494M)enihL)1o1e5y_}O@Z~3c40wIqiCNglK zzn8u0)OT`lg~T?50}j+f_t}AvcpXITL8BcJ69gVYd;vs|0Q*%SMYtbLz~8;mUq^wS zO58w&EyJ=52(cu>5X_$kqTq*>L_CB602m+uNI{7y;5LcU1CY{4TmYn5AP?@*wiz7K zi5>u^ph%Ej#X$c9Ca_h2MBi6UpAZh=3X+7-yx?jkStVlHw(A=IKT4kIxZqb&lXFdCyW zF5@uA}4976u{228%w0EL9Y|h;Ec}CcOawd7!qClC7HX3VJl6q`-zJ>jL7)mtx?}US zLp>IRDzrmQ(gZL9K>-A&U=Ai>7N%hyCSnri4iv%;B&K6NCS(fcVm4-ER;Fc2CSzV^ zWe)!VkuAd!JmzE?<`1Bk0(2!MdgNE4+4TXy7_>t=lx0J_0y_8uI=n&+sO4rE6@Fnv z19d_*)nz+kNj{_{734!-zQkW@rgB1NXfCI78fJ4or*sBpbWZ1B{*p9AgC^(zb7p2? zZsb0irV6HJM`E3&p#VGBL7-Sf70?1Z?1MPu<#Od_L@9u0Z9uAY!XLECCjzI>VTn3) zUO~)40v;V=B&T&wXLTm1axN%?UZ#UiXVR=m8C0f&E`X9X!2y(Jc?t+3vXH%D1WR1O zV64EHA;dP2#d=}{8Ki^VU?F`%Q~+!lMzjDYzySmr1R+$z9r>r)(G@?0gJp%oK9v8$ zajFD@KIn2rsFHRkWi}~-__X4#tTV#8+t2nj%DdzGr-*fVRab zM8(=|j>I*I0-yezNRGrTW`vT_bJRW@jrVrYW|rk8f8gMBFD zgy=ec`1@?c4c zmS_slrGXyCt_tg6GOE570Ke+%ze47OGJ_T@sg!Q%nQ*73erX4Oq=!mtRis&ooJfkS z$V8-N%zSGFDO^TOm(DrFlbD-Rz!SkHOD@1GH#N`p^#jYctUJ(x$Yvn5At_Pzt78W2 zui`AP>g-|aK$R}d5IARaX4sW3th0jU!vPM6O~)zS`_y@~ooL?V;N3VEzD+;R2-! zt#>Lb8VqK$a;m3RA`oH()0&RP8W03L*SM~jZ{AwZQ3WVyi!?-D*rNXqmW+e(6~rlw z0|2B#ITape#I4*?XRw|w-Zts#7C@xppMqv4!p4EZGV7+Erk^PyNxUuCEUp0&5#t?^ zeo}-exPsJD#SJ`z~I^Z1ak(L9m0x6@)O9(-^#iYL+hcZtvWt zuH1GngW_!&R1Co;=wt$JVVduFcBS}UCEaK*XfsW{m&c}Afx@yZiy=(p=Rr3^r zKBR*-XhS;W!yN!XE5PRat?x*fuIeJN%_=Yi>+oStsAn#4Aqf9L@6hf9-);pLE@~d` zNWh~!(qpR*nBt`YU|0n8`~lw?#0-eSN=C&6Xp0D)@O6EX6bJ+O2t&76ge;&#J;=j1 zuoeJ>Kr+mOJ$OT`Rs`=_1P&*#4+Cr;3oG3|QsM-y5R>l_Gi(_;?6X2F9@}t5yks%N zPHb1%v4YAG3L8Fh=0zLF^?Zf87IA!brG^H3V2x zXp1I=GTexY9CU*@KuRhMR7TLiKj_Q~?1L#3gcbY)l~Mmh9#=#y_bU%u=RAvVWa>cP zZD*4T0VE{sVHR`4k|*I}a7hg3K@{gRZ&MS@QC(z&1;}MV@El@j%N=X8D1(M6;Da*c zL-)PHUReYc{KJaW!9Q3_LAV1=B7|TJ#ufa-6KDWT$Fxk(G)>pEO~bSZ4Dk-^G*9=m zPyaMf2enZ9bP*In5ezj_C$&=ZbWtDmQa?3RGqq7GwGhBlG+;thKlMf)flvcM5OBav zhqYMKvYNxhpuQqG9wrjsOY{#~27lJ7?Lw1tFY^QcGD}p5Cwr~G7a0j<=5BG4d!d*9n zDFo?|7AaqA6X;w509kSMY}i5IDK=EJPiPBcZ}anZ3k*tuabkorw8K@T0%jY8W;eu2 zuRu$`G+n=SP76U+&$m)HHGSWAP}?_t@3&MtwNMWMQb-bi2Q?8Z!Xx-MP8 zHG@BROglJ)L%4)bI9%JcGGoM_2I`>FU};Tp7gI!U{w6}q>S4@7NpE*!7eqUZ2Mod^ zMkK>KbYDS`v`GU1N=Iyl-*5pNFzOQP_SXNibTTS{M^gAgX@*S#kP9vn8}kw?aaih6 z`&N*1Jph;Gr?@o)j5QHeXiE&MxVKi`pw)vMq=G!8G(|*!jHl%}r!xSob30GOJ5xkF z`|*n1eKPQv&xt|~E z>@q5$ryL_M63a1hNUUtjvh2&oY^+Rq1=(imssD1Q$@lVQ2S0d=tYrdi6d$NSM1WSG=qP{kan+ z#_KwIap%S#Z4l0Tl!pZL9<=mQ@2sS}0VRNE?LrQO#0(6THPgfw|AV;aJgrcDMv!|$ z_&lx8dflr1-Dc?z*ha1^>PBX&zYco5e>{|DPwp#=b7y`5#wo{zMKR~{R6ZB6hLW2jRkWGMSsFNXs)U3H0$q>Uocr$V4)VY&qPoE<>di-foBE_Ku zITQj?fN4{wPoYMYI`#kQjzT-AX4Sg2sa338!G`U6wSXpR(J+ZsTcC*|MNO)boq9ll zfTIEvF1%YY?_P_2{W2_?Q%*N?HUOlO6WC`^#*ZNnWbj~3uoMuPblTLSpet+Ce2)1S zE^=wpr%?m#n0m0^q)XSvrs`F8ZK$+u=PuwClQd~*byNLuNRgV`a;4I>dlzu(=FSzO zZavZzK4tl&0C+_@bx6nE!Q(9Oz`=lu5HfW_Q*a73R6fQ1Qx~3oefxgDpPqjAb@1G{ z{fiC20M)XpH)%8>P%1SP`QwM460-YN8WPDhU5h8kFdISldCqB$hihOcpXvZ>bT;KsDoNxt&hbrKt6DP(n85xniMn$;*67$P^hY8?n>0QEG^T({?w=)JHkwCzC8u% zlT`W$c;EqKdXed&GRm;Ppe0<9fv11|A>-6tdELuYE;n>dDMYtAl-RK%JQk`WoRMak z2L;t3js|^@%Gd%bJ!;d(w&nIxKZ6}f7Ins`M~+nFd1cpMdqvHpJbKxM29RJ9Wv3Ky zg`wSj`JMlXT~5R0Z&+ogy7pLu3mt+PX`UehQ8W}uWPySweJb0bx(zI2jlYGg(~KgR z#U6kB!ABTg|LylNH5*{nRfr%cC>Cpi*-5m2RL)uFic;R|W1a#f7($^XO;%_hmXXF8 zP>crh2;$I~tzs%Cv@}ahJ2q|Op?=QDgD%E+6J-;3Hf;b^&*>Prij7)eS=nHGA zVL_)>{?VuGz4->9=exSrDQKdRB|NUCmBmFGXttO-Kxq|;qgsj)Z|dTowzfLF%zX+x zGFkpP1^^k7SqC3?k`W4kF~*^X9&y4bh>CjXA;^?<@=@oGhyL!nCzBRnHI|h+frFq4 z>ec@VbZ>lbzTe)t4%o+m4KKWUrVuvrz&^6C4Pr!&Fw}9TF87IZjI-7>eSnRkZ;W=* z5#0-K3Ynq~c9;hMg?YBIq6=^0ktGeFBOJ982pRYRiz^6YA6{?>^qhwimVx0Hy%57g zGP8*h5F{8h(+N8MVTA~ea9w2Mk@SW#IKy>MP%I=+8KQxp-HcB+M?i!kq9(q|k*{jn zTA#PBhP5Di427sc0XytK4$&3F6#Brx>i*#bfq>y3R2WDxx}gdK0>B&K7|1zlq$3lO za42Vc00ClAs}!ZD405BJ-Ee{{GR`qi5bRtLeWF6bxzI>_42~9>#i$wXFgHG!RviBt zB{f2puP5ij+z){$9Xy(58=_O9K~^CTfuvv_wD3R)j-iex0-z44lo7POeT6$Tw5 zd`F@oBYEOT^Ffj^+SG|L{c;L*ga81SBnS=MaWa8;fgSzm$2z1qI(N(g0H_qmK29-^ zR*a}1A6UUZC89cE@`PnE1Hc3>;E)W+sR?qMK~7%r4|@!hqV*vrPrx}6WC|^s0qW>l zbdWS=RCAC+f)ZScbR>(&(uF!>U&;v09K`I&c0Shb8qJgiBDuOXW)dwJelxm9|My6m5Y%D<} z#rVfOfE;C>D7d=5-HC$_M#C%%lI;2s3AFjfZ(FzgYl73>#XQ%O+Ot>VH6zJBH1nyrX$N|9%$nfKylN{@hw^R_aTUC%s!%DJ8K*$+x(f0!f6x$WnVx#4Zih@zZ0 zg?Tqu^ORXolsuqe$N;zu(g^mxiiS;#N?b=Sw5jmXH^s}bqJKvdkMDv85b_`-UFw;Z zj>&bJc84I})geM?Zpe^O3{-R>q9&$4PiSWnIugdnPdf!ZtjBO^VVgogIM;xuYCJA zhHqFS7G&2xEWSFpx5Pi*gqYn}$0s=rZ(30Q-H@}F?+giKU!h5%;q{)18@3{kH9$W8 zsa}2`ZZ`MX@&xh1yBhHe z3X}0S@o#Y)$bB51C>Kp4tj!8>Vl+{@W(Ox?M{#HyqJ|f!t&?ZXaR622J$Fp^_r*oR zEles7obS0rKPQNSPbs@mNY5sZlR#9dHI$h(@TYcfNHm2rRjZxa0qe)<4I$gruUkpQ~>|@_13-URcJSD5b*glD{ z-KWve~ zI1sI(&}6_`WlBR0Rau_cX@F{2rjx{W@fFTmsL4Y?Q!q zDtqitm+OR7@b$zZ{#B)KH-`Y%&p;sO(C#BhfuXL#S}qOuCMU z$DDy{j=A`b*lt}~?~Q23I(Hf_I>PSKw=TG)gbnO#imfS%y(xBSMH(L?V@Jxf6ZQkD zeNgNbJB&RCy4nwTr!I_Xk53;{zt>Tyh`FP619^hzOJUX#C0HftKk_&+EVGh0ZGCLQ zVpLV-O`T#yR!zr+ITLZDZLOuP{mAUV$pFkP`#VL^pBspjM?t{>3$w}638C=Ct_%A( zZCy_xP*0JhPVv4@X${BzYl6EAR_-Z*t#X>@E0-XqqhOF@vh^Vap*_KgJ%#&6oWPpz zNP*OE#`sG(OKXV~TR4o_oM}gDs5U_~UP|oHwCYhR1o9RvF$COC$n{NeiNS11F(^kA zVt@}~MHF1rur9_prIdMyCd6-fPjqHB;beqf zS8L%a+x+9ucMcA7j?s#x{F#fc9PqN<+$Y*L%pIcI#M2D=p@OVCwxDZZ4$UrW^chO@YWL5VIbNgd?a;|q162J ztWiMstCC4meLkNk&0i!0PEBD-w6uW zXXjinB`&%?Djpa01wJkh9MsrwaCY*o;oB^p;TIKI#pn+P@g_O2CfG1VVdqNEOrIn_ zDPR6lZscN^mC_u(pfCe0K-3K3VKJ!eacJs@?28D=w6w=GF=-nyKd|XYJF`YH6Y<&c z7k7s?)V?J*VtwKH7GS67v;XZ&iJ+zy40<4_X7(07Unr9GOML+88zs3rw?zSqN!}eb z-FrI_hq3*qY!VMsCT6_tnUwq-6Ew?3EbkW|y`(0QKP6r6ZH)^jz@L{Nh8WUS^Vk0; zrK@&%h4$=`HaVJQJvw7r!l@Vz({Dzks%YCUcRbZe8mRerQ+Z@ZT_mpHPag=DuH?-- zrzz|q<^-pT3pEQ-T}p$SdALnK)!mlHwWz0D9TyuP5~?w^aG3I^Oh;mzCKSz5Qp^Mi z1mqT}GIjT|iq1Y-+UNu0cj*WWGq-Zk2V7#5WY ziRA-2=>P#n8cX2$kHC;V3ub)Zu6!GuUiCBy;BRCBQCF+lI^ElQtHUUKG+4Bg0P=%P z=UQ$5k2ZRmyJ8;#VQO!M*Zj$T=jqc=f&Ee=#U)Hu-JCXWY?``RQUeU5|1k35du%R* zqfXlvJisYGGM*iV^N?hCI`G$%gq8i~T{Nf(P*#{)LeJ%wNF$LqE&c6x>xR!!`vd)*3(e>B!bfcy zkgPv@m2_czop~26nE30r)@Jg(->VX*{nyo0ewyJ=mXOO7nR$ zyBt+(k<~oHj?;8SQ-WbEN=8EChh&VbhA2fg$VXvFZJRN+C}8Lt0PS8F*Z6<{K}uCO?n-LC zjM&7$#mB(G4HSPd^=*v5mv6pglehqd)PkD(>Ah$O_QIlRV%LeP zXkWs`GukDet5t=D|J=i*1GG0b;YlQ-wh>Z2o?wqNlg~4?X_tquml%`MO9O({6Lr%V z5j4I$)JGF%NefO>+S!qBV!avvBH7aGs>2^7BF=o7suuXiJ2gPQl~^4=jk*EcTaqO+ z075^vpUz}Vs=vmT>kU654$3lg4vLeL!6-AqqIang`0Emu!MM5j*jYcP-mm26_FZ2JK1-U7%h-;WiGRCIsm`?yGVzxD0-*k?Y2Y^el57UMwCFKLbmpjLrda1Nlg&8wyD zL{uj)>RS7FXc$BNat1aVDaE-N$+DIryclR}20}BJ>n`p4C|f+r*(KoaS_wq*aDGza zZ!p|%`|k4B-|t@Ea}t&D`pLv-ABT`W4z=B62~6790HbV5?>^5^;)}kS4<-xkfhD82=Q|+0%i^$ z6Kd-bsV;V@S-Kp(zLr%IGPjjETa%EZOgs^(w5g|v&-BgIZ}-MK;e)5fu7x_%ckR&y z``M}wJB|MHc~Uo`;|HBgN^9iv-O&s|_L7V(QsW{d%wXwi5TX641Vcl#8%_M>&Pax6 ztVp}(O~_oUALhEZ7gdXUf2Zi%Ai1=IcSA+gk~yHPH%Z+B`Y)6?5LvE~*nQ#>e>DhO z4_92^$Czo41nS_fe*nlzOok?Fa%(u4E<23s3zn7{DF6!s7b(WPLv0{|k&Y)x>3=e4 z8Y}XKWELj@Te=F`$XPlGxs$RxmVj24TjePv3Pb*5y@=sh|4%AVycF^1MIg34;^50#st`T#X!h~r%&yy-$&GrXL@ zA&Qc>ZQ09?wEery_4JwetOM1q?P^@!uKjXL6^ZQbY{ahfd<#`3G5tZ_p4grtUxvmX zR4dtoA!;B+DJ`Vn(1-sm%AsFSN{F*x48AMiFIB8}6>>0If=R5R>*DvEXxAm{YDHI{v6|>R3JGagw^i5mXty=b^RaiN>3loNxC)r&cEe|J zb3*TUlHwl#W3bU*isvL>o<0-a)O{~qRO3N15Q=ThkdNT8<$MkDQ_;J1EXiS>JXI-l@^z8$ZJN;GWx z!L#JTT+Smlk=h5?A)(Wp4G3z!f;B6run~}ZiFCh)Xw`3RApW3kzHx}rrW!^4JePn$ zs3QgA#HA-?UxQk-8i+w#K{+#*0>TZZM1#6Z6J`PcCzkuftFpMa<0hR5Ob+4Skv0Hn zNYbz!#vjwe@}a+-!+6E)jmw8+5m*oUpuc*DS(=vQKa4GO%}-8*B6d*{(+0xmR7jJ% zZG-{H2vP=RY4HD2^bycq^o!jMM+4J>=H4hPdU~nJw@M^TB`lL^^c)fZxD>SP9-U7d zaEXtRK~x|Zq!;O$$ZwgW0yJLgvc4Xl7U^4GRcDx*rbEG5y zgL){}$_;IbEVWd!N_zjoha0wVi&Uk})2*@W2iF=H_q$ z;qK#apmWd1%$r_$SP2G1VFrTQmdQc`4qA*?6sb;GRef4KZG2KX`4HU@&k6)`LnKso z@<{-aj1*j}4nBtl%G|QhEhF15l7f{UBrX4!KY&MCiQc1ikE58|{uH7xuabV7^&gl*>jB>CnO=VZS)0XIOy>00~X#EIvj9)QfvO2o^XhiK|7a z13?)35r$3t`SFaXYE{zN#tG&YvP<7j&n7e<8?|W5c$!}7OS$chW#vApU}0t+E8}?1 z+w9?Kc|}_q{dzJu_*7B~ZT%oAI2FLa?p^>=FL@7cApmekO^LM*0(rMM@pO@b(A3?f zMaAS1eIZ*Y-3wndaj5h@iNbXvTOD-}kusp5~8nHTRtzFqQ zVUOp~y`v_0;pZbfAo=*w%;GzADS0E(=1%cMUpq+f`lcIM?NlHbf^m}08M9#h{tHYB zSO6OIfn6Lz$pUbPBZ1=wb4keSFZ$*ZLp}r@@}CuR7ou zWJeSqXK{+>xNpo`0gaOB0u>BMKzpIrbaZnUDkVrFYmMe{m_GYZP2rigs}J%QOYd!x z^X36jjH@`WHV_qi%aHO~l!{g64n6RZn_4_v=z)Ei{qkcI>ZFPoapTISnNqW)<5}f@ z4+D@|q2|sp_6Gku4M2BUF{gOny6PS4@dJx)u zcbLWqOQcr7Ic2!NvsSC1cBz!%D{5vt)3`ttx9@S`LmU;v3X z1l7*nJ&Ycy84fv03><9%_DTlx%m>oZ`G$P=@O=PVJ4e`QM6^>O+;DtJx+S5IrpI=G z`7??9ha;lUJ>1hF04+YE^1-{}AlehC(##iFkK`V>A+{41__xGjV?L4rCa8~3wb#-& zAXRN>fu0~24HA!*N=LcAEsw3rp8*M;X9##W04+CzRtaNTSU2mvGD^Impaf`I!2}4COqLoZb1(! z0tz6+0qqe?)y9j3Lm|oU5w|#~!G@17%AZ6MmSo58_HV#@FU&2WCdq9-NyG)*aS*SH zoUk5>C;A01ST|KCJmDv!f&o9JS+2j-Z#pDE02?lryBew`qj!`QHRBMLEn|useUjKA zvLaRB7poN40VMT6B!$wHlZT|${S?2)Kwr94utx&5$FC+?txR3X^g|N*3v>ufqBXV= z6%ST)4U2()n)QALFz*-AW?GJJ$`rqwEnk*LN_tLjdS#0b$xvV&e@4I%I4C@|nLp}I zMtQ7-#O>X^sTt=z6`u46Vl+Z+$|V_LbU4xlO?ZI*$wISsA9AW6^j!(k7sHu6n^NZB zGyIXW`MzXqTV?Ds=A{*8ML@X9u6?E&G@d6 zk7NQyAaNAM;X-%M9AzebRe>US)uJhnqRNGz|2B~IJk!4(6;%zTv^}JlF+~Y6m5P+9 z*;v2p2T>uaNGeW+S1lkqb5t%f)Ia`--b=;S9#G34dRPHZX+dQX&fz64#U+tTS=AqY z^9lUMWJ>T^DEO|I-Kv{cXI5%_34dLKf18_uqn1hW7nI9UmdsyPXjE1#7ZO-hhTB!< zcvxn|mmW+|&M80(jBx*Eji?e{UWZ(|haA?f=g`F@)AJXPs84msnkwrEB=2855?FjA zP?@n^JYV)B1mp%qPANu?pL?t{AgcP9?!9AOwV77%mni5&AohS?`62>u&Ay_?if`lz zKx{l)M}fT9fKV%2&QUT!P|R4$3IsYIz?eRa3_QCb_J~ zFR7ais?{(?x#K|XYT&=XHOJsYDUgd+5rm@9>6bG6!1ogXu?QxywFXG1#k+s;arao9}#P?HSG z18PwI_!KAQNc}O_um9v(kAafFn^M&#P};FnZ+%p?2jA>F0s?{v)c%0z;;O0ibIuQ2 zx|dq+ahnF{YvA>392YB#(wYf8kd|A#zZ18((t23y|2p<;IrXfYP5+A%(1Z?Crhw8& zt=ESC_pk2aUkvePkX7?IxW;H1DbJymxTH1aDE`;TJGJ$X-3V6TF}-w#Yw0Z@zZ|5D z+Ni=@IadC+w>aO?Pd``JTDM{5Bj64Kw?GWgJT^#dfM zQjFGxaE{v8v;jF^f@m0bOfSdHmU|n%hl62|zm2rVqW)fcj@cm2>(Z}nHtz5V?6A7` z$MgrFbJpQjWD-;)d_b%4?CRP)=o$hyyWJy2*0@{oK}dBW0)n+HLLF)P-go-SLKQs# zKwQp4DXvhNx_)1~Y~L<(A8L5#<8%J=NN9bATf{w5kx@VTkM3R1KMBOO3T=O;Xgh9O zA%Y5>U)w;Yz#mBeko10{UXBbLURQgpq?s!8|K?Acmv@WG?H5;YlYPnJKehoy{NBkJ zQZc|wkNRQ!!p&LXdf5W{XbJ&8_0bAQ!$GigOypdUHbDUX(e ztp9+Rqv*6))xuMv9;jemU7(Bi{I2lsavrV#!jzqRp;{IXFE|Z~R18L<<${pAU7DJ= z(nl8W`!SgZl1Y3OGa+3k-S`9;Ws?ZT0E{zx*paq@*(gu~e7j%-8PP@00-p&-jGaU!^G+R0(}!hiT3|X zTFDO=O@L4t0km;T00p{e_x6UgVhWEtjJB#jj>M;rvu1i|b6Atdy{jBC@688CD|+BB z`22oO5gJS|Mh+6^L8pEWPPqV8Vk`QOn#ahH{?(@a!SR9M`3xu&@ih2@Z~z#48-0rH zGjRXH1zYE+f~PF7X07;Uol}Y&o0^+4YiQd>K1Fu7mvm>4%rWf^SszWW!Oj5l&`vLA z_^F4x=>Y@JbD8CHdwau^X=6(U^HPlHp=FcJ)K%tDy*%x$YWyYvr}ZJLLx8VXHa{ZH z($UT-5I)^3bh{Ov2rgQ+o2RViq_q!boC0mB-8j*aVMYfnn`cdyW>Ze)0#AEg74nd= zU}{fINwSvFVY*}hQ}Z^f1kqz~ZDv$g7Rry7&Ds{FA3KW!ef+*m`=Ga+oCcn?F9n@y z_XvT&H<)FUt1#Ihz~Ty7$1gax285VOV0LE)sn6$?N%5AVme#fQ%x?b5Dx=qxAN*}p zRUkLqE&;ZtS4E|^tb7KHR+rPMsY&GhXm`x2K7qi_IALx;%Q zcB{=64C>nES9kWRfJT4gywfckg?f;0Hy6eNw{45yYcF9(D$V!+Xa%4%x~q=1Q}MjZ zEWZOkG9~AsK4!Fnp|oc^x@T{&l(^h#h(0RBy6>L3?e&H)Yjfy*w!6-{w-p^4$AVjU z=&jHJjkH}`vnT7|Ra(%i$Ksr~OdW~mppAeaPeIVuQxATu z?fe$mEa~V@TqC&ox?A*DE_B?`aR^U(z$|bgTk0Nmf#lZiU3iv-CA=M1HT|jT zq}22HtH>z=XODC3S+(tc_1IyS$ewkKTduE9;0E#(1^W97-J()?UsW&m*vi4rGa!4L zrvC9f`quf|$)(}?cy{BwZ4uy`8>*54+VS8J@a)ggPEzE_xX&5E*(%EUJL7aw*!M~s z<8mzftcrMVbF8r~hGWHc9**hcj_jgH6RJyw-zE00N zjRg_q+#ns0uH@APkWP#UL-%$Jw~s20l)fHXoex+kD|}w>nR~nI%sO!VcI^`D*6?yJ zpj^N?eqVfc?+|m5Pz4FfxyuS$4rQPGu?`|uxD0&Sic!9I6?F@d>rV8$h5a@(;xjJR zd4x~8O2_`>Y|WDIN2Tx$Un%F_0eQ%Y{nn3urAPS@$@;OrvsYC4pTFppHuL3Qle>8& z0>IfbChUui$5SN=xDWbJVds{B`Fs?8`^jc$2w~Uw{1&t8M4$GK?ffxx{bG3n`dT=V zIExABt`3+1f}+Ss)e4dRQGfQuWiuO$OX9XnAW|wEv{%U!$Kz3RmST+k5JxH50V7oi zkxgQB!(ED>+Lce`G#_VqM?Z|d_eTL6i_`ncx#A(#429wcs)e$N*gR!3hw6n2c}gJ> z@6gmT-A3D8BImwNysv#RwEA-=i-oX6LPq{`r~1tfyW=5GJS<-ewQ9FC)k>y5Ljn-= zS#~Upx`L2_&sKDmi(3%{A0_qPenq%hsZPtu7r&LJ-2SL? zHJ5hYx4P_RxA^Dl^{xCOpP4v3I#uE5K^nK(0J3s&Rn7JQbc9-d9PM@S z*)3_+cyEQ@t?~5wKy{w%?b*%#{&Kff`YKo4|MBtmyc#vx?YZUYsayc|1GY>{Z;Tfb zQD0eNg_vm7h?3x#2{xt>n$_P)+AA6T*rpq6)Oa4iqba%wj=IJrJuHd4Q2?H45*8mc zxOJEthLYw25{O}}^tYdk`JxM!Hghs+wAqwVl8(nft>J2i25KgzY>Qx2Y1Y;# zy8s{wAw-^QL@H8#p)Q#D3u*MWDi*nX-ngP=Zcv;IY;-2a&{+1*E9I0=3Z;_QRk;5q zB{T9B6+aG0)T_!Uq8e5Hp=!KQDL^??@A$Mh zm#Zc+On%|brC3M*(4HP-y`P&&mHsqMH1E>HjCj&>{?$`k1E1Yx%<)b)B47G;sf(uc z<6l8d)~Pz`uOU`ic3q~;0EbPkc}Zz;DK}lEW0xbtXu&fp0DgGIuRJGnM9e)8GV(o?6VpP-`{QShH9DKiWH*4$j{b~~$wl1)wl^^+?-L%vv z|L?ger4A}G1eN#nyr}~JN4Ui2#~p`3>J)FsVOqDxIGKlq!INnCKhsN%sO^8lOr!x#jt$cw<3Ap+&4vAgc1gL=EIz# zzgOv=@)r@47G}XAJUO4M#X7D;>i!^oY2yu9y;yVsbFV$mxOJA_OsKUnZ^So2eN~dQ zF|L&p+(haoSrKh=0<(>(z=ch$KfPA2qwX2{|6YW%2hv}YZfxC)up?8L5$8d$fZ&Eu#}~?opQ^`{w&Rv!C(D^2B0}790uMAhbw~Ew^21dd}@NY9G6m)AEfda99SqizMl$wEs zcIFh0_VB5?Rl_7Rsi)!?co-%ANhO*@lD#e@3b}?v=+$oFwYzt-mR-1i^EM=e>p`^kPYTIP5VTCHj85h41RqF|VMl)}bJ9$n`M^0ls2Uw=5p5@h z`f*}wrZ_^wmzy+ARvU#luKl3w@AW?8O>M;csv{XUABt?2$u!=UbMhP9wg9slYsB4* zzZ5MgSE8PPC)2daxB|LHpUIrOu1k4^@i$@M54p9pU6P@VA^0`Q$U3z~7R#a{eD&1n zcO+`OZC2Pm65UKtBMz8Q_~9n=Q5-N6j_OnY6TdfZRY}o zd$B^Z{qsm3-GMCLCJ`<>lB8}j5k{Di1nAbcE%*v7xjFmI+HqF zS<*=KH}TMH+-(xkM+l0ycZi>mIGiM%V|=u?84bP1AVi;?5&K`b;b+}p_1})aD!t8F z)cFa1Z8)a1znF7?TSk%@f@yo9-g_M1wy?e2B{Nn}_Jot*k(_=zWre69QO@X2cp>QR=@Bgf_-l>!zzJdX3%GBgpIz;c3|rPl4fPJlJ^n4@#*d747{wul z2IE7GKGkchB3XXXUz+~y+F0pxYN zKdJu|APzI_bS2`B2H}%2baBoE9NBmm(7QYU(EuAU+BfgXZGc>?&rdu8RQ=D$gXlBd zRkhHchP-Zkz^@0A z^q%iODpJ9_Iak=ob2@7+h|pf_NWEA9D5ZjgrSbJxf8TSy-SD>DV)d9<$D`=uSJwud z#}g~%=cPs8LnZ3ePsJ)R@TG9 z%w=g^?0stvKf*Z~?i|U9v^g>^Y^PRzXr4saP^(Y8%#cNM8Fa{a_9Hjq;7vFo&p`>4`~*Q*yaK@5Gk z@%;FDXSJD05cvq1SZ?*Q=bO?1IWL^e_{XvXf3~Xyu zi^lM{o}VWJ3U6G6*^u;NK;U`Xf954)Dfx#DS#P{RSWBW|!}hILa2Jq#J^E zB0{4eaV9B@-b+YTi0)g^?wlG(RMLH4ALuO;%6t%Ln+qh4%W_``1+@aP;ocSXK%E*` zJsnP1c!{?Xx>2VdGc1V~j?R)2$nS2+dXQ-CMvur$Pu+!N6{uGnUP>Hl(mu1%#Gfkk z-3vCm2F@uL>_G^Ahx%+%v27nA?@WPrt=R;UdX`jZ>0za19I6UydI~6dD^>a`jHJu# z`?R@xYyG85a{Kg>`m`ma4o3LYqA*3U(+s(B)V;+f6CtQSCBAm`RnfZDNMlCEyJEQ6_{?TY8 zgQT^wZ>I9hU_kbLl{;xa&v{sGJhfjP`nI;v1QZc{o*8mEWqgwPKvoxdnu^p2mNj9;)Q zUpI_j3MtaH{Z>^admntH83pxA|4z z6;%+vsvz2^0DV-DqE+78bBU1wD-5tGV=CyYDj26Kn6E0xea-NuQrN7jIKry9imG^D zRq<_934Bxuqg6j-sS;JH61S_q<4H+ZRmp5VrR9^BAE;82s!_43Q46clD5}wZRipl; z*bMRKv=4lPSEgtUWNe&ZYFB$4RbzEgW;>m_eNp4!QRXC_zF<-RSTxluuYTbi$SKCN zlm>u7_=hlyD$qWS)Tl1BIxWzSBJw&7KdUZAIs*g6(~uZbe<@GdNg`eHj@&Vr`C_Bd z<3TYfL+4^a9X(@LxC5vN%Pzyp6Uhn)}{3 zXSo|~{cG+Ax>nV~oIK3D4A#8Esg?qzww%tZ~@j<8u1n45Bv(OAMwgh?` zfpv|#=2PM9{lR{O{D3fkopX@hj++<>#+gQqb)hp-&7M_OJy6Bb6vaVgRZkXsRtSm*J>g8uG|Gf=I zLIP*)BGUuFzgZFa5CG+UdX+xQkZ64XK>x3zUN+xKFM5!zJJ4GPoD;HAKDI<~%~XTU zT$dhguM)zB1ZQs##yLPoFy&bG4{)6nW~>QfEJ4>z1q-^vs+WNO@k9%P5N|%}>g0kY z0C4t}z^9DJZN;@k9I$!~EEkjy=*(fbqqvgI5aR3(-trk;M_=2FZbsq&I}*Y%s~|4! zB5S1v(Sw2(d^)oq5PMzt0C9m{457^K2);FNa}3`$Y1a}pzumd4FCzFqWUW8#BI~$= zHBw-XkHk44|y+(l7)IMBB_IN&+4m?ft-jNp{kF|{^u zrB>ow0WJ@ff^oo(<@LAMbpV;s2CLDHv=PYADBB%@xT@1M6^>B`!5c~J?e-f0e`9}3 z2w=}LxP?yi0OsF7SHa;?D?m490IvgpHV4Rd2cb(cD@gue1%m)@%eI*d!<>hSu8-(~ ze*)YN0$mBebx4`=K)-J@J%HIPSv+(QaxELzcEhzOfT7dtX{X_~NWeMJjy|=S2;)D(GRk9LOcmK!Z3oo z|McpfAxA>{Eu*s=59LE#+<|t4ZExG*GQOLMN>&kw{>gXYQEQeDIDCO0`GVE?GJor} z`5$`m)AEK`v7TcQTBwLsLv9|ebh5~oMNq4x< z^@n7cb2$}Y&jDP^6>LpxUmOH`gF-os5WG`Y7E=Mn7hs3~1K`8)fI$L%4z@|_4i zfY(1pkFlMwzMV{xolc3I&e)piE`VKX;J83wm(<4Y1tzEYJd5_}{v!LT8l~7lEwI+Mv1yhUV1>oPka5Kw`MZOR>J_HV#5D&o51sQ|B z??3JAf3{Irq62`=Vh6!w{G4IH%(0WDBzu&miy^!qXPHj>R0pwq*m!ARt03a1P=m5v zJHUnAw9zF>r+v1+!-wL_#d-& znHFAqzuDAnnX0dl$*%||u2_No5=KDWjqqzFI~<+&?{uK}a*a>#2;gvJExzQ1#ySBg zEZO70x(CQY#WoK8Y>t1T&D?>E8|XLcqP|9=_XX%~VS8Hc;3apk)^P02+CVwq@t-G1zrbQ5oo>nj>7-ZIUzD*)I?FRq6DV5!F*Uj=!^>E^*05 za_JnpZCt&5h4c3c%5tZu%|P_e>_;^N0?dIl-+?HG;JfFMPK)Zh9|L#F%6IxHS+=5x zI@LG6@1{}6(JSk%y2bI#;GNBY3t&UYwfM%*-EB7pOtu&9$$Qt;ZNmCH8p+*xtOy+w zUK~qdfAIkE<6gL_zx_fg*a-;GH3EMkYvGOA=KqdaXp+A|CXiP7=IoQ@n!wz#KZ>>e-RA5F9-PoP8=dsamfr%Y@l7ghDBL)em+YdjGPX61YMBwk7(u^KCVe z9*!LVbUCQuAd&RUjy$aPT?hJZP8^+n@!bUiSY{;HZX`Hxd(yo7&i}t7-v#%?X$!LiK^%ubM+Ny_|oFQkx?>!mDnemLzL9p$E z$6BUz=waB5dM71L^b^@4ez53r7rz93_WO|((=W-Vf0rdm%*veU%#^v!?CKAcG0or( ztZbUnkHTr^I;C^1B2vIsxVqOX{sAG^(Ok+$%m&k#J3g*vm+QON=VPn>9_=O}hDljIZyHW_L{>e4&l@Gx z1^oxu0M@qCZZMgmugL4u-TC%JwVx>T?F|Y?nClORt&VMCDq@4Z@Tl%nQa* z)5!}VFiFh|C3alM1Cs|5=7&)y=;Vjf=cndJFxM^QN3wSl7DRoV(kY1M-AXNp5xiO` zh!utXP#7nPty>uXg(|HuL7r=|Fi~0JLs62tny$I-v2I#XvcBVDQ3~8t0){w`_eD{f zMSj}v^dHu^bQyNtABr=b^7#T-PB#)`7~$}`p-Lj#C0EK8fYkgLk<*({)m$Y!=gF_d zNkNzbno$8U!kaTRlT62EvnW|Pfkb5`1!p`X0*{|+$fN*#fHWh0%IXvFh-bV0pF_&E~}!s`d4 z5>|0A*}X49VAN10cKQ~C3vhW!JY>3l$6<;-5N0Y1!4zcH4Kwfa^@}>GV12}EVjbP@ z!9vv-?8S>5sw#j6Q-UmDOC>M?JTHmu5u+M1U3JsSlB7Igj5~>PpSy3+Y+LqGlGr}i zg&o(|h@rAF1Ef)J##z+rSN|;A@iIg;sE1t+t5@QyBUC^uIDS+%?WLT}1`V_eg(*ILgz>3K#3AvoXKE(a#&hY8gRB_<>XCCS@wrq7+xgdS@?qPovG zt@~uczyK&8;QFRw4q=jWG~7wF49^!eub z`T6zf;pyq=_5L1ue+<33f?jStzC1iWK0Z7=+&b?aj^2_4W1D z)z$6g_2uQ|&H2^E<;D5=`SI=1#^uKH`O?$z$;Hv>dz~B{{dXO_os7KhjUOH!?(gsK z?(S}HZ!e$CuN+S;9M7-r56_>@&7RE8p3F=iPfs08&F;@kZ~q%V7#rOl8Qvc1+v&aA z+&)@g+uYpTUD<@L)a|cUtgo-HtuL&stgNmKE-%e5EiEoCF1**=++5cNJg$eIXO8tHa0vwJUBSm)6+B7IndeJ+1}p1+!ou^ zR(IYU|I)-g)CB2kif(CbXlX5LX>Mp(t^dUW_v9Y$XynL}VXC^ygEUut4 z+rQt}8RBT!YHrwMFkk0!QOn;_-&9vu_qV>ZrlGv1rUqIe4=qN376G0s@Sln?UW?$L zexn_hOWu?a{w;6lD-VCmaDN56cIEt@i4Co+FD|JssIIQAs4c9jswyupFD)-BD$gq| zEiEoCE-EU@&(F`v$;r;n&dbQp$jC@dP0dNnPfSdVi;GJQD@+W|j}OSzs?$)eQBbUw z3yBE>Mp4f7*IlSy>s{Cz+d@8yg#c`}XbY*RT5e`Z_u~>gwvMs;W>y9w-e36bB26 zfB*#mo(b?@5#VpxnRmI^CETk7yc-n^ekv#^$jZuo`SL|tT3TFOTvSw4P)LZMpa0XR zPu$$xoSdBO?Cfl8Y%DA+OiWDl^z^i}v{Y176cm)?*+>eIVHRohU$waa>RmANaY$z{uRh1GJPFxD4i}=DUi#OYh;=MaiT1&5KWJC zRvYz1kjnq5Sgg04F8ez2r*gT;etS4ezNu=p)&2UY=s2W&z0?1-e?h*vX0s;@huLtn zxz@Cf6IPz=YGPzK;)@t*3mVt;_i<9;AdE^6?!$@SA0w11|8gJCm3))G5s<1oU2c|q zi8O9(I$wtbp^_`LHD7Ma0KpJecV4FubXXquH{K`bBmGL#2{s?W`{OkWYbYjrhv4JY z#soPDiEjJzGWna2yK-m8>+{3)@w%PpoA>KU3on@;+>y4CFObS|%@=uXJ~s$;jex=r z7klSh2;ujV%}^5814;k^>_Mg{=8`s*4}C{Uegqa%YIY=E72#Si`5pbYXuiFY?HHjg zLK9!^1bXUl)-B$`IBBA^!f^RHH<|?YIRdlTwO5(lUpn7Qcaynw88^e=DUG^P&62J5 z(kv4e#YspD5BDZqianrWz}ehPyCx9y3YtFQk5DWI%G z4$7ph>J>VW3NQ3J#y?_2iqNFO7HjOW$l63Kp_O8a!Uc6kOJ)WxWFYOe*p5l9wb@>P z!V@sGO6z&BQdcgX<3br@y4dMzP%r1Onk~Ac9sD3QRCp z-`*+NxwtXhFuQ!>3h25LlQ-BCJW+tq1n;nN@4oqlEb_=6f_xs07Cdo5zynuk@Lv}^ zVS#N9(+qLM6xO`(&D-hRTv)FllnFoK+G{e&NGGlIdq>X*X38^T_j184`vtYl71v5} z&ODpjwbxmDcX7rDWn&G#O)stX+HC)o_I4=C%<{qeP0iKSJBO_<*LsKl=QCh`1OByb z?hZ6WKY^fKZ`+JF?zpmx;}>_-)Y+|&82^ai-7Db?OiVI&%bhphTN60=!+raGdSHbM z^h!G~eH{7YwAWty+wDFrdgWCgv`sGpP4I%e*l|8^2%01GIYM{`7Pw!}L%%xKq*pI_ zr3MwCjxPD)Zu|G(&+Gkjlh2*d@9r5-_d&}a)V$!S_dGrIrpF(v{r8L59ztyV(?s{P z3!eZ7sJQ!U}iH zV;H*VTmjl=iE-Qm9@*HyE5b6ufxNFe^K)Jfb%?*`MDIJLyWal));2x@8u5rdDk5&m z2Y>)5;E7O-q7!&7vT=+j_#q#e5Qs3k0fr>70v}8; zNG9+B3Mar~9x7ZO4E8~aBUoV+9N@q)u+ggt6y%1|>mj-nxk&37Xov9AALEpW#7bIn zLzE;O0tKP~LU{6%pbVubN9oBGtdAh*0|4eU_rN3w1Q_+;fIzU3s38z-AlcwvLAsGB zfp{a2pzFdvYQsR#xo>xotX~ix$w+ZE)0vWNTP80_&1&9fnylL-06Iy^ZhEtnryNKs zR~f;24CEE$7)UWd7l(h)b3woIM4dAJ=q$f=&=$h~kFu;VD1L?+12Z8{0kOBb0INLE3DAc1uXsA52 zYfKv93}zglsY0BjRjEqY!e(@^%))9=akJHd2;&<^P{FTQX;RmrR3Pm$20AKngfFln z4syJQCz|jIJbDgvo^41b@&Q^_sKW^=cu`gtiq~ZSD)Y7s>e@1#K?{jGRj>v$tZ;{m zo2YVyiM$gj0GiMZd;H^plnpCpjoE-#phF++NQMOrHBZa30z!R|X4t$tn6arC! zKY?|~#U7NQ@2#zEnWr8!4Q^jL+d-S2_tp4vuNaR`x{&j z+xW%;0WnQP%-93x$HXu}F?v|s;@qk@zFWZpep?`8{!-MxIF7PmbvzRu-v-FY)GLZ`s07N)r85hQ|eOfm%DogqQ&5m<(OsuR`ALB>M%yVy;={sg}ftkS& zE5b9J;Rql8dCu6|FqGlUXlu$DCUlkzp3gIBpwe~4V(#x;X*d4~8f+p+{3W0!uAFOx+Ec8JIZZG=V z7zbas5hCutkXveYR`9t2edIm!nbRl#k4XXy@#!GM+sPE-fH}sHN`kERCA#>=K>Toz z4geq&@h~I+bWsk097C=E@J26(b@7Zl{c#&#k2aGl6LNaz;{bp)Ok}-vS`XR9Mx99! zl;I3z<4z3^&4v2Nmmk?a{eA0(*7w9Ck zf(6)T0%nMI7=k_@;0@yNQoW)utY8IH;0pRM2?7xU?%;-*P!A0U0ARpJPVfp8XK}$7 zh{`BC$(UF+BsviAY0@~2)L4zyD2+jod|pLPonTI`lTHG0ckKjE@ib5M1OTj1bOL}5 zqu_~K_+_Iwd8Ozl@yLYc(_5ZqW<0Khq71pq7MQZE%#Ej3dy;16NM z4=&)26*zrhIFCjDR(%Ii1cX3_{0MVUHHa5Elvt9H08ogGn3PJ{h|1MfA_-QOb&_Od zRxqIry8sN>001;eKVNv0I_Z@NaR$29463+_K&faINt9~IB}NH^HbG*K6nn;a6EidB=6mW5fS zn_Kpd(MOnt36|7n5Mnr%5b&BHNJO$po6K1uw)u>>xoW(r9;7*6sF|9kSdZ|i5U5CY ziHV%tr(v=GnU>92p0&B0x8asGfpy6D7oUg_p$Ll5_nW4vH3)%^gs@w#37%I)YUcT$ zIr5wW@t!lmo|6fAS{R-3h@II9oT63`JZWalaGd-}A8e+7=n0@2dL9Crb-o#d(@AL| zYH3`_p!DdVYBms=M+mgw4BuIy&PZb$I-{7Bp^~AVG-04UhM)>Tpav12@HwAdr=9fK zmDe{2`srsx%5mM7G>u84P?}>lnoWweGLPpnBU%tKqoDS9on9)OU84riy)`_WidZJ*b0ER#aX3$p-V4t6gG*3FJ=2@x&AtsLMCUbJE%4#Obs;CM> zsdhS;_35btfr@9qr?ax8QYW6EDy-gmSfOfs+!~yVlORMS1v6}_}M;Za|)~N#9pE8QEDod#0)}-Y6u?~x_Fzd1TI;LCy z@UPD>05Y2^E^D!Yy0W6Gu`i3K3VX6NyR$_W0fRsYEKp&x@USTRWZ??5Dl4>xrmdog zqR<+%6nk=->HsARwHDg5ZT7QNyQWtApj>OTGkdgMdwCCl2!v1sIIFWrYpCPuvr~Jv z1&d9;=2aE|4Ddh?$S_l>Mz$&HwroqZMcc7pXsrRzqE9QfF)Foud$|TNP4s4Oue1(h z&;{Ml4UmSoTdTN^+qUPrxF?zbg)p}e&b zxOuC#rW>+rtGaiqHK56gaV-sd`A#~w-dGhcLWVE zzT{iJ=6k;Ao4(_l0fCSK>ifR%8^7txzV0i(_ItnQOTYNLzxb=a{QJN0>%Raz!1>$0 z1bo2dOTQB!mRQgLwcrf0fWZ7Kz!J>AM?ks&G`-XtwCD+Xq6a*ikPig$4Z1`SzXuke z5C|%~!YtgvF8snU9K$j^!!%sOHhjZ4oWnZ2!#v!>KK#Q#9K=G*!i+!&i0}uNfM1X> z#7x}8FANG83~n2Ixk~hX;fFpUJi;YB5a0U&;akB0Y`|blz!W^j`&-6le7|U%#`e3$ zYz)6{{Ko1_zY*I2&N~5eJjY_3$M1W=!;7IBJjH0coFYhq{9uCopuGV9z`erzw#RF{ z#S6))>t`bi01wQ0&^xw&95NT{9ZO&eL?Fl(r9^4ChHXd%yW6_}@VmjA5EojylPt-o zJIj=7iest;0AK>J8)}(cxzd{~!7vSBAj*ywsHp@D>hQUtJGz@(r;iMyy-dr=OD<{P zNh|;WyBZCVOo&m;jLDJ$a!Sk^XUu>L4DnD8$pBN0jJ(q<%hCMK?d&&+KnPnP5M+nR z@Qk+vE6y03wuu|d&|J&;%+Bf&0f)e}x!iKwOg`OgG-mrD9#94RY)SqM%hK$~03Fcr z>>aCl1{cOx9+=S#-ON&qELAWK)9`E)O+Xdx%nQA-FAdWoO&t&akgH4u0QdaN+)UEm zoGceG4Y7a*D}6*Q9hi;l&H|m(7+oKzs0fA>1PUF~>DkcY^Uxl03bBw2Lv2JwU78H5 z(Mx^N1RWj<(7Jmt9geV%Iz7_+d@N`X3)27sTRlKsJ*!epykb4pNUa{rI|)Qd3J0#w&^rL``d*QYzs-od(rfCbV4)y`0scYUK&oh+S99;Ofr!JydT z!`PU1)L^aGdmYw%O$dc>0n(AyFS^-O+SbP+1+hR4DL~qWXVo@A*hUSqsU6vpz1rTf zuF)|8Nh;hsZQI8p3R1w^y&cF))Y%sJ)%7aaG7Z_((XR^s5FP(&rp(RO2>}Df01x*t z4t-J8)GghQY1-F~+SyIp7Om9Vv7%T20MQ`}&d{ghJ=iXb0_iXeUvLC$P=%iD+wKjB z@NJVbJ+vD=-w!SsJZT6Ipx>1cw(?Eh2cZjd$H@xrA!rZ`rm*0|*WQ}M({?@KcwOAa zP2AqGqPVQzw%`oU5U~GU-Q!9Qynqbv01lwg)AzCnaQ&<%{>$&W-P|qVOU~pjjvGgM z;rcBN5bW3+WqV{p5cq%(y3hroa1Wi}&?rtN9stxredLy#n`Rph;25(L z8bc83Fna zjx3+89teQgqn@T}eznV_-NG*GEAAbS4gi>~eb~+62H^$!zzRvQ3H2a)jgcE&k+@INY~h_~<< ziR}*mZ4gg#!!GWqe&^r*9M?w(5kL@p>hbIU?(Kj~GAHl}p*-@1P4o3#@d5wyKp*bj zVY37Q0VON*LCWz*3G&6V>+cZ^u~6bVU(yx3^8ar2j4t#|?iVe8%>!}ANRRMguaQhI zEKctpngG|~JoSoF@(Zf+|4i=w-s-nO^aOFw2`~0af9muuG9o|?v2X=!-}hA?_j1qg zaBuimPZM2F5X+wT9l!TwA1P<=9=Q+;gg*Fy-m)s**buMl=W5NU08kY5m~ z&-d(&G(bEcYqwo1cPtOJMugq|q!9Nhg-}#&Wk2I%14W*#`%g^)Ue)w4L{Lg>>f6@B`F|pad znPb27+<)z~eZg}Y27|N`d041 z6m#v~#hX{}%D8UZHeKtMtJJ|y3mXo+HL=c)S_%e;=B!cH#Z?ar{ku19U(G}{1fxcz z^JvngO#|hOHFMC*MOy==`1Upb?76c~dL0y&U>0Z1AW)7iyE4($r-i0A&NEo7Qpue^ zhYlUN)Z#yFvmT!Gy7lbZyA$1RF~Au@jtkCmHcM@A!QX*akFIlie3qhO1*4x||Ng4; zlfv&QJf8&QiNKuCYGSE^LlH+Laia~1 zdkH)R7hDl23uk%}#um9_kEZd;Gia=`)~j&FoiHrXsGEY+Xt`5}L^4SdPaFzJonn*; zN|vNtiOMQ{3=m6*9313<$Ci<-AS+QC(;_F8G>Azw0azrKX%JX5PC1QJGpI9ZDs!Ve zFWS?hKK;}(!5U?{(Y)RNdi#yX+5(;F&Zk)UrxyTF=*66S*6AgLfxOU0o_Mn1VjwoW zndcp3ju=P`aPm2)6S#()^B@hTi3N>VZ^iYlI^Ro?wnYaejM1F_tcX~MtaK0&FV9O4 zBVdDlw#i=a@&X-kB&7lwKav>39ApII0G?r-$kv^Pj=)EkB)ZrJ9D$CgXO|~N;fD=} zc2!c8Pfp0SUw@^-*C$7#6n5BxWsKIfgAx99r$P-1X(VTROxVt8=ic*YqssJ@!T%74E2EltL; zpliAXQb8S92BPAee)=h=WP!wRho67C5kVkxSQ#jee=aD9f)93gDer$%5ar0ehbR7^ zzkke}#=#4(`Xs~?Z(dKMu^^-n1q?F7nP(iJe0kN9$7%?7tPsfSfj;mC8;UOQrWh~2 zK!zOLUoc0PF2L9(8vy{Az4qG+dc{8kC_vx&OA4`|MqP@xK;j)wCxIhV^rUw=JtlmT1U2%!?$LyLg&2TA zqR^WljL?eI0bf-*Km|5Z;Ty%E0subHjcsIrAfsr<{s6E5dTas!yYR+9VDJwx06-Vx zpqb4QBE=Gw;yzG>z>82K(ed9$*MU6yYG~p#}6piKk8? zgo;4%8v4YMgcsBjPENoFFrGk#V#osq02qTmT)~7cU?Uy4gO@IxKreeOa*6*U!iSa+ zNow~0Ymzc~B_>zNFbfi{o8Od)76@?$vqVT@X7naoD(M!liD7^PL=`Z(;VEqlQ6QQC z2R+_l4JV{(Rjqne0spm}=2X+5bGqh*)|tg^60D&~OXn3MijoKnqLc@Tnlj4SMR2N< zDUy8Vzck^d93Ir9NlGY7vI(e%LbRi4;UY&R8qRTUbRY)+)8tfn#;2@wL@DKv2&NGX zex1~)K>{jDeCkP_TBel_iRr{%dXkC~f&~Z39y7SN(~16Pp|MJ8hBR-nFRJCf8}daq19ElGS(vh zUa{&yc+(6M9B!{%{oY4)X4w5mK?;Ngt#m@#)336!uUovVOktW@)hgzbjX_8)nq}G3 zYSS;Jl@n+4Pkz#)(q~yOz}wlR(LM_O^AP6>skR@uEFU=$>JJ^kc`@t zyfe+L-Z1=}C?HTY7KSlaR;(1?y!de{E#mu;2;oShUAueV_rQtS2K41P7`Ci zpKfM!DXOwA5v^PUq8=Qvk6B2_h|mbJIl0y|o` zDn4|fHBHz*3k1qyDlVuAOkG7U+R7WDD?)G@Lff_(d11a)r;Ss9l5X188p?EhO?~Q8 z>$un0p&(?hidAPYBT;&`bWuJX9a)=36w|QPt)*?ETo-xQjb`+De@)!Wt=Av}h)iBt zN@T3{8BNVD%`IXfylJ;vNCG7-tU*a`V7q!ip{9^Unu`$L7#p>tCUuJcd4_J%putUJ zb$7y@3GYiUE!hFyHn(#;0P+~>F?f}0#9xhRhVN_vv|5D1MV_W=ms{SZrMJX2es6#$ zwjy7=o@9Gd*?*@TaOPGL!AWxp3Xk09vR-z+S8mCcpP1JVF9-)md=PN6I^#&^^T~5t z@?2E`feQ4w$bpV?xZ0fM_AX(E=Uiv(6`STY2m1-RjwGFvM#)*%I@Q5^?ZysWP+ku^ zL?Dfj0f0%|Xtz5hr5>lYk46-^2m{>X-tjd%Jlhb5I*3b6R}&8;tH%a>sN^BW&Mwn@MLd)}uWA>JS_D7kcZ1FWTwY!thW>7ribeYazcn8kPsW|KG=i4b6de%;kjFYK{S)W8nnUa`@wlLuhomK_PRkD zoIB17J-sowX&AI4T(Troxg~TdD*Qr51HOXb4e6S~^ov0MD}*Ejn1*Q>KQ4qZFLX0C zR6;wv!`{O_rUN1MNJ9?PH8zAKDVP8`?7|`RJ`F6u^)tXm+&}h!#Xs;9zzHq+df!~#s9-Z zl+wgoL4X(I#P5D#bJWJE_Czz{r$5#%x_ z1VglH#h>cMIYEP=3da0OsdxZ|5YPup5C|vu2Ybq}aI7>ul*Mbr#{ta2$`gnd=s|DH z#VMjk4w*gEh^APWrgQwQYeE1`$cHBwgMa8Q08j`2Qh11T*x7`0(#&Fc_772$OnS>23I3S_=h8CfT1MH zqBP2*M9QQb$_xmE3{c9agvzK)N~Uy5skF+gJW8s>%B{pot>ntDj7qNr%dyPLrX)%V zs5qs}o@NLFvP4R;bj!Ge%edsqBdDZTActCd0To!uE99Gzng-^B$+BXk30N0hc!wvz zNuA_LgFwjv0);@3%*mw8%CyYO#LUdp%+2J?&h*UB1kKPC&Cw*y(lpJ}L`}=w142NA zKfugK2r^no&Do^Q+MG>LxXW+=E0&a#6Znw-D;P}BN~vrRhKQWVitNeV`N^Q9OR1d8 z=KRX%gwC!s%jpD5>9kI(#Ln!5O0SFnQo;hIM2~2=fb85(?tIGgM9-qM%ag2!c0dPX zP@PQlOTN)Rb_-6z97k;+26l8u0Dwn%bftl0uve_afFwG?89RQ9t_34W13d|scmn05 zfP#pFOt1nr=mvG@03oc;y`exj$xr?KP=n9~FgOA$&;@@O0{{R9b!f(CjK=fx$Zs@3 z1SLt3EC>hy6Iu8=2nEM?dWD1#0eJug4>c$aI0ZBi%n>~(DH?`!$cJ~xh86_?Q;dgt zNQM`f(T?mud;C!woyHrft8I+G;R8tjF#W#?-JJ?eh@C`ICzaDqEYT{QK{ZWKF`dR= zNfzfa!v?*_d=$Nh;DC6rNcx=9MBOjmj8Fn~IXw+PL9J2Ycz_P7MKJNhFvU?IOo&|& zgChWgYmlQk2Etww7^+C`L9 zp{S}os1XyuRDSGNb-hFhEY@iVTA^(qqV+4I-AIjH*rlb>pa=lEngsS30NKLTFQwX* zAlKx8*yQklCe>Q2MWa@g)ufGCunpUy;1U)HjHqdbDA-%RHA%az+r*^_mW5T94Y;<& z#ivj@Eue}s%vmoT+s*6Qqq=}NR9rz!3vxAAMFH5zHQbp%Km~A$76`I^e+>))> zy^(@9#GTItU4au>vE5z&rPW)Y*gKWrQK{)N-!)$2%iV)=L!iao#oXR~UEXyV z$}885NL%fpM7BNMMBH4XGS=q(UftDM>fKoLJzt^Nx9e>P!L?TIgUwS zyj4LK-j6m=g*?zBnaG5mQ{h;f;B56_S9IJ0EnU+E3NkH-36KWuDI>@|(ED@VIH`bC zPz4g8i4-se&rM?g`~_m~#o+1P;TMKspIG04aNj3}VlEzG5>^E|IOC&YTmz2ZHRj}gZRe%DTusUkk!g*#pb*8ateq3Qr*J`%rnb1Z6h#H9z=Yqy({T)aZAO&&Q z2WzMV3w#cT9tt{8g*$NNe8uRDMrDQK=sNc3|0U%x^og=TbdAH z0O;WV_98pMCTMf@sY=!T04s*Z`x=^XPJh|n1wfhe8RNgaUz27K@aFi;h3ke#vy0NZJ8 zfp|;;(wP!IVGSQ14*x?BNAJCs;+dd09033b0HJ5d;@NicCnx8a=!aDt2o&fCjSwII z^7-%cNuTv;pZAF$+!2O00ALTa%0|ex0P+Y z&g&0{@-5bhey(y5Vup}CaS(5{T1E+f0CRzWfqT#h6=EURd7&7Zp&9~!8_J;_>Y-QI zhk>|&e`wJn5(o&d3E0+*3Rq3nh&5`XH;SV05N7Zt9gl2Xyd1$;099cX zv|hNKF#tVaWtvD~n8)|>rup9<==rXBq#0GvDl$bL!5D8`2-nS3r!AD+{;Duu5h03@5%8w74P6``n z=XaI~2Tr`b=lg;9a)J=^$Orh;FMMNX{fK}p^k}bK{n|uV^e#UMZHOKJZP5MQ*Zs_= zd%X~Vh@R+~_`<3ENSv2%9JWsvTVt+V#8s> z{2h}yOc*N_E(^x^7h|Wv27wv?-6)i3QH)2EDjmwSDbkZImN|2_tc6jhPa`hf%2lgZ zo<31x8$~eGwXiQOs%<+GkE%9q=hCff_by%lFbBHY(6;B#r(N&=4z636?qS4WOSX7c zbruAUiQP`7y!h|flkuJqbOJAL$GxCIw^4;BrH4KzE<4XN8~@d$1|8-9C3jDpey;o}d;>iud&D z*MpXwEffF|?$+IdpOiXN>G`4i=C4+NQUDs11yxpIL6U$wC8(f(x@BgPHoXu83^(i< zB%6g#-J!}HDFqWtDH)15B8e)=_6`*QfFe!-nUup6egQTJ+>E@{_*_(WEeJpmwN%9n zA!h`D;Ens`XjqXu#Yhqu_i*EiE8N@zMu`}f=n@pFOOnLJG30zR3=>yc zNhV4aprT3%D7|1F5tMrRsfDtML&^~Hd;vfg?!X9VQHHMMYD%!8B*Dwa7GJUsslZz{;(=Z(XU=!@a2oA30 ziLZRQN-k$b=blwHBZ~aF^_~8oXZ3wA_8mp zBOm$bM>0Y{zz52pbP`ZtEOPO{9UcoNHTxkDYc@NvSui^G8`cq#h!m?;B^o1hNCb%I ztMXN_h+#>gM3~?QKjaKxp>v=B@}LSRpd<{jn1%*;s75lu1WK;Zg*>{!3tn_X9=aG} ztCEin|di+%bfCEE>4RP0mml zupr1QWcMaW=8=zmM3O0$7_Lg-${E1_iwFn@5dqBkF_o&!oc=O0$6fMrjx&7VM^aG% z9Il3w#>|jxIX)*^TlDFUESMoVd$ zl%yj`0vj#>04|}^fg@0bcu-ObQP?e`MjZ`?GSQ8A#G@OTa8Ni)iqdb^k}f@JVis=n z0A5XTrVFhqI8lNEZTO=fIUC0RE_&)fxUBQ2Zl%;i^Eo)M(v_xa89*bF(+o#2z&Qpz z143P*yNnE$uz%bL79Ua!Y{Xz5Ib#Dk)LOvOoaU{T6;oV`lGt(W(}=bNWLtvJxDLJ# z0K}QP zW;7zOrk&AN3Gp@6*43`9J;^*GC0j3i#fBE*6kojNasTawla>I&}5U>In0EU4VjkzIboum{A<1v^^ zf+0?f10VPh2PdEk-_@QJ$}4HX)m-U-hxA5rlq>O&i7aL7(HL()C>T#mQiTSCAk2nF zR=`M64_$0g7xf^8O%uvyj1{>fDoqYE+69ryl&pAjJ+Yn{TH%7Q;vW)n$T?oIOw8VP zhZ4Bd4Ng)3O#1fFwvLEw(2?eWbOIfbE^d_F{GSU$0H7Uo>87ER0QpV#$$4fiW=1^_ zFQ7vlr#=WNzTuDmZ;;{zVd^v9=B7Yugy`1heu!-FA!7hA0Uy6+?`J_f={3LkY9F4+ zWF$AjPX}ArYK900%rS;-T-zZ{c!fFkk&Ru?xYaxCLBS4Yk{6ud+!ilWz{oLDzKrAD zjGQ;WL#>hyJL4Ie#&>as=V^L_8ruE+#}hsva|#@!7`y-g!7=g$aP;HA4#b`+dT{Zf zuO)Pr;0HFKgpGYv!s9}2d7Gczkpm$4*cv&^vga3dsBit{|M>bpUSSYTjKcyrFStX# z(2I7|;}|}7ptw^a0-|3WLtQXN&5Y57e>+?1lm6!a9TkE5yUbNnps0 zpAlC7;6y;cAh}ZEaUks-p#^ppijm+zn4rL*VBCb!7@b6UoCi}p!q+*&$=%@5$c8pN z)j(vzIdQ^^s23GJ-TOhI2u_6HEf;g_5df&4BFP~LhT!)_694f~L`{@Qd`P(gMG#0s z7%qbik|EE?#y#jC6KKZ~xCs%0UmPM~A8JGlIz#NKk_TpD6js_L0^)aZQZR{xNsw1k z)B-eoodG&x83v3w+|fYjf;j+y7qG){y&(npVG)kvMvxpMCeIU!;v5R&b*03QeOn;% z5L+!+E-XR>x`cdvUG>Rg_ymj}0a;RGsU_yyzQB!@CsU&>Jb zKq9f9IwE5-I^9H&nVF&4=EYM)RhD`nz}M-7Hg4k=9f2HPM6kj)%)>h*1H}l0 z1pos)&;v3YA4H&@WMr6zv0f={L?dV*dxhdUVj>^@AxS72qxpfOL7I1E)K3M~dVJlw z732v%BSc_BCr|+wT!T9J1polUI*dUVbVD~p1V?@(Nb1)~0ssa+Mib5oBM?vRJ!MFe zVoNOLK9p&NV!e9s(7(+K;87D-KM5w?&P)P{rgCz)r z6a2%eJOo!7o)l_gIugVHRGlNxBT7(!BCH=Uq9kGFo-am(x)DUXy&Vrx7LLXLf+i%z z*LfRTwq?Lrf;|XBWsZW|NJJ9+LyC;SKg^v#r~^zA1O;f{6a2#wG=OgICU5qpZ~i85 z>ShK6LIwnmA!#@OCXhKlHfJ2(eR;o-y z0a!zY0Kg{X13`R)ErJr*eH|zS0)*rjov7ZW+*7MXG9!b(z(LYHQjt-RCt~L#Gp|_p{3Y$buaNdz#YLtrdugFfg$)TYecW^Sq{a&|x<`~aDjshOTBnx?6mu4$T% zDVx42oW`k{x~ZJjsh!R#oI*k4Km#P)sh!GCB76Xtl4p7js&p2rp;9MtCaQF@=VV62 z-R0fhVI~hHn16P}tYuPByu&}J4UaPZCu_mjs8Y{5&suI{687!-^zKbFJ zfhs;`>tW?q!fKNqm8D?HNt{9s6~))Z!KVUf=&(Zn%mWx~!aJD%#X|@HFtCIE<>g)i zKwti)Lj)#9$f^#M0Kf*Uzz!_I7OcS@?7-4MAkYB9Hmt)wY``ik!$K^@R&2yB?7`N+ z)nuB*R;&?7Q6O9^?m=cfP9aKcpUib1rGi(poWvCn8c^)RKjg-_N{eg=04vagKlsBv zd=f+egFJ}A3kw|XaeTajzrUX?bTK--+0kh#ocy%9sc3&r|9lT@UBGo z?(#w`@viT|wy*mZEaoOJ=N9h_@X8hdZ1kF~Q&R8gS#Lo^qGeK|C9;S4-VMYV3`!IL ztFDAV{=?#uFI;)AWNwA}#xKIcF9r*&25&IHR_+XJZr84_ z7OxSQ%=4b`*xF-ZZX*1lL^pn8IF4gEo@1!gFb{z*NgQd#u|x=bT@aTq8J{gs95E7e z@bS)Z!q%}JV=chSfR8kT8MyEL&X2(EFX?8b^j7bqLIgr8WU3CSQQd&&6(VQ41RJ;U z1fSv-KZP9UF%x5OC&zEq0@QNEuR#@p2?s18`!BGiWCefE5Xa5(sY3JNr+%iy0{lZe zSn?&?MG-^9Cfo5RyKgYBZ`4*DB*gC&6M_*8Y${_hJKm#8G6`JDrQXsoCS#QUm1TpW zWlDU(KXi*O@830#palbK9?LHtpYt#;uf%5mpfen^`_=&d5^OWGGRZ=7E4N^2o@Q!x z?>NI#FtK1se8?xTL^k|`sfM#N{xjbt#V^nCIu~z53$MaLLRB~d2AA>-&@&1jvZV1Z zOYp0Jjw-6)Q^PT|F=-(gnS__|a7viNKLCS5vl>cA^G-Z85>NE+>U8JQ03^`hEMPDQ z9l|nm^cCB4wmNe!qQsMuw3M#wCJo}}odO!LggyKND9rRi^D+Q$1Wqq;I&*SZ+i@1q zU@gc%{K~U*8EidA<~?h%$({r{h^lOrDpapgD!Rtk>8n4w)0*=+-*MIsb_wwG z;lD_|f0gt~qKySgj9`t@%`BWrZP*LiAR`}1Fy^S>Il z9;^0YkF^IsYso2rP!j@CA8cEftXsczK9>Z}>MYOttRuVCKcd7HoWg^hgcnqDX?ymb zIkaH2Heye1bX%PwvO|io@8ZKggIa6hkLy`7v0- zKzM^pquU#=QGMR$K*xe9poDV6xdDfINGEtk$harpd944r`;uHOe6XxPE!YwQ9|*X2 z6L@7$uTqz8Uf5ja6$B`}gFtk^JG{aKTtF|7!|4FP7@)%kWcom?!)(5SIFLB2tI?L7 zgeH7R+j0a9q`IoBM~P?u1dKZbtb=l{3v;|DHdQb-uG9L}e(u8(dKQa!zt1^dke%6C zp+KmBIsi8noC5=vgQTOtI#3C=3xqyw!a$6INpGq4^@N-olckzO7gm8ukitLIR=T_G zw-Y&Pv-Z8K{EkB`AIJ7;|8DaN`o06ZD#P1>H*{S{9_11I2Y3TEAjJiELos;47rdBG zC4((SJOE65#b3NYyu#paJSTl?rkF%7Ohc`81UmeKwv@cdQ@v%UJj>5JJDdI0A{l?v zF}_P}Am=Z{^1Hu>H{HYWTy}Z&pz$rBU8v9{n=lNd_XsBLv2)iJMh#3&;!Lk0sXPUJWzo`Z2CZS!>2pMy5~*Y z&aGWg`ajUz=gU**H;=3LYkeDb%Tq4eORW;9OHdQ`?}CsrSFGIEeg6)--QPvd{k%9N z!O*_Izc>Lt0E6)tgFIjvKmZU3pp(3TVD^!6@=70-fe#0M`1b)~MT-|PX4JTmV@Ho4 z1xi4rDhJ4m3#6DFxa;3Ll`mn&lsS`TO`A70N~DMrWQ>0?cwWR1NJj~yN0BB~x|C_t zq%;E2a5|O$YSp7qrCQa>bVf91(Pk*cy0vPJLWH!C)e#6oP?HS;HE;_OuH3mF>)zey z6R2L5+j;>I^N(=hBLc^8lNV3hmx=`+W-^zLT%4Q}{btr|vW}`cGo?(MCPakFdH(`$ zR=t{aYt=ek59F(PXi>7at&YXLyQyy8T5CCbrevw_-$=I*Iumy5+P1L==7la$`g8!* zThF$>{UL1b-);6#rN@9wBGY0~6J?SE;UwVU$CvNcdu;7~YaiEtHR^u-#{FB$5oe$= zgDC)y!-9}OjJVCY?XZh2LJ8x7?!Nh2s}I8sH8MaCReF#qmsm&)#w3aI;ZVgDS%gT# z?0%yEji>;RLy$(TY`ifGXq<7RxBmRA0THxtd(gTGTSGF*3hj%rMa^D(a>dR*i)j%O z(|ZA=WB%Dh$}hp(F3Qy|yeq#OcgqpYsnqmOiDjIr#i=&8lHm;HWGIp?2$`HtN!I?% ztjsWR8k5lYa8Lym31aeq8Z6iINC3hFIMmWh?=p0=LESoYO|t0xR4gDx4Q?6Ye#}Zg zEeJ8BhTV+xvrp&(RjpRNIK?z3O?91)fDeHX5la(20)?<%kxlj`UIld$zZpf{D%5EC zQ*}*92+V>_Qhzhz5JIrvEmm4*rO>V;%O%rUWnp5L-PPz&)-Sn2UKMvwbTxMER?U{4i_G0+ zRGV#^KKdj`La^Wt!5xCTLveT7QnX01;!c9Q6e&<#ic2Y_SSjulDHKY9VnqwZOOa;h znRowZ&3o||!)=S<*8rLH1Q56a<2k6tKRNp`9#Wj8MCazUZ z$F1uH#%dv-3b88GBu%3J>h`J7R$T8T3+^?Q zKN+#amaXn_ueCffeBRT&EH>peOoK)IG^CD}fcdOFF~jnAOZu~y8V2my zyVlYh+ZL2xotq;Javxv+aTrNB%ja7}hx+^|CcT$r&wc)YlD@EMTu=5=CG4`hBjD(| zCW+}UtE`C&>oY!|uaLrsUXt(kzxv@$aO!KClEqQa80quXS0Sf~e(EgXmkLY%ll6U*L6;l~e8T{howWPU0C!F?0Y z8t7$2E0}9x>;wrZD1E935hnI-X2Fc~cpktq$$vHmP;U$>EcL0d_i)(g9!$J-8<4HY zJ$YdANQ*Lm7U5z#%}v5OIA~*`n8d8>DdF~oZ0P*}J5hA#PEx`bjV$?O*f8F+R{Pia zdvZ&ss?qsx?T~-tvl=B;XcQkZd!S>*dw*iO7FP#ekug_4kZDt*AWKf*BC0|q`5rL^ zTsRo8;bqeIRHVJc-wxMvA-9x_qVbYpv)nOzkJ$W#Os!{U`%X2^o(iW>OvWRLcP7Dy zJ)kNUeXZ+T^TM#UBFk0VF{QnoB320`@td`9A4IM~_r*&DzaUA%vqdL@-8dn@V2J(` zm3mTpB!WzGN5)b4Q_)Wn&MDPzA`w30O5-*8vpVCKpKL}gms>KhO;aRq+4YH(l_-MJ z@i;U^Q}7iXa?$HJvO=Bpvi*=0?4&aClt}%x0!)LmPNqUeKaY8-=BqYgdx&Q*G<^FtgVLV*&peTgqO6#?Z4$A(S_)R!W(=R>_SLBK z%;JKtzgkR*)V@Kagxx;nDswV#Y`$4)pr7DHx2BPM+kCkA0?+LvrpARnF89TSZ&Tjr>dd;CVMWDPFbd zNNAHzUztdWv{6<|qEeYv!?TBnFPAnQxr|RRsM5Xj?w>a)+K;lMOk7f8<&N%hRpL=56x{58?$=**Uw>9>4rwB?73q zWS^v)kgljs!w-+ykGiNL%F_Mssz!&M%TtY@VuBxeYd8a=!Ea8a&j(~p4%m0!;o6!s z+izHRu$X?)NIyN?Ag%4d?n{VOtkhn#psgP>`g0bw2jW*s9(6B&8CAt|=nHMNK&`{1I4fNT^a^aK!yf?V1?A(&Y7!J=+AO zdYB0Y!5&*0PsF0caXAv^Se|$>pp;Hc6G^^_YHoKS32SmFyvcwhROQV-Gl%mtw3zLrKxMhO2 z=%>%s?qFaJQ6MGZSU_8xjCKEqZQ4_3a6+xkNh`~v4a$A-eD6X!qF=u^@&;O83#D#G z*5>Z<$sen1l00H4d(=+g*sR5IN<5p+^+A}5XX+V)a_sHwhG?+GZV9uU5B?cnzuBwK zZ&MyiwP8mL=;9THq7z_;@j44+MpeGZ>r9T-imko!RGsZE?V)Jfy4eWVmo&_Rl7HLb zN21>ZMa*&qzX(>HRYJb~s(+56*kNj_j;Gk`BMw>**$+|o&7m82EGLbnu-$W+BqY`! zoNzuJcfT8aC38H#xn||lv+^Sd^eYz(cDliM>*tD6U$rhh7 zRqr~aUXkj~mf-L7$@P(|cq9dcRSeq>*eyt@)ra%M>+YK4(54^wU2tWtel&23CbR)m zsjO6+6tsuoX{I?Y^x4dgs%@Z}1^Pg6Ga!)BVJdzx925kswGEJ@gl|8B9B;1a`CslXE4Z z5xVD_`j|SYE?qwe_aekJ0jNxo3eL8R3SHfJ3?HN-+LbOD?Lf6BP{Zd5CK*pZP3NH> zJ^z_+mz`s~)a^m4ljQ80K`NJu^(K)jd+MT*@bUr);Mv5(bc+bv!R%3()%duaSvS|| zp5Bw$0%g3G(R(c}63XpO4#U09)13C%k#XYCRtV-gqpQw7a>P5ouCv-h$l-1sB57P@otWQsZ2_Py=XqysNMqx^p zIiA&BhA0-2AWzOh@ZezTgV-J7ozp=LZ#t~ASGeq=B>E9<_ zS!8fBJn(Ifp&37V@JItcK9lE@H^(MSaG6xP$~aHar$F{|3xVRW35rfbiJkGxI`s4F zmh)@Axi6|@D-aPMIPqAtk)2hB=;F4NBa5_Lzx=Pa(z<0kgRfxd>%OyrfaIv{NS zU9#b~b$6e;8p+tOjqkU~z!`RmMWuXL+rb9B@|GF$NuK;)XH*pC+0b#E0x{}1+e$6X zKvioy)oNzyP+lb_FhYWtkxoGQBZ51Xuk(v)<-u#Isz{Y{eT63=1(`?c)_}PEh-a^Ycdwb3yMWD?w_YVs_cJX$BWs<=*Z}5Y|I!CQ>Y%1Yr53w3Gt9a zSQ$-9KznoDc6}VXS#XpwJjO@gaYpj#2Cr)6AojR=AxI;R+;Csn)ZEn2ep7EiRdXPg z3W7!dQ~3vgj2HBnv3~K+xWrH$Z1_pxK?683hYv5wLyt~C6ldem6u16 zrr1qW7LX_`xSh=NBqHmwTe}UlF;n6XhMWqf2I{=L>6gZ#`qmOz22st{M`E_0MZfR? z=pZVL(!DI3KjKF1)n*TE7)GrcM4o7J%f%$y=JE0_Um62+oOb*aN-p^=#1tNz@~dUZ zN-VS#0YTr_Th=Gm7OJ4)SdXQ^>B+-WoE#Ws}*E}!3T-EDW=nKb}|%tq%% ztdx`fkBmLTayS6yaO@HW3njQRfXV2=a~TS^MPoM?Ra{?~4~Mv)1WX)lC@ypE6jKWn zE=5?NsD)Unye3kP&HUbc4wNeM1C|JP*uVj-tnHM5?l#^&ac|G)&gq2%j>Ac7YLw9EoI??|Cv06(3YSW zu2IaAk?etybduO06xbOaB^DSZ)gC2x9felPjS9eMu<&Tz>u5uZD0NAKmUsfA>ll}H zR{g+eZR%Ke>ewJSOc@y&)E*aR5h((P39rW`w8x_?;!`9OG9}~VED{O>Bhz|)8VG!y zc0nzrhyw`QAl7>jAsgh2&3!;3P?EJi0156#@@`T{{$f&OhOJzuY)Gd52u$5?Pd&O$ zJ(Wzm3{3meo*Jb>dn1`fv+648pG#l$fA5J`wdU)3_3k zE@;8xg+rcrvY%Q?Jypm%b10Yv^}_>IY>~iE9p!nQ?UWmB8=>+8yK|;KC!P*a}N_4KjC96wuDx^EA*CqpT z`+`AiIvbruKl1s%N?6VMR&LY)Y)TQa8*jWo5ZCjEw*6SO>yeOK?QyHq*w2oKJZEmD zPl4}jx0dZH^J}9%H!9TN>1{C`_c0%riQJs9!jO=%d2*c%s2<(B21}xZ;KxePhef5N zJJ~Nk#?vO9*F5xTIc#cqp3@~&7NP)xVqxI~_t78QG6XYYu``W=W9jurDA>Eq}-8Y=X zU5D6u^czz@W{ zWiK30qm=1R5#Ebrve>}W`t)9~?4xNk)+7q?X+usFt6iZVE13@X@(Z~Z1|<(wGx~N% zE5R!Ch&R<3kJi&tEqG9|pfQSSO5{`~E0my(iba^2iF^Y8FR-lmjH%#`xv?}HxK3Sf z3-1O}3xmdlqCt8mOl^K5ftqS^n`Fs!avpu{x55*q4ihLoSU3_a8unT0!)Lks&q{Lh za`%yHALe!M=RYV@dSB0L-_vGhjy`=jrEk@x5Z`ZKMlEnK#RMXM1OiB}Gg#Y#1WKqz zQO@8;LAnbwh6LN7&ki9Bl7??Nsi&J4#W0gY>7|_ua=##3&Max=?&TDrCdV)xMA6CW;L7>hS7y`kPXw@xD*2tW2Q~nGWax5BeD90#mB)9VLAY>5R>;GV1Xa;w49pr0a1GO@i3^@?zozgXQsx}Te%?ow)W z_d0$$ik`z2K3u{mX$w~jhd*Fk{-L*=%>{#&(<4N_(IqNMlmWE*Fb|TURbRUtd{<(7 z#c^|&wUj_K;#}(Exg7djN#R1~J0Yl#P!)Y)h`wOz^IgVeN5NDFVZD+EzHk>0P>a66OIx_S98Rk?JKa|S8)GVaM&(h z3^`X+UWZq3KwXL^CuC1or+G47n2s{3WW%5_Q#U)TJep}Yz(D9?eCKMgtiBWOwd|Jf6S7h zNaEEtN4R8dApnKH=T6EMyH*`JQcw63S7#$Gf=QKDE|I(pNp=1AeruSyW?riHj5^(7 zD2w~an@E?(Y-06GZyYA_<(_#t8@9saA{}_W)JilQ50*b9Ni?l}2tDn@+kV}&-WP^e z^uet;{@xq?>sU&a%g{#ZWnfl&veet1DRyV}nk=n;#$4SwH}pEC_rJXf#hvGHjMK&Gk~Vc@C{7!_?g782sgRiMQ)P zTUZB4ib!kV@@t!CTxC3U4QArc>fiPxSvFkkcQAaoTR}dJPcc4~RjL65 zRC|x;5c3<1zkThz?m0-Bxgh9vlT+F7{;_}E8|yOVb8ts=;VTd8#-0O#?qB0chlSVU zPED><`feseq6*OfYVNZ#L?v5A85Bmszu8PK!Ia{wCO)yk`-moh06t>yojpb5-SuTn z#~$sASZmJDc`f5DEd=KiD?_q$%WhKzt!mou z+sljj6ixSQ);OU^zmDLH$xG`e(==^MzArxPHab4*2?~!wqr(i>H9gaH5|?y&l^APh zfQC>ab^PF;5=r5d-|Q$nu5IG=-EBmJj(TvJqTzGzwttRWb^P$M3vc`S+qh3C-aj5D$mep zu87y&mO{UR1fs0Z36^Mo*XYB4X68bAGRkyje%b`?(J0R}L%0oWQ1n@5SYu_q6}@TU z!CxPbsH)X|pCT5#VJ))Z09S3}%qU~ErYxKIsL)FbqKXe~tm-*s$SdOM7}~!=3`(I~ z*Io&4vFwV2opVTDz#@$KRN99tl}8rTBI4GWp4h}QqiH@hi;C%dBbtg=q$?s3U^e*< zu8Kk0RyY%AmM1cv4G+pTPA7EdGj8k{sjW63!kO?bDbM@W1jA1Q(RDM_FXQq-THY`8 zFUlEdMn@{}dMUV}*ejGJ(qA5XXJrSMTPz2XV_q)^I4;Z<8qNBZI9h~ky3?tdxbubk zIpW+l90eD-B(<&Qva+Q6WeQl*M78R{<2*p_Vs0)wEu8EJhK}%ucsv6uzta8l*!gMj z!~vV6DxGdAg45o5z92IG`HCV@vfYgSwbCqOzU^;!7v-|;&OC4KUEi!hD zaC(VDf(%+>Wwn<>ET*f(%Ul0;S0;FsmD%0hZ#>H z7SlwyyURV5p89LEcXa(V7BVl{Z4ZRrqu=Xl9hex#9k@!c&1a8#@XkFPxc{QS=T~Dr zXCf?k|4tM|!Dk!MVSN1p^5(OH8@Q|MamI=wMeUwaIGT>+u5GBt2=CYY@Hgt(Ge=@q zD~hTw+WA-hmmi!UtW!Fy!*f`?jWRz`4K;GG=3uVJ+oi?K< zN{?+LPn_8v8AIztdMLhlr3Df6lXnTVv9IajOtOx%yu2R7+wf8)AP~bQ-gz7HT!jTf zlBd-!SvTrl?ftTghT#>?fDyA#UYIN;Cu_=>mKj9E^m&wcX6_W&@LZ*2MTi@pqy1x- zx5LFxj?c@a?`%FL=aS)X3zb{WCdi{J(?6>_Nil5~1=+l)IHz-2mhH^vefpg5{YuRl z2X02c%pjwMlm_T)pmMapg^fA><6ZdxaS{6=iJj9_2T9=L2>!w_KUjwmh)*v;%+m2JH+*7TD(lndw{!abyf497VGwoIW_Jdc{$XziyupjKv zqZG}y!Bmx0I2?9w_`vq=4ejo=5?YpsC;dB4jJs7-F`3du97n{UzMmSf@Sr11$`$5UYtZs z(Vs*Kx=eZgMHSFtQ|~)Vu7n>yi(;OPd=}U6mA9i(FC;&aHY8f4;55Fo z+~=OCKfj#9J0>5aZ;E)ZsSj-ozw#=)O5-8{-z>cv#iQT0_v?k0-p6kI6VmK^6Qp z@!+Y6#!#|+KyngA!Y`~8zE~T*ILBa(04(p62uWwuUcgHHgBY&lp=+HVTyEICW_X#Y z2iNhs3#m9)sdX0*pY_^2Y{xAE2V;Au^;{>#4ySdIr_vcFlAdPhil-vqrh+X=6f#vg zG*j7W9Pn%GS_5MOe&B{61!|3CTfE?O14&`C3Av{U_T-6?yD6HIS*rWV1A{Mk@JRec z?X-eK3HC$@gLGx2(3xT`kU%G@4HkUquW_;oDH5+!q}noe<}+9=veW{zgmTmMxJgUM z-Q50UY3@4T;~SgvWb3C8}xxZh;BxZSRsfC+Qu44i7uPJ78%Kq|)y_2T&lr#5y zx7eO5e6Zawp(Z`4ri5OJB3ryH3sh{#R&035eW_U*)#pYz_R4yoc!4r!5w}D^ynx=a zh+?B;DyWR!kg*o-t8~N3ohZcXYK{VAkOdcqWOxn-yj=PEs_@UN(--A3ZRHMM%hzxU zG5yWQdHx$t73#FF)lbW@fTfS;DlDEB8>(=yj%45FmD;wKep@QVx+x8zEgRk|a7=_@ zCp<=4v1{CzXt_$dYe76|c}TA-LN%(^@-o)2Io3cr#l@KfqlSb(zWfuVNY%xUU%|WcY=|M zl>u*XpVJ16xC)E$cu8n^S&lom(&py}=d+C0!B8&*a~m#{YF|jcVpFYuhO{Z`Czwo( zsokj$4XCoqt3r=fG1lgWFE@~q*xi^kot-uuQ#W>CWz@7(lPB6BI70V21^n_;juOj% zEvL-WmSAgz_tX|qAXV}5o4&niBKX>5aNZ<)UDn3M5yxCbRcn3NiJDnP%_TY$)s@F- zG*R8c0*sXqNpDDb&3mCF&&HKQ0L_UfZ(tg5otM5M%k>ca94K7_0dE1ErztGBE<)=q zD*!DjrTDfjK24kL!MTVOM;I@4QT zkEFz1%P6`DZmYw$X*Ul|#9MKnQQ3c^am3GZq6+~*o6c`qyD~-Kddjd17bF-Eq94dghq$)9^PH(gD`j*-+Ro^lAABn= zN%~j^?0#c7_+aG&q_2iCx_>gyU)!#~ePQrbZ9kM5ghJxlmJB_d9D3Y6y4<*N;CpAyTH3y8M_(r2bacp73 zA%Ia^#bK$ROk_HJ@_g+IU%Se>BI3U_`>wPxKYFKWM-lu;q)`UCk0f40u(G(I-_vi5 zMAwhU&<{JnM-v|nldMoL?GuE59VmMBNLgpBfpf%pqD^PJhF7wpYj=$Pxn*8DanT8O zKaAL=a?rE@R?|I>avK$|hcwELHcyU5lT;eM9#$y$F#Uc)J$DeQl&^6&VO%|Cs!b7S zFu9`keho$rFaZ4Qg}z>)o$DT7n2cJ|8C`Z8j$v+DBN(HSZTEQ8?)9k7iMnYzXxzCE zicY8Fn!(@kB0ikKXGXxRO9&A!2p=I}X1#>h%|yQoSbrdix7Jyeg@z^*fQnchzaGgQ z@?p9sh%*teAp;3N+$l)u^jG?fhe^09y7Ou&xLGG)&4zjHsd?Ro`J8q1yx~2#;C8hA zr(TR-nY;vYpfT70_{(bi7bc$a8C3c?`DiJ9b@eL)gc}ZWO5Jf<198Hz-H&%XiFTFX z*gkr@ejd94*1I{#-4OX*!Ddhd(H=@*FG_C@MTCU{V8t}<#iW9$*Z0zh_A>{ za{Dh+_wyR}GpzT&$?X)&e_bX#C}%`}Ez>(F_c*9ZUHyJP<4}sX1!t5HfboL>%Bm_OSfq{!ytis>?Ztb)vVmK|JyKtMn?w%o7ZM{u8 zTK;sj`bnihfKp|h2s5l~`3qb_64E{gt{D(mpWuut5`nG{`>cHcia)WQ|I|+nG!pnM zUIGOY99ddZ<{^m-nR8c!g;$J^8N3l6gXWXLE{PC%yyFGt3Zvg)@SH z&|^gtG6Uj#06^7aTZ0Io^=Vs=@o2KBiM8Mb5PkMk2zroCT#;OyzwbAz)64;mfR#0`~bIY0zCv>O)UE{(G2q z=%<~~LA;D>$n16M$LsVbpOTsWy!d{(Wy`{4$J(~bf?#1~mYZ8BVwIU=1t~0njr*h1 zG$ZtVob(4X_5Uyx<4MlejTYYoxWUI z@RMC4uY-!0+{8@ZIP+{#qi(yHt`>Xl?7q*83Z4qeEPax{&#}9f(ZBlEbYfrp_j}Xb z>XVpF!OsBtm|Fe2>{|5g^7P-sk7(krF6`C7SW7Y1#r>b>q&U6%z=M#PI zG*c=?i%Gx6InUR~gbz;`R6lLauIYcu7t-cF(*AO;F)WDNX@S=g%*oiD$|F6LEyyH! z_x^CH$5VS+H|+f}`tS?0eN}x}SHP>@ya-?UwQg&8?OA~nQ)j5*DPPb;!S|M)(Bswj zYfr{LM*N*Bc{W}C8&`Cu25Mv&gN;Wmd(zhcz2ojd_l6Mm7T#%V4iF0cbXOo&Fws$j zaKC6)B{wGp5St$7+7po)Wxc5;8(_`ofjw_U4A37P&WxG0 z0OF;NVLyj5^IL^0*&owxG6~w9oM|Hl$bEE#KgfczSjSC#bj8PHMW)2JvWzDsc3XWu zN&lM9oRa;0k*Oz&CMTbi2UD~fs2p8v7Be^MaAC*Fr~4Xd@xHq-(h*tkHP(~4yf8LU zq41kG+%4IXL^th~s9+mC^t&{*u+R4UVon8Ru2VzL`k7mYTwa>nL{a!#*d>WwSvX{x z`ddDI<#%Q2T%PT3+np#bE*Pm$6UHPkytb}G*?Lbm4*M)1eC;j? zFspISNXON5Ig4#fbO9BnLJz7j8+{LJ`^Kf6>ZZTtAJ)Cg2|jr9@}{%w?W_P@P3zbJ zZC%@dJf8=;<@?iAkHIe-M4lZCW$P5s-WwUO2HfxCCj&tJf|Gif;G@%?2H(5xv5~qJ z@6oSavfiI$e&6}bs8EIZ&S^{B`_3DihxvVZ7;x{mWdAbEfBD(_d;b-m#jt?2kl*(K z>rqtUftyKAE?K@Or#nft7Jr@=1-y6;;xqfZ&(2GojM^=F-dqUG=du}5P({FmkgQC*dxJ)#l09d5gD6xG48I<&zt(rZ_wkViz4VfW$-RVx7kmFUjm)y3P9Dhy{c(HknvSmu(0kq`hKhNYB*`M*;o>HA2}n^}!E0ZCe3B!K#Kb$GoEp|8a{ zCnhC$ubiHuBe{XUb{%VA!L5ZdVWI!Iw+)o(hw8Y#$OOO?CE7P|I3ZXWAUquE)ES&- z^;ke`&0#TFu5{LUdn$cu9EBw$xy@7WOkBPlq09~)farPNYyk&Aqc2sLtq&TGZjP5p zR>IL;VkK9@t3r&q=s56*WbFHLh*shOhP9@k<8*uYNH4C@3J4>>9BjVFv7v82mU#)lLqs5Wa0 zX8UmXLpcP9v_jQKQR93C2+p7^0kWkGDzJek9UCV4qgVw8j!hvX1OOb7rM}!LY z5yezR05Yi=GNPDzk|qFH@5dTDiN$kUCyt{A=%;#H;GpdY93T!8!V4!qG3~oMj$i03 zxshUJi4?lYD%ls6Q2CS6B!TEnMyF&gpzlUn*mYF3$p#Dc-&2J_My&cPig=vf=L?#| z(G*`1Oh~Lr5*1dfS&$1-Ivo{>XCg?4MS~;v*D&>iks^HoKru!E0`TFJCPKF>8Y&k$ zm*w2d*Zdu+#hE)W|CLQ~!v&`6Nl)>%5vS{?*7y*8c4)XYJzs4mR`;0j5M{7If4`?L zH7b4NIx?{shbvz5Uf0bYKWf>irx=kew-Yf4T{Mg;84%DFe=aUUeKq^}5wXMK zhn&?{TLeo|_Bho08s;Xk>qNYhi#3L`>Jqqf_~Y~6re@R7$e6x$;>zM$5$ zZmKs5J8Vx)A$aa(GUrY2r~f)yV^)?h_n`^zy~0 zY0aH6W&ZV8iiaM8^-Pm}K$O?)8rGO%&+mqlaCG6eIXL)R2N7U^wP+2ev|r|t5Ud6Z zdC*ec==bI!g-!hy#4>Mi=1*T*#B~(Yk#C~(PNAN^i6es)MLe$s9fiPf06g?Bo&a4s z!E<`4&&OH!hv?Zf-=B|IyO`pC;gNzU0O<89+&o3O6}r^$?j9zUh?pFqm8Yc!AAf&T z559W;B>lK+kqqQL@;HGnovNz%H=tR5WtG?@GF|}yzzHy*0qpfObt(Wx74GZguLk6g zx=O8`<(CfQ+yMZdx59iP3IZx0iwzY1hV-Jbka(dVpxwQ1eZUs*crh%bz&W=%X|38r zC=h__4==0T1Mn;<@m$B++0<7{#>!v;tRWrM$ha_4h#4a8Hz}l{rJVSr_Qyc613d1h zamTF^kg)>fKZC>eLOwxJS=YWl(gxHb0)aNik!pb$3qA@$*zSP>6)+WcHkC-kKoLv4 zC|_xNS^cQA%ETGo6c1FIo?Qk_50O<>5yM6rI)ibo0Kr~OijNwkbd*&@<5fdZ{Cp(~ z6Ai0SoFGVnWO8HqZGtl9PqD0u?zWO1IfTb6?gdM{AvR#YtdR5&TLHvY3&8ZXMNwU= z#eRlv`alJjz-Ahex+gugm@3TC3N1Ky)jB|6JrcAT`M@?N@C1ujBi7^w&!yslQS)%_ zL$JX05ET;f>U!9ftqwIKg~)##0XG>E>Ll+pwf@y9D>{2 z74ajifx{N{BW&#>p(`WdcO$E{%7_xsGdQ>q0t~qB)2Rk)ui!^QqWBWi=QTqxjic*j zpLlV7y8BD{w3cab{6^z`^wnBxO4U<8s5*&y-W%sFDOk0Kv^I!4MdA4JB|^8daeSBp zdgI(Inu;wZ9y7=C9#RP9PFQ!m@qbho5DIA#o$yiAPPGDu8G!q-0o3id0W)!ah*&|k z@{hG*vUB5wkjb~v2qT2fV0814+vJF988LNiATrLuW`w>!u2dO1Nw0&cJRQ8#8Hv`R z+QQ|Si;dHsT5yi4l7O|TAp-+o_r2(kE!f_p-~e(6*=jZ^X$kKHwnuxMr!z?K8aKE%mY2TQ8!&PI z%>Yhl#LUiM=G?}%haEaP!8#N7*bAh)S3-Oc8SWLsu@|kz7LUJ#;|&;|>S}o!66tY` z>kfz#K!8h@qy4L+qY1j1-Hj!}KD(77g99aP(_1a0W1b1ehTJwpw$JQ36!X5~*S!WS zp!tkYlHlJ5a;(wD58O@E-HCaw!NIvE!837E+PI7T-OoUA(`50AGvH-1h=Q)H;t$fh z+c@5f=s*CH5L3EaViM{Vr(S4k)nGb*9T`zw!?v{WpwEP4bzTn#sZVGMpk5HT2mgtb z2JB%I`k*4>s~+n{F1$5$Z7_SbkVu3O!qmJzr-sPh!{rzt^6U^ZYH%dd&>?&Bp}iT( zCeG%ASzwBJ&?=rqV4R*tqyTjcsg==V=SUrkxQKQN?n)!xcayp$U;zVEuhOE!J+D85 zVhB8jqZy=sG7~{-=c3X|Ngo9bMp_iegFFsBW+*YT%a#5ZmzCwFrOEvf3B|3XJ=PeR~UTz z;`{=`ZvXiYb{l`5S^<6h4ZXjC{;`h!F?ssyAB+3q*UrV^uam>I^Sz_1 zy~SU9I~b1pU;g&)&eqTEZ4AMEwz0FbzHqjqMsEzEHwMw`gEwnq zH*5Xq)uFxbgZEoKx2ru@tKBzSvFPP)^kVPLV%zERhr@-j`}xYd*?^6$jqjLq)c$>G zVtssTZ9H{ledXJ?Z~qdxmp5#dCwu1?=P?@h>|XEO+}zCc$i$Z+48PsF+MGL+b3NAj zZ8YusSkkxA*wdl9&0*AO*UQD>n&qK{#o_qHp^$}vilu?b`GK&{-8~Z>trKs8Z~Coo zKB!&4Gq`Kv*%?sX7;yg9VL93CKQc1X-`|hXyt~>v-@bi2*xZZ3w};+Vjx~o4_dO2m z^RZ|(JFd;0stKNGh!|@M8Efz#X$Tsr_q=Q1zo{YHtrcHtu=raIy?YJ8M20Y4_kAVK zPEpE9lK*`!-(4I^XlSUeu5PHP`4`9ix}frHS}Vrl&dyH5oUE9# z__zf9rhf?TusGC3hzvRcfDQ%}2bV@fAj85Uf`U-~{{G%R!GG*^-`T~XRh7^JoToDU z|H8LJ9fNZ9%5(L~B9;9dJ)%?s8!>9PMA&;_pJd1Xu(++Qtt~ArO-xJ-3=FijwK2T5 zD&}BtZ49q1BO@*$DJm+0Kp-%xHWwEcnwAO;24jHkdpvL%11&2nE1U_=@Q_zRULc+hp+O=4C|G?UKGFkr#YriOoqL%&du(t62zrosC@K~a6 zQi!Pk3D(Y~mUTfI;GQh~KVWV8cqQe3!P;!`eg6&C?tu@E%gcp668s0&Zmm$?ifftV zW9t4s5nd^K{^{RgZI?{K9*+NjwZS=8$u?FD?Pum77;`VPY7dF>6#oByd+-63aY_(A;}V7ydnL*ZpQ+&pbF?@VMLI zA|iD};P&T5e^GD^;Po_~dz*cCe} za15)LXV8#1&}{&_2ciuDZ_4j&5W79>dU8o%@^R;pzB@K~2@D-KS`L?w3k4YT;^d4D za!8*h7fDoE2$TZDy#Q&W>rlT<>Z zTainAY)mg018c815Rq!6p99yu^PZK^0TG13xr*@RTwFklVk^qcJ_P4<_!r=WPzKb? zYsIAjB{b4d=Mm13edMt3uTjJF;4C6L`L(Ew@7Om7;jE=e4o>wvm~j~3PjDHU!i^Tf+NJ>GX6@lESuz^r%1pttNpFY3L zQ63Z=JWaK^%7hQKYO+3SF)qTr2*Xb)eqv&f>Z79+%;Noej*DmZwe+Q+4h{h+Np8A( zph?mx#6|J}6p6UQB0Sr*~I%FTf|5gmUR%TWFu2iovw*u>Q~bFVA$*CL~~i#{g>#ElV4B59QZPcCZc;K z{&ELD30cp#>7(B<=ucn;k5yXb4rzqfCb@v@2W|p}^&6kt64u!Byls0YXDz5pZj*>3 zvDC-q@$E&X&eP!(OAg&0!j!|ePjiYP zSalp$J_PZ)hwGP-c{}f&1iiz>6-u)wg~0J`r_FZ~i&b!)l|q(F)#Yho-@J9c%<62| zeP>&ERItzR%#wp=Jw_@SHSouEloG9xMf5@_HMpLYW`ZQ1rJI>J0DHg>pcp0bvyUi^ zFq&ekIZjfTZpk3xW_kUvRe8?sm2u|Cw;c-Ccr^@E_=gZbsPQsNq!rgMp4ISa?=VYm zdc1F|$k*Q|I3Gq(6Xfj!v`=ktg=lzx2`DwgDMmD2$ z#R^BJ4ovmkIH;De(``$R5$2=V`)Gq`ZakLdm)KYsCSFxe4*;<2wND2?aHW7=gl%U= zId~b8gKBVpNB)3|K@kyrDYXwUz7vO9aObza}W^7VgfjVs$t$z=Xt} z6gtLmDZ=)TgGGb}q0cAXegbCtq{EqihBqsN6i$W}Cff;1JbyFU0RZxoTrkV_0k{wW z{@SHpNZaWLcsQ6~Js^lN8GrButaP_QQM_eVm%oKgqs;Yyk$3B3`{?hnNSSJ0|Fx=h zx@7<{|MnZ=;Pw2A*Hl>O1Jmi7{Et0wzwcwK&!+zluNJ{O&`HTukesc5M$Pr>I3n$R zMB!esSR@4B|6#Q8b$6c{Kh;TI41Cdsgq(s~%n0OELLqNl4oacuW@1{5q}@y$;0;=9 zCft1okb{Y2_dUYe@CN__Hra>>7sCDl@PvN1)7>oMxPuIBjqpoN?C; z2nhnhRt-RSr}&3noZl#GwIh-XBA40m*` zDx#gXwVKgv+N~y{py&UP+De%|-`7Jr?4#0SLz&DywqL_6n(-B{K-SI=>Ad9^If=Lz zc%kS9}n-GEXV{#dCK9?gF!6bI^P!HcgZ33Ze_RtQ_CJ@ke57Pz{?^lcri609o5J)_GX2<{7kUDuK4=Iva z=zyV!g#`f!q-YK!V3U)Fle4#zWVt0h8Gn93V~Mp`jg^!r2mq5+S(gQn1R)FU@DB1s zmEs1E9p{N!qYx|*3iJq;^kIRCGnQqUm{f9>NY`IQ*;T}4Tv+9nDdb$xC0*245Hny8 zj;NPdc9mM$mwX8Te=w8gP?LnoEPI7CJ*k+kX&a20jD)8jo*6joID9PGl76{2xS|4{ zK#Jw?m8p4Qt4T7g`I^Y-7qOXfvzZ^YDNryuE4f*Gs}=>Ja17=kfq!$G@E3;0nUl#G zp8Ef>oWG}%^5=x^@tm#}nxcu7?O71=Xqu=woVntipoW;@nV(F9pBB@YF@~O|2B4_6 zm+twVp!t#rA(LGeoa$n0GRU9$8KL(Mh`sS2QY}Ao`{Qfd!!e2qpg} z2Y=b4R$8ZXI;n1RrI=JHmy#-)x+$o#sh;Yoo%*TZGI+L$rtRpGPKuxeaRHtX3X@=0 z2}PwhnWB_ht5ssD)&xmn;-_vhC%pQrX5y=QsxXAQq=xFD+ZiR+DF`J>TaOB-Mkc8` zq6M{33$_|)6pE;1daQ-|tlR3X3?K-ha0Mk6U)~y)wE8G(;0&#Bt!0+2$%?85s;b?p zt@H{2R1gZA;06mu0o)3$dnm2$I7p@0R=%A|#fu$+dg z1e>w&N}pwVsPXEt9Q&`zCkif5t`w`9DJCq`x{nz#{)0P!>C;-@35(y0kPanrj*gLol%?OPnbiDX;(y&w!yt z>r^k>eDZ3uGyAb)E3=9U2pDh<@FlhY%bG{aAvN#}(9joMdtYBGc?`?8PW!Za3u3+* z3Qiyg3&sF_Td~D?pT+_VLtD3Yd$hRrI~}C+qoj9sDhvX zC8}qfYqer&ER3MFAHcY}MN#ecZfCR(iLeIWkam}QxCy(rA$zWx+p}>Ma^va&YI{_r zTc5alu?DLnA0W4kz`DDIu_&ih&E1(^Ff$KnGu5Wn(^tCe?oi6UAA0S>rC5V2Q(jZnl!e8fnc#7exxOx(my z{KQZk#Zo-QR9wYYe8pIt#ag_@T-?P+j0vIe38&Bs?{x}Ze8y<3#0{jrhl#^(ED)C@ zebje8K0FXWOn3YH5B&?n3;e=-tigW##~2*Kf(*!nT*xkb$cX zzK*QGjaO}!^v`lZwyhFgn=5k4;;7;JU9^fTY)nSoiPix$V#>fizH5vqbdLZ zDoncbin6DBEGX~{(ZI5wEKQd*hGlq$W}>#4gk8_Rr)zC;4Ce*gd@ z@LreZz3F?k#v-&t8_dG|wx%=^neZFqP^YA%?tg#)XcOd(g}+y5VxGq$mq?*as$x-4Vf9x zlXSP37Pb#P%_9xV`9TAs0Js3~0?g;Rrkk$EqPXGg(M10Q(nAK%c+1cYUDDnGx(zl8 zvxd{T%Ff}_&mXb~T8nHnEkrh*yB58>5UtZBeI9>H1r)u)LTwv{$;rqf0?fPAHEqgvzs=LnA-*3V9fyt9mrC2l z(%9!A2G9@-cFs`s;%I-F``%i z0MS9U@IBrLp#$nb4QrqUir~q$jW0g1(ZNXIdl%aK_1QYbol|J4iKpVY>Dz(59kc8S zwOj$KV6q54+X)d2>fFZo0?s0y-X#8f%B`dm{@(aq+Nd2K3J}QxQ31rTU_4voS{;Vt zfDG604&ktiMQz(u(h6EjtUtcX4hq;&4cujJ=48$sF<#3Mj-9wH<(`c(JE1WIVGs5Y z41Ba%_QKri(aW`P!(mR|=$hsWp5(%v)(rn{8`eA!H88xbe5pWF5cr_Z$uNLh9x`Aa z=rG;3MtKRru`hs2MVPQ0I$8x*d6Q$ zu?G5J3t%8{@^tATQwz}G49p&>&TisF4(bOE@9{qEHPPz=QCG&m;w?Vr2C)d@@LgIS z;30zs&z%G7-t4G&=7*lshQ9Ef9v;`8?Ft}U#Gvmfp71|=>{lYU@O$uXtMU2m?z-9S zH(l*7uJFuZ?*K3bcGU_Nzm6~OlSBV5EPVbR=&tS_|D7N|SSOG2K2PYC9rS<^@dVMV zC=T-&&+a1g0~_5xIsa#}4u&(oc&U!-4IkWCj~gm4yzq7O>FD*(Ztf!E<4=#g?LPG# zO7aPQ^*vwc&k>l|P7tq34jSO~1fh-)De{q0^Y0N0>0b6`pY%eH=xh)4gpcNdQJU9G z5Vwr?Umx>fFYqEG1B{^5fG_rtI{3P7@`k_pxo#71pY7T{a*luZV6XSaxbv3}akXxh z^xoTQzxIg#7m8mH$6fjZ;rNly*io+|6=35VQOg1Z z!2mP~;mObZ{2r%BYBg&bZLJ+D`pa;1s#HjJ>*o`{Lo>l1J8MIhv-M)nzSME)-XTuiV z`Zcf9y-WN0_3HL7$|0dZxmY;LoG}Gj0}Foq_3m7^btx~c1^}3EJm8$N*j!Zpl7DI~D!AW*BJE#0p2AT>0{b!MT#=sd_c< z*3`#Jj}Du!c9(@kAy(+d+_@3C;bNx=oq0{?>rpy`R?Gc-`t{MaU#k8l`u*II@~;WN z0R217I+zrYjiF%#Qb<6W9DGSX`%uDfLXKLg1q}-~uUs;CL1Njvh>DO>(Y1^^wB z8K<6gl4*&cHMWT-9&I!vNRe;kc?TOU5=tbTd(wG@B1MBNVJ$`wMK;;cz~qwAHP7qR zrcXbbmfC1Xq-oAN6*_t{6!s@9{7If~R$Oc#2A#)z)P zw%KvrG9evBx+!%bR_>VqfHnTff*>^h0RwwH0;hJp-@}^|~UXkbMhb366m8Tzv+@q+|bJo+Yy>>Hm%^|&9p$IOm zav=)Hx$W%Empr{BwsB%b91h?%oFE<6`6VGU(&?w4adssr5qI|a$D0`lO2?Lj7Ws#S zg)~T^d5n;5IJ3uq5^RJ~%9e}VmxqzWb%pnH@)4vCw{g_s_DGPUK zjXR+fzR_kP627TsjYF;xhw^xkj$ohx5#89v0sv6F<0Wq)zW7H3BZ$3Zp`kcAuwDkO zH@W|rzz-y9GfMbO0>Y$-aD*oOVCpWgiBMdjA;mBUDVT!76uJ*49;AsX{;>}p{=*;p zDAWnOv5nUeFv1`UgDL-R zl-I;2kV<*OQmCa z6)9y6;aE>7*BbitM0VYXO##u6+QcxfGkqsS5p~uLDeW0_Wou%WLfAeDR*nCNMI&Cd zcTuZyq%fdhK|{n-ju-q@vWq%d!x%fE4;V|ar)AD)Jpxy-N_DEPZ7pQk2;10x79t6H zA%i?y*&;dCP^z_0W`KcO;vxsQ9ARxcdHWyQ_H?R>p+%)_Ef!ylxmTPWFb2rafM;N1_l4@-@T*JJtVhj61mFFy(kT zi~t5KZaih+__wz+j%bNZ3}h0Y_^uzxs0$mS7;@Cn!b&D1lfC3*<-lSkRED!q*u0Ps zf6L1&;&PYsOptRjpdlDQa+3F)W-JfZ%E|IUG@wDNI5(Oma|Vl==Xz)6Y8l3Z&hkfG zAPS8-q^s%^G=l?M=tDsoIq+eaqg4&HL-VB0d7?CQ!D;DBH~4#cbw~tkBSV*BnwzBl zZL5*hij@><)yK|>uy68e8~OUNX!fS9J#yL1aut0Z*lw&r`!rJv2L+}@cDO&%Z2&Oa zF|<~$w4MEIE>CGT3}L{o&4_O2hO}wq{>{R~y>A{VTVj%?l!O08Eb59v8*3G#g4njT z5IKyeJlQt*LxJ623OTaZ5w(_# zn_c5*m-Vde&U3d5z9O6MbVGFQ*Shaqbze`a-VY@`zi%Ay9$&kjt8VqeH$<;5R!CPL z&UME(7Vk}#yrHz9=$uu4-sW%j=UH^LE|2puq z@4U}5-yaou?A>!G2et$L@qyc$l*J#Do1Y=`;X4}kY?r|jsNG-n_ch=9*dzb_wQmR&W3d)PA5fdV!)#<3I3Ih`4iz5jcm^AwL8pG;W)~FcAaZi9l7;KjtIBOdCH7tU4Ev zB`SD`j`Fh+yg<`4!TDRk9}JQfOt2VqKf@zJ(qo9va|jr?3UnvJp1Z6Vc!&kLFTx8y_?yC)^FjZ}@d0NTFD%T$Dtx>&L_#h+KF+g4 z%tN_LdA^010_#!&we!N&ia!nsJLF&-XmA`jyfH0=!6S^i4dg)aTL|=Xh7rA}MGh;a zMOc?G_yv48q-j`(L|B7w@P=g6!&B_FYwSNtBnTRuB?2@C3b4jzJQG>85KlyoM@WD% z_(lR#DtLGW8Ni2CAc!!)r0(*^T9e29%nUZf&@r_CMZbr z8Yu~Q88Mir;US21paqD`#+8#q7lg-n47nGv zwH!;cL`$}W%eV|nx0K7eluNp_%e-7mywuCSoXfNH$`9Z}vOJ%25CXpxOTI+R#Z=72 zv`a03C|?i;Q^v(a@1kT`m%}fY|PdJ6xJcSS(2H|AR=5$Wxe1*vT z7mC9s0YHER7y!;hEv4FqX;{gGaLKD|o~+zT$7IXKG|#+5&-A=Yz+_LoT+jD}%lMQ} zwZuyrV4*7@%LOrp50Fp#tk1Lr&;b2P$P7w)Xa{w$hMHMGql_E_NB~06&eKw=Zm0%@ zWJmyTNPc>Vn+q$Qo5>*z(UP$#LCC>Ov9201#hL`Me-MN5)PRLp1Xe(Uds>GRXwYoB zg9K;+W1G;mDy3jR1T8>=VDN{7K}U7;hIWKWWdy*Ae8&;Zv>3>$tunG|+(IZtI(qVj zhnN9*2o@m$$m9rt7D#|P_)-71DkW-AhkJO3Z8#VJ7)E%Y2W&v5CXLdGq)91#L|b#W z8$_ScTTwoJs26RX7<~xS6w_@S6G%t^NJvv4WmH0pNt@KtNp!}a^f^n^EbDT@EbU03 zw1{|l$whV0$aw=E&45Vtut^1#h)g#<712w@RKN%U7FtDxpvFuDRZT_1hX{s5(1JtQ zhIc?lQx%gAV1qV@i84)qJYdz78bx+v(JdoXYHhG+bch8Z2SM#qSuH__u!eTHhjy@r z)*7XAOMEVCWjToYTd1X z{noKaxaop77&3;hs?{g;$lp8F4rzdxD1Zbo0F%WrklhFmeZ_Md#3Gc~rMLjlAwa{- z(~cF`k1W_oU{;tIfCNB*5CGayLRn4pRh#`X zT^U}e%sha>jbR$Y;0}e=dgI`SU0&w>302Gu@t|H524YuRV)|%dq*wtqSOE#X&g?wm zkIh*X#^L|Zm0c_5Uz^ZY$5>xpO=C5dnk=4=EiQ^kzy&sliIK&FF(%^>p<@tzUA$G< z4gLwl>sPI41p_v~^Sxr<`(s3516+uNM{RAt!x;ckYB z5|ujun1ZVq28hKudamdF^5pMIV$Og7?uCgaz*-w9XG6>71f=F(m1AD!X2J*stx^b$ zwJ-n8ePVPr=93_=f81xzXah;mW0*k7Js9Xx%V>rmT6_M`h?VAPehHI%J_?Z88z|b7 zM(MYTzj>erL}1~Ori>0))y5^rkfu(2K4`v;<6ll`lNhp1*cJs?5W|$|d!A@_LE z27D-<9?)W)1`-y)T4@C892M$E7HgGe=dv~ld(1ijD4Pm<>ZgWkDU697papTzhiq7d z;dMH#ri=yn;)!a z&h3&28<+(EH@FIwYwMzY>lrSI9k7LQpa*M61XmD;!Rd%{ITrv(mvw2EcL9KSnU{LG z7lJ^QM$m#ah|_=>n1YE@hp=O(z~hc~i7Mbxv$btC1mt`MxlyKE{Lb&0kYa*>0n!-; zxhrmy&N-l3g>1lwaF_*_1OPC=hmJ^@m5H5xf*F~i8Jocw01yLx5U7RFB!Va!j!TwF zrr(#40OOr+`X21wE^OXb=%e_H}ExONG7n1=gH2omU0j&K{;ksG=J z0K35(y%~p?S#DZT2X&YR%cLU1xuWG6&*yQN6@cZwb_sY*aTUky7I*R8HfsOGHi;p~ zs(vlt#W>*`PiJ)wVwb?|lW3jSsh@;paoj!2V02v zh{uNM0Js@}`fvaUaeRLmHaG(xMTtniUw?04OAq*l zmv$H@^OBGXoC5WQXZV6AYWOvYC-;YScye_Z2W{X`kkF-X;3digCSf8bV?rhe0Eccs zgLRbdXqu*KVtK{N05h#Nn$PLhj@q$i@ts%uOaF+Mb%7a2pFo6cfgkv^M~QBba+r`O zdWs->!Y6&=&>p}Bd2k16*!y1jmDN^nW)Bhwt!=Znk8_quQg>Z#FLjK<)hQqya=`Yw z$N8M6Y5T5Y$ES=HXai+F2_iOP$yW}`Km@#oB%FTuw!e8y$Nm4@_lOdmgsU)yHfQ36 zc6)3*31lEIWI+DpM}GHM@2~g*cI|1D2mlIpeSJn6R96TcSoPY!`=J+ly~X^(2!#c) zFVDSiop*R|{)lcEo^Eje_jiBhH~qO-0Dpc7r2O9MUk}Uhc7+Iodj|*r0tXT-Xz-xH zAOC(JZ0PV|g+>(~Qmkk(;zWxYHx9(e@#95_AV)$JNwVMtL7|M9Ge;^y$c!gv3iL?x zrp=om6*AQ6^XJGE|55-gYLsFdT#|%jVo7m+Nkoh zniK26vuFvbU0c(n+k$OLV&Qep+_^~`=dR`37p~i~G-dzjAgF_AT$)-FGk&-O*R2jW zLm)_yr!nTtnm1=&OpTg9YoDo2vsHMiV5)x6uD;sZEMUg3Eym#0(wGpAvsK4Vy!&YC zliFkvl$DJ$$HmAqN5aKM=a>YLmQ$~8{klcv0DPHP8(iw|so|rJKU&^=Z;(pJwH)T* z;eIz_F1jE3?o^_~yZn2@1PF^H122=qmxFCaTX-7f{0%<{uB30doo=lC+ z_tS(uX*O$l8izEp!t-Xb^-3Jq;41osCkhAW0hy+@wMR2{@7? zkwqE_l6Kn=H-kIu)I%IZzx8@R$LBEaEu8$~Z3e#2c4xnK>q!h-wy}5W}=|4ljTx zz-Xc@W~wP;YI1}~J>K}@i#PQk5+{IrT30{<2dMfgtO{yJPZj`N;|l;;)EMQV;x+0h zW{Zv_?6AKM1cRjQg(8XzClL#uvEW4ul&2h_Va+(;Py>dMa>hzh17ECglK?>q@GZLO zc9tpt;?R1@A1?aS|`_Nx1lw-0NS zR2w=SkU$g?YrL^k+O2|5Kiddo%UHbLo7w-u8l@Z)z6}pFB75c(;|2hKgdzw`2)jIG z!V33HQ?(mOu*#^bNYE|299wh-E|SzaQxpewr!>`72bDArXgDCy8eupLY_LD;v~opc zmyKlvlf-O{9G5x~N+?6nWOhkA^K3V8QqBa%IP`=Q4n5;=OJu}W8#I9=xSVm*00|&) zis6w<-caH8>Fq1tn4>Iql`T7@fR`eOCNQa0M0rh_)e5uWtq z22re23kjf-JMfchh0RuA8UMBBo44-o^7J+Dd_z+dGbt(W4TMD~n_Q5(hMaRB*y|(3 zIO9C1A{Kl>OiKd6O;JN41N!kRtrh<@Cjc-S{?s7Py637Z-+w`n)sk|MVgvOwaS#1A!JkkibJ;13^T8Zg)QU0iXeiTO3Uq*Me4Xu!QQWoK=Dbq6n_=fBtjf zKmb-Ea|{Cp24R3oP{%+PeorEAP-$KFPw3qn?oS# z5I2lb2^3L*B{K%Wcm5@rADQPtx*^h$lC&H7WMXrkLz7gFfrJEoDQC3fj#m)m74`Zi z*t+M@V(qk(m>EH`MmNdN6%!B)$f8ai%1kU8&WgYr&{AkpE(8DrrdD0o`D{^-WVpf= z$)JZV7>d-Sj`N}Mtcd>t)F!YRSY(~dYG_%_+Ea~y^dVqS1PK7Z$CH|H1&|pRO)f?Y zA6&JtalsKQya5k*c!L#JbYmjt3N6X*<*X{RtV3WhJxIC%O)4nZ!Nw}ixLOXfAko1# z{Lzmu+z%OiHDO9`!YW9>!mzf*ic@i#JkoNCw^CuiDDFZ)3e3i4INPOfu_Doe)DyNceAcDn3T}Z5z)G_+xiD>a6RenLqUF9mo$txWYL&DKcN9l`OT#{E zF#aXiHRWxHgA4z1Pyp4(+rVDM64Si@NhgTyqu*Ef&%mbutkctpE0|;kwF#-U()D^*zE5u&hQ!^VO+MxwKg3*XZ1cM&5 z5Nnr>yxad@`-H+^qFF@iGX%If;mh2HXMG(4N?ZJ+O$bScFYqj76J{WBteuGnqap8R zn_4^SaP>f5p$=?|SKGb@woZU5uoqBdE~e9AP7#joPE~ph>JW#!4?+uY_yZiY*fghG z>BIsj;2E{xH_8E^9eW@Y4E7+n8Vw%lbI+vKVvj^%fJeGzSu2#{jom9zyS_x$jI_tth>%hk7JVbxFs)PSV4I1b68JW`8v6K-czu5f@C4T z0)f3jl+JW*xMFJmJ>?gaa_o^nF#);2dhY>E?4rE+vd9nj{SmUNU)5+w z_GRA*WPtHG(AX6q&27ZlLDG6n78vEwP*L9jTHj50$_bc(51IiuRKuSf#J=6$l(GL* z@kxcG7{e5>#4wPc)o6!m^#c`F;X3@n*4P*h=HLs$-ApJz=gG_n(x5;{AK4k;8Mcu{ zfM2>`An;^>3ZBGN^;%TG06DM&IzSSTL7_99k1MdlFO1SJtb;7rLOgVxQPdyHXx_n9 zA4qsWvOM1+0l)xaQW|33=$YQo4FnsaiyKZ3KdID7j9OKk!s(gA6!2jQvdcC&)R`dCVf=iewqV;>IGV?_VPOr%l^ zK*KX+p;1W6={cb_a*TGQLoN+OFciufv_n)V;@X8{>2)DO_@5r`P$jP8wlO4lxuZo4 z+L0im>O`uoTC0WJKw+1t`3^KZqftn}=~*C3ZVZlSK`?MdFlfO; z*aA4n!#iMu*9Zg$Bm+Fm12#}4h}GipwO}SvBteXVz*r9hrK3=~AY9huOhB8oQJb|H zArtx4fXxJ}jDbByU{Rc25msfae4;kIf*GJeHmt+cOv5@P!Ww)7oT&dBTe6@+!W9}C z1Q@nQnT^dUB#sX{i{98>8-1%7(N0LM;9l%E}TU4B05;A5=ZV)0^gEugQ zE1XJ2?7%;qiVWaG$tO7kugFUd;EZ7c3fWbffNh18i3=G6NTw6hC zK=z5jKWIS(JSc=lsDw@^g;wZ;mOvwvfQ4=-hjwU%VyK3CsECf}gn}rEo+yc$Xor44 zvWxChPg{mlx-e`o{D30!^j_xRmYQc0O1lJM7*P;LClwHgnJcE@PMLhh& z`qk&RXh%4>+J2$IO+ADIWW#2%!aWcKI0Ph-qTcDf!nBpCnVu<{rm32)DVw&bo4zTW z#;KgnDV^4-oi@TM979VG!=1M2X@){3^r@f@Dxnstp&sg?zCw^5#N$PtFHBx@LS3gd zTe4Bb=|Snk%nDcT*B87TMNES_^aPiBDVPp~g618AI;f9!=m|6e6}&2}#;UB&Dy`P4 zt z#$NCZUvJuoMovx!s6iV%DMzqCt86Dwz{5YB2Bt8390rfu0;E!&=h+qN#&5&=*)Y~6yVP2z0|Evi9GVHHy072@N9tgPgyPc(f* zveg1KRFzSjo^dK}72!?>h`}0|UqguLn3APg(gQZor*wucNQ^G+w(jbdFY2Bz`jW2t zPHpVY?)p-#$Vvh3nryb|?m_x)LHuDLF2W!d;vsr#)CE$#;ljO*MB^O58rb6<0fj&O z!x~60tQapzIPF7_Z~U^a+Ggp?gmrs`+l(0UV+L@N>m zECRs1=GmlPQ|^64%nraux)e~H-VjRgo>2erC%y1SU@!@btp_J@)-Ev|saB(Nt(B%2sO zLo^W9Pw2qu<=-1e1rY<0_n-M5n!PQ2!Ij6R2@A6F0 z!=|!Urye#HG37`=Gyph5eCh-}`~#F!wxl+O1v>;>PcvO}aB*j_9Na}Q5CKy=HP)iG zcuMtDyY)=KD`C^{T1T>B`PD5rv_({EE7&9Pp2X=ft#32PD6e!WbHs3?@^Q!Sd!w(I z83PmG_02H%Y4LONi^=`M(*Uc^-IzAV#_Q507Guigiim1 zg#WhCWi%B)fsg+@A;xXI;89AIdsCIL%OB&xk_vT6lg7ppLm#y zIdyLayS0f9B*Qq=!#X5G1Fyk0#6vu2L$@kaJjn1kuv+0dTbf^4rHX(vz=F-r1iM99 zolkf@_wIUcgbnC<94tGtH@mYxJG4i;v^)D9G{PNBJGN)LwljORU;DOy`?u?Y^L0D8 zm;160!m<#;rhor=?v6RA12!~shQ(nV0GI(bkWwO~gRq+bJWxXzn87u;gG^KaIAp`D z3&bJpgDr@`FW>`Y8$^0rRf7LSIQ+v{4m&m#J8Mrxvg?5td_2g9yvUC{$(Ovzi~Jij z!W*1C%eTDCgM7-b{L9b$%ZK4GctOn5yv}>U93;>n;K8~-H<-hF#C^I19Xn7I-O**- zE8fEd%*#K#EE@bnDFs6{yu!iTihq6sWm8VBUsoh-AV{=dHTi@*V|;)_{6++KLv;Mk zzrD-nJlxMc$;&<6zda?~#W8%m-QPXQ!$H9aLL2}+rw_e}@9t`^AXW6;>oL7R$ih1a z#0kKIFJ%7!37GoR13)6ELkeKMfe!62fSuQC{6IBF;DUs01Aq^}LP%Ed*`qyns6Aa- zbw#+n-`{@U-#*;uzV5U99I%Hm*a6?GeD9BZF@3@u41Un(ce@+Cb^3K{ZU*bQ9vkYw z6~b9MP~kY-tM#9X=L-ZrxFVobv_PC{3Md5WUy~X%4Y^uGDj9%4Ft78D1TFl7f5E0!W=^6)C<-01L~!i~$^oZP0WfBT^S^S4g|fD_)fad`R4 zodcH{=&g+heP6%luK=v0_41cEnHo~WSBjZ=efw>2wP~v0K!O1PBzOjzMw)UUu0-rh zP{9QmY|1kF5?l_r&qABc!i;3Q&_dNTl!z2_%+ci_4m%`>lTbF9Be#-x>y4!b0YLwb zK^bQ(F2bc?w9bqj%>btwGXS`%8^m6s#hnFQnqZ!_#Ng2udCbrOfNQdO$(w0xdN9W= z8#@CRNg8O%fCLI~sTOE}X$p{6Qb}#JuTCzh3i2Cqz~I5t>cX&RnkK7>hliNXdg%~-XbHm? ze1NR%vN&lKDg#My`JyQT5-`A}H4KvhDP;bEr`BVUO_ruP6}*(PJN-PZ&}dWBlUjo8 zAjceI>>$+I3+M186hI8ptx=R7ZE#Zi)@8TS`kc)%(?sNwOAD72@g^R4wmJVqrc_^I zWt@A&S!5?>l}#9cHX_j#DZm5+zySekA&@9}{;5jgjXBN{VM}qG5VUJYo0epSO!l*) zb1IB&qY?!{5sq?MJU51PYYZyq9NQf(-i{yp80a{Wbc(+OSO8#+XQDBTC==oWW9X@= z?o4RrevS;vLg3PrU=LLICE^fKs#X97w9lIKDyvHn) z4`={~MvS2>yJzpi5wA;c#rH|8uHT2-t$9qhFM5*(dG~(lt2(_``ouF)fw)( z6P!D<#uF!e*4DXP;f!4qH~>Ha0k35!YyMda_TPb*X>p(L&g}8Y6Wag$YvpH~L)&8_ zubebEVisiPgG6tX^wd$WPxaxxpN#e3vwWR=1+(}v1Ed59>;eGJ1l$>+7Kp3p^YKS~ zc;Low?0DoyBt7IYZ#5Mmhl(^OK+yyu6rVsK_G&h|7pbdz%n4s-E*P2q<d&On^IRw8AIu_{TP+7{-LfaCJ_cObv5LK$59( zG?XX@=Bo9>)5O6xxFKQ$wKu_?Q80;0Y?c|t=n^sp(k|({MF;$`^a!jKFSCcJs9OHUEywHhKw2&gY=r?9Hurk~4PNBqwzUO@gqoBgL>t%M$2G(HtsK z3|Xa0^mw{HB5{f1WSlI+NXujjg^EonApm|5IA}0pCkyb$KYp=JeI`hqkeT6K&}c(y zMr)uExm*w9*t}1S3nJe{S2+C$%ZP%knYHZaK5eoC^&zDIy>f{bb!QWL{XX?7pC7=K-=$>A>5IqDca~ydo^<>siJQ@+A+%u;InMnV)pEj|gl}zbLWpV~YCbD*B z3Z{2zqL^?Xm8z3DYF<`amzE9?l*{YtXbjjbn|?JR40K>b9O|f^l9P|+q!T)&c-5-f zMF0rsWdMK`IH}YmE^Ci10pJgvQ zR2jnciGuxWn1~X9{4JJx|ks@29h?i@)%~N|v!&q!~&AeVfTQ}v)s65tpq9rzQawHr)2xD{wd|3fe z+Q&;geZ-Hn^n(h!DzK3?pO?3nf=af_p^b;upDY z{o{UT>0KVr1eehrN`H7+rbf!|Epb`jmeDLcEuRz1j}h`3J510xBSe(YlU8qWYCX|J zdALBOa%M6}nLs}V$iMUPKK~owp>&j&wgcvYiR2O-{{tCmwsZ#}MA6~A`C3F?jcqlI z8Z`o-{^yUA4Jpqi22jGLI0gj$8S+I64ed$9BrO-m* zG_^b}>Ny+a$Yc97S%bJXD9`tys%EQ1SAFGm4qKnNgziv|7G_4C_9d42hcAL1Y;O0Y z*giS7oR>Ua3&A11c2;)0y%4TYaAJ9+K`HN)AwyxUL7zB9fT66$Bi8>gFC@3ckCQ-J$<;Mit!!82`f0HhBWHTQB) z2JAjG$kVR?hzojTo@R_EMdLJlrZg!BayTpfPj5`}$0fo*QJ8wq{!VqvPke1nCv)hv z#AVGRQR|&tz^=S3El2@Ci+_wG=okMt_-0@2zoSdj<9u2+y+?VW%>@y3sNwUvrxtpFlH0xfnW$VH<8@4-!=kVLr{9W)`x39Lj zPI)wkQ1OcH38QPL00ToK8ua)_H6%azn19#up8q7%kv->`?)JhEdG99TJ9?{2ndNOQ z{mWCodzt^Y=C^pUPj1c20f+#1+K9^za*yW2)1=)!;W$i}ji-Vd@Z|Sq2m?W^{FGDH z`7RGQ>XA8qN_HUO`4LLEuLu~RK^pSmA9O7IcufD4qv!zY@;E8;lv zW`p$V@ANj1nP3h9T>?L9P7?o?swW!Gc3L4C(qXlP1q63Y0b`>4c;fujFZ~j$!$hg3 zZmV)?BNX(^LNw6+0`K_?tE}jif*a(mQco8z#rH_8Ulw8Z1EOVQ8E^>CK_=JeKF}o z<3q{;Hfr#PdhiF2F%yZf4VMwc{y_}lBL&)ICM19r?qP87CmN-Q`fAQEdLqVnX&k}; z?YgnGa4{TdVjT7E5y_Dwa<7qyBP1xg|#66C;83@Nc7;O`PIWFxbU4L1=KbJ8B; zBOhTR1HfPng5e$f5gKt4%|s9vtj{N+U>yD-9c*Xzpy6I@a;_RuCku-w%c~1565k~8 z>4uRYEbw#u1S$VbFDaFhGG=HSummNgPx6pZ@ougr7Qh?+K^_L7mnuMuVBsv$GAmU| zEoX}@xymik58o=n7=mvj=*S1#?SD$XW&ryn@MY@Jn5 z98uSl8L7~B;s?C4X6{&kF8?i6p4rRFc#QE9Byk2qx9UsthFZr3t| z0CAcCm?6Ed@Tm!qH2xy1qdN8x?$D5sVgvMn;rcLsC3$|oI`WAbB7O)~(|bs?#&O(N z$@9O@Y3_ok2@K`p6u-AAS_*_}8p(+A5q-4`SkxT#a8#r%6feivk;~$74NKof_Ays? z;uDOvdJZm_;IG8*nLOP>X|I`6{Sg55xE8kyD+#0>b8_+?swaz|fM3a^9$zTuvuLik z88zVt!KGWLJZDk*2aR{fc+;6F(-NA4ba)fo!LNIiU+wmh#h{GW9?oFw@>%fS6Aw^Z zgJ@z^-V#7DBzYP%dj(RbWK!pN;k>f$Zv3J)QgWIX?YImBR2)4(2Gc389BESQ3(7xdLt0Vjs&GS&4Vv00AF3@ z@{eporEKW9iaok&tYUCTvOQI-eP9#qPk`O^Sb_j_O5FJiy}KgH_?S|GqQG zIwfSGT#Vp#y(UA`m1evr2Odq=OUtfr5?HtS(Iv+yb zD~%9>ARQQ=x?zhP?+6))7oS?^Qo>vuYNk#(zs)Pg@#(Iay$Q6ZWUlOHDQY&M^JmOqy(+Cm%Hr_CpBcu_n;c zRNV2@){Nbb)!B}s#R_p${Z>wT)1}B>rqCMx#$nLQpegxZGxd)W8VHN=X=JCl zqYoAeX7TZw`x8#sG)#3RdsY$7uNU8461YU$sdT78I7?qO72Ma>F#zfnDbGkY7F~^O zq#v535l!Ynf2kr=q-w+GCt2RAl)8uW>N8qckcIltesgG0cM7dFK!_8j%_F=(hQJ<3 zA6~ENw??WZX7g)$E5c*8Z&aOE`qK<_P9u6xZ(IVdolCr2I+6+YBv|bJjoXEwZboX5 zT=`n?`{kJXy$y9^b+ESm^zt|kg<_8Q8E-ihpAs#fie?MyexGI?Hv>jXqp0v_YD)Q- z0|%$m$LX-GVNb*be^5G6YLa)~qxT44*$=glPrzMoaF7CL*?3CFWR56+Ov^(&N%xtW zT#*qQGS5&<1dswSDDhI5$1#P+Gk>hxSf0kZ8$QrQKWXJTA&g<1QHkOH z_?tMS{&urTzz0>&1yeA=I}WMyPl!rBL(5+!dyxFE;P~`yl3aMa%HI@5fz-&5AYi`V z#j@MKOnt;{twZ&44(MYNiB>>IYkI#52C^%xLX*L&=74D-?!zfyS@**icnX{()ku&5 zMoreIOJHmc4D6*iHX|z@Vu)JFzzRp-878VR?Fw6|X^uh2VCQ<4HP>%}R8;~(E-;Rvsw zpDkvGHAuai+xv=|->r>V@X>)R6VBKew%vM0C`P^mqV#g-<@*BXMzIR~ws5YnU_bln*SH>_Oy0wSBl6t1w=ZLNS#=`r2*Mja|xJO>~y6 z7FXeKo_^mxc6@Wrk=USW4fkt}?r4pFXie^D1=F-;b+qOAwUSYDeDQ1FH1$XCZOh1M zZ#HQCV~Smw5A6}|93(>{6-V)Z=$sMm`q+U?T7W$N(6#N?wI=-iDChgiTGxqix1RyJ zHmNfcv9m1ICj{KkaWv9V0)W+13k@y=4^-I0d$j!QbjbjQ5A^08n5r%2Jy*No)0nu_M8ZEh{$)`%7SUswNg(>LWPEpIhj_+{4 zj#2WCvB&Y$2mD;DiTE5nKC|}5oQa%{j&6g_v)s-J;qiZl-~RYbJw3KOJWf4{OoO|= z-#rXZ=pD9;b69S3PzBR_gUnllQ<$H)sto(;M2c&CUmV6&M{V7&{#Nn0OX&HiNMQ4> zjFqmVlr8CJ8$9u@We;15aSWKD{FR_`%wo7N0x;#x4qwg+9#kphHN$#pEbT8IDgB>jc?7(=o&Rk{WOKUw%y(*A6a0 zA%FUgQ++l=v$mN>fq~*2<>G<#p$MAo0&9unK;x6}4FQqoxTHXu_r?Z@s9rBj-Eg4b znqI)MhFnG2Is-6V`^<73-EzHgD)R8@8=&&&$_GcIyauZUVdG43e2+zB5GRF zY*GG{JZ~8p{du62Zf#`opduM6pj@OT8FI&Lp{CpsC%b0BsqdvYq$W26G9V98q8*q< zQTh;ybARxhq>(03BwV!UA zCFZ<1d1W6)Jscm8n!=JSb_-70*Mm{pOX1N+7`P4V2`0QRz`{0rv#JH_AAWMMeawEYA+laS-K+-Q@G_cCes>k{6wE|s;;xl?F`ef zoXfpG5E4ntlvY;V8xQ$H>Q%jRWV5i!U~_ZdbGiz4`x4(F+-o-i0K8#3$?L&8_y0hZ z>|nSZvJrx6C}Y3%+7*Sb_|`%TihNW*`5GxJSy}Wct|;8}CX*WWt{Q_bRv6_Dv?>WoIK&NU;Ow&s zar!zs!tFN6%$VcPb{Q{<7@v#FMe&+J&+Dqbvo1i%-kK$8{W&Ws0dk=OWWR{DnU(2{ zy?3mbUt~40xxSupf`dKg7WxP z(Kc;(h)_2*8;7Wuq9j4$(bKy>#EcOk%vR#hKw^y&wm}K&ZySLfiaglQcvw7JpHCc# zc;1I7&|%Uw=>u0M6`Z@EMs_*1evYel&L!8v`1A*vlBgA*0|{iA3Xpepx}UzI*<*ZN zl(+Y8{o!?CbH7^pL-fJ_F;VnE_Qi+3;m}_!R@Z7_hH~Z4tV(k^A^{7$zsP`nzt*+{ zemi^~j}t-+%>9~@evO9?H(siDta#19J8$rd0e2^>tK05X>c8o&&@5p zCn)6X$9#qHW}sf#!F6!;0|wc8jxGBds@16@iok*kvjaapOe$6w9m?A)!Z{|QAfAG` z7ym)f+Wwye-T=wr%sRJ)Q|ku8qxS9~pZ4waHcP|I?+yq!SPaCbiRE|t)r^8{!`>D1 zjfPcd&9LA>lKPu9MI4YkQ?N_>LxR%-^ya4ZaXHpCu83sf)`ZO$-h<4d z3Lm2y;#A~%*-r^03~_xTreIuXQvnhhS8(Jhqz~2??p5DFq3n_&TtbI!+Rq6Q^#9uT z1tx)CFpW%}#3&NX{zqmpdhIG7LepV86xJfBLi6J)i47?BzccI9qySB%=yhT!>yRt9 zE1NkrUG+~)|CTreM`kSz`YqU|@B{3n+XSqV1R|&f46`~=q3CiBa{SgsBT$T|GRmJr zW(Q=%Q&FkYuoY9Q%)VcO&CoL`QmdKYG7H~g`Se;4XdIkJt3r1o1ez?@25`B)@?uBL zqVHVV>2yg}(j{xgYUBarQeMZMP<|(kLaRNGR6mu72i*2k1Vzi3g68l`T;O6fRB(>q z85Kso9ufhcB%cbm?D`wrL%$L@1tgDp4$@2q~odYvqBkpnI|d4{|X9=peMYNp#$Kc{5}ovUr@E3XH^hY zALSfWn+>@yp>%ndAZkXCOSzagCD=+_iLXzKs z6GM@ayx71_88fj(G{s0HJ2v9TawF#~nZ~HofrC;&~?{^0-!L3_W zKW9cTcHiP_Vky3AxrS8c=AA4N0eYMb`$)ez35(+S_7Sy&%66|0HU7FC)NfqZW#hPb z?J)+K6TUhIb23WXc+tfk4ol7!Aib0yn_D_TiDdF7%u=T8Eakheqs$oCCZkMtO%)hl0ky!cQ~xcie~GV(Uuq$HMG7EGW+6G zZl(f7vDS6hP?*#W%rc@%(5k~@JgWTGPo2JXY-0ZL;-}fTs{Phs;FI7zMYfS$uf}+q z)W<0aNh?5hjrLq!r#;i3-8mTFHywrBYe+#(eV{fasxWLrvz514$OIhcq~Jpxs&-B= z7swEIE5vWVv7@xs$l|xAq4@!CUE73n!e#Es&x1@GWCky+tNhK}lK!5LQ;491%fQ$| zymElg@0YK)J}vpu+5~A1(NC9&J!f&otR7yU26T_}5G=uso*^B-VKGDM;l`C732Nfl zI7&-!Idv43_~hSCcZL%t>Th!6d8ne$!1J)zo!i)nw*y4aIPpGVJFl?s`udp&BCR`j z(Vd|s-aEKT*tgZ`GUrhwA`@1DN|yZYzOA=;+5VBSU_%n=RJLG6(@ij;Nd0DGk%n9BNKQ(FVneSmH5;bc}%?MEONm22Qn#~ z*Z;*kdA=g>yrP@@=j0c;SN|A6sV+cDY_s84lrcb-ajzSz;2V^k%M3@pNF#7EL`Z)cMv*6~9<)=Ww zlEBL*H_Q=SZ;+{sG!8x|=IuFbUKNOwAJns?Y8UCZS_pv9dxO179J(bF&t9F6|SorZZr}VE#qP6 z6K(=wofjotQs#hbP)~EWVm?gEuZ$k``LHR|8bS=^Hu&L;<~rzf^!K9_l_g9 ziMwO+Su6ATbQAt%D{jgsdS*l^N7wViCzoa980E!y^cizmS_k@GfLgd$hbo!}RqS;U zsC@u^02T!3;dOKg18u7TsS=r)jjwK_ucHzlGXown6NzoGkX8b+ObI|AeWsc0XJzf@ zMs2?1!e#F{TcehbP`Z%aY`B&Qp*D1K)m35<60E`IN+*8NogpXnsWc4$qs8+D)xZ zpTt&?iU2rPicZW6!{n5vz%?|@O2LkX^$Orvef)&)6P`s99kYb$YzvJZP6Z%&D!`K@ z+cL_tqBf z%t1{JDv66;Lgj5jEnv>*aczQ6ae+<8On)^>Ua?k->1GlzI@- zw)kJ}+>7OG6tgV!l>Q&u(45q_^)rCsXg`~8PadopxLcWz~EoWs~6Xb8jB?=WSc$OY` z7saF(L4Oog2!28}L*Jsp{u7L8#);7B9s#<(DaP9dLBW=aQ6RY==-R5LJx7iaKf*MH zVD2%nxYhDRJNTrnj{s^!plQVi`JycSh@5Pr7dWc$k5X58b?FMsI#U#zB+L_2HL8X9 zxN~!canD?m zWi~0~JE!kkdr|6A65nm)OzA}$pr&ny|Vx*4{^^hF=3I%w5a%Z_7Ne{}|osB_N$K5xDS{H@g5t3K&{4OF<@`yaOW!z(F2*jzr=u%2wq z4N?|fCVc^@6CX+QyugDKofHI+YYmI3$`@VD%eiRHB59kGNlp6&xz~?o%x?SC+LF22 zX7{5ppY_|~SQ2_N#%aD3PRBPqoZ=v1T%8`Rb|KUwAM|fY#Aj%o0nDAKl~Fg#<=I&+ zajjpt{Rmub!~gjq8Z!mDg#EgT$=VBrdr}6i(33FEripzYzB5q+Lqk9e1)wo)v`~hU zH>NV}(;VnMAaZ!h*-6p*b~CbCr}f9qByZI3Md(>&oX>5!k5z3ySh|+w>c80gmc;rB z@P9j+Kx4gde!n>(JNB%$#5vl=TF=I9V2Lj7Yq8$_N1|m=_f4@nwhFD+1})k8fqp}L zTK(y4JwX5Qm6Pui_{B18y-4EV7SvASq~g5k&wuWI6cCRI%)HPl$L@T_qHYEsV?Irh zh4hZMrJS~aW4r9DhpL!I+;d^I^XPbjxJ3Ce#2FJWJklalYR0xH-ER}>Z^l?ICWeV8 z!y{AKJTbm2b|>l#+4ol?>yM9&ljMlt5!c|ZEAnA_A-VW8;3YSBUqOIMFsvk?s@?2% z_#nsVV7FqpiM%9IQRhNN^$hDco?}rec^c$?a)r2Z%n(ORHAb!)Mn=`F*)c1gkKPCv zVP!`cvQu>5Kg{x>_s=h(YU7}FZb{(!%q8ba*#4Xpn;1GL>%(&u9QVLgsaFj_UjQZl zXzxKu`n!n1)(6hRg($^s=c2N+B&D7#9FPYdIt&TL4-uTrStuBZ8fP!Wi6rT1$AwVLu+r3P_O8D8oCzI! z1{{~54S=s?DRf-DrJSuF7bJ=VD&Zm@qvzW@x_3QAGTxP&Emu65g4Sl2E89eiJ}C4^|f=+@!{WZUE^&JJZzlDw$bm^@Nd9^g_#a_@tvbiia((cq@X zRak(J`RGO@CF8$G%_m3mu;6ch?;0_kUg;^N=ablGoN_?3(+RiT`4rc>6!oH)(>kX~ zqC~vOm=#)T*9F-1JL*=tpvmh;WuoVI@K2`Ic9Un8)qT;%=R1_YB9sv0?FmH(wWAn` zM_56N^l)JN6{P*_5@j3EUXOaW@oyD$^22SdT99#WYZq`Gd(PYSC`n@2HIl0Zd>1+MzGDUHSc8gwsF7jt9FNlw#d*;>axG3jBlWaM=?`Wg(SKaOh+mv@-kpJbf{1Yhn&64~; z-~0QTTb(l@d2Hj(Qw-X}exG7~I}&}LRdFxz`^)y@pu^^M%DV?6p1ZEey)@^=h8h@- z%f1J!YSH)AM^}Y$|cW`ARgf&O&ngYvM_Y%CB?;qEU2xs9t2a2mA2g zzhZ528!B;N2r2=G`=1?BN1RJf&l?06#_J68p2)dO7r5LZKot!M`H1?I&EU+#&w2ghP$#rpZ z4(Wzt;~U@ob=kvUX7%SfkBQlvDUn=Er-BC~j#iqTzqFFyUi4>aRb4x{YcS@$)=Lz% z`n~Lvd1A)xslWD4bLHlrXjh)Wx0S;fB;_995-FC*Z{JJhe9Y%%`Uqs&G#IUXwWN&% z29IVv?H-IxQRFs`1)KLu`vmo!{12|ORG5r#L-YN05xXeK*~ye>gBSV>AryK#F+40X zKV1*5;QWwbR8QQ818iRI0T>POsv3O>0y}2u1eeebvJB^H7Up>ev}EdhP*e8?w3&^cniC zH_nV0m$1%qGe6DF5-E%gkh`m|;8$4wa(C3Mkt%7aRDTlITF^ufv!8UX>l|B(vs^F1 zry0>&sz>`A=Vs(Xk4(sIwoCIy%3}Bgznn|MZ!s}I=l*K7qMBZ}(gCrHx!}^3Uc1nD z9G{_vMbb(W63ydOm5K~&6|+c6&Ec12!|BKn$sVuL+_d5686sCgVCt5@v4;|sa?0d0 z*#N!k4Q7$utb%)8&!cdgVjlIamtbG^-ga2pOVPYZd4p|}&^nNrz$!1j?L&s$if5F(`(Dmk%uX8!1o&zu``TCplc;o!(ahjZnmqNb*4a8~?h_W_kJ9Z6n z%b`!?add*$VwevEFU1}w@e}3QkX487`W$r7=GE%WH~h-sBd4LHt1{`kUs=@IS(~^K(#e^Ny zda#b^d9w1&FdZ|a=W#d?Ua`C5^bv)z6w>uxiTzn;x0eJ0O20!+)~Kp}dY3UCFh`6u z42o)(hg!xJQJ%;~V4!@Ba2%keTovmVo8H3otKSVrG8+^)rA~N{U-OzliWIYY7c3M4 z3&$Ppd8f&hWM_&L@s~CZTXhyyih(;h7Z$GM;)W_OrJj;nY)Q{;m4?{=C<29nz|GFR?e;^hHz41m*kf+nYSeC1@;b)rZnMm|^UK4VbBifLja_(#sj&PE=d)}HM(;fgihZ#ap?Pqjq zrPHytUrV4rWAqzE{6B!*j}v~zmv2B_2hHMs>kr1aLpt9to5g7l{Y)NbGf=3voP(ao zKqLdaZAi-2N~r#(?xe)M5bg62>q-p?P$a?5Ru z^(g4p;uY>ojpv06jE4Tg1$GG*;}%OKz$OAz7&+RTkgYwP5l_W(_mLB(28-|cE~?Bm zN?J7}`1u!A!&@8-@f{tci4K-+^xib4=2^i0*ja z2{Yt?it_doQ8?NPchZ4gk6Sgey>NlWc5|`*%LPXKFBmu&5{fPY4$$UkPK}plqqb5XVE=g%82GY|NR`^cMrSWw|~5x z1vX#Rip$-6+HkT~r*?D93%~{qhnW!l&2uDIGzMUF z13%^lc=raBkq2?`2XT3&nERv%J*4CnvEJVHiI<0Jr4fTKWqacp$ikrl(NXhQZS5SyN%?#1=>|h+jmMkj7vKfOSAic*_WkV zFl1ckhn)V?XCmVMO&6&UjRJBDBq5fIY(nokRfySB=*AfDVw3G<8xKcT>{nC_l~Nqc zl_j}_tIuUx$MI>!#f=tc{%9IEr;8iYjGDX}pKutO86B7A{XRXOG{qJ-FY`JZ@>AceS3MJ<4i5F^$-j&kkn9??e@(x|fuGHkAkJ7H9^2|JR zODgsVIr_M1a(^%31mRDLc@D-*O8EUaxd)v(q?-DBHF=4zvd1}fAvJZ#i*Y@WeruR^ zSFCa~o__ED|A@8ORgvEQuUK0Z#ZmP|6Aq34uUNZA6}_bGFpILV8p8kp`S{{>h9Vu6 z7ouy>+XqMb!Xh!#F;H*8p5>7q=V13(45^U_uiMBiP%!uw>|Gw|X!@c(m?6V_iTF@l z^CP{=BPd-ks0Y=;Gb4grYJiS2MDa5u>u@_8i0?EC6*$;dHqsZMhC>gfXq_Put8r=n(@m$Fd*9%NvNuc;vOwep8 z8}`}-?3)>09ml49L#weX|2EJttuFzTFH?f?j&0i!8Z%9M{x|s z7$tx@9IpN7GK7p6hHn`Hrh&fY`XMeX<)C0M_qaK5@O+8k*azw*CFnBdNU?rpsc&U@ zcIEK$`i7Cw)`B6g4TN%f{{10DEEW6_5zI0}0G;Jq?|N^v@MJU|ZhZ9C5H1_x6vd*8 z6#V-i{}zZ&Tmp*|X0p{&&5D%ZDi&ey6X`N-h@}O=d5`4n0`A7FeSI4#y+8a95j1dzh@21>bPb7GT4a1SJ?7Ya1tmWg3@#mJ~7W9gu<1D@;5@P=9peRk5kw_e8Di1zXaU~> zxEvY`PN*3yqqsM20ktfpy)5D7!Je%s6eGbbEbDwZkwL@|ss(^6)fPTVut)Ix`&$UN zJBGT`9-qVqEvx+?m;KU^4|;@9gPurN)vy=RuWK+14-Z$%)&6^w0}bVUEvFBJk_Q}T z_1NeQIH~-+jR)#jR*no-I-etO=jLrW4{&cI1%B+qm-mgO<4oRs0Kg6$IjrEO)^JXf zPgVN9giyb0e&IK)dzmPnnetuv+^k4@KYAeVP=YOcEJjViFK3?D1?(ecDT~D+S854p zMNyEB>#qrRfI^^%gsm-oByU}H0PF*B!6xDQ(7-6vrJmPu1jXVLkh5IPrJU1pYtMkg z1|VQFTz{1CYy+RR{d|1{2iO(V*0WTuQXEFcX-sw1(^5iQ@u(T{B(bL-JleOXE2jf7DdavWcul5y_CtX99JU$Q; zVra4U@ryWZJ7njFEQ%MbVY|FZVJ%W|t!YCS@-a2s3xMTCWdJ`1@7KKS(-v~AL4VW| zS`Uh=Zq3NFrv5aq;t9l)czTu+I?n(lp`vQ0kJ2z`a5;=rIDsgvaS9UhaeKvWygQrc z5Zv}U+d-fN{~#su7ASr7$$TKn32=K>QR@`m`dck_{N%UO>a)`v)}JFRC%|EYWsl?J z@5rmOo!8P^0+bdb0Ot!r=i1 z%UBJDeYuTgxy@)WWTN>6$!ZD*7&0pX`_3$Pk{rdV&bDUZjy$1W&YcC5obK9X<_sb+cZ%0Hieewiggb_iK@!F^b`j z>l^xSB=7k>Lm^%{zxzl2l3Tk`{(=)Hs^e5`oTNwoVf%aSiNU-17k=pWX7dd{5tPRz z(i9;J6%zexw98}UcrgOYmzox!Y_;A?vKiGy3aAHjGBJRD$Foi7l*eP>i6NB~f_cR% zot_q5D3_sesxQ8yz3a7$eX@l&`?5Jsf|D{Mo}8&MzW zSnk>{@UgiPC9kqwN(>_t0U@P~(ub%f5#4!E-4%U+_)piboxvSkApWKhdzX*;A9Q)O z=3+(TKEJwKD*+cU`ocMVi*@cvRe*NWLJlxlnfJ8y?r{}}yUK3gdjKug z1Adm_qD%&C{0Z3HBr`eRfo}o-JqGNG2JS6oZm9$wI0yd9z=HH_;Twg+5hM0~hY>&Q zmbG9VdBeYnEi@Pxn6=L%d;yW1x=1dW5JwwVJ(r?{pupS2pgR+&fz82dAFyBfNA?~F zsWq5~ohA727wb5y?@K9CN|q*5fKo&ja9f5J{3&P`Kl%=(mW+n?sFd1c!72Td);Sh~ zVuc(1*e4E?zBp!ghKcMq&O753?u=6}K`986#e-?4P&$!DsnUaau2lJp#D_}wMnTwI zHPAHke5soRQ0=Hd?C?|GWLsUn_!gVKDkvJZN`p>CQ5E*R^Zi7X_v_8?fd~*5n-Ax9 zUj#O-a_9Vb_s4`^+YcxJvgWY(b`bQ}8239=mWjeVU02LLDTEgl!XJzs936B;x#nKx z^X6=|#d&wK#*hEc#`mBbkv&2TS57?!9ciDHDyzxQ8X?M=Ei~D)nZV8%i0QDX&S0+% zkRwp!?(e}=kxE_QTfcP1(>DDI0&1N))4>=6Th?xm8AK(LX|~R?EksN>r#T}(1f6?1 zKNMSnc-x^n7kP-ZiM$y6t~aa~O&IZF4<-fSSWe4VkB3HJkxK2o3I>&G=d)c+)F!N)!c=6g#3%b7Q^xV-p(XcC0JXRrLXRXFR#V_{i-D6W2aK_tyR z9{1UDYQk$gI?{^bRCRf4F#z=)GJpvH0I<0OWB~Zc_rOTR%X)rBJU>0ZT%R7Fo}XUU z!_x!e@ec8D_4xSs@bK__e{+9-|8#SMxH&;w{Y6~t-96sjKHS{h-QC{aUfo^Y+}!-T zxw^i-{`c?S)%E4o<<;N6fB#)vUR+%K`*U%AasKDepZ&}IwLhy@zki>eo?agwpPZZ= z|7RT@A00oR{CL`*IyyT1_3PLE{{HUn?w`$#!}ZayrKP3C#YMzy;qFW$Vz6&>s2?$A|7XnQp+|XsVSa9IZhT>Ic6MfZ zdU|SVYJ7bB$IBWS9U2F@6D?&|9L*7@~UWAt=W$U`gt<5z~Z_LjDe%C5$` z)^E+-O?h8`Hnem!w6wG|H#avlS2Z-%e*OBjzP`R{rJ`i9xNxE1%Vb_nV_8*WX?cB7 z%#SFqZg=xmQ_Zhxh-!C4H9n#Yj3@!zR#DuR<35(5K9wNvR?2r)R@BwiHB?pA)YMc} zRaI1#6j$e0R8*9em6eo~Jmdu4M}BN9EN)KA&o9XT^5x6t&!2O1bCdFtGBPsKQ!|p1 zl425L6QffjA|g{l3&O&~;c$3RP*7lCph}&hQk}eVm6}GTvvptse_$(rVDpWK)%6F1 zxR2p}zJcD}AzofyuC8v*9(m5r&i1a6+U|vRcFxw;*5>Bsk2*>ZvQkgN0{5IOkBqcW zugD*X37>FbThdY{CML$l#)gK5y1KfWnwn~AYAPx!?|kdzbS&iLq8X77ps#mXGQBYEnlarH@ zk`fUU6A}{Q3RUyDamnKUYqqmjlz;hYvfa^)Hs6p^?j{Fg@?%cj1Fg`!c&HUx z{b;I~D^o3!&y#OvnTK&UMNk)u`&?n|plinpOyH6MA8 zrb>BYlxx~~PZrBf6s}?eXvSDq9z<&K*`0nr4)GKmwy{?C~SI+@HD&60o9&RsBHl0PE{hv#K;7-^%~cle8w-jik(M=LCP)1|y#B(hB0 zc#_>u*R`tH|HP}uyd8zi?9!WQ`N{Sm%O+(7NI_A2bdcjR)Ml0AT37*aSMkj#`>a&B z%owZ2LUQP*fh(1u+vOsdni2En_^>EReWX0i6vPR@P_wK&D$VseJ}TAoPaZ5Q{$zJt zQIOz!T*isvvi5no7eRXR1vD$am#?@}XG^{63T3{{dpZ5Uyws#Y4p)n_hc zuvGokWNEh*f--Mab(Xnk-riKI&k0Xt%HkP6e<%lMsYAnRZqU-jc z%K7U=yG#*CEwerkNMrM!x);Tr;CEh1No-C(cE?y*ZE%YM*T>NJy&7PsTK**S-F3&G z5xR`if{|Y{KH~T!7=|w4P(->oKG8Bt!vwC1;`RjQuTF}oiSTqZiL_H5j_*u4)mO8M z-5FPLrnQDVURWi50_7OuOY~3Hh@@llKtWL=ZD+9CDv#6^rgI{^WXH&H{z48 zkOMrI|E&M}w;CHDx}Q!uFeIu1{c`q0rU%6RTU6{gZ~t?sUA zt7!(&YB?ApT(|q6r`GWoPd;wOauMAQLjV9O1}c>uWYNEf(aohfN5c(qxCQCr?n%8X z-wx+04<(%#>7zIoM}qd4G2am!VDwbVwHV^OAm9r;&L>35e}f?iiUFj6<+K&;iZ+6 z^VH(u%%odk6ds*$+OW=9#-ImCSNw3xc2BP%A7Ql+6!*oDBG@F3;?4yEgdQy@Z*wEx zWdjkx{=ZWwa)_fi5>NqPRY}T;bL7kHHrdVe$&~m`tLsu!+HP4ma6w@UX9Y#s+4rhw z?dZ@XpJ|XS`>I%9u}o}{WXK0&!2P9Bapv<@ShmnM7*Jn<4gjdaap%>|Rm1t`dyxQ~ zX;f3lG*Sg}YT|sJ4A?F*!kL_E@j}YQR1=lj+i%3=dpRoLwp8Nf;)-7C=Oyb=wyU4d z6S;aUGm*F$4yE{E;9LuQz&Y56ti4C>9f1UH^B3MWw`lJsB%s#*rgTokLXFUM1E=k& zcD_#=JK+G)+B6U?gkB*74Y?E)y~#ZUM5PQX!1t&xdMk8+taa{M3xK}hRV7gU5#vBW z8PhPH>N!pQtYy?8-10riRkK+q5;2L^sa6Nt%7G9+XG&MG0Be;xKt!DE--~upI99tE ztr%EIEc0%18-s&<5C1qxhFcrD#-u1oaRZfMLQV+@MT@P|f3UB;I$=C(=%M(NFX7hR zq+9y_rVToI47ZigL(zXDYF-lU94fqwrjgo>nl&h#fD;T{W6Ys7a0!taSHc-9?j4Ul z571;wMIA$KeQnI55lyxnDgOsJ=o86Seb>HElQbZP^;KMv91njtV(_0hx1u3A9x=b( zkbKPrExQOFD?qo0^13oHe0-k+kAy+`dwj|!&p{X`34^jUPg*q7hi-L21OrHSKsaV* zn{5s<0D5%IxQW|(%}O`k!rbVK%q|+KoHf+vd7NX`2eRly!b^8(^g!?A6}`NhCI3*{ z_}%UhUzAuh%*(3GGip1A-M5>s7Zhv&JEH8Kn9WRR9yRUyd?eJ`F86$;IEj(Rr*S*4 z{MR!MK?s-Z3?;sAtc;MqNZiiKC)%!;5%g#vhi6ig{S_N#w}AjSOm`^{n84ypz?a$* zZ8KUybM=yu@Y|r}#m_^00WUolTq5iOyI5~IB?WF# zgE_X42$Y$S1YD?-u=6cQ^vb2)ic!P3PA%}&%HO|hN^(+aeAtsmXnKnS*hzf-hW7=? zJ*6)4{`jqlFhFGogg2-|Em?^q$)S-X#{UC>Kz_eDZhXAt7TXxe9qiEo0DyuWiUhzd zz#))B#&wqoQ8{ivkO@CF$sVgj`3)`yP86k_(skC4geICqZR^TLq9B` z02pB7AC>?BHLwnVEc_!10LVx31rmyM7^H?_@%)a=&{xiTKRjX=2>;mu!(!ft2j&7v z{Xtf*`qn==?@^{X3yl4a6WAW$`-wq1%nN|Oe?S}303M?t5Boq5%+^NBHxSMTebP4& z)n^crw-c22eH55G;RgWY_ZKSmKwz<56I4MLltCNRK_3)CBXmOpaSPf&5Z!tOGhipcJHJFjVriTeZ z1BdX3B1vFd#wED`3%L-Kav2jt8FN!3im8~FdZ~)lMOFggl-(6tYt>dUQ4P4@3)0X% zbZBN^sgY#qdSV%fc&G-+7y)bfZj`1p7kC?HfO#!5m!LUhI*Bo$CuU}cS(-(LPZ^b> zMOvnXS_k0?=b#SB_m$l@bH!+k!)2BSF@GRAmV%gRR=6Vz(36i4n#eg2b(wyRsexv9 zUD@S2O$FYa7&8$j?dGakpH=dyIG!!mJrD3Xn=T`TJ~zAnIonE zm&uu&%jt{a$rZhLYkx731W}O`xseNcCn9PH?hb^mIoaVj^x^O@9@r(jwTGb5&sDWC%?qkmcu zSa1l8Af-y$q_y^@ne?bQ0s=khpp9CA^$9QngQs8m7YoCuH0r0pMyeQj5XE)~8irh> z8k~%UsyH&It*V9f2>{R{E!zSo-O{Yk>a5q&tl%OpiFKVRkbqo%mo9&6H z#9AX1(36dTuHToe0wE^R>Lzm%u@q}26Wgo|gRi)ntD5?61mU4;APes>3$>!FE9Zli zcCa;K3cQdB4C{RkyRF#@s2tm|JpV>z1h58&AO+uAvchU$D*GWIz-=!Jb}=iN+KRN; zs;?WHhX8<a>(;1sX=OKAWJ!TB2A& z0j!#}>vpu8I<{&1wP0(vbsMOMUmkN^xaqpN;k39K+q8L0x1~$EH5UPfa0o1*VLOJoRy(f5 zvZ$5nxsWBdJ_otM8n$!WxWk2vYTy9v5MYlht_I7tS5g8!83wkCX}IgLx(m29%e&B9 zQ4gR9hd={TTMU;AyMZga#Q)N{&AVsd#B8j10llye^WY3S^=BxXyN>I<(;L0vs%Rh^ z0BicX@=K4Rn`g*UuF$|Sr^)?1rRX2 ze=EUyd%6{jx*QB69*PJE zAhpC$XZxEn4}7X7OeKvF2DMAVAN5In*MGyacmgqnk;fBJpiB*L#aNuhTD-+v+{IU{ z0eGMRUOdKRT*h4t#$s&7YP`l_-EwcN|T9Lk=c$RWnaHIl@Q zTw+11fBeTjlU&J{JP;B10adI6hg`>cT+MiF$k_bG+Puwc+|Ays#^4;zWIWE~?8RtY zwhd5N#6SV(jLz5m&SRX&Gu&><(ge8>m&ZI}P6UKPxDQ0Q4^Yf_j+YQ!YhxSAv^Tua z^Q$0&YMH@MdkX!%$Ez$(01L4&1N)p{PDF@?h=^LS!jK>kY!$->EzGuB!;#z25iGra z@~Kt;01>ci4FAo)f=evC01I@w(aqISujC5}`~}(2z%p#ZH66r8J<%-fAaFoREC2w7 zH4Hcmsr8IB#OxuO(2hL)Tt0oiy}%Ci;0!ob)GNKzN?p7yO~EF@2#0_L0uj;vcGf~% z)#h{69kK#F=>=Qe({?>sC{4p@Ewg4V*GWwu5wHlX3jikoU_E!#q)FGylBnk)zI(k@ z&wI1fi`gn&)<~@$z}sPkb$3(EJCLm`l1(0sfO$k)*&ub|CYigW@yw~WV4+BZGitXx{+)j*9(S3&;mMuD?2Q{ayR*?j0mSeQx}D=s zG~=e-*B_G8o&e)9{xwD^T05$4C`PI-_RE-t}mRR z)k@Au7%t!^-sDhzHM@pbO2Q4&0FB5xy^vAfKY1a)PdRr5&SM4!=Tf>`rbQf=cO? zjtn}c;o+n)J0ZXWaS!)!3tj*U_7G5Gt}h+{eZLOupFZoueutU9-W~4YIIbQrJrIjc zyyqS?U@*$ z{!Z)yZ{s4r?jSE21}_lM&2uMj(+B|u`fv(PUGv2Y_sDYE^^wz@;P$su^XBgHb)WS*@A$T{^#E|?nE?3xxuk(V^~6H> z^bw!DfcTN4_*BpMntk<+kN3ARe}`b1197&PfBAsV@k?JaGf?PS3i|ln!6BdXyZ`u* zuj(V;)&v0oe*5|Z;h&j*-t`jdxWBeCuK8uD@HlVa>R$Z?@6-f=26ILM#{d6am@oS- zZ!&IR3NPOL9{l{g-}}}N{HcETS}*(r0oTY6`%JExaBuz%d;etZ`>4PE?%)0Z0YKnD zf&~p89M}L)1B4A7I%IL^5DS7b-o2Bdkl{m)9Xo3D7*ZsF82@67M43|M%7Y*NeP9_= z=1iJ3ZQjJ0Q|C^eJ#o5(>C<7!lR`lX<#-fnL#0a(Hg#$cYSe@ageG_XvgQd}CI42f1gX3`2I29> zxUz4W7LAm2aGa)K>d$QBslBcEV0|Un->ba z`OlZ@YleXZt%Q5}_3g)f9#y^0?l$|={BNcJ1w?PD0UM&NAPCxdhl=ueiwr{Oin_0+ z{3`Uw0A66p1Vax$1W~37$%<|-312Hvx)Z}XFs2q)da)qHA}HvRcZLbz!MS1-X}=If z8u7=2j6+UHBab{X$n;8FEkzakaYACChXI zmRM#evrRYaJF_P;Z{jhfI!C%wq&)Q$bEi8aGK5Ck-f2fS9si*O)2BJ#Bq&ZKdC8>< zMkl2-G)H$@w5B~n+VrD7`TG>qM4!wl05uNLvLNxu`*O!nYsz%eOO1r9Qd@7OYt}KD zw9?g4O+?h!U~>Xg(19Xg(7{%REsa-P2h#OfX{V)@rD%V1*3Vb9`&CM2BmA}|Q&Ba@ zMjQ$1)YEQtij~o8f1H7gYUibQrgve@R#aho+t$B+{arVod zS8Dgodp{&27G4ynH)D;_YA>&Rt$SFebRQbop^{AwnWY%VO?A*h3p$yplu?R!sZ##Y z1ppIz3CEstbO~V~Fsg}%9cm;Mhz)JzQO6k_1}cLaeE-DZ#JP^2)nGGuH|DzQf+n7+ zW|e1#k!(B7Mk!{5)Rv0uf)zoyAYjI8J79tB#+Jglz!;~SoV9S~jvmYirx}4bSSOh$ zvSiLhctQaoXa+R|f{oz;pcC@g9<>y(q5nsS&x6z=A4~R!r~L7$eVQtvN7$x2 z_0;v3*zWUKfv)cfs`Q~`}jvT zL?DoGlwu%s_(ui`Qh^V2u_WA+7Lh(UMqGsuVjoLi3uCuNHnPtqQaD5*5@3+q7{dYf zJ0S}5C_*&qCmmc6NDu|`0c}WQBN@0w4i}I7AE$B8+!nVr{derN{K9 z7DxPJAIJQMKlXvK4rGHGKNN^3(h)rXQ2&4)l>k63wlR>Bhyef;9LNO?!bLBp@>!2C z!70`0CNrvJhnxbY%xXEdd8%%AZlsA74zUIV(D5DaIKeOLY0tB~lO`R|LPE8$jb&&7 z0EDy#_y!^hbX*bu3z&x`0Duc^3!r@e->bDbweX-`Z_vsLQxp45pa9$)H8 znmhoPG&qQOfFaMBl4zK7`5z&@(SsKh6=P7ihcBX#g=NG81^_UFKTzR>FHD0RTEyHf zpujoLmDHTm!dObhTA`JW#GvZxX_y9jzO)YJmHJeJ01Sex+zGU;ifU5f*bQt$1|V+HK|d}YX6~>)*X0Zim_G}PG5D(S!KCawyIGrE3_eJNw~)d z7~&8(H3(PEW!F~vlwM`6PbOf&3u;={w#tERNHj~bn99_%`1~zQ_XyV<6$Al{aSTse zif}1Lt;6Jn4bCt7Kqha;fG`iA#-EZhc6uB z2;b_!>k*@hg>04|55>gwX7hrc*jnwOk+%8IY}%AbDpUy=7W&gw`PuUn$;|5hrls@ z2RT8q&`Rek_t;i^)^nsmi03*xnw5ZdGNI2bT$L~Y5xGPN{ff)m3B$A0Mz%DiAg!Dx zn1W4`hBZxAO%Ok`5YxT7HLf*%5I7=&0SAG=G2Vd&9G-g7%}O;YAzQ5txi{9&UdgPv zX=nTyd(OMoHMZ}T5}ShhAT}ySKaZ_#oYdMq(hd$MW(#e0rv%+3q4s?lz3p7no7@6{ zD*+DT0OXq5%DYOodjFSAtrf%q7JzJb!aMSAb2H4^q@K679`3rnh!n8J!0rN zZkSLWrtscTC;xO1kv=qhpu6fz&iYJep6?Y$zIPvTOK%%Q?Y->m>%+$T5BVN6Nniyl z@-F-a6F=LoH@-`C@33y^lb;AFywh_p{oQXr%U!S3)jz@gc6;C6;V1w2^AG6oqSpBe zW4pt{KR$B5JBzz&IR&1hKX$V}iHkkVOFrd`z=EKSQLB-rQwh)#yMm%V53xSb;DYS) zf(3lG1}r-8L%|80F*8%Tn1j9yEW1NNHn=ODxjO|Cj5QOKJ@(tb0VEK=vo(ZZv(77* zcQ6L^6TlSIj}F9;4+M=*;JL8EK|Rw!2vk8O145+Z!5@4GLzAC^;I|rzJ|A=^CUmX? ztQHtp1^-q!gDH%(Dug}#t1mg6Lm6W}T{;M^D2DQa!7S85RVqLuaYE2IJw9+lDulnp zGeh%ILJ73IEv!R?Fh6mdD`A_tK72r$P(0=s#LrLyRuF^&I7Bdm!{fWc%EPcsG{s{v zE&nqJI2#6i(>q8k!$1_0PV|fe7z9=zf>HdkQWQU0oW(|T#9|Z(tWX0BB#0Kk9c39t zV&pLz3?D#X1y}IJAp^!9B*SNX#BD?}8IcI^IEcCNib(WEvsy&^z(vpK1D;E#YfQ0h z z!~YGO!O=TNTbVm+EJy~EM{|V6hE&LfyhnmafKSs$g0PWez&(mo#r6xx(iwy7hzsb2b(jZdZ~>0k#NBvFZ5+wsLq7BSHDI&EU_8ejNyp1V!+N>8 zQLxGPx|chk11ETbTF8ei003Vo2Q&BrZO8_rtjZt^Ni3vCe_TOUJgtU+Gh(1bkX%ZD zi^r2wf zg6tcCz`U)~QGiOohb%CIf0!bHC@D&+rt_ z@$60wzyl2+&-7H!^&C(0L{IjF&-e^a_mt22lu!D!&-`3Z{M66>oX_+0&I+I%DAID|xagc;2Q zVVeaabp zgKQ{=4rr5g3=Jr3h2xpjle(8%7y}*Pf?Mzh&oN81%!ajmO

QRBhH#MO8P#O@e>` z#*hV3?MCS6t5j$R5s(K@xYbIn6su!}KIm0nJ;+}m2YgTmYUnDUWCwb1h8JKVSh*%-DX6R?Bc)SAu+prbaGqTsGBU{^a)@P*-M#u`w z1b`Eup=B(Xv9c{)fnId z1jiL0$mLtg9XH9H+_PYS0Sz@mp)$|CS)Mpb+`3y^`NUQzCI8bU9n?)i)=k>loz11t zr$m5AfuI81xx}dzUUbac>dW0qX#k@2-QS&F-~3dO{9NwsUZDuDG&qrJ9S^~6+wa9$ z#TB2gz21!hUcW`(;)TnJ6^Q_#4M&iW&3y-A5LgGKU)_Su^%&XU_yeBPqV{#)?1kR# zonO_xHU}mcgJ}WD;EHx&+ry3DN>ktPxd7`$V2yd-%FSR5X4(A2^1aS3U|0*E~Z`3_2WFI6e9pdQS9R; zhGbQ}<0zKm^Ht+c-U;Sw8I4%s<|SfJCa@ze9SPXQF{orq7G1tJ5~aLTHX z0Vb_uPIlx;du6VX;a0AcKR)9?PF-U@W}jdIwM~dj=n`Sz!$F?n7bfF%($(4$=3&0% z`O0KQL}vJiT`fX$5H;@WbRm04xejAXe(9dfhOUH zo@Ivy>6m!hfuI5gL57NyK`1te+f9xERt_A3}DFIW!~Irp5_VMJORcC zhDT6o9L`~Go(T@{z7G8@edcAG;5;{D0A3=76Ntgboa!aa+j;l} zc~(cJW)y0yyQl8ji-hP>hU;1u=#lWkfd~NcIEEGgYp^zIYK{pRAQ3!{uy}>4Gtg6YNu>w9DG@0RX@e9Ktai06-kYVI0R1hy=O=9{7T;!W_-vs_Pc3Bj7oj z=I#(7W{6|&C(dVmrU_8KOko2CS=8;=_UYZ02}lU+ZU_Z2?SXs{iQfsH3L1#wIiBPx zisfmZDA0!|FbI(ni0pCjlq!I$JLn1T?wg*zZvMO1o=2AUW}7JK6To8iTkoT8@0gGW zUjPGx$bcdDi2ea07>_0a0ssOsApZnXAOI+Za2SPgActRgM{p7daoQp?{UXaUPFEOh zB427Fhskw*>&G7Px#kF^i-0ca>ev+YrS0XF5N?*}p&t??ff%A95{M&8q9qatU$_Tt z7=x&(1}Y*s0KlRH9taf$CCl1fGtl$i^X`@gZ_WPdSkLV`A%Hd$2ngUMV~_#2O!TTw zxtQpOq8tbl=m)ds0r z>E-sf_4AL8Yd{b5nW$@A$Bo%VbP-o{fRqV;5O#rp0ecvUVmc-$QYL0{CTIcxX`&`; z!X{PF2e$YJ&w+Cb!l0A0t^Ye;;&4B=Rxbz}o^@Hja15u32v7u2WA|eK=qYD%TDv(> z5QTm?1(P@VXRsWRKq!S`D2IZmMyDu?!YGYmgMZ*!0O$g1=Wzh=afe5Bo|_MezmE#n zWO#>d$!=)=I)u0?bld>w5NCSGPG6Q7hjH+Sa>)8|2nTAIu9XNXZ5S#GJ*uQys-}7> z1K9iYIv_|Fe zdfCqXl)we0#)a(H{_F?-+nRti1oz(;;HwFCf*|%&R(`8b|8$@JgFp=N=!*W8evzhs z^j8VU2Y_nO|NYnh?!T=&2Z$K}1`;f2@F2p33KueL=)Hmlk2loXN7L&6p$+tT{yN-8)PK9@4})v8YjrNRu)& ziIOQ)s2e**t!nk65>~BDUG3`iE7-7N5l#i*%vnEaXPrG8H?6AEt4qfMm@C$9SiE^} zrnGXX-Me;FBLC|BTG%jOv2inoFj3G1Rk{|-O0FE$!YWq03|Q{$`7`LNWs@cI$Bc9` zU!_pMJt;S_6l~BkSl_R-h9K6r($?eM%g4pRQ&W# zF;?XCB>$CQp-2*o6jjqpLA_uzV~swBHeDWSy7}gTcI0G@PX043nG_7szyed*Gl zDFrI1ln1o{3{dSHqJ{ulRyHU}kX97tL}J*34JxQ$W6v090tshm1O@^ssilJUTs=4d z&#;adI*}L5e6!6jPS}{H zsbk?7MG4hvyKPs`c_T^;@`wSz7wGIc9+&Apnk-ZGL4XNh?*KzZA%|#5EW1V(YizFP za_iiu|Bf}CE1C#=Fv1x<7fC+-P%}^|%*BfCy8Tj2*S-{$=fEY$042;|eyxE(t@);C z@&Co&$$F6jkeqS~BnnI$aKc{2K^-qO>%4PA0KVV_X8?o&g};5Oi|f%yGep28#qdT& z006LX$RWd)jIz-c)3t0wPJ}}bH{8$zP7j_&#&cC8u)<0#`l0?3?}apbHT|GfEM(;WKb+*&mH4@Dee5$}P3%UP_u-2;5Riq4-Z2Xq9E1RBI0P16*S)UaiWER|(8$FKW5^>FPUwT#S`}*@4NLB0YE>DKfQgW~|5dfdy&@f8BVPR22si!X+IMJ}& zkz1=wXb9F8i<~92rBQiKDeR#OOIV^8^e9C{K{`@XqBAN1Ktnr`ae{}?AXrw@DKjgY z&y`)o32ev!00tRQml}j%uy7kyv+5E6Q6d}cU`IA6QA4Iqa;ME?T>nTVA_LjIqm58{ zK)n)&REjFqnPi=a398|be((SQzre**wF-bdPzM&B6D(pYa#E<2^j37O<71)1G{Ce2 z6ATbfN7Ya`i6%9TX_ZK05weVFgsZP?_(ov0N&;4_Vx>V#ENmmPSf+$lWA?mfXEStL zg`9w`!thO9R8&-9jj^XG`$}yMf{rc#KpuVN!SPZ^GuRg3mC%5N|6;3Mhs-u9$^Fe| z`DNU!StS5HY{w-&8r*)t)m}G5t6Ar!Pl$h-^f*SzhK=w+ep9cL^emTRPVO&1gnywf`zA0h9PY(@ml|$BViO zyMziJbB9n4au_C1?WkpC@p0vQSBYpL9n!!@Gr)n4vgudADP4sHN~~mpq=|$BH1INU zOkSQw#R0Nl6zLgn2=&mfBMNgE=VcQW+-@*kmw<$`HI9&b_PF^Rkr%W&Z$xVI1939*_8-9?7M||Smp?g+a$ci&O zI$L_zs>NNBXs%xvykVzsMyTL4!PwR|Fi+p(4Sr+0D#Q{0*az_c;g5YZ&mjKLhA3Rn zqttWLihFQFq@fZ4U<_50$~^tQo^$itka_{B4%vOL6EM9I??Akc!Hpg|_qtd8 zd^@0p`D4qiM(K+z&yuZ^#cMXU^%G5YiZl7bsG7Bn&C-A z0APX-8PkF}-uM;X1iIQow4JsvpEacvD{R0(EC5rSKrxsDJiG%jY#jlHV8CpGIn;t4 z)j~Od!YQyr$a&Yc;oJKi7zaYcvnifPN&n6H;NAvyVAb)SLx3Rk@Lz0cjuK=7FB}$5 zXad>2L(9cr6h=lhh!sIl0zhqop7`JcDq93L;Tk#w;t>;xD31Dxk_6VF9U|Hff{qlz zR-^HOCcpwq8N~^}!xp}v7jDaQ*aN-E2oJzYfu$i3wxRnCVMDZl(;Pz=ikAkmAtf%M zjwO!>T2mmcKrFxl{uu=@5aK`l1TY+;3`RycL=r*VLO5{SInY)fhTrRPmhQQj3uajZ z-Cifk+%7s!E;@vhq1%3K7mkELE*Mr)L_jc*oeTiO^|>OcJjWg2LpS`wFLc8_+yMZ9 z0$`zG`%NMfqGLm>oYu8Y1%wj&dH*6O4r9q-M4Zi8ouS#1O~(>s0w6Ml0+1a@VB;4S z1P|Q8S=@pSFhnVAgFL9iGdux7TtF|Z!#p^H@-4*bF<$E}P)D-f%v}Od00RcP&lL>O zz@;NGLf*k0qe4{LrQJcMZCa5nS)&0$30xO*B?Z~(A3+At9x}u)H3j9N-gg`z-!azX5KhRG?Y^2NWmPZz2S0)4jWF02NBS};M zBCH=*s-ainA|y7%ycI;fmH(wy;m8O)LN1sAQ;^-cy(L^m1|-zOFWf_4g@VN3(Ldmy z8T^9?5JWl9WI)z=s*MfCU6F)a1JMN7Uyqj03K+7aV{rwHfM1nr*b-{bWZ1R zLML@zCv{q9b2^GW=Sdbq1bioX8mD%aCwd0wd8Q|Ot|xn9rw)MSL4cgdkzB*3>D28UJ zhHfZ_cBqGbD2Rrrh>j?UmZ*uID2k@&BOn7Y$wG>TC>$)pA*8{J)~Jo%D30c+j_xRj zdV+i!#L_h#Dm-1()&Jy@Ee{}61=;=QX%a*|EF^*QfW0+@FOb7iH0XmyC_(7v&GDvh zzGri~CzyVxn2u?7Ca0N}XPE{k2*{3Lq$zN|;~_8t2f!(rqN$x;=bGl}a_%Xg24{R; zW<&Jd-vu6LYSpd@k^y*uDKwx>DS#4$IEW^Jnqfoqf;sfnK+I-s4#aJ06c{E*R;#t57)Eg4&3WIUYL$Mf zrBUd^KS&6$s{hGz48SSOgFpC#J>1el_(D9C!3*>&Q~`ieGG#VArL>+SRaU0H6$G|o zB2&yE1$Zm0f-5hQ)Tnwy0$%I_I;wWmDmUo?Dm?YBy-2TiL&(4Y<80S@XQ4{{NH z!d4LQ+5qS(EC85H_`^S7t;s5*WZW#keyZOZP^-aV$Lc?D57REq9X$PU9og$6Qi>N>8h;^EsOL@X8r zE!rZ~3a)?=9RTPmG;nH4m;l+KZs;b(HsbO#S zZq4#;V>fGA4gm=W%&9_;oI0Qg96QgE5I4TSY> zuk7;d;AX@@Cgeh%t5zMrE0Mrx{=@siuM?V_JVr3s1;CZL!_UfuUmyaZ@vrInZ}U3u z17lA4&Qj(QgaQ03Ni4uW9B2dIC-2g(;X*L|R+I(40~%BXja7}7b#OxTZx8eE4{L8h zZ2zQO(k0!N?Cy4)?*f1ouBAnU!9Toa3)}4r3!V(m@H}#mNWMcHLPY{Zrd)Bb5X%@4 zlkpgvG56N)L8Rttwx$$QamV?9-KB5Hx&$@+gMCgh`QEK%#&E(GZj_(_P+)>p3>q5$ zuP!38@~W{x2&jD(C<`YsyeU8eQ%)(KVn&3+Klp+kOLF{Pu^)?FY-oar$bw_yL{aJR zA%8HnvNHTE?~^{Vlp3&LS&`i&0MSF!Ygq86Q zpK(F>a1aA?MpWt}*R2a9-4g#{AYugB38pV^EFYVr{AMvZdxZ+R6QKE2M~zH0EC2El zy7NS=UMUP~u^uZe*WDn<%nOvFPfkP!klm+#GdNc<__gvd|M6Eqz-|}=3^K)V*;q5j zDhRuBJTI@j(yP7VtC0pP5&@B*iAIhbtV1$9 zK^8OvI_N|LY=bnk^+1ThK8!*X)IvUB@{bU7fUVXb9Dq!4!#@zsUT;TVJK$f3D|Ev@ zgeR!OKy-jQqyhzGfG&Uo3Ic!`h{FeDw{7C4Ds;m_xc4ksksb^L8NkA$W!FT&zRcj;;`1pI_Bq_f@N&NX^4as&2_%S2;aMB1$#6aoMWl>dW9Yk@c*AUG7T z36w*pQ20RPgC!6|C_t1!aOnq_glh+wT@Qq>fp|zaged$&beTAGptwWqI6^@4nKSb< zcQ66SPBCm<#!xTwB5dT9b5?K7g$3g8zUXfT&3SJl^!(N% zUHBgG?St?U9{_YfHc-R*)=4@94F%9cB>+G?%z8ikUN490KwS7iP`Q<#-T-J05kNSI zgSbFQgaMG9XnOjIgF5`7w11QOw_61j07Vyzu~B4jO2#*x3;%PDcY9~ZAN|=M{_(jr zI0!+A0y;?50?fmcM*;nvf;?zJZ8pO*5JWb3w~0mib~zsaT)=gKIIu|sb^k-oX*(@( zyD@rui(@qw8%2G;gDkAFOQbSHulTy-_{oR5#v4V?@wqqjK)=3#%s|0C_(Bw9!7{|d znH7Yhi-A6j0u-deYG*jci`W$n#502UyFt@G7`Vk>yu$l6Q#Z8)%Y;I^69b4mNhEWr zw|bpdJ*;;|&y|78_U1sa0XCdvkqA+xthm=$w0y~HM;S1s9AO9^V4n9>;App$4v}0F9Z~)m6 zS>SsHnU{p9+jzTEzEOyz1-Elb7F%EWJTG3sB$aMM%Qzxvd7{GF?k@V8VT4aBAYBSbL6KRh|`2Y=Kj_fn7l*OLSU zIL&=8e??f3M_o0zZ~TA1GV!}f>9f)Xtc?_X__X(PvXY&Dem_6}5IB%vL4yYoCLH+T z-v@;cAw~oc<6jJk7ZWzX(*R?~jv6_76!{S3NQnV}y((@OF?+d*5h6&%nhZjGde0lTYH{kJpo_%}w-_x&u zKYv0AV()^vk59jROhgZO@{KUwnj)}30mb4DJFv7{(7~NXNG`b=R*0oCHz2y@pL`zd z(8KB)EK9+rFu+5JB2Y|G#T8j>(Zv^6RR6+67-_80#uQ~d@x~odOv#unY|N3z7OyyD z5f*MTa498^VzNmD!y56!qe7h0N{En4ZVv!>smzpz2Jq*fTCOb9%&@AA(y*`6D*}i& z;fzzxIq9s^PC13ZLx?;1?9)#;^W5{#L4iQyop;dqGf+b3%t4Vuu9zT6D9duPC`&J; z^eZXPyeZ92&)h>oK>#qNGF}W&sEn;d0M*r3ar$)AHN8qt2oiA3Ro7j4?bX*`cfA3R z8-Oj=*kf}QmRMw&&Ec4LWMNiWW_hhajYHHhLecNLF%b?f=SFY5@j#+JFfzcHn}24d$I;Y>;+Xgo{)pha$GU zt+8-%!Z_n`yDB%|hxYyWx&pFfB@Y9tvg*r(wgN-sm+=kRDUXZ#7vY5i- zOx|f{3Tk_1c85hE1%l#9yFE-}ZaI6}Bbs3@Nam`8dn~y?Cadf+gf{u-9IVL(^=hW5 z_Q__Sd48Dfn~T1A3f3?Y*lmDqK!i3Dl&-iYj!|oRK)?e>EN!ySF1s-z*bSkP%3>)2 zq3IN_+{(m{Ivl69-!3@r&XN6`U>kO z`#N9{3706rLaQD*NJFl8PyZgf-HX!vCeA@eJ$iyg4_KCWj>#e5>U}M8ksWY-9csp; z{@eDpWM9g8n3-2TEI=gWnlh`tCg_5#ZgF3K;@bCVeUqR!z0loFfCEe&&ZgiFL{X1` z$8r>;awR^CkuQA*I$xzKXq5kntbhA+iV`HW3JaLZD$qz3K~S+33V4u(jp-mxHYkz+ z7SLb~q#>}lhb+?J$8$CWmbI{Ty6`P+e7VWsl8%VP3-Swh`g>sujbedSNJt4$fL9po zw-sDKk&A?R;!9%aks035S2-jj3Cw7$>t(Np2Q*g1v=>1lPSA);L`xE%WXGBH%Y9$$ z;!dEF96%VLODZGC@&7LHM@2FSU54XhQ^t74VEIszx=JIk61c!N8to8=0H3ZTXujC# z(JSQ>rDz_RJU=edBukLcAS6ISSny&YTR8<0Q$^=Z^{7`5m@@-V6b z%+E3a5XC>fasN}Ho=YjHY@$;*DoK!b4x}{@1`kPUtfN7&SJ0ehOLv0Ji)eMLST)Hz z&1KV}4kSVn@_{CtvjP>4m8~Faq*1|=)H5#iZ6Jk9JF2iV?&ZyyRsAPRWokiz4wf)r zg_T&_TCzRx0CMv9M>5(PS%e_=A%=yBT**jRwt3W9t??Q6R@b^;S+$yhWeQg#g4)!2 zbtIN`6=laNs^pNWkk{Bs3M89bg1|N*u2l$TZ>ZVNDzjKA8HNy}`YZ3H)UPYOs%e!- z*nq;-gS-`L4cIjTQ$YhC|Hz+i!E0T!(6nZH0wxZL+tKv;%24kZ+Hgyns~tS*3dJHV zMpR1|=>O(1rj9(S^2BS=0{kvHc_0HU=v9sxfH%BvEi8G10^DJ)cdiuPl?{sVj#<=| zk~Wx)8j$O&`*wA|*JN!Gr~Bals?xy>_6hv9Rsq}c0~(reac%=#5Z@+5!UYtrUM;Mv z>lp(H9F8vuR#ymoj`pw5m9EoHjN;#D6cpZ&hdi_~hpOecqKuPJ7VhznYxMNSk>&D0 zc8ri7(=*5uKJu?Ji3X#0w0H-b)tDK5)ev=3x$M*DHLFWa9h;Z5LTOc&s)Y}v-!=u!Z5Ui?ZzZ8*}hFK zZM6Hs>Wn-)qg&ZZDh$GfdF&$|bl5Vu*NqViutFZyh>9$EVG687e4XuH@lt|~?0IiG z$k!`IKSQmnZ8!Fk>gXiX~DF$bNh6 zd4~uyw!*Ga?80lND4yjNx%XQ2-S5E!e9DbwD0jTK>PTiCzwi8Y5;NX3VHdl96LO0& z=zt5i@CO^z4*H0cVk^2>s4HmU98;iM_+1pezerztPA9Y8xT?W@HeC238G^aYQvARj zPe*Ure)iNojNN5i(|`Zy@om6HGg^9dN{C9sC_z9<=@6v5rDgPJL|S5WOQ(Q@bV>*) z=;#on8{OIOy3V;C|No8uIcJaE+>P(!dvEX0=lyyP3k`>o`Do)@^}4-L_*|D}2Y{80 zI7ISBL5NC(uKwH)lGQDmIxHo#^u)JcME+<=oTJdXIEla0Ot^3qx?3JufkJk&Ye6j_ zM%|L?6f3H67g~)_;+rW9M!;QP*0l(vy$2S~e^b)97q#dKcdG+fc9XH<{)V|u3o#x6 zC#GW5rcbCW`0FeI;6iKDUK-5-DraZhs$USPD3BO8-nt7OUHQ$2=z9wLMU1P)N>vt) zP>ApJCXXuU)_GL3t~94^x50wHr2u9fM{Ue{oia&<3MUAzI~j-Wxt5&${cw{S+qNdq zc5k(~!ws1G>*pX8bciGt-6Q6Y{`z;Aphbb1I1G0&l4^Y7cV`djp}WYN8khp<`4uz) z$>#pJa0KV`@ts8elw4e*zKlBpy`337t&iXGxptdabE? z&ube4BcR*dJ&WHrP=nlaRbA>hvMsNNd1|xtyB|~4^U5B3w!NJhwBSDhf+_mOQo^ay zYgwO#V&=$6VnpQQk2w`Ym{s0VC5-k{x6|F?ijvhS;D0joqW3Cbc;gVKqZa>KB(&vbSIOLFJg6cgen zYSc<9J3shS|G@GCFJ_#a8Y1LhMnwFZRJt#1Ly)o$v72}LuwZ8Y#cW1tqd-^VQN%t| zox7A2Z;9*au{R~Br5b}#wd~k91#u#gHPS5JLe}dmpc~3y3;0!OR zeoZ{boALlwhATr2p=}9c(60HLS_H67mGzmC{yCxGbH+_cX;29dm3$cBj5fY62q@EuFwJB|@ivPWJkIcUZf(4l!4ju8;Qv zXsHeeF+8IR|4PN0e5RP%&a ztaR&cH%SFZIl2EbO-a2;+Q?p4j*GBQLv*HsM>UE%6=t~N#xaPd+n6H=FEl66RtNfM|18j!Qdt^&@gv0t>E3up_?rBC z(>(`0LpNtYM}abV3NM>AwF2Ok+*XXBJ`4cnT3{BM8)rca@BUtRh~pF;}mfv~>; zG=S^^I^sgmhXb5qT?jqeTSv@C&)3JO)kjMV_Xv&eYVq2k^|j08YY#DBpM}@a0J10x z-%v5X$c)#4VlSgF{oGKKixhr=m%eXleIwxnk9&M7#C#qB$R45sntcOXF9RAg0(-@R zbQS^!T7!Bsf+oa*4GbVB7tO-7u@4aR#H56MeV{i(5CJhWv_4GS7bd#^)9pob5t8Az zAxN$e>!exY=2p-fkytm0vuexYwIExE2jX8{iPR>LIP!ey?)G4kRO%6<`8noq)z zpT?Jy-HG(`21^f+aRBt@3Kk+{@XCnGb^A4J|FO49tM|M?kfp)vd|zaAtAETD($^O& za;v`;_f;Vwie2=5@AtaMHz4F*aEN%E7HwSfRcw80+{etgUh$wMu}Joo8d(%Q@o&-j zH3LpW)JvNXAlm*N4L}y*aQrpCpF+J%-$|}2Oz*4RE2xRBs1rd3_LaP)&SE>ia`|Zx zqR@lx0CLTI)n6bBBdG}1t`J>{B6_8Vd#?erNX_&+l)ijD^*S-BL@Uj0 zD_w;aN=R6F^7|HW>J|I%7WfMkUN@dOqeN^h3+0*!#X5+k zB=v!kIe7FLc?j_Xd2`wRH%6@ZhQ_d=c7F@w3G3_)E_%yXr{s56F^$?q%1!QOU&^{} zs$3q6BM)7lp=kShnMdVmztRDEQ1ok|OyvbcxP`=+JRs9f0fRs&j0ed0dzB$ff_0ci z>UR&?RUR0N^Tyh{!la|3|Dr z#uf#}wPwjT2x@RIi0ZrI@)A#>ewq4|_A~|afk=9ivW|a8de`-P`3|AP@5Ha$un);H zLqPoXGegFESTU=oi~&7ZfnkQUF7DQx4{*9gCG}c_uQ1U0lz~03r6a?mlAzSv_2vwL zuXEs2Mc!UUOV>GMazAy|b?QA#TAm5F5C=2IO3eeq@dh$>r@`th;{Yhe8(r9o0tUaU zZ#-f3^`*qjmn_w*@}7H^I6?BIA3M=Tc$-afCD_3;z4E}GQ8_q6F)POdI72Fs z_%n*G+j0inN4#T62`(ImfF@qv;k@dMJL*CAu+mB?MI8kBA4$JIW2Cw^rJAauTj5s$ zKJjm*Vj=3vCo|j1ULHB{6k%Lt!CbH|VR~6Edh4WM4CO#;8CE7uBxt9=VLO0%(Gd0` z2xe^h@>Q3{6HER(AVu|O{G8i_mrP21X6A}gFPxaz*ArCaYx4ZM7L49jEuD?93x6R= z7mRxEFQ`y%wM8Du9@yw@DZXfA`WB z!idsYnV~bYZmZibVYE!XR45qriDjEl*@_e{c+`^r3}{_zovEG|Qr+EZn+qeBR-78k zerK~-7qFFP`jeNk+U4&S=J|uoj91ZbjS&5efJFeqj}H3Ja9E1vgqtahhn4ZDw{~T3 z!z|K_gmg}7(@q8bE4*lkUEoLPgCCAJOij-hN-AHHCmj&j=Fg^%gqtn$df!`#h9I$t zM4A^U1u_ndC=W)>gGw<3PcRlZoLA#+eKI-uaQyp3nc z!wU(ki$8NG$7U&N+jy2gLeENVT)GaN{wi($g~u_SdzAs33Y3F?>v5ock${^bxqZd- z-zw=hS~QtaK_lZl5L=w|l7PnC_$wd?(G!YGL@$km!f~WYC?tdM$*~<}a(-jRd+RUb z;~1p^?(mQMKas&O>eLZz}DGl+EA*|eDtf!NN1P>q$T*hrA>DV`}5ySsr{nqm~jdAJ>1G#f2Z#-i@Q^?S&) zFBT?rtzr>6fmvEu@Rrvz$n)8Lgr6sJh+17S(2gv__lN55&^hf+(6GEZTzSM6!^$O| zA1cFIzNXCPtjNfDKij$&R*frSl_)tgux3Vh@fjVJFT-Q~JfqV}gM?8*PtlQ%CWa}% zr9$Pc73ZK2XFB)Z`Ff&k!bXWQ7c}}A#4-R^^_ks=5iV7knfXmkc?Ex(x85nj<5CUM zHrxcym`^rx)y^xHqG2|4RE09U9Xsi=rHfqN7Ec_LK_k#1a0$(P&nS$>p3t!z)J12I zBRRplqZdIaF(CE3nr2h?o@3@-r5)W3d6Cp^C1q`wBq4Wkp|O%7kL zfaoA=00Xvh)GRM`%!{mW#Up;9G#Pt<`W7J0iPVe5uQu=AY7*3#e-by{B)NwoRX@og zs+ISsqZme9|5ZnIN_Pd$Hm?e1RoWN(O9{3?zB|%hd{eBmgWoqwQBvDoIQE9_4aJ(dkn4)R*=|m_;X0?_hi`Hjf%aRRe?%SI{v5-)^Wp5RAa zz>$>^z8nu7JMInuF7Qg>jeQDvzy^;RJd83Qe}G5LBlbo0E2?*hXbwY6if z82%4+k;ypdg;$2c$5AuFrG*TaJ19aYi%iiPClUVu5e)x;o1B$IsM=R_oc>|JsM zD_P925})VWc;{laWAw19+D!7WALIdJR+Ms+FoCW0C@B9yKXNWP%Cp*#_u1~?#+NVF zA^TP@?R6g+(ATFi6L6@!Kt#*US!Q(Zmk5Orj9U<%X87GJ6-hFR)`)*X*=PNkm9!VB z;@1HstiIq^6i&BVnMwzmC#x*r5nexqJ_XVqmg zo4gR|;nlpm{cY@ALrX%OGTUdE?NOCOuJ)+%dqu0AFP-hO(QmACv(>gG{Aa4?%rIx+ zG|l+R{4#WGU=Ql{1zTJ^9v+WQmloltW$`}He8oJ7;QfM|vX0x87PD;wp&yoX-pZ; zw4*o7#24@JDuw7V($9zKcQ(z3E^RnyZG$xd#b_3*9w%MQXwJqCu=xv7wYEZBN*~|r zmO~8zm+jrC*PV)#$Ek{3WIRhFDb1xBUGtB4cZ_oG9@dQL{k9cKdCL=I(Se~>MN zS;#Fv%i0|~HNFVqVO{9lK~$?4WgU4U4P)CeS8*q)#9=^9L2Q|*eSZigbx`EoNlEnbs*?4|q5jGj zq;DxJIfCMs^ntqR&k^lUk4-%Wt2>|38u*LB1yzN{d&7fPGl!^;zhg)8wiO9WFe*(X zcC0!>T-2Jym8y6I~MC2u;?jFE797qsUj1JBkNHLoxW*|Yn}Ae1IS z@!a!7TA6F-L5lvU(Utw`s+TLD=!S}jh01-vO(qT_ z`|{7)Nw-UWE^Ox52h3jXpEOwSjGJi z_$QNGpi~4+b6P6~{{D{m{UUH+FLL*8Tsm%UNjTM$-iET%d7I&@^L(r1Y%bbUj!UAF z@~Tyy!8xb;{mSXX3rhx(Y_j(qOZ^9pT_R(SI*vx`f6duj$nUqQFa*Igm?XecxlIv2 ztyhT;Yd*U1M~AeqSM!uyUfso0JJ3da3;l7WDVKOO6SKUrW{!u(XfRh65EW10Tl$YV z-JUGt*r9e zL~#AAH>t9f2{g%2TY#LL=OzVD!;^d>RwggrOADpPxV@VJ0(`@VyEeU99O!#|krvqW ztI^6wf|3Zg$(z>w;rn+cdXs9O#hAI2Wx3wj`E6bkM2ANC^yk+4Ro#D`e|ylcvUoOscWD{X>;IOdzeD=_bTt&>*N;#1BtC zM6@9Y>m40)hwR(Q&t8&Wv^rcFnA~tPI~r3uv3*#=C|RBuLGs8G-Sm+j^;w5slyf@gmIQbdGTLA8}=xTW@|JM)3J|) z>S%rti@prSuB(~&p*6L*b-lME5hvj!Vvhyz!d4C3zNSV9v_<5sN6nN)Z(W4>8d8)M z>7?$k_-8r>FWZ?{gz12w%8FODW zrl%z)crj++A|^BwKipm`zQoYRkbfPbRxxZ^h0jte9u&1;)$SL^q@x)pp3u!2?L`&C zRUb)PYTm;Wk8IW*KqAF_BSK2!BNmX=JDAq9HcT}3O_az;oF9zen@J4Yj)!=J^F4@Thp3<1CoSxx`P!19XGpo0H#7Ec$>ni@AafC3y32c1*GO}grKDb-lpL^Qr(Q}K zGF~h#<#$`+#9~S&I8xZ*9jOQ4ap40k0t}t_5~ZYsiS)IGY?dDI`kkIld{|iQ*G0#t zBgtg#@mf1!F9;|c8X(Ts_w+|74IK=P=~AMVQxyGQLPmU4c9Z!l6zwY#r~MvLN_hU@ zgc1TWLRmB92j4PXYrdw7PtvyLnFn`prUua2#QM3|j-(*2U(*xtMLD?BSjef>;rhds z;woqpDk#05>ZW92NwCnf2dzx<(b-M3^^xP%4?xiO^4wy&91g?0=kN`MkRUITC8S=Lg`J}m zX$njv3eK!^k0WxI=n&s|18$dce;5_^(iN>e1#ON9jqu_MjiM%vD9CwpkGzW*uF_D3 z1#Ea8=MMP{H~t$6SirRS4_)EUrUd)#VmuMxNETPPJ8CkcbQY%s@v!K*UQv@?NlbE4 zcV@xmoO!UZmpNaUvcEnHp&yBVIeToXRpld}JwGq{By|)du&!{#A=)FBf~3RKH^9)p zql`1HE+J3^M-aNo=F@%~hzZ9=nMW@~;Bd1D(I|ju4bhIZ|ZvQC=ICAbUdZ(NteFG36Lk zhdD+?IKGN<3`1srs3t75kqos9@NDPH^AN5G1K>llA+ZiM+@Up1Llx}JH7nVAQUTy1 zwaSfvcqaNF%bR#`c_rIkz9YEe*dF_e>#^mA+YY%z))LI9)>3Q8r_nOK`QStCSTo0z zE&SrGq3Vj8y2HI{dVc7JKlaBe4}M`&sN_szarGnk--c?~h$qYC)c_V98c*IyyI<6h^BWrA6i)LJl!V))F1^uO12v8X5)+g%A&i3JeDyLHz3Q z6cEEP)x&Y)!wLJtN!7zD2#5+`BrRuH8HLM$8hmd$NRNQf_ly(>j27;XprkRQW$~ld zrlS?(qh+0=HN<0f)i|8Q6pT<(TMLpE6KK{)z}6Up=@D51m~bBs1bGmlVbBQ}2~Gh? zHyV0FoPV%e=3^E6Bf=<< zSi-E>1gGn}&;kHN&!9Zo zq|L%mV;Je5X>9%x2P982DF8JBSOJpB(uJV~$)w=k2~gAw@5IO5vyZ(}oddV;*%?(9 zK7ROloy989x5Ur1+k*!xSSTtanSqnjp-4sn;8)YcKi!?8WuUQ4c<~2|Am9?m!2q|* zQoqcAggn7z9f8htdp^-y$e)b715;FP)Qrr^bTDO2W;yvU+QcKWTl5MBO?HdQWJ)HP zLo9$+33ltm0C3=$HUR+f1*iTC)1NP_GBawXOP>=kjjv5euTZT)>I?BaAHTS)EYy6M z$69>m#bMZ3Iu;bf#?q6`SWqNiQ9xW)!X054kuX`J%s7?D_(;x|CB))!!{?hWlwqJf z-WwY%(?~G+N|3o^l7xcj*(x@C-h2UyCBVBx6X_)5jX}wT0RYyX{(su%(9i#ApR3-D zb0@B?RjiS5ep6EWX2-j3_+yh&d7Y(x+NQ_FQUL0VAlWq`StJJh4kUXo^Jx`9cKQC( z3-irt|IIm*u9B|pAm)$3lbb|>_1D4MQ`y_)gdbyEyNrG;naFq2k#rs&YrHrx4sQwzG=iZn~pHTPnFZlGaz`*~}!Y;FBJB2kgI1*&lWF z92Z1SGV9E|LC?wVPnjQByg5ix+xeEaR`b_*`$O!@#GTf^zp`Wx&wlK7eE1C*KhQM% zeN4Ll<3kHtbA@}j#bEgN^&9LwJN=LOZrk5O(%MacR^RV#uBF5ybm`Hn(W651Lvpg? z<{!s{r0uj?t#m)@*8d(H{XV=9JS=tncI>1hlGt8Ne*7*~;bG@W9`7cPevZe*7pLYH1zmp*QnzDbwcYm%)dZA!JvfLRaA|S9Hgp z-soJ|e7K66x=J{_N+P>{D|G!%>pIQtIwR>itM>Z+)OGIRbv{#V+9kw5QSX5d_qN){E1tilMkHn#G1+ z*7}gNk6bs9!d5EDtjdWT6-QPhiQGDlFWP5bsb^4I4n~M4Zw+LLF>K8(&2DR`TUxwwfLydY0~0o*hu=NbU-}){&2G! zhZOC^>nwTPl!{(-zJahe)hhm79#b}JXRh`;(d}X{npbaIzz;5YkBF^ zZn{7@iOcNUnZsO#UajrQw{xe(dYh?Iv+ox!%k4ggTPxo$-O#;}WZdSy zCe@CdWPZerXdsjO1F%P@yX{EW(cQ!C6#5hqbge?QH||L$d%c6x6KOqJVV4acI#Ff} z><$O9QXWzEq8_yMsxWFMb_jQ06Ru4wLP_ZBKig?OL{hr_)+wV6Z|m7&_EKYY93*zx zKkA197r!Wl_mp!nzb@Y`9ALx z3LjT$B(fc^hcFVZ28j$3Qe!iknhi&hOth%%sCNP#$)${>!yv01*U>mNT+bAOaLD5T zr$p$k^@hjUeQrl{>zmyd#&zWJS0Hw20rD*v5QP=L_j+;P zdrnvD88rgf)C-R14k~DZX%9}X#@UVPpiy>{rsM$TonFpZ?F-9r9^GfkX?^x(H5bN! zhLx7@Zoqq+jOqdCHPWhSBd$2LJs@ZK>)c2KW5=4BCUckea~c5Y*QZ-C0@?CqK!7YX z(;|Gy<-*LKF7I+ROi7{x-VRQA86f1psGKr=gPSFI^GeKUGosX9XR242{Lt12DVv7{UqQG+hY_`nw{c{8iN* z1cGTJ62Oo0YJjO2m8Ma=cW%tT;*JX=)*gBn(RQWs!nsCdJ>P@;Au`JWdGis~0EFha zmy>A)c>t8khvFmPmeFBhu0ZbcG2n2}X`hUWs)tVR6?aq^71^}+98i1Zq+Wz9=xC8# zXgJQx9PX9)hQ7vtd5%*E>4^p|dm+p$^!vwW)-iB+=cx%`d9Si6U9;YjwNVpsaDAj-tMNjqZ{WWUl z69x|oXc9$Aq=Z6AcN7@A#z2zp+TdYoTn4jW5z>pBa#)%O!6<-)$nz-7>8xRx-vfrQ zsT(PPKzJ~*#;TU^Jw=ikDB!WQD!vLng0!5Snrav!*mKOqO26T;{(z0xrcHi&{wN%q z$ri^hh(D|-WB~J`fd=-;G~L4CqQvVILxzK*g2KoNZB`;Pd)a$;ip1dd$j6nh01k*} zd}&vMH5B-1fy?VO=730<$K=#F%Y7_2M?-U{FfNh1B6&OqFbnlgSC}b+VO)H)N==^R z=EZcF+Qp1qy)xtZm1TQ+!6Mo?jO9g9Lc}SNAxc1=FP$Z!-XrQSLC-TkV;&-DK7UDigHVLv z@or1Z59ZP=)Lvb5F?;YBmCiM)-PgvsS1KAr&#=ga$Ll{GY?TD zjZz_kii4Gem-=Ng4pJMd#k6TBt32jpSrSGHYJN*q%PgWWUHmL5cs&A&^h^ct*sMTj z5O(hCp-_Qo+G!CrqsbH=i4_OzB6p-KHqknp9QBZx0>r%-&CuG1#}7;%4~w7zu;UTx z`R~n!S?E=np7VY0%bqjIU1JebmzVoGKNW_0o-5~3rMI3vU-SCB%9n{B@Bl?(gODel zxEd4%5&?R_C3Wst51jJXyi~-xC4pHvnEpoFR`PkHWbiMH9=W;!AmVjX`COQ!rX{qw zAR){6)GC=@eA4dg<@4Dpof8oVhB~8(ec%W zA!suWdP7)8*($0k3C&Pu^Q`9vf#HFl9MNS=9KC=eB}rm!=uJ0CA7JqnqRhk+goExn z=1dVB4qSd?hy!r6wtD>s>uljf_R$Cm#{to=*82CD(P-X~scppFwJn6)J04d>5|9a)E?v(& z)Lo`j=_j0ly!A#wNB}x0MMZ1_7a)<_p%rdCUU(sjdI{eqAjt5a#EFzXE3|*|%l~U| zVpEOBeZtjOkC|HG_;q7;vP`aQgmIpEx$goIZl|a<>+$GD?^Ir3c7BhJcn9f0VQ2_laa5MXB}sl4uS&GX7V?Oc`3Xj7P;dvL#A zeq|HXJ{+!alBd|YM5NdZ4w|DJ;_aUR#bNRZ#c{8k-(`3CKw6);=G%vw9sn>`mAC+3lJp<*e!=fm>1 zj{)~tMY(jqyd2Ne_Djs|b_nJVCImnX2QtDz0@%Z4IIad9&lC=JhC_nj`0;Rp95`V$ zoTw8{JPs#WhLi5Y$?o7#VtH~#c?tn}N@;m24S8x)c^YT==xKJ^czL=UdHNR#FAUkk z{X+Z7<(c>8S?+oV+T>x33Ty%j>_PZAJa|_-QL4ho>5gc}#R#^r2)7=Hr)pz38uxP? zIevk(S`RpIF^U@y?ve>{K!}p!K)R*s*_{=|f)t6W1s|h!CqyjcVF&C-)#P z{6L!G&EdlU)2k>Kj3WCVRHs{Pm_@Iw5I)2U1W*@;sG@OrgyGYQTROqKIAd z?g*z^1HTZ)mmZGZc`?v8_e;EhdN5;d*;izm?Nz$x-

+1lB#*_^i8WO=uZP@PkVP;M?+6rc1Lq%cYS_)dsXA&f76K@8~;rc zSN@wO&YR4^(!^MoIBqP)x7WwA)%Cu{7~z71MP&#a$`>Qk8v2 zWkr2$%|A48b@hK};*zR@|Ioyk_aT^QfAqVEy6l?5!onO>PEKx4c6N4JdRl5qYEn{C zN_-j;iF_AP7#$fG5fSl!T;h;_yTm#bdWPwqSd{qM+xF7NB*8yCFfhp1H}t=X#Eu>@ z2LFh}PPVqTSdsXTq2}GwC$~}(w<7$vJRE;u%zy6D{3VBm8yR9bViOY+0|SHS&!7LB zBYyTwQzoE6RmVU@MditpCyI)Sa5x+*63fWSNlHqJi;F*g{8&^}^xq<}prD|DfB-Kq zFE=+g7Z(=?2M5+A#-hZ`Sd^HF=^vDsmi9j=F*!Lo79u7fC-@Id{1*?;k%)+xnE3xf z6N7MY{zsaaE9U=66KCQ6SDN_2lZgL2OS{!J5yAB>5Q$O-fF^X(RMJQyBHyYKtC+Fx{YGEX#oa`;~~u~wYseH|x?!8)rk z=3}iV^WWRNe*KvE_zz87F?wMV*wzR3qrdkv&h+}EY9e1zOE9?ObWgO%YD)88G%?v< zOd5H2=ROppkoj_|yX*GyXnibS$UVsa;PiNCfh<1+^ZVp_I}d>a+Q|z(XZZZq9_X~J)-#3s*B#WEx_7!V9`BAZ*7j!|l8iVs0Fo24naoj0D(x?s4 zzTo(WCVtXkU-XuXz8_HE>yT6WzM;LKj0JSfToymVn@lKNY&zV|GRC?xEw&mqiP2r0CTjtehlDM=dvn(tnSi$8Kw5J>tgVdmP+~=LK}BClTEN~ zgRAYhQNuEn)QkL>Fw>T5%Tf99$A@O2u<8durIkH&r)QJy+4u7A!4>Cpv)lA79s-Jiy2rSaI1{bjOv|4|rCm?-=g07~Gx$jC>cT1aTF;WUqDO=1D=yxkH5Lu;_>;|c}1f5W_c{sgv zGJesMK70o@T4&V)=F5AO>zrsPg18t4c{;2B^2FofK%M}mTR*iY5rCHPWTauqcKaZ} zQ^O^AAuCb%i+)W|J(z~*GBTty3P$vBn63t*u+&AK$l%QRn_@wxa-LkFxNd;@YIw|i zbjQ{Iwum+Q>9``7CoImH<8DVJ`GvO?Y)~5v*gHz{H}qn@fr9}b{6~D8U%^`MaRR8I zB>o)zlvU~_bYu&?;=i}ks=e)=HS_=sMpJ}Ro-f{K@y2MpyqOK+&nbXIzV*>xPy$9a zRwcm{;`TI}Hd+>8N?8CLfW{df;D}3nfB*rEXQf^ikEQ^iG{dTABu^NrrFGQQs}TU^ z1MxnA&9;vf2dDYs6THvv4{NUP*TAL$B@fnzv|Yrh0Gd}r_bg6ELXn>CQw&JZC^;cu zzt3U%7q7rif34rm57PsBKTCZJMP#*b=M#L~4Ub0=f2j^;(gEh@|v4=uS~6R4cZFv-4gDvtV!nNV<CgS+9#~P7-Z%3^I}e% z>-zlA_ly0jKNnY0z$f@L!%jbN4(HOVg5Ta>W?1LSaO(S3b3e*O+J@07vxMoQPR+N| zG8-RGeh7^UO$hpm+wa^<{Q9UfXWZ6c;vVL)n7LLCb&3_t$$w0qCd)4xdnG6Helxp9 zL!9(OIkkoC|yfu;1U(o<3dVA_2dtz?Yrt|Xwyyz zOtzxJEr<~N-AmHXhdWU;*&?Jqk@3Q6=sTBLbD~v3i@y5Jyhtx7|4+38u2;6K1$5}K zl3k?rawvffK;;4M3|>%97=iW9llwH*iB{SL6z4|~@XvKgI&gWK>$<*XJSKKE$J;fb zwF~o}KN4MYMqGdJu9FVpU8SdRfiW1rAt|K$uV+%jIB1@JwxWcjjA0N1PJ6hFEC8WZ zUK9^NMT+5u5m$qH=rc6%Tc|%rnJ$9Xwe8*xp3m6Z=tr-EuKhF=y3gOnEiYGdiBYH# z5q}TuO0s>EB%&mC8tMmP0#ztKLME)d*rEn(lvl!a>q){j5Zoch-tndASlbs5_mCLM zRH;1aFF=HMsnieo8b%xD{M-%Bva@0m3c#c4@B3|uTAXcf>sxSOcN9P+i13E6_Xo7{3!}AX> z|Ng3X?PYy2d6NE7O8$ZP5XOUi?+VXsoo<0(K=MMK%#6MM0;gAo%6sZI57P|``S}!` zrbGx~$6!tif($%f?)Ou7;>n#T%3XxZ-So@-#eq{lgf_U7U`@xeqabfC*UU>x#&Z8G zU#PLR@uwrMdF-X0A?AP1%j&}ZIWL2Av1pTgf!c(6iX_SF>iGEjFK7gpc~f1oDWi>} z!3d>cW{^GQWu&4cE{^Ylq8ycy;tM5}R3-H}C9N0GHptUfi0r*g=oeo`&P?d6O7MbR za9TPr5>9;RPQYOpg&+Fr$1zY}I9eY;G6eHrwIG?D1`@m_+<~bmToX^+Fic!Us-o8Y6bCc{FE!q9KAZD? zwpjdZ87mJTY2d&}Q9ZFQd7>H`{)2*|A50*b!0+4NgwQ^>aKWkc9WhGBu|FnMx&yf7o!TwEaZ?W`qvNMB4do( z)3W@u%?9tRUObL@p+-$PqfOLtL=1qZrY+diam5kRWe^sCTkt_%Mz)8g=6e2V zZ=MRO7*amcH}IX0c(r68&I3ho8b;W-;H?sDB1nI3q?@0I7W$+Hq(i?&CpU_x*?r9r zdVp7)tP*0B{fIpCp^jBsi3vpYMUZlO41sB%vgx1?l*66u-CVjEzJuGYBhyZ(H(d_Q z4?l<|O?TH*wG^o|6QX68JsI)u6QfMYYI$ zL&CD}PoXC6_$I>oH0YAQ1f{-Vz8vc@Gho_1^)3;bwdi?Wh3 zAvF~gL3z3)D|ZV2M+E`1R{}XV6}f~0IoSeZuk>RADl@YDjV;Q8zLum^W_Z3UCVvGm zI4a8sNJFskq%~B<_VIMyRP{*myrZa&@Z>FZER2;bi^&E=xZ{VzEzZv>pZJ9lu~$K7 z%oF{qxOX{Fqns8qHE2oBpQ9CAG2)(;)x)vX&28Y?Bhos=hb>@qhF6|yU(Pqjw3BaU zB!mGMyfwSol^}V5lRLg@kDc;X?XgP3(`_yMTY2;}2FF1K?Jc+;^ZMyz=$rkQlF#f7L& zzM;~@0(hWpPV3YfG}@ZT&@x2O_Ljd%(WF_C9~kS7uQFZVchu}7RTKC$&FUkE?oAtS zu~VV}up^oDG@1C`yo9~ehxGT&&L7*FtL&P~!9aMi_ig*H)z&vNP2`@S;$$MYU56yK z+bPY{4Q=pC3lcBL$AYoi6!orD^^ajyLKLyMw8?F%zZyPa7(SlT^OH}%Dvs&I&XOK* zOR^{bqX%nYFU!EX9!j-cIDKp->Mq<&MIrz>Qnuai>t^E$!~;1b&gTf_o@4c7POW)bcxZF#-4D_1@GE4VynD#Ld_pv$m@pbkw#Pc7v}C*Ijl7vD!NTxU29=p5@8cJ5aq?pK3#-+$htxjRvUStqZ zXhm=Zhb|mR;gJWKej)HX8n9p-eDyDy*fwa;KIb2r*m-%-^={CeamZ78$lG-2bvKdA@*=!i5MF%%{}Y`sjNh6U9a**P%32nT5gf~elCmr3i#4;VA{O3U}s1byak z{+un{kJX7qs{2v~hVCq380J)i@gnKobS0cYOzT2D5ci^x=N6!R_r- z@l=g|ZI5?AL~z9aY3y$NoM_@IZesk7*QXK>003=7#vPhAel)G=>O>X;CRdl$<&z@D(p~-lb-~F0?(HANr{-N;>yGmkhrR3F|$JZbzp1kc0QZBy$2Qlko>k z%}9J3CEVqV#aF?L^%RTrgyWI-O`Mq)_)NM4)R*4m-z=~ zrR^u(x|D-Gj3@ZUd;eQe*SEp?4+$v7K$o0*2MdzHjYWanad&e~HP3Thpxy^dZD#ZN z6VrqBT_dbZzk5J@GK>=m9JQD~Fi7X}xXX8$(eDK^%g~zd4XddUaNr25K0*5muhHyK zFn2@-Q48M>iTM@Wp~!FT{QHw9~9VoL`u!~v%dGI(#Z;$E?!C1 z&kgof5Vqm<42>g*#_3&UaYYC8{vbdw>I&=Mulzy&CQQVgc-Mk#`3Mht;r<@;Bt5Aq zv+UZJuGy{J?^~?JhN$)b1=v6*zwJ7+5FSDUOakJ-3t*rGbO5!0ZPQ8O0S|lQ+eY3C zedInq(_Eg<+o7?FAOXPj2nO5ZeW5M1fY5Mb<98yaWNPKSl;a{E;yb?Kb*|$ePUm@! z=k6io8=eX8Fbp57-S0!uRx38 z@d@RC?Bv1*g_qyVenPW8-P^9O)DG{uehBnD5HaoUj9U=MQ0!{Xv{H^F3Q)4^&hF06 zpd=1jwtnl;SnO5Lm2WRU)-49BTv@yZ1I9=|7LtNXL{`5pfCRB!TF zulB}Kr&~}E@QwVc|4$QP-y)&^An4u<$Lsu5!~2vU?bUDnUVix#O%Mb?q1@m5p-%hb z%P{5p>gGQ;=)eAePyYY`K;S@v1q~8xfTzJhh7BD)M5qwr#D`lBZ7C?_9We_45-y|| zQe;GsBTY7x@lVD{mMvYf4Dm0-OPV!blFG%#=1!hHef|U*ROnElDOVEpC=n^dk4qmm zb=nYWREATj7PR`a#UVp23c`8^OJLTk1Ib1;T2^hym^0VD9T)-bT)K7b-c_3x>DjV; zsrroyIIvQMDcT&a@E)4mqUc7MIR>quJ^JdPSmr@>Tc&TWjq(e(yYg(vk zlUogmD0t}||F8g$OGdsuS*2&Hmw5|4q4W1};>C?a1ic!yTGl|D|9lR8`PJwY5f=;) z?A;}^)2Vw$n*4ZA-{Wh-Xy(d@dG_ty+ZFE|{NUWo=a0URzkc8REVmYdjUbKMxuCoK z_&e~k-QL@&JO)q7#T8N>q_9E@cZyHC1pn&qv<;oAuBQ-p8nK}O)Ho!uufig!t`c3! z@Is0llo29LT*;+I9e3n$pcqB$&_lXjq>0EPgAB^Zf{r+(kPH-qr?D1?M6#zJdo+kf zEDKU0y(+c@GtBX>B(X~QKGcs&G}D|*$$?Hx(IDAqo3c$aFJ(kvD1#bI&pi8P%!xv^Tu2h5HwU#;nMU-NK12+Cq_kD zmDNP#zXm((koI*6=84RHO6Hf)PMhUNdqUz6LL@K5t4yMAZm&Rpp$jFc5B?E#RffegZyTR z@2b=;8}&m~U)^n0QAc2nLvAhzfnnZ3BX8DA-+kQV03IGtCpcKZDWgsiS>8BrW zlDPJqeg3J21cAUAWuQ9#*`S~aLI6Ld&PBb#7F$F|Uv$zF?Y&Xgb+z+-_%YonZbA|; zD2sQ7VL*5J3vJ&-*5?x$oP!GjDV{(=aE)hxWCPbQ1{lPU3~qD}2H>ED7sfD+|7Z*V z0NB$W_X>iFf0VF<;|o<4T+s{_q|b$58{kMx=RbDEuV*&2NdgFQ2qYZj7w^Et>Hhbw z03zpiYH`Fr_OZl&_+uZS`am_JF+72E;v7>0Km_Pf2>{3f8$SAn7yxj&foRSk-wU7D z#uXt=ywHs$i=nHAI5Qm5ua0jq5*7}z1_T&HBkmxA5O0{5BbMa@RzRc`uyG7403Za` zm_`Q(0t$0@5C999ha~_|i)#!d24MsM*0jd8J*iP#q`=V|RXM6ShGd2YdF7>2Q$$zN z@@z7bzz%z85U}(@Dz?1k98c29p9t=e++YF>lnJUQ+(Q>opu#cM5d#2}|G^)paKaa! zA&%~4j22J$gvU5XE+e#p6<}CpIsrw@U=9+Gz-*g4XE{VYszCraW6aKISVKbo%r1f> zg9%M&t!h?d9qNdN7zI*^Y|P^v%y`1JvK0<)jgwrgSVb$;xlu5&lPU0w=N;!MPy75Y z1BE!m5e{NEIth}WW$`G3LZ+ustb!Gw;%H8F6w|$dw5P&s-AmsIRNnnh3x`lcZE7cs z?fjIaXenf%W-6u^sA3g0&}mjL#M56AwWvZZ=~KTWKM@$>5MIgO{yNfCv6ic3Qx(%6 zR>23Y*7ZSLb*V_hs@J{Ru_YG4h(QAI!yq~ptWfo*sNfo=Agm$~|2Va4WXBZMw;gt@ zmc1-rMdBK?X5=0406|DK>sE3t7EA{a#47wCS=Jf{ulpP=eK5-*ue$Fg*EvYN#3EY1 z>L#(FGA)=|kkKq21L7&yTZ-b;JYYZ3;?j&^msn^Lno((V3M zP!;Y`7*?^0h-%oz{bUn}g{0#h_ckPYTtoj1a)H}rA!h4k|1Xk_=whjw(qtIT-i@V< z*c|&9K?)ABl8=0nT=I}1vJplfA#7!*aF{qS?$Ic0I%PJ8XTku~@|Jm=BoUAJy&^fP z8VGO@2Heh4W4^O*-|FO&!N95|Xmg^0V&+)Nvaf+=F_|4A0+g!sAhO|KE#nMms+f5= zXzr0*_n>G}^MuiLcJ!6!Oy^Cn7$SgW2m+Y;XHGv_(4{4G$%f$AR+pN*r|z|3C4Jyk zYiJ~#We6JfS0GJ$IKOY+RIbSd0ju`G*Vk?du$`S{ET5~}0GJg+2%w$9Hv8KIg!Yy| z-J{`Z6x;6>iMG$3uVE7#(hiYSgA1ZRVldm>#l{np{{gjb9{C}>AAonlmt5t0XSUuS ze)vFQH#>#|02n~D?YvE$ZY&XeM-9MeMHN2s(Q!O=!Cr2}y{++;t3O@uTc01?<8Et)09M5XQFgx%KX;S~yt~piSqTnJc!j@R?w@CT=pEh=WFJJ< z7@xf2pKW;xW8P$dSVbN0lTD(+v>_s;yiMslzzWM}W| z+N+xK#uh#iKg3{$SYXyCZ~9M&&l%&(CJU5FiHJSsPRz1*rV3#`Cw8^H_dK?~`F@InC~48kY;H}vDW z7o%E51h#SN~BOHnC+l(lz5dT^Q|2eQiHWNaIv%MB{!O)8vc@ejZ+bue3LY6Q? z%|OEn*@IR1gEpM9H!MOe%)K0>w}D6iL}0&5+Xxo$KQfFrEUb_}q>vH_FAX5XH~Iu_ zkOz6NhK~V&3ebggn1^I|frUFnL`*y`l*29@2p|)(A@j3WgvHfcz!!qO6zs$ox`R4! z0w<7#e4qjV*adPZgDk)`?V7qtx$B)vz|J{qjA*9D11ArvN4qtc&UrIzu^c^N6Artb3j&r@R z!6I5wyvnTPN~he)t^`Y~RLY>70NK%kqm+$yAcC+g%CBV0 zw{*+5%t|GQDpcSGWrBeeK*?|fotnC-mK2=`pcq;}2P&w^o6JdrC`l9Q1Uzue$Arwt zl+4Mb%*wRP%f!sg)XdG~%+B=8&jiiT6wT2jP03t@Lr4ThpiD+6Kv*cv*M!a3e9ca% zOKoU9z7(4nn6dB!%=C$d|6O26hXeqK)JgE+NuQL%>l`6wmP#O1dOTdMJl*I0oqHk$|j_AMDN0kp^Q(M@V2t zcSMPabhSD3PZ+#NHp#OO^dsxqM_de034;RTgg}Cz14`fmI;e(mKscyN$p*Bk0+>&* zp@lI}0xqBhe<%ZF9EWAB24{Q-c+^OFj7Js~k`^$l&MFA&dxuw8#EjHFf%*qjXb2Km zhfa9U3k91GNG%=M(68YIalnUjh=vg@MO{z_dQb)!c*YfVQLXF8F~p5<+ytEh z2suU7Dn{kg|CGf!l@9?t2(b84Id#>IV=`nY2Ye_8WO$k&B~{RoPgLC~RmId=O+Q71 z4mhYZd^AuiP0*X;&-Yl<3IQ)x5LICv)@V&RNM)ajv@>HB5fs^i859U2xE&jHR#tVh zZ&Wuz1)BxT>DkfIRl%bCWBoigbm4nB|CdP2|Y>#3OI;-Y^r%=*nk^YRZ>F$ z<5*SlSOf*onzh-bu)9U54-l|aa-GmhE_|igR$W<}2mrux zgxuiQcL)YBO;@0;*l{7+3IPJg(om#*p_!$|r~O!vod`*B0m-nNh>b<3r80|ErvnIt zRWMSqbs@6lN3(5OxLt|_Ffpsp9|L^b!rfYN=~^}=F1$@2z2!!}EnCQK2_Q>=sUQNz zKv%ViEUoLbza2vT(LpE(4Ahfsor}H-k%lUpjf{X`-m{4wfEIrXsume<){U)Do{w@ zuvy>uo81;|Uz#|oAnOhyD8S4eU;>`M{2kStlHUInmjLe8I%PTxK8O}rR zW`KmxDUMC%o*>?F9f&gSXCA0nx}yReW)>l5G8@w8jI4Y0;pR%Fzd7C=eqW1inL^y z_6a*KSEl-ff1PVs*6dq*iFMcobSj7qI0caa9O4;lfgl{iK^(qxixY+%KImW;=EH3XiGGRT8J+|Z zh~r5ffmojAc^-k-g?q4uF~AmSxSl8jfbHoXf>_KGs;jRJgs@$19%=6WRBH#G>5(7+ z6j6~2xMA$hZnj3_@okBISjB-rfqp1M145v|UZ4gNhzE+G392Au{0Aoxh^2`r5E2Ob zF77n4Vi!WKRhR|Q?Qa?RZ()n+3l_;@ei8)V2=FcKbv8Ro^oIx+h#0Vkkw~H?njR;D zA}LB#E5afz;-Xa0hk@9De;83Rs-n#)r4@G}xoU+8iSeDv?49oM|L2D8oyY)1@G=ni zA!3N)GB@)}Ug&`cg;3}RQ>gPgUxteji9<@HMQWr+ilj-ZB!R#rO`-#*5r{4b@leVd z$R;JQ=JNDuELO;oFt3pr-&TYMX9jNwdlZ1`-tkS>Zq!XNaEYdEiQ8_(A!X#pb8 zj$w%61s`zXJ@uE62H~s;fYMQ)6o@h~D1=fd0EmHPkOy-BZjz>`ZV7AA@p3R%_6pJT zr7iU@_H=`AYbm&$>jv;)CgGsX>`#mL(AhOsXoh^Q_n;U9|9ZY8TjuU0=5(1Bcx`Wq z14aYJ00ss3-E60LDmIB)$mCiu`I9&KYM%7;ae!lQqlO0x2q%aMC-^y!<7dD5eAjnI zJ_N9+FRaD)eK&OnABk=U0BJz_q(^#{mn<)51ega3f4EivZ~}R#`S88?M8}Xfam%EcRHJg!h=V6$Fd}--w9<t`c0nd7^|FJ`0jCR;l z&(`^b7I~H!f#4Ph6j*t?K3mdYJym(tu+x>+F9CXaF!0I0te72z#FZ5G-i$Ai{(SW&D$& z@FB#A4e&IGXz?P(i4`$&>{w8v$B-E*iYzISq)92k-n|=!#Ux0RG7rX_X%j%rn;{uG zv?)!OL0#2!673k`Ux=bgmonuDXjQ9bCz?{NYV|7CtPs;t0pMwy0ZQGj^30l3Yr?Z= z4XRyBu&rC1C_@tI#j@QYH3DGHjr*~$-?xC*|CY5m#vZj(r>NN*6WHd_q>m?Sjk1cB zD@~L)bMEZ1?<_Uet4fmbbT z(+je0*mybl>@l+Q=r%Q|TGcF<^z7QV-{clb#yT+ozL-nh^D1$y>8-A>+TJ~Fg%>cj zW9dr@p+hf!$Db{H@_R}d$DLNt5qKa(PqpI86bL%_;DM3k(+@NRjq;3n!EqKKQyebk z;fMVh#K0xQu=I-*0BCW@8VJk;Vo@;0D56yZ%A^1!rkDbW0uUNxppOscaam?T8hIpT zFnD1AL0~+Qp?WlGIGmK|RcYma3K4*Y|1c~ClSKdkv~b8FzP)%Qd|3u2<4iV|#KbrB zWRnd&-Y{V#kVtY@!YZnCr6-_)3Tlv>O|hxdp*AIYrkbtw7l0JNur$miE&{;78i#0c z)1v$}8ds+~sb$S)S%l1vdR#x$~tRE$|R)>uDRk0C6*haNmZyN1uJZP zQux9WF_>6j5Eh3JA_1qr8Y=CypJr8PNc3=FP#5#8DjBVx?Xk)q0DKTGy6GCk%elO` z`>wmZvPW%)^eQ!MNciT^9l$DwNS_*M<8nNjMlz}uua%{q>gw6jiJuB>UM_1 zDuUP|mBk%cZl-TXBy(i)|H*)X@CrOE!9oN=1gLSy7DSHRM0RyH&A`py3 z!Xqp0>0?rRa}kjS2tz1BY3y%+N|D1V0MQIrT)~7c)QUMcVGvH7 zLxC9_AC)wSJj#Fo7L!85@gNd_E#!p&H_Rap{o+BVLGOh&89|>!p@|eYv5Hg~g*|Su ziB0H&9;2|~139=R+=&Eh2?+oiB=`m9(5f|N3lpZ&=3F=m9wClAudh@c=E z{^-Y@cu|WI60#&i|0-82V+o;AE>4V&dZZ)cLV!!u2OgL}0C9+@21|8vjJV8YU}*Ue zV?09!^0*Tn#uB6^%90}{$e0Q=fxT*SGds%69UYBn%d1fGL@<+!){bxpLzroSa~!8u zzL^knbO8X*1OOAfHBCQu(<4e-#Ti`D3>fsYpq-It8OfN?W7hJWSqXsG+HnaZ3dU*@ z*ktbyUuAIa#3IX>qjYEHEvP*epIPS>Ei_ETt7tshUbTGp+d6(JUQ zh2tnlllUYcQ=1|yRt1~Ps(NGurbq@+W6(!%@iif@8iFmZ*V$@rf*bd^2RAmsNXl+7 zvN3h7Qivd_cf5iD4{?o76M#6$!uGHHqibjRKrX2AZM1|81wCki2RzV%9-#nZYhem1 zpO(z05UtNJvXC`}jHzHzD(p|gNf_2z=pVOu2slt-Ks^DMuR$ms44PpJ4;Yt_;!tft zHX#n^LbA7J9jr+%V3#%C^tPuSR_PPi90ayRZy} zJb{E5ewtcF!*S!ZEOcjbnIW zwLBKzmIM3Ro3P*)EO`YnN0KG6k&Upq)-_rff@U>~@*Laxw2%=(WFsS)zNhZ&KXpLd z{{XtW+oB||ijR$JGkZh|U22DR!&{Jn9fER|E;GExduxI?;vf6C_dooxj~*e!AJ+)Q z3jo#L&YtuHD{Ns?K+p@A)g@rwCQzCq9)b@-Vva3W2!Ad>m2 z8eiMI&1Hp^TVd8#P{?`(zGNsn6#${#CR6Mp40FGu7Y`@UDf=Pxp^qaK++IprL2l^( zo?M8Su+Ig+Nf2Tmnz~9CcTpM%YIO~quTWft2DaT4A_yZM@py+YKK^s(Y=RuJ=$tIb z;R#c$W6DiQy0Dl2Zj+0|0s{s%=EO8P7B_vj90fPDJJxl+e%1pArwSu3{f;lM|2;a< zSY$yc5e)!r!W&e~#3*2cJe1r978o|)+RW{MX10(IK~L%LnIKy6Z}KOEW{rYi|AF? zEaqL)5dfoMLJHml1t7x6HKHH}qJYFALXen2oY*9G76epB3FscqDaEB}SSNZ0B-8^h z7$YcP$VD*0KfGKS`~wLT#5g?HK}%A-L>Bt^F4L{=n5UL-~m zq!JM0K}Z>uS=l~?n5)qsaW%y{`~x3Nqi1A;YTc6;l!rwa05kNVCE$ZWTtoXA1S(+K zrFFt`1*K39B~ccoQ642yCZ$p?B~vz~Q$8hBMx|8Z!6W#ZJ7mICCS@WX!Xjj)SAHc} zhNW1JOMXT@{NOz?0g73~E{H=<++o?nxUgQZe%`cq+&88V>V_%)+1y_MafhC*+C_uyj=t4QfTq?F@E52evJRz6~<4bWNK}aX`Rp(9kUleMmfBvVu-Gs!Y z8O0^zXwhJN*+RuBg+Bbld7>v}41g)jgFpC#J#>$7t^*msfQjl60PMmz=wUVV;Y08z zjb$f-I;VmLsINsIRk&UR94HjZXn)cuQQ%$B4V};x|J@ow+{|^G9*_$`V1Oo`qK0xt z1W*AOSQ|w64BAx#;D#|+(We8+ucFj z&0XC=$ahYa4$x**_`^SdL6klXj2c**x+$4{V07LnffnfCttn1zXPMTKm_o$m8HDC> zp65MCo=VjMd{{wD0Tr>~Km19ce$1dMgrh#{q4t-J4ro;%K&HH2s-hF5B5D`jgzz0> z@g1LoY^qc_89{`WO6i0R{sWkns>PgYq7^Ek)@ryBgasT6nx?6<6x*y`E06Xl{oDlm z8N~a=AD$*@x4jZUu$nCt1qxgmvm)!ZvLKK~|EkF$fL&0hRkVPZ8B9evYjZ*;oGQcw zRv<52U zsBxv*0RVsktPmUM1T_3ZaL#SG)NR*#|E<+J3L3BkCSXNw&Fs30uD%NH$j*dI`X&Ix zq~ea&Kj8pDXhI!W=}dgXKkS0#(k;>2V&IOcCuKs*yuvOng;=!{;0kTfYVQ0^>Ohfjlj#l320aMh&KX^j!q6_B!Z0}xNU`RoI^umlag(hLpvX-v*4sO3D1aGP?a7J%u zsV!4nnto<)t86c=qHp~L#`FEcvRK6svB)82F4&5!0fP+lDujBnr+dOD{PGo_2*Lvp z#1xRiu$sgNTpDuPudLwjtmZHB&cp>s$}q41R=kn%Qf>F{ukv=_O>n4(f~bh1EbtA$ zs{ldlM%7HftzB~PtavcZ8fple{{#XY%P?p{EtW4Qo$m?*;t-d_6HaNB8lbp7+({7x z44jS;%mgU>15WyI2k-8TJ~0cg1!7UB)dlb{32_VGUkL7)bBuy{0RRf0d9OQ$w-d*va$Mp?Ew>RXZRS9 zMH@j-0zNFjc#H}c{DWN4|H3hFf-WNiGZch1;O;P2@xy%<1q+lBj9*AZ>@yEaG~X>1 zq6HC{NH2tmzPR3AeDXKT9vO>D0#`+wCEh`J0y+@H2c!ckM8F2zLN}l@0F*&EgaAAj z1UZl+0Hne;Km;*Ml^Ig-3hkap!~j4Cbf640Cd;B*T);~BFZV7*7IHHvGh!Pf9VyQQ zr+M1e5kv}%!wg#iI0&6Lhz1>#gJYaDLF9ua6vQXgP&q~%L!j-$Rbp+P&eE1dDExyy z;WVJ=G&QT6RuI6k@E-^(g}t^L?;iDY@^#iFwMoc;vk^p7hrl&F!$xetH5daJh(R)N zgB~eE`)M@*aJ5&1|20oyDOr1)19&PUpmj5B_CtunKU9cYzcpZ^Y7jSTTtCFqZER2z zMaTZ_B}X(*?{r7tuSL|`z3oH3?VGt&Lo|3AL3F}71W*LfLnQ#fI`now*jpz6KuQ+` zOCy9~hQL^NBCr}9S~EgO7{I0V=4tB*T-)~aX+;*W1nV7dQS_`7`ZafkvZQjx2e4er z9mC6ofHh1*2N(n>n8Qjgz&vy{6tJ8r$b%JxqdXTxHQ2L4ytGuwukM|WGIPW_|HGP% zHwCK&JV7t}Oh`e?d@iJS#B7f{uwy)!3;pu`7Q=Vj0X)SjzzV~nHNru} z3tU>v&HRB}e58kbN%-^{jqj_MgnNTL(HHc(%Y=#_h{>;%(lhC%)3id+!aw8#)ziGl z?;X~Qgbxiv2@SH&AAQ;`ea1Wh%NLhI41k}`aNJk@zO(n(`z}$W z|M%ooxkrcqMy2oH2cyAXMA;*$oqJmXF8vU&0iPf1L6muJK0bn2{m5UvO@KJh2R%lZ zyBcu4sVlqZPd*e!{@LDT+W!Ft%=-l+L^%9IHn_fnz&_n~zC{GUu>ixP6T3+?iz37k z=gU6#cfXhq{^)y~Wh}iQKtO2W`a@jW7cl?p13$Ufz1Z7?6~eadTSQ*}-}cA8{_p?# zrpwu{6hLTDwTfUAO|B3&TL6GzLx!9Fm2)_eVnvG=F=o`bkz+@XA3=r`Ig+GC8UJLI z?AQQL1C=iUuyhHNq)eIsq_lf?>7z}M64o5jLeuBXkVTF5Y?)LfQl=SCrhGb;|0=@} z|3XyNx|J(NKm=F)VS*6h6^sA=J?XlZZCkf*F-GO;6fRx2c10op_Rbdpr87TjIkZLs z(WP)3;$^FN@!_{}5l6OoHLGOHmn}vCD@a2wvZN}~LW`MnY15Y>Yh}E4^<2j)F})*3 z1Y~Q9NDdilanrWy*L8mb2kbWW>9>@PCwB{BU_nx3b5X2-mX>ns*Rhi7^<7EFwUSL)7q#Hw;+=u`3CaBJm{#6{IP@6j}60GlEn>|Dl=BG^v82 z>Hevu#T|Ks3&j#e95KkPOl&ANVpzD4K8&z9gb)#cTr$2Py}PW)l78$lq!qR7vLOfr z0ZR^B$ijsbMi>(9p9;Ke(@mPP{7}j%=M1qLNhjgh)*!H`3ch>*&vu6(IbLkDFl z&NnmSl2IP}BZ!q*$ZCcZQVh82A5$Lf)YFX?h3Qb0My)B)iYV+Q06wYAK)s;^z0);W zi9Gc|TW<>WQ->VgHNhdkTBVc#V6 zwmom3y_ZQ)#U=UqZo^{{kL8OR}xWLU!wR z-}$B;*RX?=y7$v_>%A`0Ran6VI#Oo&r<;g5_R?V`#bwywkqG#OuT}BYsD(lRMOd;@ zuMHWok2{69W8;7YD;8p%(dWRMfo75B+7uSGXlO-l=#qEZu{LFlfI4Iglt+H~=zy=r zI%zmj3Yu4}yuQwXbyqoMMugBQ$C$9$)^F&)WVU*17Kqsi(K-XrmN0&|{VY-aZhTK){kmBcZQAG)}dS#lUet}u@yq2qxGkeEaz zE|G~%bm9}2SOYxN0E$(#;uVu9MJi%3iLZFaFnqv8D{9e++9JdbTKGcn;I4kVLm)*y z!3}xH!y0rj7ubY|7$5|zc+$8ODIS+cK|Y0u8!@67{}G8uGA5FdRa_(&ukbH4G}4KW zRAQ41frK2Sk#B8;Vb-4J#*5sc4o+}_Eb>8xUEy$$Oi=*Y*pZGuUg~G9wB_L5NR>lU zl9x=hWG{L7ODmep7r>0-6q#rP_i4cdn{;6(*(g6y#_WI`QOCRv5(kQ&*gF?%UYbSe^=T+GBf;NgXJBJr0r2#OkJ&`eIcOqw&io9>A74=99ypcAl& z0xE$IRc5m?@ugAu;MqrWtx4Up(eHNGW= zMDyoA?S~e$pn@V?n8!ZWQHMJ=)S^>K0z0HZ|BzOEGmt$sDn&4g5si9Oj38y|6P>z5 zFA9SOC2c1XF^PmEsuY_2^yDXBN=|_iGz12nNCcSh1zMnEp`K#pQ9-hSdHe$%lA5I^ zu3!MT?iBz@y~t9Z`q8TfR)Xcl_e1i=@E{@d?>|-YTr2oGfM6qAO{v zjiIK62{O<^i9mow560yzYAd2z*EX@W)2*)g+;N54wo_Y(K&ft@DcQ>YHktv=r9)^j z1|@KT7XB!MW_jw|kcTsi@?EkELgIPh_fXuKD`{1u59(6S7M+#pyc@UT(+I}rdAn4Sh^@oNX{#CH-S zjN7dN5**t^2v^Ok4shbFo5L}WDi5OXo?-OVis4|wNdp!-4wfE zJlJ4`TX5ozrR8ImPLqC??cHXbj1dK(r5gKf2!08o-!zXC$_Ug(2{_%JZT^}0)O~@Xm0$Q#?5fhYn&f=^yL+%{lJQLQbh}Dyx({Knye3#JS zjj)*SLS`A(@Vqx`w0xa_7I{=e|H)wCL#4NQX#ix}x-NdP37jfh+O8G}e|qc_!5k$C zH>S6~t?;5akB-a1f2MR2*hy1#E+Je+IudD3q7lYJ%lo0Ij~HO2)&#kAzw`L-BNAM|Bv)cb-`S2D2Uc5&fWyEa>~LkHdcyA3imvrzakw%8 zE%YFPM)Z*10)SkIA~*TT#XV&gBlsO8C2Urcu1`}N8qs5JHZ{$RKWV2K3TP>Z2R2fI zVCjJ9K{Wc&TMYAGt8>OH|7R+W*ArEC15V;rhj(zHJ@2ib*Z`hDODH_D;*hK z+BdD`fzx0Z@5u5~ZJ-`6%U$N}ra80k-W8nRN9Pr-KsV6xiI3zVzX~Y4;q#spaO*kh znl^B3hB0WS&R|1ps4C^B{_sSn`s!r{a^dza-xSCLEu#R5*uesX)9df>M^C(smw08z z6IL*zPJ6?1Kl8ftKJ!CNeZ)F1&MwIG4kGyqLH@9On{tEemLEKm<^&JQz@Du56>gfNFH;2F?j9X=o_ z@GJcmkquRlCRkAM(C!A2NDd>=*aYtWx{3$)uMel96R+bF3kVAC0WG9qS&U-RI3pE% zWDJ;r3>~2%{{|ox%)uU_!3m&Z6=9+kp%3wpNfJE@-PElXu`v5AuM6L86L--Xo5dHC zM*(g@rYM0bzCsR=kw@r279imtnvo$!VIA;*3z#7s*yJJ_aoiq}^{7Y|r|_Pvu;juK z|G2Q~?2ZGq&I2oI0JZ@w)M4YO0u2FS9<>A?8Dap;!T11R1n!{{;sPC20vq2C2bHb{ zxN)9l;G|f~67vwI$T0)EZ!37wI@IxS8h{dH$`rV5Dl{NWOw1#91SA1~=e(dHsKLGj zQYA}*B^mG)wFn_MN-zq+!Jx_}#c>BA@*&643jvWLw@D220WElen+8uQmogtgOd|mx z8IXY@|0aN}x=slipfCOMF99X_as==|2x=fP6>~8evoRg>F(H#NdjJo5ATllU zGBHyzCo_`tBr`p;2Ivn9E^{&~GctK#2snT+RdY21vjgy;16VUQWm7d>6E}%sItQ>Y6GA_rqp6Bf+r9R5H1yjDd(~w?2;l-L8jyd53n;kwR1bU zvpc=>JHazN#dAE#vpmi7J7o(P&T~A?;7`(EJ>fGx<#Rsivp((fKJha@;d2nbuwH&L zXz0Kn(83$=jV%;lxrV?wQ-mp<5-O$AA@Y)-_7XU8(=ZY9GcoitNi#z^bTlhj;uID1IrC8@ z0S^E|;3QKLN3Rj!u(BXIP1rVy%Q$2qztSb8&LMLV7qfKY&T^baK&H0g=iox@R6zrR z^gcYm3%uYTLct4?008!}AD00jlawp0@(G9rOUp4Qby6a4C=d&1 z0qE-=@Ij{}BOcE*JIKH~|6y&O(H!n!8mm!BU*b;TFi)S#i-2LHw8i?k2=@fFPzhBN zv+hvQvVaEQ6J&}cErTN?)mesfBs_JU-VmLn@9~U@5}PVeZ?P-~byd%iQ<+6a|CvPw z$nYQTVGl#%C|4mVZ`EFMRU~#5oqE-nV6O+(DKrxaRf{zuku_C+Fk5Q|Q6a|wWI?8Q zp|mceKh*GA-DDtN^5__^>8zBCB#@(sRlLkqOOKUH`!A22fcXBw9<0DPma{qSwN3C9 z&p>sf-f0*fp{@7!x+sJa=YYdU(n?C;uYSI_6{Kt{*;}p^b&CrboFH?Z;o`0!Wir;bt%FV(19U7 zARSO40yf|lx`7xQq8fAr0LY<80U#B&0WZnwBziY!$Y3r1VH)-WQjJ$jkQWk3&V1m( z2i~w$y|R%!m+D5gfgM=$w3j9-fg9MwdmSPL#z7Vu!V18lANs)?|K4;WSa+fFfoB=w z6V8D;DfNCk#sft0?-0aR|F=g1*dR$xwqOAk8%Z!S378gG_l#9lMb{{L5~) zt>PMgz#68Z0~`Vr%)!kTU>;1E4CVn8|0d#g*LQa(<8YZ}0AL^( z|DhTRF-3qS5Qa{aQ-qYW@x>hQ(^A=AS%#Hc*%rHYOJ`Y~@lILS!h3s}8<+qF=-Kq1 z;2v}V3aH>1)?wqYSQh9R2FzG3L*WTfAs-6&nOT@wVqhH5LLU;DMHV1Tl#iPg#G6|( z;6(Kfu?Pv=XA3$unC=*e*I9`5IBeayE4+77DOCv=q715G9n>Kj#DF1;fl~RGAt>P+ z@F8d$1)4qO8D&a~wd8Rv8bL7nDqn10A8*sVF}HYiq_yv))0v$iIHijVXqaFf&;lQx zvP(!z5Fp^Fkvf76iAlBbjo0a7zatox=S+oJ``XVWJ(v* zw?}F%3dnjtk~*$`Z7(nZ>7rIj*C2Y&xgllQYbm?3c`~oHWUsNK0Y2*=)S<1~g!DSH zu%|<{g6A6yl4(Nnu*vO zdfgbE?b^EKd%n2_yVrH0wS*4(0WHG8jCTc0|El%B0i41?f^s8!x|rIR#ErcbA%Qbm zvTHkZgV>~R`(Ss41Uma4-Vt5s6~vQ+yt%c&#fYs@T;eFwg{L{1D$=hTA3XI)_SCrxZH~1SEVqgkTItHXe zLR6X|6a+*>L_oTvR8k3np}VBJk?!v9?k-6QK~S36`F?-r**#~^?ml~+GylQdbLPH2 zpZEK9&#oLAMeMF&DiV(&c!XXvi3mJ#SRQ`8_d;*y2SbOfE;iwmq{Xl=LOOxTvf4j=T&Dis zDylC_q^o&WcgVESMY?&iI3?C?C3AYKb3OIA+I@2(u}pL&ux#xW!jLd=>fndyF}36l zU*q(0*BHs~U*sOAF)1g5dap3PGbsxE*}0?*cUAVc2ZU1pOfd~_-2Ij%&)jaeUZl0X zZw-2K)mHV4gQs@nR_FLD!{KDhPGL(KTx!==|Mliw>u$?$)9;qDma>rba=)}CeaxTf zm5XrwGhU;6W!U~~L+bC33X9$E%UoXm)IHa?P2Sl%isIxzxL@P6T>qdweeCh?XX*y9 zLCwykn;LqG9p85NLTIrxu|Q^5AYAr_L|P!LC-lEGv0!!&Qy~TyiU<_U8HnL|-|&s| zXIe-cOk{1{kogCeCU(8L0Y`s;ia++EdAzVsUzDmqMla(aw=Z!71>PZ%P-Q6niabK}2V7z3d`P(~5MAd-YYP$~!?a@U|$;;$- zv|>*p|DL>NJY30G59}Uedi>2m_$S}j$<}ZWy<2U{sUOwjJYD9^?qK3j00WKC6lySOteY2skJ()1F z$1YtP36=~5$u?Fk;13E$F3)foq7=M7q`DmSe@Jt`>t|;`!-(_vegobgXcCzw5~9^# zb0)-y81BWyebnM&i1#s6oJ=N$rYni4bS1n_%uaQgac9dIuq-5TzM3F*x-gV4u2~7P zDrqYKj8W!5F^#u}B#_X3Y+JVTqd~gt1M`$=!9XW2!M607X9BkHC?w zqpcf=$lpw*B@6M)7(7ZWYhbZr{4k{Sx%uBp@aLAR1u;Sf`vVf2mT^*Jzc)cVM*bB; zlE18t#}u#0s$;YVu>(}A#@WWh>fRTP+chM1&)fD$?fSV|7S)CEI|d#Ba0D6!_@J-O>Ee$F>}m*>*!3y*GcRuUl|N z#b$Fzdz*y$nocW+uR!HWvW2>5u^$_uRl08;+}chlSfvkevCa+G8rm1CSI>CuC;eT! z>G-1}78L*b_nc^)+uPCHx3uSaR<#Zy+n>|^e(iU}oYM;;3;S?f_NW<)HP-w}B|onh zHG1~(`!6ijb%e|6#cWEEG+*X4U+X!)Pw~I0-`m|TADHanlbShZ&L3%5FM&(S(*)7| z84`||`~17r|N0G|GG*$OZ*<_=P$VSVl3 zPUaGSo~Lb0u8TicNJyM&sEkfr*G}dyKFu*<2=7YXkRB|;f`zki`=sG*q+JYWC{dw- zawhpr1+tjF3bF=k(ttV`v$?-8P6Pi3{wd~pukTNW1#G@D()^^He)GH~#Wsv9$cy10 z5HAIKjTe1jLjTlGUYtNV{4x=b@l733dMK1M0NBJY1Fv1HeWDL?kLba!Q#eU zhAf9q`cNZ1y*OW871_d_f65{#5w96UF%HcCns%BqEe0gjCKDO&Kj+4C>DF|qj6l_I zDKZ3*#RtjdJ{sP#b*FwDU=}SbO|*d@USFG{W|Kv>mnXlU(;Jalk#>>DEWUzP`-EK) zfAi5o*fD?1_WP;Bj*zja??NWoy-F5oI$X^|`KbV^zj?)j?9I`N!_W91>jzwSw}2Ft zv?!v}-!=S_uB8!b8-V^$o!ry1&q9mudcq4;eV?6+Y`s!UfO>yD(n*x(t;};SjW<=tYtg8Nd(E-V>3i;tg>^t!6@GoxB zL$swj{Ka&WWq0Y1x4cUfS2P`h!)2H{))27QMGum=yrDkk;q)<*uV$MRt^z7CGmgF2 z=&n(a@$!=^X}?ZQMoqnT@n?O9LbhLaaeRoe5|5vC`i<+gOih2yo#U`VCSP^vp#QQX|sJNQ{A{}jPc1a9!3w)SZnTVE@_CgzAzKc6yY)^C!N6SHwe z__d5dGp5-eB$iSj=pk`gsB2 zp23qx^EnkGj?Ec7dy4jp4$W+}t-9O7u&F9gq8$Ur2q^@;rgA&!clmPrHbO6Exf6#io4lm8x@;)tIxKj9pOJnpG)o!K3{^i?d=P#NM)4le zGriU+R(zTIb*@$Kz__$*zWMfYiPHU)lhlrG0??Ugbc+rdoxQiGcm5cj@~3&}$u^&q zW-edxX+x=GfegHCm9X_}f?KlX&Z4^S4ei!o@l8mIzQFvbWWxkp{HPf2fpf~h8av&> zSl`+(xfmQ%qJBG5xQuZeI#(F`Ao9!Ks)~?I@SJgq(gUhMmyU#;+dvHvq;p^SS_z+Z z{E)kn=bP&yTCa715L)5JtM0x-6FE5?%zlLRd1cG|huu^!BiTR3{UqQq>TNy$LE`-B zx7;1Kf8X`qJ#e4eb|K7jU^VyZu=hSZb?4pnd1MD|h(Hji!mllt5T5zP3tQx>KZAj>%5e5k8ei>|R z44=3if7%AVY2ZtY73yu^OR9t~CVgIU1m2PU$J-<}gbdmEI!4Or#5;Wkf-*RQvJ`@H z%!9%Wf^v5;PDfAtF!Jtl3SM(;A3oK&%g?DQyJP%M8KMk zLFy5ZZ6pPg0jw8=AEOFSjX)Tc!LtDTiU@ce4k<)9aMg)I09zfHj;OMMLIiLg;QqH0 za4qaNQTPc*_^Cqp5fxtL1mR^~xZANDHk67XiooHFz`=LgHS z;gNDil5v8ZkRbBFNb3AZ+Wts-tw_qfNZB@=zY5=3Im7AEg!BgAx%cSPMU)6|Fo`in2$iH~Um0mtB92pq69$w~yGFC7yI zHiR}JNLPr$-tUoZD1@mxhmm*^)1Jap(1afXV=eMyt@>j>?!}se34POv2w%iGTEyYM zfP@^!y7tGp?ZtV3<2^a!y(a!7n?E`rDq6n;E0Bb>4^L?C^Ryxf|NY6FQ(j?D#j@g92vNq7j}>r^(c@~pbWPa zoZRXR5>N$oTO{`eCimwj4+bWOwU*M@jrwXAP`&`_bfB0f|5!&ofrzTE&t1F zs`7h3zCfUJzq)?SWO$u(FEU4az|UknN8{Jm*dE&dGzJ^w{#V!pfMc9#1oSQekzxZQ zh(M5{;4uJ@&Y75Pk(if&C`gFG-Whl+lBe^-E^MHNs-EHXe(!>E^n)lO26Dm{@;F`G zxd%i-7RVS4@KY@D=WHN#q_{KuQ2H`Nx&a1uTMnG6X1uhZs6fU5s2JkcP?$EUmttN$ zS1yYpnrES~B`Cj%rbysNzMeor)&Nu)@sPhP_mvI20l-(cf$Ssj0DjzU1Bf~n+(d=` z2i!yuWBYy=sq*Lw3U{u)UL|9FzR7(g}P z9GMw(0lioYhzKYFyHcrhJ@Ar3C5ZZC^o@Pj8g91|B+a+D_i zC_&nnQwLW(SolWH9lSYSMqZvnMp{WKP$_g>0n0$&*;a54R+g$28T=|Yq^y!5srap3 zm7rarJXfjI=pfKju6I=xNrS0|iB(w$SM$48K5?ynb5)sFQK_6%K`U0lrd_S^zUH%2 z)$n9B+_%tRzlMyd<^!$k`@(8t+ENSdqSGLi?W-C$F;d&$+I#yI4)1F{gMFA6GxfS_ z-3RN08*4O`>JYCh;R5xr*Y()8(&(i6c-s2J#d_k%%FC1L(85CWeu?w-H=e@G0IRy% z_^JcJhHRz0+`@)9(Yi0R6}8;80Vj2~WQ`S#*;RuL)r%!R8Y>zW8=n4c*!|Pkwx7`v z+|)%<-l^0)&fV-V(`Yl%G{T+q;uvm##9QZX`Ki>hW!17n+oCuIRz$ZP?zjAQZTU6W za;(()_kGJBtJX`a){8<+>+N;R&3-G+x7K~`Hhl3Gz`6}Tqz(Jf863k&EJYt6$sfqH z-?wh33~8q>YNs7)r$1osX0|A6s`m z4e1mq>J%I5lsM>=f^RC%y{qvCwI?8tOUT$Lhr0q+GqflRyUO*SW@kAU`h8 zQv2uiUQgu?G*6%JLA#GNmL_fwDC!HZue_xJ3tZK!Jy=#Q%F z|42IUL0};J2GcLA$v|1t01xRPpgLG1KFH%V$Xhave7iW zc{A)IFtV&OvYR-PJuzbQXXLnP;t|hSzec$0P!3W zzEcKy)kbS49PLAj*Bb%**9O%`Q4u3aHVokFHpE>Tl*Vn4tz&pK7{H4l-Zp@b^K*U7 znBdV(f}%*4Q1C4S$h74o_wod^oCLG>SQd32u)n?C&uK@)!yjS09!PO-X8fXAm^(N7agPiuruleB}EY~VXcUodG|fWpj!k2A`L zQ>whvAKj+4pnyA3fR{pmU%;$$@ze(>U~xDL5dcQ{r@)b*QC0X3io_WL=+n;_f21^R zo-$vawQ5F0O3dq`A)5y9Wt*ua=!_A)ARm?YYf&m(X#{~M;$c%T^)e+364nF|D540J zM5uBjV2hCuNce+UJ$DnJY(=XHxgXR0Ks0P!`7 z&}Dt4zj=vIV)d`vYJKtQ&EYD*K)huDR&K+0;?EkT3Y|2kgu+%4Dy#oOR{_=a+uK#Z zAfzuZWXOCF`7m@@o08>j?T_0Ac?%)~IbV%MxDil26yYu^9Z+2(OkE?9+~_@AJE33a zNL>W4|BPA&*P;lN%l_kdgCjSIO4g8gnE=W+P?O3|n$q_qO1gjXn>5L3B<)Ze32`K( z7ey5%0c=MEJg|W~SyJv4BVdqrN81$vRhT*wc97y~r?T_q2!ui5zj1;+Q3+7A$e83$ z)NP(5_JoY4Q--7>9AQ8>17^=eat|6At@Hx-uPOm_Jo*(Fcx^$M4g)e(etlQj`|@#5 z9!!}(60HJ`Dc7c~`m`Srwokl{zXjk$y(GLv=A@OuUe)it*~3mFcQTH4dp`Yol6o+B zG(nOP^znY zOgs+WZ(F;D0k?V?Enz1#tq8i`C%{;C(in6r0%DW#<8t7~M}ZS={ga2E6ZuOKf|%&| z{DkDa1ZSE=@m0*UWa%HC&nI0HXW((1<+b&w6yk++gt*8tE8`Cisg2i+XO#MX0h_;C zm_uS)NEZ=c00-DtAL?m^8NQ%8!P)U?PrKvHaBT4ku!2im?Utf{jrNi$Gw%r8g zjgH|c-Tl6FN+Nxn^ajdt3F0vuGEznl0-KA#v;ZhStRIC-iu4~d$T&TQub`I5%b>ne zf512}Gd)5K|3k<1%Yf1gFw<4`=PL~Q3VZ@C7`*}u5MQoA9gqa$YtUEVY&cCu9p=yjIIZCe_m(dIC!nWR1ZAEs=rvJ_G6as5%? zZt64Uww3YbR~mu{Q>+X_tUbp;YVI)pUo>$5DSgicI{{O%71`rY>UB!VkT53J0pVWX zwW{~bZ$*dRLDzY$xJ}uLhm%CUDo+3Vy!xn$NM4v4yYh|?REOXqPs2gdoXbZ9!8uowrxle5h)5V2wtXA_&c(gheYE&#wfy?*n9Vc~OqL zrx8eioJLxX?4=wjTICKWFx_69^fR^3Kv`iEEhXLwKZBC`Zr43AkzT+{rD(H{CC+3* ziY^Ug&`YY+l+$s3l|X=2uaZ^(;~A?X`e>%D1bY#Kpf%<537se;*GMEQ6E!$9QWnP* z)P}Yrn6LqK2W)X)dr6jUsBxEx^bo@$Z3ENaOHT8ryh706(_vuFv~6@n0MU9XFC}DD z`jcEVKi56}>P$NA)bz7=29?ay>gxCHm@9nQ^8Cqx_%m!}TyU;0cXI4kwd07$e^G!Vk&z{E`_g5dT8n%}k!@!F(+i55r+nQ!vQ@U>@;0Mzl6R*;=48A@;gMB*M%l!(Ksxzf??T9ozxc#Mu zVKfE|fPDU5iA;g~ql;H=J?KfyowOfFlpk$w_4b0tNg9}gdtCk0=je+Jw>=0)3OMzM z{E-ebzEEWHk|m<9@C>&pdnG|LltzTJCXHB#!1%DqWf1Fj2RmlVQp@53lm)io&&U1! z=vatgvVE=esrrgJb_>8vd*M3x+#*DWY@+bne2yYe>CaAN59GhBXu!+e7`b!0c=W5@hvQ1cd zonI)MsYNAiny^b;zEJg3i_T&(<$UR^sGh49Q)pt!t$V4c*`pR)nQhAZ(OF4nTP?0} z)0EHcQpteeO?)SdnLwzsvI*Opgh3OtM-TduAD+KSoXj?R>>Eh@lnF#|uhQ&k^W{q$ zzemw?_dbXWJF7V4R*Df&`3fJDhbkaJPtP$CJ#0;&z)x!rJ`%5YVd7)%3BS&y`Pb%0 z-i8i!7Vp#`-S3fT$`EjTuAWJrV=nk|94gB1Nq&w_$7XK}6{C$`=3AeMuWCG2@p5W(9#S=It>c2qbIE}HVW2z6tuL&z$^ zhhkZiNQ4x3%)`M88H1dyL4m^Vtt+TMW3|#6cF|DOHe;|#k(U)Rap;7S8MoSO;Z zmn>Zcjh=f_Z72lmd;$3{08M!J8eX&Vlg`}K+L-=YQ_64MQ#qZ79EJPNd1AW6uDej? z-<4WNci=<44Y^RgW4MxfESTBby2VQOT6?Z%8;|$B!W-;DN}h%_Q*IfRzN~BdIIN@! z#Mx_R?5eZL_O6~b(pLq$_o{l(l~rYf%i4DmPO6ZTtuiO4NNyD9?8JnBuanD0iwM2` zyoe#g2A5Lwb^BJ&yOvYO13+dy^jq>zYU2oQ;oZwX4+Cf#^1w)jEh5D6=4YDQV?K-h zs!7TMZ<>ho&%W3%Q*WXd9o4ptzr>9p@C_HDjHR6k@Qv>M(CjX0ekO8+6ZWRaw);`; z2`?V*{}0mh7JDu+H}<^1Q%8p66J`6Z3Z;^XK^b z&lZ-Lx;tIPVxCyZ^Xz|No;N2uSj-bEd0rlE-~OIGIsX0o82kDC`{?NE;OF(u=H0K} z>#g>~!^2;{e*F*TxxKSHFLN*wY9bNbMq(mtpEIZyE=NinunPly_?R#43!)X zeaB3of39z={uk|BURn7M+PSbeKR-V^H@CIWzdqB1r8}o)W~Qg6v0&%Q=-lR5^Z5Aq z@bECEziMwF>a;&%yC>wXrS7)p!>=yiU!6X?-M%LsE;se|nC9nqHG(4pz4Prqwi@i0 zn_b3hvp4F$EY#Ta_V#skb+xy*x3;!6V^3XEO-*f8Rn^~$=Mxpq6BS=;DypZ-zl@cC z+bs(Fmli!z_HDHE%V>$?P_g4s!KZ-&+kt$SfqWZGu`H&T3X=!Mo}Kb7!hWN2*0vs%b+~U`LW!XM$;WoJmWZ zNn5;b8TJ%ZV8PF#qN2RKyxg4J%#5tGw6q_I1t}>hSlAO2;(+mkEeA_sf&h#M4weeO z^#JN3t?T_z-6299etfYpv5DcSF@9NbzVT=FTL1K4*4POa=yB%0&_Uj7~)9`4>Q9^d?(o!!2Cag}u~!E&I&?p4BWHSYFawzdwRKYzAzNU^te z2sMiRVCAG?pJi-ptgo-HqobpxrFEtx8?Tae^@Q(+4T+(mz(64v^3 zUcA7%pE5Es|1m$s#YIF!{s;Wz1nYQQznss24P9htvCa}c~e3w2jq5wd2T*if>{Bz8E()0z?5WrF0IUzvvIAI)Cvg^ zRZ%^9?=5Au6$Ju83rN9kX2?U)p8y|{X)ilk!*VYtn(M@eEdI-{y&vh81DtvBE&M3! zZ)|Y|1x~4Rzk-xkFtuF9?!;YQBz2i5qtu~n>KvgZMBd7!T@+SD{*RtF$Pj#bvY11_ zYrb|+HDw1bu9`M0!zJTOzbf!p^`hNR`MFJ960xK4&PuvB+5T5K-Yu~abqDAXZqvnf zVQEMoI2s`1R)2>A(;PjuX@B>Tgx$E(<$Xy#yp!0l6Si|sNhU6hj=($Gttf3`q-YD_ zPd%{u)6b#Lnh8=cLGrhgGBmv-P*4D9yCFZ6vPT@B^E?a@XFq@Ut_hh9mU{GUC^f7d zmh@**63>xHOE}yrd}uZ@Zx{nujtQ3E9tUYgtDNAX(GOitf(;;9RHVlM zxjDAw0FZxV_qSbT*PHegzqeQ&4wSWsi7^qO@Tkp@fN2ev5zZ69c6<`Ze8bEjQnW(y z&z1x!?0KJV4G^mFI6%V(?wZS_n|b2uMx^W0_0a)Pe_3%M(VOuyzxh`K{NM|Ac@lm@mv>DXtBmpoHR&&!4ZZ~d7F!3HM8 z8ZdxjBK%QX<#2PrAiet=Av=Lxh&e72XE{Lr3Chq5nhHyzQr=jLt{V@-HffT~tvt1o zY59>*DQlJ&$3Ndc5ldzgY#frW+^G3nXQndrxNk@JVy`Caz9A8c-iri4Oi=)+42UBK zK%h#X7m-CT4YWPxOBjFoWin~Ki$UYBjHip{1Hui52#()h)L^UzCUG|T+FII85H=s$ zfyxg=jstH1#5$uH`o$wcTv!f_1!unwA4s%)U2ya=YksgmBdO|bkxvK1j4(=b|II{n zOpNTy_l0Kf=4UqPN|D1vgb2;_LcMKuWL6wZ|gFZiUSY|MdD4u@?|_9T;{xqCw()w%NjExaYh@d+!>urAFNzEII;CtgK@0{jmW~)>xY^Zkq56s z0XZtE8DHdYCv`t|lZ&3CMH_2L9Y%&;mM%6GeqoWs4d%&BoH5^L?1thRjjySCRm1EY z`JCpCXI@E3`hg=X)QnCL_2th~U%=@gGnCLNQ{5OfQV924Z0Lsc{YlzSivw|2XW^ITuax?>EToI%pU8 zFLTSEcTX=$Kau{$6ZP=vbr%OgWtFj)r`kn5T87P{^fW5igUAxU7r8DPhU4X#jzf21 zK*(RT>+^Zdn7$6Fz&79sx9ihjY7JARQCB>07qgu1X%w6R>5-fDcFhy|*96=jG4)&2 z8cP0m_G7e(Nif}*&P!Y7$qW)Cl-!vH*vLpa34k6&cT(YEE&;LB4A6p?4AOLs@L|L; zi5m~jYS#9+mT#nn$Muq8&vtNyR_J~2PSCpi*Ne^{ZWal2>4>`LI5n(vOt54;XhZZ@ zNxeTLwh$BO*)9NRp1_o_oetNaHWos%FrzE39r1yK(H&S$`ft;be_bPE_(l#}91`pE zGiJq1&&lcHI~XR34Awr78J`Kus%kM3aV#()jK6g*f!uqZIldilD~LlP*826$AgqUW zaYuQhk;{KOjCBP^opE}%!Z~@Jls_!|E5XHHAlN`%hon!`SHs!*3@iKa(D=VJ*?_6B z@RuxTg4K&&HUKr`$$|3`80$U5?;swalnc;hlE6eqtP@jY-`xmlOK52S9y>2i#r} zP29Fz_|CSjpX)cssG)-L@EE5^H}DSm_3NkH84<9>boyEZ{DvRC94kM~j+pfa&DXja z@3^J2yV&@<)AeZpI~s)T(mI}cNER6u6B&+d8J;gPwUf@_DeRhg)o(tt zyVGCz{>pZLcVcK!_57i#HuCJbt&qH7j41i z^_qHGNj`)DZvmoYj9Gwd1-2^KsWFSg?p^YM1-X$q`R^SqUlG^$^Zv_w{;Tsbc+xoT zK*D`MtexGmb^gICBu~&xDp4Zhw-)({g=xhP)4o8D&=*M;mytx{c-Te6e`QHcFBo_8 z`6T9nQm8; zNqmw3ii{7iNFAaI9T9din*Z?kI1LE;9wUI)B2v5`KM;t#7Aj}yUO?x%S~(vNs)Oxz1{lW1}X%JI={gb|N%k`wcA2RI%W zSUTh6vv4tE$oR`CAGx?7h#w@OY4YyV1mJt(cmPCY5xF^*u|Eblc7=WvC8qb|@(-!; zTG;UpT@?+}@D3I5E(vNGE9TZKX5f;hzHhVe56bIE%nDw35TB6W%M~3?#+hAFl2E~U za8+{5#hFP~8fC;aLmXRMP^jz=xC2D?fEM)lM|6H(=mwDck6>pZRU5b1yn_vLU8cWL zHsq2Xu$5BhQcNL=pc=q$<od= z4HeSCh3N};tpz4pN(^sYc|Oxro9xpY?q_l?X1o)tTI2fYeMLycU#YJY{nAzU6$xu9 z8X~J&v#VWOqg^dGSo4v)E{Zz!ExKwN1zZtVywT?A9;m%>s!3ePx8$y(YOH(NTZoRp zHUCv@Z&l+iCh}91HMAf+!Yb%HcSiL4RI38-;{Ap~F`uOdVCL9>XRvBv*W~Ns12%q0 z#~A*P;D!uWltMv#sZ~>XaA+LuclcN-7rHJexc+fcV@pk=1t+A3rb%_?GUIDN* zgUqeq3ba_=;C213l9Nyn9=U2`LvGugKx?R4>%M*2Rg$5GzoQo}?o|XB_ciEkUON6w zQCO3)DZg!bjXPWVKCIS1lbx-WGdxdL_))CMRd zcPTb?DKB-YgmlpufN74q)OETw4!T~8cfV`u#s=WEmbwj=y7lRLOsu<&b$ZMXy48|< ztc$v|4gej1NTLlGAG7#~4P0PVPY8$=!bd?TC>mne`R-5Kd>yJv=-@T>v8QbfTa&g9w{}GP=R2 z8?YNs%?xed4{kKbNy;yzFG#$LQMF6HsP}DhZA=q?Mbewc46z`+$ib1#!q4;mrvM*$q%yYezx==B5H7>Gp~Enxdqp zH$TR4Km~6B;6BQ1KbV24nS;eN?CA$ z<5HRU7B=0n?(Y-yY7IQi8V#GxzxmEWmxaWe@HNOX-(%D%4#&sbU_8tIGg?WZ>~>l?)+-zq;d3Uya|oQ!_COp?4Q5M zoc%I5tHF%Z&JTHFHXrOaFYnTn5IRX)Jn!MkNX11IYce}CH|K^sbLKjzu10W<7ByXmS`K@Q=3^|U9kh+hHEu~A*A(jis2vK?Czx1 zRkum_r_sOT9d0%_LnoSaG;3kY%N#G4)Qw!g?#3jNh%<>*=*Zed=!X86<&cvKyCymq zpqoR#@=;`MubwZKe1mvo-LiPqdU!*sWWC(5il~fE!3vsPureYoDRc}uLcuqW7cR)= z8N8-Mk8~f5=&_ej}(_h zV!u~f2tNak$AjoqJ+duXm|*CeV%XI_I*PqJ;x5^9IjN!IM+iX7<5jrLqXh6XV4t3T zIcPih)pA6=bablnb4+)ih>l@N5~1sMcvSy!?06TjIRd2#Dz6denH(EZ?Y~GohO{21 zx=l|Q{>EEhBuze?3q_ce!5jENNf>@O#cuDg9xKcKNxsi9*{f>Q(bfYvEf(_(e+E7J zbeOA+utLEuRAKq4N1Q)F_LY^Q;m^e3N83ujQTl&IJpbU50x!Otv8L{bSNuX68NMx5 zeAoIrY54EY+kgE6XFvpAL=KUW$A(Gk12YU$aYVR9>nT!y(K>BWd-WgNXS&b(lX&Ch z(~|!@KeM|2W|Blf9PiFGFc)m@=f^8MCl7yX!pZHhe~D)u%`#b5hyDt5k|3!K-$eBlYvJ!ylC51R}5lB)HSheygVOxhELc-ml zk91QZ;_=-yGC^%iF_uv3=6XzR8{4uJ4_12fX6JvAp604i9R8n7oTjoAa+so?yzINj zC6oV#MB}y|e=OEZ{Xi=TU6u9L_ftcP?G=g06eogwp z8zl!_axgPo_}o*KaSsF!=9-cc+1!NekJIo!xiF{dT-t3jc;dy-3tf%wNfy38m-u@n z-|ayKPd5Injb1ih{q*Cq>2hR!-=cwLX7Kjg)!&nX-cNVccPlq|A7)`~xnte|HD0)F z3R!;+m{r+s4&LWW5WT@#S$f~%`DLL`r}m^%X^OyI33AbaU1a#m&}Xp?o#}<8TvUBs zu_i42vM{Fa$Ik=8Cd=g+J?Q$LrV)=3 z0oy^Z2?bdkzFw9|2`1SpwFaU5_m89q77zLr?gJ-T&%8bjh9X(z7fv%C^&V6x13Xl+ z_|h2ovwKxi@;;A7o`3yipD)jpa_=RNDKVM^Wy#IabaGZSHBn8mEI0;!JJzA%ua?gm zDW~sSEyR0G9FwcS)bKY$$FcZtm(u&hNjNb~`M5yOjoxua6JPMY3~x5oKPG<5gd9)P z((W2T)6#FJvpC_V7VmyEy^LI9e|*@EEG_aRRkycrJ7-sm8Q4lQ1~k{H?02pg*-9Np)a;^)=2L&=nS{G84c z;}zda#iF?`5B29_h?-Ux#gd*hwXF4v4P7~0rZE;@q7QvQs9EGao5^9#S}FBKk&4xg zH9DcD`r35mKcuID9{ixTKo36v8RbTdFo$~3;QA$drmve>#V@^QCJJB}lO_&0OMe0? ze9Hj<*bH_`f+*%yP!GhuyYb8x%K(-c!`ZpOR2e zIG0YqyKg57gz96n2U@^%=vN!#OT63Kkv;bVZ1|r=<1ttQ#`0?ZQh(RuzR~}?`Uqv1 zz4_akHhzaMiedyJOT6gPX{b+@F%dbjmnU-Mn-KsICXb-V`$>tX)gf{<9*(iQF+iG` z6H49Tgpm<#($!P-(cDFPdZE_v_=Ey4VxtHw6guA%B78Y*fJpVR4XYD8<~bT7ar_Z; zkDsE8q>)6Fe9OE$S84w56Xe#NY8;r||I8le3>l84V{m7=VB4cnPPLgZRBVX=#vsymQj>00)X82|x>U2t-ic zWI=$urL8J|M9Dlm;K|?3Ch>>fQlm=wU^7N^uXott%PC)VCYli_m-TMzU?>kDW*vV) z5%O!($&ke#p~F9^L4m{Ai}E5%#R;bb0O;KsK51%Os6$zVWe*4LOjT@z-}jzaSicu1 zE>0x=89zQn_pf;EM77XAFLE>vIOO@}rEKh^0fKh&`*pv@^Q~jpdd2V~&ha zeLp0ACfK$wi++K_tFtE(?x4)`?Ud7t*BZNlAMFLlZ0Nk@<%)beaMxE1Hre-RAnq^q zax4;RM=L<9#ZDqV&q-l+emp7Qg`?L*hcBrCx5D{dVD1wiz&pOsix zsUYAA&(``KzH|*7mMGtojr4ZvPNrr((YxX1 z09z3>6r=lK6Y^+(9l$sQu#E_Ou)&2B@4<0|c@;9q8pT1)Lc{MZ@I6Cjb8G5C&@%ov z)LwYu?cWYc8G=glJRS=MHTw>LGl_{hq9*)=Z^GL{!i zCJ2H@pJ>fwRzLLoOuI$q|9b{ojn_8!r$$9Ln2|R zWtjLf*vuh__m)>Z?F&m?)FEoy3|`G}Ii#5J$W~}M+5h=HW(r}SLIsI~sfU*{te+m6 zg%AIV;X$E6EQdd=n=Lcx5|tZANWc#b{iG?#n7Q)sc}-B(cD1uppR{YrX%Efc{s1Mr zX|_qT*`V-Wx-M^zP}H2rv~){?@YHO!Wicj9^LCWqMrL~SD`MO}3%z+i&IR66ASGk4 zL_HaSc-XXrYo#$ymHl{}QOpC8v`Y^W`OeukXI%V zb)CDv+f__Ouf&L!%=#FGUJH%&n%>&c-IKY_>NInAgDT9PV9^Wb`5&r^_pB>dQKDj(9`Gw@detn z&HBol2dY75(hoQKLu*#H9SOg0|Nes^uxRosc<&d$x2@)~aSc9a7Q4#-sQ<*D1oZVI zTVKNh>-qNT-I?h`v#y|lcla4Kv#AX}d61O*G`&<(zx?^ae94_B9r6?5YyLwk{oB-~ zWTE+YupiGze}9%rx%nw2erA=lCEKuVpD9TsOj+({pD6V&t8u@vrqMfsIwHphiKhF` z;ZNm#bJYripm3F2yGcsxU4fS}M7Wy#Ga`-5N)$w(d*Gt*cM*O$c0{~uco?yO2Sl~D z`zSz2>b|lBMYhxyUOUcNKt+YH7ZLmmjttIOJodKsrjo>cG0-!qh=HdCPS=6Zk(e=V z9s4dk-$_KUn9KZ4hVqPzvxo%4nwN2Z46H#a!owoT>wuaimyXG*!Q+0ISLnBA)h5;? z6ngrAXkJ9us0gAQz;+?R7tuM9C5uvTcxWQdryTIuTO6Q~-F(z}hVGz!-PthK;BFs4 z$btW+uFH$4@i|Mge6*Z+k*t{YGf%XTibw!wVw2#KOs1@CBdy$ZyeADAZoqD1t5QG& z`Qx|uL^ZOzG<90v@wEA%AN$1D)`_*gOa@=mhQ2By8F3{VCHIvO51`uhH5}tMp%XPt z?sA}$wz?PN)0d5-NVJkca97x)BQ7i56#1wQ^z>T*KG5>P$S;|{*Zx4Rl(+-GTz<-4 z##cGut5S#OF<_P6Q!LiF9}t|4sOda-9!V2`|v=S%wbm0KHycEFOgFK$vt0Mbb#C%Dpg20P3}pCkZ8FM(pyvDRFtSUy{cTf&x)rH8aQw| zC*tW4Kzm%}ACGGp$yUnpw9NW>l+dFJlL7DeZl7afVQ!`GQ_sFlk-m!{c%2*wYNJwI z8?-wej8gAS11V}cw8Vl+IgthMoaauxt6pnTAs0|$e(*-gH3RW(J! zuCDUtQJJL%s2cSljH{1gqE7_wT)h%H;2x1rz6%i_Q7s$#<#Qu^y8wSDz(40Z+SrEB zxzCRR`|A%GS~XEvy!X<}>8VRqXo8je36I$PP{ic7U{xO?ILEVHF(U47BS>xU$4Fe} z3w$?KT)^DV5#`Me5Zdgj{Hv-RHjzAry!xWl@57%T)cBIX5drc=oa>O#<}txH#NPDb z2ITpu@A?`yjb1qWzXEXF`aqr>ULG9sKF1^J*<&ZkuUA2Ugj@if>Hxvp|AVQwerxh^ zv?$2zb=up7V1cO_S`z zREp*`FAWVbx5hdhn(Fx z0KEfJ=6!)) zk_Hfj>>-MdK9T~tJ=KAz}Ceok!2E&IHuxnNfba4HO)HO z|K^*U7>>VYD_N|sk*~G^;^ii5`c|19Crhp)!Z35};$OR9#-3u+NoYZhNHl*%fhgwt z>fCqyblT@ldmrOA4d5|QAuqnj1 zAA7p`^@qEXgXFfYbfB(Y2Z7g#29DK{y-UHvAt~CLzymrmvzEhwc!Eao&qkoN7!n-< z5M;GY8Vbwm&2NV%v+Z>71#R1#uRMO@1hkdtr_ZMKkfP&P^W$(7BY|?>Fu;O)nma+{oNu_ zRvC?FZLK)Ma8t3ZJ?O%=usycmk^>l0#AXu7Ranc-iS4)?IvYM%K`<%Q7oQaOr@P&> zZ72NQ6!CRt>LObH1~Qx>2Zc+}+)bE6roA1vx)>g3!T_`$Zb-E2qbIx9MQ)U2?lL>> z#ZVUwssv+`G&aLg{N&Z9lp&fO z@mPH8o2xu-_Fwic zu^wH8*mpj)e`w9lDGw@NdM%Xf=aG50`K6rZ$koCePWksV{5+(ZJx%)dNdr+<*zTmg zt^?)!1tp~Ar&k+?7qgaE5!unp3imS#!f5R`-#d50*lGfQ7TzSFNtP%2$x1%_oEu=< z`RJFjYe$jNz4yxRu=vJnr~Y6TgCOe1#)~2Nb-`^lK0a+n`EExe?{|{Mra0sF+e8m= znz7zw0=``Vs7F}Sq%p^DEuvYm$KJ`l;fu!;BS-#`oRRkE+Qjx3uR%rFC_Sn}ujl)onN-^*JRjAfpwI@U0V=`ZhtKFWREQ7)aRF9MU^6=lm zex3dFJt*GClgUv+30D|L~5IC>KJUOGtbz?;?f-B>A3)>R-s{ z7StZU!up^pJkBiry9*A0OIbf25&H#0iDpo0*E`4)rk__QUZB%l>OqjnFWRTcRPm#G z9ZAVPe!B%H3xob-0}`$$bl@xt&jt~<zdYAyI9H=TGo(AcinH82;P!$dX-NWMvdYC-Np5oPf5a|2tdZ=AP!17TqR>+rUiX^`qAir zrI)FVm$f9JCiGV-5i>|ED{o7vm#lcG6VeWr6tkRYNI^a47sRRuh>V2(ll&Z~8*hU_ zdAzvrRQy~0m=-`)w=B**(F|Ia|ngeH0i zLylFD9>9G+{ zQWC{H-B|Q#Ud_Iu(#pAAexo%&`%mnT$F57oTW5UL_-~668glL~V=i1TfNCAjH6bcD zR$xr8J$UI>(T-v;sgF~Y|2XO*N6HnS8|NhEN~AH2-{Ez6e}?~HYb=M)qJ^cXVXL}; z*y}q<#kt!|r90Izu$~+rp!|F%fdAc@_j0we^W7e~-~i)=nA4xpU%yqK-%DZ<~DAU1{mbV#-T<*3FH%;;-wGSW~lJA98q!tuq}mpA@6 zmAm9Fj?vmx)pMV%e*_gqqK;Ssm_q$du5@!R9X1?Kn|IypuW#^#$iF=lN8;DCI5PqR zbWgn8XJH_Q02}@a4u9J!iBTgO>mUSp-Es}98Q0?j#I`8Fq_RH}UObI?ku__tXE>iXwn-3A@5Gd z72mjwEb8BDf&SF}av3bx@`saO0CmabA3Bpud)bskt|iBF7G_4Yr*pa! z#lOD&9a;0Avt3j+BSHYEQkAbXC6RhzZzG@1zV3dXEz1MIl5VC)eIZ@Yc)4Z<9M_d( z*KL^3Nf8?}yp!K!xEWH1Yle@8THF$`Y2aUx|B-`y)Q}BkP0)i4}nhm8SZgHtJAvme!e3&7$~ez?4MsMhq`0U|_yo z68CF7ChA~q$sqWB!3Q01$-Hug5vEAAD4GaW;sVYr?p6- zDLAUQdG)}M%m`kYx-Bvu0DxwbUyXNsK*z=DQ+B2>?}PM)Y?hPbm|83ffG#o)o~zAd z62MdLA0U1b9mgj6t$M3HBAX!X074ysP@^tpkGuu|R@S%I)t~>-xlNZU zQ{uM*ij|$RUz>lTe#I;@u19J$o2~?8+NRKvT-=z9SAdbq<)Gg!<5S{QJJCsa6sgB4 zum!CS5}abcP%n#5lg&wHy$9=QOY093#Sg~BP7GiYZN_R9E(<~1+%iu&(jOUW;@hYh z;xr$brHYGbFzizb+VkZS#$3EI@2y`KvHbn8zE&zUDrWg9&@LM?x$Xc@W&hkW)7L!R z(NkKmhlkTHJGv7!vRG>TbU^L9K` z1Wm5TKRhWWx+nmND0IKxL>_4*I%GtkHCWF1M~$}e7v0^kO0IxpA}=_x7Lg)H?k1`|4HmkTLqyR`Sz?rtN!YgX%*G^)3j=A{JfA;_T# zXkjm8g2Nc!e~>#}nd|oV`0maPJx9&n-zFYIsksSe_e!MI9X}!qYsqo6!U+SozfZEP z+hN98qcQkiiRYSXoIvYL5PJ@Ks<-MHLI0_C=`0Xn-#R)S(E8-Tf!!5R5scr%U0K}> z7>CA^BQQW}p2=BGuGyE25u?ut%@f0_=viS|trH2k z$06CbrhS3;E7O4m-|FDXS$LBJjkBir8o14*c}@BG59bFu`W2+lx478<%_J@|iOj=F z(VT~$Kw5JF)kf6cI5zo3+jB+8U>!2UL7~zXqu*q`RJ{KQk3uQcAan4aY^jW)nWGEN2KTKngHjo zsCRb9NA6L7Ujq|f~g@LB#sqCr!(So-Onq zfFf4yu>7f(>v-@VPxJqJ#oq~=5~4%mC>=Fm4=E_8SV536hmmoa{-5Dv!LV9tc^FXS zS*}SUQDPaSku}J-+3oL-_azZ+5F^Ub?09Zx@Sw1-u4e}_rqN_#szwYOt%n&3HFc)BuQnA0wb zZ4?XU%Md5;ZKC_(;2vI~OpO@45@F(~hqm0RnGZ+Be5?DAwk$3ImM+EDcK^IXKCOY5 zVhR`swBR$0!O|Sl9L|Rq!E)bE$pY%%UvSm^iK{VYq_Jmkd^p31-_CRi{h{)U!3HjS zJDUls;Mskb@mi!h+Y=pLK~v+DvcT1a)pq`s6OP1#W7qJWlwZLizq?+> z-4e9i!awdm-aK6+s&e>g30AcKh;K`j;#*oJfIP?CW{wky}C;GZxpF;>7WmKvQ+L9`$g4)W8C zug@B9uAr6Z87wxcWOvh~^;!p1aop&Q5JN~CFLj)xVRTO%xnx##eBwqQI{@uJ|LU?a z{#VH>IQ4e+JFLJSc$KiQqLGup0Uy@(1FDl|l%o@z@7pL3CQL07=|s%ADO3Q4?y1Y@Rsla&ng(K+ zTd6dK5&U^5xH6cbdXNTyfY^iNK+fucAbBhfPbCYF56dPlxXP&Rz#*tbmPIdYPfex( z{(J!h>An(Y+Z0ol)()+q7GA(6szK7|ck zPHx@cb(7)D56YU~0jL?qEtTSGWpho@+c*j7VfhmjrSYUF(LAIyi6s!MJ~;@$0K}nq z)DAA{l^V)lSryPOOEFa{=FWPCYKmGzF9lwf2;UEL^oHg<){7HlIY5Q9AtRX3ZA z(osguVkR4m#@qz-0e!Bd>Xld`W;|5Ou+sL()Tg=x5-#MTKZ4@lB1N%mR# zsBFZvV;zEqITAsS$N7@VAeynR&N*A$r0#)i?(l~ndGPDu*1T?ByaXpM?jy8}+?gYc z;CG~Ka0-NQwR*$D>K#4Y9xr4=zlz`C<(`fqKP~^?=4cd4*fEul1?a*nu$rrX7M_YC|0&T9GF(;&5m-@oX4SDrXRig##8}S|- zd8B;jdg|+#)41#ZL=(_g_hY`H4ycxtzt_m=RW(=2Bsy(_GBzPvAYw7o#3BUH>S(HX z5_gy4XHk(zqPvWB0&P;9WqB@n@@M#krX zb>2CMOcsi5In=5^mtiVWvg{3ux2670L z88|49v?&Z}j9?9qst%^^tx0~Gj7>`&H!&~xYGFNSCseY6R^@amvV+ci4mKY;TH`sLmxm5H>(MfnwX>Viva`0?8(K{ z3^cb;a>E*m9&uhk1ehgGaZE!7-Jr4DBzbT&)aa`*2|x5@cnWMjUld%a+ST;n)`{fS z<*YYd!9*-$G*{P;Xou5$`2cw^Gb!SybE5A8H2C>UF(!AxrNU#N+CZ7_ItdrI46uYK%BbE#yn%zihf~VI% zrf@(KF?15BUSI?!zKxqeAXHoi)o2D(!8~`@{(8WZWr+X{3XH^t@kp#D9u!n`i)$sL zZ=+1|(>ik9zupGt7BJ0lXkBbP0AcXB2Wc1(uZ|qsqfbv5t@R${ z4c1==8m<~dLX>VbN@CmG(=?RdRhk=V0(~?jff(K`4S2l9Vr*&b-4I_ex1?-`q^hKp zPKT6VBnc{PlpsZ$i zMxAKhZiGzRoF|+-U8e&p5i^6=dFwzS)}|??p&<29jQ(7lI-cb@fc4v{0DZfF&ION& zl$K5q>}fEcT`(J-sDL?Ad-HS$1mffl(p8nvDZhZ#b?Qe2X}=BTsB8bG4NkD-PwWpW zaaH48R`)1C(YXjeX9dwctK++Vt>1I+JZw|-hbUCQncII18V`#%4HbbfOmD>jeSw<% z{%RYoiI4WZl=jVB&N#6?R#v}2T;gP`zNUJZh+7LyFvf{4{vLrvnb#zSE-;XqU=!(b z-BOp&f-B_>@OI*{s15@t>M7rek>DXnzO-(BeAW~hQeNz0?T#zc*KHtMg>4pvxGTC% z>0dp$H zUipTQrN%5yv!nXN$0`wzAIO*{tI2(?I=^<(KcwUmN3Q|4dM zkxc$Mc~j0~_hi=?k@_2dQ4x7F`GBNOwkX|s4l+74gSVwjNEQl?PGj*tE20{kQvBW z7oA|?6)OEg>fx?7zoQ7ZyqET|PQZ|=Skt&2>A-&q?{&;3lhj>ET;Pp8(>Tu;IzM&x z&MajAcseh=O7?j_SF>Zt9meL`78Wmmt1+e(vtk(YPVsi>86h`-RG6a8U=l0%J^H)F z&F-Vk7X(s&NrP8%7b!}0PTEWP^QhpRk82fi6uL9_25!*WlJdmFVxH`O?puhz!-F(m zG_Uj5ZHNPGQ~y+2EsS^{;YJn1F@F7|JnS7#7uv!Pd^od>C z$#a!%{}C^MmJ1+uTKoAqS$}?TtnZIdzh75x*%=atq}2cva#v(ow+Wwgj*P1j-{iPqE0P-%iu^D-RqdXrBF3 zggAT@e|E9RiYK0BC>#E(M_x~kn@tH-G``ODHgR*QwH#?jMlqI0gTkYt3t&{R3)uZ! zsrXy?QOEZKr2KiA^JljFL;euJ85e3Z>|lkUM3uesSMaXOOgi&>?r%&S9@EkUn1Qkm zPW^UAK7PpX%7_ed97{mY9XsouoF1KOte#7h)yySeNXU(78NR7Q6T(T%hKp7=_20J` zmkNF?sjnY>X$sZAnebEIiZ#BXEg3WuU=7PNdqbtV`M>){Mv+RxGqd|y|LznHW-*JI}~_&iX`*gTf3=BZObwz~ciNs=L; zqX(E#+r<+iu-z>{hBJ;%{5T;wr}cayK!~*QG6Mo&S(J$kZu(WoY1?e0t6qaBm(T5b zfsMh9MD=a%#e`s#OeGs&e+ZP>DI&01Q{C0F+ETb}Kpn&laIipGo9@0q7Rc3=$By5? zD`*!hajBNbixn5xBPAm!ik#v}@*`Jxv^taL6MlhwTdclDVQR7?vfA!0J83-=ewWR2 zRBH5VwQXb#jd+Y)j^x7IWyRU9I4kT_?OsgU1*@IzRT{1Y5C?? zHn$+Koqd(zwVS8jR`-$x%0!Q>Y6LX+f5c6<1&&5d3;pU7yGbgaz?~+QgYVP#QopaX zd%2-`co<}a)cy8l;%0yJ%mffX`^bh=`x-CdSK`m~B#j?X4KpZ%ZoI7*$Ajh6Y(`uI zAZ=!B?Pgb_IJ)*DV`jAEVM!J0KY1#qw<&%r?Tml>>Ir_Ix{2h*Hjx#0JSPl%8F7La z&^L>yuv>hd;?$;io$tur!w-7EA|*skHbOnunxI26NPrTq<}eH> z5!<4na=sm6wF~CDK%sM3&rFk4FUG*Nj?JHfKWE@os+nbMyk)Bm$T|$1X2A(ijrRE* zkUTzQq5$V4`uEi`yA+}q09l03ww&*ANOR1;+flLsEnJ*pS^{HS6twdwIy!!U5;kF)#g1EfLCou+$apvq8JyAt>S2SuBueUl4$Nn@7P; zrk*8U50D?F);?1k1g1d;inkvwN`0c8QdYLGKdK%JJ%HnjGfFCLu9qnOYB0VKmyF?; z+SP2l`P>qKC1hPe+R~|I8}#@xxP}iAypN|x8cP}OP404>?&qbEaTADcd{?^Eqa>N< z&tf8N_%8F#FqUkjYKE9!E8jex;H8!;az_1{3WVp>W5n1JV6IbfiX%r3S|B1OM>{gc8nGU!A*)#dw<4{Z_N_12^I&s|#LWiL9SAF|=es zbsz}Jf5`k6jC`YhTk#x=F;C%Dg*JY;Jhk5q5bxMU(CEUee~2@*ji=Z9XTPmgUj4eG z6oVco!&!<`Pda1EiKdQPpzx=RZsog+?MLTdm&1rM0+2?@lODAb!*k+Y^~Y(R0!%h@ zIn@A{aatWHBCZ1nBWf!BC_3#yY^CYTb#$#G8_N9n9{N+%n6RT?GG`VQJ>SJA&jM>S zeU$6;+oq%D*!REUZzlS`xn07SlVpP8EcD@Ex(fVLFC-Bf*SbLK*`!M>rVhR$3m43^ zZ1SD(Uc0A3+0M3lg&Cc_SHVh^ZAllQNGB{?4+=2s9AD^VCEyk=&zy#H6J)d3Q)GR> z47eGcB*!$_gBI!`+7@36DhpC_mTPY5TMeQuk0;Ql3sbtG&xVAkJ z5d!$3bNT2aYCWaR*adKRJ=&MY;+D(OtEA4>{&b|~{m-K=Zmuq~EN`Xn%%6KZ_scwT zJ{nTS1P`4N~4KjiAIiHAEAz5Lu_g1h&M zFxB#6TH7a?wCa$@yQFXESE-XRL!8!>J{i_D{|!Em^0lWT&=Z$-2c&v(_ZfDbn@Hw!-$ zcxFZ4FUsz|8ja{XRDra(T9GDaB1=zAUwqpuz=3+@wVrtY*2i07{@X5h zRnV><32~2lAHafBnAMU9WR4r2;wgK%{uFX0VGw)viq~t^J4VR$LX-nsfkof6Qfy42 zem!_91?aiTL=nGSjL(ezHWgz1l3H*GR^;WPu=ca-kmbrLFs50|G-)9iCu75oD3|5GG*OqEB3=c?KZ*zHE}3oHfax&oIl-)= z#`Sli9lVNervO^ehhKO( z(mffV9>>n4K)8YjfOeU;^M1cu$a&lzFyV%Y=M^?GG2W|ct$Sn?kCkQ$CO@w*VB!2I z(5=sKC$=9=K*C$acvs18oPc-!3qQmk-$nhfifH6f{cLatz3YaFFhto=7d4DGg%uHf)~Gxow61gut+r@ z&U)WrlFIS#6oC7}!`RIHB*od22c(v@yZR@)QlReD>UTR??vbDIv&nuk%>c`=j_slx zS4JXWkvPa8Sj_2?$ZV2K92jU!Dea_~*SgGI&);1^scL##9YB>|MRvSJ=G{zN4QI@A z_zVSYYa7y@c>4liz>{_M(sdf#L>APMlKzz`x2c0Ee+H>EsEGHd)7p&ezihI~+4S)2 zML8_8PxmVXC8te7**I+#3*?d-VLTV670S-iS1*ihh6->h#ZEH&p0WeYR|W%9M`q`3 zF)THe*N}~$+DA0%rxelHo2@|TgIPcgC7F);)Qs<*AWHjt8neGRx7OSkWGG-6)ldUY^>p`$fci$WTgnyf9RBU}d5LVi39KXA z2wmy+^*rc9KaeXA!@JwYjn~Q_VZuE|*2?xEh&v5bf5I#v&ZoC^Y>i~u;9$eRNr%M+ zO(nSOm zT>)>L<6fTwP6Ud22Ea^xY0-RatLvaYRJ3h5gm^(hs#QxzNHBdax!wU3_>9Tqd{1SA zbtJ1;^b2tJr(+%m2#Nx!n9wwe5@~;VVDRj(TQ0t;deng<;Uy&i5o8ub&Yepw<7_dK zg$dP0b5f~MpH)f(o)ekO(ia6y0084BXFpObKHZrMX`FC{Q)vsE!$2_M{0;?b3vml4 z9+qT!-a*1GBs&%<3zd*%ZQb9Q`vz7A>#x(SRvx&)rItE|zEZ1>&T)Z~m|9&`fC%y>5Ul#e0dnbd4A+W zE>nya^qGqC+^JfyW|D+%%nsK(4&-2m+^2KL``;LacsAn!NrGmbm8luVrP_}{I;eAn7v*;O@odxqp zD(Qhv;Wy{Jh4>7U_m~0z!)+xsBfs_s5yBmFMg;)9SQR6a1da5V$tz-0%6vWQ4M3w- z;z+vPA8}Kod?N!(*n>94IS%%(mCXEI=A?NfdOsagfLxseJUWI33)&BL77UC6jB-0U zaow+&`lx~&i1i#pY@01?L;}BWJ!Bho5nZTc$&2Gip#GpTZ@r)L@P~zs5N56=Fahmk z=5eY{EiFcWDJ;}}8=6m&;2_#Ium!+~8Vzuq5{r&mwom5Uz6jxzpji$DQ^TB@H!Woz zUs{f;(;p6-A0E? z3an89G==Sx>j3bAda_fnFxDL@Z}wLlu4HQPk~OcIBQM>Y4heuxj12 zxxizHtK0fY=(0oX+r`<>d_3nX_7foUPCGt$5H^<^PUYx6ppO&9Pz_^=_qzRX$5(!* zGX9sL{=XiPY!&zeWdrcv`uz*_y9}l28KQuM1)djBaBA#v$~@u;3tDS=;{VCXTO|Ij z5?|C&)E6!s{?BE$0)iFQUKwj+vDeKUgQ)348w8%IwyGGV87P zi?KJ@K_{oMca|bWhyoi#Xiu(wx&k z-0v5pfOYbIHNV^?+hel`fW3A+ReLNOGpPcSSrNkEkzfOZZh??O%Oqx8bjv-I)F z*XZ<~XzC%RCMn z8o!*Jy&SVrh|Udwb+~qD~fln(KptJSCm;p^N6lxMjJ%I9S6M}C#jMw z@TZ^2>1z|Nm2}>s+?%DGK*re3Wg-YZU1$-3;WByq{SmWuUh{G$4tLEzP>|JY{ERS< zYq0Q|OpOLm5U$=;0N*c&yNO%tDcP3INN8X}-9%whV>5eG-WZfE$)}dw(8yMLPsVeZ z2Z^QvG|;q+T{r1HjHL@!Fa8z9e29pCgV9oVd{N0jv0M?YQB>Ap?nG>z)!a()-!<#T zDc2!qy7@(MwEYztzqVP2GtA}(d1>LWPNID04#T;P}1pP9S?HwGW(o*}F zGo%jNH>>!5A?p3gfA80#-ixfizqfSm+r8h6A{xe297cWktVrw?Pn`3$BZ)axmAP{* zBCA&vm{I9%uEXb+CmITH$i%#ZYm&xR26fxP0)TA71BAFvAnVTu92XBD!j9yIxBp{H zSVn)e>HBD@L@vxhZXZ43**9XsGUBR~SwAomu{wNOK>>hMWV}N+L}Ku6?Bhzz*qJ}w zF^xbRSj0A1g$)F@g3gsbOMWXD)YxK|hz2YJ>A@iIN#%f$)38Aw*^JWELiE&1-_+Xe z)KV##Fp>=0H+_6N{l$KI-+{{Bh34e;^C5;zDT0E`G57g@V?|32>s^>ppHGLpk*O&_ zsY>tQ%6I-%V79%ENHsb40YE2^7m7Sd?&x7jItSsvO4N0xvFFgLY;HbRl8ngIR znM|02%tLu8BxcEOZE+J;6QR6p!%7K2-ampIM^ZM1uQbcW^oen;%~aV1##%e(z^-5^ ztYF22!a&^NwCLk6uej!c6(n~YDb)}r-VFze#6%Z62dc%+8No1{Gf{; z%W%Ky8~U`i+5udn=Dd8jLoHmnUv{@&sd7*gd(hB-(0q5$rgGR7d)V-OsfX?G5)(+e ze)y^XXzK20R^@mh_IRcL_>)TOr@!gA+JEKqn2EbemYD+KEH%b{+da7Qkk0%0^my3( zKfL9b9izMN=a_ZI^3(fk7>;u6z5^wl${FyEg2jsBURWT+wyFGdlT!6!O?gL){Z#M6 zh3nmg8E)J1`K4a}&gPv+Sp-IWAwHx`fa2Wo2IWy+kG z4-cRzdVcGKrC|E+l|!mZ!$Zf{B903+A8?LkH^8cN3=&Mtq=Xh*S5vw?N;ij|!dT!4 zNIIjn`)3+97RAssC%rU$05{H{Sn2;$dh#+_J7Fa5BU7HogVo8B?o%%mqBc7BB|XOP zFH)h(DN+rS_xUJ)43V^;F@De8zlpcnjmD6d)f|+TsRhtxmx*HKRGDMO*FI%H223hz zzn`WPm2@$k8i_$T=bwMX;u$q^2x4YG>M1s9*(Bk#GD}Tm??a`;6W10&3~OhKBglAgUIh`*doDNB-kc7=hS_w>7u9vbZPJSLv?V^{&2}!_KtI20crIF`*|rb}zhI80`yO_xGHgl}8AdQA;lB z)z6Yx1fb3k5u3_fh9~>B`5ugs{FSeIZR|vGEO;2A(L#;S3Zn>9D#kU;Ihm|+R&b)s z(WK-wFR!aPnaY;SN2(V-8Ql=O5$+lG)bV=r3Bfn_N>BGRFMPhTged`G%>Xdtgu_C* zI24A$ASo)=aD+@Rt9EC9GgY~J3N5^8%tlVjWr=1_F{xJs8q078VlyPQ__IkB#rDq( z7}Zzj$X~mj#1T_{*puARZ@G%3BiOMHnWn(y3rsOQRZW8**R-I#@%IV>&^7mrT121qS#W2iD0*4owSe>J=@l9uUg->$uhSu2vv+DW70KhBy*D)z}`4Tx`FN6*QQWOYu9@SIAJ=~F}_h_XHIc+pJ@B#V>fKikY$dhJ@m|5_ zY_E5Sy``pqo_C)QX-2JlS(cnay0C|q9cglh(S2PTPh4up*5JF@I#!tPxzn+CZd#0g zVboKh$nag|##;}7Fpg!B2DxCkJqii<^atPPM1Kw{{EOJxs-re&tzi+`n-glSEZ4vU zB>jhSFg*%WMQ-^!=e8y(^R9nTqJ^k~SYYFz5RUJpL`WucET~zRjy(sT8i!4y$E}m& zVrLrv*PK7oy>HIbAh`e6oY!}PL?8yavrFu^D;}w^wNwi_3=bDu#|z!<1!l?2Ihi0B zhB=&s#s3*NITsdkf1t?XdN#yNd&&Dz;AgWOW*cr2yahMtb?E43T)MB|F^BVnr&iWdaXE3jdp;{M z^fIR*um5D&NMo?aLWW(G=zk7Ca(iAw>fQxP1LU}BE4lP|C$lpxKf1h#j3>4;UVbfs zpHpRspP?0qnqBam*HJ5;R;v}vQcms^%av-76)7^$OU$ncFXA@~V~7v4=3zIu3QPGr=< zet5i-$P)IfrL@fE@f6iU`+k?2dxwtj34wLI7%@eH7^79WTyw5OXpO_;qbijNgR$Za z;Ck!0V&_|F37?9N;maoH;}n)YCYR0yWZ9AFU$f*a9}1kmkg(4-@3*fhA^)vPPg(HQ z+D-FdNZOrT13#yJXI?K5uB2stR^IVJ`%d~DK4a0h9OvaD&c*H}A~N~Rv&YE^FT7m= zJE}gO?;wbEqJ7^Jyd~nM{{+K&8$=4EvZ0Ti&EnsUfBI$h+rW+@sW6;kaTCGU4fJir z@2L?QG-oB*tN>f{9xYZnHKhgil8vRrS-#upL!j~E$DQ^jZNP3VM+@P)g~0# z^I}m@K=Vg8=d|sjNjYBWk>zw|YS!0u+|N}YL0P?w-^hQ54HFtRIeoEkVv{Jc;@NAq z{0`NyI?=AO`6(Hgcgss?A~*DU^YznF`*jI}F?lv#TzhCL$-eFnx|#UW^Vg3s1^&T^ zB)#yqa@F)4k&fz#kAKb_XF|WS8h|BI-8!>~_x89{BNsc3B`idmYr#kJf}Sv!{5K?C zrm2xU)pP|7#1_N5jqm!KWK3V(d~@^AVV=%o<8JYl0z7X0NcCxQ_+=dF&o9G_f*)(Y zv;nD~#(Nmf5=P3Dyx!Xp8nOGH{{9kP0|DQECv4|C_5=YnuLFpqRvoA>DwJ)ziC_PH ze&qN2wLrrUX|9N`zosWz!$OX!XaNj9p4uPu2ndyg@2MScx*v|S);;^1@G64GZiqF* z?WnP6Bd6ecINke~(v=|dUpMhj&yB}Y>%iM8<`J5>tcA0kK9(IG<)$fbqx0gwDcG}# z9<&4p`QxU*7BC>PAR&XQ>etvF5u?`8QPzcwaM`{>F*wswXLB3uwlpyXd2{5 z+rf~!Pcv*(8sPdTx8-J0UA~!pqo)BzjJf z@YcTdH|^qP4Vk}Z-OI1}OMOv*pMNfb`ng{|px7fFJlhtovSATj+^_79{FL;ibge4# zwuvpOW2=&`108Z!q7aoc->>lYfo@hk^|Bl71}DSc_p5Q4ktb10*E@hv>X=%h)f!S;+V!A?pwzH?$Drtl0jX zQ8#XbAeycYQFD&u38#^Q5x))qDao1fjUlLa5WS-)8YDNF93$Ocu=L*ZfAk66JIGMJ z_?AHMlYj*Hi#XMX@#EWwrMF&`8@f)CaWZ2_i^6--nqx1F>~x0gt0{QfJ;AP?kzNcx zxq_$>;~v_hp;>58V3io?6ncpW#fL}6!#E7ll*W6Z9?*oL-+^wYPt{L_R_~Q|Sn#(B zvZ0!|ki8@~ASANTCaRtY&X973heM;}o(|^t;ZvHwmqpVuJkzL+%n48J8H4M1LGp0%2*V9Vtz6sf11hq}fpLI>eA0x|$T=wuhD^Nd8uzn2n~>M1n=Y zKp}B3jzX-OI_*;rl|^gP9}eQE<)ni#`H8WV1$Vx$Th7z!$SIG=6*O|SK6UW7Td=fB zUj-F@E9nolBn7@q(?DQUA(5kF3h7MN`Er5^5~XDB_!;SiCl1jcgK&kU|Jlv#_29{6 zkmN7QDWS zu8rm0OGMqw#7A4n-~qVkim_bXS;%prP}DWlNFgwqPcs08ax;d31u8Fz*keES9d zdR7aeBqt7#TPgMO!WW2r>e~9)S`TpXiV(^(K0bnh)tOZD#<{t+aCxkNqAoq1un4!C zw`t`oetAz!OM66EtPlvTwN8ujAoy=ZgFZs{DcY)n{^>GDYVzAc9>N!R0wptgCCz-L z>a*Z}&y-W^GF#4K2i@X?)3hrGqCeO4Y5Wvv@+Ic{WwK+5l7t%4goVqVDIBe3UUOxm zH)UNNutkSFgd^^yFXH84Zz4#c!krQ!1uBo!OIs#{T(0o^F4DbWq)dWA7ci=e)-S0J zyqY8KZJ8p&Z*$lpjepvNyxXr3AILasDB~04r1)dVltLjA&aEBqI0Sliyz(shFPcBg2s3s(=z=iN2FgmCIe)o>!f8(--+ z)_65m9pIn^SZJMBV-5nUvmu;>AkfY$xRb9&(7Z;Hc&?Z&3R5;(qw3 zuWtYhHiUhJP8~FTCTgA)Z2qF(JTne0z(5xin$g&rge+*D1A(pwLt62x+5P$h!Uj3r zs_>#F`D|z=7N6$-5O$YAZN5?e;6orJc#3QB;uJ6LR@_P{Qi8O&mQpAd9EubuR$Pm_ zdvJG$;uLo%#k2W6&+LC@XLfeai@eN>doq*jKG!+l&tiG1Xpz8VQ9@SPZE?l@*RsXt ziYP?cf(#^V0ul=-|JGdCU~58s7X^1l6_yFzQ*@?DkSj~{YKRci#ROK+B{L{ckgOUmfQDwz&TF;gvu zWXf^x!zznPY_MxSDWwY@))IWH;>$)>iK^C357jIm4{-qHDU#7N;cX zI3W7yRZpkFtF6k@eOK#bMEc4Il}cK+@U0FgRy|FLRRk4dO|2fasja}Oifyh9qH3^T z=5WMmh-j%N@*>t%ZE*9d8@+=_rZ&t_Vnyb~!i;FlRl{wUbF+-?>n>ki@ftP`)cqrJIH)}`adu6cF2!!E9q zs`Nkk^A5W!kgkiG%5>%sao&b{{sdmOT^{7YoMU_yXn@oSZD@68yMEfj_y)`4F`#1(tIf;aS z_eH@6#DBL(v{w9>KtglZ2hMN?Ro->7Q+MCp4^H~#nEGh*;hv0 zTop1R zkb0B}ZCu2tsd8xelDe#;w9H+nviqpFlwwS!WaMjWzwd)Vit$8R+VJ^9v6ao}6!zq7 z@hH*C=!@2I%as23*2&k#gRc8yCc53U5*74i6O5yV%no%6_TvJ@Q+LKAd|yWRqec*^ zGY7?E!p9?`ZOAGd^(p+aG8T!la2Gsg)yY-knfkEFOw}N#_XVf5n}TD)1&k!ie@ zR_VtIHi?<<_LH&RGrVP!u+cUPyi%|O<13#z*Oa+g_E`yu27Q_`84)bQwkbcc`O=5k ztCD#es>L{yIU18;Kbir5iC#PP%DBV1yA%tVmRZh~S%=#N!qyQFu8G8`MU1k=anXg= zk=78rG8sa=oVJDfrK!fdsln1E?}ugTGBw|oCA>lGeK^5Jj4r0hv}o)^{O}@%+Va@9 zg+}$6D2EZiBk`U%(eITNuGaa{Ho+c~--BTinOPX4XZW7|zwJg!mnfIhxmGgE%I@Xx z##6>!+mMN5c)ts|rrl|3N>Lp*Dtu90z)=hiN9^4BO5gMfzucz zUi-1WC568&!@VshxgD1UiId)z*C+a0DbF2|#K zjidhZBRD>Ww>ptfAV2BMro<(`48MQ^I-v9npB)H5XyL1L3ova6V18b7d0+ME{q7e> z!cBfjRMhY({wXTd^HSsVujA=iJ0yq>J8|sv@#Hk#7cav36kYQSzAP=z#H=<81*a>e?^g;Hkk{X@Bu|l-d{A`l zmw$CN|Gs(o*B$$>e#Kv-@xQu$KvRNiGe2M=6e!|!?VE9Am3e7XaXmD4?cjIhMDVY5 z^=OlZr2mKburA@~r8v_wiD_L4rcS)3JPafp0}vy-iY|HhT=&n(#j)XfeHA{|>Z+>4 zpzg_X=i^#R$88cdHKDxBSIr%YS{a%v8F~TPKvTkCKa}%%9AQc*h?M<4-k1VMvFaEH zqpPBh{{%KxQqfl9(>Kb!H>4;Zx}5qDoeJ-J2w+T#0BOaKdW1H$pB=6g8B7V8oGw@i z0PF<2wH=M6S@^eEzbAg*uSqOQoZn}-Jn*E=_nM9!pFWj5Qf6SNuRxrPMZ&fKUkDArM#Ai4|uI7qm*K8^_qzp)P8D6eHFu8mlJlC zHMUm=WI@_3l;gz%{{aCI_wjh^6mT)@r%&Uzv#AF8t)6c>e^34_&!3ti{PSf^mS!r< z+Qa^_zgH9Bu_%gR6gyEhaF#Cyj6H1qrcmw_SX*y9R1C@f;dC>%5s*A+Ea_?|wAp67 zeC_bN>GSEBbyJ~b0U{O~sZPP;l0D$ZZtCb=;k5eIMycTa%H3z=(ISqlQ~PD(W&4QB zH(CP8s@uL*WSr@s$^FRw>7Vfe)3tWxe}86a6)Tc_hLM0Hr|QQsjtNA^May{J4XN9i z41}>qT_y==IVhXJqxQNR4~#q3-6f5Cj>ur=-akFI^o0D z9Gc9d@vNO>CO4^NRiKX$xELS_963|U_{uam7@HLtH~2FTcW{WK$o}OECJ}~e)aiq` zMwD5MX;O*{B!1Z~xJZmUoV`TNE5qGS9mgPcIrB*qF(i*QCcLJ`uP9>0S=%S)L@c09 zces72D#@7OrW5}#nmgOl znz^rb(}$93vBq>jku!}@#2*2_6Br}q0XN*>U_ z8QM;G>Bn=07Y94e*c6g0Wk7g3X-+;7xQOepbXC>etC& z48>Btk%9b#260%L;h5aWlJ{wa@aLJ~Ie5rX?`R=I#kS1|d~W3EFtx+vn9QF=dB`)p z&<WEEdf>^7uO^3LcV@cokiM$<_gKG#Q54qMUV0|(d|tTVajf*D zeReb+MhNa6c|Z59d4QX6Ag+v7AoL*z=SwLX1eK^Fk)IP{3d>0aAVA`r8yF5*azJIY zB4s2bz|lGfVhITqPMeyFCB-1xf`uy4*gT80jn9pu1_-yygfIx8XM@m!Dd1-q4yCyq zxRaQ#l(67*Bi-c6Fp$&?T|$;)Z7zWIK>J6t9zfu4k#_n4*FqH*y>KTX=vLZrPL`m7 zletumxkNj*cqZuAY>`$1J3x3H--=iUYY_&PIVdJoUneQ0AmPw{{5ppq-6sA0U;!MM zjAALwrs-f+)^Avvtq}cCVZn8XG@UGdH%7Wm)XyUa6_z2;kJm3T{%afCb>0iCWF+%9 z>y#P+kpJiW{5;3uX?OYQAf89J=n-PtECO(UAjG(t2-0&Mg8rNwY4PKP;LT+Rx!qh9 zK*PD^3UL4o4{}%_Hfga7>}MO6&wa80{vf}FKQG4$ zu|M7GL|a(q(rh`Oy>~;#MoWlh)1+3O&<36n@RRloE8jZGOso@Na(~DJ?I|)&x2#5_ ziHzFqFbCmO<6FsFqW4Sp2cu#|Qo_#*0%p zK`R}umXeU#Isj?>fId_j(=RntWeSN5BuYW!0gTBw14=h&DV(wUKpM``UewzRR**sU z_BG?ZTxwf`k0RV7QKTFj&Z<>SeQ1m4-$T8(nWaSJ5}l)cuX3rSSRqpsIc`id)a$R- zglE1yZGBX3NF9Y&V?LeFCh^Pf2w2@Mq-R_fUK%IbB833!aZ8P4@;kD!uSn+cl0W7# zviqFNh-F~GzaA>kuEPd+S=Y$aOXY|()`P_E+L9a-H`Y&l8Z$aZ0S;k|`|6KFl9ls57c?hKaz0fB_j@raSXj5|t_I0zE#31^;cQmpkb|sv)f1kGh>mcww zcv~FNK!ywgJ>C@0;{dPo1=g-7<|R&jOrh&Ie)$xTQ29aBy%Xy6^!@$U8^P0uWu>(T zKxL1JuvSc+UCWVbdy_@`J(Uyy(RPvA{&X(|xG8702AjYjzy~mWEFZg(V7qY0X9y4h zW%Gq}`kjG&lZ)H5LP;$^?q?C72g(8_f^oMZ98-is!df#2*k-6gNn$#snn8rboxaN8 z#Y+J)3;=l$1PVg~+;BxW!#!a&E_>hXyc~9OZDF7&b;tW4da|KIaT0aqeY?fnjHP z^dkx(3knf*z>^vXWc?KY3Vh2c#|J4ykx{@O*w&m7n@EVQ8dq3jpWe5Z*ywPQLPh_^ z@IdEpE*Nmvps-K1iuP_LuXO;Z2jRgP=9#BtvaRr`RFOIxI)lFm7sVSEMGGo)>#s90;1#&TRh(QkS7^0* z!vS=Cd^+tD!m?muFyS{SFrJc5r1yZ1+q_IT6&u5c&loEYnbCVgcaw;R*9^67JRPZji$nD!`Wr}6a zaC6oeH3a);fv+&&6bm8l6QQ5sm{v^riPMoT17J7ESPtv>j$5sfmgcov?Z3$JTem)f z8DbQrjF7$tO=)ODCmbY3{< zu=wb(M(MDn>#&#UaJ1=gj_Po&=x`tFynNK*!PDiX(d8o|k%!P=*;@Exb3{f;HJV0UC(VEo`629Jt_}-Tg9NB~v}-%)TlwfGz~P=*IUlteogP4d zRAm59$SY2Wn2)sR=9nfcMExezeIyuH3@qf;X%wXY#pkU@FC_m5_-g{#2lmRrnpYLT z<5JlbP>JEgBjXe$M2I) z2{obvvfN<&l{Kt0G2*6y8==r0Yp|m*_mfzt%!gnGF?;r1x_y4PT|HpYh-Tgyp-Zv=D`~KhU-Ocs= z^#jWF{!jKk|4;V*udb1Q|Dtg3o2zT&)y~E31&Z~)y1qoo-j|n`7Z(=~=ldwu`{3`v z2}zySuwPD93wi>wb0ZU~Of0dE@DK z!_!>!(|9bh7xB~wd+JbIJ6l~oU0Ob#TRdKvJ(`_8n)!V=ws1JVvAMGTKfd?s|M=d^ z%gakk3zPekBYVRmyTkL_Bhy=xV}Hh`*2cQGx)v7}=jZ29==bdG3`+c7oNJz$oEk^f z(CF}B-@w2?Z*Ol`SJ(f--L0*y4XxFsizO)&$zg*bpAarPHGva#A;?A{Wc7=~8u{kt zy4ITVj)v66mI_p#x1q7Nrm4KHuCA)Cq^732vbF?8ZX-)QkflV(LdgFh-e~_h-pTN* z0?vO0#CHX_D9U@G^ut(|e`9HGeO5(5Q%+e;L2*q!is>$^C_zcxMJ4$;r5Qy-HVM(Oi)tyn>TO%7v)w_ zQBhJtvD}Jsa&pqr(kPmnMZpsJiXX}G0!d4QBz%U%#X(WqH`G**AW)=`;Qy-K0s;cO zyu2v5n~RH!gM$NQcQZ3HGcq#%AG@2H<~bD=6$J$a85tQVDJd~AF(Ki9iZ=@Jeuf9d z!^gwL#r;2&Hv|Ite?`1ezIO`Xzk(nEXb@`U%B;>n2objNdhbBw{~zUT(=+^kC~q}% zeznN|Z_1lpkBA?4;Wy>nexaDCZwgY(umUZW?gHUUTi+E3!1!8_vw)YR|V?w1*#qCEa@%6rX8>dE`@Xf|op2c3|W#t%Tu zy6z8QSI!JPmDw|aL-bi={763*{txAy9ZU|~`yGgT!jkR9l99yV$x&^Ptu_t+u5+qh}+S|^w=5t+q5`U!f@IjjWV}MF_K@wmI($Qi~b}UPr3c^ z(F10|L6(U&|54uIA0eNEvUXCP`zTma9fv%B0T*7|q-MmOFBbg3d~d~&br3896)|6# z`lDvbeXy4sqxcP$`xi?Dj;n83y#FiB{h+Aet+PvSL0+P5aZz^kSK9(U+=;v_9ztX@ zU1`FKYJ7LH$5+eF{l`hmR;ubX!&rw_b?Sz%koNAqQg0h; z)C2v%^$us)mOYZ5wNbghW0bgW_1$y}E>_-HL}`&D)7EL&R{$_+-T~*?e-6PBUxb_d zFO%-nDj4I10fkwYIs@M|%kNKGms7?1+;xvvR?$T)BBY6Wq+hycMK}f_ARyg4nS#@% zyE(r@Z;9(Nf)t5Q;Z$1DocH>x_qThDc9J)pTMjYjCxV*ZGE=XZlh`GWq5=D)2tcok<_iQY5q*xPf?}c@U zk*8<`z@J46K|dn8=oYo&rEAd!rW`hC>*$pq3qwU_%=pX`Eoq+B47NEuf99G`oiE&f zo8b)Hi7yI5QQj28@7hm28kn}kF$2Ci;WCl;1Egu5=#k%jhZt%50C1_mMSK<9Jkn8O zBK~zVT-7XTx@iFj6Thc=#@}(j-&f1}ZU}&bK0DlrpG8DTMQ10hRz&$|nYeCXD$#K= z9aP24&9#UBH3UB=pP!N>9-+(J0{}<_qXDqLP6PpA08{DUS2O+?0QsxfS=>zpbmqoy zuAz1eg_wel6Qh^`Gd3(-MF#ytoS41>`P#i>sFz0E4`WvWLTy(2g=Yjj2&SLtgCW}B z9QY>>AfOROB}i*6??icBSyzokcPE2~;r6$5U4Y{qi|XQT&}WVU>I|~2#wf;GXD&p4ZB(*T*T!eBh3gab?&!^bm@WA@ zld=|}D5bxledpn7nN(Kl#zwXBrS9dYS_}Y5waj-vEuN&D{1x?d(KgI1bLt!Ee%?xF zsBS6a^G@dtdsQpYhr;gX8+-BEH|9}ju($xa;^#gBV{o2h`DyT@C#CXj*!#bjb!JA zM!M^F(bEb<*vh%I#mYJ^W*5fjPX)co8W%F})wU09g<1qMs-mVT*J-|&6$80T)m&rN zLHr(X+1^wBNKo5Zi4vjb{iP9gSo1OXcQVphPTwT4#Qsn9s5~HGFH}IydlQrKnWGhV zP1YaMy}-O%5eHw*oMWXwDs%4?ToNyH-<@sg8M}@Nu~lzHi|=W?t)IXY5%@$}_FPA` zc9OW)t(X?i<_*r<7vg(LQr6DIX7D$W{jv;(>9yP}vG~XQk zrER_Kx#=+Zf_);N+N!sc?F33wb=r%R zn`yXT4W{ih*j%cuB-N!MQ+J)e-#V*9)Q{`>V6D3)ipg9XaqrljKMJK#)oq}bYlY$p=Y2jtk2{ap=M3qI|WWV zRrfe$d9-!A8%5SWEsMv(ijT;I?~h-DOVHOo*ROPECLTg;35Jy=rbF?E(IXV1AWp1 zaOUB{>^>C=S0vY&`|{k{is}+w(VQ5)GfwqmkfJRr;}Am$F8H6<4Knj?(ep;am4q7P z=og%rmEAV2tgx!kd?vnf7`RO&($d30ZegHhY1|`0;Nm(iZ49&mhVNnic^(bN2n;Yu zdfU@r`Pw5WveD)q>7s%bgBB+o9&Zqy=n)<_pkT+WYk5Ur8ivz$rP?W=ri>2gvxL&H zLMd6H7Oc>R7dAEvwg!n7!f@ZmETB`PFBMRVF$-@s2BU)z9aj$9z!_8kCx|>#p#1`h z# z=KZ!Nl2{8J1jwuWjLw4}Gye^6_N|i0W&$lnN+5t~;S)wBc&HZ}jvh)4luBbHRicBA zuH*mB!aI2Z-TvsfCj^a!;{Tg)Pmw2#F5N;{0IUgn5%4Xw7|x9wAV3}jh|Rpov~cd{nkU8lAT`%MKMt%JOC4x(ZZ8G z5)4GbQ^L#~n4wN2@ACwIxP5rbGl^U4j5EXoePE48_Y9F$j92iC2UKG2y~SgzjA_1! zS71%>reJ%q`27Qf+%6a={qH+o3QyM$hK2ctrJtdRaQs6aEZcn_tj@$#rkEtGBsq}? zv@gC`Y!SGgc3z7~d5g?`Ha~@`^p|H%))aL4MAUbJ-yih4f?R;t&~K&6KO+-;L|Kvw ztl~d~LdDL&QafKg_T%A-3HeQFQaNdf-JW5;QuAM=7xbk%g=#zACh97nd21yx08%`E zrsX0B)3yg03n-HPI=`ofI;~lyZ-CQ!F*B8Ipmh+u;rx(|@Sv@C84tJgyZae&*%_0A z842MTsT2|Y`>91rQ1I)tM_3xxfmLi>=Ht6;%8N|g!dEjQ_LRX{>P1;wN>CLFw|VF2 z_3*Sin{4)_G~yJ#i6S42gXeZOSq}TzFCaNLYzl5o*#Ca!vXX`p?4)ss=4mqK9o4{J zeG%jpHRut_yx7lk`Qqz+X7S!VM@lqXJ|&;RHG}I%-hJnHe)O!5s0*ghT>T+*zX{C9 zU^Mz~Ij|3ThLi;_Km}S?FR`IK6e+Y1jXdfHpFY~=cZxunC%}F@<}!1?-m<5-HW%I? z&yxa(d8Vqlrl+{#42zs)i`EFa^TUi67Yls9rK9tviA(3>9Q=}5%85)VZrmtLs%9_0 zV=KBSt`;rPhnCbXv72J%XQ}+MP6l|Lfxk+d(*ze178e$OE#2NI1oFN}WM^@kDxI)> zF<#7t`=cb2vaq!{9jF~)AA>D@of=-8G$2~OoLvg1%=EjRRq|dfiVhT>xQM9 zsAZAnVz+O?ilHI<#pQd=<&UEBDotQfY4hke#T)Dy|C%e~%*vnLRRE}}pkh_@ib=w- z!g=hE(#7VtLzVvyDxZo=S|}?YRH~OeeNn6s=xu&aah1VA6_1gAA*CRdS1ut^wd(R) zjYvd%cN02@0}msnYW`m}uTd>8TD4F~4aBQPmZRFAuh6d&$oSDl{V+$+j*r2nRwumn z!%*#;mRgnNY9LE7xisFzU7dhxtzk<&sI!jwuud$ZUQ)FBi4nLm2t+Lvx*ENDYsB|% zxPFOTV+vD~)EVc9j-dbShjo3$(ong}J?cDDAJbQchRD@xX&7H@$egKya}?y)I^&Tk z?a*Nw$KWkaSf<#Op@!X(sj4+vxTDTWgk#V?4p*1j)!8mL+2N=t7r6CX0B_bIKy8qC zV`I@_QA11fCyu7wX71oKuooO4HEcCB+|X3gqKKp7^Y2SPx?u(*^bZo?i6H}Lgn^LG z7wOjmmx8y^&Ggd_GdIGUI#N-v*HGdJ);RHB7V<(M~?nfr?}WdiPmVBWzpyKH?%A)B2pL z`|ZX1-9|dxn$Yno4JLWezSws-JoF!wboL*Hy)CU%*$&`A7839k5@-uUH%g#huVB%s zt>(+k<@e8bl_02`@=}zFJT}AN9)p?)@t2e8pFXP<2Hif)>Z#s z4if;j7?_;Zu+rDIyw=JcOVvg#{5-qn!iYf=oQ4|v!BOw$% z+?sB+#)b*}OJ`gu=E2I5qQ#}g7bVTLtu#68G?}>B?P`pFTBZ40Ml+T>0eS;FoWsNS z%|optr&VZQQo-yoz6;{DOZMYkk>jj?$M@342JS})k7>G_Fo|No5uZoFWkHwXPPk1z+$mfn$JBxG)Qh&U*ErJ+on^oYKqzd2 zDyjubeR|7w`q|3(Q|UCIZDwPm#1HWXZvuPHd(5AA@VUvjVq1G7=G@rVk|a|m4vPzJr)J?SB>3Gpx&K{+2UKJRKW zFPuKOsvR-O0nM2pz%H7*rCtc2DF`b25Mr_r<}tSsxNU`i&2KX4m>`yP(rcoyuCzSMsd`U60_ z*i-30ISruIFc0d|*|pKMjW*jjpM^Y!)wDFvig z8sFdPkM*nm)#;p2Z|_NL$4v!pD4QgZ1Ahty6p_@*12Y@og0b$6t)He5$P zAIx#y25;>0lYQ)ktpT)fG~1)}kWV{5$#zdgR(p^49#+=)HvXV%Pt;)UfzbBOHbJ*A zY!x1?OS+!|&)KpI_L{r*KsLWcGq#LZw}fJMF=8jNbapVa_Z7c@*I)$e(i@KLtkTYy zA7KY=fd>}F2W9PBDQz2mGW*%-bIBUeddELn_-qn9Abh$btmHkC`lVR>{gv{glCc9L zv_s4>gWa1W^k>KMQOERU$6x!8DJ6Fexlb&7c88z9Y^qRlu|o^T?b_(s>9G@1l_M9d zlMToJX5s{7PJr6=RuLz_?2}(B^rUb|E|dtQg=vjI1Ja6MAiqC8?bg0OWF$Cd&OBlH zej)Ga>wESGR&Mnb=llUFx#mRq=dTQ?WdbMl8`K(r{bAz#FnR(z^Y?}CkKrTL41D@mQR+(mI~8XK5TkRxX6`Dkd`T;l z(~*WKX#$6gfQSizoh1!4k{Xf$p1PhKz|#Mi($3Y>7lY0hVrkCVq%O1HRfxI*zu^#B ztzUX(<}gfMpP&4*_E{S|)|aLWD~T?Wu=b3w0pkxy`@t;wkiz)saV_|eg%za`4QYSzPvfBfT|Dx z7jo}; z9TfC5LIcwXONDs$w>tK>uI6e#pV`a>dGK$4lk!m^$C!C(2nZB);S=~;yFL)7k{)se zx!70aZE>|pPI+^vUvARoTSiX8say8CDMccc@JPD$!)!Td;+o;Rlo&2%*c`!xOq1^Y z923slGwG^88gBA>9PMs2$zS9l)bB1Vhlp^z@Q(g*Ep%v#aXfkp)b5Q^d)^5Y=F-;T zdaHWT(C~dieke<_A)~Id)9-$sCF#;gV|?ShDeUkm{aB!WZ{C zpVlqV19cjI(bBYX@RXpj4OO&9p0ubZn{e9{;%ZG)^2k3^BF615VlTCkjnp&dl^uNw z9PK5OYvvZqy7LcVoreW!DE`!9(q4L4zh=o4uu(36dxtATl(tSO zP1Me4@{kg!ot3v<2gE2Ln{x<gu% z%2mQU(M&y%-DH1h7?_+L)y<$uh^Yi8GSxeWr25AshmvxLPFh6^<}(lkYk%a0XG0_x zg9eSjFAUm^(HIBI%t@{Z4bP}|NH)XB5|sf*&cdw0w$yq9i=pBg%7*#U5G!0O20_+1 zFH!(J0+k`VNy`jyX3F$MYYe1Ku)Gb)GLLV1D@p9S7>u(@%qnb?A1HRypJa8VYYs%R zg``Lom-Ow0NL^>G(`h>!L$*VDB$c;w1ByWK9|YBw>He}XZ~~TSC5SpPwy__DuJe5S z=|A^;fY2i#(J9dc!%);>zkHD#o(*I1{U{bdGsQ|S0^?e*iMmQqBA2^faq z5bsii?htSuKo)(Dx7ABWUA+J#PwT`r1UY&1@oYDjSR-Vt^yq*vq(5zeRu^f!4E|Q9 zD(Rbb`8Eg(Ejq-4RA_G^RKH2Xois0j%JTz{|9*+VP<6(7OFkD{b)ZzK41mIJBJjF! zoah-5w;c{Th|Pl?5J^v!ZmviIX25bBkfRwW1QzQFM(aoEN-BR+j!T@;h%3HGrwnJ2 zz*@@ndM}?mno^*`RgEV3;17aesYLrOPLVP6XQ_y>xvc8xp_R$+w_I^E-v$3NIr<#x*!&zf z)X&54x#`A+R!idcd@fNkD+!x9Adx?kCCA%fZejgwv z9`G2z%vp$UzP&z>DyP#uAJoR0V)4eVZ%V_mHYp!9UC8v-;A1(1_<7*_Q;#U(+JyRx z2QInyMwxT2z0P4q4z3k%f8Ttb73uuU{!zl>-M`nb=-t?6Wb`}J_lD}T{M0xscXb!c zDkJITdC-aCTULd6$r!qi$vw@y(vaTZ;3Li-B;*(UC>6YT+tmuYO7@=tF{uK5S8~ zy)Ds8m6G~Nc~LEGYbl5&s&q&4d(w%-#B|L z6TpWj?`b#(`E)&n{S>$LyblXR?lDj`e_BADMu+7mSevVUykFefg-5R^3yDb@pS#}F z7#7xg{hapVg$O-JIRC4H{$j z6b~22k!P}(yNl04V)u`c==3zV%`#sQz*s}s>OS^cMm623n~nuY%6QtP>}TyaqwY=kq5t^0J^;ZuU?W;JS=8%+;%bgUM2Us zCE@X1Hnj-sv(bLa{<8W4v*z});k)u4*D=zerKIg&yC#Ij$*12&tL@~HTjbBOn3v#R zOyZetpDU`Ids`!#>%4xJi@#AZgfmyaAZ9+Jj80!Y*gMn{O~cW62m(VI!HZL&QnH0o zcB^)N|CSr100KBW0cx$ATgWy6LWuyGj)V!QxltJ1p8t)7^sR-Y32(>NVI4rN^`S&E zSU4&S9kuBLiI;246BFHFmHt8A&~1w#8fgRfG~Sm~*XJUpYk2X8xx){^-wqM;_tGUe zGQYGtH!IO*asomDBE*)6TRV}X;dU&&F4W&d**6Ppw~v_*=kHY@JU=zo4UWp-oaZe(3^wPJq8mWTCz#U;*=;G=z&1 zjpHVi(Hee=F@8ooe$F(0K|D?{5J|@Xh~k@()X6EMjRcpFDY0 zOAUXo0xT^ccTDi-M&LoM#*sK=J&#UxAdoy^k|KYSvTl;9canN`lIG9k^S_g{peZ_% zDSGB92Ei%DvPs#SKpEj6Dv2O@dk|B?6kEOyTU`*=afmR}*fSXn0uu;JOaeMY+wGqH zBO-XlcoaD|GPb=qb`mu4P&@t#GyzVSe$1N|4W7Q~(S2y0mPpXN;zXn9Lc9DOZ9M^y zdK{Bfm;psiD+p?0Nr>qsgWbqO%?HwPdxu#>;JUT}yl?6&Y(rqIBi$GPcCC^5QpKe- z#b&kHq3XK6`wFw|fqqU_4%oB+N0?|B23K;RJ!>cwF~ddDUwNtb#*X}uf=-Yt=gJnU%!e}0qL9l!x?qtxm4usCS z@)L(XiybqJF4Rj4{85W1tu@#^In*M|-zIp}KYm1kb0IPrF1^P?uw08Ap3^UzH8Kf9 z9_r1D+yYDJ#?X{&J>S$u{Z?2k)z{DOC>PEwY+)QRep83RDT40r?mRj)td}?w^LE=H zD)OBL^}=`J#f6@^1n6MU0ASK=z8c6A2CaV< z%dJ)Acz$@qzsZ?3%4Oy^5<$2DpEZBxZBbV>q%rFJY+N?Mskr`(tzLepzOu_@I^Y1KTA<1{ z^SI58+x!jYv1MVQa62l6JXQZz7^o?4>xqPqL!W3|0{bd!K*zO1NV4SBm^twa3&qvV z6bKw5DWbT*Z3A!JR5$BNkif@}OO%%mK8xv5*pAcLc5~ZS%CLAbMu~BY6=Vkzk28DY zX!#~cIbaa)i#kM}>VwX&%|Y~Sg}!aI7i)UH;hBQO3gUmJxwZ_SlaoVaL#69XJ{IWI zHysCCylXd1TW1kkulLXLm!ev-BwdvfvVbyh*f_G-N~&@xe%S5Z2{%A%y^{eczv3 zr)KQOmh+?JtU&#p6y-JxObmjDjj%)*&6UmOrp+c@#melyyzjw3+k*s)-9D0oEc|eX z9Sa)BR({4_!23m0UqTsoY#ilCpB35c)B`Ak^)oS>_*L7Z1gwlb{eX!z-vx`R#C8&6L@SRy-!>ZLt<3SRKjV}Jj=2ghpI|GcuY-=9Lyy*RbU)GT^VAzf5 z6ubR~aJ4bHeei;w)}CJ9Q&wa2S_kG)(68f2gVqWV9Iz0Lw6T8Qacy5c28)7WSRz8# zvwyL09ItD^d$QgIlPk@0TlpyN?f*J4D?g5CTno6NjQ?Z5HfC$O10g%Za2g1;bjB!p zj$iBhO|>y->qKnL8L(Gwoym9TjcMDGaTHh|ru>Bdyt0_7y?rgw&Q&N}qY~_^75dhI zDcmDo`DeUJQ@k2QnEHOaCVdzhU9fW_*o_AiWtb3sm$&`mnN|F0U%jkUx!psCUD+5U z;RS@o8p^A2Q1#q-Zv{e52XamZn?nO%-(YrxLu{)^lLr$WP$3#vNiJ+;NsS=q0d%JI z0H0to&ulU;EEf%pv|a9V4&w7*Nax9k<7xXThi^DC=XyuVC|LLC=v3bY*bh-s#`N9` z(J&ZgLWG9VQT*u4^w*+Dbou!!?B~y_0B?_-fb~588;b82#j1!8L3>f^(x+VWQ&k>E z1{Rk>nl5~%SQXD9Bv6|Fi>bSCin4tJzQ08*u`J!NgmiZZEZr&HE!`bTcXzimh;+N8 z2&f>4lnNr9QUZeeaR1(U=Xw5vo!M*7xpvRv_>$eFNKmNuw%>jCTBF=O2?01_%fYK>aNawP_~eNuBREM}#wut2 z6JD@?*GC_?TK@0096*KG8i{=ww8IS#26!Pt;wz%&v}}xMBrc!ZS-HJTT;z5V4I@S-9JkP#V@flUu${7zZLC{e|He)WVZfhB}de+tV0 zjfHV|Wu=XMRhC4EDB_{u6e=()R91Q!*jYq=Rm^*X%W|VLPC-~->720LO&;{O)**Q> zMr#@C+1}q_Wz4|D1SD0BoJ0+wN{uI0gi=V2N)fZ@O?(#yAd6sB9xFoO?fJn2Nd!s#-+_03OLh+udJ?=TuwL+Ctt~~f1-2)Zt&Z*49T}uL) zC6H#0eVX9E4=T=YWXmvlBu8_^v+X_wr z2Mp2?u>s=KYsg9sSvs+(a{+E}ujOy0$+!W~7Kd1x82UplXdj2!oK|I1OK06yjo{bH z-36l0&D)?P#2>4avw6Y|1tY@wu)CK<^BpWEoM}B@xqs=_UnexWzpZYxk};$Vn^tNn z-v6DGAt@pWtf0Kyo6|H?(EQen&rSFtLgJCOxjFkuT(z?sg&+-j-L%A0_I2m`FNy6R zHJ)%_vCMo#9b?7(usWcYc|&<7l{MENOTb^1w?hFkPN~Tz#t=(dG_l10?kHO$?j1rf zP2g|>^M~8XP&{QM(<^KM?4`~Efw07eeU+6^T2NjjUEv(a)l|2jB9`6xjXJLYB$zo% z)pUZ44|VoTBOA4$hm)?oT~M5w>d^26ojB>ox^i^9(^~3UZ;_vW=g*J>64rWOEh#Tk zD0My?rrD1{;F9FVphOD0CT!4_>U9xX8k1M$!@ArY_eXQHR;7+30W}4Oh$zf4QnOi7 zmm_mv#FK9naHv>eH!EMkpP%aIXm^&T8&3Qtfbs`=SL}_~gKYFkOe6H+y6J*-B|kN! zd<=|tConTz4&-RUKxzbvk`F?v_49TRz+?#sg|{?3WBFc0ueo>vMU~j6h61-#LqV9 zAjts|X1AxV`yF2~_MmQpJT<&y(Mu)QIqQ0PPuW$#IHe%=tBR8z#kX^)b=-^8Tqv_0(| z9Zl#Q^9J9_Ne=JzW8m45C$vogiX10ZubrbjX{Zt42GwhJB}fCZm}6D}4r<;ccv_(P z?_bAT`xZT>XtX&t|L|rk5D$g>13QkKFe$(5a=^#OT%g;4uKGe zHD}Dr*7O4PyW35^l;~sP>W`$B04VQ!-$`9Z;t~I9_cw<#b;CiA?f;I_uT+SqTjD77 zJC5S18D=c-^~lYKQ^b>vF`dPDZBm#^F^%ph?MX$?&=;>zOwQ?o0nB|$)o=AWvLX{^EFIB$-t6QqXY7}- zG~t0Myk8HI<*0;Zy5u&QDb||kSu4Bt+JXq700P^c^5M_^trqxhKYUh2x%ZqIFm6(a zDLB`LDr!ltdMB7!ypw}-qS_ak+0kld3hj`JLVeAVe2+7%X4~`j;u?etS~MO8h^X53 zE5%QM5GLZ-aCJPK#8Tlzs61}p9#1JTSE%dEO5|swK49Y)P{<6sIfKjox`ti^n`U-K zP~IcdEFRZ2it zrcjPEp?q&JBh3OkAsq#RxWn%`PobOG1A&~s{cG9w|MG5MZ@#!G^-cwHX8E}R0Z%Xi zM1xMtw9^r0-%YWhvm2#k&w^Qa%T!a;@4h<}l6Z__sCru|;3M6P5ig-?$aq})hZn}o zzvtF6`_3AkoX*+6)mJ|=n`}$P|C;7`@8k7#){$yJ0fRGEDGlp9|7YLgSd8VVAs{@% zo~COYlW!8fPcu>->&f7_Em$weWXV8((HAXprIKXJCBRg}dvy_={^fp8&r0z#=17!8 zjyHi_1QRXRq7X!PF4^48h(QZ`1}N8ZB$L|TzhuDMqMdqBcK`u50AN+5QTb>{LB{HB ztX~Ut3L$a9C`FElUXleCrhpP8v?AfSeT$axQ0FK0bz8hB3((yYmumep85F-_gdUR% z!u$AB@a^-`GnM2u+ZW#%0&BTW6X_wsWd-qE=NVWgv(?1IubkgjAD^bj6ut`j(j6Lf zfkl=uxQ$C7ngG>Hdb!NV@Dqt)mVS9wM~M>0-3PKsj{uX1OA+;ySWmF!61~F)lYY?k z&4^|JCEG##n)`ZCwAW~TvB)ne=d%AMT#J}$h}SmWiAWHFOGT-p{NYNxq&}E}ctd-N z%BfO5t&mV5+LsoF+j)I7H`!S+n196$3vn%J*!40G+sm%MQsYH=rJzSB?X|HMDQmVaRGk+V)CIPgw;cR2ir>C%(?s)8CFJAm1mqm3&+xh=QVF6#Q z_x~CA7>#CFS(2Ty@339aDI}) zYiE=Ak+Q>J1)M1(4k1%pRJ@Sl#$A`?>BDzy2)*oVgoKmwgH73vH{BEL>2p~)sgscc z&DsG;Mf>r(%5sq~ep&tyUHruN>hURj9LULSCZ=539Y0M1KYCPVFPi8dSY{7=MFNp= zl4otk%$loMpfDa7S+cA_aWE^+{K~|0#B~X(z>14_{^onSI|8fLN^Xj-keO-&2w*S# ztntQ%iijbFQXktINN+nL0v~(qtA8}GS#vjSFjg2pj-8qNUfnE5kz^zP@Ksua@kt(- z!_Sm%vLt$QlS-mY781cGmW|z(rD2a?m8&?Z+?1vG(Q9lo--+T%0kW{f5I`)xRbt>9 zN6Xxd>7q87&Y>0SCBxmOj^68rL3MIOAc~K!%(d98(0Du** z;He?A63ezJM+}SvQz(K#)f|bKtAu443Z4H_SzH_1rj}RShWP_CE2x9mkbg_Di~?Q- zF+_6NCvee>$mNWRj7Li##j*Z+hVsm?2?)&Ylv^vo?ql zn?Q-J*tqdX5b`_W`1db6*ZN2%#T;H|2GhOQ0cJts&QPKSzW; z&x1WrZ$H~5f))tMH*FxHmCH?IFXCv(uVpXhX~^qlFA+f%P44H>jkt1*@4xzf@PMtV z=Fl+9D96lb`UvzIzeRxud$(wqp`NJv6Z8#+l5Xn3Uw9D*~`%|IubwzYT0RQJ>htL-T3;h@yWWg zoQBm^>FAY%Rq%NRF5Vd1+>cL@AhtGplg=NNt@Y`1V0$`BqB9GH4UoA01hdWo@{xYN z**gU`WPEPO{n*f-#y-%E=FA`F9JFj0gzZDF$AtG#gD`fPBE6v#*PMTxsK)(b*ik=O z^9W-@>9xHAq5>pf-F}{78?N44fgyP>zoE~`FTD7etj)xrcrsosw>~NkDL}3}rJdAA z;<#1>*XTLgVPcmM9K;CmJ4HLzYYRLX%fpq;%RFE%HtDpYbvl~7Q(>PXdKxjpTn|oX z90#m}Bz~>G#AE~L03%zEK1v`y?liMZ94Q@)3$GqwNLL4nY?x+jVizzZ2w2h57|Zn* z!%GyU@8w(I+-tW}fP$!}XJDDdG2PT=$rxEYJRW}_fG20nM`YKxor^uoeT6Rjt5&pl z);P^{P8#>#k8kK^Cp~5r6~-r8RZl=1x>wGWvAR6=&2mDKomq;1_v^l$J4FsTHxI4$5(#R*hVA;Yc+p^s=R6O~W6~ms?qGx}y?9rm^R?kPYMN7dXz_Ar` z$+aj{zLtk6V}5+t${m!(;{RgTi<0-5d37Pb=Y_`!t%sdTJ(FzbmSoaVkTvgO#x$Qs zv)nqPQRk1zFwgNK_brLj>sN`l*N_*>4tFf|QAA!dRFx`EYvPrDDJ=2s=MiG3IC+#s z&Sl2h{2Mz3ohe$haddCrSlV0J0Eksjov@Cg{ zf7tBgQ^D^c_e#Uk7(LFVvQFL#0D)K=g2Pv)?X|R91We{;!Ze<0B-&eqF$jY5 zGoO~fKNp{z>fr8q%BkQ{QE)utLdhK2KQTL}JT1P-;?;>#b|E8ZgBkMSw z@!?Tf+zlVDKK$uZ&yMfp7E68)K3Q)M;`*&L=gr{jOnm51A5OjJAW|I`CAJNxxz7jm3G2 zBjkkKiORD!-VnF*Hx%?Ym-kYkX(4Am{w&f$Be(=w-@&Z{O7bgWchVoUcR54+B*)PH zVC7B)8AZ$^WuY2C^to~KiqOv8mF(=L^Vd$Ko749b_aFb<0R+!zdn@GX)4)#^h0$P# zm+=lVxQ_1_tg*Tc5CCHCN3l}aO19Hc#zQBLS7nOl`1`RNB?_NA1{4;@dJ0tssFIuv5OaSR- zHW4j3&MUS&CW_Z0cNy@*YlJJKLQW+m^m=@jGCHuwUoZd6yxfZ=UO{Zj;GemHp@n}a zmZ(=K|MQq{%Rm4b%@{3nBt?vTZ6rVv046mb;jaOQ386%o$0BgY$@jqQ#%LhdhJ2VI zO%U&rcBEXuCy3}h_*Os2nXOmR>w=&BGE{Iv?a!FpJ3iPy;=rWdP}gIhWJqox#W6s~N@6ZyU)EEtoUnWT)#EW(DqhE5gxjr0u8L@ThJc=LOj&=+^q97=Lj z3+-?G)kIVh9e{}?7yvOy5k7FaS(Jp|Dr8o^cVO((sXP(YRU?5yQ+`w5S|~&lPzL!e z3vgGXK>kgXoo>3P`E&Py_oPoKu=t~cqmX0Yv}1;?k6 zejo|sub`>uVG~*UBG6N7*^PoVq&>LoHO7)MoZJgnni{PDe8ldXJye`z|3+>s+r{N5 zD-^Q+t$Eg8MXktj-=#80H8T>vkNdja&fS@Uek@d;2+sqrO^bASjN5pG6do-JuSGiD zlmCil)dzCGZ<}6+NgjXZ%ej(`z}?J%aNm!WgiG%!|GOxX3Vrvl@)HCTPtpoJsG`yJ z;cv(~wO@fC|DWWT-?1adm<`AjS&>UoK@ulfr~9DTF)5lGxftpHQQp?F(O85m`n?%8 zW6@MG_1E?c#IycKd8gfog0`n9(T<&d%Lr|7A(Qj!AiKb> zRuoYGs<>9pMmrlAbZ--lsL?H_FO@Ded4_I$S8sqnoRXM(sFlk#5J$?Hg_{x!o{QjE zAR2%BQgw1NS2CaH>uY}um(duRsSzn(yS^BE0W6JEB;v2SEg<{wbmYhC}K6 z)Pu!^zB}v{B2p^1rU0CYng3~Do^EA*md5=|x$8v)#juBQ)F*lxvFGS7x5j~A ze@dIx)ee{jUu0s!Q`L;EvrSW2k{^nHm4pVKLJL1>dOYo2-!lL7l7ykskcj~yJSOA4_Ah>mq{MF3r z>#Mr&pJ18qzoCA#c$%rStJ)DG*u@+&8HRgX>C|fN0vhb^*Yw2tE9~`{X}{=e#hC|W zo*)DhI@v&3pKs#}MQ)FLHCcbF5i1Dp5-lhS$b8-`S`$#?2a5b#-W-yLa+B!7cw46D zQXp3y3?fp;M_Cp=l|L)!4)k4_Db@vq7maM5U@x{x#PTn&aSERr#t9_U(i@&E_|(wm zRH14#sb_K@M;;Z4YmMcLNKO0k_Poi!Fp27qnlQL(-pjK>Lvxu|T}LYpxv|_9{+>8$ zMI_C(WD(T=_M+d|ZGVHBWL(FhIeuih&>B_vV2~x_h>eJ`CFs{-I|E+)i+r__7|3kg z7~ya)y5(QD*o&aO+plX25*MkDkqWDxx64(Z>~zpHfuxoat!)F)M(RCMMl&Z_y= zC|qsmA`W*lpr94lAA%?s!F=N?B7lAzZZAE8Wxq&6vE6 zFMhMKqjgk_nhbG${ce`35@5WKMO9m%r16H#WGBVdCbxF2y0(`@H$YHcs)q;boob!T0Om(QB`Bix9sPucVmn^ zOUQaTS7{M6>nH>DR@;4nmb%JyHYVx$Y*h>ROlwYl@4J^B7|=A6O#iRiB^R?!qF%RD^-{^(it;3cK^+c=tv6+>;IbVtxWsR(V zl#cxHRXSKpM>xV3A83Jz0u(8b$T2)VGjhD4!CDap{ofbWj75*3pCU-~rzis6BukLQ zfXnN%GbwC=JyWBxQkSZ@SU1B0&TTyWjj2-^J=8f5aWPBkHbf>pa;w1kcudL(o;Vw_ zsJTQHa+@jkbx;jQ+B~!VJr$`A?-kQ<@CaNXn~D%#StU&v?FteG&O9 z7O9IpW&kjL;zSYwx4yTd|1`TJBRr;|`$Dhu@IK**47PF%HiF$v1xZzEJjVd@O9Ejy zsn}PbEX>sra@G`b>$Zu>X@1sZUoyD&r?he%Yw}YBD%*)V3h>l~vihIy7_U=u1f~5> z;$NS50*ONBP2Hv-N^jnYs;GS~SZ@_3iP?K7YmTSB8hGy zu-SW-CYPp?MV$aT`kijwd(~on>|)cDuhCx%aQU?0Dx0C#oaiFb7NB3d4Lcm8yIu4K zI3Y5__~6F96Bs!dPA&wDUt945dI+ynbgq})Ml(CcRC9C7s)l~nO~dcuaRZvfKTh(B zRfJWD(E}{ARMx&PwcE@e9{@tvqa*MVN4ckPLZS`oKX(-jV(@D5o3-uq!wIFo)gvu& zafr}(2>0u$-GB~ptEez?#mS@NXZ#zS4GsZ_^gA#C#Cq`Gc8^#2 z@zh=l3<#6{up%Y9xuYtW_30UpTJFrOQ*?xz9~WjsbgeO7KG*gaR6v z)f-=HH?a#{1!(cpOhT(nrZi7YK9gTuJZC*}iM5W9s+uzeJmw)6TE!;cdvuzuN8vDQ7SpPuXzV>r2y4;O))hF}nYJyG3VLmu_KT*mH;AnT%LU2z~ARN%CEkKUuSb zdj^y(61UwLtJUV!A=EI0d^qTx%#vyG@6qph&hv+1kl)Qk@ii3#v#nyK6e~zY)_6tI>h*jeQJbTN z$hrvYAD*(`1TXGEEgD|^xZYZxS)Zuwzf3i~q?p(FSK9E)Tv|NoiVc^K28i2^-cbHn z^x`U-3vqxBQsNy(`u1t_9g6G(zQu?FU{u$^uRe>epgq>B#>mG|h<8$pBY3^%Dl4{-ws2{ zV##DokD4Ct!pRjNrQ0}G!2rLnxIa!+;>`xxt%5OnCn(7P_IRO@`&j2M3b{R5FG)iJ z=Ig5H=QoP=DekajOTOQ}R2;l%it?uUU>R=YH6sEU#aMSO%TWCJLUBmDPr(z=r8U#b zSi2FiC9Mf0Z#(*T^f$uOcF!{?2gSV+i3s6{6ROl2+(X;H`;!H`kJx`eH-Fg8Ic14? zFN$>E^1%D|crt|W0@%}V*5&B4+z^P-Iv)mu+V|i>Tu3=D=tJ6Vktbpb_gBDAdq%~r zM_4;E6+2ZE8^aOAtBl*GnT!p>yY?iPvoWJVVW~o~9pwJOqM(8v7$#?|2g;;vjKDoR zd^ie^P!6^W$N!W8JcJWm$U%s;@V?>Tt%K0u zlVkSA$x0l7-z1+%^Iy-`WY7_NkC`Iq)~iUQ2GFL9&m~_hhs`M zrXIpwmo46hNg4ix*k_>|uy%rAHdJSvLDIRm6BrR)WAj~RG)2#9a}aG2xOg*P=njJtV}l0z4g)z2iQ5NyW4#{{9o%X3(;uLz|s zAL*OF2^zHMO^V!(pN&Mvdgsg%2!fIdnTHD*pb!$n4+#}Q-gY1fg=9%dkQWGCGDUnc zA-M-Z{C^uWMSNV(rbQ=w_%?}ATu93GQCjr)J6601$aKZU!9~-_g8BIZbEhCq3_{7l zPszDc=`j!Q?Wa_TASggQ>fFka`pOp-q?arzsrpJCDD}@3xgx)L6`#oq=E&=+3$Rb& zFdotuF?{j>;l_vwC08k=rs;EouDJvo3FTo{P{S@XrEGyQk>qYu!ixT?t5^onIJ7FV z2n`e+Geaxa7bX{B<1b&deEluH<3M_^uA`ho;*XOfQ$|LZfiuz2-zd_t;}e#FKoQlW%uRENH$L^F&5sA z!n(ZDmFln(^)q3=`jd5DHH@HN2T@GQ0b?rRJ)dmouT97qZQpLt*Qg^>Mkw&AK(_9X zgx}ay6_1p+bESyOs{ohECCE7fCjsHw72w*}?K*VrIuhU-iy(+WxP7>Gn>TdrK#6=t zxPQyT?kB=(&x4kr!07sJpfrL&dc)(k+w)<``69p*9pDB1;|%WcBK+e?AnHw-??T?= zP5lS^qp$|nl8=NnWm^l*FIyXf*yo&>w$Fr};>iF>O9&m{nj8m#e&GK@c?SkK_XN2A zd8E7p5{0OIdIG*6uW%{@V*`T{dxBE`1Z9c_=LQDHlB)`d2!waX?*MH70cqO2xbP6q zA3phpUNbWW*m4>oc&?ourE&&Q?-nxG9|7Ut0^DZu9w~3PtuLhCMPCdA=+e8n?k{=J z8hL*D^RoEb8%W`U5fnk(6M^6BMJN_|YUopLRL7CuR|H(6Y3CUS5Gv(_^46F=^9Rh0 z5Th~U%mqbw!~*Qyuk19%bR%c9B?F8Px3CU`95S!0fJ+YKzoqJgLI|cHZ7tMV$mm4P zcw7*q+nQa{2KVu0TBVZq9Dr*nY)EKps4f}L(xCtNTDI+ocS#dQNM(7GE%c_i1scn;9Q|Pqx zW?bdmS8ZlQ3$tTx+D`;o6?dj+ro}yw#+Q7A!-ydrh{_-o*QUJ9 zIlP2c)VlWtStL#ncmcHE1!ZM_NnyQ;n`xK->x7wbL4Op<2DK&YKT}uilT<0>L~EGj zu3Y67u4q{tVdV}Dxa`7P)eJ_T@Wa-7%`nzY6eWw1#X7tW&O%)2ez z^(!(6#%^XH3kQ^839B+GYQGM4=(q)XniL0$$G=a&5&21fAj_RA50oY)(Ge;wwJU9s zlY9lhVe7BrzN_Mws1^>X<~GGSx2_VGs8N)tk({DpS*?~0sS%`l84QSPG0A#!TMjHT z>FLv>UuIRnvoqTu8?B_9-6YenMhr$!u2<6LF@%i)DCcbG`fVgJ8HrFMbi=Y~4T-6C z+pxA&vQt-a5cbrgSepYOnbd)Fj8viO@788& zF1PI=jl?4f8=)K=p}ikrcsfdH4m(G}nD0mV%}2LUMy56+X!i9{!NHL&!~hl$);%y_ zVA%He7V5ex_5Lq^R3#YzFa#YXT9QS`MbPTlfFw|4C|Pw3Mrsl$U^bE#14P;%8D@9< zB&NW2G{W)mE}f$WCd5EEoPp9ELxqDzUy5;>X({LFP?r>%>WnDvW7aTL=hu{PD;G(qxGZd1@lgD$OyXh!;ov zbOYb!LmEV3I+hP#9#v#ZAX+!M3v8GOtVB-L=-B9a@l+LvWi&k!lZ*4g+{!+J`efIB= zX;A0y2wcbVgW!E2x&mKc>bpbu_tR1?^l|vf0HyGx=<*N))Ykg+q5xDSmH_ffl!-?UUu@{%L zB`PhlU*6Lm^O_&8Az&2i$5wPF`~MtV#ZKhUYQt^AE-3udk%&nIby5*!3Nawc=JP9a z1S12@iA`hI{>586fYw*;l73C03S5TD3;O6oGr3Dm`Z0C%U($R03MCSnr}wlpFbZL~ zwam3eS>A5RlJoG6yOo}MS^hgr=qfO6tVg@e@-Gk+@&8la3=xEACAKhZe#VH$zeQCB zv41PlDcVbf++z#WOl2~oWu_nVM>W&AjEYyqWURm5=WuLd-x0I1s7R()+}uEg>fx*e zB#%4%fNH&z{{}&E-mot=V87BEl9=OIdPTzR@qly9As=ruQ>0iA`1-c1hpZ&LDTjzn zhj3$cC|UIN_jbEKj7JCL5lU%XxYT)x=WVuyOLtvF;vGAhvJ!#Ucu6bo=Bl7wm^^#8 zf+KTPzzni*3Eqv*%?#J>_-mcrUB|8C-N}q3^$I_}|05 zg=kEvrRC(~lcX|@CN-wuOiT5%R`G`Dee++o=>Det&HviMZFj$m!IJj-m5mATI-fk0 zIqE7_%9X+Qr=cK{F9VPJqY9H7%L|d87GOqW>*%LhepA8^6r&Y>FgdY=7-AQr%~%5m zY_o&_)myUM=O+8Mio!qrxAN2?BQ(OggP{gsGh|gF3tz^2$6_1*eWSF1;~OR)=_N`% z&Ibkg&!zTHZVs6@qv5b96Y0oLr6buJ#Ok`c+9wav1gBNxP;ljJ_g_MPRZx zr>Vu&)s{78yb960BP$K!*x7BeALQ4RX}xr=QI3FBO{&F^9sH8bj1uO0liY52WcXfs zf}@eBA>;tMh8`zR?7*?eWZ|xi$#Q(L^um>+Gf3Dquc@7k?68SvB!*M7Urt5k^|0RZ zuSyD$q@y>tKh0L#jc%Jr`ZgGuPhN44=WAkv>1&WhuV;l1FmSbx97Y15G5>_emr+DtpG??R+Sy8I02qm{bjQzeH5W;0((-CBfcHwPvw zw{?&`%|$=Mlk0}pB?j)laiCk;HoAT2QKg-s`jx?<7$ElZ($W3(^oA6S@zl%vf#i&^ zL7MO2o)V!Rh6?lOsF#fvI3TLk<}LbdMJPjh*b=m##xE-uX$hT=~^BP=8C-AwUf+5^!FGCS7-bm4dvl6+-+r*RLjqU@IQpGO%~;(wP2^N^K|I?LE$Y^hMe?bl z%)4-vC~HWh;z&!&Cob9)6+(I+1%+ItxcVptFU&R;@(^2neZNTD*EhB3&bUO1%FQ2c zDhRYwjD|qu`6hvGtpYxNW`Zl8I?-v@I00xb(HH`otFKSg`{JGctdgnY7h6TD8*f-- zsKHT!g3=+J&AY&4-D%Z{3)fO7HLHY(xo&jA%Q-W>>@$dNVB)=w?RdI5klAwZMu?Ab zH*5eIn( z>V;4nvkQfSKTLOOf=`dFBg~$AC4R)r_DMeJF9%%J;Mq@N1nCOub&{TW8Z?D^%26~m z3-+<{v{?%HF(@dFWnF>0PhGJI;qF_!kU39FXyr48U4TFFq+Q;qFn=$%Tcy>;l{VQTOcJAj?T184kP1DQ=YcV*B9nHS6_6fGe z@=(Lu;4X6|sm4e^62dTv8RqWg!r;VcFq5O5XL!Y86bLm|D!hnsmf|$N#!BQNS!k=` za+4D)%Ixm{!W3Le3*NgxEiYG^<=u_c_qUhrN>X3onW!|v=koAwOi?qp!9~Ak!@_1G zTU&Jr9Kd+rD(lmf@vW?>hndn`rIC^WMJSq=%3O~uI5e6+Q6CN^EWrH-#60?*H*kN< zYjth*qbpBwu$}R>%69~_g3s%ke+ma7e^$Q_)8!BI$hWrV%#h%5#xNREM8-QO!=K!P zaqpfaztm3o*%H))*wDm|v~t+U=pCmzscL#wXaAHQ|>vP01kNVxL3+S5!7LRtCNki$Bdf3r)vcoofv4l;?4X zmq~$}XMnpVk_B>4!=7^zKxVM!eM)E{@tsXRtG<)n?HCZ*86#SNezH?6_L z7Oy&FJ-lJeHyWRUPK0cZpYi~oYqV!S0ar*?u{zx+j=bh7NzK<)aeX)|G z@My2Vit!1aKRM~#E^TbZ%5{^Qm1tzbhbr7w$+RnEOSr3rgy>hdoo?Bz!92B$wROlJ z-u_@IRz2orz|2!GicT0xd?kaSYcDQar|3`f)H0OMDTvmHgMMwx8EnS~$)U~~~B(h!N z(dQ?>GA{XALMhaeCU!u0()#h3t*B(qd26~2&l6rKhh4ROpm`zul5Nzt-@9psHre>= z%qOVAcQKNx@@Sq*Z|2rZr3Hy&7uLbQt1o=1w!= z_n#Ds(eS2uTMVrKSTqaU($=o($I9Y+Rm-(23ySZ@Y=m2WzhB-pxDG8Zed-?Au*u5) zsprRs%X;1y;rcJ9->(V23hCK-wux|(TPs_2x*yzACb+A`vf9!Y9sZ+^zG;V|xdN>| z3SPY+E}2qq-Ff+tMe%LRmEhl>A+yl9n;NW@{28s7ve`NUg_ z#WWhmEdDWxU`vSZO)Tx@NOR(LuTQAPCY8h{&j|8k=SL^L2gcbXB!+c`#*#;O*Tg6p zCaZMEjZP-iOeGK5Bq@H0eicB}G)1Iat=+mDf0iH9p^`k?tJ5=OTQTK3u$=s5it4S( z3%_NFabt>|2@jZC}`U_&YLk+Qz3O}FKuK#4bqurQIo3qEDBpCkz?Mi z{UX)&=EWDsG}QCRcCn0%{N!S?^wau`fXGxg(v)bw^q_hQv7GeGy>x=T_$bzw=b|q$ zg42YZ+@O6KOwf3MKstG3(p_&XmN9m!S0>$N>cdSEAz8-Nb8kBKjDw(zXUbVp`^k)n zs;uudu8dg;6ZJN3SQk<00);7nhQ#H-xWV|e?HsgsIa$1PV(wW`t_0LaArYbUUP@(! z=BV9G<(AN1C0DF4yX=vQrie9x=10zFfOm3dfO)Ndvh3m68htcQ`=Pq*xgXh{8SJZ@ zQRc@xllh9f5G1k&ikma%TbnuN(QW2`c$FstE%=3THEv0jz_(W1=u$n(nm`6ZWW13Xed7EeB zQisW3o34`Ms8$iyM|6Z`2UV-`xXU+RO=0DTE`|nLht!c2)nV48hPhNvO%dTvnMIja zEyvX-_BU*FmTbJMPn|9&nt=YYCRp7-W8Ch(3OT6BN~#U(CHlY+z7^XL<5K8#P$Ab? zSnd+7#?g3^pq1%GkmrTbI|p-&O}1b!Z4GHqDsZ7UXriQyd}dM~cb5{yp58>2G)ga-S0NC{zzJG+s`fAIdiW+eRK?)yy1jR^~ z^IC0_Bjl_0ms?EEnRf0+?i#m)f1o`c(ZO?Ab~s)AGU3&R$?KAk*DE+QmVB^pbFYoP z@B%X+ws6=x1RQ~ap^z9xUTD1i3=*ac*ti!)7LuR@0k^6ksIkUqiy&Y&bf6k|Q>~&V za7JLo2XC*y$Iu1RiGU2x2$bglfyq6=O+BGAJ>g9~0*}SX3hd}6>^N)9#~4atQ*ZK2 zZ|Y%h`ao|BvNv13FW0p%U$U1vvaeXOFBt&ULqRGz`>Uxjv^Ib*)&TSwSo9J7Er~;~7;rZb@W~83a3y|k2FD{mo>16dZ~3%^L1~XhTBSxS3o)`}Yll>nMm} z%-5`Eq-mg$6U>VoR|o?O=zvw5$JJ-YHIE+CALH?W2~8TXqT7T~%7jVtgaTf#{NRL@ z+XUMN&`x90;prspTt5nT9N9eSN;BwwG$}jS?>#%|tMRT&a`4Gt(yTLlGOv+oNjSF- ztnKl}90B{=MzCQG0lmTd&Iva^A0o+p>uR!1RJ`tF=EZ zM!&iYnXWCF_D-7ST%{JQfSDrT6i?xgMeFGe650yFT5Xo9;r{^8C>sk+};=9 z_4ufdm4?-fxDe!6V@xJB&)2`B8jmSjZTMRBVfDU4Sh3~y7M^lOaEJVeMiJaq03Ok@ z$JqA^E_hxAj0FN9<|D{89|cE_a?FnM;Eg%Vyq`_UCHey0_9CcnY;2sJZYi0=9-6~1 zZPE#%er$OYr~cRSW)}Hh%Nq$VjeuPO0k{Z)Yye>4kfbeQ2v9Ku&cshk(Lm$PN!`{9 zDYx__HJODhh_y6H;LoEXN4k&jRpB1|86OR-33{wCjF5OI2qqSkTr|!RNG;h9O*A4HDW0KEJ;;dUAL&>6f24mb?=4Uy#k zLfc+%C}+M{v}9O?zg)&)|GJ(jE>(v&)Z}Aa5aC`H<^I9Oy=u*TIV<(Uw?Ts(Zgye~ z7M_FUam*E=`jzh*%Y{;_?;Td+KjaeKt$czGyBK_^N?oZkc0l%6r#yKCgWY_xRx6 zx|XUC_aT#7_4}Cn_tA$BB^LY}$KO&O9lVzBq9$vT;cH(szmc1w>rP8^e_LdCTl^>s z`Ee7z4*9q|d;9gCd-xC84PpYb^k_SxpDVl zmEt7(pH#V%)Fx5uPa3UF&VP|Vzp;FC|9Kz#Q}Xa9Z`s!M!6sk+4|R?$H@Pk0VT&OvDsQ9J+@t5YwFKyVi<_k!k7ev=%+bC^YTYB4|Y}?{w+f-}Yif6}ac-zin$Jlb` zdFzf&*^cYUj@tJf&*2?!o?Xim40PKRt38O6q38cn-dcOH9(#|JcVg>a^2fc@lfC~- zc}wq;=(e?Z@4A2ZALR`@sN^}Q*82Y_@3e!4)`Q0k=_BR+8g}@G=dk1Bz8@`;ME0<+ z^>E;k@;*6y3p*O&IU1t-Mf3*n$YT4SZ2P%lOb_qOo*aFmdq4kTXHM(b&g1wi&(2Eg zvBk&ZZ)w{HQ|p{&>v?kMzhpOjd8P4^!&v*5#p%_5lsE6So%XeZ z=k@dS>qp1i_0zTc>Gh-I&2HFO=WLdGcLTWv8gBXBq7?N-J5+i!(>@g&}C*+8maJ&=ZT|@FIxF_}E zc?#CH<%IM*ifjnM5!8R4O#U0cgjVqINwm*7ntV-N>MG{RRXz5i zS@Ck3{F>lt6Y*qIz;)Bd*VnZvS3vRAsvR7!nBZI!r@7B;p2)Ax zxh0fB>%1Wl=tX2&rv`B6sFkj(eUf}3@HzR%ST*CTh9C$zw{_?4Vx5&N+1U0JjK*4- z${+l|87B6CSdLxi=T}u_&hM@kd*wdK4jJfne@NewsPj0$Yc*2GfZ}P%H3Hg-UOQt)pu9i+X?ue=9B3huCi-eQAq^fpC{pL~I<&B5FJYL>fW57f0AVV&? zKcJ0)^ncnoGuB1eE%F&eE1XgByY!CwILZ+;!^Xu%b(k8h(yM*C&dMP)MS)_Nei@nH zXDxoJIbdwvtj7Q6rK56yfT-5fC)LlU7)0fCG_!oz`PFk_nYw5-;8`dofLEH|q74`p zyO5;cc5{go><=>31;)gwwE1*O)A)t{y3tBPE~F5O)nPA5_yaM&ssLGSE*cb!!LLsCf# zD2r3(TP7OC^nS_6J4#Q@ zjo2!>$G)yw_@uA7CDOZe@z*V2Ae9j%^Jj0h|HYSNS+-HO?0o-8(f4vC#wQ>bGT|Ih z-1I%)_}zpjb-p42BNk8OPRDN+={|bg{7>!a9tCRU2|3G;VKc(wfK3NNfKKE0fLc%< zwua+uR!1@H{E$)cPrz2c0qvIX1qhS=$ znzGcN67qYTcvurZTmneD6L(jRIWFhyl+SmHiETxq80*$ZA9Sivot?x1BEyO&xUYD) zA-<>sJ&Ar_%sGLHmmDe~-3vo>3R+UX5`I-FRq?kD_Cx9^sn9BpTo&S%%h_ zzNLP}+gADVNB8k4{kCXKh^k-L);M!dLoh*OW%`sPjFjC)`>C2avMQjX z%aoKH2InK{?8_`-y|cP@+~p9VVX%zztN=!xMnZZ0}U=(DG z!_t4C)>e4o{cGFy22uNcMHvchUAF|PlWJ6{H3Tr1hqkyUY1;E07*EEwB=2L?uv%lp zmaW>0Pe{t5X}n8os6G!cJD`<(-qY1K`;EbVi^NcJi>A0T@X_y#5p%qo{RoS&hgmfp z(gv$0JlX`o+$?mW%5^^Ln`cMwEGhdqVX99;J6_E{)r8%L<)sKb?<2aD)9lso6?(|wV0RT6`}z;0sWR~bBEY%9_(>Gx+W?Ob z8ah>gdHaT?`hK}O?s$zQ6#<^xr&yV<5fAx}ewJZkfP;~0)!VEoqKS^XGR>mkf#B~s+aiNj>2CGYH0m)W* zd>$*`mnuLP(?`3-3l*3-K!oM~X8m@f@8+BX`F&)&Qjp{Wk>uhXu{ehrbc036(}jDQ zUsb0cvcwh4J|GLt7@PwzN@5EUDG#VsW+>QBP%2_%;)mG?;9jWnD|KKN?L=7?@bpL~4ZMS#NUi1dZ#3 z`)5>HZ{2hWnzZ@jpEGK`eXAu@ zhqDEL9#(7E?EloiSf~#VsB^J7kQGJpLFY&{REJW2x)N~x+(P>-M=>c0YH^+ErZqFk zP)=8mO76Fi2Jzz6`~k=11#}1W5!#+a3BMHEK}BmXsmyBj5eiltDhc{IuvQf-bG@=m zBb!-g>FmV#=6ry5XiXN-1vBGFGmiV3flH&dKU*IMLbfT80D$M)7!#9~ zpw#hSBMCr_>nyfhpPm9d#3)yGt_CsePa$M8;X z#(zJM18$3ZFtE?m;6FA*Kgq$z-T^O8D3VMeNtcl?pr8;Jqu*-7=Kf#Z+^zp7H}~S}(e?fT z_GlWrH~4333Hx~&yIzl7F8uTEHFiD*J2Hr!euy1)!1n2%d^`F2_3PI6EgX)E6L$Zj z>KAmUMtr?t;yRor>^Kqv(CO1~szkK?eW~n-NCOc*<3P*jXU{dYRo16xb^ z-{{=@d~BM{j~e#h)fAWIbjx+7FY9Xh^79(nt8s2F4$W<7XsB#1`7bxO_P^ZR%F4?B zoz5-GthDQ}{uj#4&dtuq$VkPcrX*oP^22eMZv4}D!-9LCqvH}{F|o0+k&%)A<>oqB zVNLX~YRWri`W27Sp<$soH#aCK>ha^p{sB)PJb3W0o9pfE{V$y>A6+hmYWs)I?NEJO zFB{V4gf6WoKtcAP_7pEKE#H|F3Q?+5aCm z_e5<@GEMA!e}=K7UK-CL%;@)M~Z6;3+?Y%z5Wo$Z&{^RBvzOKJb_?eS9qzz_XoD9^oBlL^0&Ov-|G2r2q^Yugl3HNEv>E@n zxi#C*++qzipq?XqJNfRfh)bjgQ(b7}{kU4` z_Q~o^1}s{XPdSs!LGHcZ9cr|KW=Wlx>MrBgCWYMhu7qAY&j@R#3kHN~!$TX=;_FR^LPiz12Y#27Qy)qb)^$LaGn%KR3 zIPckU^uo@gR-+VYZgAZ)X{J*zv2^(vJH`Co<~wP-w}@bK3X8k!#n1IbsouNG3u*-c zVWv;Ny(L*GSx-U^aNfZz5-s*TUMl}Zdiznh%j00ZlN-^*GQtscof~cMy}No^VbW4S z>79l*f?%ya_w7791l~4&|FX1l524U`Vy$rYt9{$Xn?Gj>82)Ox%Hfy4R#^|^GrOb| zi$Jfts)Cd!Lc%e>!_|d*u3qS2nXi9r_;~z?XxE=%#G;gc`P21+Z@}#~x{@}JITD-9 z*ZqN}XxS44SuoQEUM50A*1Nxncm~Y;eJQqy%#k=?h=aa`cjXjVMf)s7G0#9j`~zYG z5q$=RR~%+!8ax%ur|@8f%>*nqE2|Ih#y7MKzoQo|6a{du#v3MzZO(N>e*zd5?@48iE=Mr*>WfH&;Vz!hjnU zwugt>68VMXsrF+*z@fMNaTQhcUWjQ_j8a=OZ-ggD3a|=}|2Qhw6EqtBE5wVlLqj1E zgbJK%Va}x26hzfv0hhiF`h4?9Q&U&Cs=|CO;l2CA)ckNdk-lJFj^$6)L2nW)&*VR} zEl5Jvhxmif%1o)NkfsbukMmmt0dw2gav&y4*}+=qGYB}TF|Y^Q0}jYxsdsDIkt}mL zPn|hc!d^%u#P{7;vX3BZ?6{p^dsbr@X05(As5&8Cmd%;DsFTBy_<6xqQnAGlDm) zHU~1FID4ijflEL0f0Nt_?HAg zv)M-|gNcApHgK>EXtKH0^pONCsW6q!5R*NlNU^_u=&y9NW=M3;EdS*J{=3~cSh#HG zYs%TCVbUg)lfU&lwk-d^PvpA^L|-~qXghvXtc30zG<2J8B!od4o>UR7f3KM+*K>WU`cBuJ&&2NBbLerlf8csJ>W&nSlIVs;57L_D2sARS(Jl3SiJWZ%y* zd5M)bdttR=k~m0*Tk=hni%7hq6RA5!bTDxT?(b zLu6Dig99$+%E7XSQ9A^RV_cU8ncSE)IR_k4e0)vW3Rc?M?)`H9OoV=15&IyEs>_S< zen@W3AGYU3zrYNH>x+`_X6VM&NG+W}41vA_^h16m5w1837lmVSm7c<@%Kpp3g^TQ} zP@4oo6kg?FTn#SQ#{4^#6!Z!Wv4IPgw7)tzdi*pw5L21zkDo~3gZ(g|8*SLE4S8EI z%$o$C{09^S+@2*<0V8SG;A05F7E((|rWrW-s|`+DctTv2KRn~XZg0ViFYB!V$?^I? z^EU8`c9el3D_Wev90n9GBeKookggO-5rB^QurDjX;(-U`Y*1MVYC;0Va@=9p$6q*P zloF4b&ywy0o~=uc(7k#1LFUyY`l~;%WSA75Z?$=Ur6~+oCH5?=03pR2Cj>f)4bxQy zX`n|Gxk0G==S+YJJtJ_U6ddtTnYn@L>F00ymnC>%zVGj!J-Q0-=nu)8UR4O_%Kvl5 zQvkp-UWjkzbr*Bs=1bt0q3Dk0M4m7(%SBFH-Ms5XM0p``t&cnwu=T;b{91n8ZlHK{ z))1i5RTW_$;jP8zszlQVy?O>v=1 zapC82sLnX&Ecu#@yQ=5f&G~3>@*>cn2PHA>}%W zPJPd2Ck6g=LaM)dQ?5^>6oorxCO&V1g4yt}kN%pt_-2;B5yW>;#4tjyhpusbxA_9m z<_t);k-)^UoWu#&LxdH=HiuYycpLaSzJPRiX?{luqZpXV3&@ z9y@3sVfQfcAfX52X+RbSEqI;e*pU3wiRaJzo;w&%TqWbWFZn7eB}O8o-yEa){i#__ zNbsG+$t4V#mfIUNy!%%o7tP~E2yk=DSQr9`LZYtV>KBMRc)KBxvFO+;RKRvLO&J)4 zj5&fvxW-}#q|+_M5{Yvqg0b{ynV0F2V+v*x#+ZAllN)#KAyjXXu+AnDDYoP+r~~;U zGk&+2!BK*O^Z4z+m^2MBVa;@FEf&e&A$YCkNk7bIxiT^XEOOf|2>pn5o5(VnGB~A^ zZ~RI#)XbK52BVsicg8{oxYBKYXG@)Ca!HF!ZCRgI-Q^v-3-+`5&~8Iw2ET=41o5*) zW-|;KGP6yS^}%>3d+(6=%v^$;(sABMzUA(?Kd%c%IGpiEtMa2P6d2??&(Qm~K~ zvyy)Hiip0#EqAgc+H@r2c~CqrLukM_XFe}!Pi8#FFBklmc{2<-;WfzPDlb2Ve80WC zC*L!E-p$url6u-lSb*INoMK3rW+>Pl=jf5nUjXI5%YDWjgvzmS8Vy2t08ocmQVO^1 zP=@rkxrKl`+W|vS7frT(f5RfS|!Cng$%DsbHxjggIWR{fz>r|F_q#W=_1{cqH_w|4|bq0E*1{X zV}DR0kWf-VBm(9rBjiYir5E$=KO=dCs3m|t7ja^{QC?z!i;r*!y;AM^E&$>X{3KR+ ze@@UjxYEP15+~knte3Y-m!9Ra3Iot6U($Q0KwIR=q ztI?L#as2#)*o{gV;tJnj79vDpd9fKeq&(+;I0 z;>&6~FX|>8Yx5p@P3%|KPCS3NU%S$u7P<-!9yV)vRridzev?>gj+lNLTvu~Zjk!^` zugzle8+=#WY3YKlEg^5mvY}(Y#%I6bdcX1TdHqsEc6bwLY`?%HHYOvZ@#0m@)r}_L zQv*dv{bB-hJ`vuECFy;thTZ2)sNp8kPgUeMo29i|xOAGozG60pLb(kq>Sv0LvID?= zjVi<~Y}ncgj;Afy;1(HJ^T9sLgBy7CGlAtm>-eTi*j}AfSDW&hJ?{`rwF>)G zhx+vLdbWb=v40yk-d_z@6q0G=y6~(e}9{UvDvjhChNy5hXPuug_qA>D+}b{2nVY zRpRb_Gt~^2pf+_PoQb>KCl3)-aquGwHteSj?Z+u?H@f?omit+*`VmY6>~aH~)&tz3 z1HAbI{M`cr%L86_eR$vcwnnMm z!1}&jzSgzw#SuFDA-%>^y++oog6&J?hkqiw9MDU zSntM|BVSd*0AtK6udY|Ya_wPYtdMI_zI)L%zZ*A00YcJ0!T``c1tEU_9wQ8C+|On9f^>S%~a+lPD)*j z8q`kWR#);F@W4uADRC2{-R-tr6F-dmtUw^!;wjL(ww|fU!=DGI*?I@#mR52J_l7AOEeVI7L|9o~ccqVjeh6AfN_u*dL^M{EW_-30RnT=T@Ar*G-aOC5DS5v}17gi~J6FD$>f4vk|HWN;LLIl-y! zHxap@77QyE*sm90M+-35dF!?3_?Wp(x5cGy8kIK_*h7|zK3FT9O0|h7*B5XOGrIqI zMyLLrhu5399_I8eFnD&pP!ld-Gb>ck#zINZeFBTmffHkh@^D)KUPe(i^F;z5%aYy| z=u)*#60SbO-MwUt-YlWRtZ)w-0g|K@$tdDSkcT2DvN0<0`lxHO6kCwyX+t&SUdJ?S zbvNfNGHFb?eoP|dy{ROXL=(|70Mz59_qt#yPxs?zEa~!~Jk@frHh^iq9A7p|f?GYt zAO0r=5N0%OCC`e7A;`l_e@N2$bTt0u&FAYkUvBr%fP7!$^?y9O`1qz^;%$$EB$BNE z1fq9Bptk!K;Rrb3zw0Xaav}eP=wQ~6bVZMO-R0;@M}JxvF5wjc5L&@gnLnj_!CMR; z&62X`;8Ia=D)ChaL;YG-+n1rFC4glWA+#Lc9Edu>Md|9_0}ar^mB8h$HAC2FG1+I| zr>BCSk4x}h_rZ+%Hb#cmL{mqV_1E15*Q4dvZyA*`iogR8)`?iA9aSVbnwr55xx#ruBP%idpq2QVb-7lG%a z$R34p+-lmghEusB-c@)bt618R4ZAhdhfYFNi3;%ODHreKO{(`@BZv*0+?&VZXD`I? z#1@B?K*DW+Q5J=9p`uCK-8a+6Z^@_{72sT}^NT`z1TP%yFyxg0BtwMU=fjQ^m{5`> z8&*t|hrr(S2aXRr(8HE53tn$aq_q8E;6vJfCi6Xgk$$T0c0|d2ChGA$?K*?X zZsoeTNXq9c2f^p?Ne&q5fWQdIPx_+Z6H;(o!NT%wrDwm6WkrCM9^V6uFWTsPd`ACd zmN}BBcP5J1fxs2Ow|E`?C4AET>nXN=ze@fmD)meyq)P9}H=?}7mEIrUQ{RW!{E`p< zHJ|@$|Icaa>tFDMPF5gAHKK4-jgh+#ACw)rvQALuMrZt|{u%2NQ;aa$Y z)w)&HFX6Gm3dzC@Lw&Fu1eLVyh36A3uDDeX&paBY%>k zh=q#D{zQEBGDDud-{;B>`}N0X;j45ko!rD5{Qi#(1wW%%w`U9%WJ~d^3L!(iME6nG z(v8=xZ`;*&p-3X@u??X*fLBn(pqXE8Q$OfKXUS#KRp4nI1 z-Y_15H(j&UwymZx1Np?xwUr?~Mi+6=ZVFM%^NSkGS2<1FMXuMUkgMO^&-7eWi_{A& zf4HMdJ`>-cV)%;PC~NbWeB^OiOL9?Veg(XYaZ#>=T`%ZMD~8@#k*s_8e5 zIhv4ojgxPmA0=Pv*MIj7h7S;oC(Kkr!|w2++(?w&l?Ua9#(VMnv<=%Kp=(?4ME5{@ zRXV$9qejXS%Nf~=K0J!&#DY_^%`BP0BJzroyZf~yGTpQNtZtN|BN_K~>#1$;`?YA_ zY~+M#SGZ4kjh8$sCz=xJSx(X|nueiBk>Rz6Eh$5~MEdAwL#G^q1{;ytb`Qr~0q8!y zxS{R?px7RWGUwLH+xoQLt&}$H?#86ER zQbV(Q5+lm8H=o}*b}nc)CEzLG)kE3_j>)^NZ!DM=DR@bgm?;iM(>aQyIi%~k@=98| z)yTf+HIF%>G(#|MX-%hg)6~e(0L|iqq~yWrR^Jz{(dKToM>_Ggf$`unaY<1p%dlVa zq$>qvca1-N!vB-@IlqsT$N@7lpZT7>R$9y^ax$Nu>+xr?EmkX_2}I|&FSK{p9TvU2#9bJGVIToSU%hl;(&0VLZnQvCY*ggjUzc(%c|Re|gQBTlGP3lsk+I4c z5$w>L!qQ5fbH_klnb!-CeY@`@faxEM7afvTN5Gee)DvzdYmJt0A4Uul2^H_D7jtiy z#3bmSm23zb)z9~%5)suNeI?`?q1B}--C1s)6k7-T_RQp3fCTf1$$WI}wy0Zb%L`(B zzcJK(rx^B^E+C+HRTF{B^?(75QwkJ#k|fPN{I9AN`{D1 zQD&6R>hB&TX-glPqSQ$aOe?}U)*64x3F+Aq^^Hgwgn~Z;Xj(aZ5JZV?QBI=}d!#oM zqL(@(C4lI?BHAR_LP3<9M3TdBFA<_tQ8H)W$i1eJh;|&<{|00Hqjx_?1nOWc^D62N%B{cJA4G@htK72U=B1 zaJN*e3Wi%X7+Ro|6dH&&t1|+dCeNoePU%3KL<|Ic%jnI4K4=>#iJWtYY8Utj-c%w2 zW*ixzYyFBDd{2E&rXQC$ItQGd!5EFB30zLVk`gj)+RvjCo;`HwxBT!DV@$$HMPEUT zaLm1n63fqHtRb}GdG;;Ip7Dz>nEYYFB;OJqok^#%=yE?Ekcbm~QDC|prDT?sB-%Sm zR$ma72t3S$3AN}Tw@JGZF6ddt_j~t+WAJdcJ3QYh>5c^#K^h$pNeT|stc=|-Zkt=Y zbL)EQe5hDcjVzYrz-gC+NKgb%6KkGb+y@Ei)Ml& zZ?=ud(z)c*EqUTnNzXuVewvNO!+pK7H3`>ecXg-(XJK4RFuR;#!D{1lS+i(b)JC+@N z&l*8Y#dW{P#@pq=;U{KAd=~6mBI9XHrli^65bMcLF$cuWc#38N)l_%ka>%D>=?^2q} zhK$~T?jYSGITwbC@RXW7cI+OiZf@l}b3iX4VL(?TcIs%8~ zeXJ*~5MKB2K!^c=g{cfcACR%?*z)c5P$`YoPgn8 zQzZ=1OH7t1H_O`>bdmXZlMHnhy0i`7IGHZ<`r(*Vz$4)HP1PNU-jDtKmA6@TvY+vr z9@PrpGokL~PkC^g<~=t2C3vKK_@k9M`BwAC$s8Fmldm85@mnd$1g!tvmsT=$^Q#jR1Q zG7r=M@4_G-Nhgaq29gtF2Pntij=I$(Abr>^n5Z<*sH#1sShd%N?n8-*s|e%2RPLtC z+Qrx8RExl<@-4sCY8#S|rZy@?#Lsjz8OoYaOY$!W$~Y%!8fJau8y1io*4C8~I#hO` z<|Ezg=)91u`HnPD9c1=Yu(nR3IEUEM*YVtn{CzN7ayhJ1KJ36bQgM*RpjvM`$dcso z>ei;TA<1x7ACzqgU(dJ2Q}v~n^YGoa(GZdmp;=-{*MVqFkO$EIzG3Ft~sV18}CrWsEl<8l`AtIcoMl0%M>e?t7`=Tim z(f75Y_M;|Et(fGh@pw^S^S-#70LoeqIg+ zz|>w~^7@5t689TrA@P)cnet->OJAq?{+>@JTE(S&+qAZS!2MKO5E4Mh%_ zh11MZaLrOm%)+k$`EwN2y;<4-Be>oyO&HG2HKM;edt-Q(A!(LrYnJNsEDL0gpc+LK z8No_w^s6tH8aj7FVvY+k#~olyX%p$70`Z;UW9bBeNvRog)L-`Tx5XB1_DiS;ee*=3VB1Maz40R>O-_G!aIY5dw) zc?q4W>pu$^(kYE`XqW0P;d20shVt4j@YqdjeLml5E!dO-qwcDQUOu8B5f7+o8rQ4Q ze=qm+NpYk}JrGkJr8xtZnThp>g4}7SVJ9&bIq%|m#|aNj8LXHrpix}^0KM4TlQI4x zdJ86R9@0z&6d3HE5mBAvedmWwFAaeX_1m18dX*vZIiSE!{0N$iU$U8xuhL^On}&%9 z{5uH)d3k7dU}Lg~d{75445^%p%NzwU%s zd#eRfn-!}`t2$G9qPL$Gr_WmBen>hLkx+eeW3*s`F*i(r)F) zCw$Y@{b3@To4vKJF^#;pTCb%x7xg60zAWx8#G~SMT}#2+&+!y&vCCf|_rDbI@`!*% zQ6}nNW9(3u(|0Xe?v+3Zt6^-w8hm>7D$SOla)nC4g0+EYEva_!NQ3T0Uq_EUlESV6 zh|sKlmqs$r)XPmFHW zaHozVqTg>cqdQqVk@$nMa`IW|V=dbcf?4=6&{*pY{uKx2!!-d(2YlO2is^X#9K@87 zd=#=Z!`cAp9Tr$gvQ(rk*@Ls`8p9pcQj}Am2t@E~R6IVkz zw|*O6Kbo9&%jn%^qT1HiBO5`5dj$yL8zyLyCAcXPFxT&1429}8Y}u+O#S>51j0hSN zY^(P=3fyS;7PS8GfnvKLQ7;jY~?4;^oXPGV=B|CyIT(ETItL7u|{eqOfc)JnX8|V`! zOG#HZbi8^G#hyY;AAGM_V-YJht5}ezaSX z{G#;HCPLr6Vr4sJh6W7VL3G8QGJZ%J+0*IW*PY&X`zF&Q#FEjwW7pu4l`LJLX%*Ay z6ck|jvcdh;&)tGv54XM5wS|NClm{*=pId0Rdw+VME8|0M=|uRF`*PTLl-U=&NQ){= z5a^2zOoR?lyc&~qg47(gy*RY5^eUf*u75;E`+~4*o&7T`P6yV-XD2Kh_ z`{OSo?|Q#@Z^siH|13bC!7ZYBBO(pAUp_j15Suxy4!xV#G)_zU@XoR3x<`E0)@#!} z6Lq5X?#P|6&ss8osoo6cQndtJ-@uKVOu|K>mo*5qF zn-k|qkEaa~UV`H5|868bYhuW20ijxPjgoGR5uGu6~Y^x6WkhzG}Vy#w>MjS{<6ZV(?(od)NCBivf{_AwlQ~j`B6&=_ACzndkV}B9P3B z4h3z21xqE7p_s_H8RocwA8zsB+yW?T@drEMGa8MDKePNH1`qj*(6bQK!ARj%*duj= zz2G0dfnzbkfoL-G4=F&Alrb86DqVDDQS{TOK$;HXkBGBxinttSbvZ3Dp<(CUxBQ*{ zOE1iyw&Ssyk6Xm3XDaYvUnqi<&Bck(lk&hjPvpTfXbHuQqUhTt)c(x0{w4imkdUQV zksJn>&Jrd{H1mE*bl|)i1&*-sFX)crYW|P4_C;SFMndF`s2tdLio#Zx`d-2I` z)^X#GUFK5UYgIJkQrvqFj)>i$JBek|&&y;d%2*~KOB7I{^SB2*<&{$9(MvO!9XcTd z0e(BL__<{r*0r8avLVI4sUygx!zWYIfn79&Xxils&(FL@qHt75T}>PYU19Nz&1!(l zX1(G*m^%W_?Wi0RibP|{&IxZjaoepI)%Z8K)v1pQ`v$ZAByK#*ayelj1SoG;xcB+B zzy1~KbD4UAZ-DcAJHrjm@tvy~F&LiU7M{>Kp72v16eTo*y&C8DE zG}a+J@)~sutIfpJd16X~y2{ZMC3PTfh$Ov}ugk#h*u|+=8Fs%+P!HGUnJQF32QYXY zf0Tau@&wuvxEC2_%Uk)W$1h7{uIKR58DiJH>Z{tiH}!RMBKwvPS?4eR?rA}6;T%AeGSZ0XLA{Y#`S9g{sfc!a& zo@T`KPYScyKSXlp!6`UW}g}tXD8aZul!mRdx1tQ#?0$2F}f` z4_;st8#`>(tsCQ2A-ff)|K2UCTfKU>w2xoP5r#@M(?fWKeXM9iNFLm+wi!44q%676 z&V$?Kl|Uxjx?T!)*8QZ_6}h5U@fLZR;~&)kQ@FX_P(5=_&5m_;xGg{L$_>S@3 zYag}AMX>_$p>eUW`-}~m))|pR8uwit|GK${Wueu@fw__W$2WW*A>yw5H2DnEE3o|5 z3KznCoCgvorbmXeGt`H?B)h|64g)YzCO<%FS_wv46v`ahG(%a`4Kg2%e|7k6UjM-m zlK}>AQC0Bz2Nj~ zQcL})aV)9jYHQWubU(6Up>5{$%K?qTeJywSC>@nf)ub?@n|rM^g3V z72;+?MmVBzwB9p(+Mm5GJewABd!4$CtJ>!`K0S68mW_L8v6#%7? zGm5TrHkCAR9K*B?O2CLzWJefO9DN&NY*B2oxAytN!S>Bk$7v%up0fSP}Y)1IUhYB~YYi4dgXL$XRIvLkX<^V?y3FxV?QS;HV zO3uusfc>gJZ%&Y8^rwU@JF$*o`t`}_A+~4AAxL=-?C@^OSbIxA>X}@TCMn%}?pSf@ z((W=CEk)Dc;pffWMe99FlN@bPLBl>gmW!R&g2}0+c5P7nDGWhkX?u%&DeRje4*GRf zQTvF4epiU+`dL~Vez!3zYr8Rks>KO{^Y?XhK6TV)r8bK>+ujh2EYqX!Z|O}+4UPPk z5L@h6$Xvm1pZi;5!X81h(HyHt=a@?al#(0kHTbvlW#`yNtF3sY(#~_MFhemMnOB0r zSPs@e-bZXPlwNn8LJWQnY&FdJK7TknXof_=yUGiM9o!hxBq(z99Mo2~S*%iT9E$aj zg{OqhH8aMVD>I+`5DwG0wCgAr)_Ffxrh<>90wS8&?tFW55|5XNEQw8qxgKiDunKH! zjg8`Jm z)*^-nzr{onq9s4hl6k2{x~T^ED@84Dc9gH?2DXpcNuDSHcnohEO(se6`%}WiK|p`; zaK!jH1=Lkp!$#rkf#*S9C0pina=5tV?(M>GF_cIGdo!+#!jUiEr;hX-RuUVQ!){u*W^05y zAg+|Zc2ogkVmxr;ad{U_Q&cZizlZg#iWy5Mi;gG1Me!9C_h~!!VF>Z3%)m3B4|Yu- zT0`Qk+~+S1%(s_v9~9h|b!rvlLe`6idbt4z(fNGtpXr|mY?1|>I!h({M3Wu%@zS#C zoOd-zr~8V6A6Rq0`^o$wuKsJd%X{|qmp3}qN>ll-`%`w*A2*le(+X5OG5or%etYiQ zSm3V~1%;k5u>ZoRWUA}C2`_3K+y(u;s?N9A-Mq8FLg{E-l(8_q^!RT*_5hs&>QQq7 zfkd%yc$Ot}-D8nK-%ZZizsELb;&vYozmaO^NN*VJODAZh?)el z+Rh9bbc^9A!-^G^uV)Wooosf9IH~&vsRq7Ltjj0SOQU2af_Eg(J+o8fy~!aVoUczl zxb(W+Th9qM=h(6>sgz(?*{Qd+6rhHp@fe~<)Q}*4w2Feb%C~RU>RYC2hglt+MVsS< zx6kNR@&}|A?8Gve{$ws2+eGd8sUb--pvkM(@%UPX{m>zMh+(wI0vO;$XrPp&nBws- zC>f@da~+}?oChF|s~=~v7zL3i8c`Jm5ir#K%bXYMfdxLe9Neg9XNEv&zf}6}Hlf6} zKpcy&l`*3DFhxakKnfQ>O(;?ejSwszl%tQj_(uKK5TS-d(lR*A_K(p~535fwJ8?czE}W ze|ew8d6Xh1u8(iCV@!i9XYeNC-OU_4o_u9l-_>@l((gSRg2^0e_JF$}yHzNYg~d8f;$BF5FilT-Q8V-2MG!8A-KD{1qcM` z={(Q(etY)bvuCR2KDeva!KzvZOYe1E|KEJPd_A4Ox&db*F!r!JHe$*R46?oHLpi2v z8xH4%-;$D%%2o%ROzM9#vqVNUl@kboT$;@1SlA!oyon;yQZfTpS?;%49ujx62}yBl zhLAW&k?QKXP44QYh3k9LOV0*BlrXqp_kU zDO&|wbGk|vo+&`g;cRopSqvHahQozI2&IREgeq`E9Nrq?TC>V+wddwowT5c*$e3d0 z*!xi1XJI?!!B21HNi-%SmgLeu%b_%bY_(~fTW1K5dc?fo+P#9sVCb?-5XN*Vi&M7j z@`ixbaG0)zenGK4r2NgF0e_Iqd*f1_s)3b(wN)cME3+WZgl*YFO;Vu%Hzt5Bx{`O+ zyJfyWw*Dx#@pqW6(xMg8JPJT*T>wXYuqarXM_)#^j>c`@3LjA_t)@58&ywHht(_|4 z`(vhP<9G79l>4@n2S2Du=AcO2d}Y!y#%>9S62>;wY_z<(y#zKrJSlyHyFtP+Jw!Ia z0;V$2)8)}D<-?AaX_BP|lQc;fHi}h8S=TnQ;B{H-{3~h`CTska%OKiIWZT2yWIME& z5D3hPRa6IEyTD^U!37Ni#CI#zo`R)g`(2}KGv>>maRBmVz4k2#{?>MJLDn{5w7VYp z3jI`tlP0;=+KiX4KbXTKAqTo8$o;uJN_I-5os{NSl+J(Oi|GoF{{*)b(<70C2S|}V z5SBr(p(S{N!{-Au2~;*}ReF~uT1+-XKw>sH3>9e-Fv9^WTe=)9ZOJi;G zVQsRLyg>+RcVbnLg0gnBR)3YV|2k3K6?gJwy}E0@`kT@T?md&dgQ>I^I59~B896*i zOa{Y7ilJiE8Abssl+{cew|Gcjv6B(WV9OJC^LQ`=)O*GF-~|DUu8CU`hEn^bHKTQG zW34q~-`K_nYsM$oe$3bWSZ9MFxD&^LwB#ZD3B4184&=zQr0}&v<7w01OHAJYy8-?9p6q6j@XeAGpt>HHwL*ra zRBG#N84ZP8Mrs(rPDd^PwJe*%s+=OhK_83QvJO_#uV;*CI}16A8Y9dEsq{z_s|SgA z^~$0HI12jCm|2RI0*mMC!Uqk{gLXX0K^J9K+NiT8&-#~2<>i<(Mmp!!4zz+k#rqSB z7G*ty8gk-KebX||62@bIoS=U-V3(Gu zIr-ubRAZbk`y_lJSlJxzzRdVP8y@7Y@W%$+M>#80w<*7uJ$uR+2*4YDVmo<3CVBfa zm%%~WB_IhC(Kcg(>@E9nsf)cew}Aq;6c}W$I;!N#a%tQ^`THu4kW=4=q0pu59qF|v zXm0Lq{iFJ!1e+@z+z7REDEYz_-j17zX*Vyuj3@{km&HZ@w$WyNV8*!LSs=s(_kj5G zwVG?4U%!j=Z1)ZNAVvZr(@!^p*~Ztajd(Lxf-4B1MO7)^A1F_Os5({x23Mv^P!@w4 z7ukYxA4Is19gMyLO>c|d5H`meXv)AE>&=F{7wmXjg?^|DT)A-%mSSx zOG_m^?Tu9VF4c#SFgF`KBxJ$2YODq!==h}AhnEuA9*~1yre5xDd7ot;5i|9Jwccak z8sVY7y|E!|qWYWxfodaQ!!eA5t1Br?VJ0v>qf+OHd}jgTft!%Tt$~ZBi4z7@WuAx$ zU*L8#_d7m$KvlsfHZ0cnY7)HilahrG08`%{iBmgGi*a4Dck+EqNWo18!!{B(^nh{Y zxl{w46AxC~Th(&e+I73S#unY`W@lT#kwCxqEduY8bY)8m3+)}`pqc3ax^241Z+y@~ zjk>PLa3d}Aj_JG2+iqT2-I~T*y+I|OSFS+rr&a00q??;ip(kk$g*(e3SFM>A!&m$U zZ2@7Xc3G{m^?J7|kGD*;AL89^Wn&!ecvqIT-O~dhE7RIajyu;sw1|O4+HJWDCySKXceOY5AEt!YW@v?htH6k3W3$ z@bWKn>!Y>75;RTe9#IJ93l(6ET@2+i_f2l~8~q?S^FdaflUSGY&hFyn4AfFR+~TDEyv((sDaRVhb*G#Am8D;@-o?aZW5GKu2+46gk+5F2GD*W<0VMYCE_uS z_%dj~ww8#G$Dra?v0BK5;GPc7(=GjjEV!H3NLqEh?QQc1|1+;3i@}U!VV!JG*(Vq5 zKJFrt%C`anh912VAvGzT$kEbq(f%x9_O99{7>{)yzL=3-!SM6^_ORcwr*k0~n?XXe z!NRK`UG{z=p*}kJ9 zm2tuo9|kk2_pollT#;!hG9u0)_Fs1&c8kN+XCiFdf$8u zMY(yCaquVaSG)2>(dU%`AOo1}+nyMHguXi>A(OoeVKBY+D*$m{ol~EqL4U_k0;#wR zb^&Tt@qlD`r%$Me?0G9kyr}lcvR6eABdZ5tYuY)!$Y+bYZ;y|@vjq$y{q!|`Qh$ly zAb1!N9MVS@3nPLh`*=fy@mT={L4pAt)x|`}DZOl9+na=s!}9GzpM{3MHw~vhMRzv6 zg{=dNde!F35DfW@8{929^ZOPQlDh3-q` zss)l{W}x%pZ)c^EfmJdh2EM%#LMwB>Bpmoa6@7Z!?{Zgz&}rY@CycQ@R8~ zs?BSV&?m90w5$ASzTBX5=Hl?zD}CK9>EE}C3OBdU{Ds-iH@vss`$9QE#p1}c+#pG0 zn_ynUr=tpKQpIjj1rVSO?%|@3(-;IG7n5dsmhL`7#{OU3Tr z3|Gk&2_bzC-I~qej#u|11}VQ~Ta7XUa!HXjW5J6R&LEoxiYfsryu=W&qA>u2DHyY9 z%GAo~`amSr%08mcngK0dHQ)?ai=lXu$52tO{qYgFTJecfuV2IXbAL*&y?IMeCH++k zPRC&k!E`!8t9T@VfRs(^pwr`ih`cibplq>Ec29}>gD9%Ln;`aUaSbi?Exc@XH^-B> zk;`p_128-rSaUk9{bLX4I=9JUtk*shd&>dH8he){4HRB2t`rDCmLTXPuZpXotiZDWr#^9>QwE99>jJtM(VZC)l zmMXhVusFaLII6Qz+%m68Ev-#0`%2|##<)eaKb;Mkr&v=(2t1PEzYdyTdME#fzg}Hs zphewYxamDLZpG2NRDkZl9T>C-2*ChZ6Qs|cc+giGg?NPu=-=+jx)(+95l6tOu<%1I zN`RvJ)$4&M918l~6+hk>faVBZPXKg|!bx%El0L%8luhhR&L}fVyS5mHi)%3cO4G-)#)YuI7yhKLrV_ukcV4ijT|ZG`Oq3!e3qVX5O|lV)o3Lo)-uUkVmnKq= zld~$@olLD~r;It9;%3k?G+*a zZBmwhKP0+|+Pp;$=GF^TQ9}*PIvB*aXC{#?P-yO!-`9B})ibGM9I~y;&8ool(h!ee z>RI^NPr>*V;dl*dYVJ8YhZ=lBi2$8sOGN0QogzrH??I;!e=3fn!xlTQ$0p!>nbg{r8o%V5Ti1M~ZEpV=MSu@LtsjyInKHu~`t7yl=o}r79)P3I*M_6+#7mK5 zdDlza8$#EZfPjmF<{lgL`4SnkK1PM~;aVzp&k;n{rz`8P=}PCFOte=WMX`1 z^|NEr)tZr?2b;Jgf?)n_3yp_-qok@Y9OdOCVuS``Tb#f{_o?gn2O_q*#v@ZRJ8o}#q`tX?*A-WW1doUaG^{(dD&dv+Qq z6GMRWGcwBJ(r)ps?48BuZ?^<$&)Ez5;0ff$^GK5ftLI|8Td@bY-guq%$HqMj!H+e; z<`|i;5EK<{_iqS-pdp9;(1nFhgkqQgOKS8q0GeeWRU_ilG!{Unht>%Qz%D;RbpmeL zKTDQAW3oT!A_0#rPKvh8_n8HrIH6FvdT8SXbe*$9-yR$kNPZ5X$e{)ja6NT*)Al;D zq3-OW27n$$KtE96sL%Gqhx?hrSn$WE00B@;DHMz#lm}O| z3;o46mkybI>4motpNzqPp2a#HB&~1er;IC9pUW zf2<>3yTBG?n9^)ue0@S-+i*OqLHW@fwR#_OkC9u{9Eq?9|C1{oWhD8<6nQNU1@Gjn zt_4nvB7t?C;i4%{J`UkKZUl@5+&8_HrHE90jOd~uDiBwh@76A+Bp8W@tZ5h=d`V0Z zhTp-$(t&AF#zaWZL$i}eiE~|C2P=Hk9M0*c-3JB}gYf7Q=y;RBIPmmC^`sxA;OZcA z%NW>F*p$rI$7MX1$J~r#u8fRqc=Sg!=P|^57}$|XrZJzfZ;u(^`udZ8Fvnpd99&(j z<37Y4(7vDEL^rjDzHH$M(4g1bNxhK5NAa_0TT&kf}+b2P8{8YO(ex zLw4|Z78OaMG^WYKzvh;cA<3GOj!7cScw=@wv>nu0=mEq67_)r%x)FFHMCaV|KM>Zf z_>+U$akb^&&We`L;L@Ux6#ytEBN(`-U-O*G<6hJhp0ta4Qv?!IrvF5vembSf19DLi zM6@xXrvxeznSl{E2__3EbIja^V?;5uWEDYbzwqf_E0Y+_NY~=4$EIK-wa|4c1D&=Y zG(avW;wA>^mi8FK(ZBkx{u{7N55*{m?>(3|8#W z)>>#04d<8D<5N7T0@7?jUT?WpNTJ-*f9<4&}gjg$2Nx zJG%yf|8jF1?%-}D5k*ZMMq2-Ia|ImdS{UmPSCkK^SD9#+j+a5 zJGi?$XW)YUqks#_7Z);97Ysqy--NCNUtC+#TwyA0`X(fnpiBgyA!d#WrZthDwwWri zL@>8S>b1oPDh2Q2-hkh~`G0bA&At%)F(Y+J_gv_2Fjo(#dIPDb zrIC6|&_#c{C(c`H=ve8cfr|(aD+JtrEZD6GpoE$FEq(D@`weq*Kka?-ixVn)E&Sp zU6>0g%#aUJ;TVlT(=e2dY%_sG z6&xOS5^Yu#RO4N$<1O)@!FVh_cwGAE0?VQzq&(t2C3`}pi5-Z#*Q8IGCAAOX$pryx z0r^N-*|y&1-=HJ(Jjdurmm8wG} z6NqXI5h)7`W<`SU@1Y$G)UoPET-GD(?a!TBsvna2+|v?j;?;1_)&SARSVlo{(d{(q za6*J2+ufHok>;S07OFLu)%LZG1VB(}aL>)Ye3OiZ8M-MS!D$ei3v&`gb22w9Y8Ndz z7SpE}pma@0k#wL5mk(OW$4?cHV89I>K3S)VcVqf;hUQi;_evP_nHU?nr*n*~TJTlb zm*xIW{lqb8;v&>E(C5FH+Tz{MZ}4u4tW4u;Qx~ZK%*Uk}7(m!Y z90d|0g3tzGJ}x!6lFGLS48Wxs%&x_oE%czK>z#v#PuqfsQmbSEit}ILuM3YdT8xtQ zg(d?~*q*1k#b)^ZW`w(Dc#W_`#b#xnr!y-EWGH5(DVQ5c!hdwa!u=IYx*&S0!Jnll zR+oRso06pkGK!dzg>0d9ZxVOIs9baO{X$$QV$n~i=p>rCuYAGqI|VFCI`RNq75uL% z+#Sl`XKuP&ZU@P~=yJc`>PXk>kLT4Xv9&QHtl6%$HKSD=2orYC+LF;426aJY=A2^A zxLBux#hUqyFArfL*)4?XB@p&1B`75clWq+-Ar#H(p#3dV1SuG!TmSKC2nZeyHwY%r zq$1wZ00WB^^D@4yad#MTxk+M?Zebd}?3s!0TYcJx$*^YPST|rShffFIFPI*0Nxdi! z-skNvfD14n{myN356|Ng2Gv@=^PhuRzk=BMgV@GF?6XqfQ|Cv$~7mLZ+gC=D%=osUSZk}I>U)+AWc=&elEPinyiM79Zf%5$l z3+SX!cnRl!`S9`q*n>?8JaW`M@^0N2XdeIhF^ULY(9KWKCm87ytx#C8P#mmjlY&s3 zDmZILxG1>XDtyv*7kRXY_Ik^JDipLxStzTYQ8&)@$h zCEmD4_PNv-AyXICAc)jxk4l!9{lg)ze9mVF)%k5VYG5SUb`n0ba0s2#Dz&M>9o7* z9a0iD7)u^V>-XYBQ zqq#^qSvw*6Si%tP^}Cj>7S@W1I{TGxU1=Uitt~qfXK14LlD)l1CMOG3oUVbch!kfAenRPlD}z7+1BXQD>V{(nfmIIeBe3ogpFP^4a~LI(CbLc5+GZr&wf{a9(a*nYa= zxKJaac{X*AaKnOP%#wpcC5b5HX5MR4SgvK>tr-yL3z^vx(GVE>Wvm@g>!5}d>a)Xz z9BR=t1STn9GJQkd@p_$^mT&tAjIe+}_Y|;Mhk^1r}CE0wxe%o&&vWA|1;WQGvmbkw$7T$V*Iwseh{ zG0y#ZQAuJ3zI-9i@6QpqKuJl#AUQ@S%tp7}yro)Q#ybnYqB{!4?P|xm_tlSbjMZq` zM=?~{lt9y#H!6iFQ?RRjPM3yA(VruCYl7G9DBFqW?N~dat5yy_|2U>&tLJqo)~CBz zkG^QU$|G>Jnb9=JX#uk=xF9F7py2# zK_-iT&67ouK6haa1=XAx&#L~iaB%~lhJQgDBCRXHGVmoFRBjxjnA}4>OBtk3_i)QX zg)b&0k(a<|30I6y<*{aMawr&cMO7#m=Uegpm56b&n*6hQ-uiB7{mM6GN&}9oB@Hg8 zD2vj0Blb&-9c0DY*~OgVGH|vmi`<15PV<)$y4r!ul0$mx-Goej^xe*zj%>lzpP)|o zSK81XUhn;)_!sR}vo}Uda{(LlF0SFG?&Vt(@2hXW2*p1ywiU{^zuHYpCTQR3GQrf} zFDteQV5>sl6+N1eFqyeJ>#*I~s6Nnp6<1leO!UPb*?3`lc8|k*?+2rg_@DjkJF_wc*6d#?c7_F{$)se%`M1o8Y`vtR zT-zbxYQLy)ent#FWK1zB7)Il!3*|6?DpVVy&8hFTOIV`LqEN=SLCkb=#t1y-!8s@- z@vVb=EN+RViY02xUTK284e0c{V|SP483=o_acHiEa;6!5QVavpywq0AvXS_ll#P~g zmL;qvm1SL9^8Rx>8+1pSit`AU9QGN*;HX(_)n2>!oyR3A{*X~^1}(?DMDV&k%9xE3 zudZA_I^7Q%MWOv^4#wAJM)Q;52W&F&0jSzk(v`AOWliQMmIvGejY>%n_pFx z^e8x}zWcbUmHcuU$4aOYxZF{UyfOqx^QZlG+y5=;@OZ z$$~LKPvRydNnBKs0$-V^8zt)@#b?u+d1Ps4ha2fMUM_le%-WvCU7%E5EWJjj6`Nce zdU}KvW}2&oVKZRPgO_=xZEbWW@}}Z)5`Q%!TqKD))HiUhIz)EIbcsgCKe45zN0imL zgCub&u$E&t<&Cyc)Efi=zR%K~wpU8M=*or=v@sZZd-;B`x5_iP@`s)In^xVyKkn2a z1`3=He0rnb-W0MwZyO!_QJ>J{2+FrY!F<6%oZWVB8E1E}S1wX(ymSwNHqj5C94{sW zM!9o!#d~eMKR{_IAjvojUI(! zUTqPnWNQA2s7*_s%X;9|`sF%b*NKrL$FPQ>wWCmxv^(Oj!aG!OxJH|bBdJm=lY z3rx!GJ=%Sh3WxzP(!;FC@UAgG64@FMAb9#kr97~J@-z0>;1hBaVyTwVz2!*rT)`a8XA(<)ui zY|(j(*&}&RY}}iQ7{}vCl5JXBZ0+PSH$H7z6};*!ndP*?#uC=Gaq{o%li$u;(-dMi zW{*Bp%yrc%VgydVeYMg!DNY~5uYBV5vtwe}ld8Te_9AD!bD~#=t-n;^Q{k zmwMk?l5_01mEv~zdMdya*6HZcrn7ZJE!nw?w@Jskn4$L=G``NFSe|cRG3SAuwH@&Q z&?~=SnmPRT^|iOX--*P}yF;3|oBHUo?N5C|?Hg4#$*QjXItSi0ev~)K#pH(%v_2%M z9Cu$OqD~)K1)`2Xn=YDkn4sy035u~5IQf<3^R%W5LXNp`GOP=q&re^N^ChAW7Ebwy z%E*hHrXh=`6@X5W61?^I?d5qVXN|9DxSbys!y_(QZaVeQuDvVOa7rDVUu~m3DGmtc zo%hjy@}~YS{hH``uhIEs-3$sT>zq1DHdH;Ii*pJhCK)OH@Hjm7&KH4}YIMsv`}$(S z_n;bjedMoPS?FfBQBHE>JNgMS;b3!NLGdJIB6i|x1$ETlb32g_V1V-@r}0aa@mp?Y zzmZ42E2r%YvHSDE#|0^1=ZhC{Mqu1;g@fNdXKw?jE98)DK4mdF<$O@i{~&*x?u5|8 zzq;V}{kKief|Ep#mq10JkdT!yvKH_#utp|`hAHG7h6BZ@1HKA`=rK{r3ORg2GF3zlOra0NV+#IB7^t z&#<7jFioKk#^r9{iirFSGB=x0ln50xT^6t5px96-QG}eOTAO;Hu5VR&mRjV6`%ou0K6m63c z`FYcD#DlirT?M?OMYfaS#2*KV?-kgok0jm$k?MIh?~vo} zGu~&n#b@ZIOrq+7?%gvVCfK#>!e;^B0NUSy51nSBYD;v2kDc9^{J zWD-iroQmq(~Qt8}8l1(0& zrfDk_ijqa+oqqM~koWz;?=mbGzdea9vtVXFcwIQ) zAv6EcJHh%O|FAt9UBfHtApyR_A5kRK^r0|uBr+K(54$QFcQg}P7F+bLkecyziD1DT zO3ngF(KShajj+c@+oG+=B1$SJTvnPL`k z;U;4LgV%O*XI54;BB|gOU`2y*doStVcVt@hz=yfGqc$Rj1CUlmYuAozH&E-gNbABS z>(-UB@>q%yMqQ9lA;0wEm_Lx2NMf$nSLp_zdu_s7fH8-#abbRK4;U6KjDA#r3*&1C z{^4s)fdJD2tRhK-&jDDMdnqG6nUj3@reNIWdJH-Z;4wc)`w~li5ZVlviZ!rH1&)@otj%4X2|F1kh8rOFZr+LlC| ztgoWmDyzLhI1fUAp|LrWn7G)ujo6sfX6R#J+?510c1SWInH}*X7AYAnxiW4=f_-`c z(qA_>x;?YHJ$tM@jST6NI*nsfpxG=RA8?#meeFThaafxMZj+qa}t=Pn%ziK$<$EUAq zlWwc|@uy~r1$Tw4k+!<^=wl;eH}dPv|8jGGDSy9Z{SMP|MHAp2$DrSzPyTUppT3J0 zApK$Oezb?9Ecol@qOJmuvs;g=TXEQWtd)BRL|chsdW@@k$W{RkCk0m2C>y50o>yOJ zT;cWrXf%NcJM~zP*qBb!=;36zG@X?9TqrbCD97r!Nsp%Mu&kHiinxEY+9a0Rl&oAd zeaF{1B+HcrNy19%zHd~~@i6Sj#&^Iq_dD(CU&;dd< zeWIrg;FT`OYKo&BRw{P6yGW&G%-i!nb)RZfIZ=is2zo94$>NTD!g?yeLInV*3os_s zd#PPfjuRjNFz^=`1#tOw>Qxs&y=x)6i$HmZUlFR2tB(1*9wRQh-&eGZ#;16IWUO(# zZq4>DSlb?hu&R!J$q&m6!=U2A%?rR}1pNhTQ|iB*f${3G+hB>?yVV$cUvVQ1Mn&g~ z&-BM`n1`EU3f8{<_@O)ej`}NYJ;uf+eC{AzoG8Lw0GhT7!oVh`C;-6YQvVhkM%LDw zCSVnDAyjZRL`2st_SDMyVrbj<~(cH zyyEDBWA5U<-~=!8Tp+t$aPFi@>|(UanA7vTs>-kw#*#DB5_|1ZvdR)=)PkSmvckwx zZfn z-$GZ{>bT>gkL}73#<%t}eb3tYLX73*wdL-vm0pS|I;AyzVjHE&Hu-?{quTY8AM0ml z>ld}_$}T9%fQ?(njo-QJ*DBDB`yU(6xf{REHh>cwf7mw>FgM_xHc`H=B_S<&=Az_yqee%JKvGO+=X!LN~`Y5I_=8G?JCy&4>wn%Zs#qFh&1(IH&?H2 z&tT%On`?r(Z=kxWY6b^&LBP-36o}bJtlPKe*mOMK2Vx$$PHecV9{hGZ_~5kRU3YNt zNQ!xsjJX}BdX)ZcD=qGbi33jFWyIp$ z+8p^Y0}j;H^zCtR9A8D=@t`CAe2rO^Dq-FFas9XGW)8x}Ph{m2$B@DkA1$)3my^~y z;m&pYwuzJ8ID$d(gnr7?@pI;GC(=pEvtEv~Sedio39Zp}yyZN+)%CMQ@z`4}U`4la z9ryX36X}65+3~mY-SzWBW71Qn^K{mx=0D#qZqAvX#MgnGmvCx-SzM&} zOO(%-Xg@D8E-taKu5dW7@YJq28sK{*F>kprN1{oz^h>oVNqzU;23V0*`t-_cqo1l{ zZ2+#b3jv=Ku3&2I;1i))!C$p@f)w{(wRWQZoxRyFq0hfCz-Sv>ScmH97IApe`OshV ziKO!5e-9e|HrTlJ=Df3{!fo-XZttk>Qo0W{ zxsAxbjZ(vft4CL(!d0q=v9*}ZT!(=AJ4fi9GtO_G_y^C8+gBS8BA*ckO)+n=G4r@^ z%P;QarIC6r5mgG1icLtIP|Mwv%Cm9wi{I#%TajKXeJ(PC+r>sVnS^)VgfBHiJyl0i z-bB6%cudkjs_#b5!vYj-V)_&yjB;TnI}mP3yohkZ{lG@i1R$<-W7uy&Uv{Z*V>U4k z!MAIO*ky}zdfQBSi~zW1*+&}sx5C%}fD0<@FBZ(HrBiy{db)ugsj@#+G_6RL8_WEr z&T=WKR5Az=hsE*`yGSOAklPOa5`}`EQU6APJh5((K=DSX-Ew)Bemn>XkHg`fYr8*+ zh!+It;mAl~9h&9`sNdL3m#WUyg|fKYsZ=vdcpK7b^n9__KduQTaI+jqwnq?jWKFf6 z%O*Q`sYctJX6II6nmXA{FHuYh=6Bv-)hn%V&3onCM?VD+(JFdV-hah8ZZ`++PYkq1 z^L(c_<toaM|UL z6n=dXW&1u|$L`_4l9tiNLR={Y!Ks+rdh=~mIx@NB!!H0Axa)Qqt{c&3ST{1+ldgc1 z{8@7w3jhVksEMU6x^s5W()DgrF)`R(_8`;W)Jj~Bce>EBPi$?qi`*>%8NJABF1|e} zrP%bMzQIqBjMVpS;7)aM4HJK)>s6Cy5DpH_W}u%8S1?Ploi4quZ*!wJvjY~ivJ0Y? zr&-J%G1PL=^MvMLx2T6F@#WiZQ?UyK?WeKUDo4WjTAOJRxEzR0Cm$L=ek=cqFJ1uF zTJkWtnf714mK;6+)guMlLL5-kpi-o~Y0IMlSPf~Kg2sYVQ#6ri8_JVhCWOnR0a1$9 zv=0uGiP~Bu{FhS-T3OASfd52o<{;R0y(u!x+=Nd4PT(w%l^m@q@&2{8 z?Gjt+vI$U~0N~I<&r@n1mpD8VDZg4HTF~mZwl4%&H4AGeIkVksuCkvs zAQ5s1RhHvQVFuO5%OIQ z0ezV+s1%joNCK+8??`N*b5Eio{IkG`lB+!}~;lKZw|7Y>w+b(uJ8R|*5K*$vW7dafcru$|osJs~E4;J9C zsQ_>bj;rRHa7{=yJh}<*-Mzhl`U1X!0mj6ANoHmg<%`Hibmk&gJ%~tJrsjB=HkGsy z#l(nhNhuYU^wL|sO)_N2y<_7WAp_SH#Gu0t*lLtyRB2;^x6B zToJ*2WP*#+?&92XTrU<>y9(yi7XyQ_U%Badx`6n;;Vn&i z9QKi%5JP!lytX18qj#kLsVaqX13}$OVKuHFE+EQxgGpISNl`?OLK|L^E^|i7rYlLY zv80rVLXXq{z!UQrfCy;YtMw0vHZC}}WLps$QwIek4#7+E^t6pzi>p)kEe-PxSt&fr zOc7f-;4)*lV3xzWnA@O|@)4K>AhumRv{k0Cv|dZ}HH8wwK{UKqla{EiE;T|!)T3@y z;k=ds#fg3n;}|!Q2p+>ysE50UY3Lm|A$9Pmj|!$rERtBtfNqpOGW5jObkWY66^c}E zw4~nfOeZ<*mN2u&2Vu%+;v^yf>W9ld+1N>Dm%*2_E-?c{12NNqroig}yxCXhg5GmC?;OJI9s61S2`)@G7X8fYIF(>2$gat zJ7is6VtfoK?slHW58u@Km43L$_>^|tUq+FJv(^~8La>RadZ7w z+)4i9=JJvgtSuwMUX=dJ%@yvHU;mGrn}J?m=Hu0eL*`v5mZyQDDhwk34VJGG1nta~ zrU>cB$?zTbU@-Xxl3nW#%243NflZqB4Gw%3y7I0BrwdWi>gCh31F-ZJAh-t^KZ)*K zQJHi>r7TAP_HG>AO7>hEkAfh9wyPK}7YMlx9DsguD}q5tD%9ki?+yj@-v6yBr4Z)e z@U_V719344Kv`4CnDVs4hD18)eu#J$e#rIpbS!+R?}-uAXEFH^6`CM_wik#MNGG?ah3t@VF?_wnX6y85O#zDUW( zyx%Xs#qqx>MPUKDpmiN-E=T~+ODrW1DpdD@f8AU%7WlhK2PF<@)cA_%%8_V76!Rn; zfL%*M)l4E%5{YJ10y#z!B}Z~AAavgq#Bm89CHzV+AV`5L+&=*b*bMp-9Hf--DzyOK zdoqYjsQRY34#7cUr~pYV0L0b?e_kL-u?nGF?EzkfxO5}EHw|03q;|a&R=p2jz!eeT z70DF|^SnnYeI<@yNQ#((tTfr=8GtBv2;qE^;wtIZ;tJQlX$ydT7(c)Rm;e9(n*z6RZ@hOXqi%nv~4W1(YX(4KG5DL?3#BXqz3 z`c3}i?)dWZFNX_*aQ~rjPmlkO!=2-;+9FAU%ob0FIBbFxcY1nlOJ!|yIZVE-Z7Qp3DuwyCl?^2|wKe(GIr-Jum6es{<>mh^ z-&UklhnIzA3%yzjZHG@T}4^G11r8*U{0@($doShrm@*QiA!na&mIg z($fF>w}0_l*t#1H7)nYE#l?Z5qrnK=2V#O}c=$n1b}=!re-&I_US4i)Zca{4c6N3c zgv-Lh!o4 z32=FK~|97bS{h09K|M>vnpv5u{hFH{xe@P7?nb) zxninVA(_Q!w7GJoT)kK+SE+?Xn^Y18;bvj~e?z#@q17AT1D-+u3xq2Pg0f$$MJpx9 zF_HW?go|10%_l!q#{Un5Yad;w;=}$Agv<8={9hql+tpU##bLK@j6*)J7r{Rs$A+~Q zKRNs!bC8F9m4&Ep_l+7_-_c;E(nbDFNAB~fl{7@ z%BM@0^zmHK%G6(Kq5M-Ita}dz;lBAF5bjZ!X$K<%0PbnC|345e%Q3+}5N>G_%P|(5 zjF3&>XG$osebE0!)qQxg8L(jkj|{OBdlP%BRW*VjHmy}vdvB`tDnaZ~t3_=!YpYGw zs#R@6?a|uQE{aw)pZERtKag{hlXLRqzOVcGy%jaBDb)BD;G!&hzPeA3_xt}K+#Sm| z0u-z`fx{NIlhyu~c_(wH*13uW0*d>8SKaEd-~JSLZkU)>S;rhD;)FL^-UtIGKD!^k zyHYfJ5@aX13Z}SX)Q>g+lIWf&uWko(b{*AyWbJHJ5w00(F(jL}xqpHtP=Pl}j=#I! z{ttv3$Z#59XR?Zh62L4<`icEl(GYUUp2iOyZ`^$o{p z|1E@j+JD`jd<)@zua*3~<5N(dZmxRsUkEo%Vs!QYK)844{bw&8e=1rbw6%OY7aE5r zzxW<@`YGQ_jJ65J`hOwZu2h+{Z{rj!% z5uGuKoaq08aOH0yT!Bv1>$y2y5i@06bkDq}D4aZ(nfv5U5&Lv#Qq2g%P4ZWxos+;B zpwLUd)IMznst@_0xB+|j?~Yf5{w2_0 zP$>t|yPSKBAws_*7;KRTAipT|66tV@K{1*gsub%v8sbO*u}@1h9m#8eFpdM}Nwkl6 ztq(iSAciml|VeC5T26S15gzB_&DT7I?N7WQ`qJKiH244^y7Q!W%*^LtbFw6G0k-v!}_wtU^$^0-?NxYadqQomR zJQhM*{?ZdAF#7cNN-~;+-vWvZn;e*u<6zvYij$GxXk_CDvGoJpzI!a)U2LNVIPPjF zY4(}_lKIt+rL7OYWTsvRdcOAYf3SNhX~RnBUw?GNwD<32VmMN@B+@cJ;nv6S##f`NB0yu*bi?EYCX@G{bQ#~n*={ALYmJ9yX_-)|BZ zt`7q7w>3OjxLBuS&J9z$ubI5`cCBm1^xZGgr`*0h_lS|N*{gGWuyvj5T%nKOXjSkg zurS#0D&_V$OP|CA3U47alJO88(dd^(6I(;!zdy&3pWy*v_LA+ePZ1`*Sqr+mvf29t z&vr+oL~VA@SF%Sfhu@ant#;-*4R*VuBY8Zoi|$e(ZomLri;>UfXi%@&tN2@9#|al3 z{I#b8^bv>*DZ_kmDzd=eD$=Xz6sAKI0OLM&g^8a{ky4y2zpm6-Yz%*B$#-J{D!ycV z`MUW>>T#Qj?#U}=5h2E`dB~gk&DX!9AwGVfSwsF|mW)-%QyNvo!$zn;7B0pc``qdW zgE|e1I828KP5K8OLv8vLCeTy1@a29-Gh8vvHM4T@yi>Zey!uetS6(@CRMn6Xe#Dn* zuEY)>p?^iNA5}KXQ-_})Ms1^Dw*yb=LmO^@4JAb+98?d$#fnf5c*k6a87kbHE|=|j zNCK4Om_PFS5InyPx>=j9bmw!()b&x6n!e};0o_x8>UEF&UJW29E0Zs(w7*7x%xKR4o^;DqHGB^t4Ufar3kh9>S8{usE& z4#W^vwwW7N1{nvk$DhFd;4t_;*q<~$L>l==xN$D$fACv-D8Ml=!1dAs3JqVs7saU> z9%aIAd28Mp8#?-_ySAu%o~r}k8otIFfoQnFi8e4jTDvi#%{e?w!!4LLXr2pO;)IQ` z1qR!Y-{64wM;1em*bxYbF+XJKgp`mExPT*LOM}g=O#(+LIL*zO^O5I${JA~ zE)tv!2CDP`2C+Cl)3|`3xFDH0bM$?#4-e&JqMOk=ZCD)*5TM%u{+kbeK~Md+-LnTj zVob2hCQJvaQBx)L5 zuJ6q;AL1F5go|a@#}b^*B=ue;^)V#BBXS5c^|Qy`w`#o)oVFT&U`1FUv9pUib zDt2lnV*O-|`lMqB>XeR9&fKiDAa*KmDAObIHB+qJ+l=h#j61XaLLtbl;=?mSy>pxYbxi_n=ss)tb~2`|DH(4hieTkR=J zkrw0S;g%49HElXb!g9vn5^4bY1&?32N|#8;(vi(*jbR642!m~cqHMC)BeQd53~qxY z6=NJ`0y*;pPnm{aas=mUYh_%e1A}okpHbMrg_Pjjq{@XnvB$3x>2o}Pu+|FLXLY_P zB77xP@~EUbe=9Oi{3&6uw_^yP;G@7RW35+hyLrpiT-CDqO9uJj_=>>Q;76YYs3(F8 zb`scTbK#r2(9;;;VM5`2wcXOfE&uzfPd02I!L>Co|BWnmpP2f`?|jf7Do7$+TtCnB zW${6E-s|e@%iJQGajk0shGu8aw#pKKSt0PxOQH+x#}a}du>#)hVz60}ze$PkUM%$< ztDi5%JDq)#qvLtng4)d+S>M6xnd2$uj%6|j!J;Y5J#Wba-x#*1%VPP zv&t*VOu&ioWT{A42=DS#C1#vAVozk%FdmRok(==PV^eN09%rva2)ISseB6ox%&Ij) zN>-*(Ii&(sQ`LoC0&h;MO9kJQkO#AFL^CmG-zov_YlnK6U`EnFX3{*VnhFH|x}GD6RWBFHi+gnSs^I~Nz46<>7=ubFG0Ft#-_9tnzK_AKTmeD*`Zps$z4myyoq$ zW}1)eMsTwJVlm=1K;a3oSWAFuE(z$hOp?d)-pb+`1-?3GM?j z=-b^NZHw=2NF;3sW)QTeky^p2?N5m9Y&x^Av$q1gfCi-7tB^-&<`k3ChP zUHVLHb%F#xA11^lwNllz>JGL-I7m7XB;t5+a1o9;ZNFP1R*~bLPop~MvX}@s34TG@ z^>M$wY`vN~1t-L+HoexdiYD1%EG~Yx z945Oa+@qbkv>i;2`+p!@vH>;}luiG?5boc8zWf0ZmO+Vw0e3|0lRlY-L;zb80|IQ!FXv-GLWpaFma#>N33C%v1~sYx>D=u0Eb zxcvg1xPQ{MO_Pjy7!+gJ*Ly??uq%hm3zvRzfB(Dt)30t8(mW^+01$$MeMWRI=;{rU zjWKZ&cLKfgIo0}hLd{6mvGCwlVikF+l*{nLh#Qvc4UWN7%oQ72Hp`q1$U>B z8X>4b_&x&KL%TlW;JhV@Qya448i!Jy_n(BO@w(HO@}>7(Z!4F9im#@CH`cI~sm>7Q z{aRvi4sZdA@ZLM?kfnA^(pww7Hrr3M@*#xgS-8jB)B4?02JgI$JejG;$!^^>7O_tG z#+iYc8OQyZZxeH&OLGw%1jes`2AdTLLQ}>AQ(mlNn+BkcG*Tim>h7iPpaSP7a54(m?FsrvRzw)j7-JC@vAb$)9G-%#n`UX(=_M?^q24A?t z(OYo)$rk8+W&J*9IlXZ6t>_bN)W@fQ)wj6BdGfgB(Wyn~Q*ggGDYY5EP7K^)xk~51 zI9?-deHZxry``Ij5KeX=ye_Q1PWEkyuYP^K?o%5_$3|IO z|D$F1y2Z^pj#pxnaz_(;@1_ns*N^H}Pb}9J?^6pa!vD$FRO@Z*?r|8Uk#>7eh;e}J zFij6q^^jg$#;L0hQ`bo;sO#kJbJ+wn)HKtG!Zpr8gMAd|C*;pKW|9xt_Lo14;VB7= zif7!tYz@9mT8nNfAH7V!|D&~}>y8+l_=fCd{AOma^PUT66G!^k2J8mV!T#fT%1SMH zLR=&UO1ba){M(mdk)221HcoFgpvrlH2m;X4DZcHk*7{ANHUGum9E$L-lH}A5C&ae! z{oLv8wtw5Eh5Jt_HY1we2dDi2_D@fvtOp7=OLU|;ZKOez6wUf%dwt|tsEIed5ML4a zgT~!J(!*`8+g!;;M(_9Q`eU&2P_O8+sZ(*NsGo`v{Fgqg&Ia-l1-s7LOE#R#azEC_ z9(Ue5pucl;qqqYtITRCvgZpZ4<&9AFqis?6Wm*qVnN;xoe44}pO%aL?|NdwD(e`7C z9T_|oy2tpk!1%Yq8ut^|JyVL}IO1Kv|mot_Yi<4 zyZFa`8N>E0(_ycR!OsyeH{ze{rvMqYr6<+~hWJTkrKwDO$&12YAcJ=W6z7)5xH}xs z@A|Mc+>vGk*EeR;+XcR=&DirN^63%33hw-Ff?XTGzXX?j{Pg&wTdPm58PbU%bs9M+ zD&DSxg+9IG1c9ZF-AR4>;CFcB?-jP9PV3*ay^HkWe=}?WactCy_|y*{p8R!U&;NMm z#k7*!Mo}K7=?whyjcZ+D*ORrK=$nkmO&W6Qx+CJoe>W*-e?GHcwcN&F2vDo2Cq&10757c{5TOuG|vt$j@nfWw1FK&!MFPK81~Hy%e$RrQu&MBFed| zcAubP41ks>8kh$&8Sm{0y*e+`eWeYnkXp|wMOVYCP5gssg;eXz$pe0o_;7xt z2|jW`?3NZu5pws((q6SWjlb|dRB;H&-n^e^tC&8?Y;<-^S~9BtqiuCo)$bz3xf* zBTCY9z)E~uqP!nB@OG@Pk2UpW%1p}v8KwfovLX2=;ArI?v>O0H$z9>KX1A z>Y4e(S!r=$_-E6$_JktD`LV{}U@8y29)e0Gp5TwFm@D>y@&L__LN8Y5UWR0TVutC51IV-l!-O4LaLM_QE4O0&$uZ^ z;(#cw-l*wUgwd?@)Tcbuj(!Qlvl1OV*`kVq0Bw=>O+$Wx%w};-gs+E0vjm^~+h(cq z^_0OVX?eB5yUKY+QZKqZeti6j9#f-iS>|W8Q*njJ=@K;gK4-SML{Jsxz9M6(@nh$h)9F$=e;Q*+f3?g< zcb_>L8JGGQalqu|SmG706&+Y<; zQ8jYGXvr39--f!gN$*5n{kquN{R^yhtSnO3cFn=t{qx^utNTak9%niVA_tSGloV|W zOTF?aWmf4jul@xjC}lLxBXH~7X>;|=uA;c`_%+UE=B|FDs2NolAv&5BZdj6boEoDo zZ`M6%hM=>!AE22mwq7Cc`$;V%pQq=?bm%%xh>dk;%HJeRE75BA6())yt%9ANN~s{A zlnLgZ72$Ln=r9{98DTMVVIWF!Tz1vS6(lrNWe%DZ;1!JQS{*KY${Aec+km0;_C0^$yPcL-p8&mjh`&=MnH5F+nR+SuH`g`%<+?b@#^vgw!suoA)MKnZoiix3?D1qVc<_M~NOGk@h`sq(z;IM2SiH{VW>!(Zh z!ylSkld%J%k@*||!l&x*^dHGzCkQ!2|HjDl;>fQA`mtj0tj5>W30WtdLxvF1_iR?S4GV8a{@Sjrixy~JqQmO zg)2@bfbu7^M08$jnpBA@M%BL%-n9MhWID)9w@Gt@iuqwxJVEgOI#^4#|2= z3rZi5xoCRsE%r2I4>zLJYygUk$J^6@5(bsz^x-7&eR%>}C4tj@oFqszK||tVNr7!EmxdkZKF*3;c8eq z6hUEnJ0|{QIviP>pyx?fMuP_kXbvtEKut-_VUu+2vz>;m&%A|>{T?Ch_r6%H+#w83 z>sQWtsIxRVtp#W$<@{FyEB$vHw(+JUYHmulA;D7Zt&)N_Z>K?xcFY>rx5fULu}F_8 z#LC|a9c6xEc6huEp}nh_&dmM9zG=fIi+tuSrjdIRL*U>(RbsLMKx$A~k-sB@{u&S{ zKx0C(bQMDbKty>+4TA9CF|Zs37y}vFpafuIqzO->Ywe_yfQ*Fn%mXHaWC%w$HO~@F zdBM}M^Sb(0MvI5g`KUfVLTEbsjV5$yhe%p1nkG`ZCmqX1GpD9kr6H0JkFoC9fC5f{ zN}5ezA?|3Fr5=RvD-1D3K!(1qj%QG3%i_2C^m^a&$_FzV=22wMAVT6kNxu&B+opl` z5Jm@j6(++U)f~*D=CLM_bt11JRn`%g0aTT&qfN zy4)A(R0EWTSddG(Prl>p?I`aK7jC+-PW5HSKfqjfEBW{}c>6tML>c-{Kz{7IXpqGw zXEKa9nr{f97K+%xwDgfjmNg-Vp`NhU6=Ub58H-}NiI2H12KXYfwr!N<&ZQt0S?GCLXPla?>9{t3LI4sb86<66mYR;Mgyw5`SX* zq738re>T3a{7Oh|iYg^bH+8Q5bDV8*^d#m+&mDiVbtmk(mz(M^eZ=(wltiht=UfNw z%*7FFigAs853vyb-Oc)kRN?Z0@FH)|L0i=|w!Z}HOe-2reJdcHnqLd8ZM7LZrIfk-3E~i$u=biBK zpk^|PW*OB@ba&vl%x}&?iToi+sUd=Cs@|oTW}hKL?9hGgA&xTi{UH*jb&$(fS=Zuj zMvD(^DylOoL-QTT#2f-4;SbI7YRD|KE&79PRw7jgpCm&jDImS}<9jo3?gQgq3v9}K zC=pbjeD+H1Evfp$SpJOfDT#4KFUAwgoPU_oPOf2x~gtrDchln2Upl1OT%UR z!_T6JX?4|}ohPpGM^Z9I&OcT6KF~NjLjjTLzevjseBOt8bcR`sJUbu2i_*w;V6v}* zNC$&s|KyH(d%VMLQlS8`6e011K`$1gN8_;?(XTtAr8Mo&HFBg#lym`&D1yx#)+c3S zX%38c$;dpLMqXfL5|YR4(Asv!<7Gqym%kYs=aY@E?ma!w3hYu-A<%w@Q)c5H50=z^ zlQs6dc3e3t@rD`z*d=K#CVcRCJU0s&IHVR6mM(w;n>;0Y^b`EzKs)$)TpO%qvN_f$ zoR~6*YH^?dj+St{>okSwq;F=pbjmq!>yGzL=)Q(y=vj#B(u$_3bsKf1 zM>eSx6CmSZLoZtzvRU-rvwS2@{`89fr94sO7b#-0)%d9Ci4P7E_^-l&(eTXcC!l$B;JgSqhi8 z;;wxB!BqnI#oJa_sCIE=s6IH-CF--_9f}t`uq_4nvxM;LdkI8(%IBXBknM+?pUu4o zV}qg$+|W#)#LEo;8jVoClc)$&nOnA3&!+CT#nhj&FV|uB@ufL(&q2gg2+aVNDM|PE z=OoqMIm3{Gk8R?gvsw%VxfliG|0DMP3Im5Ch&(Yd(EuSz@7ouOBE(Eic!Jpz^vqnGKuiUkrGkpP~KC=*jCAOEzfo^f>X*R)cw z+{x?{$ecIr+*6)8pSyFuYIA-M=lmV#0{rI!W9EWh%mtS}^1g{i?t)YibNcW+{i?YL z$UKJJRGWX+t3w$XLkYT)kBe_L^f4hb&vR^y!HeEZi9IxaVrQ&DYht4|laexH^K0H1 zvXCY+lg{&4|L#KOjWlheF?$u^XPL+8hx0ii3%M(%c86VtX;43gI9up(nJJ^{L5&AX8`66PuO=ndp)tE!$3v(txR+V7&$!S`P3rp+4Etw(Kcz|Y1cn~3B zmCfP1)!I=Tz7N!T`XE!kcmeVUG>Sa5CYHY*+R!;I7t4q<1rY-%_Ht*$75y7X}Mn9 zF=VhoWL#A)J!~bkoyf+98;_yv8tT#C!ZXgLsh}ycC!U-E`9mse$ zqxFC?I9j8(==G-h-9l;8mM zTFnvKp&(C`BFr;fLjNOMmKXh`TJgg8F>MI)n>XFRYU2^I-xxEsaM{8`mw^RzZDYqOw*zP<_O%d#X7^DqE%hbL6oS#iG zZ6OLF&eQCYA&6|pOeWhz%+$z|JkB>gqhra+0C2%pve zX4q{xY#)2UQS>cC#EYCn$fmK7xyj085>7onQf;K8C3bKmfcj=s0Dm)Z-C9lDcnE)Gnkrn z>HFsK)+>GytpXsz;LS4#w-^r7MGrFqB<4kN(!Ph(>+bX!p1Bo=%}(rMNp^1YW8a*Soc?HoC+bli!O)R^2vEM80d5}u?=$cv_5iNM=mC5Br zzv1jevHP~|P$Gb6pmyt@gEOm%%a&8V)n_O4ER{30U92}ivF_Nh`&j7XlYdrDqGb8(c%-H@jO5YjK2l!3p zNeMk#==I9E!Z0-LH?D5S9$@4Ae$MG6%O4zHJUgXN^#L%rL?SSs;t9WB{M>VTvKF2Y zvIQZV5Fvp$VyL@uh)hW5_0ual0?b{NuegbmdeTBl> zcR<}k>cIl1bMW!ImvRhBs*FXxOmp6v+2QqdE=ol{+Wy#7}j0P4xNP2XnTV_w!o-KyLBV5muua0ZU` z+fUY2O15=Mq77xXEyj3)dGOOls2>6XsVUqaW0QzTfx=^K`0vN^10>+lV;;X`!UgVq zInj#nlgajp6?+otO|U5zQ(e1m8uzP{B9VL=GP<`}-m79aa+T<-gx%UA~ne&1*+bBuI}G*pcl z{Cvsoe1wP~Rzt;x?#Aj~O>uX`r4yBMF!4splyaMu@`iBU0#9K!!00|s5h{^b8UKbx z^>n4f&qBWgm3{}zg=EeVRUdts*NSO_Klv2kg{@5pY=j7l#Zv@XqyxBZIk{DV0JI^u zx(_#i0rGSn?1O-s>(ADWb2qH>CPON*=^6}o+^OO{7I~xQP4MYd zjIrl#!%q(U-v7zsySB>q9fxA5yxFf@2~xddAG3tg)BU50NO-nN5Y-p?3_%>p$={(= zg{6v*ajS|;X)3#-IQEJMy3i2tYK8)QF{J$bo9|h@9=j<9iR9TO_v{Rw*J57L#Ee3I=$_{Lm+HLyp zSX-i|cs4E2;~%Wag7a-}<=f%`jJf(S508a0FWAO(Vt$nl9}V#P3Cpp)fLKT$wY*KH z1KsG8A%C1l4WcZ)?Z3#RBZpq6iY5L`UT`TAL@?*wwrzO@`)}@m_vQ^lE z%cjZ%z&)+Ira5M_Ri>tdZga&&!@n?0uTb1Wd=4&rw-9dE8+t1XVH6H%G5@ftG~cVj z)wCySt48;T2cyn5c`m8PXtWpdt@+2@rHo2}u~Py-vuS8uYklmWH>O6L&7_ntS_GP4 z`BkWBm*86K13l1M?p;Q<9$yy>B3hg_mJK8+t%?UODHTV_-dV%T?Z93Qxi zgW|TBJxA6ImVLD|Hi5~8aMo1-PD`k6qidAm>|A_P>QQsgR;S0?8QJ3y{}*3giZk8~ z0XH_!PP{xkSilLg(2;w0<zjHzt>mC=Fb+^ zZ)8ecm-c0PKW1RGGp9Oi=6VGjy{109N53HB1=~hV40&JQ=nHqo+gZM;Df}mQ@O14V zNoyQO@7+zvPWZ`Dj^t;T&*0rj1EnujeW9~s??1fNK9o_`r#{GH>sEE!^hq+Hc)CiQ zG98M4ryJz&%?wcU7~q^a+g=PEKgg^@zPs1Hs*BH@agb^|K5DPUfAkhF%0O13;DQtO zA*({8z$k)bfwGtf&@cqJfD7n|ttZ?QgDR+GD_+$-kCusMC%Hda=9<4Q&WtO7Qjffk z`}>7^q8Os=7D*0LhXc_3i>k30*0Pz#IQS5$d?^5+?KcQWA=2oXzU*he5jE0Vo+jy@ zO@q%?vR9h+vz~e*X(YrGlg>(YkbKmlI1qC=KSX-hw#H=aQyf&FFS&4aST+Q9=Zqf+ zh&M<)rS*=s)a5t=j0scalqOcY-2Tfi<|aT>B==F5>6*Dv36X(VmUcf-S(94Nhl2X_ zLXJt>0fcB7L@aA^b8gsR66aA9jEca9#z@{`=3mvPs~f{R*r9Ss3yjj$=+28&zjfJ? zT_xK#G(jQ)A^@kPVVcE315}eF&weZXJnth>`=~-~*7=Eo!Y?83w^L>@$NeboA7n3q zy!S{K1p+G2#OrC$dmS9ly~*NIl=e&beJDwvWk>}K<$pY!nAH1yg${^p! zwYviO1U3oa^)uiLZK*VQS{*!q*f1st_co5+d_}eX^_$A67gbT+`<68!Gw+;Q8~l|q zY)%)+F+dEDmI??sn)r~mKC@E7RpS-mKukbOYb>V2YLJEV_0df0TZ~+_g<;~?X2F*Y zzQh>P!gQPjQc99WT)9lwX7wN!=-ZFQh!6yVm=osdw_~>ctymtKV z9>?4dbf>hi!|v(_x>|&$K#0LQ^Szw0)n`eh#gh*s6R;F?2otjV%bOw^hCQ_XbUAO; zrVW@7blrW<$)oVt$K;)#;`%?zOUS12q><%mw}@w#T(7*;t=F2gIketAi9*gR1I@yl zBf9^tW}s^)shH3BRpkut88IP)wBibyOH+Av7)#@3&rAWN(nhP5oa97U_R};VAs5q^ z#QL?=>cDBs^Ny*uZ)8^L$}ltJI%P}R2*1pV8(;LFuRPWD8dWSAL?;|D@jmO)Bv#KC zn>pOt`l?XCsvO?n!>f=dcNeKI0`{M_t07ZH)#Vq{Q`C32ItvQ}xGMADWMb9qQ#e(3 zRS6e)7n?7~0j-O41yn4;(d^eKARvT*^x^^+(mtP|s?THXV}ul5VN2@XIDC@wR*u`i zD-R1atUt@L2rCU#mmNuA^~@Q+uXqg|ixu3ACm^b3pnUI|l26u*s~#jLy}! zDf#1Q8oWYDm$4Rca}}`XEa~jk8FJ^O{xS}+F?u2vMG$X5mizVB$e9K5fOzUk6yNjJ z8QQhUH3bxS`)*ouB%X{7@F&9~^=gn$YX|H_B~Zo1c)@>5`%X@FJe$rX-5pSsUYefw zEz;;ApV;tsyI9@`M-0?FkP5_cHejs$Qvh6Rberi*^P|%AjIyLxm z(0^ak-%)=3W*P}=TB z;%%l=29$2gd6QKIMj4GCT1&D6_sw!mOyK_tl^ zmVOz+6C#m1iLEJn3`n00N_(iljB{wDGkM9#A;=*zVQRWqR;y`H%%{f+ z7>?g7#eTn;NpP?wo|mQ$#dPG@zy8IPOxAq8>{PSgq49(CehIhRVu5&7MSc)Hp_Sqc zO3Y?LwMxy0b^Y_&hkM{9R9ckJ)#TOM>L!7`atBJo^uDwjZPspBz96n4ro1NRspcX`ot6F|99kob8KvjRX&823q5U&b&$$f94& zV^EqbnzqG!LG7EIirqB}m{`A5z;xZzhLhBRo+W&fp~52P?;sl`nzAYyp!b@U2`u=A zQ;3f37wrqh6*zh~jnBIeoncN~VR6{%z>r}Z-HK__jsBCM#wn7a{m)K5#9`okLx~Q1 z{{*Xe1=eQ)E4hH!3qKl6O#)Ue{E`8JWgH~MDv`82Bdak=v*kn>0Jv)7A>oEq1;aC% z2TZ+?JCj_>9_vs!`wb}*mBv{2zE}?yFwLti_Pxwo)D*yk)u-BW(#NN&XfX_wV6>Fbj(#R&R>Gieax|AP2!I4q#mok( z7rQs}`jueZIFc;LD$tuwG4(qNb}ot++b~F_^fpj5C?ln~@9xQt@4rgFM1TT%n~Ell z@;p7T-icgpH(4>&=t5PBf607$JBD+ctJPU8`I}^LmE8R${p>~erVR}D%Of3)_jQp=d{_x9HyDAe2pu>vT|CAZA z_CMoAn>pp^R0DH*94*vcX%hQb=2h>_M~V2UDvS~UY@(zDtCB?>Q{>!ikQhO!v1bz> zkn0t(c7l1IS>vMAfTA`aH>&h-7qJruJ8JVC*wS2Fd8akm+*jzk^g#nE6zZg_m^; zg(8a;o(mxW)*#GcugLPS$U<}7e>&K{9WJ+td^KoC`YtKs>m}qa)Gdi~8e#q9=q6Clq&n(lz{KyK~Cha4OpHlSJh% ziw?io@lVbHw#|MvMAW%c!-dzK%YcT<@FypRQCo^w&a~IEr5oFF)CJ?~%qhwY4uSwo z!jIcumU&)OR?VTCSIRov1)c@>WOdi176~=yGd1pN~q<(%_lNp z$}=1++}u^FefvG8BC~FFs#v_Wb%<*(8zBk9$AmTxi!1<}1Lu=(9(LM4t&)$^+Pp0p zU3a3ON`FD6vtp#rfie#L^4|SiRjRx)Lx5?Z9NK9#RTv-^IY#mGU0cOC+rIhou4I}3 zbvFbEPf|bFsF+8SsdwgpYpQnXSIV7yJiAq47EdKHQUhPKh=ugZt|ni;$%YObUs7_$9;P-!V&0) zsWG<&t$ZP8@Q^bOc0AbMY=_0BGQfwgJ!Q{`5yNk~rcA^mv!_O1R4W;wEzYMaL@ylu zt;syux9HC}yZjR68(+$1-#c7b3>7+(jUN{AQh_vA0!o-O?SLXZSFhnkE1ip~VpS?# z%@6WQ%Fnc@Pj#42(dSq(rVLKq!0KcFbdg1irWn#;Hp*gzc0g*5vKvlWrJRk?aZ9sq53Erg4 zEH3;-jVcsvB>&6QsxIj z?q<_TJ!JN<7{PzAP*N>gY&B&uEvY-RioP(`K+CgZYo`Pq-;biMaWvD_%JKd1EH4YB zv;*~-ZQLWb%Lgv|trlsRtV8inQ8CGr3{M{Ya%A@#xbpvA+Xf^4l&cJ_@iOyVYIBfu z)9OBVi31Z?(Mg>&dBv)kKAl^Me5>tz$=thRYT+@=#y>La>mO>8yQLzA^Hx5=S(x@K zG3@$X6Z>Xf7;H2NEs0M~K9E9HRz!WU6=1MFZZl@S*DBbqD(v}H(Q~@%vTh9}yw0ag zhWbWRY=Ib5aySp)(2Ov0_bO_SejQ|v=quBVj${wgnV!~5x%7{=vrdBSZHobFz5WEu z(!~!*f$#v4DK(kD(IUw*zAJ5>H}^hrwisrD3F2{5yDr|9Lxl0Pl@c-ml`^cVK`Il` zH=Hd0F0RrJ0hd8C7Ndhoroarzlni^8Or_uE?{}cPf zhc7~c^wF~87LbB^sPsLA4tG(j8d8_JlCUJ)RP)ue1@$aP1-34i1uE*B>Uin?r;Qrh zM2`nc>GPLaDBas$NP?w{|=ll2vkVli+gDl*U^znmx z1bxs()jML!G&HJme(E3(kVJA1$|X`UK8m_=KmqAQ_oqA7GjatfVd*ibgoJ(i+O@bL z{n@$dd9zGv$mL57w5rk)4fDHB((rGe&MlJd1iqD_q@oli##?T)KKlJi!kj*T@haSy zXKZS9(k#JA^I?{rT(ix8%=NFALp932K5dJZTe}R_24k{}g1@U`o!k8exi0fbgESHE z%+as)n7}->(I^Z+J_`u;>l4O;@`C$i;`_E>SXqxlBfn^HWC1XKz>%$wAqXg$@&T3> z{=;|V2lf8Sqs~F0{d*)a6~SW7Kq-p0ENKq8-zURj?$CR>HrYi>)O(Q1V@L zIwq-b6d^z5$R2%{_>e8`JljLNV>^MoXAZ6j_S>FfGtk@*6zuz2%nlkFjpmJ|1q+(QIU;&vdyFBYM01E5z>StexE{?IU7_uG=2Jp#ou~MFD*37k6)(`3~#Ku6WucEoXM-*$%jrU!%i9G zw9WI-Yte8Ha*LA$5x51#(|AkX7mLhvhEQtF;-m;Uqcs;3+ejl?-ulaZfq2js#! zAAT8|YHiT+${c6DO&TECzrB)dep*@J*wW#mAI(HLQut(jRnu6%=})_Y_*QLmRgZRx*4HY4_I#ihE!?es7Pc{Gp541@%NI_^bM=go22%+*z| zVCO7Rqc+|KgN9EZxcvYPWZ9T*q_~>p)CO+xFrd;Q+>cA9P23M>fogW zZ*3ECGZ-juW~WtpVrkzW z$H^i&WL>&aPGGrP$^K}r_FfF~RIJ2d&{bOg>{|jJ@8UamC#oQLdApwZfADpeL2b7G zy08-xGz5Y>1SwFgP+Hs_3KZH>oZ?=jxRv0pMGKVR?poa4-P&Tsp=et)Z=V0N-o4kX z*|YNLp3Gz>bA7nynxC8pah@cjcD@phkI}7t)}pd|Sc5%!|*0)p@E7y^cRV zoblaRl^;`GWj@@}R*I%Ys8Qo)`KLKc0wqd(1g_~9)=~@V`4Dy!#$DIEOaQ7WJm8Vf zI}Def;@8k>uisn7P5{j&1JyuprCTLJoZeu<$|(uV@?jvvU2L%XmkPb^TI#?qjQsRa zn*0qMYonn1x@IbbODqyYE;Y({UCqE7q|BLODfc+EFq}UihmhY>I(FN^L#R~=cZjr( zat7ulg-=EGyjJW+%Q;d2*W??IN&T#!IbhXBp60BWQea>^vX`HEUPva;`m)#8$Q1_z zRmcRYz1ED9v}aM9Yi<|c;bX;8+T<>_YLCS~WO$yt%@+4mIqSYxC-#{IIlm0z&E*!A z(I_LpI38P6i69^jKbO0=R+>4IIEnjO=9?=JFHftSIcY=TNrDZDQDc7GC)usVFJEh8 z%5AB+oeE_?QnW1(!#?|SWx@)Y$IJu!65U7&o8#w*ddy8SkAowG6lcaZH;Ch@Y=Eyb zKd1%e$8r3~FOqy|BX3AN9dtrFLVgemdAVJ|9QPMn1fP03q3hH8{L3AIJmsp-WW@}{ zI_5vk<)sn1iTO>w8&cXznh};P5xaMNw1SB}$rJU=9N!}3Q4yMsJUrAa)$1KMTBu3H zm$O`+i2UF7Dz8J}Ne<0J+X~3Pgaztk%*t2cVo>2XIU>PPZ5MgCMyvw~pX>AGp2Jln zt>;Sy0v)=aQBysW0rnh)l)60+*LxoJx*~SIoS+-<>}}BVl5G=vKkmb~!yHqLh4n~x zKjr+rotc+uQ%w1Ad@!xPcAEpZtm>J)DbVSkoqiC=2e55>p*zpy-q0z-i7oizb>mJ? zi9*z*yoeN~uKC-#m@5@4#|Ca`NzF`aLZRG&VH_$DE}ifAjy{!4?c`FYP_cI zuXb9NrZ!=)_`ls;1G%QXk4*?2^EliIw z_cLK`sU^L(+u|qfG!N(Y=r?-%hs|Q zQsNKO5G5MdNvwVT47zdwEXqC7^yO4Km1@fv*3St!mDYKfOZ(vthp3)xIEWMHQ;=Hg z>xFEit8C}SQtM~{KP$ip&;AdIR@wDbguX!TB;Mie@Cq`qk?(4!#m-3bro6zQHqpav z@?#Q^|E^r6HsajgO0d=az(KGT=rp&hxr$sZJ!Ts_BlKohT-`dl@~0Tze$5zYN8hfh zG^ru&8fU(t-NIh34P&Lt(x!9;zg_Fy%DnXwm4-zdcgWJ+qxeOhCJ@+9+A7pfRwtW| z9mC2z%zwR`z8OW)yHvhdWjaO%Pkw!W`Sn{G$WhXJGlT0K5v0!_@K#l6TBCan+;NcE zDKc*LtH0R{^iXF<#P5); z&lrFIKE~qBy?+{r!RB<&0Rug8I+ZY`ayLiepE6+?)1YvAaaeK|!XJaFqEN8j#kBFi zt}^wR0T^PAQ<)tf2CzdH=nKma{}lJXahcDy9O z0r>bOUvn{LIZwY%C3b*QpS|Ok?_A7!0gz|}o?ZaMTo+D`6RGP9MwX5565S(6-UV2E zTw(k+_-MVkaIW}dXl)W(ln^Fa1qtH9=gXxS>ZYGFp_Q+*Y~~|H55n}<2;!KmKJ@>_{0DE$R=yR#|@H0y37`Wq; zRD#;g1-?4+L?I^xa|=2Re};vGn9~5Z0)EA+I`&zB@Dl4q0#*VoM3bd^3ckU0TaM)Q z>|!?E=rEcgQv69@#>?Qw1o(aW$67tmGAKo2hV5ky>uXJRW-iu?=ubzC8e*mpg9GA} zTDL~WZLV{631@2GkvnUGV(((MueG$Oa7up3`R8vHzIB#o3}&WnpPXc&`KafL7dYn*3ohODa(u z?*p03Fis;i?=9;{8;Gge6Ommrz4%?kILst^7^LL3#Htt1UOxRo{`&dV3@fkH^Yh{7 zHk%YAm46-hSuV~WQ^oK%RDgN{c)7YCeT2tKPgvwKkz^8U6((g3nZ9d2(J1^2k@{)(JN+BUw zIkH|mva9D(7N!iXN|Y8%zg|6)asDJReIeLVN$&Bfi8p|E#pIC{6AqRMF;9*PH$YKP zLDB1(To?wk4L@tXi+Ek7KtPiGB9z6SOPSAEnJ$VP$Bafqm9-0@QdY0NjQfI0;RV$7 zrA02LD>mEc+@mhd{_jvV?Ifj&Pb>{C18GupI3S2E20`hYG^rdFD&WftS1DOj*2y_l z{@fQDjBtI^uu}k>F;xPk`j`JaxY3CYSXRuP+|m z)iVH|YiMG~i;`(FUOsJ|kwCe*42VckWhT9K3sk2lRoAlCo-NRhbJc%`@urUWk@1B_ zGT9SCbHSxXx*7g)GZA$E zCkBPWT^vCmhIDuH@bLQM<|ydlBj~9w=ur;D^#0=!(galPA{2S*x`rVD4~Ez@x+NFbIM{FYA&=_2ZZA+@OaH^o(r!j0RMH#~%R z5AJ{E;eXxafB(lHD1^ZDMBp|fpnnk;+J9h_0n?m>zX3$#LV=Gw10OdBa{mqF6AF5c zem3znnW;o=B6)kH7kPu!m;b2$SXADm0Njx~&6+xK=ZeW0yLD^(bT)-%{RwSN^^E!B zS<>Y3+?Zpc3&W||&8<1ykJ2+iD9qn8;?tk-tY-I|X7B#gC-cN_e}!Rv&fz6^$2zZQGLHmDMRu7AbZfbB{>>V2fh_S;IBhep|6E#$qSxK6WiUiRNt%z>;Cc z>C%xMOp9KgW0dH^i~K-Rj>G{NldhN$=>4{sPt%G^W`&X4%WE+Yq=coAeYl`Z;^VjG z^eCY2s=cfra_$Wl6*R+JRxAzwgqMeN`<(8;gsM`@ZgI)Uikzio+j1j~S*hXfpxN%% zQkv|w0V-qxi3J$N$+Mj{Bf`2?cqc4bpByv)n>kSHlOPpy?J%<>Rh*)5#wRcS)UR2Q z>;9KeE&g1*!mpnzsG_P$o#MX6DE8=Y@iX@{WFCJ_y-v^EU5-qDnvM@|eds1%`igPr zN=(d%_ZRx**Vbn*stiR8%m-Ih!N6>DIAt$Y`e6FYdtu~sL+WP$J&r8>UWGfrWk0P9W3 zAr(^ebJB4TbP)sFTAFsRo7Nf_55<6_Nb4r$;Nj;&Vu5tqIW%`zdObPx#RV<|*Fm8{ zyePdKB?IbhV{hZxJghxqBFc>_plCIwPc?39HB`TvBBzSbrv`hKxIBm9Z9omKXw7{~ z^&dFl-!6N}8>id!Tw$LlXCU;rDb0cmUZe>@Vi%+@hZ27iw3I`U2FHtJqzg7B)scoI z8k776$^y{^VrkM$1Q}_F;-(%#0`c@gnl^sD@`|g9lS=%f2oa7+OG#@>#cfNCXlui2 z3nYL5&!n~cwnZx-xkt3M^|rNY74`rpyo19Wy6R-TOA9_5Bnyj6NYQpksdMEL9p&_* zQCwOoKvG{a9R}62aRsM7c)hes*~nMnLX5~9UU>4?jMipMmBO0MA_x#)sI3=;4xEq{ z>y!8Gle~lOtwWW>`Xy;$pLs~%81$*p_DlP=-*@3tZnWpzWJ^P;E%!Z&C*drUU_%e9^8o3y2 zjDK5?9(v#yc^?x9NA&Z(nva4GREFt!{GTGx6-?@|^TAwn@>$yPu$H-5IHKN5;)&fr>4r7ESo<NN-+XX%g^-JHT_&1{WxY0LpdW11J$>8ZI#KdBnLrE#8p4H8i-q&% z^n~D32`v5o#URQG<J?u0z1dt188546YC zex)a%_Uv!!xvX194+V;DeH~n5axH!oyr=t#ZSMHk5=9`<=9#dxyFwr1)9n4Z&80P9 z;pMzHzt{Plw5ss+;=b**{%?`b{v$x4S8iLVWUcQ3)WbC|>>0 z27U7Ie1g}bl6(hMVsa(Pd+<}*2(P1!fvo2xo{wydE#0iOB4iqhWlUSVh%%)(PDk~P zq#|t!Kc`p{zvKLd^*ZYSS1(Cp;!>9hX&f&?lJn%lbwTRb@BwYb)N;#oUIqut;}B5N zc?xYS!Hc7`c9}cDa%A^_|(kWQP(90rEhk&IkaPP>yMSbMP9yF+91!jtH~_v zFC;pao14Jc>3~!P4mKto8IC@Ekya<{N15p`SIPIOW0@)PP;cv_YqcV-M?Ej#=YZ%h zPrR=46z-FODCdD%d4u($y^u&phnr1sw(r;b(eDk{71q|>_g}|8Ab5)|33aJS`kXxn zt5^HRB~a126O8kAi|ve{=e25q2=+}g_M+%qH4vxBMHzRm2Dc*e+^J%mx zV9GLEoMI`*E0b|Zkpg`el1a~8n$^%Q$!^p-9B**-Az5qc_UGTeYPHoDlp?TxGU53) z%tOxAP@yyH^%_6WG^XCI2(MZV1Ep`%Fc#1$<~_zu(4n!hBk|qyuu^u!yV9O{U*KnJ ziGi);6pnVW99nm~4!0Ga-tlnkMw>4b#(2}`svatAyY~LX}>t1L>b;ayPa<|o@b_$P-jr@4ecS_^;wTvK?Y+t zZ&@e@=;vyWk6B9IC_4q_MHr`93Kp##SADo|jrg>OMJkAY%9cHu~Cc!1L0f-ro=R!1JqwNyxt_`()`fr7MSUewCm0#*h&!} zzXwMvr;i;sE^&Zgy${LZ&tptxPy9o47~y1}&rH-a6g;KL?Y?Hb_CV1k9;*4+=@3pi zVAb(E;6>6V(<7ys)PzuRd(u@zm`Lmfotpf4LcQxY7vWRox;G#Eoik`OR=UE(*1F@& zE?L-@6^Awo_}&hSF`g4AMk~qX;0>{deKvnQsAubv;W)CR_dz$s@a+?uw8KF{H`7q# z^Bia#qZuPn#DMGoe}df`C4z_U5VdcK8F!iM62oq?K0kS*JZ>X2kY^;46|c<)NLj8w z3oBu{1xmJsCck>KQrj=ztzLuxHXTBb(*$C`JhF+4TABG+ zP^}?sKXiE&%{I*vj`EM(FSadH_4=;W+U&TdmT$vqW#WrmxZmb_KKI?ZLzfEi( z*YQV1nZPkA-++0Xx^7Yx2NBZ2kM!7sY7W;|cT!t93wJ+qm#^WEQog5o&b|lquPnO|lX+9R@x?3R@Jrr`( zfoFEq^Mc3aKGA?|r?KzrU#4VJSt2SDW`QBHtEc<5D&`cjuyM;1ew&Qw1-5s5Bf2bP zoq;wChZw@O*{&#S_HHp1rPNn5MQdC)0%b!c3Cok25^6CQVP+s7Cw8y(UbEe?y+6CNKuvAUhO`Bqn+3Ux4h)Ea^@uu%tDqbK^#NEi)dd{U*RtD^t*ds;!0 z{%K*9T7zE+zh3`BzXrkKHV@HK6`s~ ztI#&jRYcH_f?7GJbAFpuez)4Ct?xwlyIIcvbH(e7w|k*4y;r3j&!+TGjtipb)_Gs@ z54!E2H3hUu_`nNGrYf#fwr*!!wBLPuZDZ5g`+3;xmyf5lg9BmJ{Yy&?-S7>E51$v7 z=U3Fd{Mb&;BU8WqN*aW$<9^rU?`t{`PQhg*B6JO}x;u=q^1Y1hXereGcoq9ve0zd^ zqMlRv;%cMKPHX3F5L?F~F+=;W5Qn4cx{rUIGuuGfmEVh_B7Z9{_u5NFQws7b^tBMS zj|9Z|RiTW^io>!GBM2WHsI%8-8?$KAsxEdZF8w1Hu1@5$@4pXb@5NJm{QE1r@z*H9 zwZ_{ArwInsyZu4w@C2XvFm7~gssXnDilD!7nE6(iKampajg{-2p!LHp{oWt!gCctwHs!QF(fGg)E6qWh|+dlv-ECTeE#i^ z6*qe@_gUbuHrrFm4>V~{-n>FErZM5{If)AeUN-r$Tl>p~hivXXCJ(oxq?Ey7`*5r% zBi@ZAL24^ZX&;+vs-+ZS_bITXDNvU^Oh`7MXfT9sH$*rfxToF){|ZYmJjhwl5zo_) zbt!c1Pw01wFc+aP`6d7M8Z6_bu=p!!fv`|^wvZ6dz%c6&!lCeN%ExZuM7E*CVPsn2 z3)r8QP&8ti>bs=jzltI<*`s<>A}Er=rT>9&X>vU!e`-?}=`i>rBVWj1cLr#ru!mnM zgvSkr))!lSK|{EnuvpK4U|@8CK=h(k#1Kx@*b<_kDM(@uQNtSZQz?x?CEs+Usn?}B- zE?I1WHJ)+fN{K>V-c7|eZJvo{sfjgW9W{TDyupej{;> z`t-s|G93-fA)&fm`X0rJ{L)EpQWI$UUP%-sF{C?sERxycl6!@D*xL|gJxXqPn~bEC zj4>umSO+&w5r|2d7(GrhhNakhB#B%yzI^`a*>x~pM8t+rh~R#F9!{`$M6BCa@3TB; z1005hAjmsSMLtan{*&l)%(wIvcggfi$plO^9GK{d(39 z+%FrCzicUg+4f2cH2!>|7*`@3B}|nbN0nR|fVn*dt$mEy&x@_Rj=8CUk8y?q9!)`1 zVVM2#1aBBI_IdF&*Ksb4aWQf*Z{T?9U3h=iHF0Zfri9I=Ew(SVU6G?~`H zsA@12k^8tbmvbbS`yls8Y3`GC?9&`Jv`H%%nI~MDCmNYo3LpsquB?UDtt{wguV;xoF!@XQV);AKT3R+zT5(WXg;!R? zQC6o?)?i!K6j@fOf@`No-U){Q07Y2RxQB2U8m%n=0O@!k8|yra!Z4##LID6^ry3We ziTBMI#uTZ^ah4gy;Xb3BwGfd7&Z%Ir&9#oKWWNEhB5~x_D}UitopDrMs8n51SBam3 zTu(tFT~+r7RVch_AZIn`w(7d23ak&>=P0x)t+o~^guW;wgwz;w)R2r8kY!ZbiliEB z;QY`4c2O6B0zf~f@IZ|JrLTJ60Y(tT7@E220KlJh98du6fiW!ch8(T(s)VK2SEuhf zWj2F-1opp_<0e;Je^Dr_4_Bg=M-se&qhQ@4FeW5)7(qsdgmxk@^)&E*NEz^m!uUk% zo^!$kGb)%zD#SBFJah@;t5c7sK+D7N>Ls6)qnb{a>r1J!^8#>CNWy^I|FT#AiGn_@ z!H`B1u;{}9o@>-iaKNTGD&}k}mTYq(M;b@mlYbf$>MtiV+BCh;kMnJ9I!4ca&?gY(%+;@T^VwFWR9AHZDZvZx5l$a07AUW;G4MhIO#!Ddgl71dsy#SA6pn5*^=sU5%@zfk*ne zSZuW|dIZ&$x0)pKH))o$Yvx7Q{Af!NQMn<&h&~T%c|BuvD#ueLQ|85gGMKwEC%$%a z|82watuOXzFNmrK9d(O(h0yr=(~W&8!|h>d>tV2O=dqWi$#_f=*;821!?f0edDl}0 z>E)vBB~NH~_3GV7?FINYJ&o=wTrT*I16!)}>_iRnYt zb*Q2AXoC#=kx<&X%e+*viH*zG1F8P(=_ALbjQ;S&>2SV8D_N^rV8Q~8w!V-F3#~8?&Fy! zP&7|F%da;3{Qaz8%&c(5tmycx`0=bHbWWOkjxz?+GLKj`W=^?c?#1|=+VR{=C~97F ze6HY#$ch*fbU(=#HGfw=uOBmMcszfJzhDBLG*eqRv0t#tny{%@*d1HAGXU#2@kyEi zq@+NP)TYe>7JVwFy~h{*vlb!Hr69WLk7`R{<5QtAOH^tgsncdT)3FS@aT1|rT9e*X zy5&**WtxEHjF{f^7&vmAOdy&$SA3-~i!Muzy429OEM`UPb_Jt*g;H^ag=n?lc-dcb z^>xy!$kWvpztzqxik|mg-F~Yv^{b2tYYa7OV}5Im-&O@>fCWg+Jic%9F;t6c)GP15 z&9#5~{_We+J;hqqxAhq3ZE==8I+la>?>kxFPt?ZGxPM%z{RhI0`Egx=`f-bfaF2hW zpzA=MbP0B z(gkibR>LsCH82Lhb;92`d> zf1&74GY|xE@!&VS*tIc8yb+|`+36Y2*`>p;zaP~ofBgcWRZ=P>NDm2cLgKa{&&tTz z7|uvK&&i*_GP>v>2v_7bEZh6r#R zFX6<*C2r>_6vdOvOW>A}p0SL+W4ye+q(HYL$c-qf5zwLl{B~YgKQF%5*&e9tgdNu+(40? z_d7FqKP4z;ueXwJDQLBFyf(_<87PVkIHVs*u(pm?%wgMUfa2T}B0w-M8ISqW)P^ho z1!I&upH%6wtcN>n?`fF!KDm=~Wl=t7mH~|k0O3uw+b`1iEGF`GUC>ceU?>Li{E4y* zy3P49{y71L4BK9$>$NtBu~8S7xxEgTWVb62+vh=!($#u8FXliR&m&fcD7Z8B(dGH1 zf>xroo9z|un_`(<1t7v$8&4)ocY_?DF}lFL)+}6iUcP!&8Rq25qz>*X)t6x=2TCQY zkU1-UjcQtv$I(3>4(W{)kBM|Tuv)62bTz zXtj>?wVH4PnYN*q{E)VBNXRb+0pO4cgFuWNp7KQsx<8`t@~vU5lTnJCka zuT%N}qi9WC-HeKcHEUp+Y$oAEe)&jn_1uga9(Vmq13#eWf`JhV>ZuZvuM?IO3_E#c zqGK|egBvf4bYQA%Tt;j_eMtx-&bBic;qbf0 zi^1TpY)FtM>KtSnx!De0e3hRRb(!MblU-%~4y?x7(wT8KVqhw^vwF zA9@yKaGYB^vEcUYqY^&kWscvA(nok?+3TW&T*m8ulcU<40R!Z8fSLCKbZ+@`Hu8*% zsL*!19aVZuE9nN46@*K3vk%xe z!AC>~x~==cO822hC69YIydO^mSim=LJzVe3vm6;;tdq;K^TsIw;JAyROma^EK*yJv zu{Zv$4?u_s$PtWKel-Ln84C9I1u_b;!&z6R0m1cw?(<*azE9KQq13Pdzz|qu2lP+q zB?`_e#|U`inN9vVj*;&O`0$W`o8E82KnO-W`YsK`QGqd%f|;&)h59ha&%70rr~tW0 z0v#@vKy+IgWo}k$afigVi~gho-vH~^=V8Z|hKROQ577ITn8kb`B|qoGdn6`9kL{fF zWP%Z!8E#5v5-o6=D_*65erUVR@trewChw=gFe$Awo5*%#;7f z()`g!{0Jrar?o_eQW$hYHPisO38^-FAbD&z0V`{t4uCgM%y=5Cx)&6*<7L4_5fQJu zaGpZCZ1Kc@xX;X27V=68OGra0$n}m1FD5?h(b4Rfj?AZ&#=Zg`ul*Os7)abJRB;GN z?kU7096NK9rATK4#HK%!jC(l|&aGKP<`8=nCm6lQch<5K$rcQLHFrzr_I?%cZ@fROD3gVklfv zW(OI|iyYM8Kcur2yPeBhs;q?k=1NxgP#)rt_tx6kb}bTrq{}+y9QUC*&|Fd~ROG}Y z)`UeXO^t|E@Q5!qbw#mE?CP;h8{XR*rr>f*dAnEgQ&H~Ky_9mBxB>^$ZMS2|W$yR3 zI)i!(b%oCvZHGcdS8Adq$$nQ)@W+`Rs`L)*G$4OH#(26@Gt>>whd6|AqCSeP&QCo& zV`O_QuiQ|mw=h6f*820kqu;ImI+k{G?;{827$1XeR_(8&77i|1w+4F(+AXsM4sI1b zhDVm#t*bvBJlby!PeZlawjMcpjr$l~7HYR2S~&WAyEXbdpxtp%;OKYk^X_g(yYu#^ zqyPQwI{>y$7l_p<0P1TDX4C10SULr*2C-r*>hzElI)zXf;LS7UV{6nqg^Aypz{1kn zDaoB9)O<}zi<<4Qx^Tr?a>9e}%IL=sV0|DG$7!jz6p!(77V+PNv1b@GmrGbA)zvYc zEI}UuNI4-}TX`}?-I3RYPs5`Mu~_7C={27Bi2vRVcd5R@yM<$tFroNlLtNp3c5SeD zl6)*Sb2FN;^+2*d;8#VYERli+xT5sVN(x(V>Y)H3_S6pYJDM-Vo-Q=m7)THr@7YK) zJf=o>M))L}-EqtF$8L|HwMLlUTpqb2=>rkro53ym4q=5Srekj%hM5GqZv^e~6u)xQv~OWkQ454-e=iqwm;cgIOOY{3hS3OJQTeIoNK zLc}KkDZ+=da2w8?sPTUx+|2+aeefF`uC@f&Ti%uFS8s;c|K7hJ2NLPKl#<$|D9jG zyZ-0%KloMDzxL|Y?}w`+)W!PMpR3O1sD>w~8m8W_T`dijebrr~4IkT^k^icz&0iZE|4~=# zYHDi!qpn(@%1HjBu7c3&>O~3TT>;i=g>Fk(IVv52itw9H@@vel{Qtex0<^bUS^E#U zT2WC^P@VJN$<=~?(A9h-5}BQyot2f9n^b7lZ0w)w|F-V6MwL1mSXHY~RW8y=O-)Ts zPEJfrMDwe05lLZTVQ6nPBqRhavwjTys2=Z&@_t|K6BZB<;P3ArAPLLh|CL{zFCH)BtGHVo zX((H)GVYC}d(l|FTxUI7YB<_hvD)OcHIntBsnW3dZS}#oQSGX@Rs;w_ui9L_(Hl+@ zc0B4iB+11oOY9}b@^ol8ncKgwe3^N7f=)7Mf!+Jrz)azjT>26>oUO%bv&p}^d8Nmz z%`S)E$6K3z{m?SIy;qbI`hn$4P5C3r;QB-Rc(z##&ppT0!Lur})Dl0Ru@hg^4eC_= zyJxsR<4D=N$&U8hKc`!xsn<<^eF5t~b{DhnB+xAL@!}W65s?lYQ5CWKBM^|8N*@GM zVBZKPeLH0A2V`Q;4mfny`4YxpOUV%aJwYcod}G=&$A_SDZ!?N_fSoy-^1Bt2yWnOx zlmEnWbDoc|3Pparq-nu=^lC%+cA~1l{`RNdWkoc#`o`vGvW{iR&lJ6nrvumqp^tac z^u2KlQ}FP0wgbc`1h+ppQd1OV+O4>lVLRC`Ry_|5?(!Jd1 zx7~Yr@d`J^dC|XlrNZ1w1&f?AdKUKWvI9RqR`Z~Cjn!_v^NRmc+IVnKR?Ui1qLmK* zUJXod-dX7;pxZt;tkODJu}h&@>yjf(YZTrrX5@gpEB2G7;jX(Z35OAgnUD5M>h-O_ zy}yTYo-}V_p)1USZB_s%*54+FRvfAf%Q`BNTdsyx>+>>=65RGz69qN3Dkt4I zY;ER9GTxeimZKILJ{cNb&49uOVw)#%SMEnO<*NUISeq}Do3S{{&quhP3|05TdPRS< z;y(A~YnO1qHy@bXhtN%mgWgZQGfWTEV7h}Jz8~QhJieS=YWH>VdG2GadraDN~f{rUjZmSXEx{U@PAnJ!`6m013g8gH2NWd+(=OS^=@o z$AnsOzZRR@-Pas7e6oEnQ&@gMJd)r7g)kqw6oI8yIp3ZZKTb)1mg31 z3(_Lp1YX;wWPYHoAK+K$OUD-7G2*g=6eg7(c2o9@9gpmr~VJR)Uxj zW}wOpQC#X1Pc)8~TiYU1kqQwbZtkK#G9!@-mtmDz2bu9Q>%-WGFlE!~pn)1@O?BUC zh@Q$M$Hawrjxm3VP6demJ&Qx&=fko02f^%MFF+R!4CNfmI@1fnu)*R1@CN5Yx2ZNb zhn~H91haJ_a?<)6W(S@T3ofq_iOo>v&>HTp8Yfb(a4o>`SgaR4I7?}+hcVy|j~YEp z$Ky)pGi@lw1t4W;LCcs=0jHtN=T`eu!q9+w+=CX?Y_) zU^mI{G+k+euIOVLB8eXoFw^Wmz|mVN7vNlgn|&ZwvoVeE`^ABT(#Kg5FJf_;r=fiL zqylblC||rAnXjZ~D?IA%e;(}=#EtWe9;}9x#;k?7kOtytpZ3v|S`%{FI%jDAl_Lv{ z5BF^gz{-{iBX&TRzwW6i32)~(K{u5gVNx~G!?rz*2lFF(3rc$+gh_iH*luo%;RM8_ z=Ulpgxrt4-GZiKhPZSd5n@e{-g^3Y@2Vg}#%cJ`P4`W?u09g$M>D%5FW063XEu`mP zJ0qk7T8JQ?rpYPXc}EsSFTMpM+{6Q;Ub^Gf>gv#^x;wZY1ZYTUkqc?RJukPwD;xd( zyJx%QVA)~JmeoMu%b$*caSg7P9H{@!pRfBdC*I#)tYd%x9X}JQzOgpW9o(ljGc_bo z*H1%}HU;H@mg%n0v5gd_G%>tF>Y!}xi47y69yY93^u;$5q-FxWoU2Y@R?(w`K5TtQ zxXvE)xF)0&6cSWv@`AOD-)p;JN zibznNm;eW3$cH6ny2i9_sb*fNSGgIAtP>KX`-pd1wM+Q3R1@*GC+y!%vh zvHe#ez4c1of{UWbTERb+uPj&@a55F+P`}i#efGfzjbPe`Q{fFEdWjmP&@uAnc-QQh z#Px6jZ5$Tx;Zi>dsV1Q+4j6K`2PVRd!G52T zrf*0+yEf?e-o9GK^3MQZ$e+_+Lo(VDtxj%@(DQJ2oIbJ{9eyWK4p`j+0Ia@--#yPC-%&rGz6PGqL6>r9)+nXBZ*y&~*fD4+^o67y5Cm^<@}c({ z!5H4~7=Lu=-Gryd`*AFQAFUxg-8k$YUA0pTXIqED)zZU&PA<066{7wnN!!RGR@g_J zM~8>|=Gf8phZW9|H8;TZ;lP$RPcb7NTXGL*$;#>nS2b>##U^$OO6%d&o^06+Yj;aB z!%lcR+GI&5DUd9>G;%E6McXzVqgQR{!_iL2_|P3UgX(3tQ<}vtJc}kKEHy<9LHdEl z&e3)T@Z$Amsp1ZjvL_FJGDyBUFAXM7^}PIeS;z2jIVgz&RtJJ~<)7mO#=KgSJ2!|s z*cBCW8LMN%eDWg{Mc+8-*EG2c(om8lEw6#R3qw#(?@7sMB*Z>TUKQRqYI+6ag%)^- zopn(lUNZakxNV;Crq z(b{W<2w+}qP%~v6cVYc}ksk8rD0!(&~NK1?O+#HeW2@C^k2xzG`hpE~(sE&ix{wc(R0a*xD zkTJn$MCg*D*UD}v>p5$MS-lvXONye|-&!Yr1Z;i(kvCnvzCwCEYlh|HzviKU2a zo!3^$Z$ULuI1L*3KQ-_$H6_*wwGei&hJee0&^ybhH|`ck8y`k7Aql_f+$p1#un_o9 z0cxkbBc5?R)4^|=5I<4<^@74ogiay5*sD=y}$96yYx?BVc(`O zj&VqGK7@6lS96yV{ACb5jBm{?-eM^0&F_i4zk2KZTpPcL;J6D1UpQ(z?Ss{yH#;~q z#3(83Cq+=OQvzN>!fCNq?;eBkZh}IIsH<$$-n<1u?;O)1B=wgNFp635Bd(Tflm*`vA z&B;SQW9NK+N#f`i0PKX}JK>TTYv8^^WXw?sw@|qg*QI_+O&^P6O9iBZqv&^EbQc%5eIMF5eoi5#2#La-WXJ7~8zd6jX!6oJMj`GrZ}-D~FLt z0kB9p^4x5A_G&ZEiA>Ko^E#LF?!VIG@?yL5;(dd^m-o)4ypD|&);+$aeFMYqK!RSO z8}vl%01eJ23@%UaM?Hx}z9Wx(RJaB(LJda>f~eD~fFCX3=3wnYFv`2IE3FVGFSDu} z(v24EIf`6G*b{3@GHuzDW=fEFrP-zIDVsULBRQcf6hSuFJOG!cgT?#8wDI1&i6fNp zF#I++$XS~TF zYbE$FV>Bn~3A}K8zWU&^jdV%jvI;#z7hZh403K1+Y)MTbYN$q^x|Ru&R`R*>yYv@# zByiM1i=DFyEL~Oos_c+4{nDoHMR*1=5%eofDxkS~srOV87Z3)Tg6DetHCejJahRWqdY1L_Xwz;*GKRfLNcVz*bR>sFp^@ zvby4xI?yexvUXx- z>{A$bA%Mh;S_Sf&KhuRB#-MCbN8`fxWX6zRyo5ur*afZTS3b@8t#!7dZPC&x7I1(o z1mY?BbuuFt!~H8{iqnt2NOl@yov<;yP zc=ingXXW@^Eh})q^oz~~;j-=A`f5#ZH!uDvF3CDaGtgcaSJ1;$ArTZn(4+`!qreDA z1w);Bg))0Z+Iq#-dL_zx>0sD&r@e9peF~ZXti>p{^{L|b$*lEhwDl>|_M>-VUK{l5 zwDoFd_KV{K&5f}+rvSIl@g&;%4aWK{GyCO?JL@Am=Qq+)@JMb|(jOmb38uQ34*Y)r zu0T=02>Cz|){sdAad=(v2yrmTgj~pme8`BL$cq2G$c)^`j{L}w9LbVA$&_5lmVC*W zoXMKJ$%C8*q&WzBAcv&D$)sG$iu?#{{K0N49gyG)kjc4~Pzl*v$1MeSa<_1L%*TE_ z5HnoEXMDzK{L4`s%)$)C#9Yi${KUvy#mBtNR; z9*jcNTOJ_*r!oPq;!4XcHF~AT52wcuKlH*e+&Kf;$dJtq=n+n}kI(G}`5Wdquz779u(e*6B`HayUJ-V+!o^_xB0I&yR>Zl{F zI|RLv5#pF=pszuIj4l0AI=8#;Ko7{!P&LiLkaoB8o4)M3(==hAFdz^lO4L}5w66lf z!jZYJ{M5gfw)T9y7tPUL?X$uGv?KrkCs1jxD$-?L(ghtMXb=p)07-1Ucy683avj$^ zebYM47!w%-0uim#O4b6Mn@7!_23;Ns&Xnr@h#F5u$c* z*8woJDB9PTU9Xvqxti;wl`sjOE7}G|+NOQarH$J3JluQn*aDHT+u(_m&DEAIyAVRV zl75aI`ZFmA9+39~HU)Ro<;ec$-~-NfzSHX#9E ziUIlGw6k-FAzzP-X0g>1xo);A&$A$a6V&J-qm=1=U6W35l$1z`{f{QY2g{*2vGy) zkPBBp1Z~hrv|S;3@S1TZ-9V7wjqXy9PLqJ{m$6=pN1nPVFc3mbrZCRw2eAqfr^>ax z9?TgGOAQk*8rrSSWOB~q`K{ku&gIOW5SK0x0idWWSmu|hn5}jU?SKtISn3s`)^VBJ zsh;fj^y*)!&LCId#&NKZk=Zn0x~NQ_izuZFa?-k57-3m6k-N~ zP1p%h0Ms3&=6>$W?(FN%?pHqPkZu!*>be3!wW-lRt0uS!E2r4gjto@@Kuu5^};&Z%^nh>*_x7 z67TkNjt~eym^zD8KNiO&kvaQ{E`qP#Ajc@00U-Rug`~#8o)c&rrg!vi<`s#tNGjRY3&HGvx^Kb9^ zt9TQuz0PqEqV7Ah~LcV|Xs}Fis5B~zIyp-?a z-Qc{*Z~L?T`N7U20P!o>6#xYd9xMo^(iemc9X^B@QQ}036)j%Gm{H?KjvYOI1R3(8 zkAFl&dTbD9Ye zF!~a1LAw~44n~YH>eR#&(FEgVK;nT(m4YP9jUPvzyzytmtC2c?ZriQk+SJoJ$E)`s zi*DRT%(i}AI>*Dxsq!{Y5lE#;4${AeA78#j=G8%upNqe){{7+e`-eyZpHM&umTqEc ziNCO*gQ&duSVB)Z1t5@UfJiE7;z12J~Q;l+=My!b)}9ET*b$gn;Xk4CUkRIxdf+ZZr}j9gpKA7*@hWGfg$0LUOwMq@1!jD5>%?q|{g>W6OhJla0$aZNzQOi^eq0 ziD3VH5kgQ!7iE;blKzwv&L|;`lv0T@uo6pyxbqIBIaT{qA}||mh*0Br2?mmh3J8KB zQeTC2!#4l36vR+-s?*L}Z946R76CiRKmr9>EphFa*xn+yM7 zF4*9i`L+4M;ff2oYp*{VddZ@7ts2*{sSdYn5|uo;4wVs#r5jktPW$T2I{D`n0B*2_ z9DCBSWd?(+fF>SzoSDL)HmH%O9c0h~K#ObgDaR3svYv0f_P*x4b4MW;xnz=)7Jcc6 z0*Jwm7aBT&n{G~^TWO6XCd&$Qu+bX|WZ*br3v!Mr$b)xsQR0bX)>(;&dsaE3ifFDW zhzNRIVL}sr+K34A%?vQ(6b~dSAd*Og^t^oY5ehp_($`P2?$Qe?!45h!XlRsfWHI_| zv_qm@EDy-xLNxS-kVNET0RX7NKZa0{DEtEn04T&hBm)3A_+urj2!}z8(TxA>Nd-O% z=tVGmBoP@5;Cv@MU-~BXK9I4meeVkZ8C2I03ur?|v16fO0@avZxB>tIY{(HBiSKh6akJ3{LqR8xdA#*VGt;kqaXbk#{vtY1$OY`AJd>g zLCE0=gSg=z8$gID{;|nTela~%IFt@3;sElM(Ucogp|RK~Gc}5Bm8?V~00>Y9JGh`B z0pQa~js_mP4Q2@Jh(bYtXpj(8gBdT`Ks9z@g)1B*9GK(*IaV=+EJXj~877=$B`=AP zEq2j^@j;cUBoc&4gyEFu+*c|I)=F2hQ+=UpNDAyQhXgc)JKOk9{$8m|{q^rFg!l(P z1o{tu@S`gqn8q{uSdd4sV}cN%hav!g3TqgIBm}9VL9p0CPo~FNyqL%bq*Y3Emh@HX zbjmJoqCbbR6lt++;XxQc%M~~zZgb=3KK0p4xO@N#KZSxdb^(QDQ6m~1IEW_JVL|{b zU>=MBfGetDkRJR43jkOJI5fyXh-i;9LZFuu?zIq;mX%Z}wb~uu`9ig-(jnPF0P9=_ zyPUc&VtK?25JNx>a2$aLf9=W=?r{qyJYg5{=m7w>;Ez%yp$h-aI0q)Bw~8fX;(8pN z4=Z|shKV#GV`c@dpwMbIo!SwmYqTpo4I-c`ImCYWgXL*;NVB}^O$(glBwDy2jd;8R z8ae}jBCauyb|_;B2GIgGC}%m$%0~xXnTP`_L#@zOH%z1Dl}mZ)PPcM*oe05`o(=+n zZQQV~-kpd)8RgXn;mf-3B@%Yq*w*gKww)m>*SQ?R2fqO8y!1^kUaiI6&OpFk<7CeP z;JaX1ol&)HweJc6oK}M%OkoW{fDOek-w8)Vy^A97W}MKAUj!#21@Hn%8NA~6$d_B% z4NPhw{NT|6;AAOt$Q-r701ijEA|F;%h&8i-5RQ<=M~?rmgJ)c08mFYSNy{-_e>^mC>$1L&PT8P1-* zGRfpQhdA1^J9G^-nr9bjczyFh&iXP$WH3@q*LpCV#-X5NT4pDUtTi>YsoW?`=m67p zz^B&hXm$AmqQE$TW>RbwpatWe5h~=PGltv zeD-+G?+QAXueIkRCppDaM`hNPcU>(<_{;aD@ytA?7Zj+F&ZWL{e(zi1fe!j}(qM-= zu(=^C_pjB7-S2QqI_B}AKnOWIb+()3;JyAi(35`O!BF51wS344j9&7%Q$)*aVtQu0 zOpy&V0h4VB zJJQ9%T42l7ycCbOyf2>le{X(120)dOA>#jqOOM|7W?cN`g+KgV_Z=xLxlz|#!*L$|G1H~T|8{IfXzd$HK#zV3sG z_;DNQFh9DJKr>oDQb9oY5IE{`zy~b7;v>L>%R1Hb3IULz7g&q9(KpL8JxKe&MhU^p z@Blv$D~SLDN~pgQY&!^CDGJQL4(zn6^N2U1gA7m#Zksp`TtW4Nz9O*-tRNxm6GELM z!lbA;FEqjubpe@A1F2o3x0>gPj z!4y2cyojrvfSPSUwE?WbEQ3QFltcNz0D)LLXu-p&(?gy3!acl1Obo*!^h2i*KYYUp z0f3E0`@=+BwHsWoMwE{$gqASaoJq{NO0)<*)Wl9~L+29-3j-FMm?Lk5#JZ(ixP{aRCiFVB@Pnav8N-}Fo;tRF}K5&7n*093ur#gnVFvE%=8>DhPDggnm=c_H@t(ea{H}h)>iMgkXS{IZNX_&WqH~ zB6*AwTgK1>&=ZP+dEke5s7yx4hl8+&Rd9%I3IQhgha_l#8nw|I#nBwq(H-Sc9PNNO z=zty-(jg_%8~xEBEz%@aQXd7()Mba-7 z(<&8HBJej&;-vp^cuLpg5D+>?iP)MEJs}7{f+|>rc3=V(Wl{`m0qGf(Bg> zPx1r+B{)w8^~`Hj%?)kHkH8C3dx$MPfxXO1fBn~ZBMBz(Rj4}%Q=kWRC%STuoc*UAXqLkScjkid3XfCdsz7Zt6=Czi1^Qvd;tml4xZFJz24hnaV>iZJ7{=hs^@!Ao0ht7V7I2-^RN^=G z-M)3n*h_#21fgqUMJVv2CE?_dQ!0CL)jd&xsVI3R#-5$Q;2n3tN&B!_45JMS; zM6u+$&0iUoD=*zEH>j> z)`<9o;(`!>DL%wR?qgs+WntD?Qu!!~@PbIF%4GJOW!7OGX690^Mvpi-{Xz)-+J-1R zV0G?8wQS@@nU{JQE9xcZ&N1igMPk2&=4XBg7o4&Ho=DrJ=b;Sd4iyx}#F+m`(3pNM z=U6^t2-RQe#Au0-r};q$7AUU{KHr7@%7(sYM}`aqYzUr#V2bu4(Sw zpI}Y^7y%o?;l3qlzqDs9eiaOW1gV^eICW{x`R61K=w@E$4n!CiIS31Yjcn*;h5qF- zK1GM-7ynG^uUTrRero^K=8T9R95Vw4A*8eW});4d~V>1@_&MwaVW@dNn#5il5Myyh6aersp`%I1A zlTK`Jeiq0sBgr;wxUOuChKMu<0FV|ohCXe|M(o5KVLA>g(hg&owru~hK5UxyZHJJu zK{kjJ;A!dn?ASKt+u-IjQOx&%=n4UX?!;|T&P?V8^0iXcsc0D+d_<*~M9+>Psw z2;vQC?(~4oJCrqAn{Ixo?(l}=)b8YnU_FCifJI~LMof;Fhg`@4^RDdECwnf^fLF0)PN8ka(7D2%l+i0|`P%27MrhPDm{IIPdfrJc&p* zWLEH4d2dcuN$bw=hB)i79PBoRZ5Y?@EdB@_*aUFchh-=P^)`o#X@D0~rz&41!aGBoD=qL9(RJI6BxCeh|2UI{RjKCYc;T!+I0UW_82*NQO#4(5g z*aUK5-%miU$*G*n8E{fj2(DRjWodHxe)0V-Yl&bHeFcCyij6>b@x$cskl2Av5C?kL zg)Lx&aG0WtupQh10Nvpo-vJ%~5FX+&9^@$qTNnp8Ac87jTIr!4>%pF`y7NX^4@w~7 zJwGW1pKt8O^6ZAZcE*wxC@)wbWWPpk@YZpTC}s zQltiYAST!cC1?l?+N$QN7AN3@xP6E)5NBFvaa;fML|;wM#%hU}M=JC612Jx5ck)~B z?~RZLT(E+M*nm>Fh#vBzAQ~b7D54`uq9p==P9TR(Fo*wh$c0q}fQ(|OEaE0#^`dKe z?t!#lbg%UZzVdZvcYCeiQKO%EmxcL6^m`Zit^SBG_lP~}qhT_LKpLciD5OJ5q=LYO zd!U9aNG@oQBuXj>OPX~6@Y7DZmJjtjkN=rI$8~%U`IbM3PXr2-&&T+VdaBQNjpzr? ztoeSxh+hh(fhQ(oLMCNmCTGGVT=)lWN1(R{fNU!IZ8``T&3J23fMN!p$98%(fqD&p z@TpgHDa#YACwalw_3`Eie*pV}=mC4c2!IkOM=Gd;N~ndpB8Msnh>|E&*aw5yfPdIn zioYU@e+VLf4`=BG6N88ih=f`F`$Y+S!f*G<&T;>Q_+%2;1J{X#tQT)TS9C{N?xfO$ ze)t4UQ2tFw26DX!p8_hOBC5SQs-#+~f^aIRYJ-1xUjUc_xzDO^cXd?`6AUOakCg7& zzb<5nm^|4PuLl4F*P>0SLe1GhBJ@@*$;7V>Lxdszg@|eMCeEBXck;9e zDHtyUIGa?8RG=r)q)L}EZR+$X)TmOYQbp+FACam{8^md#RVi1mUz3I%i?poSo@i~p zuu~>hw{Cm_XkD8&r`@|a^ESQe11hu{Qyu>T(DLsv;;aC;NQ?Iln!$rTkjYz@>jpwC z*z%QggmY$1y`rJ&=yl2iP6v}J1sU!7HSE~3XFt8FnD#-wvUTt7iW?#C*uepmuwy4% zw{3gI4tL$$x$mfce^XZox;l0M7xS)dM<#e5c4$4poB{D>KA%+=h)z1zI-O$f^ zShY7GZ2|g6;%p`|hay5QAlJ<-BM2zgd@S}xBY_4k1q}@VK=UJzKWexTghPsE1|&I! zQHd8uI{74&4EcjYLQ2RJ;%&I8SeO5e!gcxDmR#bPPz&C~H3|cFg-O+#Y<`Kbv=E=9 zUUurKRB<{r17--_5ZaS;1{xJB!JM)xtg(`pOD_HxLu)R$cv7la>`~XIRKNxcDW{Z@ z$iggfX=B1@!b0Wjv&8NsYE#T)k`N}#M5(H*Ora6XFFNS7fuG%)du~;wp!S-tHGT@F zwDrY1qp>uOFbbyI*pWh{jn*4#fl$4}L_$lvvn@^NHe~=W!Eln(7n8K6FvS%owLu35 z4Y3JKjQ%?BiSNQIa#uYHKSfUz2}My4!l+u@lOMtK zvaU_th4C}eNi*aOCIHaDPCE89omRVAn*0^CPi5WI)?CK{K?^TtBZnPyXfQI(AIm(g z%}zmMOG36t)3ee%LC{MuN!}y_C6xeCH{d_J^8^5oU}Hcc;&|+C+Kj7>9R#E#yWbuf z&|$|4uywuF)mV4V5VcHUVUIMWlp>8i>OskE;0!_1iyt|G;a%&spIgrm02osW07LLh zwTO=kKfKjzrxid8lY7I*2m!=k2N?ut{<)jRt4X~=p))mwG2&R0OA>OjZaYE?5PcI6 z6k13=`+$O@$q@2j0YLv1>nvV;25<{Xhu-Ji(0nA<%j!%ip6sI28dTFD~8~g&)KsfjMAqQU?qnz;xsk1r)+` zg}4aaCa91FK;l(52|^_%;Q$>HF+)6d{N zI%R=LK>|7GagA%xV;o1wVG#k~1YZOL4L2Ep7uJ`?IkK;69R#5hxp)@=h~Y&i3}9IX zScd{aQGZWViWiZx3}%$-2F%db>JmoBQvd}5bi5>nkWrIEaS|C#EaV;WsKvYV&xFiN zNLW^A2N#4=k9q&h5ma!NkSWXqjcF`R-o}N=UB)IC9{>QZf|-j?jtiZ-oSfDiiVMl3$Mmpr&70VQ4PA(OJwo+JSda6m$x8mPll zM8+l?Sk3>$fT~ufn64D7kOwssG!1#I;;2~FCqI?ClmPURW&P2~J@a|hekE0_ZEK%c zCE6XMthKRD$ptDBf{I}RFH3nvYGDa06=f<*3^2e$&TMIPZpND{78+0o7{tD1cZ2w)MHZSdg&J#m2@<^TfT$}6Q}ieXcNBwZn~ z7M+mrh2CPa)1%S0yE|EjXAt5DcG&f|m&NR0cf!||K~<_eAweDNkOt>gkGai-t^^aS z!=L=32sUv*6VB<~0pFw(_OJyb7-0)~bfUbZ^{sg=%99f;vm4pi6jBI420OqYfl=8U zSUmsyVG#pht2{wM8#Vxda#fd?3uqWCa7f@8BP9{jc*i@YkqEs|RId+)aBr2;RQ(WF znn+neaz#L5r+}C&OJ*{OO`MY(K*JyXFaj`LQPWF0;TO5Qi2~$E<1xdg$LPhYgd@xo z7Q9Fn?nMfG?SO(NpXJF+p>v(-o4vy_Wf#rxfjqF>2F115y5Q1NOn?vxbCS8yt}*jn z&l~A9$K(Q|=>L~MhDeIU500IpFBh<3cyi`D|c=6hWIKZJ0 zbu_Mb3*`ISmtIH-TU=nVT&5s-4jBM|sPSTF&gpq7(2_DvY@2E>1DaY8O2-2GsfDRD+YZk8S5W{;TO^~SGLmJwNb5WxV(IL4ND z`Ad*Gv`OMVc+JRN(S(>|XmCDjv6(e(4xA zUr-??MEMTYCAx`~cy$%@*o1?>Uh}Y@`yhNZlQ+Z=6^g$s?QBPBY299GhIIep9}kI1 zIZSceKgE5H28i``7IJ{U~P z=D^0~8L|m$_`@2T;6Yfi4OCn*wDgX>2Uu}?57u8#?epG!ULnp6K4cLpXt#at)e`!Sl{)T7EbJfmbG6_Tmd$KNc~9^CGo<*DTEA6!X$_p|D{nO@Iy10 zPBZL7Aq?OLd7a=noVvw@EHqP8)ZRkeo=xyzJ(b_6ogWi~01>X7LMZm-YcB|a%`UfPz4EG4!kjh z55gf3Dw_mq9KayPKbV3-3;{dj%o5tf`^De9{_v+ z6l5b5Si>$rK}>8OpctaSodPd}UP7dg-@pc3WCO&-f-i=LmG%FFJkBFJph6O91tiYk zBsSd0T!1{m0s?478}1A4abgfsV^utxH7W!KDvUT{k`Ulc^C5&S!Uh_C!#7yio4q4- zG(tL{f>)tJI$**lz{CH2MLwD#Kkno7pkZ<-o>pLD56&UR8Kh3cp&XvyY1u?WqRT^K z(zgUd?1Pu#jb0qNM}>eXe1T8tMJ^r&6~sa_Zf0!2 zK|Wvutzg4Fya51Uf|j9VX@cEW8sk@3fIQU#F@j}s`CMXZWej2`PQ0B>SRK}Bo%pCF zZTUejxRFArhHSaUVfZ0(QU?*N!l0~z!X<ku-xNJi!z! z13IkBEu_O1n8Y-cXLYV5U_Pi;xTL0l7y@isCvN{}1R~>7bm&5yUh1vhh<2B2B}A>w zr)ccMKez#lQb!i-!Zd&cBdjP+;J`nq#|-Gh3u44SlvOqMrvVP$b-Kn0tjt^@o4g^{ z97sTsX6TX5W{K72PC#EmB*FAO>1_GIFF+kac$>@V1wH%&fo3Uf6hb}V!aZP_CO}e7 zAi+O);}-lwj~oO#h-gAk05CGaKO{i|q^hc}Dyz1ttG+6%vT6s!K?lUDt==lGuIjAT zYOeOGugWT|{;IIPY75Be38d<-4(qL!Kzz+vuO_RqM(e9WtF%_Ds#2@9S}V3zD-rmq zPWT@H3Lv36*4)A8K}a2wjD|S;gAzjOY+(Nb>Z#fk*iTLvz%tAYRpvuNSc7LKgel$XI0~bsi05k%j z-GnWq!)39aFRP6sjT*N{^I^I+SmK_@DG>UFD&TZ{LrbJNz8)X-4 z#KS*K4dK3qCy2up$U_z|LOW=}8`*+7fMc1SsS>0q<+3SizFwPZh30m{D6Ap)0bK%! zR_N;K=t^(tLPanV;V@32cl`w2Ed-01g*?1&?83$Xe8N2VgFo0qWZlFq#Df-81P{FB zEuh1VPD73kFP{b-l2*ksDz5`Rpj1GURYfo6zNwGqgpw*mJkFy$*5f^D2L+feC7bJ^Vw=j<0J#025pRAu`7uMOXAe zh{2isuQ@M;<+PAR%kvG>a{?>GmUbysf@vB*a-(?wjOhgr{6lDp^hj6k@fNS~Dn$!m z$|$gOOD6>ZJWuqXvKPx{Rnw+D>x86Is-?94y|D0niB{G1XYDQ{6oJo_MbSmReQEV zD@B}kgDkWr0rSL=x(r?CHWkmdS#LgR2g+KfQbhcCp3eu@=eTc?cQ$gA~%_Fg3#zd5-%}SEWlytvvg+& zb;tBoSNBp}K(b`RaULX6+|wI|H+hfuZwoh6l<)bb@A~3xqfx+515wUKMG_pw1K&54 zd_f(D zynS|jf$4feLQ@AKa}Dl06@bd#KSjj(Q`XC zLGPy+YV2UJJUdSH1BgaLa!MHfkd`dSgUH zL&hM4CagobEWkW$9TRBdC&&X72!=5z142xLwwF5Y9~=hY%`fnNIx58x97YHV|L{-! z@&7nL01!BkU_pZi5e{q+r$NGlEx2{#&sKYgk7pM_RGpo|LAp9yOwQRw{O?RBmy@jL%JSa-nD4=;|XouUNd;5+U79qlu4lYIql|*zk~12 z((>`+vCXF^&MFwN-Iaoztk5}%di(eBw@qF={N4Wk$1^B^Sh~^X1h$q#!Hzmg01zYM z{(~z*2?Io_y!B1G?(h$idPgr|%(A!^hx-x1Acd@m zg@`5sa!LRQAj1wa2=Eb12bFshPOXmAk}DFf$KY!45h!2$R1>W#qKeMlF=7(5&zr)lMON0dcnxMM|VIQ(=vjq(i;) zl+rjs1wa5@37vncc~;wP1)_Df zWV-@4+!y)iW*ZhLEHZ(^V3^d+T#N0})?2e$mfNbXx_3zrfwBK&w`pU=!NVga1P#gkIlGVQ47XbwvIV8fEQKA3ge@*_yJjEEf2O>V`C2* z;jh3V9!Nn35uR7ki|5>w=a1}NIj4Mu#*j~G$C9C<0rvUFm7<|ev1J%_9;|As&m6GV zUuy|~j_G+#c&Z=y)$0jJ~m7R_HI2(THcQ-F8x}vii+|C=nspCa7ZHCXJksEa9 zBp`-0+sygrbYGTt@ru?~xoy3P`wHnuDiY@(aVYQHJiamZ8QJbm*hV5vEyc9f$K5)c zCf8s8yIYRkp4{`9OZgawJ_Q1x1>NYzji?3z>}cnF6^!2TwsO6W>Cb>|@xU*3w;LcJ1QoC9 z;0e2eKwvHKd@}3CC~}s91(5(|HMHOb>4ZP1aS(-SIYswGbPx!1=4m}N;{8BlLmVoQ zK-s7cbJRcw9&;6u}pyG?_p; z^9X^m(w#elr+)~+t63yYGA^*g95lejHfr>Z9A$|cKgvc87A%|#bqFhvHi>F&Vsj>4 zWkdC;NAJ|aTnEBT3GBcTkgjB>C+R6kehU9ok^WP10d*-#&>*+5G+_pvfxuB43Da@q zlWZPk$q432$;U`wM=tUh!g8lmHeaf*tHoJ-I`p%2gzgKw32J##l7cwXFSQOaliuo7B&nwjQ zhIYN|UG6WPd);1$w_0Mda4X*b)L{{oo7{A{s5nJW-DxFHEj zK!rY@aN+oVm>|oT$2$Bq2_AQ_zsj{NTxg_?5fB!*1{v;NR$P%MA7si@M(ju4p-^pM zc(shMhba6tmJtqle?{(SluKJ1tUj!>QO-bDt&HY0AGvtZ3{{K?q5wtYg9$qR7?}-% zgU+0Slw|?5_{_{*5vzqjvtS-x4Ts=3FWAn#q%+X|!GsWO+KdH>!aVp94-0R3#~&s_ zXD~s9l=7epN;q`z63x>B&l&$Sm?a!uQ#|QKLo${xo|R`hV+w;n00~uCMLYUT>Oa5Q z1Nr!eJ=V#J_kaQvhIsYuVvXKiYlQ)jf}wD6+hoYhn%0%>W+d;YX-+%j8MyHCwFP1T z&56ner6A=cKp_cucP`tXl{1uQQ!Z_At<7+GvmLw&@NGNv(&oD#o(lpEUA!CK%jnD- z1Tq0oAk7lg{=vTW)^GJLoF=8~h8PGE)JT&d!Q=k7!hIdOhC`01tH=ToqOb~oaDn2l zMx`7)N8H_Y|Yz;4VD-08g~v8Il7bnl(-D;X)lxNOp<{=*sp9LNne zzMGDN!UJoETH9G{ZncycFitkC2Ba7^DZd@=(DeN0$wO4^m0GeT`iC+MPY_A0g6LUr ze9<6pT&tsmM&4kbirJC?HN}9Ud7ph{V=nW`h<<~lm#f`^lMq3GBJGHHz0hL6d8%6; z%@_EKRu!z40AS~mk(Yd(``%zb!gty7okC~S;SeQ&!WD|ox1gTivFMi@^lceMul9<2 zwa5@>-mkxl{|^AY3F3;c{GO`{I^!NbfFdLT6vC_$Tmcl8ApSsR{(LX^wBiIJ0)nVd zErex?+-~|haOwYet=F;+t&Gp5vLFFzpdt`~`Njg@KtT{FQ2s)U1mEc{ny&L|;(gjh z>2Q$YFwo%!ko-QZ5IRF1@TMZLfZ9ZX+Ne$6YLH+okOxh$EilWbbWJNFje>x12uJMu zz%TR&kfc&jppefU8qXs*01Dj@6mVb)^`#1{E(l2?08H!xvm)v^>kGv&fxs{fPY{p{ zP_9<+AHdAQrV{7WJV#$5vqO;9oDcV%j^bu^6J_`eP$tktWYF)5#ju6BP|Ue z*T}d2PG17=h>)Q(n8CV;vVdN);9`;@H1L7^Pb9Rl_xe#MbMh#Wa{LC;rI7C*jNmJY z%qah8GuFv24Ja(DY#O_wEa?s(KO!Tw zODfOp9}BaUND(Vd(THdO96G}s8q+bs5-$UAGi!oCV!;nT0w*(*EfsAn>uMYcQJ}WK zA38%9QV%t^B@2{69sYq320}5{!5*F=2`BzrH<^h7-k~$XVFt=mWr|ZE24Eeo1OR5>9u&bL=#w@Dj2pD@EE56&)MOvuay$QL zQ$$DfFbQ;(DxefRqe2&yLDka;{$UCRLNn%5HN$TzwSre*;TJz*`z|U|LbNl3^hR-X zK)sWd7{N0lv_)N1Ah6&cl0qPiK{yJ60yZrKnBX6hpaHnFOTF|~Q zlwy$sSwT}-$LG{KLm4_vU^~VGrr`WGVG2&N6W{?3q97UKGhrKYVJmheGIT?!lOQ~l zVyaRzW7Z=lmJIh5g($!nI-?z`6=Xq%Gk|U4knwXQ7ryNi-_Y>O}uLC<^GIGuGiZ z%NE35wr2tNB&L>X2||XRhX^eeaRXOtf6Y<31yVr<0))0RK7nuh_AdXHal2L|PQZaG zGd~T&d9E`c6BiJLbVz*`G4}@x_@Oh>VN);Hh|YF9)#o+ak|0Q6M}AOo7nfmu_jfPW zaql7(apDGSfgJ219c)2C1;PrTAs*nt8LCwalwlp{0UOkDAQE95?g1P|4IvZ5;0QLMA22Rc`Joe-;Km3Dd_z-ZhQKqXVF~}u*K8HGcQ@A~?yoP| zSNCwXgjslgfj54M@i;ty9Jt_GwKpHu2?0+M0HWX@kia08q3n!d83uwH+$|x(S6gVn z8a!i%L%6m^SaV_cBWBVp1=DJOlzvHgieK1;N8&2)Vi%sqh6Umg+Cd;bz#U8h0yf|k z#NjjtLK=!F9hMXou)!d*H3VWpV}&M3JL8C-c(S5ciwW5y%4I3(761ZZV(1{3y4Z9B z)Qel#evd;Dz(JMB_y*7c6$Szd%Ap_nVH}+JhI0%6^npbIAQRZZQ$dxFL1qWSp)>q} zYy(-4W>-ip;4e@vku8NIwwQ}2nRM%y=I)m*hJYRF0|5VQI0UMJ88Bi4s$mzb;0lf* z95#R;wtyZQVIWReSOARd7oyb=QF0hP629x#C*=y)LP*ke3ra`V9o(mARI z`H|rkB?tggASN?Kw{-D&m^+$8!T2pc01A}-XH-*v)CYPVLVyq;2}O_|5UGLzM0&4E z5fB8C4kAsY_Y!*Vh*SxP^bXQXkY1#y^lqj1E|AIpK5L%2GqdiUHG7>`d6kuw{Bn}L z_xEGS0Ijf~D^cJo$R~s-P@g_S(wei>HRW3*<4+lSVoL_#0-2JbO^%5is*(}T(smNh zqhL>HSc|^e;;}#`ZnhLwUlu+wc#S$0e4xnX{h7-f;0_Dnjsx)k$ZP}oigyz{7zJLT zj1p19XSfVG7Ku=%VXxAcULO|39hgDz4bs=HX92lJ86VHz*GfcuQxs03ot0C3pw{yM ztUxCx!qD(e#F+5mpLsn7b5|UJ_pwA;R#qYDXDY$kc;Ypbp;P(wx5DeJ57dnrnIB6& z{en*DFsq0+yw0o+ZfSyt$a%W+31Jh4fmB0A$-k$biHv}*#I{5cVUGNxBcrA>-`u`C zB#y|oPkwDJZEYR@+Pbsb+>o#u$@Z=n63?;iQ+{o3a+)aU>tw%{xuzPce-0-viF0;X z`z=UHvh%&O1#FQp7y%`u9ZPYArIhNv<=+jzLV$C+>2hdWgK3fNpW%xM``F~)ew`)@ zDBQcYmbd(_jNQU4tzFj(ttXc46l-w9_CAxVJ`1V-m;U``Oo$%MSTm{lC=vQ-tLV4*eUPOV15ptj(@3XZ5PD1(Vd|3tx7>EnR$5dDTDH zK0$Fkf)9^?2TY3i|P2u_ZJ7xwKUgVQ%KsBy)yDrF)xRLZXgXPYD_nJ92Lr1=Nvi>u<#^a*a1fKZU>)|R9OW$6>Dh10NW#E?+B>N?HZXtl2>1NF#SFzTl zTyP1Q<=-eMBU>fMD)Ey+$`sSfJfbQyr@lNoY5ZF>pxTl4iiR zWY=~o%kkvkm*D%|l8Jn!SO)2sH12FM#}v=!sg*DIi&c(hYg1oQObMWW{92`V zVVkX?9$??LJw?tp5YJ?Rc~UADW4QIlI$}kumplCbZBDh!a7|Q(kujRgKd{SlS~$LK zYIUo8y3(X;)5DLh-uR27xEJjLRh3zXhibM=yu_!?DRY9YTaIF$j=frT9v@D;N2jDB z`1Ve6XwMDT%%kZ@a)mh@>Oa1d41!6w9(Pn7eNKkAyf;Bd3cl6jU&2`n)9b%lv>;)z8~n5I^5Ese zHJe+3&(eMAd^s2t-W%R|B00p}&8l?zHp()Fw@U0?kQV{Bd7S)fFFn1duRjup!Yt|X zBj|sem}<&@eZY~-==6O}{)^aQFU<(%CqXPxF89l~&rG9VDhrGeeTV~nHT-V5D5j#H z;5l)CO#J)k{7(35qjSy(|63Q6{_wT^C$xsTnJ@DKZ%TipyLxQA^fae>$>^l_Q9hE{ zt%TA%QI5rqHdpXDl)5NWH;YnDBMjgrqF_6K)A$vEZShTWiCl~$rBR7vB-A59bcH`A zlG#g+VIxasY>4McR_lX%wcYj?PwIxULXrqZ)Kc%}Rp7MLUw`sy$)c^OWq9bI9c!10 z(MdA#P;It1I_2|qA@;iGzg73IO67eBLr4k9lB<@n!DENlT{kym)QvWFZTuEXo)%WR zKXz<(TQ)(AdoGk@3sr3bck%1g8{0JeWk3+Q>mbujPpyaSEhh6OUw2_nU7Hkxl0qki zD^&J_NSk7L!r1~Xs=z}&*9nEld;5mq58HZ8#Ju)tnUek6TZPn5r9SmNoXN@QBwnIQ zq?PjT=q~l7(Da-G=qRQq)$WLFG0ZR8>oK(KwpNb1-CCep=G%BpwGv=(h3F^ZDX+L= znH}%_<6FU()OiPZ#;kU%kDH3l&&^?n3eO%Nx7PQ#Ac4H;DNv>NMp5ygm{x*p6-{u| z^0Tzel>GLV97FX0$z8EnE&h#S9L&F*gTzy4E1bEEMAVt=ZA60ISC*5}mKBQTWc?Sp zCtaN+;{j)-9|ON__K&Z(Y7?__(^$L7!lheV%_t;JW)=#YRy+K*18y#ZWUn0h6036$ ziSAm+>x4ROqasGxDn0i%7yq$9x>IJ~7%eR15#687y2*4z0UB9=!E~KKp#_X$IOgEC zVd>`cH@-PmYijtYEU2Y(!~^mSV%$*|tWFcH?)R8w6T^2Z4GZtlS<|>uq2fqTidKJM z8RYs<;%dq{MlX)^+>yQWU~=&FO0o$^QcVdLEw1f*kh;=`@$RbCcZql87`o+uzS|4PUi(oKWe!j)P1=(_)!jsNVd0H{K@+I zopjL9L{d)04@NsG)#=x&6w5poJ^iAOPQ?y%%l%2IMGqevHl`p^##5Y<(IfPMuAKS) zOs{|S-)`j>;x6r7zWY?H>((LVqu{tTq#NlMkzHNR4&wz~a@)wJ$scLv->t~5)%qbu zu6IA_P4Rz-*4ot+=A2T>x~wXYk|lTJ?kilm7yowj&T{JA+V5)DS#~3@irg@?##|cn zEtMj1NydM(xuiRyhpcD?^Mp2DsoV@n%9r7iF-%i=@@660_j%If6CU?4*s$G-gnoRl zFwZ4xaw!^9r&}Z}ZKaaiGMTXXz?;?Mks8s1ujQ+3@KE!f;Z}Lhw{?1%t4y!N`bY<} zi60b8R@!g)&Zp#Ak_d4~J!Sch&WI>W%RuZ{J?$c$ii*(k1AQucF%qGlZhIo=v%bl6 zsNEufj6hqNl*!n&@?d|sWezs*yePe#?j`20;>+B6*6jPXEy95((EPdXTchdERL|mG zDQ_8x%suOiId#P6C$lGeMo2vv*5PzCfe$=>b|&r7_}+u}^#|YC$<1fhaU#)Hi3Jf7 zDIll0J3F8^22T>D z`pO0um0W5;MPzPS)EDX3=UzKImB;-den%e36i4x}i3#&YS*zu-=kIuF%gLBune2Xl z>eW52xLAsPCW>3?RD3fd2-&rxX2o%bIbBj#460eBR6F0@70JyM9DKzi#?+Xyy>5Y3 zgd~TyB3N0LX2{(dN3B`h%4HYs%fIoR_TFevenzJ!`F$-mTp|x(`?6`EXfWH8KJ)Qo zj-3(T!u`gosCn0pEuDcul`bujj64lT$LiLvv;@cFMeWT1!ab%|V3IlDjRa&N zf=MRap_`PVv50+1J&_!Xe~WvaXI=1{eJ`_$oITF=dXqgI?^V0XeQCr0MoyI!cZlpR zL4bC65V<^3=bVHJK;uaF@PcD4^d}P0UqenPPtm-J7#Z+~&k*9!M1-}_DLghQcOUOZ zJ(>WR*MnK{0XWws1~Mt9{gXloq3r0U>I9e*yGtS9ow)c+~N9SVS2XV&$&YkOTwAez^akd zZL3fK6-0ah*+C*$S7Ai}0pmXOhjUO{5;{=LcC!8&ez= zQ(A(HDIbifT#qR}hnU+^#{jTfauLU(2vIbw1clJnhFwpNB>c=E+{qx6 zMuhEhCmyLKp4cXyc_;2e!dEiFjRzB-ttaAchZFE5X{aR;wSwy66cq$-BZxpc z5rmYWDJ(g4Ex}X`*)wON0R+tAX&hm2-0)x=Xf2M|B`QoYehLy5JL8?G8j!-}yV(?| z{w&q=kDC~=uXZCHK7Qc}NW-n-X-ELrC-}Bc-pGwe#6Ni?0wD(<<&Jc>#o?FCBSGDf z6KeOr4W^jPA)=k(@qmXeU8<;$vn8G9qDrcLOZqR4*arvr_QX4FbBZ=|UN$+3$q52* zKIs+;0M!CVSO{g=rVKnC?KF;QeJwmQGknx2 z#PK8G@9-hGW<7+;E#Na}GL3z38v-s30K!_B9u~jUhrW|VRUgJ5nF*K^uy6ce%dn(oLByh-QDxdk0XsA!IK}=HwyvY zk545&2t6)N_r&~jEwn4kqlXr4a22{46$d~|tRLr#loemJ6ft!dI$eGYk|+sbC`q!% z-1RLn%`5>;78$pe#4!}7OqW_p6rFk&zsf3pd+Gcx3x~)aE-Gs+d(&DF&s&_lS(0jB zQpAu`l2uv>Eq{MmO7=IC^>J?Pv$DprH;Tw$8Fa-^S;fe3#h1;B@zx5ZeTWiJIb~lt zQ&#cyapmlAPUcq1BuAM3-mxg%MQ8 z1=atC|4;m?dJU074M}VbX?YFVNDakS4c=a*bg1zTCYrUYrHielFRx`Bsb$`(WhJX) zkUO_Syb@lhHMZeLS%W%bmF8B%A{6&Y$FK6K`lo68ProJb3}DcWB_M+$q>`+0W@~&| zUSsXhXs2FdTi*DZtj2Mx(WR~0S+dqExah7+6Gw8BuVjT#Z4=jIli)!UqhNCwV>7dU zvs-erV{LPsUvtT1bI8AD0m>Fmp_VkimU}ua>9HSAl3Vy{TO!U{CTUuwbXrAST1zBb z{gYccCtIJ^wfZl#yq9bXWNfQzqpMa&w6?W1Ej(&>X#14SfaPoXEZN@aKuu!~Jx!q- z9%=VpYxk$@@D=R%-q!A?(=p-KG27O0C%xn9pyQIV^T$HRU7^n2n9hyz&aIKoovqG2 zvaSQZt|RrX6Nj#|*shE6u7BA$2BjpjKj!e?XeeO@?Y+OQE8=vlRP1*?)7eJGx=j+c z?ZZw1n7%U|6b%K8VITM3*(DPVV_-ORJb(g9YG9}P*llXut9q|rW4jk5@8uckGD=# zZ{)z?NO%^O)(H&_cOC>LNDmMsIvDcbm^9J+(b2eg;eGOG4A?-MVj4v|vp5RUfy`oH zm>l)b8l(Mjql9u4U(Jagqsg?{5gAEDO4>xjNibz`#83@64%r9Dfsa?A8W_^631X}K zu|EG%j;pZ)sqs&aD_s3^TfYp8Sr>n$q_Yj086C}A4=7L`-cE&iF zag*S+Z;@A!Y7CJI7IK0f1!+zY$4?YZlKxJj6(9u?X8OH@xqL(D_PK)KqqOA!{)0x2 zPlg<B&>lMh!dV^r$9L5O*Aotw&C?clF4+6G~y`+CgnWnGy$)PBRxc+vzO-bq!-=!=M!Ep5~CME z`HQ2{pYh=7gd93206o1!R|1S#xx`Pt%kYus9rB{H^p5prgH<`>^EYu6Z2WY2&M*!k zqHR=$o6DfeKHP^Z*(rcJm>*%h3h$Ss`r-&oU?QV)wQeX@K`@|Yu@K;V9FnNV1W4?M}s0a_!*As$KvZzeBqQDFbuH>lIvN?#(qM8RG=6OE%_gtt=$&f!B* z)IC+3q%PalH}G1glzP*xj`P@VvA8K1aEE6*QER(=d2<=I+l*d{j3Zm^{EgH0ZkIuH zv24$c?JhWN@4eqvliJHk$o^OJ{c?8;3!^P}uJs}Zq_ttQ(zJeBQNF?VKU`A5>61?a z=q^zdgcfAq5$hWmhz=IAhg}CJ#HTOMVPLa4%fPTR1%hR5){tmRyQhdnGsgUoyZR8M zLo~ae`lW_^6on8@0<-#4G_K>In5r!RvkzeR%-4>%@(%fAkClUtA9Wo+coUnq4_A*T zyiS@}ui6!LIgzVAQ5uJN}j!5PYY3GJx7Wu3*VRvGDHY!bi z4*nOd)xP%+%bG2Q@wV4MXb;8BPQc~n;Ic!pFFVsb#;CvEM|3?w2%BG9=U(fO0<|Ug zw-Nq$u~*FE27mv5^Qh})Ru(ajyU`>?0Dv5(7=o>`#`8B928wHnQIvPJ;xYtMKkNQv z8N(7_viO1OtAjfi)n*Uyhd&R;;TtGmS4|_6qB{9UGn-b>UT<*nj#@IuMWzx@5~-vf z+-j^M`rF30Z0SMzr@&O%w?q&{$(H-n))#`t?{_bZrvH#|+vOWB5cO@p2=6cCaTlQw zSoF%E@n!cq+mTfOkyI>jpn9c41M@-8W|7aE6Jk1qh@BPrX*|l))c!2a9leV3IXex{ zC^XBCqS+J&IV?+lCp)lsoLy1Xdx_ONK@*Hpmu%56XP@ zoSixl-Ik=m>_Y?56q$3U))L>S*b}^m(N@X%V`KR09T!zTi5!Gfn{!7dGe)jHr7NF)oV0DLPKw+F*e=>^uDZuoq$hJotI6tP=mVd*aYN(|AHcE(l ze(q!MVBEE^wji79FIJ~EqNmjEhoygF90}GNUrZ0{t0{Y|0DoCr9EpxX4JK-fne=KZ zD97DA2+RS!>6X8lUj%+Ny)ZG7IAi6PlgfAz#CoV}62li5W$Je@WsvHAEYD>Y>}wdo z9Pm}JXf<;G`;nI8ArF@cLa>w0dPm~M&@B1UL;Bwc*Wka*)-g2PP`lkVsB)$VZIo4_ z-B`=7)LTCkvb>jrBNp>xWf(SmUoFqtWU&>HquJ6+iWQ^+KJI7_TTBhH&{YCf9KC+qF2tn)CT@8{fu5$E`xX8`MVDDHC?%m3eWhvjY*ze zxlJh21-O4z7rl1>{?s7AWBP^Hwa2X0y8zF5ho)=KMYov%uVufpYp>N%xD4*BunLxrUc>g%gSmq)JLtB;2{Ww9zT{~Lc+LAg_mB80ro~;F?5=avQ#nJcBL!XC>u@}gMukKTV zbb4hQkx5$ng-p=|ay;8Vl*IaV65KSFsBZ+}Qe%p&Q-GY1Yp^WN#6)9xX`hLKLx_Qh7;TdL9k%<|cU&a896B>W}s+&Gt z@f*CAPkL8rjneGWMxMfV;tkB4`sakIWL7d!@UJ&P8Rx30_!Bab@|cZAj9BW%Le4-- zIDM-958}mXg6$$apYNredfP>`d$V4V@JBmMmlRUI+rg9vYB8DtmrpS)-*0U;lZZdg zZ^Urwm-dtWe|VHM;Qzlo%IouU-1!#nnmST*_1)j=n=4C)3pMN8|1XB}&;080*7E-Vlq)L>%gf74 zOG}H3iwg@2^Yim_|4)N*@yqnLm2dxRP)OV~7Cx1x_ z9}LBHbl^HXXPTl%o8IF(AK_ZWaSeR98svJ7LT_(xcXxMJS66#`TT63uM}0N6IjgC? zuBolI5q~v(!aJ08|0$F;HF#07vFv}8$?E$2%DQ6w169=@{JMNBo6U7=pWyjOT)8u@ z41p_w;EF(as&cQ4@2ZG+v^=D~qO82U{C_0Ml9H0*;^O?$^p77u;1?ie*?B z&c|gn(6zLn1e5f;>HaJv=;KyQktcNqO&T3I9(T9wmD2SvUt%+;iOz_O{N> z&Ul{k_3PJmc6K(eY^<%V%`IR4k4I^2Y;0&~sHd-|tE-E9tad3SekH_z#lv~chEEcv zyP?F#-jlg#YCd`LL`zFcU0war|H-42las@Hl+x1D5)u**CGZ^Oe;y@D5Ox3leE|W1 z|J5fsxj6CqcuSB_Rl31Ox>C-yS8hZy@3Smq)pw_`e>djRv8lal`+u zNBODjDV-$w>>}^e;jaH{k8-Ka`)KncUwHXS7aF%atKR&7c$9pmqs_HewUQup;?Zws3@?Ml3vI@7R7%|0nx->zJKnUa+gV68xmvLJg!d@1p=7LD z?ac>2RY=;fJ6`x;R5W9=9dKRkzBzSmIzHwh>6N|QHG?C+Z_0Ubh#LRK#6;imZ-M{j zllPOZ&g*~YM_VgTWN)sn#|}i3d@m>sSKUGQ?CbzCp(yhZifK9vh3&hx`EoZVC2J8( zp6hFor!OI^vg7jS7&P_QcLjcY1v3S)T!&``-oh|Fwy3k{sGkW^r|UoQcbFMwXim#W z%QzwSQnUC)!MVZ|5{AseG?67pp|^r5-lH`3-1sQ}d|8!49vWx zw}Izxj(g*UO^zKe;$yhhvzg*N?H^}cZdyhccl{5U|MMsxwwh&}#*<m+Yqh^=g+mH53{%HY_pJrR1(cb9C?*Se!t56TwmH&3tvNbn}4O3e{9~3F9oQC ze!aqy8Qnd1YA4bxFAkggF;a=S*o@ujoS#3gY=Pvf@8dnnioEXM@!}vV&StXe@FNy$ z5Y?SouJYH6Po`@Jt~<|M%o`euQ5n(i|MMu{4b*tUtnLYRTE4~%08>ZG!U^#YbCN-tHa*)wt+uvQQA*C7APeiPc$D|T_ zt0B-uV2~fdHb47eOqeH*>e;!jLtxwP+1^gu-}BfwNx)ok?jS}L3nGrTRbC0jVH)*_aBBg@1ln-a zG6)gH+Ix2uZchH;_JCTyP>3J_)Fqc-db;rsg*>t;N)-zJ8uvomhINW+P*~d{$!^vX zIW@7ih}ln^M_7B3;Ae_Y24uOlDBTljmT;hw8b14jl#H;1y97U#g?$fGEtISjz7O{Q z?XyCDSnZedJRk#V)>!wW?n)i6kpY8W6Sk9jI^j3anJ$jSbw z;I?Lza>s8?fcsE-Ozag;e$!ZR$v6auAk?@LL)h=TA)%;9P5>QiGcopoIG{k`)AZmK zDuksU2`CjmDv8dz=RGr8qWcb-5$|-@=eRpuBug$7)~J&UiZ+oX`W)+wV29|QgBfjX z6Cd5Spb?K-SS&(7xzEvvb3;NvK?lY$ihj)ckzL2?)6Daesp_#D4In~3(NIme=KBNQ zjg;Z<{Sps3wXRK~o#z`aZwE6RoU0yH8R>rFwWV1b91stj3=0ioXWpAo=JkyZvnl+^ zvV;wja|PnPa95#$WQ7ctv8^vUPp6wMCb3fM!Qnl;Zk%Zk7_FA5!zGp0Y9~JZ2|6a! zzx=K#JM*!^DRHEF1@ut12BRu?PfTwwWHfU~+0goxE|Ih`TkAf>g6qoDr88?f*|{%# z94#Z?UjBFm>cb4&AwHft0_~LC%6;SGi;0v0B55?bPx!k>~T9xW0JT z_2UBT%xb@w`Y208E{23x>Ade(7Rr?`=jlKDW*gD5on4u23zlzxV~>%sqx1>imd{EKpxb?W= z$1On|55RIfLFn7Yq;~pHsPlEe(=4u(m6qM3Dvz-o(kqK*dStT?MSwHGjwLN%-YkDF z85TUMz(BZRe(o(O8e9>d@hijbS$(q8?sv?say12w3JeKf`_;BojCi=sdkc46ff3O@ z56_5>TdkqRtHi9W8dCcX7PotMfAU-gBJ$(ocyf`#w(mZuKD5mgh^LY!G@njnu^;}vps5J)KY z-1Qyv2qA6uiPWU9^pu)Gr1ov}^Cxy*@bFKO2h5P<$E#jJ zkwG>Qrr-=#UM%?8Ab1)}wmuE|j-cR5LKMltd_!DjyIojFT=8ANcU}lyZv^=tbMD)b z=aUg&%AmPmd4^tj7O(=lk^*O#0X0wCcx@Q=!G^(O8skfXUGbzle9bdgR_%~0m~yS zNU+v*iz~7{ipAabjxZfSiHhqrjO+J~8x)IE^h6Z?l8=I@x+=Wj4F5c{7@<1_4pgrhi1UGmwv)9$MaLY1so{Es0cEFice}0hgYzxaOd7n;b&m{lLYR6i1sh+D%$MVMBV6N>-mV z6)XmOo~+`NMjM^%#1)$RNq>*#$&ucZGqBtZK=dQx$&$C*ig!@As-wwsFT51Gdq5B* zM}Ca5A+bmm4o>A$d{s6L6+uyx0BP>g+!Cbsx-;T@Ti*3H#}QNN(r0RE`sni9qMksJ zHDbvhbf*MPn=Oe%{}v<&Tn(btPPHIS*KJM!aike{JM9uv^EnfFqy0RdXFWWK1zAMS zvFYo*)Yr(=-!7B^CiKm2J;SLX(#>HTt3J<5{rE{!gQlPU==Q?O!5`RVn)!HTwitRv zGjc|{q6k1fSl6QGxi5mVfL_n^@aI`~GivN~^=AMK?ygax2jadne6l$u;XL~@X-+pO zGbxrN2pblggs`_`3E?vP;=^c0=V@i&IZcmQ`ZCj4$LxFZdCbIQkeM9( zNIP>dI?O{XJi8^YDcJXKF`^=p#El2TZiE8cBci9B@0gQq0`M;FCqe@ur)SI%--{&mY~jr?$irzt~W36)Vs%LKwI^4sjwH3pohL1)P3R zATjNET>RETqDbH(WuluXsD^~^YrD2kaDGOjS2xd z?}#Sb7&IJgK`}QSES2n|JOPZAfz+Hq#Hh;eMwQdPm9trucuwd(2AIFBTxFMGg5@^`TLX>}ts{QE6i>P*nqcy;{yN5~18mIKqW^Y)~4-i zG-&;6&}RIk8{6;-l^KuB4@G@4YWt+^KuT3^inXVf+DK)5(dc4SNF0U!hrwT^0JgNC zsRB1qF?NX(Mpk)eH+>(jTrO)0+-mZVtrSKJQoN`kd(j*vSp&~*j`nMgTc}C+*GwUo zZoCSqw69L)YXP!b&KPPHC2Efk(p^ZY@qj>^ZKE8Il)iWP^Fgp@Ofi7geTpq6WV_e< z^c{6KjLuybv3Z>B>D*T( zEUo}wF<3h;Nq13am%i(H#nZkQVNE(kq}Vc!d%g0Hd+RsZtY3NBjmA1KbsOUOON~LN z_MQinz;E0-0fBkCeB6LbPL^4=rK(iNQxt?~!?f^XpoVTxkvt)J^lcvbaO#>vz&>E= zpKLBQJVfF^+J5V04YUg5LMjNP4iCAk5BX>ehmQ7iY>%Y4)BxDBh`aq3?ZZs^y=nfe z>{w{IHgPi(rj=<}7o7P$$8aESv;?Yh3kldfH|`%DPK~p!Zog$Ei9hg0Ca-+IE%v`5 zAJ~l>+`mVkhS!GxJ(%<7xyAMyK9h4w;&Lps8A84D+j47h==Y*#h+|)*w0LAUW@^(Ou;7|_EQ8fM|4lKn6BI>57UnSdc zrbtIvk$z$RT1sLoHGA}I)*x;+x?|qy^(;!Ki?#ux8I}2iiS~o`e@)e33@yjS$Z}!x#7GKx3@6qtHjgmc#+SDARvc@~^;HRy3A> z8OslV(&CdSDFru!t!NQAJ- zH&dQ5kKJLy1V;Hv1RsXP*EuPW#mu(z*JIeG-SVHQZ8~R`sXnA$vesX}cGgE&QW<9I zdp6U#EGBuKf9zpvaMSe&0U&mlfKVrg@ZsMF%bQZ5*=*yj#~xd)GV5W1>l6uFD4ilW z5l2 ze+~jakhUhUtD(Hx-nm8aX173QlT?0(knLx=={7DKxoxuyN#4Fm&;iEr5x)ChZ?-2` zs0sGB2<3lwa&4Scv5t!$R6RRj3_73>+TDD=`__AyknJxUZhVvCKJuE!lgOu)vs#ne zY*TAY@JfA-fA>f@e{e?zkq8^R7}&pYWMj%2^1&=iJ~=>ZS%kdbrL8{XuRc(^PhDiZ z17gE#nqKT?M<5|c-BmATSK-qj9clPCMfjQQ6Ze0kNizkx_yCerEgvkVOp9FQ;JzvLDkS;#Xj#w~xBU|fy?)WrD_RNp< z4C~>qvbXE9Tt=*N6tH(jVv4YaUCwe`7C*VPeslRmrld%UfG`*!I2{xoKUVv_bJ_j3 zA@5OR*T0DOhlYDsyRVN~4S4It2a%N|z^v4Q`|K6@F zcI2ITEM3m6q(_Y3lEOkOQ6bPt!a#}}Vvd{LHy4DsD}X?5RW1bYQ8LY9H3|O@kCIy( zzwkoPdUYU&>XGuLXIIHN*ZHLu%JvAlc<^T6Q98d#C)4Z?GqMa3ID_}6m=w+T(g8PM z2EBFd0_FJr9G_#0Vb;g;0`AaBYrV*)r7R7;pUj_Cf?HU=?-!2~h9s;LZC!jSH;Uph z@C;|v;r!AJ5wFxeaRH)Q1Fmm~m<&<6tuC1$8$Xd+%aR~E)d2FAT15g=6cvYD+;Txf z>OU2kbKrq@_9H@z$>}(MJG7MqD%N>%nVuX+7xH78+=xeo_V^~S#?&H}y4dL-H!P12rJ6=&P5%TTF*}p2H z$0UUB2@-@LQ4uWnDy$Ei$rI&y$zL|;s4^<(@v!}@JNo#TpE<2W{l$FR zHyq^rMb7Vq(ZTaSmR;8un94fFy$t{+h1yoZ zc%$`=N(tEcj-55_+xB*&ck(J=w6D54c74@CSyrEihA?s42-nw|O1*ZVo|Y`j@$`+7 zl!9R;-M&1DY3J%Jm44BO4Pwqc4#A!(0JqAWSr;B(u0o2!#lYr1!*AMCxusfe6LC%yK%nmRexmMEA<4!gWp0y?yXajQ58+FJsiD78Lk_n z@4m%`S#H}%$pZ9aH=&E4Sg3a&Tw&E5Zc$6GBk>IFg zMm5vadt$N*4@6takFt}W=N?A!`!1RlA`%?WlS#X5dk}-G@n#SXqRokL%JltMHxvit zOs)@sLB=~ka2$|>3?eF2ZK9A^Sendp^zb|)8N_V?6ew|3b^3G(*QMxs_1=*(p%N?| zbbGH|3t^)8%+;qqnakR3si(V2A*9rkNW=z~p#=bLa0w|62?8MbiO)ZEvywmRdr15> z*2ep3Xw7qm-P^|v?&)bdTVTXpgBIQNPU^Sh{yZ84h;$hZEb^m-KEa#lB(%g!x_SUD zPhlDD4pAc7ysZq;kRx-t_W*KU69zI~C3^)?Vjv;Hax7XPC>yZlJUpY0i^QT)#`17| zl%3Id*w>E@^&bcRy=wJrRpB=IfcjrIdV2JNUvJ>*(>uW&iX1h(cZ6eUE;g2 z^erY%gNTE9^tY@f4MLBPjn{2M}jp^EsdY_7@DZN6N2T4UP4L$6)vK7n#cpJmJv>tsVeeiGn8<$yOl5aC~Lew zK5Y0T@S8u-Ouc>)y+a0R-f(3{wco0Lmgu5GKuA7XE91rf&{ohCTLUmz_=+ifFZfE;m9Q~^ZWHbU&7-xob5i|nOQAs>5Gd4zL~ zyjlOTLI=LYpd_`9j~dOEAgKG|;iw z>xBCKb{XQjtrAx4Z+7+jBaPRIwoFEnOd;53g7A^1jQaK|%s1I5L-RqMWP^W2bfi4Nv-0~CVQaql!W$N+_{0|@ z^^Y>O)M6u12}^r2Jd!}al;Wpq=4jYibltfe!MNJef@_n+*jCk1+js<3S`vX0EpU8z zvvg$qwRKdF#V1a2`8YCB9kluKZFAo8eshlhG+);pM9}i70O{2#>ln`c>-f@{j*B3u zh#mb(hxsJ@ufz76+r9)Y7pLQ_k9Jk}E+g*Tpr@-J9j23@OVfC#I!J>0BL}ar&1fnO zw?SZ6n+PYra@}Y8Z7y-#Z}YzNj)C3Ezh?Xzm2Ll*wLIA&#;&=aD2BECGevBAlFWr) z$L3QBVMUpI+k)2%vN3~|^#3|8Qy=~wVLv1zcT>kAtfPsHMPBfBJH*OiAZXE;JJIME zh+0njFcv6mBM3{97fTBFjUtK)S)%L)bI5Nyd>{dfT;73Z)$!0-L+Wo6-{$Ke){tTJ zN6?&$38ABm*jiYXut*LCYMRe_m!DHHbZxo{WMUD4z6vDm5;&M17o412;E+A?yan^^ zGrzlH-h}jtpaQpEEsaL|%Y&HkqyqDjj}IEU7~C_lq0zxS8Fdon68^FR$BOs26=)U} zG02?vb5PM$AmMhF`gV^<+GmnS^!od#$f%I7o04kn(vQH(kQ^oT_O1_dxwVg?MAskk z#wdTL?o(=4#3F(d0fI5BzQ1mL&vWD%G*m>Sps!;wm1yuqX^X)<1%hK`(01}XpUQ%y ziXyqPeW8+b1*xwjgj6jDN3CkwpdxhHhgAzPc7yCThuSQtbZzy&lu~*VrfkgwH3<0_ ziXyW_qfv$Y0~S37I=xv@VfxL?M3k+*S8Zc0VUFIBI4?|u2qKEIhR6dQX*L*~CL!xTE7a#yRBx)4`CR%qr?=(@hwM5$eIAbh$w+BtI44gpmneW z7sv-f5Qrn7u(o1AX4J=$#K&(O3f0rZ7?TG|NXmPV`+jN|;zkS2(R6 z$^#(!O0aB4flvTMzy~BCgMXkbffxr(P|Ky%!*pcIx2%calcU6W1bbo$dU}XFYKT$T z20Y7w834@1{0kQNI5D_FTS-i!qn##zhka-VHUI!czz6?=u!dAP2<~bDB>0CSXn^EY z&gEpz=5)^IgwEzX0XH~-=(Nu3#7^d%&g#t0?(|OSq|WaYPw(8$@ifotEYI`w&I$;G z<#Em_83q>!PxYiv?VQj0#Lx5;&mZ7RY*@aSqz*Xr7Cq1d9H>o`qn!{S0w_R*bU*^% z1Ww^Jh`#(ROK^h=#n24Z&<*9#4)xFv1ry`x7dbv6Nl23;UavjhMm zNK4jQ%X|btW&BjO{0X-M$mPg4(yR*6M3%k$QLhrxgLnaVumnZTm0_eqNkzBLK?O1R zfhIr&f9NJ#7>6-{f@vtq%cM%YR3**KOrUT|gW!ObR6@+WzUjfbfv^Ttpw%8R03CD) zZN$|{{Y6|52Yg6}XMi+~T!(n@NTaMok!;Iw97&tVM4urD2dL9pLe+-YSA;N4h)98T z$b@a(5lV0c%5jJupn??$*Jr!OQ1w)Zg-id=WQq3i0$UsivoMBf>{qN%Rg(DEgGhxj z_<=BRhIC-fMhQ%tu$_keyoV*pYMfU-bW5I?z-J@~EZ_*1?AVg{Sb5pYy6c5=zz1{a zg&}CoMWqfNph=gt$0Z%0=>yf6m060F*Ph5HlpF{O&jr!`uW*N>3P`@k(2s-r;U+f@z8t5jL21q|3+g(;&I+C*HpzhXblh8NMImcF$fVtpvu%hKAW;8?9o^JY+__y{)=k~3%|7K}o`Hw}`w9k(o!w;B zOM@)i9T@{v7=wtogGc;b)C%5+m0RKcUetYwH`2dm>6l`e#<8W{A?!tVRN5`66+DR4 z?M0{V72oi^-^DfFm+;3}%Gi6WT%WyMkoDWA09^MSmpOb$`mNv6Euzy^UHpw;{UzR( zKmg0oS^&^lH1ya32HMQM)((8%@JIqq$h@z+g9T>bP_o|%244x@-{EbDXB`L&NSs(G z#139xFtpw2-4UG7I|W(cv}$3-mEp}S-U>bm?Mq$&K!9!&1`Ooa0>%( z!05Rl#9UjQf-KQZ7PmZ>6&VCLs{9M7+gw22*aIZJ>Ft7f?y-QWJ~VjW@QN)1^}+566bAWL@r20_F*1@ z0UCkFhQPvB7NSZ<;y(stW^Lw{m;j!!R|3e7yuD&ku3|V2W*$)mRv3fu9@<206^PkdwO?b`!}Ni?Ye1cQj|4LfoEA98-?$35r#)ntbd z4xos}xrzQ~7shCczG#P_VGGa>Zt$h0!fSVB>VEd;y`E`<=m6s& z3s3f#90qBucJ2Q-8|^b`(nfrU>^TLu+`4%Zn>6} z%I53jR_?NfX@Up~SVDmOFa|c3ZuTZ`-hS_dnH$KyZ~X2R{f_Pb?(e?#Zvco~0qB@x zAnXGV?*!NC1#gt8OxQ7ba0pL1z0T@c=I`a6Z~$pl}0-~?BA z)NhRf%sFupw-5=h@UhGsi#c{uYsZ(Jnbz)a_nnOp@c3~oIb?oe;TK<9}?Z|_%!byLS=SLzcQxA0>R zc2-;DgGhlM`Dvr*Vq-3?`PFqf4jxhub7W8UY^P-c;Da+Xh8nN)NB?yNe+hWdg~mp& zHWv&c-~^&Z2ofO1Y8UnRGwiBdR!h%cM&JlyFmOk|^liuVny7pYDUE^Ge4!1kiI~uxf$V_!ghAWk-k^(1dKzhh-oHZyk?kcM6j~h);KTgj{$N zQ*lTq_i`U^R|kL$=(e-SX@Ea+jvsiR$b@_FhjcInB0Kq)4-6?#g>!3&JFo)ZZFxo> z^_ZvmMwj`3-^@iQ_9w!6o)>n(3*nE*fluIuc;JOGkc4fhs*~U&KLR8{A|$T^07OzG zMjD6#&;)NN+E55KOd_^O(-ks!o49d^Cyjb7=5?F!^>OcduSa!RqyRlH1~UA5pV#?!PU>c@k0)S&mre$g-fe55F2m&a8v}?+yM}xmy0b>8A zKm3hLeDT3{ZFl^~-*`R5g2b5zU?{cduKeIfcFZRTcen**D+m)1)R7pdg2JkSNT`Ks zsJD2ih(ZE=Fam?fs4KhuT){!$PS`3~#oaFxIY)DS?|J5*Ar6@IVORtw!rA%1`XhJ# zfdGgT00t5)Xz<{{U9$j0qjk_yx`8UxjS69c7PkceK6TR+P8=>71Eo0}ILRGCf-U~F zNa^w=%$PD~(j2(J)hbFbLFCaBr6$mzLWdG9YV;`5q)L}AUD=Xp&>jDNKqcD1O@pdK zuV&RMl&jaEV8hk~n*r85dh#Ac@bc#a*@I)_%A89VrrnxScOdOYqo9m_LJ|LI8^N$7 z!5QOB5oGeMU%zfX2Hv_?P0W~U&<1+@M3But69z@JC@uBr-PAQHtzuOJW)(em2B@xW z`!?>}x??)s4L~YY-vjgNCSDw?@ZrdlU$yW^9zA-oG63-KhtGrB#&K`I-5us$r2hUA z)L}0wx+Vh~7HmMtI2AqQ5X}276Ao}K^Y81qBOmx6-Fi-`3{GowuB&H_gT{IpPUQwB3 z(oZNlW}-Q@k3ah;0Dub9JY(2EmY`$6Kq16~2mqt#Ly-Ro|C9j$Nd%pA z5NW2dgrRC-P!d8+R_JjBnsLfGC!IlQs2hhNb|svRboEKrpISMvNHNg~gGB%X1;E80 zTqOG8o+FC5Tc88sNK`oC_(M*n;dIl?6hW!L1gT6|!wVAtv_MTX0uhwSIkW+=06dBS zP{uz)4CKUrsc1t`FU`DkXPvs?pobnk6uT_5&00t-Zh7)K>2Z-tYHhW<5wHj`(G|0Z z00n9AM;{Y-M{RDEYNhU_ML`1tQ|!5y%@8@*yW|n~*n-3oytJbO00vwm%@a^m%R}VG&Gp#yA3jT_6161pzjvEI7%7 z$HX&Gv!npPER8$fILB6#EfWejJ^0cAlWV^D*u?q;m|$eJovoe}#tqf!LuCL=bjLhG zfpU9Z@W&q)m~1%Cxa%ww;x$3@0sznmKfLgfpUF8;gRIhu#mGDVeAvYLGebc}yuybfF7>^g@TaxWy-^x4__du!u% zkK7~=Vv@!+a-sD2Oej@k?XA`G}HVi-rZeWjys1)ZoQKrXk(IXfun#old z)rG+QvziS(93qbr275?j6r+%aJ=V6d6yC4~svv_)6rjc`$g`w1Bvw2oBWXHw3ZJfRodu!b&*&@qnMkc_S%;X$HshY6Xq zs`DdOHZrjTcZ3QG=jbOj1sc}eB}D*>VB-Hg*b)?P{=oxd-CaPz6VXjFwT3Lf3I0+t z09jeJug)VDA@b1=gl*)DFO4f)5ev7v!6XBCqlYjK8Wg{I!IeLqsZ1f7MWZNy5TOV~ z9hS6CPKKd{gYYYARS2ydJb_98kirqbdRei~maIh~fFq!D3`a0DD6^}b=@=WA)GdWw zb1e!Hx)G0STq7Rc(A7reS4=XpBA6*5K@~`v+U;Jgu7`c7ZEKs@pm3mN^ZbFZI-3n=*#WT-P?1~Z-}17<8^w45A4gH++#gD61{c~}8=6CB-^{DQ#-e6Va4 z``+NfcewN&2yUTcj78*BC>ewqh2Q_W*a{cKzB18eL7V^&|8kOruCVSw25^UrDY(YW z>WwZ`001BISQiln?|6fXS(!LCMdd4s6kl{PpM%|s65@n?DVjEM~>lC!% z;|1Gz#u^JVqAxUNuauIuKn^lcVL}1co%hH_>A-a!P-moU+9;ha%ASw%0%iCEANc4; zGF*`5Vj6%FIzdPekfp3d(>gi5VJ@z7&DuVjR+u z{&_*LfFff&Q7LQ%C&@(&>~|Z)#Gm*FVhBRKsTa@XRaIUqs_c?X(!A?cA=WvlCMI;S z8|c37`N>m)fO!|x(nwj<9~MdweQ$-|oVNQ>Lj4jcgd-bK|EqLOYQLu5Ak6zjSPBY4-e2^4)gAD9> z2@%R58oo|!;9``4D_U{dgOs2r{98Qmivq1fOk*AEn8qRK(&&s|9`noxfUxOtj731@ z0qJwA=ueM&lP~>{syB#24&xFTJi{OT5Wrn(^;7I;aQ|O04zjDEPxzT{Fd!pQ0bW-0>T^00S!x)SbD6--xb6; zH~|1$AOHx#if#X(UnPMma2Wu&QwfA16b=jfg-n@g91h+f3KGQTiBGXH#d@iaT-4yc zrJ$aP;a33M0+xmY5(JSL$vz;7k|4x8C>0Sxfg>TIRT)5l4cI^wz(_?QARfdBDn$wI zU-OwD1aUy25S>?K&<2Ge8J1xrI@=`nTk5&QsFcd7qzXbX17o~H5Ey_j{KBfWUkklj zLBtRqWKJNq;vgnPAs(Os$|C!?89fX`05Zh|Oc9JA1l^rsCEi^ylHTb-n*<&N6QBb# z;Dax4!#P0L`h`(nu|_K(4M7Y56~I#~y5bb>RcgfI6`tUH4Wp;IK?pcPifmI=Ab?xI z1r(VfFk=7VI9{Sm9OFT_Kq&ZvCjv|gx+b=E4C5t-47oQ!~js$K!PB#Xu`rwTPnnZ zCX`*~ogG9*P|M5%^@T-}_2N5{V>trl7|LUPrJPWF!zkcfcTJ&RNkJ>T0+%VkjH%>G z1|PA6!$J~-B!mM^+GI_7rEOS1%N#?|d4-(e+e`c+M+#-#v1L4B5mIP^HTZ)yWI_&D z8&mpK7_4DIxXEl(rTh`gJycuH-9uMC-&Z1LZE!%hFd|uC8XwG(M!Mx&isQc(qfrip z5sd$WH|T>iWMwoa8rlp*g!lwtTBUStLnstPDEx}$nVn*SWomE$6Ac3;P$mEzn@>(= z$yw(1MMY*7#S~ma=!7Pii2x@ESV6=F;+^K=0oFb=gD8kXGw4Gd9H#!!qHijN(6t>r z5`Z8%3O9WuNRnq=nCEz6=JyeW6wtys#6vIiV-lWXLG&ImIj7e_3l#7IbMe9xz{Dq5 z!#kuyGVsShjDRhu13dh~UA_c3X5lP`<89a?FhsyF#!_USCvF0TT6*M$mZy3m#b$P9 zGf2W5;bDSNqZAaxCCw0icHJO0!z3($6D-3x%#kgS0~tU8HB5tCUEEDVXoNDwBBcLC zEI0rF(A}{iU3&JW6$+{MiAOcqW%T4_YW*V#b>JN^+>16Gu`nP5ssNkF#0>ny+PFYI z5W+wl!9Q4I0yboj&LdGK1v=6LEHIS5-J5u7sFOORcIriN)`U`4sWc{7Nh&94CSI4$ zob*73qe8|wjKWDC1QGm0s*u4y0M9^-!%U6_10umc6hQ-wDyf#Lsh%pTrmCu*>It~P z39Krt#;UBEYOB8LtllcFvZ|}*DzBz$ojyVckZP^=s;r7!1>EYe605SVYO*e?vzBVJ zKI^kaE3W=PpxV$#k`{gHhKZC#k1ivPv!3%Bt9oEv%O9s#@!Micz+5k^;aOL14_G(S-#N6g?1w+tDo95Q{ww zY7zL7!ni~<T~@1g2^#0C1{4L%IS7iMThbq+Z`|RDh1rh z9rJ!Dh|cM6Mk!JlBtk0WQkATNQCIWCTC&i^Dz$_6N=NvzZr}w0DhLoN0B=D6je&?A zg04e6FzAmmFaS62D}8945^w=0Mde;@0%vaUJ|sDftW3CMD!~7wOv1rttb{QPim;%&=0(Ok1@j4{NaxYZg*qWkGDE5i1zX ztwJdb#Ia;BT_nRlXkZn0PT+|FFH8f#NP^Z`91N>q87sviM8_9{@!K&9;E?ekOCke9 z8%zvlK@@>uqG+O(foTnd6)fCc(851_Lmuy~bP+;4;KDtiA0`-F`>@vg1N2pmr`zs3vQ=rg1tPbyb_9-i0Xq1D1`l*bvJ#EF=*=!B@Se89%P( z(gYTy#Us#iEguD2VV@(raszX5(*bcz5JGfLXLVjDCMW+|2)qI%*#;*3!yPiS6&FN2 zPz4bR!6moy|3dO3y95?M2P}jOpBe?+HS$mfG$lr|Img6)_UC`Lv5hS;LEwND%vxBC zz(0_KJrim{fCESop(Nljqh+yd?lLbY1#O;}MJjSpQ#3yjW6ud(iC_*}90(RDPHCwY$WI&+=0}LWmo_#Yh()1a}=HlYC2!d$~ zh$%&b84sv}fUSV6k%a>M13L&c^%lecgaSPHgFo1V#8GofJM~k~1O*HOWKps64#fe# zbY=cCvnlXF1E*KVg!w%xq)Mu@e6C5cP)-1Vn|S}5S4hD>?3`QUVF)0B6r3ntbG2UQ zbxlM-%Yg3=6NOA?HA7pXI7{+NkgK`20lKOyyGAwzCmMC}z#MCIRUAT*boN-EvF+_hQ2Y`I`SP`l>Jcx^J-zcvZc#E37D4@Ip|#_=~T1 zQ@?jw}fBwZ+N&%h%gDaH=Q8)%c)viOv68@6O;=$j2m}^ zyEcylK;0G;lG-3p7%M>E`C&WskN1z7qm~lf0S;6JIQ)Yx#JQYH`Dm;3jPtky;LR`q zb}r}mH}yE6e>pjq7@4O8ANw)S26Bndp8`-qDadVAxH%^}dYaFbdIhgahZ_2hym@+D>GAp0D{86?fAPbi!g@M5Ok;{5j(E2!w`L)x;APeyG=_dxm!x8A4EQ^#pydW<(c(92^0 ztWq&N_e{rxZce(muRY60eeKFMUEB2pi+#f>4=db36wG^${KFA~J%(t!P;tDZulxya zd$%LK+RfR>hdH)0{lJ&A+^7G%z2!6fyy!{#ez7sq-a{zSs z`>h`YMrMcGtGv^9e7PSJ>AxsCFuLdu{_PW@=~FrI2R{H%fXqI=x2MD|Qjy2Ye%Z&p z?c+Vo0Ra`}`~g>` zNV*kY-VK@YA(nac7OBl!@WP)z7w8Vwdr zU@hr3@*)B9M%@1`M7U;Tt44y_V{VsO0GQ7pOVSZY1$9OV!30{k!4Cj3z-eK?fymKh zpi#0hNQ4%!jOncnxzvh>Ry@%I4=Y;g=N}}xOjFG+JKXKVef~}I<5yInKu=f zsGA9Ec)_g&YN9!TpiIsw3xEaS5fur$LwSdZS`8d%8U>B6muh>bAZ1@YCM0QqvC5d- z^Uo2oS}&|aZhK?qq{D(9da#&wpbGlh@n?( zk0fIW;~Cim#$EkGfJ?;U6$fGgV-(A62?)=4tQf;yZIMv;;~yH2h{niJqJkIvNPqvh zAxK3!D3EGN;_2R~#{d9>9>UPr={E9(7v(XMZuBH&y12+jE|M-a=;2pN0FrV1V-2Kq zWpYM|mPe}alY1n{ohBkeKKZF*eC(qy&%!XR94eHGjO8oUq6#uvga~7K0WzT(nPZw| zmaeO1F9(tVVi}8e7El(mu&KvzUh^Y=JmWN@xs^y1@*}wT2RzalPr9H}E7c@hC*3$n zdIW<2(|JSuy3o&Yk`smmt%y0pNKbjzgaxP6LnbOL2-7mtMu5B*dpJ-CQ6L zvis>kk;>5;TE>+-&FM(Wz|Mz!;~&>}>Qy;}QOER@hDTNEiG(50$S}YQ^5c#{MTpXZ zf|9AEbShRW5(0;kKp{C8O9J7V*N?olC0x~_TG^($C-R1cE(B~^y}H(sAk>R|)hj|u zak-f$#1#MN$73-Y!RKf+v539j`r0>C!w90ITM_0k@#oRfqSlv;Euv#HOOPo@6(M60 zRcvv~Ev;USvuK6n{a}Hj6kg^5%KAWR8@5{39`?6vMJ8->YXFCW03kjwV{Wkv-Icac zrQH=&BUabC%Lw3NUXTECO^e?2Di_G;wN=yIHH@DgaC3lmW zQshV=JFwu5+0f?Rt0;KE>dgv+X+q4ligLdEElCn8*olJ>Vl0BQFlPO`*xq_qsmqB- zF(|Mb*clbVEorff9sFMQHn_F%J!geKJd&k-g}MY806hK?jT~n-#31pj?K8J;CiEO;%9n@$g2WPF|45k zjTjW*^+VwIhkydR*v2NYfQ@Y9Hn5=xMzGBipzUpL4@3@~sGui0k%^k>d*4kZ_*opS z+IFL5$*kivK??gqb|+bh@4j_8ZCsFb>{o)(&Z`kRfofIT;~$bJI95HbWpKlr<$BR4 zFy=h$hZKg226;GM&TVCx>wMu{M0PWrd z{*jHA?H#9^FG#|Z+jFg)SVb|v3xZ8*^RMT5_OuVX?Ntwen3x?)X-CL2Ag6hwbNd8H z|4K9d!4FX2hV(BrJ&ykFS;w!%0>lc8KsbGY*v$?hi+4%w_YD5J+&=uG{s=U5k?*)S z-yoQ%JISfh2|KXgqR;2z)LSn7#ROLv^m9F1v@XiNkNi4~01Ghp6b>cK2^GZP2busC z{GoH;j{X!v4MOf|)B)f$i~{A!{saQ`)(Zh?f&>4;YvR=6@H&F=D6Y9|P5y?J^r8*&q;!o8&0S$ss2#2qpijW15kS;)KY)lX>R*d^pP~2!~`rc5)U@)P=klSuS z8N`7LRSgrq5SoS%1ea?Hw*moljhoWYEbPdvaLxcN!uz055Zz4<`)vJkkPN~>7xa(| z>8cM6juJ;_4CAm2+2T%$q4f??D^O6*$WHtkkri8!5f?G{woHevaG}CLWipWq@rn~E z%oEE86sfQU(Sicz==zwj>&%9iUNH(o5EB2p>ewcc7iZ-kdZ7|>u@ek|7u~83u>ueu z%oSG=76AZkhT)QqQ4P260G;s};V>9qFdF-C1lr*r^q~dF;2MWW8(WGSc?uZs$qlo@ z0+>v^WKZUvOn&??7T58w7E;X=Fyk7FA3tmWtYIvQ003Yh6YYQrMo%B*%NIe&A0tr| z(;~Qn;j9YMECL|T%8wZX5g*gYX5$Vl=W+E2*-txDv_Ik|qBHOQaqVD*_ND)$uOv5-MY|(I9dvYjWRUU@V%! z!{X8p=aMD7QO20^A(D_D3`{Irf&j`Z@mlgMAI&qR5E`xUF*EB36tgiqkTf3>{{qhl z&*JLBF)LUIZFmkeLsKw=@*PL>Fiq_V#v*D^Go7}QHC-_OvZ69W3o}!K=BlVR0TV58 zQ!OQNH|fuN>_G*BQ!aV)+lbROTN5i(=NQmXIZMLV@W?r%Q#whqI0;iKxlA?T3JJzy zAD$^Yg%dviYclI>_5=W8l9N0~0s#QZ9KlXM_tPo&GCe=AFyC`Kb8HI60v}|+KDF~F zyORu!^D00p#T2q7Ho~w%%|QQ&%{E_hEw|A@ElkY*!5;LELhlnr5w0$wQz&VI0ER)R zIy5CNtvN%KL`#%L-BBjt@##$SAKn2wUGzmQR76?A&hEq*OffcDV#UB|M4$6Buk<#j zlP#al3C2PfWF|?$5JssrO+J!ug?D{29lVJs+0 zOe=J=E;JM~v?ZQ2N~N?UG?OD#(Mr+uOo8+tP1Gm%tp(0uEKJT%|I|awGy&r@A#4;! zmk}jqGxiRYNt+ZL0hCVTfD_ zO)bJr%e7HCm0=flOHb6)CSfejfnDVl2W!GY3hf+*$OY~}XH-sLA@xy5A^;#JT*dVx z$V*Y>bWjDAUF zwrQRAX_@u}+~5SDwrZ{RYL`}OsTOOwHasnWYm-)M!FDz;0BpHdY|S=p&vt6nwr#H# zZQV9*qn2&uwr>B!mTuGb2Uyiu@zj-`;L!d-2y%9z-il{$k$D8d7q+b+P6dE0!3`ic zawT_iDYtSh_i`~eb2WE!Ik$5?*A3p_Mq}Y~Nf&ZS>JJ2=bX9kCS+{jv_jO@6c4c>V zE!PtEwu6rKa|R$3P$eh^cV5L}S`T+16qjhR#Axj{dEqvB<92!N)@#+)d7l;oV&?;x zcW$@#dfirfwbyL9w|lYnd%@Rg#kXqpwpekuZw1K(xM3{Pp+$dJXIp}2eHLg1LTI&h zQ(G2hM?wkzb5|8YVI6f&RTV?|cVuo?{VXgDvh5#q0cYb^ep!NN2Y_Rn<74wzWCxQy zQ$o_l(=7iLLO@w|MhVz}Ik;(q`r{RW^~@8KDY zU{y6ZH(mB4NN^tXvWOAFY%ond%Xnl<*opHOiiOW&U+Dx=0ac#uiV0VJ33H6y_<$=S zxWe*O+eV7YGLTQWiQ)K-PcMO^Sg+Qgfm4BxozIVH4UhwKi4{U1>A@(6b!{rZxcriY z9hr;;S&^T3X5q>Oqybe3!ICf8j%#9DOBGnbCKwo%AP%w%2y~OTbIzChxb*o28$n7uhFjTxr~KpV!QA8wGDo0*nr z!j^YAm>(h{grSr}*&vRXHotkBxjCPQd6lUXtETZEm;qhTd6t(HU2nN193VT4(U1*- zjeQlL?-`;SIhB1boEK^bpkXZD0SX2>r-l=n5f&xxgcyEVjRD}&*f641nUN*Br5~A& z!zXvs!~kXiRXU}kJ=&Rn*r3~)Buo}m8TxgqSDsP1n^hW^Pr0J|*`kgB$cz+mak}($ zI%GjQWjmN2j^SY8bOOSI3*PjoO*yH<+Ncp2rmsh)HDm#F0aa3=Bcqz2ZI!3tG$sFr zSTX_NAYFu_$C|8*nx$XbqF*To;(=m=;H{x=~Lp3EbfF96TG7~kM#d?6DKpD;<9byC9~Sb(*pRdXX(4!lgRBYbdupJj4eA0Tgi}U< z={w1p9IWqrj+cXO>;`Z2hHw04AOJ^j2&H-LXms*FKAc+2<9SD5s^@`HXHC-*@TbryVj+mDmG3)=+UhP30#QB*^b*L6l z#T0Vf><>HSMU2?(UdhALP*EZPSg7XyZ|-}V>(BK$1%8D)r~$xXEYJa}{r>EmenADl z&QqC^{x>BOpAF;wC>g);jeX`Z8?YxQ1(5z9+Mw?<|L+U>^ex>YGT<-Lm?bv+6dm8L zwSJz@GV&uCblPCHXCJrF{@)+pBEZJCTjJ7=eDRqd_-%jdMIDmsSbSb!8&HJ|l3)2Z zp9nj@>kl}g;XC@L=mSc*^v^N)h5!0ZS~v0jbN*#4paDt4pUB3ao#&cl0b&uoVgvvf zJcux%LI4{2{P`e2VFNb}7FxWBF{4C^8asN_II-f#ktF{QhAfHF! zG;7+t*y3M{n>>30P|)q)KYwg|8a;|MsnVrPn>t09bLUfwF@H?W`10z)tQmpPbJX&J zLoNk3iqyK5BigiQ*CyoZ764qgb34YI88$X7W}_54|FU(ilTE4-Un@8Z-g8we2^4hrkpv}@bWyE<-T!V_u4 z_zgU`@ZrRZ8y`-?jql^YAJGHG{P>Nr2waNRYno|x?bq{eSNh!`>f2LullLg8&6M-( z+q-}7(fr!oeP6gKWGKJ>{rvm;{|{h)h1?gQeu@7WLys&40w_oznN??9Ti$gSS9nQT zcoc?4SvVeiNXh46LNCY=Vu>c6m>7s!(Wh5(cEkZ=j55whV~sZ6NTVEX$bn;wkkDhy zi#^uZ;2(g{fE9&wDY=%08!`zQlv;5p6N){lXl0gKZpo!lSWd-aUdhRUMww=wiDsH= zuE}PaYPg|Bn`Q<>Pb_k-StKBd#E_(f6-wC|pn>|iB%w_TN>!Czvh?Mmjy?+Mqm4Qh zW?W<5iD{;Hz8R;SgUmzE8Je1z=NyLciII~%smc?pts+_)tW8mgSEL_JYHO~#?s^-p zOjYXErK1izET?zILXR-S=9xwur}pWXtla+@dMLG1O1l)TylUj@w%&dVZh3s=1?*bF z5{vGpaLSoRG4wz(tRQ~;0Y(~VIE!k8(ONsGVXoTrZ%x{Ut5CNDAB=FqC>fkoxoDl6 zZp3OD+h!y59An0)^3rSXz0anKEqEbcI5NrnhIaB(11rq1!Y;oIGXO0g<*-%|ON?`w z6thVuFdF~Cv6=Wn%Uj7A8hv!iu_`@l$sH>6i8b$}lZ+9$&Kz^rTJwsvPc>h4bIua) ztmYu{(9=k!X@CKAy=M*$GSk!U>o3wi1x(Y*3N6~LP71bmy>;P+b4fT)Ur!ab z*y)m;=8wau&34dlf2?oOa%XGz-JSoxy1B@qi>GKtGyEgQ;Nu?7dh5C-e$(PlHSRdE zkfTY=yO^#Gv>g{G) zEYBc!rUA$we)#@7=9?vN{OCv(-x~YzyPtGQF(J`H{vudpz%tWZeZA@laDecEolUaW zl?LTXWtAiOSs zEv%vy38O-qAdo3EtYMoP_#^*gbPP`p;)AGys6Mt35j#jsVjEGSL^v)Fg$WrzEzD7b zU1jl#eC%UN_Q;YgE~SfJTvG$-WG6Ol3=n5T;|0|S!bnPzjYcHi94}&vc8nnhoHRl7 z{0PcWHU*F&lwn^8Sx7gnD@|rY+nRW1IXMXtl0{r2C2jd9_dP8kA{5FbJ}Jsz3X>4}OiD79sk2q0 zX&AaolLUWQL20IunvVI}u@oUNB}r39@>HnGRH`&}BSv55Q=V!S zt2(_3P>mwgLP8FF87tEnzF7IbPLew4JVdwbb5( zT$d-=UEt2la144lh+btCn|P7C+Vswpxv;(HbJ<(n_bNDR@kPjdZ&F|G?d(U#fae1L zOWq+C*uWcpEKItY)95aE#9C|cK^|IP*s31Yy@X9!~0(L5mB|6b4+nAgn)@XuzjOEN;`B%9;<&cT|#Wx7T zhkqDIl9kNZ88?}#=S6RuIk#SxZ8^(yzAX%cY^g7U8BgW=10RG@r&MBi&2%NST@8Kc zH;eATau)w_ogb~oIV%OlHBoWS&QQ5PfZ+^hQ*7-9t!R@GSjrVOW|b=|X-KO&OFsqx zrDkPI@L&dbxUGBs%9I>cbxiEsBm5F@ou}dQ?7R|yM5}} zl3U#TCQqx)%@TBDO5M-y7^ftM&RmoF-r3e5zJsl0aQA!S@A)^fg{*Ae5?rmzgcCcb zP3<%@x#1op`4Q*6Tww2*;w%r5#qk_0Jr{E0Nq*BA6q@jO1DM{W*0q~`F5i3$d*3ZD zIu`$l?zM~OIpZ@2!+r~HNH_dQSveQEwNYN)o-h2hTaWF^jSlu+A-yL6Pl>>p?Q~~z zoK0`a9mqq@bB1?apFoE*qZ2mluQ`4el4tP_`?w2R^Imx z`GSpIaY~Ol(*d9Mb)R`+hOK(s53hB@(;e}E6?()Yk9x!OUALE)Sl~6K1_Zqw?kOid zj_bZ?+>@^HT$_CAe}9wJd%5-Kdi|(=+h2HFUEU@K-Ka&+Va9(Q_|(6O@RN-*;}5H6 zL@s>ja6_I~d(fA7&xe1bM`gShY3CP!8Q2onhjGJ_faroq4XAvd zM}ZSqg8FxY9^q}MhJhOBf+WF#OQ$Ixh%W9%2_i^)S%-qr7k<0egQwAdz1M;-NQ447 zgiBF&C_zXxm@bkNS|j*?CK!RuXGw}zV zM|^sSGsq$g4OByan1YpPiBsr?4km|(n24Q-5sPSmm*WEL}*J#lQkK2{-jLDdgUT1#r7>(Z)0{c)02eAvv zkdI+_6*drzX26jh>5(4^k|8OQAUTfdgoA!~j#da|gt(B(=#n=Ti+1LaiTF)A@DJ-@ z5UEfN2_XXc(*j8F4@J-bLrIiHX_QBalu4DbfA@A36^0gmSahlUug%0Km$wJ04LxEC!m&Z372uXmTf7Qb!nGG$(C+;mwOqP zdC8Z5xs-khn1gAQf_axe5R;Mecr(dkHF=W;F+nZnybm0t?8Pt37fGgo3lxqwP~BTiJQ3@o0gE6DKw3Y8FmmU zkrZi>2+@=I1C&BZn9JD!7cdAm0G-h(ozqF3)oGpA8J#qsoiv~WZlD9(37+98p5sZL z;`st^X_(9jnCYpWe94~extH$=pLHpp^VyelxtEB9-Dgx&ZMfk54GAHkgdiXt0wRbM zgQ8NDF1;7&7!*(`5|l0_q4y$)AiYTMO7FcxDAIcoq@zev%;Y)GoH_5Dd1p;N=S$Yw z_sZV)eeM76dxX{zj37gx1dyOAJoO3Dky<7t=OP=y!*}sinizxzlKNB|e&&t{z*C=Q zP(L~fZGojI@B4NrH%H0?c z<4pLinRib;-$IRZ1^IoP6q)#!sjU#ygd{`&mWC1lv@>pK9MUKNz=v`;7aEa|r-rOh z4qy;pF_f$(pB{&KR*S*Uw5i4VA_Yudzw>;(OPra!X}hn?)PSM{4s$6iVc*e+n;GzI z1Sv1^_s`4ZHO5epi$Dkf2#|q)#2~U`s41LMgb;M0h50e$VdSB?FKr9%-YtIo3loHc z&Z3yo!w`2+@LUW+{g9dnwk|A#AS+bCwg{O}FtOMihCw7^;S?fC+?_>Dg>EepxjX%( z?WzUuFG_dv3)cPM8fe6zEka0}dJuVqSDU&4Nv3y5Ik&7bcZFmn8jfBC(qBPk-6p5|My~L(m8=1WgD46mJ)n z-z@rKi>MCEN0~JvcZcN4=2dBLCNb3lvT367Af6nlPnb z6gKh5TcfD=%HbnG0m75!Gz4)qjAkw)Q~#ni=51+(f2_P(ZnbHJLQ%EMK=qKAcSW+# z%ejVn$;N?@hB~{(h9bWve*Rd>#u(nlq`B%>MRmgU6@n&B4W|twYTl!2P2&x9Q#+V0 z3PZjyhm_wA^OV>{*5;Yyf>p_aL&`GNJ_J03@Lnc8=l40ajqcBu)H5iljfYoxbV;$9Ya+YNR* z?EaGlbrS4(qu%3U-{Th1<5Ar6cCg2Lx5t;N7dPJ{;*{Y*3uy}I4K3~sAMB0X?Tx1D zixupPQ}26k-}fP+FR8dMd9W{aw~rV!#a4t1)6r$x6Z-Qa`U{Htiw65kcKgdB`Z;&$ zZW9^0!!EPIlA6Y@y5a$&!GWd+T`g3DT7rWegPmRWgNhM@ed?V9W}Q+6>s& zsiSN|9JJJ<9D9LW4x_B*W4sz;{HfL~kz-`uV})E}Ds5wdT%_6M(g8Z-_ZJw&9he?O zj^EQ5mtmifC}EUp8kdW-R!qIF8p*Bh&8>M!m{6wf(9`&8;PBNj@~d&lSJR=d=6heC zP)}M4O+M3@w04-3`~|8-{G*cQ)?ckj49{j`)VXul;2F~;EYB$u)R+N3$)K)`Wu!n; z*ipl?uvI2pkO2&wfQp5P0J)fdz)}xUhR~+z$OWJvgZc=agZoXNFf>i!L`lGYUg4Pz zaF~X~g6c8wBRo|+HBbY;Sj73|Tw9ZnT?Qrb z9dHLMya0Rkt9#^3ZRD%A`^1>L-#DX)M79UXf2LqjU{6|#?N*4i4D=vl*`xxJdsq=k z4W#4Yukhf00Dg0a{;tm&WQBAX164$keMM92ajhSEBV4f5-?V3!CsuE9tWih-6G&=Z zG`I#K262KtJp^fIP_1iMlE+dV49x)u@DYkq84LTZ4KdW&Knbq_F&n0f8&8_^o@#!x zd4>3hhKHfRL{9WvwN|A*M@whZFly6ec*6p|YAN;2+M@E|MYgO&&h5CZ;DIgSSDQxg z?{DFRRh-l^BomljrqU{he8*BiM!z|7Y`&3Vi1gX?;P~$KYWvU}R)vDd5euzYSo!`p zjPNFTHf$Mt^`}vEp&Cfpy6srxSo{y?C{>=D{z%r^mjCj0+%NM|28TEX-JKm!yuaQREDw#kkLH= zbD$P;@H-802?tOJ8mkP1*LEIoSfv$v2$UaE6Au6Ur4e|Q=Z?$s3_J2=$!BZXqi{Sp zTH{?qGw3TdO1 zqyR=85#yY~3d`{42lV$~1+g=Xmp`RFV~YnUPE4F=PO%hP7y|4B3G=iB@|S5Y0K{J@ z5~LA+SvCO1Ak1@C25&P1i&WV#h ze{F7kmf7V`vM$P?YWbE!=v-{d2HaT#s+hg;z^a+>lFUx$GshJjaRm*Yg18CxYeZBP z_E@wm#;Og{Ut0AdJ%%U#&9=eh=92IJ>0!434RE9U{CT=fqGc|UF$^K!ObaA#T+2=I z+xuMj2c-Sr2lVD)E0~cdzm2>s6cz7l0YV4)Sja~pYu8sDw(TTaCXnTm|6USS_e9aT$mc{x^))C+hhLul*48nG*2%=jpzGW|VO9BuwODfUpSP zm|uTePKI`UTRacfUym&0OIzCGhlJ91eTqTyDr23aj|ktD*wpPJ_4PC#T4NwUVFg(x zV%3-;+2`usW~&YmlPlrJ>(rxR2HT!MGP?g_FtQ{`Tu=W7mFu|zxU1x5Ye>Fp^fSFblf6` z|3$*Ct-~sE326C(u;RmF3t9N8rcE|U&h;yXRYUuubPjg@8)JQ|^(z(vQ;AX~f@0MMjuAOorzNVSmtZ--_3KU zRM$Ko{?Po3_9>Md#$U`w7Qy93N+AXHzdf-c@!A*)$c8B0jKYR`pG8W;71A%D+_DrV z2!EFK403a&Diq3+z&x*=LOI+Pew~e*Bic0c+=QtO_V~~b=v{_Lp2-4iD;(7_?N{7K zqe9ORA#yxVy^Wx4jJ!HQP_9tYFT_Y`JQs173JTK*kz?>24MBqes`oF_`%^+0r$2vW z)k>6u{CI9!f8LXc5`lZ^XNy&FuS-v!+}-~gMm<|ge!taPfC2xM?F0zshi;|kZYeSX zOj!P5r|9SI)bRlmT{JA>L4N~o-_I5eAq9C16j{BFOD)#p?T?Lia({=EKtm*c=tNoM zk0CWYRGUk2G?)it()H^(D1p-f^kisaw?gi1Q!J%x{u<)~sSI6?6HP*0=*LE$kXyKy zLk=8wlE?`B9ip=pQO^Y{Q#RE%MeiC9Sv(#8NbV6$lSoVRO9*Q=67el<@}-8G4P7*t znT+e@hWZOtx(}=yFO(i$=)?r+=Ult~Qbog4H$GSY(?1@i`Gsy`_rD&cgQs4~H~l=x zjh9;gc$5%>eEI9PI+33GIYf_A&DvHkmALbzXi%v4$=0C6)1cVKpvZK?*0AZqpghQ+ z_}O(k;~~$-Uvdpf?5yof7cM6EGbl>me6lm&^E7O{YDEtdP=-JKVAu+IT<(9pSpU?- zsFU|`MYy#fi25)TGkuLU;082)pM+W^BnC0x8Z0E6n_T74`97GK7$~*`^BaLU2FqCp zfM8qXTW9|#k)Mdz;ak(rAU{@XL_5zu$pCWw8iS%tfVdzy&?lrF8kdnGs~!{PaAV|V z)@9GDSQ%p;yCKA!$oJ8lD0^Lzi~d}FbaMj@p{@% z`}AE1lbMS1ugFiz0x!N_$Ka^F(4T~f)E64{;0G?n3jagpYQ175bT!B;QN7H|JW}9O zOqs8d!<8LChT<=6G-L_H4z+O#H~+Jmq`AWR3@H~Gicf(WCbVCL06}-vb>ML@pp?xZ z@S}LBD}W>?Xa_`w5;Ytp<9@x|A3_Gp4+1i{S;<5Ky}qjgW1gZ7U<3eiTZ zGiAc!&?YHD-Y?akOK^dD74H9tjj{>BArk_-um8<#86y2W=KGsWlFisAh`DZ*OsDhC z6j$W!mnKsU-|pth6R%rx)9DUgS2YwD8JBVvJG+4E=hVwx^vG)bA|g;O)7!y*8Yuy$;nB=D4sA8Oc?bh482~M==ooC zDWRu_&}T>JH2Fsgnm} z=H}+=>iXu*8z(0xB0NfXZbLBCCTOY<6dqJtSP++{t*xz%jm@)X&(LV}|8hu8O-&6A z4Gjzo^z`(I8mW$s&VQ++DnxfwSxHGrQBm>Hqet@c@^W%=|MH^*NpZrRTLi(I1THQD z69a*khCoUAuNgYd&Q8QhB_$=r#l^+M#Qyb3MMOmY^+|<FDVGZ)hnD2K#STDH!z6=O3%|Ke$q&XBtRc2LJ#i z03=X0K0k83c){2K+zJ((x;z@acJ$p9B9- zwDkACXzAF0LrXhw`2w|Nqfa6{gJpiI!HnbNdQqF=o5pq4;lTX~=(|rK{m6ZX#N`B$AXG zr*+dKBlf?erL#&rvQ+y2g_fSCNl@{_R#99}fG1|3OQ) zw|p!o@ACqnUQFkIqNUp}=`2K7zUSv8T)fOr=|{DC;}$0iivr~c%GU2b3p3lv1xsxk z=G32T@07LP?A&=9XR_T+=E7TKPsY@UZL7p9&h37FVX@p!d%N7TC~WSv=}wxL>&|M8 z$OcQXdPiE(e*La(lCbBq+n4~#b9S`fW7urCqwLhS@lsJ030ryX?JH)ex>@exn7TcV z<5wLBCBX_Gn(+HJWJ+e*2TfPE-{Q%X^pSS86wzkufu!W!JRNi(ZKnZLkKkvkTW{Q) zdRY$!(t9A5f`AJ(4 zWAppjD?OJdYcapK#a_KxJEgpFs)*<)oY@o7hIw4;3=@)|5v?8N6YyDI3CVj!w}#PU zKi~cGS@PWB{gT`HVn<(j{2R=?SR1b- zK)TOoKdHj{Gx1*2miQq~_T55^vQ>R48JdJ?FavVGw+;Rj1;F@8?&#`(nG7a2r0Zg?W5@cNy651Y3BKBSMIy}U3;)hVst16 z5edOA*9X9S|t4foysu;)QxP%T#ao9bp-+2Fcci9|=uJ zD45~s5G(TJMpV5ny+6TJ%nF;v-Xr5%>4;uwCT6 zZWIwM#edI1-?-6Onp6>)ul|X3B}8023&jEI3%Cnu4>Ja2s0r9$;T5N7Lje83+e!%u z`2l-GiX~~pCrVduKJ@Y+im}`b-uk|vSiKY^HNTwHg~S`xv4;&}T}{hp-Qa}6yP{nJ@(`?2iW)y17Eex|_-I0>EBx7b!DNrH_lJ zDpvUU8T<6uAEB0-n|XCh;wQ!7HGl&wpGezHL&-H$J1D)AS)i3Gd;`P zp6-=6t%KVMdzYG|x9&x_k$l;eCzG6B_u&I_wvdO)p524hmOr)CYZ^#pU~)yQca=HRhFW|tJ#E!CKPb}TG%#TH4YN#~1^g??1yZ61i z%$~sLT-pQtDmAWZ2m7#HBXqEo9)3vwn4$6qL=U{c@mGq_U=p8-lZt@uEb2sQHYy-Z zv>^}MxnO>~B&^37iY(|=Yhlw1v-kI)E?Vl}xSvlo3qJlF9v%Gc;82F?5)mky_<%#u zbc=E!29lPF48IF*qnZr~l&RK^R)bnnO&x-R`d7kuk7YR`5XwwHxI(YJXy?#GOa|Z5 za5&Lyc#!Nv6Sgz?o#CKnLUH5P8&Yf_f7xt5Y<=tX`5K8s;>v4C-43xm6@e?ZqhX;*u>=%|1R4K`; zTCRmbMn^E9wE-DUkO`J~kQsqXDfccuOP1+BjJELuU8#rYVvjzpqm1fCSp>LQveJ#&D@TbC6nRC#=lhEvMVtMJ;{4eG-eI;r$Ka)r@WpnE1 z*4LJ3ZvMfyvY8;DQ|8~O%$WGE?Dr}?*j4YSqUqejeE2Q1-TX7{N%BFt+)KhXvi%#6aJXX>{}w7&>@GY zH#jS~O-Q;oVYjD6xCNAPGGE7GB*v513QT!PuGJNO&%#@oB8c6U<}IiF2~|NdwZ;2t!&YjwU(_1c)mp*8I}COF z7@G$}_M8%1~Zswzzx zqkrk1ywN)UqIG$!wb?^sUTzOC1k|1SCT_i5dCc(`O&)ZYZ1XH&*~v@fna_S=tkFBa zuR6irXR*l8U|)9x|NH2pbz>(6y*mta&C9SnETyPys6l58wMtw~Ch2p6l}_4O=;E21 zZtXp`f>=5Jhq8Ta0*UO#RR-oR?|z>d-&T5T6ZqKH8WE0yZvjw|x=0FU9pFV=H5ZvH z!s44)?6Og8*7P&^q=XRC=!QVf#81Y%Q@R>S?*N2Jwt-2WHG)@$#v}ec%s4chJkf%m znN^z{F++1jCE=lmkKxp9rh<|NFitwpdha*$-hbxpS6QqpisBNL5Z0F@WsKg< z|JYx^MGdyAnEfm85xye(j95X_8IOWU_BXfH46P`^h*#!!^OUI%WHu zYkd6GLD2K-XqvZ3gyJC$TIOj@QfdOTWkX#|^Jn0ejgS%EoTQ61IlIEGrx>W)`iqi?A$(^wJoyI9R4+Mp+B-M6?a6j8{ zoQrAjb02LQ@DWui-c!;EOhAEY4zoG&U?vQpV3MQgnWOwMN3}kO3QbB?o}+-qWHWtS3pe<<NgZgcP-e?lkVI z)$9FkxG~Ux6Uic4!TihN`~b21)j%Q8#;cB?_iAGPFKuSdIB zO1n@*+fGBr1N$}~T%1ce34ne^HQ$=IQ^iA7E#}oO@uyvys#D*zEq{lRaFYy(0ljiH z<4);RIBgYVY10@i*Lu(;)!43M)@3uua08>r0{}sInrw7Jia^7iWr}SS&BQX<8>8lD zjVabC-7#uiOJ}J8#Rzn07YPAHrD4=z;gtd%C0)#*Kp%phTmM#a^K<(FJ2N`g<(iuS0F$8#;UA11OjK&6qt`|p%g`j_ z$s$lR9bX13=Lg{zgSrs|b!6e=Z6tdaPlqCRZ6zh8tf;dKCpP8!K>H*!4QRI zogpB{ozbL>8SNl=A^j{o1XD&d*g+$iJ!$|<|Xa&O?Z)5aJv9Nn%SzP-lOG!u#=%a#!&Z1d^KUO ze`v0|x$|{waO^4jB;ODN96?+KAkxgPUPQa->Is3-BecvAb`m`H@$ z8H5apaC*?A899wEZZvM1w(a{$9XaJ;K9oN+1{GSb zJo5=fhuJ3c8Hm#i1rni$*6EmmM%2X$&=9;w^?iu0RWEY~4acfSq^j5c}fV{lzVfg|FU={EMi?BbLujR2yS{$UZNWh_hzc8+aQ07p;9w9hE~Qj77H8@ zmzPV%W@bU=D}4^1nKcK<_AR1Imd{I;&L7R7nn61c=RXSdWZzqknpqV{!>~%Nu?w$r z`Ychr0zlg!5DCfrgSi{~3+W}((topLrO*Vm)<^p*#+vK5E!Qy10H|Ul%h(Ad`1$m0 zt)AwF)PD85p$&&u8`iJBH5vjcnuspSO_$>Nmx~z&&1~*$SrZ5xe)DpQAa-Vl3vb^(~7-WMrhoL7I*O0lh5Bx9X(HM+5KlP{e>Cp4jO}uAYH|^7EhlLH zK(ri5HUh+H5O8KIz0aW#&3+Zf&zIsqwcv+>#Qkb`msKhmLrJni$7Tl$BnBXQzu+D`+~`oKlSaZ!HqD8u{Lqx4_CHNR}7Pn{iq5aDx;^cm2~ zVrbHdTbY^tt&LY@v5L|2U*X4QOTVfgkf@lSfVf&Zuo`-t$2iV?|AVMNt-0XnpMMq) z_#Epx)DR?C+n0NLE&coglLs*JI0XCTO$cWV35?Ms{d{{=(k%MXsR~&;N#1eD_xPC zN@-raM}>LcyQO~r7IMy*C{p8`cL`*dV5NXSCr9wwJ5mMYJ(Ax!ZvaB-*2(0<`k}Zd zo>kBC>;_~+hZZyAtod=h*xWP+aOeQ<##O6wS@P&-nm0GSc82cmR{q{;?+{hrEhHN2 z*C_mRw>A^$d)M%l^dfKg%Wl=j20i4nGQI}A^Ck2Vl4e5ZQwZ-<{+>+Etr?yWVIQ1g z2IuP0I#lV0tb8VvGpABjpp4#DHJA5GdHeUrR)vjeoosaK)1^<_qQrSoFXDaV#K#A| z4BH(E(|i$GV?3dl%}#>=hgrjXe`!gv4+;C?G8uQzobuyrA)eP6`58JZb=7Wl9dirC zuKrLH7a2Spr+&nKS0A8gZHHf{lFQ<>dL1%8@eW@U{$2~fk7qo>({A}Yqe7QSwM)-` z27A(5W`K=cX_b>6k|=kkszmpHF|jLadaaiwkvgtUuTl~=nA*ucWx5DVw?&EZpp@f% z6fCLD7&fd&iL)sgxuj<4484Jl_n3P_9gauISy>@09VuRaExWayf9dQZIHG^epNiWn5GOG(5w}r8BVVp3_;HX@N897B8 zv)Rr1R_4dez_kS1n^CgKn)Qe^MhgN20G@{O3q#|4s~0`jqFW%6yIOXn7=Qv}N$`>RS(gEk7l91(jHz7RZ zGVmsC2gDcTwwm-f1waPa__Sd&lzKB+u#n{=5TKR9tQ_Rq4rI{TBHxR0jjQmrc>Tmd z7QXm`cQ3!4Ot~(#U*B!b0{p4C1_T%R6+$N)UK=cm`XNB1SBIg;VqLT!@nNpL0ARD+ zb3F(jXy%^%RBbzeHjVx|;po$W7bke-y!(`H!ll>krvC!0EW4fIFBy$GdA{P#WZ_bM?rgYineK?2Pak{9K`2w zTX*@pKCzJ-+1YFib-klJx_qwlPd*%PJ(3@O6j5FGL^>$8TTb=$V@ayiYs})Rx{HtE z#c)=|H@^4Xt^OhOve5q-1u+UWjdJmhH}C($s7jMC_Mzp^Api4s{Zl1ldT)7VOrb#5 zP4}0A9m=gju>~>aVFZoD)=ryyYEx>k6336cDLDeh=U3UMW#OLrF=V#l%r9B!xW7`( z-K`SW@@!W~LvelU>-11}<9#C_^jZFj$;2$$G&#EhnJ@m&3r$W^ zt@2ODInt?lT29qt3C$B(kcT&QzPXW+6!W-MPw?vswU3v<81fB&eKN?~)<|@%%tv14 zYRdo}41x**XOs|<){puD+P|KeblI9QzznM~?@QdM^3)=Z?=O1V$F>bFt23*z+aW)~POFb-Kg088U+nUOZ)#G>N3h0% z_+%w@M=vJpXGDeW2F{sag6`Iv{|W_}C4l|30~E^qUh%kyEi61ftv?X5c75~PXzg`P zgWKi4UOb|vjyiyg7D|&cR@5*5POJIw5hfQt$bE6eu<2yz0P9kT6UU2Qb6`>v(ZoI> zebQONVT$p4lp?eoX5aAZkyDs~-5TW>lQ-)G|_%skhjmLW>mB=a0Wys5+S!>|*+rReol0 zFHkM|*VTsCE4M$qnpBya@BS8^^Af)JQcwEc&Vs;ZLX(y2K@wTyw|LQ~Ec+OxJ7PvS zy?hWyB^LMWeBKfkTsJ17BXd>XCFUnLSDE1Ce)^KhH`x#MCQ)YcEI~2>8q?V@K#WXm za5>OMP<~9>;&vimm|apUHJlO!1#{n_5bH@Ae)D)GSd!OT@BW-HrE1mTqILcoq)XZ<(3icSZ{`;Eh3km2>j|b7b|M79jYg3wBf;bZ6oCRvye56!A z9G!NYo}F<`(A@((uMh^OO8sugSU*zH{Oc3>C8WMf;VzU3#Hc;Lz^EkoT7j8_%N<9z z^@6nbk>+cEg%rE67xIh0n%$aD7Y=;My_U(O-P;)#4}+DwRvB8{yYDX^MHAj~Ory!~ zow3tiZwIa4ZSfeEx1dEwD>i^qUB?8J(i&yDntoDay+5!$HygJ&H-|o)PemVkQdkLbtStu#z->yxJ}mxz z5Sw@Fv53P%XbyCGzoy=;#Ln?Efjeo@x#5B~;zd6*-^mA9s!vF$Uxp=(i44f*EQn^g z`Sb5)&;+H@Dp;fz$F~gj5d#_h4!V6vYJ(0kebe$lx8-D~I=nakNdvWEK~l?wDA!tr zZ=zI0fm8sB#7#SZlrXqb;Z{0EWSA5SU>GfxZxgP> zx1-F;LJqMm?g4`H?GjYHpyF&gN-;IM4(LutJhBq;Ac!`io!eQyLlvsU1$J#N#2;0;$#3_{Aa%(Wjt(;o(euPXZfu2w#&$>Td=Jo^|1XmZP&9D zMO*t0`IJytK6@fR^p6O{2-bCF@V4~l3TylBH(vSAy?E3*J54&fe$6QaBytL(uzrbt zNnAOY#_s#s?XMMjeB&Rv42Hf~SCa4SR(DoPS`J~l8A6|bon(!|Xx>y#rVXrW#m6e~h<@Ik{<1Fvr zK0)Hw3s~asK;5B5#{<-6Du!PMdLm$re>zOPl;A1qAvZd3G95n1AUc)7W;6Bo>WZWO zgJXiQzT!dt;=Z6{6&&`u@s*GYrq0|mwKzayPQ7~6th!!QBSK+_kZYy7ynE+!JoL=7q)h}$WQ=@xAqg1qKQE+G}MR`Dd$lt6#SVpbNO6|_BN+r**=aJHPo)LJMrjTlX z^q^*cvF1)Ew2ci)35`Y@b!-$5g=-Ifi!VJA9Qn%w-8R#bY8eA1~&X#h3i#^IPKt;$Qtt+m5@M<9DWnGZ%_E`1c#BP;q^ z)Gng|s9{{9>ITm!ErSmEry;se1M~(uSgTP+hfyYLEh;kX9vBGrVm$bwbx1!}?Wvg% zkLRrFKsISJ3F!(BJqpEY0XGKEi$++#jy&S0injQuPiY!-5QC z0XKdKrgPHB<#E{hV~^CStl}vu_6a}gsb4ASf*35JUOWilFlFze77^Kdne#Q^vOlnE zs&QgKSLku5HZHG-)vCAW-StV_#x%#T>1g(^T3KB|krU=shJUsd_**&Of1M(^oMG9S zPBfTKV!!#W$;gj-LUxbjO(APEg~{u#@shA9y*nmZ-uGi7O;Uzt1{#fV(EImsvn3m| zF`s4?yJmeSW?wVR6p)!zGK7?&)UC>OsvS%}SXVyNm}6*~Eh!}0K{I7!^L!d{CK5sK z1Ls=Vr^X9s{kO30J9AC!U#i$=61wIZn&$nrv6A^*&&sDe+0BA4^#icv1_*!hmnwbN zh5B9QY|Kr9y^R1QxQ!d4WoqWMH+w%N^g#w0;VnK$1(QLhV*b@!aMId%P{U+E!y@3! zKZzOQ8fh-${rHB1S%5oEIWg#MIoZQAx~g!q)xg_pL-RFNrawx|{L8U<3=mp(^J#0N zqxDdw400c_VD%RqYfKi0kpf5N7VGSf34sOyl+ot{eJ6L9zXv`^!IG%d2DxJbZvz3g z=!AFLG$$CEvlyBS1oU?+%_T9P6a#k14|XaK;JX~wrwHk!*a5>ArK{_CS-Z=JNH;75-f8;ENdSvFdfTr9*d-f>a_;lJtMg_ z-FE%uJ8Fr3hM=yi@MSNdCsRXJ^oTivWk$N^pe6fNGk>N9e+;?)8L59QR;@KevX9P( zHbm+?PR1!*mOuVlZ7??qszj15eDc)#(t^utWy`=!DN2}>DS$-+B8QHsY+nI2FBrcM z{oMsKonbUzVdyx2k7iDgjt#Jn33zoFr2hhE<8gJkB5`UwQQ`0EBTeZI>SrRa%wyz8 zT~eial;2PHuiu+o50*3vz>_PpK^gJn@vV&B=SenyKVX>?{br=}GlFf1k2FVt!J$mJ z#KbTzXu}SRX_^8`Q$J^KNwGPK4H}pv5+o~wz4Y_9Fk2HT9ln1L>Vvky#o#;=8PblJ zePACmX+yHaKjs*-5R=2cNKyiB%g+~SRYd!|mh-hHvW_jl@uJBtp~@}*B9`X zDTMMY7&^g*i?I&qeG=t*!=+jeuy}5+2%|-TW6P6i=>d^KQeN-x&xXwvB0^tnL3{x6 zs{J5)e4zbj=n5Cdnk>hLCC4U?1DBY#E$;98;t?=S8nT~uKpUbgYgL#aTePSj`BkZ; zdAp<+kk9ARpcpl8yfgoB$6NE8|6!ovA`GyFkg!OCnD&A(oW@qe%thS|Zz@_z4+c$wMDzi<-o< zfS${M%Wnsl_Z~)n+g~M1wdRFBzb6uNZ|79V@pv*6z<@f|2W4;M$GL0Vu6F#XiH<)c z3qA^jpB};qjtuZazBMXeUMP1=!jU58na$DFp2JiuDO#9V64Z(`0zQaqQu;b2?%S&; zZPWG$lO+WjBVC5H;x0rUy@ZLF{vx`6^z~?+Bjif$ z{t3dV_RNWZBgb@ zhPN1@W*D&FivUxo(;b4;aBV=(UM@om2IA(VdMkAC#8w9}U1$%Y0BF@IoP{^-Ie0@{ z#7O;6q%KCzinksP*J6KHktk2giU-?ErvEISto*efe15I7xHn&{byLXk`TG8mUq~oEFKZFzFTenbU@9HN9!~N|I3FdP$N3zP06n~ zN2_3RK-itk&K+XFM7lzTiM+)>oEW5(LE^T|aq9-TkMH?AX-|=_q4by!C&Dm?h!*>) z6Z7{Ty+iJ42SUTsptty7ST5KMRXjgE*H1wM56i)7 zc>nfLw_?ZYu@Iavh7E zUtojWTZ3A=-J61I<`g~Oab5;$0rH4qX2#R-+9QP1l#{Rb^oKukgL)~oWM+T^fw7g$ zwD&DO-7GmVFj?%!N_t>9-zA&DtSTe4bLp4P@|%dn^!v-$>5=L6bmw4cSHEde_bu-w z={wolWTf^#j||DyIRE@)c>5|kWL(SpKGH7EnkqlrM>E}fHv0VOEth@f5R_5y{^{RC zvJhV`06|1ck?jE#j8}4w4j>&NSNJ%*@ZU(fB3NimI%|)zyQ7dws`Pat3ZIZF zc;Kp}E|BQ_avVLBEb(UBxi2nDo<+jg0CWcpFxeJ)-dg`=w4XpC*y^TTg}J_d{l+w3PL`= zw!dc^v^yH+$METu+Mg2}{JKqYJGbRE<2+~**3L^twASWwSHYvY-!RUDC`I0}v zlhINR#+3CArHuOO&;HsTJL&BcsbmpiyK$PVHdRo&>H;Fw&IlLj7rPeumtkud0ij-j z`_o;VW&6{9iqVzMG-{oIyqRtTXF3seb0^Om3wI+-CaAX4;V~a1_B!0%-3zMsk(4uXf=M&+<3;j{wXU` z;^Ib5xGJQT=Vu}*6q(z3r|+X|MI$Y;FafgRT|CrY{0|F^}^@YW1 zL+*+5HH|DP7_OTPph8^Bj%9f(SlOvb0dNi!e;&T=Wp(#s{#O$LE;;^~taq_G8i-(a z6^xaD<9dRCKnil@V+{Fh;*nYztPW2peF2bQZ>Bld*;ig({4RUl_4-js9vSO{87*Zh zz0Fiz70Vt5NJRMlV?Vg!09M;ItHq8-% z>gG}0>K3`AiYwF?oYo1Z@csJWeU}cy&_t+GK)EOx^p~s#8AngJwzw%Ea~qIp^?yBJ z{`S&E|CSxYogw-jmMuKv$n#9q>=4v@FlM?UKu+n@>U7~HYh;By;p~!zmwXf*brtMg zjF%LDx)&&6=6@-+9;?Q4@@2u?^xmw^)b=QB?&Mjor`{t=rK=PZC2o4|2LTdeUW9DX zaq^8LEvYI(hn5r-k29s;!5<7DSRp1Xe$*we>5+F^pyh#&_eObnszC`lm|Y;g%X9Ig zBRofOhvgVYw<39@E}(g1o!9}Hpc}Zm0TyXIIvSus5wexq?9T`FY@^?A-*XXtB;uUQ zRd@qQ=^8>Rf3ZooYaRWT`6x{eo)>e)i1cdBbO2TS`^s~ta{m}V9b~>Nji)*Y@!k&c z^Z0}K0TuW2RxGta0-9V*8HuB63?*f(l|HI1)uxSI&W_n^2wdco7lU0D%HlB|E9)G|iK zc`bBk&a%5(S@D4;8EMHm8%Z%KT~fS4G!N{WGNO()a)IZ{$a2peBrS-!WHd6NaovhS zA$pbG3VK|gO_A;1({F_~?PUT#KFs%wzfxjT`WWOY2}CJ zK~-F#4$R-kk0m3Xn9#3o@5@0lxyUKp=JWFtnhbgmkAF&Wo%DaOb{Aezy=~v{H#5XA z1I*A3Lr4kIT{Dz)C?F~w5&{AO(hdx%bV)aYfOJVHB_$~xN=XU`3ewEW^}Fu-UQfNx z^So=l`(N0z&Ncgc9>@2C&cxs`oMV;*yLm_6Q>nwx`olau+~M*}qK0R%VvC#^xHXC` z6%fMsFN>0^hWF&KuGp*5%~9TbrZXM-5J>gi+)9VLJT!MxwKp9Pi_~AG|0P8v@Jc@( znx({i5KlnDuGDDoiXz7z-R0{Y-p~2NPVnN$Ua|0lWO^f6+`^)|z_WL+Q9dXv$rZ0Y zM_p&k4<&@oY>2?ealDW$5Yv+z;4qc#-lg3{_OBr*aKRRx8fqX>Pt2p;sX38h{+wNM z3W8J2!i$O@iF|_&ylo1rum2Ff3?|R(hh4J~0?8dL{>Vu3Ydpg6=*gnliXEf3%Uw+a z5qx{TdI9D#(^ERBwRTfnuUr#*89q=~=GZv|?-a+4C;nwjmqMw89>D*kuds6Q^h;*> zAfQ9X5FA|>*rR;m+waDvk5>Y2{;z{2ERoH<@^?IZWfxbunm&wB-*L~q{cUNrg0+w? z*!7L9*^gR7GNfCjchhb2WZP71HO;-7MEak;*v! zRq~|f9xjE$Nb(gW`MlX4pEOdINBnE_6V1I6ABAJZDx!sXqq!!&OewF^3N=8v5Oqu1}-h>yVUt{iF7U-HD2bU+8ySxE0F(DNX zjFB$RCCIFPLZD43Hk4$UYR$ycVvZQY4)LDg*{!$A*GWOU-HxYxt(ln0`2{z)@1FkP z+flihwW8*=^o*oNu;Miuo=rc$*v~h{u)`K(Sj5h7WC8{l#)U((3Ycvo@j9>snEL^R zB<7ZcqHoWg^*FqZ7tPg6mC5HG7#RaD8xxI>U5p%CTe#VntcU}5T;E2re>+9~?!O=? zWOcKqsax*pf{R#v$|eSw%}A5C;QmT7jL16;4Cy&_Gr5z!E&rhZ zp=gN8t;*o2T5A1@`$6%PoNL}E!&TF9DPGxBH0gSJGe+#LdlNd|V2^5Lc-HlHjOb;s z9G3>urb(Y!s_ZT+F?Q)Pho3I0lX@sEIO)VMrFKGo-s_E~mvW7F;|Y#a&p+dm{l37% zXOc`iFIWe-ypA+J!i^4CeU+AVo>h1Za!?;Nzu|Bl*Nw<+xBhFmt4U$0lfApVRhf9v zH$<_r(F=P!LNl|1v{9@9noA>x=|*+^V4YgRW$mL>l5_c@i% z#1O1;a5iYZ=QL%BWYu!RafL=^<^68n{V^l6Zz;bCR#bp|`ozbBB$!(rV8w%OIV6Nq zfertwm7Xn1lj;#|q6%Qjw85KA`#X-*JdUh#NiCAbF(%b9p9T}1y=;bA60&9}Bmbm= zqQs!}vh|U_5wyLA_c=Rwh6qM|*fr?BFyfwo$ zz_4F%dA!=;Hoqp#A|28bhE(q6L)8Hd7m5Tz`B?*h9 z%!`c*>{KEDEy6&%vTq;vua=9rHS`~1*Z>+1A{@B#FQ}HnpkFxhsu)kN9tGmnU zb-v`KYprkze(cU|aLozi6gx0*Ifke}v-)^0*$!0k70}Z!EA5|aa@ncfB+~Z8BPH}? zm?Z>W(0pW&@#hz6Z(q(2-8DgJLb@Nfa4DB2YWbFiOc$$!=YAXBP(kFAv*%N2Iv^S` zOOVAdnHy)lC!FO;L|KU%osDobdlVlolqN7GPKn!x;R#j*pRt9FX)xb1X#MWFO{_v+ zY#Hoj8S;&{qmn+Oh&G--S172bN87D5vB1%vCS2!9=q>942EQlB%WgSS-qa^NMn?`I z*IQ{K_!K{)*??`Oegsq2R?b_;#7ak#`t9Wv-s`z8MK^5rPHCZLSWW>??wu`_>S8bQ zE$cfyM{WjI>^u2yQ8{N27w@ zadN(8?=AE2*WC%w=hR;QAyA=;TNzLN+gE%&O|!uiV`Wq3dtWlBhn)!e)Jc{2K{ALQ zq9QPtN(TX^OZP!9&ZeyYF; z0*>~U2rKu(f&E0gm1`_#*Dt&NsxI*=Uym#T^%YDkAE06<3;k6=R!wqW;K-cdG!lN6 zrUw!07PQ1+&~hN@Eo*QGc9$ji)Feb!3Js$Z_)38<%D>mk=Q{hLOL3POY7-9q!!+>7 zxSXCtxc>3GJDa4GZVa2%bNdIz0on*XWdvYKvK31{*3HX=rmRW-a%(|_~Msor1FM%*JkK? zv^5Hsv5Q=3fcAdW(*CM7_$xwIcl!^jQpl2=d2oy`uvQS~u|{(cB>m?Px?8b1MC@m+ zv>r~CbE!%yZX3;lJ?yn9^&W5c6OpobjuzYAF{t}+MoM2PY8N1UI4-F8=h?Snj49%I zi#BEvslTx!Dsua1L*kEq5JsOu>?I%;_vp{Mv1cMhMV78k{mTW&W;b zh^V7lM~&=OW#(ZLBemqX#qTw_X}@`{ZhphNQX1MP>h|%$-Z=A+qco#IGdpT5%@Nc- zWk#E#s+-5EUydH((&R6d_1-o-Qa>)ZcWlmmWCd!Vf1u4aWJmY1?5agv`efE(6!(Dg zbQp$^u%+`BW0#Q7JNo+rW9lGoQUQoJG|=7k_SiYN_sd%J5-jEBZEw-|E!bP+r*S@!~3**-Ho>N-i4QJ#JBrLTrPJTZtjI#A0KHgM7Ki4P2`4{-GI%o29sZ+ znJtGz@+Xg(2Nk!hpC^UczqInaU;ARgoD@Ia@ww`k)y`M7r4A8|u0MZ1Em@J7J@Tb( z^ck&k(vtA`f#x9upJsnP#r}MHTw!gh(FUI_W1xIg9=dD|``-J;YL;+D4-Q>7$3$lf2i9D&KKZv70AD zwatY^F9h?0!$waHksqE_NNP7V8Plx^xrshxa&!Sc1X4=-zphuj`zpyIQRY(FK}gyp z^i1}}iKi9;MH#RDlfu8S7v9vP%Mg8l-+v*P*tn~;?PryPq zn0%4g_T*EWIcay8ZxL%#&c!m&)2%4gotx_$!zxz9*kl1Tu=2EwQy&*TJH4+dQySM` zN7PagRvhRmlSjl|R=#GN1q8rXwZdWV0%an~&#UhHl@nQk54sg6Ln=mFUXb}&pBx#} z*$5e8NEx0}Yp=fp`Cj&nMhAa2kIs#HKDa$q`0=#;`?I!c(NMwUk6VgMfLpiX zB6dIR+NfE6qE+nYAtx_!zf%Cz<%J{+g~k$* za~U?rTPa7t+0>Gy60B8U(+WRvrdzdu#IQPEwjL(fb`rU;By;+T6l+Fd&&j`F;)}Jy zZtu*_9ag^`j+PI6gwIgFs$W16qeh~!=5W6Rkn#(VNx?Z8g@3uue`=ZX^g)$H=bdN< z8dQIREh!g4`Sf;_^%dbQ+s7VVjI#GY2P#p2mlrF8aQo{w-Ira(SaMpX%rs#e6o^PH zRW99Q=CkE6`yErSIvwS!P`3EnQl%I^?`nR`Y&zf1l1hstHCXHN%Aked()5*QTnBw? zFcIw?;ij1(tm92Pk8od2(0!^q5otXmOjP8>M8mGnWnawMCM~dB*Pr_Qp~;2}dFBLO zEUbTE*<3KYbrn@`p76*)kxe&S{S#QQqk)jKy7&z0sV;Zo91_<_1a}I~efeD)(FGGO z8tg3lktxvG!5;v96%>!Q{sb2;`&rpmt(BfJB&|o)HS91u0oYYE0>&i<|j|>A9nQXoe5qguy}pN%QTOq=2#}?U(~_p zk(2kdR-83;!Q%HP+3`cS`{KiGkDisNY*$R&-!rxopQ5Fv{_{0dBs+y)5Wlu(+N`f4 zrBvsWk|(o+@zmO`+e2rXY971m{$?h?Hm)%#{@;>6{k_g$DzU ziR$s)vA0@|=D91+3>hsld9D2(RJ_mWhX=RJmF>4v7Cz>9U#=SaBUHub3u%GkBLF5_ z!GqlEnN=8f2_mAEnNEWJ&HNRPB;U#ykc69Y3=4zW8U|$vv-3xll;sM6qH1s~v8I~5 zS2MX`pjys)V~XcETtpS=d_?%&r!vR__lR>b$$1Cg=3IKwE84HRkc`?pV)3ti!%VyP zcVSv7-(^N}2l}!&y-#I_Yv$%|zgQJ_>MTu|7&)jtcC2hq*GAj@H&Q4*y4O5=o`6v2 zU@uf4NQ`)#=AMiD{vw$Q1(&(jG^jhM{e)9RV6w{8e?3v{XlY-*i!+%38O&0V6CUs* zJoEK79w=TIahe;Q&;D)hLo@q90%8VD!T0GBIJCD|1t6>BfwfAJX|7sQOf)+=wC&t9 z0#F7HbYPa$XEMKoFbcet;^b2i1;`K9yQo$A*Z3-Ha`6$5FV#sJOcIzc`5jDt?}znzTi#gbT3g53LHIQ(>VW&#g(>*~)^*9k;e5+vo1G$O(9Jfwugvk1PZ zf}=`9a_X^8GEJYytWU!S-9;FDzfu=VUOGj zQ%S4}T4WwlNc9@9^Oc1Fy6M_?yxnyNpRNNIQEKLp9%|yYbxDrZCUcM_@FQLYt%-`$ zq<@|?mHbu>%B^asQxyL0;bR)*vk}Xc=YEuDHbq@hm1OY=@MSRvsXFNdchCx}sZhTl zDgglv#T5KAju&qbdVgWld{6}TuDZTZtJWy!u z$1?Y`_Ql@HtZ(Zn@8Is|kr@?n-r6yc4=$OB)F-iA6+~^NhSArEU>pgf5i{ z34=f1rU)SxfvS+Z2>pCGo?+ZjneyJn>*wPYh6f);QYu|$!AAkjZuaK-L!b38_q zPO{YMF!5b0@=TLPzJhn({B|le0n*^HuCf$6h%u~os*>hMIYqGpg#VR65xdd5!YfC| zs6iR%0aXKw86Izn<$OV{VWaX*U(J2L$BPAqO|7J51}_FDpUQ~mLrJg-_`jh?4^ux7 zcJc#sJ7XcJ$+*2NE^e(5QQwU*wxQZ?(Uk7dAnP|7Go;II%#Rn>X`F-h<11aWvPGJJ>{xK7RGnr9`G}+_+Me! z8+dozR#+33Lr4K3V(*F-;(FvpkP*F9B4?hNJH3#yrG12yTLo`IlIbg>Hp`b1G+jre zX3rjN48tU69Bt`-DjK6lw3D$cZO9O=Gc9vodwe~r?n33#`w`U0q|S2f1G(0U_?I$# zUCz*MY5YW}3K@O3g2JHi@$q^<5GRn&FqJ~TDk^)B7v+&t7mK&2OC(q^q*8|B@1G@* zsQWNBTf47tC1)P3&8FAiRi~scL?o-S;+c?I?@PeEb?bMtqiawG{ckpeE575nvg;9g z+0^E6zv3qUYxz@5zN+1K?2BC|5HEVK;c&lv7u<^E;CR%&^?;Fc8q!;%tmYXlfBXwc zphmhU^X;htj=`)`ZLXS{24Cb}cjUkmv1aDKTdomjY=xM6e-RXGQl`Rv3+9rozE|jb zqom)~_d zLT(`^{!ey3Hdk>|yb6j|!V-;(<}ybAPWmFZVZPY(OWpN0J?b~>-$+b&*69ON>qPfD~HIn4flQv+y`DA`H8Ya1ZuS=tTOZQ*098UMQbWKK>>~#@&`fF%Dr`5Z3S=tJ`kHH{E5dp-47oG&OXU+PM>%fk(|0zu&7$ zvX4eWxqW>GlD-ZV-#3w1w6p^07-+#3|$3(#iL|j z2BB6MUiBeUJ1LjI@NNJBB$H8`3goH!E!PT}5dJU}qB6UFDRoEBGU z@)FePT-e5d!SFSTLU?I@YHu~tbeU126Pabnc!XxH#_K_Zz<2VAp&7EoX?LKuk+7Tc^8ABKl0t%aA%wUgH0UfA^gA9mdU}#*kH-e02VmT21EmfU9I~V@Tvg|+acXm0s%OYPoaa@^DA*q zJ~e|7e#Q!|&@z%Gn2DkkZ#kcO0AOLlW5bLg(}E#_<($JDgaMuHLk^r89yFOZee}Y& ztoRL0qdB=O-K$Y>o*EY(vg7k{y7UceqpT ziVzM8+`L|jXn>Ngn&X8Xz!RKTPw{8jfC9H~p)mGUq3dSkm=pyZOp0)2lZxF=I;O+6 zMDO;Gtlr3%%+vX_x(?K_yR;oUh$*iZc%nkD|A5vJLH2s)uY5RqL0w+2N9-6=rK%m#me8jNs!B=)cYf3d>(6&4#&|@ za=VWDfD%Ci{*}-~w_Seym+;!#*H7DXU*OO$7bg9Hb2t2HbUnK~I9^KWe7dR8s zTN}}f!YAo>pr1_EhaKxJImrc+I=(Z#ultEg`*S0bIdIUOiKowD!6HS?!T)xBiCi0f`nvWFkv`ABX0r9ty` zorMJ&GX_d}xr z(0BH2E_RD@z?y^R;ca8PffPN#RGnl`8@tpq8HsNQam%^}lMXd8o-SJh2|M0KyXSv( zuBJ>AsGf*=KS^n1ucjtnN~UUyWA{XI7cJWd(^$GsJ4Q(uj6St|^Y`glfn&q51>AZi z-fEuH+UfXsG{oDwCe_^Ruc>h3lg=Bol#$c%&Eb<3342BCI#&o$5Et~(@kDs4bHlV- z-?T&fv@87#Uyt|GIvPNs{(z;6D2VW0r?#~uLhr^s6^*6HSz#Utra7lH+ir9>IALd@ zbvLLT^gdz(p;S_k_v|C>WSiVxr#>a{X7fPb)M~?=R~VICUGF#f&~JHat=jCB#x3qm zGlc+U{bY&DpPgSkPx10)t0%BnX6@OE6!{)4o%Weg$m=z?lLizvToV}BDm;X^OF zPc?5vLO8+r^G!6KwB#ox-zJlcvS@qC5I|((4i)nCW^+Wt>8pek$Jkv~{7!$cbP{z} z)Grf)%ol7l$iO6wH?dUc=i>xsX;X`7ZENGCyNOA9zJr4^E2*D5@S6h-KE!jJt#Cbb zO_+{0n{&1DwJWK3NgYD)m5dBmP4osvm-zf)qS4%&hjU@rbhU_w4zyJly|qXXlGtMv zT5;3c&G_@vf&*7g$&^qF5ChCe*XlAYt4c$nRnmYq(& za{d>oZ|S~;AyR+%CO7>}rgVyqZ;F3d#udF3UPi3_9bjJ74}>8S(@D=Y$vvUJaYSPA z!oxTi(zyMe+@4P#c&ZX@#l>lvQ;v*{noEA#@?e3!=;CNWU#3{nyO`N8gTa^pQAHMD z>1H$ccJE=yGnwF}uSHQsDS>{s|Io%HWxPgU4w8}F-!0RJeTy_&-esScO~A_{RLV*i z9S<&P;l~X>Gb&%m7LCs}ShPmn%20UkS62=qSe_@_?~oq*Q~$6f zpG~&r;bZq;+2#ws=B3(ZuM1u-0kzRemh zvBP;6Ls|)T%9d=Jl5MAc{OO{#W$2OmSWEl*&vva3d^8Wr zDf5MN7cbN2EB}_W^v{p8+%2-=N|k!|Fum{pa_&;++%j#Q4v|Q@|QLU+nR3>naTBD!J?`H|-Y>*pgagt8eQ)QHDcCBL?J#d;_w^TV-S~hF;1H z6F(f(C>VZkd6y)}S)Hpk+4iD8rgP|&x%7A4xmW## z+3YM?^VC;UlJX5FjH8a(3-6~E=KfB02YwM$Y73T%{3Q3yUv{DDs%d!fn@iyPTkbQ0 z1s9qt-!-UKZW*o6eqS8@HqRzgHo>$Ehkh4O|E?IYDBNX!hFPH&Te&?of04b!ab3Zk zv)VbZO8kHgqQG(PeedvUjNI%;)8nF-mrDlM-!#lxr&`xV+3_Io4Yc`4IrA*mtWL|k zLr-DTMPvQxoAphzHI0Hne$}T z(aV`%Gb{%e=D%?tBO1RQSUi+s?quBRq}Sznwi1451S*yQHam>dNFPZIxz-=>J#^W5LiBvY-tzKNP-*<@NTb z>pk4{p(1YE0-w-oYD(b;9thJBj1OawiyT|NSMSMa#137JvVFlr2)jEZ->(Vg_cH%mW(9xn++!4^p1AujzI50f{*$?vB5KB z0-@q%lkW`kD+8+bSjw09eo(={fY1h7gD@tRw#*4Hv6=Gz( z9Oa+yM+TD0N(ig?87_Q`k!{-l*5-e4{hw&*$$N)_Y6;=`gOirncX@pfLL5t^ zWeD_6za^F<`Pk43w0~>LLyUsl)SE#;ZlIE05-`>; zLk{U7mH@R|e?blBb=hhe>S{U`rK_@Ks5=3511MeR!Z?N5 zS>)KAc<5x0;$6Tpjuk9z9gDuprb^K;XCCd|%fQ{}V!c+Nb*G;_F5u3<&RfRuwv>NO ze}c9j6^l0Odj^YE1mLOhPniOkPVlWZw{G}dQ+@kfjTZN>nu5bes?5KRYRcKPTz(JS ze-quH%6C7tPw_0^3a)r21auG$9e7lsUZp+9pvZeBh=4w>R_D4=DAoI(YokTar664P z(S(d@w)oA4NUVtMAy;FwZj5YD^J;=({jn{pRPYDN(fV3j$T03Q1P>h-FN#5tcC5MO zQ@IrI0MTSUL!A&}GM~N1C0*993FNL`Q;`v?~-4pRLZ~-?oJ;Q~IN4(?p#R&1$Z_)`5%fV$v_{^s%4U^88sMC=uaq z*aPTH$bNt6y76bvfcv9wX~p=6p?iI5dr(REAvbbK>bslv~G9Dk7ZxmN~2`?suCx%V#9hUr6fz!^J*Jg$Ow<>=b^uM%Ol#FZj+~94kQwP z&vcbTPpX8fODG|0_eU{JdZOBQ;l$($PEJKBjm%SFuJQn4!~_Jb@8^+PZy3$5$3DpV zwl<=Of1NJVVer2BS7fN%D%aDfA=^8fsmK94X6$yqg>FrB2h#@9inqsx?|J58eX#`f znzqK@dnv6yZi(IX)isNq$YSK>+E1Gs_8I&WoKS<-cfgDW>^#rC+$~YW4U97KtP%nO zH&ePTdchP_`6Mn5D59OQND0GyiuYS+UZ?Tszc|W5hCK%b=^cZZkmP)eQ=(2|laRzy z`(l2VcUl(EiL^n_w_@+#={$Qik+tJlBDeQW?{9-C2|CkUCY}`M z*r}L-xEIH_4)NXFGQZe)5QZmF_>#Fo74~#Cl3k*P%#7cLe8(hoei;_{Xa&zfA5_q2 zsGG4@p)37!ZtN>neSv_0w#L)>$$g#TvTu&W4r3An9hA4~2|T>9@~Hh&X4ZX!(G>pi1cw&@G`x#0nC`!lmW?-!aY z$NN6ThUR?5O~{|O)cwEtn`gG2gwbRU1rT^FUDO(UN`EDod^&xRwJ zy0>o0G63;6Q96;ww)V3OWJnsJ{D}LjU!nGLF&bVOGmASK4;X-&X|WQ5#OyuKyECh7 zdR3zpPL_8c&EE96-60V`FwQEmY#ylC;R)^B%Y7vL(cG)rLI?5G#vfJ%>65F>cW_IZ zpKMmf@{ItY;%VKKaVyI56yx~%?Uo`R5Gs_7mam_AT1xXiBDZ_AOlpK#A+m>b+43cj zi7#5hfBE3sj#U%OTQUMk4tE*r^I^0NF-z=?am;x0Z$%v1d%_9Ym;4LvvP4->*^SBV>m?&?Z~}BO~gx zP;t%TT${7P+cq8wV0W=jMupMpKly@z?2ATPn1O$@7~CSgD2*jN|2Ykm^p~^oW2jDV=~k zlCwm}{(+a-X_yrR@RvdaK_WwZc(N!UGf1*(H}>Zoh`}y?S@(#9(g->pM5;Otar58Z z4$R-B#DCM8m~SE(LlosJ6;(PL@e%^ixskd6z-%hJQS`H^hFHQIeG3{}6HX0~emx0PP$zEHm+|tkKK6+_<3Yd=NUO&{C?2=*XhtIR7C%ahL?q3WQ-G0VGWP7end*5Vm1R zBUVKrg+jcJakuFcC?6)!rr#{aM&Kxf!1sk}!D6rS6A^Pba<#KW;V7thq)RCxsr?jg zE}00nO5}M*d4C|$I4Zg4ZHj^vV&yp@h&=U{Z=yywv9^~pAOv2}$Hw5rX4Ej1ER%X3 z)A6r~+?S&N+d%@hf({GO2O`J<5AZR0WPhZ>-KXQgc=4ctRAvL%*g?1(oxQm}8MZf` zYa=b5H$8cqV0>BpgBz?_2ysgY-+CB z7)UvQKO+VN^Wf$uNdO{6_Av7uZ&pP*yplK*#Fkl4OnP!pR5D3ac0yF2J~_%DyK|d+ z_FXnmO}Ma(2dYUii^8)Y23qGbC(qJ4-ev4Q#AW@W&+TkZzX8cog%GFGZy5i8)H?D= z2lI5f!1Eo@nv~GfeAY`eeF=h0QJ>!IkN6ov!iIx>srpTf5LpsASsgbb^&mJN9sVRT ze4vC<`UI#)lHNhw{Dz6G!4l`oq}-_m;LZYk0}!~+pYTwEjFR;HK>U1JJRK8L(G(p; zUUYlDKottyeT2|}0#R;q8$z6UH!VHt#e7genIThc-XFiS_$lS%XOxoGns4p+iXN1` z1pufVwBY;z1_(ue_K7x_FTP(!Y2^3TJEQnRY6UfP_25WHzGGE3LThp2Tze3`ER zA6AsS4I+Us4-E#FPZUV!zXv+r4?0z<;k^fhWS)AzCmU zAWSVG9|s}(7|R*W&{s8;d-GKr(CT!KY9_wyjWJ?^{OZd4p{XsTZ9?E-O7PV*Z!QI2 zk~?%yh!Cljno<)Re@JkmPpq^|bchU3sDZBLx%*+rXfNnkItWY;;0YZB_@czS)r5K| z7~dN@1z5e(Q!rc~wo;8FK>oCq?W{-3))N?H-14rIZmk2=5ZMCwF3Y5~NCXN+Y;Fm* z(ueIVmlt@yG?^h*L-@svH%R8y$uTzCJZ`klY<#-V_)!x!g&@?mgiVhj=IZ3Xt;I;W zH~GREt+g7TzyOExM(3Z603iQWS$-NTKi@6?-KI(Eb&~}Q@R$8S6zuY5hS|Z5EStN@ z)89Ypu=(xlmcXZo*$w>7F(~q9dClXdMh=K30sXh%0t8~=SE8<8#%tqi2q#hSnX%^B zL%h5LQmsZ}qXoLl=VC9V?AKB7w&k#>&i33IXvDapZ64kFPx>|~#A7Y%DgXAx_;%1C zWW^G`lt+y4!@)Kz;Va9~&zgux9;c#S(l42GzhAfOdVe}={RCnIUtN5{Grje$gKS3# z_S^%NlhHBV+VS`Gr}HnLu3;S@5)?=UHPqY5Ecfa7cGXRU^x-E~!VUHtL-yUcoA7Z7kTkUO+)=-bmZjTeBLZ?#LNu)p|Gw;8?=4pH#37=SXix|~io)Sr9FQDfV9#11Gbs41 z<=bffFLl~q=B$ZlFoY;1oCf}pHSG~yCA>pKED#UH8z7z(LS$NcRaV24tw;%j z`<1d-Bl01jaUvY5GHFa^LBB3_tZdzRj3{O-HbLm1W9+~Zu8M}02@Mz%k-iZ^xLCq7 z_z)-jxo4MfJMp);rz*UmQ1oplPUQt*cz-^HD;sW?w_lBok_NIYq;%x*3Jw^~G6sKqj&qm!8kdxuun9VGQR1lCs zZA1_NH(drnXogjEI_zU6fojO_1Bl82eiVZESA%;VaOc1O3wXLZ{fj&O58w%R!#n-` zdwhI+13X7bCIP zU0v6Wjkuo2xK9SSb`@NUJg!*+SI38|;rROX>;FJIefjd`Mt2$*80hQky8)hhdU`rL zJ8yue_V)JH*47)~=|*>|tE;Q2skyF}`IqigUXCkQ!BtS>$`H7Bu>Yi;@NRS`ToG_w z!qNIZ^?w08ESOQ$Nw^(-n@B}l9G~?l$4N=aAQ10 zM@L6RMg5oY6cQ4G!C?M(#*>p1&gK#Bp)pSXE>2aY*2?PN%#*#n{r{WvWN2vk|ABdu zk-&)x;{^C|9BepxS{wyA?&j(QN{k~Qz=1%Q6ci6-Wd3LANk~ZO-`LatU(ypC4ksfc zBOxJy!C+7*^nYfa{=;~}!@B{VYJh(|5Zr$YJlQV)-vCeDu>S;}xc)DIC%(yl15XqG zXW;4QKfu$~{{TGI{sTP0{{=kJd~1$=C~6;{F8T7B?jPVuwm`StUHobEe*sUouE(nf zTbq6@bzotvx^2zwMOdvxn#*6kzdPWwaz12cGRL3BODs+@17&CSzc+>8;1Vo%T}xuHbw z`<3-u}PSi-H30ao_Sc{k~zBAIVj=RdB+r$(jZt zMJkgg8#`_P8+g)m%kO!c7tY65njPf#js&c7%AKRK@$N@bc^PiUNn1kX{7qrw#=pj1 zyF$zT<3U32V6^>?yEW972Oz?JiJ#83Us8R8VXFPe+ZA;RbUz#3dq2JZzJ28AY4eZN zr*~4e#YJa1XTdIjkh|ibi|wrz zOA$4dduQvRwR#nrmdc>>BTzUi{2Bz`<-}q|0^+;5N-BO2HsvD8+auSJ-oJ}DVl0;kJ&?1v~&pk z!a%eQ|8QcP0iNYxM06fLw|XZLA(HKu58>@_Bv@4c8RB&7Gfi&?nR&kwv12n4D}EQ$ zK6-^HvHC88q>IR(-x`vIiMUwi#s;XY5ESO= zy{92e1&_Q@! zor((RB*w~dP=kYe$(91rWX$aB}XSL}{!3~N>&N-QBJxUGN&Q14d!f!6Z9~N1E)Pn*8*ud#61m9L4@lZMlAvWM( zEI)}29@-ClwuV&*2SWWoH~Z_=n=qgQr)2@61i%O^S4Dm-OPgRi;fe)EHg7HOMhW7I zju2f*oc7ga0<$z!sHeYGq{&&-MyvuW^i)T(-V_p$P;MHM#|roN5bk{g8ELZ z2=suM{I)u2`4R{jrj^N+#zM&!{x%Al6u=~AyXD6KKr6BvCfJ{3n7P%j{&z}V%0x}E zOd9dZdb2dN#o=ql;B4=A&36{(TO!IbtZXPO3ogx^u>lHHeteJ40EiTZ3|`-6>Y?}< z8F5<Gui~T!Ep+QF+1na|9OJ8q`Z8x5DLH z5ebu6o9rVS9iVE}kudw^GyOLT@ZPw<7qV8cifllFbG=z+sHgi?QDL7MhmBn7H zr`}rV^+M9>+ilNUg>O~LR&80bM>g~TS@mnIw&k_{Dr-J~g6Vh0_(g-M2gxJpbI9SI zKC8EG3g<+3(Xlt>VL13gb)WcF83K86I+DsSTpdcX;>-N-qo3$6-}LCEvr-J*mC$Fj z%w;y*rXRLkt(KaOdM$RDNAfK#3{~p}*9NRe=1)UWN|;y^{(Sh6Lnx{%FHVEXit^M_ zDf>8j^O4}_2voWT8)v$ts3kSFKw>G9ekQe+s``t2nap5I~&Hiz#)gI)%6(OQqy~X%o za-77E;6`BB3lXwr2Aze960UasXYjxhX4~3Cm0ijaGz z)I_(wGJyV=!Uk%%xTyZZqR(=jANLi9Wj$}6Aj(;J9k0n}^Z&4Q-{EZifBf*X5IgoJ zQG4$_WACl@R@$N{YE^@nMa|lK6s0w5*PgYhq9|(b)+kEz%jbKKKkn=PKl$UFD_73@ zyvFl^+56Iu$La$xT-h|tyxpXj`YXp0HpTKTG;rR%el+uLFiYcKP(|Hubj>Qqmx(F7 zETxwmnqcY%5};T_csSbKiSfnqCrp48&nGLZ_SG-&}0}I!M zUyI;Btb=5tNQ2S|b<&2z7yd#dza`dhw@~DDW&CNB`(v1TZiP;VG*T5c~?=o(Yguk0}cj2(XY# z%mn^xj;~pa|8O1uJ_}ee;O|+c4eHhY0MThM)%k?hX@>yPiiiO?B#oEoF^GGHq-$0y z$~qhpAmj|A4ac|8@^1|(4@|W2jR%KIRYPB|T_^ryf4%Rg%`s?MfCKogYH)=%xP<`3 zdPuF|*k_5s5Upb$jU2gDcxG$D#sv_A|R$43uCbyR)g2H27EhdxT#}Wt| zH;w3XiNntNjRkNhdd~2xiU`Gx;wH)x`Xr*h^@9C{i0;?pK-q7KGM%aRLZEbMuS=3o z76Y%8&Hf7?%r#5#V29aLnLC@APW&lDd3jwe*;5n$eAGyI8(6!Lcn-2vX{fo zi6YqGxbX`$X^I=^AeIKo$T>2S-dj4y)7dv2$sz8 z*jtRmwFhUq&b#eV+Jiq{JQX?GqglSvsVzVp|8?AZZz7msF5hUBza`vb#J-|MV6@6jAoeVo4#K}sC+C;XQsi2VS z6oMcwNDh%Tf?!|}QdlWV(SMecL~yB8PN__LsoZiYp#z9;x)do>rpi;MNM9x$57a&b z3NM%G-~JDHqA#cI!KD={x5z2CiZ3?{F1Nldci<_vrLSM9>&8wo-Vpk(^0 zRGF%DtE#ubRarUz1D<%QgnDou*H!*sz*9wVb!AR<_5TNWs;)LN#CzdD5NG~B;He!N zOpq2PQ*+rXQ~EIY);suiT{#^LfR2?Q)=PxwOR0(=f`(;_Ikl3(Wy{O8Yr%k(oKnFe zh>z8~M>6kray|&he>kvuceMP$@Akt15Ac~Go?ddXJcZWv_^@t#fN z4n+Yn+6s$fb4#V_gmjo~Oueh&B>k8hqA9~17%z9}Y@>oTclqx|q->KKtmz$j5L~DD zbyX9J3}9x6r-3RgG0fo8X%;vv6wYn_CfrzH39MQtIX5J{E-S!AaM0`2`}ux)qQmj{ zDdz*7LW+Z&@LrHV438c~6zPifee$iow?xn8#(?W}3G>m`t*jkQsT*0EsD>dWKrln* z5p@moK}$L>oeg)Z@9Wl_j<%_#Hfvz6ZxOI;n$+ZPt9M9DDnlL0x~(P`@&3C^*56Oq za(?zuWMv@~FWA|*V3B@mZ2 zQFvuxcSvrpwNk%zXKhGZ0cO5)@@Z>KN9Q;Lt(GC45de@J1ij1dI_>Df-S4`_J}lwHchr4r z{aN9zU(_+x91h?hG)qD0Lon~VZf+n03h3^r#l469e$P4iOC(BsOo%b zGl**hFgL`L0|3-9MbGZ8di{xpm}J29(uCHaFXLo< zh&ExIfNN%SgvyTrj{*RoMzwV1j^!t`JEq{{gp*41!YYO0x*8^l6TL|FMyT#*x)|p~ zUc!tqhIm?V*w@3>`-LTPW=ov3EoNY>&*XkN}U~1hUoHLr3H?WJe{W@vv_ZF7$NTuki(jCi?{7%(H-1*#tzoesj_cKZ?8 zzZf5I?pmHc`es<(M@B!{K>Quemw)(viu=a5)3g2aL{Fc5UG2nDetzH3u`RwP=sEWK zdEhWua`Cih|BCghaLDS%+Lfi+Rm$TvvECJMZ!1s8vLW&4eBxSI^;)Ff;^@R$Zr2*V zW8nrr?D)OMj(qp6e9hhckAL^Gjl@6X`16g0VBRl#paowYZ3K9_){nlf!@_=$Fn>po ztb>);!M%e?`5S)s-zOMXn8T9c0vlwX`$qJB8s>kd5`YcpI)75mUgYg=qx)%~yK-i> zz^bt6Ub}Vd`BON26Erh10#Dkm-4K}EP}kowm;9;!Z%N8)bCG{aMjuvc-Ofj{#PDI# z^27FV=Zw0$$N(=oa|{PL%*-OtFdc4v$N_VydS zT-$s_ve$C7BSW}LYPZSewJ&hLjf2I|6L!lymlKnA9)8#nBH0(?+UuX|_Osj7N!kae z>=~_*woR-ieORtw-b>a0gtpuB5m?WjJj`9&hlCfVY8{sR+iUrdQR#JLM{<;LaYV^Nj zt&;;veOUSN&yBF7rL~i>f#t8e6`!1W`B>X%vuf4C>E=3apuq$MRR+ZLnUNaolq_lRudq& zRmn-!S=Il*u_~;j!1y0uTZvu2HCd*5zSZTEg&G5UvpX6;%-)AIwY2J=f>kLTsL~`xa`N&*<069O%GI}jzYu!Y1SR2H&0ZHL zcs=4Ci43r!bBeQ^9<9U+k-Bkw?NGs8855+yja_G+bg%q;<24|x!St|ExcaZhdt%M4 zh=Jqojs!W82W$tGNC4Vcvx0?_R@Ju}4?{*EMA|O=AZr)4{F50Mum}1Q@!=W|3b-2C zMMcc6b3QPr6V`ld`-IV5L;lZJqru#7qQhabQO|q|% z1*mip(@KV~98wtq&O{LE3*39)0Fk)$2*W12#+VRl%ObR8FgMqH1Z6lUf&jUGi72~+ zNLV<=Y*%VjLikN*)MAK;jPmndQkSwFWNpqysw!0!O7NIa&*@Fvy?^tR2XLtqX#Oov=U;|JB&qtMfpa19)6Am|`6SCF zI7uQ}`oIE#K;9yv0bZh>2~IIRtFNQ|>MF65qR3eF%r^qDJ5+)_Sva|`ocD&(_=liF znLxmFru{3j<>rS<6zVdM%U7)ztD=FF*^igWB1FnNuRs>)cG zFm<~7Fl6O>cUBomLN0bPObZ<<==7-3)unIWfJ@!@Z@tbRO}%f?4WCYJrFZoYoi{b z>{LQgI5N!jDaFSx-I`D@^p(;O?s>w zoyz{ErhvJ&Vr)z~CCzR|iIIpcTWM!2BZ$!+sHdfEcO}Bpp^DG*M@mclLw%ZKHZ>J1 zoKCMIC3ToF5kZ5eYj2L3%TX!j&_cJ33D8sIw6eV(6dJ-x0ts0JDNdUWL3#n78Z8vi z#HuzyI?oHzUb`$=eG8l&4-PYtp3P>a`A9;Bd|V!ShD(uhu{i^*Il3Wj~|D3v!6q z%v(d}a#YFN$#SNqA{O>ajioHZ=;iaIHOQ_xNGVE&O_@)ycU@RD**Ho9U8+sNt?B<{ zB2PW7OssZaH1c4&YRe(PmG6r--@1G~@M{(3u8aYv-K5&QInX3yOd=Ch`_}s_=K^p1 zLnBu6!~wQAT)NSr1jq1H5~_TF8K-%z%)|Fr>8w_sLpikSa^!Q4HzFN~k@YB%GCRQHpRY?5hHfq`%3AB&X+j|@sIG@XQcARg!} zMdOk+g=CC1Rj=3gAhoPRU28f0Etlu6KIK$3SIJ!xd>`GpYE~h8S0?c#8baJ}6_eqC z(2&(z!vasG5HCCQYwMp#$@U9BZG~yxYQ@+HWNF zmeX=OcNX9cWD6)fxuWps2va!KaWWpi17L}q;>ECnowtz`fP0(Oh4P*@nt9A)N8t_M zXuPdRF1y~UrU4tVJ2V0&75;`DphWeP3rthAL8M?$+pj_5myppQ&Mo&1?qeBEQSGs9 z`NF@HUSBkZv+HRjaE|FU7f|8K5XO3^616;0Url$n8`9Ux30oCJ!lzY@Jm}aK)vea$&C^0(W5l1rr?_z z!nnn*5j3X9?3>Xdx6R_#_QiG0Cu>S>+X)?sEAk$r5c0L9y zQRm61I{}QjHKV5k!o7A=tMq{nC-USuqXosVK+??FWA3WXN?R(KgGRF8?Ku5vqXDOPmYFY#$ zcDMm`L0LZ;>SJkI@dQGzTC%Tk_XlXbyrcBbBGs#58kL2=5{zYK*T(dlG0ynr&&2^y zfU#23R516!Yiiu17HfuLT_vd4BA8Dq(hU|vYS?}Cvqw6(JHjE#yA@l+!J!8NWS_?b zRYuY7b(4iiJ`$~WJ;c9XW<c?dZCrgn)q-XyT)u2k1BNz$mWL z2Bt0L7al1)s7`KG790f|wM?CVTL zD$d1q2fvPl0w&?nQ@zR$B3owgRRCvz7bvudT)(my5xb3w)lX#VxoK%g?)fH4t~3Z<}VT8o*B8jvl{rG!6ny{*qT zPIX>HZwva$8fqzo{gL8XUWX4^E1Iwk*=wt4Xb;LK^aA__T~+a^iogjepK^twEXMma z*cxq&nc4Ypb6l;qLMQZDLAP!#txGi0=g(jr#PMb&y-P5(~vS(8S!(xA&z zbvHKry6*YFru-+QitF@xa4bMZG~$@y#4 zeAAWL-Veu6j#k8K#@7g@<&8+z#4hNdB1cdhA~-mq8a8_RV=pnBdSXIf{dpN3WG}lj3OocvXW%R+37EJ=OIzb`#NCA(nCvq{%LT99We5_)i z`5k1qQcMS(rTuzkxDcYPn%5g!-5cQzaxGFT9~i3>6Mv^mTPde=rK962rt#`dqq!^= zl8nzT0_8ixGv?~a?)(yOI1*Vl?8*1#v)q?%K8;UJWATvj=riIT9w-!so3vCEcro%E z-B7>sWvpqua$x+8s@}xPc)BY7p)4#?GugRLXpU05WebWOg`xfIF){RPI!6h8glt>I?5$#GLCeW-Z*)<`};XM}I+!iOs zu8OB-P=D0_)y9C*U+-|f!sTMJI(_QKWhMe(0Lao&ZdapcH(<{gzwppx{%V9YH9|1W zrX@_$u;cg3@d8FZ4>k?m`57_I4{=V+a1H8nsa0ZxsOESFjrXj{d&t8%=y5;!s*1nt z+wYt?;4=|@Il_HB$+A68L_8mNW(Zj)D$Dy!%w)KJVW5Cxs3<-S#+ijD&POedL9}pn zbWLSz=g8SjG+vsD)|%?v#iHSDd z!cLlb-_N;;n@4F1FadJ2E+#Cx<}5R+<+sgEY|P#G4IgcrNt8i@f96o06*zL~k$W!K zQVF>ve*2vFF#N08a_2Yye5i0dn904wNmCmWZEJy|s`ccz$d|K-DxbFzH%qdGjz5Xu z5Q&C0FD5mA3%{RFI5rQgeZa#0&3D_-r*=L91>$InOI2HZb8Pm4oj=pnl5J(NfY>5= z+cMM>8ruLqozV-?! z*t$i0rBV++$Q?&`nymZYdXB&*UTtZ}^SduGKow5n=*>|nZ#5BRlRg5r?uqd#Lf>YS ze(ACq8ndb8w_Q%Oe9ngb*obk_946=3CMVIb%QKcH8S-=l&t^JOSgWr((N-dNRl@aQ z4bw`18kB6E21M z>QWb3vSn9)xjIj27c~vG>4|v~2>J3C7`hnCzfYdQ9Vv?L#z@3(%qTH}0R zWWpjfY`C1s>{=eqy=s%VcCjyM2cIv+{E*95{WSeHC_5`VJLe|T>>3Zj70Z8($4^3U z&72c?CKIuNJ%6}}3fQ>4-BP6sSBWKem4Xl^gPzoz8<6Zc?o1h~L&LImB9g;{*JGP3 zbAx>tT2mO>g<~-tqq$xC40?w?oYkf zaqX@_=|U_QMl4rAz@KoIn_?D#6zVZFnjh9o_^%K^4_E*EB$jdi1n1GK=%ehg22Cu5&)?j4wDV+#+8qGE`HT~F6>xg>mUJ=dBmhbDSOH2?xij2*a*T}} zv0E<}ia0dGHPS3i3!Ia_@HmM+%8`IN^w2n<&Y&@8*I_3&6}$uRy+~Mu+9LuV^je^V z?RG^hB`waT1+J09N{Z%(T7^^nM`sQx&j@#`*a;cis6-tWQ|Kry!mt*%I=M?S-j|t|w5*FNF z6>ttb!6)Y&aT#$->&bJMee4!vDErLYR4UdK-aPXD%;7~%sbh@3Gvq1Oa+;1lRJb$~ ze6C`Dl8gc%9nOs$Y~rR-AZ1eF=v6>1wGTiapVPfWTUanLi<(!{;Z@;_Y5mj4X^`az?ql~Tc;Kqfv+HCT`ll!e zJu0Sm1LWuZ=MkPsD#ja2Evp@n+V#5z`}3W z3GW<}g&w*53rq?$k%NZ}i~Ys1zl{KZys}~*XGI4s;=Z$6t9bKwX!f}FTksyy;>U_F zF4G>VaG>UB_<4;{nWO=yTAa-^&TIhCwg;#6dN z_S8H+=a|fsdGY&b|D1EW2#FXglNNItVbBl`vw2cqWfE&xs*p!73@CQFPbMR95JjcS zm_R7yG@DDlHWJQN^XsHIkEBTIt!%zHT~n}TU*6;!`y;sC6M=`J5YTPrYJMC~Bg&kU zF7*9V%9MVE$CXpO@%?SKcKCA*CTTWu^9n1OgZ=UonR>%v#!~5P z>Q|!L9A&ObPUtnA9xxhjaVaXY4(iJ+L%c=A#v&?CVrgElI^v+HkS*-$c6Jb zg{<_MI+Lc$Mfqdz5{`FI{2CrPW{4|ia~8h5z2Q_pG%_aT3A+v-lS}ubE6WmCmNre0 zF2_+0zlZ)@($|`IR0BPe7<*VI74^g<%GXSFRI%6;GC)TI5bB8u0m<;zHtX*rSSDM4 zCW(eJUS?$$l5q27IZ9xW-CQQ@8J2h6XqbRmo?yRemW*MynFN8KLbGmBdY~e3*Egl0 z0GJ-*G?;Yb?Kp1#TTo*J{NnCdy5Mr!MXKPVt2kUXY63Q&PeH4Gjdv3Yg8t3)RQWEm zr7Zaf0{)=#@d%suxl@pm*sk97S9k}G zXfE|0X7cEI^fizPp-5+_#$>2DC}F_Yu@$62g)1+nB32fuhSXF{fBo{;g?A5MBP>bk zxcU29@usIR3C}L&mB9XKk7C_vwm!gLmFbyoUE5DjjkV5GTiH%SX3XC6d&RrGMwE(f zS?L$~M)$}`(#9WQ3b%;UY~#@}y1xoteB|Wk7$MO=su7I-TQIV{Vm!eEjOL}Nob(o0 zR|-y11|;NADucYuQWKCuL|SYMyrk}2uaTpSeY)7syZ{~exPm8ronIqFHm$3uo>E!} zbs+Fhj(C{$r;{!TCIG34J^1G*PV~DjhRrySZD#{tyt0?#Ja(W&TN7DJHU#35Qzd%U z7b!CUgt+4u0g7q5*zH_`Nk<)3I#c2(;@o2t!IBYB4pOTsQr<;n&S2pt5^%yZYStLs^Ut&_|me+za=@J(k^eWc*C#XubXRnC% z-XR+CZ!eiTK8i1Fev88-sElD*6`F(DQ&$L{QNPY2Oa0WjZMhIhti!iO{;h|N$tYW^ zM=IQYa2iNWBQhxEz0P|7b3{~-u<>oojWNn&zNmk#W8*|~GYuAs zVIOz+w~cQ_HiU2SX*gVnJzFT7LtHIet*w5R!yY;)y@Pn|8QfTedl?tg3L_jGa3Z9t zLW^w{lUNfeBd9dhWVf&h`=%~04)T6#e4mZZ%3#&t0qbxdR!zN(Fy$}ri{o`1#i~xI zh(tLq{pU~8tQ1^mA}x^A-iRa;Hr4;Tu$GX7Wuo*mO0A&vbjCto_!WVP?q!ds-qwoQ z+ivqH*4~hZse;KFiODbq{?!Z30xt5%kf%@u7%&05N9+tx!au8zLBlp!9F(+8%<#>6 znYUdfXGtEXjxwDpJ%3;LoKNd4NIUsrj@^aP$ZDy2Deps!&EIQ2_rc;gaLoY=5nsQe zZV}7}o`RqZeEPp?+VrPSpSt+Ho@0ThO=@g44e%_IcV*-1s$~ERJiR7d*%F~?A*-B6 zusT@(5NK)ZNK~?@gs=WI{?@)m?De9X*KRwhrL&1x(D#|4WwL8P~y#&yb1rlwfE%OyLd$ z2wzlJH6utWDZ$Zx1>I}XeuD>FRWHlU4vf9RN ze^xKGKlTz0T*_Oc>wZ6^ursn4zX35w-JE2#Hjoz}M8T)Q0C}zp6=UTjW-dr`wI1{- zu!E(q;k-&&xhL~HwlN=~q--jrnx!FsGPkovpz63dYUm$6yCF#Uc9e&$c9(^Yo_v>$bT<226cT9zS-7x`50qC+eqscI^tf-*xs4PWg3 zk)Kyz$!Y9S2d*C)`pg3y=RTp5=2ZS&MgGA*RFOM==k2B8>Q;4L`0Vj$3)6!QMmOmx z?iZWZE-V->@XdV_b1+x=V};gG!@8u~yk{YtF^js}vvw3i8Y{oX3SQm&8~t%aBZbpd z676r5A*-EApx>jxp^3T=4QrkAJDw)M;O}ZCFd`#V$d#n3#7jt zEG}_u2EW?etm*X@f&PK1j7Nj9iqi;K@k~X2ahT+Q2seI1Un*SWB9cor1uqqX0nTE? z?GMDq0aj?Y@CCOx>c?#wJ3tn>yT}P!#3M692v;x7yeYKa25?}*=!GWB!Z#z%*YV3a zYTF8ylfa{|s1o#6Tivk?|X0oJLz6cURV?iv_bJDO}v zlhpVJKM#VJXJE@yHJKlhLPwXnU(A)ms(7bDljTH5^%L=V1INxuEf2*>90{E+(BU)3 z01X9xlP)i<32>+iI;j>FYZfzEag~&afB>sp$}-X4?JGA$k(kovbqEBiQZtb==!0ep zTc(ySW%pt+aotp3Sw`;Bf4rd=E-4k6B`$4#0Fo$`n{-x{Pz59qi@-;qUJ!Ff26j*x zK8KUi=0JP%_l`lV;$$6iRJ`L4SPey~D7esm+N2#T(_8r=f@Wg#8gP24vFle#s=sB> zNvWS_Ggg~7+~tC-{HEALU|jIPq35S!unWGID#LoA#DQ~wxTb+uDbdXXJrd)MN|&`D z;Hnrqzp%5e?}TnOyKYu7ETBxyW9uit)$q1VV24@%EdK|PS=ZRnRyom#-#z3a>k>s}G2Xo7no6FBU)YG=8h(1o?Zp^B3p_9_v#aH}+8{e>}wE$g}Bd{!VA5 zP$Vyx-)=zek}O1f$J4mN)d~W+;=qY;1C8}7?l}Zi&jf+geAjk^C%4t*l*j!XLd_w- z)?~^oAfnnm zzIqq`U;s{CBKw(*Vw%{5gxiafTbGf0ad9`>PE~EqIZ8$q6pv0_u7g3&xZR~ zDt8b`#APgZ%0ZPu7Wea#{USTGDK}VsVIMg^&ft#nwc0mTf8w?IxHfqoJ7RZwv+rq9 ztph#CLq3r+M_bEqrHc#@Oe-&Qap%9S&W|p0EQ+sg0`PdN$R~h#j?|EWy@H*QvS)p> zd=S_`zbxMXvqz-74Vc~(@(vpscBj(reoz5=Vh~teQnJURph{qY$33ziC4vS+6LuQCd4E~)YFn?V2&idNVIkSc(#u;`u8JQ_%S`aZzgQ7K{ILJxV= zE8porvp!072WAJNID7iwci7@HNPr6>R*6*Q7T86QPZ4Cz>Ay@20_LMR} zJxSBbO{&|~0Z-eUoE$qNW>7{*p*|V50lYeu{}d;5ghVGCklrha?iuG9kZPg^xJQVK z4Lrry)0E>QGRK~T`=>yjeRivH*9t&rP0_S)KuW zi(#(HYPRV0X4Vg7%pcz4M(-Dq{Ae;0+XJcDD2a7O(4czx93tOW+93S|0HI!cNhinw zPv|(maZVv?-3Q0k6P{kL(_612kP^ThSJ(wry|8&Qc5?JqP<3n9&~)l@Pvy#k6cE}Y zdfm5%RZYuOnALm!Q=B?g?sEzi{7#p7(BDsv)^=8jrV|MRpE;sF0^**S0mL9+T)u$^d0-O}lpM;744#a2`6!x{Ce}QVa*>m) zNBbNYINKdq!O$B=(Och;_xJcF7VL7) zlQSweVSED~n)d{Bt$EP=aM7~^!8t#SN~T?1r0~P0K|*{H^o!nAXGnwRN6$V3X?n)zieyx-(b*sXPb_aQr6W ziuk0KDK?dNVf}lst6xEgo+g@4^Z~ zUgzSo1F9M4Ov`azS%%ZSs0_{VuHa|x~}{s zg}on0m4l?<75$3d35g7?(e~ac;6^JrDlsd<{{vw8$iRvH&l|o!NxV|2e=n&Nek(eh zqzU3A_5TTcC}p5YB?ks^ebDdAD#PZoQ=Y3H6pI_;iCaW@( zISdr2!#cd&miatTT6o1jN{oU3=MMLzWZv)Csj3aJ7D4N@2xH!@!Z`-O=I z%r!jkUk5Xm?t99-`+K8T*Y=tvSPyot!dc8q(U#kCYb|)KE35jz0xSoO;T#Tp7n0`v zFH&dr*03fhg7>NpgT@J*g=w3Ed$?Oj+I$a#Ls_JyCN1cTlwnXH=Q>73U$mpPn`X7H zwh0fX`B19-VX(nUp>X9#m&ftH>jDdQ+p9C_E$q;;e8}kTzmI&|3)7QBUZ5qm)pZW%t8t|*FjkCO0$2gQ7+b?vj+di=^#*n;xK%ojkc;{7Q|JD$Fwf4CXuLBX5oK0Nu$?Fq#)V>zjuk+jswVzL!+xOz0)H zQRY1Br(;w2RRvmw(jRs_UwPnnV*S935-RK=xksrK|9U;_h5Wk7zpK{@s&z=Il}MRu zY=F(}VozW}>vMPfJHg&vcak7bbQT|Q{8+t!KVJD49u)c+57a)Qv$V}U1% zM0Lvl0Z&YdG8z8?PpZ0@E2^6I{{c^&NSvpJY@_wiv?RTd3oS)g8TSgg>J7boHqGq< z`PM65`;TF5AiGx6XB%iIVovkC>6z|VOw<~0Rc%Z*Q%G;Ku-6n!do8oJ?S#0 z*Hffw@&#`cnldRf08erfhGnfPg8==GyJ+^zGNs&Qkn;auNyj&uosX4I3liXsLw z_*3N(x=qgC$*J0xO-9sJ#9yRi$W2+`8u#HoKd9 zx<=oW0G)jJsH*D2rb-*#lguA)eJ4EKg*8!vVg0qk^q4O7 z)fb%AwJrpbjHQb2b8UaOY&`nx^RBU(G3ckx@?D`&k6_{ZA8nHF^^fdX*Bezn_^-@^ zngw(2Ne@q3eNi*Rp+v*~egV&klX>n-V}HL*SG?!;mY#@XQP0}0*>OD$i)pu03m)bL z&w7$4J;nnnb7c@~L&9}T*1JNaNtI51Ub{7R)WYp8eB(i~d@IUTq zgsJ3l)<@~}V%VtK^D809g7-N42;E#=O*(5YQNN;#ce3RO5|Irka;EOZ;1-i)RH}&|7^UQx zmJ4K5>G>a+6z9ZDrGu)?*q<<;7~)B-_g33p9z5)&H?L31sBsm4`mnoM@5f9!%4t2u zc@}QchJ<8!Kzj6^KS|F2ELwoba+BB6HcrF6Dvi8%w@x>TOr(EXIGfT>0PQdsQkN(t zE$7qV46%%SWZnqg=2JAPHYaXq4kdCJ6xhvKj-LMt-?!leELZ71eKf-+jITEbZx}Pr z@&44;x6>b(IcuG|5U6}Tqd4FQ`YO<3J`klT6l19iKm)QH%D2UJM5J7cL~@7`%8YE4 z?BDB8+M7Hd@o(>}OdSsi&$^z35J!lRx+@c6V$swd0F)M{RfYIr9S&D*h}}^H+Q~(w zSOxYFk9+ZT%l4(`v+(zW7wYV2u=l>=$_)70E3o~*7D^X(OZpIMLa|pDBZyWSHX>N; zq@U@X434&rX6q3%&+7RNXWU>6(d%0)Jp<6e2?1V?@{ErJ1i<6E?9MKfRMrkELKR;R z*uAm2o+A4Zyvx>zB|V3p7-zeBz=P*mUx=zo109!EIikjF4IXJu@AQCr>aTlA7JNvW zb>EA;sRAJbh&bZqb{>S#TJYNaMu|qeb6I+Z;LB2B3UqLlahsbI|MD9>;THW;3YSrt zTr3;^I8Bu1poL6YS>*N?`j~sGBfxPbk92j@!Xy~OO1I)$Nr6iM5ZRn_UTZ|E+fMLG zqE-6?n{&xh*MlvC7p1Vt6~7YpH#6YONxkZX!N*T+y4e=P`7TvNyotChNfBbvtBKjR z`+n~k7T72SBwuw((kS%{U&JbZ!nr?0`-NCN{+zE4HDZM%e}@}I_ouVVKegfwU2P8g zWA!t?8Mrkj9NzQi-Q|R)%2etq5kg7$LPZ6j$vNr&D6rpP&FkWp_PK}@HpAK5C*fI# zBZG$D7~L$jiwi1Rb|j8hZ}OMc54v6Ysm5{w3{<0r^o=*Glt* zs)!h0^3UzJ_sjuQEM2@QzHa|dCIUM~DwZbf7s-n=Rzh4vKmVlgn!%ymrUvMGhCzKMnvu`*auY9T-Z`tHw*jN@&9f zp|6H3Y1rd206c{2WM%E3uSTFs_M@)MZ$PS1a8OAga1M;WN>rN4xsu1JPiduOi=DNH_%7Bx8usNgG4uxvL>P%X z3nW~u0{!Hr_v>XBfYaOc681Py*KHuN)Y4AxW>YdDu!k^&XJ9DVTn0r0s3ZgN6E}NO zl(Pc%-AJ+56z{lhhm_eL`3ji5Wu=MEoDt?lY*VxBVCW3Is@K35H%nQ+g4Q4xx7hMHE4#D$<+MG4$RP z=|~aj2m;be=tV$^^kV2pQJP54&hL4i|DOHdGkecDXU_d%y<2bAthHwD>%OkglLN3k{}lCLdO-B7-!Tw&OC`SM9rMFE69!7$lUGBd%4`II+R zvE0lRlna<2_q3Rus$jMUM_inBhhvO^NMfUVLy;KPdwGx)fOd(!h${(Ubep(p@6(~u zjYuRS)P<-gY~?zLN)E+wtD0S`lUhv(!n;wYYqhftkRD<<2fnhfB(ezJ%hVpvMhSEe zt&nFa{R#wG0vL-xK6*+kSi>@FmC`=C`k@uT3`A1L-Du;v!H=uC$8it+#EP7YgNKyI zqNVf(*P_90uVJ$Dm|pa60bQAh<(x#S)U@ zab`2YcXWfp=+=(7GDvroqHsu3%U1Tchj?R+ERl$u;gKOLiU!amj~A8CbC!o5-KJB1 zUWX4B#=i7-72X$9JgZTBe#FNjBpMKQ+ijKXSBEIN1BJ7NE2+J?L#KR>$_EN~C;_P8 z&E&hsZ(2*LdR|%>VM`g2cSL^AD_ zSW-rf{C5ETX_?61Q`PM_vGcR){AYH8k(qrSXeco)!b;1KOFg|-3p&E$RC|whg4Yp* z77*2$^w9Ar)(H{kLaeMR3vm*lb$?=wl8@CUlJy?$$+n8AeALs_1<<)2d%H$DMYW^H z;uj~>0P*up;DOAm9qI3$dicPMS%e(J138aw*vvB9R^HW335p=<`?i0O@jbkP9Dtm} zI3Z~*Q zEgPLID<3Rp3}JF3bz)W3S+j*%%fEUiOK#(!Z?^Z+L=Bi!590s>wjUqZ z222{6PALcdQD6F_?v(N@eJXZ^CdxI%3?_z+T%O^`2W~&3L_3Qloai)9If%W3FnxJ3 zaN_@-mLvI%?Pu6ioDl~(DtZHL&^V>@`i}!nOTxOf@-P@Y(fgv`>Kuvw-XoA4 z*sXJ>2v*AG;b25XuVHi*4_%{--ET=c{vEz}WeHC~lDR4|heukFdASnRn}1BXdth_U zVMU<3>SpU`Cz|3+BZh;r}BK68d*6V+32-wuFF9CkewM7J>F|in1=pF7n(2==k%Ffd6$hC&^g&8cUw6>K49}laXR6`5Zer}`53L{9qCHMS zmc0}DzC?$8Nm4o!6t?!0PM^B-N0r)&WVDbJIDIK8{fcZhQIg@={nL1rMn^V=lou5P zj+01o!1hCK_!H@rE~)1_bg!R3Ou|KlCb^{F%Y=DzH;jbWYf>o_>T){W77mzAOO%z) zh?{-;u{OOY-PK8&SBv4z@K?W%X{2$k5EgKMnUmt z2o}OxK??tr153~RX_B&j#`40;I^t1|<=dQ9=}ex6=i=Cx`S(Cer|&3a-byrPhDcGp?rq%FbJ>kHdk4#-%+MY=s9b>i<}9uC#vZKAcB-#wzFk=H8skn=B6F)7rmC1`bFTapUf6MrZ?X+xOO6g86 ze1U-S6)J9`=@Z*UB;Qohn%QCdF)u8w?605n zh2N7B0*r?;ChQD^(vQNyGTQcJyHicOS0Aa&@@$r^vd?Qx%*b#Vp=`HNq0mJOd&)+PAUtQ^bcrxd=s8+T(MH?#r%dTtDJ%d&;n~Cdnc8rDpv>;GCqwOj!1hi0h8|46~u; z4eRX)GVa?+m2^h4-KE5M&MRWa3gPVf830SuY&|Y z7({*$`&st z@ka|py}?sU02G`k$QwkAnBUsXp9?j^OA_L0 z3C8~m@YM3^VHwr&`oP)tls+kY2HhDQSK)CK-*Ie1ynOS?-a@lqg2lnQXWB|%y?_fV z_xUmRbPe0j>(;(gI)^3lUlU|f4(aKm+D9r3i$lS0N%nBHx4UoD7H+TZHZg7a8z%3Z85ITxKT8)!l(aevN zi{APWrSwa4?cVJrjeL^DG%DR^vU_eYLcmjr0eE;x2nOOB5Fq_*$B?%I4Qt>yKGwNc zRvGr62A*X)Z=|d|@Sow-q$+D5REZU%o&69Wa1ANQ;iNn(N(?3@-7?U~I3?u)#0LvHibqf9FgM>(ryW&p) zZqB%{!>HoCs1=Q^+z8@}vU@RaX8I&(aEwTKc-)HQyBGXVCYB%hn3I71aQA z0-Ln-8_K)S^1?RCf3=ahv>ft1;CF2$h$;Wvb;C~}vS*`AxGmb4mxJP`MG&GuIt(5s zBxMdC<~K)+lHH*Lu!0RMZybd5w+iRXAmt-E?gKY-cAvGjFJ?Mo1PPf}+C~5F2oHA* z2z;;R*f>Z~P{4I1D3AgB9b#>AF%uj=nbG&bN5>#kQBJsweTh`I@3S%4nOdP=5vs{O-s118%icgV~OZASn7XO=Z=a%+CURjz$z++&7w?mKv)FG6Ur2r&6v{&x<AhJvrN$@hVi;M5TM{|f220CqL zzhM}{un@N`^{8jT%EV6+Im8H@k4v`gzDzQV^(|RydlFX{=Y!)&HOXp`$WQ?r?!Q|a0Q0^0 zD4T*?ico$HeWEu`)HYmtCfX9j_ufg*a$T!J2OkaIldOs*<$X9XsCZ~7iT=JK6p%hJ ze|#@B-E;j4fAVa@_m;2UKbiug9Ac;Kk@3B}P@*zw*nY`^O0vIDvK^}Lk$I3+Bwu9m&2LUDXYIICv4Oku#tfGY_#faYdNh>J6AwHU ztFV!dMQVHIQ&$wL2}h5`+T%PwFi#f8;-92wq)P#pV2Re<=<(!I&;JAPWOvXBvF)Dt z2Y6ByEHzAs{$9ZMrC1ECPj>wo9I$jGt(LfL)MGp8b5Ek|aSz|a#m33X;K?#8z2}d< zJ|3xgGeK;g_yz()h1~Ew&eg~$dvfdXbo2IPp3h?0Q>wY?cG8sGAQnee9TZ_Y+PoHD5j9w(C8!J%P05c>%k2O5Tr`l2gn}7KiQM9?s=; z8`o95baG-V{xb5|wyt%#!rp~R8%r!%&vopy7V5{edal~|Rqc~;+B{g*LIt4wMWOu&6Z*ypP(zT%y#y78bgYHr8;r0`+ANzm`9-I&{#8M^Hk z*}?%hGAuymjR6Z)1;JvmV1Dloa_6cLHu7bNj&~>Zr>ZdF*ky7D?=I$FRS}BhR*)ZP z8f@VfKK3~8;x1YhsWIF9upEZ&e3m~A>U65LXuaf9rc`=n*IqQ4 z$K|S&6a)I^h#~ALI8Rd3`1V^iY?Q-L7jq?+<=xvBoA<>lY{m%J#0WE+EDVNbBezee zF!t>O{|~G?4MbG0R)XCxyTH=yUE;r%`r?k4@2#qom$WuY@xFG1H)LjC=KhWdH_qxHvDfUo72Jg%c2OIDUvt+Cn^^?$VlE z>+ze;{R!yvEC^kBKUC0)io*nkWqyOvg6@JOei)dE8ibM*hU;TUB_qXSY+bt#9Bb2!6>;-hL`89oS-uf{E?h=n#=+(IX*B71iLnmgH;(Sv0auA_->oJc8xlJ67_#*MvV*=QdL;o?!fX#=#QzZUp zUcf~J;_B~f-8w`GKrZEmwtRy=>w;4KW$IB18c^au?Za4ZbHot{vgiLNxov@tBLz;W z3;-sHlq?}^)fwu+8}8f#B)}S$RCeqi zo`km$ylFwWJmH^H1ldpY5PK9NX~+F50%2qq_GpIN;|65TfU?Gw?Oq5XmxHf)EYubf zW+#OoVnaMk3sbe`P0Q!aTH$@EDPgM-e%CwvUU4{p2F+oJ0i;8Q0fqD!A+CyuHxgkf z6|Qd=ZkUEhppSY>9}2+9z@4}#02_5i2;K)mS`TP`uKL@sbC96P@+CQj4+Rt<%qJGG ztSX{716Z(YOg08~hJn39a#Yh2t(Rc%DfFio=j?a=>s^6ayNdDGMRCXvQc1bJ6ZwMQch|gY#Xaz}I%K3V|mBMGlOhCE0?eRd< zQWd&gG{(vj7sH-Ux;$#sVJQNsiS7u3eM>|X0~8$NBx|E258;qKi&*4J>}VQd;!&K6 zNqoHsg_>QcZZFXm*7gUFg{@D@i^dc)0}A;Xvc_C8X+r`f5n|6Xfm~Ev6R`*2nta}$ z(7K#zSCS&do)-EdEwUsn77C>7!+ie|T%bMhVpOwRI=Uo1qy!e`llJLv`oz8foKuwA zT9p1s5YZ^w@;M_N3S^#TWS0;xVL?(x?+X(9bfRxCnjL3Ye87BV04?5@h$r}YHXD~xjp`Qj`P=p}w zxt!Q2MK#9#O&`a*zZ}ThK#2wA`hTiN3mZz7?Cu zD!NqZj@%in6FeFrn1J+OSxT3S5}ZcZ{@Cbd`+8m)TQrwva8R%xFY* z6C$V7OGXKlA02>024;XtBSR3;6HMj!5b;t(6=P{It(3a4RKzM}luB;Xav3HA(aA{o z?i`jVk^`bIi34D3?@AdPN<;07D@jYod?hDja)2uEPb^gSb46@T(8y78n+Rbwf^bIt z)~n!K$Ty_FMTiee-*TIDX0Ssj8-^w;m$hITox>lJi$!dVnTHAR<^~tLuH{xvrFBQ{T zjjv3vzSi1Y)XK3t=;l&ZAuE&k8q}G}M#LbTVQlqp_?tUZRwf*Nyv@ZV{VVAa9&>sC z%0p7#?1kRkVOs7Idaz})WdUnLg|sX;*)5Ywuq)V%GS&Oh1~yc;{C!%K+4Q5TNeTpA zL&H|8pquGrKhdx?I9d9fV^WF3cURbt(Z&{~meNeCf##Os7{u-U7JN7)Sr_TAQOYl9 zuAK>mwz1aUi`K!fEhA*D<2tSD9tyQvxVDns*5aMkex3G}vIc59!bTKq2kj6L-a2=| zbl}$l0BwJo>vijd>@4%7l!z%>TG=-`*vLEC1v)u(JGmV@Z^d@2gB2S6Dj_}DWlKrb~)@UjS>D>@;^ul zWh_2|0@ei7#^zF-R8hpkdn01|qvWJh@KV_w$O*4bOrW9C9mJ=jg;HZZ(uRWyVIOetl4$I|cqSBV#S!*%d>AA+N?1Yjw8{sC9!0q# zHeyHo3rBW$M{M(kW}$$@SV-cmf5<*%#0e}gaTI0n2`o6ysW+~506Kv~B-kwlM4<&8;MQZAZ|D^h${8b)McD1-M2P4^+aJOl5MV1E=P4j#>D znmeG3guE|D1R`ONu>@-m2I-sdn4$n$=#0 zm}3cp_9<W;LcC*Fw^zfKkNGR5cl^#Fw^z_0yE)`j?RycuK#TOcbjPw zZ!=x*WB;Qv?e1RheY@V=#O(~=w(zz{{r{#iZES4(TV>k+FO}(fxe@oH=z4A%w~&pS zOTkSi{NG@v(NWxJI&ReOde{SRGtK;$&4ladz~N!09&=oqHLgVk*Ch83%=ASVSAFw; z!b~G0BSS+&|5lm$`}^@EQ&(5lze%RHwl;jQE}mqnudm0eOtrPO|Av`xRkHtrnc{Ju z7;)v)xKh~v1~Z)&Gd5Se!>df6K7A@HD=RK8E-EVe`0*ny&$H=6YJPtHe^jQF6kLq= zd}8#!RHml~0Wbf*sZ4%;em*`vUS3|WUcK`4^mKD`b9HrfadE*pI^v#L;GP)c?%&7h z%i&ZN6KyQ*?d|`6wV6b4{Jc00b{st|4i3XX@h}s9fC+R>MOAt0mb|>Ytc;Abw6v6z zl%%BOojZ5L#l=NMMgMIx2?`4SKjE3Uz+e^@7G`EKiw1P*G9+zv7v^fPdD1=b5q&Ds^Hb;GEi7nxFG~qQ&834gH@#Xhbte1~O~iDCm8| zV;HVGaJV{{A|lupt0lHFlp*1wuyE)S-kF06A!X4%E{c3DisE@PSX(ktWbi>dTl-7t zWZ9z{`^CX8Wz&@wUC}JEUy4m~MX$%Cz8c#RN>I!VJ~+kCxi=H-tSs^y2tREJ#Eno0 zGzcztK8F!%G7)}W?ITvYBm^~9uYXMwb66T`tl12CF&(H->@AKS|6usqcrX3s^XV*0 z7vrIs+P#oByg!zP|IIVODE3V2o~@=QSsMqYH`;E#%TpF&vrIUND7N+4|RMImMv>ZN}N$z23D`s2@yz9wE#%I&fLZ1vkp=PgMfXHY)c{kF4 zK!#^T{Nx9niQ3gK=pvmmdJ8Pw3a6eq8Pn3(zV|=*c`N6NSEQS?kU=CE)W#59jCx^g zx0$J>++>qoW;mDev2xL5F$c9b@Utj4{QSvl1i7J7Uc}9eQWOojXi!#KFOGJ{v4-`b zgL}PDQHg)P`W=%>3^D(%b3s$|c76-5j6q4I!eCy3vjTrb#OR8&0Pxnk*zO0Z=ck6}mtvjPDF&Pd{9nKiezm=; z%iM2Dx-IwOOQyN(?^f!Eyuq`(bMt`{B={_Pih7K~|+U~9yyvacl*C+9(c7lu~#R7MgKrfHTE*T5q z-23!Zn~ck&N?d2}boIiJ1x1kj(D`gV?YX`W0FA=N@(H!%_D-R(U1YRRYio1_RI=Re zvJzB`$I{8mS$%^MuUo=6lxzs@E)umTCUA-yebyvl>3$PKCZr2*7}U5$DYo)mSZ{O% zbBFTmWWht@C4on%@b&3hs!QN0l&7`^bahSEuP6^m9+YE&6zK5bqieop5d6uHQW`<^ zpmITSfJNRdBIx76+qA9Q@P84neBsoJ;j8j1OBQ zQ~P^SW=dp0+A`Z=WS-n16&cVEfBkE}3#DL)B045ut=0@B#St5eSg zTFB+`u!?!h^{j*Z@j-NJQr1RYf6t(s5c`e;+w_uXVh$A*;4`WL_s6KSH2{E<4G3^= z=pv}@CrhpBm3f8FsZoGMRdbjj*=JDQ$s7zHklNIUnlh&su$aVHE}P zsG*s@V9+v~`KcB_a!4*qsS4Wg1_MTJWXV@|s0$gv~RRMi0uP{VfY3yEqq`+{YgJv;z%Nvi=K&-!%hyh(? zW~E0#U~?ZS6a8=5{>v(gi9tbTq;HJjtM4W}5xAkia}VL<1#uw&@<&gh5g3LEo%5MP5K%pI)^CZq}xTS=nS7qCDYTZGFG zf}p`zOQw?sb%wy(Q>{%W!2y#)PZM5tcj8E=>KuE>z-yxkR{mq}Ek5Qt)dBJLu8zW?dSMz35N=B3yM9d&YdQEu(d8; zVHD;PweC01SFc9;cepa}iLSuQM@mR*VkL3+gF+3A3fqyl!0w9NrpyoNZ@^5A()mU` z3U)rpBIGG*%in9m%a{|I>~1>m9xPov12$dyEp*|)h##e7>%S&ZJT_#9NqwNxbTllx z{!D}~9U_%j-IIviqd4ihziETS%ljz4+*EuPz=n8J5%FwG?XJmmh*J!r%8^tC%2e3R z8b^|X`OU4lO0z-KA%?aL3N;I6rm?SjBF=6J7%G{qpfluW?-sl*`G%AyY}5iXzzP!wt2l+x@GHTh*EC5RbH5 zP<^4+s*GpPE%xUpRgYr4z7sO8gDdQY4d;TeK}>%!z4i&8jypZbR>KaMw^TJ`Ci3)O zmV4l5W0A6Rvy@(VvHB96@52__x*B^W^-0f>7Sdu#e}z_G6ST5Cp)>VrV3Lp{B>e3 zg#ZC1>mQ%pI}UjozSH$+6+^%=@l_vyKlIkelJKo)1kx9?ZEOZI&jkIv6$GL3PY*R9 zbi4hcR^91X-L01X5=~^D3v;(Ye_6L9mwLrTOMOR#q&QWx%**9Tic4jLCxcYzJr3zs zuTafMzxLn$DCWcZ*JRrC4X?|bW)GcZr5t5dVC zJh$#U;!Y#)278Bz8W0h^v{ns%?#W2LZUBD?=d^$we+UbbatujBhtX3Th>$#@B~|P6 zU0e2j!4sM&6?4KK6@Oq8@e2LaF8cSg5LH8hWe@VJ#7D6+uR3XBYSUut4<0dF3l)!2 z9*U3&?j!0V=^G-An>0hri{sj)sP#oi!bV};D4@bFyfQM}>SOp|Lwt&oSueNZ8j{## zpL`e<=M1rB(l9+Acb=S%xuSPh$^*HHkQAbyGFruNfMR~~#O%%_h8;Ww^@?(!Vctl% z@;=Ng7e4ujetPTShe(%?JdsaM5q7D>Dr#Vo*+`%DL;)y+=pAcjPGVC|_)3)%!^MsJ1 z>K&^HnAQTYU`Vl&PO&jbdFGR1Q37!00(P@0&SxpMB`J>36j~85Yt=jN^i| zU{oq?E-~$XYN$zC_&{oqbXr7XT5MEWFuo58njXcFZu$c3Awoo?1xap9ecPD+{%2}- zdaAf<>6uN9nJu%KZD*MnhOAEM ztnQLb!9=2GBAJ7YSwpi~BWGEo4B6w-+22jFr+l(!(zE9pvlq^?ys*R`A`m{@6v?8= z`;FP`NK}S)Nqo`ldz7VPe<5tJ5O&+-Hem4fVF|TKRO-i00@t$~AS1&}oO zfaS|+%*|`erJMsO&U14Z@@_PxQ~Rb#i;y^?AXjkm8@_ooeCY`#sUOa)l(ydUJf^;w za>3Ps5hh6h986!5!~_ORs=006d?2*CDKqy0()qzI|EA5u5S&y2R0%K=A(5%Nck_8N zB#M=^@jZEZz7b>aa2n|foY(|QK4Ov3)y*L^&S@o6D169i<6HRLzR*73dErq(GtV2f zq!4Em*q($<1Nu>mA#m5^qrWzs;0~x5?+KyETvR_i<%8pvKgjd3N8{#-2|A0ZR}w;b zN?LfREu~1*F?prWi|&@P8kQE_pDW5Aq~#|_oR17x)GT;wAL#**Fd`r7Z5QyFDCNnN z*2yqS*q4_0mX~bA@H36%*$O3_S@G zob(D4k|k4iYpxt?Py123qV2p;(Ir&&f8Be1^*O@~)Y-?RvLamDN1odTS$V3)x3YBjE)WiJPa*bNkThD$0pO zNI-S_Wm)XCECw;(g1e|<5`Z%d5}Vr+s7%(C`!%XmQQt6t<4=1s&_vM&u-C3FVWu6w zd^%)J>vrZlEMq#rZUC_WT$PDj(!Vj#`X5v12_HOnpZs=tqqt+n9cGN&*S7q!uA=h} zbBV?)gGTPG2QS<@wUavWo=}+xJld5~@3MP{v4>2q$JnvisHIXtj)Ww(sk^DkX`u;9 zMRrC8suNXvYW6^+abPP=zXzBeeYkj{cCA z@UVp*YuRpwtp0ofxJNl5!B}+{{Xj5L;B!}slU#}$S-sf;r8&FJ&O?K;W`m(U{irNk z^_Z`|x()hfUnzXPrpOLPwhXzL6%@(AJF0qyKcJRjZ`_r9V)J~6z>V-Kk$h9& zyIkxH;EI&}8F?U0Y^?+yHJ`Fg)%NSosOhldzXIXFEg z;Bml&nf#c{)ue@BH83=0^JLPywWe|BLAzYMll&B7t;vmlS`Rweb2@>3G9A7k0u^bU z<(y3lbl zSI9E>K7f}IQ(r_jeuX6Oz{xGNHO&Vt%#T)#rw=b+v*)W8XDcILCCS3UKv~A#)X3Gh z^?;$xCp~zTX}{&ih9QanPCXu>>_zu=3l0&oFJxG z6PaR`n&Rf9_a-SmdBT>gs78KRIjv+<5fDawAyg{T3|N`0z#0XQv$t7tUO(VA$4CES z>n%UG|LwmRT22;Ry|26~@!njL(oEWX;VOG6<)HGR4t%h6P=s<&Rftl9LTiyp(JugA=IuqjrR6`1laEIx&H}Ilj*FI`ek6=JxZ`=c72t1AkLRb2l*NtE z%MGTA)m^=<7w_*G;zUUF_t_7dBO_Q>S(m<}^+U~m(URzl>Wr+q3(@nAma^}&j|sd; za9&RunMW%83^D$xw7jlOxe;!@?#B+?7a`HW(skL7$g*xeyyh~A-}dL;+P>OGC~Ue0 z(z!E&0+TSF?{?DSYaA%2i+=5B7jC0Ewx0z4q}Q9&kEbU|EKql4WO66u3x6~8ey`|i zw}fSH+<6saK1IE>*{!hUmz3v}sNf4)>)hMyZu!Naxu^z{AuquB?EN73%dl| ztXjy_-`=`jz8sm``}ISYa>vd5*B=QIBh2*6j=YZj#eK@3FyWt6E=!(IwrCW0JB2p9 zs6by9>FiMij=1dKD(2fM9kBq?B-z#^jT>%?CHsw~Y<49gR3aXQ!*)f;y1>K}uCOHl zQr?5*ZeK^V?-@VcKm7DFV|l5c;z(7NoHOn~Asc%K#_-GAY~YL8FgKiKl(HNS)<%;3 zgwx65O)xYOMudXkGvN^ys)B)>Cwd`n{kdQH@LHd4W@P-+`$GX?Iwp%R1WR;YRhu!D zKbx=V;L^_slq`T;qRe|lIINF%A}q$8_!3T+g{B~+B5Oi#Wz2s+4zAwUEGJA)Fe z;7-oNyiTE@{j&F`)_0Hif78D*C-_18BK_9|Cye1P^exe60^2)q9W2E~6>J`hAUGh} zM&5X^9IP4f-6-h0*bd+T_f z$@=oc*tiY8X^6sxj_slf5`2gsDYv_ePkf>d9AfksIax>BE3pB zO)v%}0j3g69U&bvb6VygV^X18l(9S`D4#|LlR)`wW()`*ZNj&#{=+j-u&H0(zPS=^ z#2~9qepY4El^jx-M);gijiBqC%4&h$&Mr8yBE0VC?vL%)m&d#Sw!;Kh358IVh@tj7 zyvZOpV2v{H)8{;Ug5x%wt*g zm2?s0QL5U|1^LPo)m_kj#ev^Gl!+|5_o3VYoIpx-*cqt)ov(>{Ds zCKK)!QK1m69+BR!IyWeV=P)J}-?%$y8Gi?f)lCc394nDOQTBkfZMF=;7#)0F^E75c zt4Q9lCws4F(*f|19PL1ia;hu+oaKA{&_}9lw{JQ+s|ePwRqF^p+&1W?f01?Y`8KDl zN40o>c5a-srwFW7p;!E^zWAOTg$#2?Bu{=%uiXZVmp?;1QXW^B^qj>s6a|TW@#~Bj z9+&dUogT@j0fIz-C)|22>+hFqM_N--XGth6rBFYM zS_%+u`fC|=t1zuLP=)5sRP6J`hMD+;D=BWC4Rn4!fgEAn@;f8rf#qmu^r>z7^TNiD zF%c9db6F*evkUL_8Ide~+Jb%~*Wa;yKa$lG$dUvaR`LPQ2z9 zbX$~LuE*$RYk=k0^P5+mKVH{Myu`@$@%{~ud&+Q@@~+*EP-;UnkK;z{teJSHN;|8U zT*bP)8@8QG#EvHCdwlXl#)Xypr5xhO&+WLT9+DD{$f0Urfe^`8FTNCw3u(y_`dFf4ZjXbdP5G~_8Q)eeFyaCVy$#jVekQr; z6J=y)J(E#18D=)G$)2^z)(+hwrjXhpUh&*uJenQ4wKV>A8(d62+ove7rJmLxgvejkY=zdV9z*lV z?OpT2DsgJ#w*VpcJlQ9!+Nn+TVHofDTvHq8Pfa7O&fb}sW(O(LbyGcp6pkemV|A&f zuze+3@s4=*^13gT75ysbp%97V>2@5EE1F2of`D!YL!#~)Ow(dPEIHEw3wI6Wma_yD zEh#-42+_Z>43;xNoovKzk!rD#f9|Qa!)Mj&`L@kz9ZKm+d3G&9iH~LuiNG}#6+Xi; z<}4AZee#9B5`xH|u*1?D)t=#;At_;mi&j(gk_JL=;x3;Y>Pt6a^<1Kute}p^{Y3l* zZck0+o|#_d(^w1g1HtGi7tyH-Z`B`}EGBOr)V)D2u4n0SlJ)D^Gq9)Rs<#>IK2x^V zL_Ez^q7m;%5T$;=Y}p?ymepZ2a{Jy$Qkkb3abp#mEiz-NR8`Dsnz@b5y|Ob9iV?6V2Zi1~(-f|^;dDXQ zQHrj4mF=%)Qz23|6pRh+awV-L6Vm)-UO@QEF0@BX!2|8Gu~P^Q{|%f9Hr`*>xdT+fKvMg^I!Z zVK=%#HmcGKu-`K;a95T=Z2lVz_q_*h1%7`|_ew)m-yHy>sIR=Mmz7{{!Tu@vS5yAG z*emiRDV{u0z>^8guXs=DL>$9l~hW)D4fJ2yy-@wY!cv;`MIt0~Ofe3|? zwiIkfu=xTF*Qaz315X2NJrem@&m(^XsvSS`0@6?nSM)^1nXdx}BUqwW`fwWql}Cq& zcHBZAq_>$FXaMM_h%tFGn=0HFM@5$&7{)opBc1lG3&p9gkz<^Z06kIri#tJn&2uqQ z^aSlBTuLHQDBNm0buxxjHFEJnIv68hW0C8AALCIbM`%JE)Wn!2dEVR_o7U#c z5qYz?RPKWka;SBsrX`?5jwQ4+0ju)ZN|TGqnhw)(IW?M!#-08)fE#?)%BgI<*+x z7F9h@HGFICfo9zgvbHuRHG#D*V%44};5yTVt~=%J7Ao&(Kmcbss~NZ#DbS;^*7M90 z`k(-1Y}SLnanq6(KoSU16A9~f+L$SeIw}YFC_j(wL~%7J?W&8As~abk0S%zxMitHP zDu!n2Pq_O0sJq@Cs`(me*a|2z^~X{mLEj?fd=@lJ%QdvR`<{twWSwKqj@0jPK_CDp z4qvsr%@eJl?HiedLCocwdwdQ(1_c_c{`f%3!1LtYKbl)A61dyx6Nw*SgtfsM9JsF-bfi1HRmP2<2rxv!$N zgZXA(NgTi0j+a&(YxCLg{^1R49%_3T`}JwE*0am6TI549kvyH^1K?P(AmM$a5 zQT=^j`M7Y_BV*F z3VDpjbs|GK58jY|F(~dbpr9H0TW(0O9!ZEEv_djc>SmkpuUr;&m{g#BqWcUqX(7D#l9*aR6#X-8rVA>d97 z^Bjd5%n*y?qe}X}@EnA)TY&jRC&X;OiW3b=Jh;Ej6@4?8)tV<%T2qxxen3)oEY=RB zi6?o`VIup4j@Yn-EwnS7kU0+`*AT%qN${&A`1L*rpbz$k1V>}Rj%YZv142*qAU4x* zqh;(gRI@`Q2(cYu!9!rRE&s4bmxSV8d_#yShQ!_i%&-IUKZQKRpAiC6;hNxANC?c1 zM8_LV3J^JI-qXZ}Yv662M?^Hp$Q2Z1?ex1nk*=Yj&V7~#xF{zm0R+6QM6BHZNm`ST z>7%aW)uRM?y>=C-w?UX-aU^LmIAJuzp*YT$JCX(-5zQINy&oPh6XE3gCBK@)Zl6Ho zj3`(H5{e;<{vWK}g;P~;-!J~P1K4z@#HNw%hP^i>At~ZUkVaZSk&@VSNvnX;s5BDN z9nvDDAR*n|Df@7L?=$y#&NJuyX3orS{RwMkU9+z1dVk)pNCC2a!U)cGC+gobT_Z_U zL|m8$mg;PimLYQXQ!9g0yP-c{%)$_F^GeqVmN4`caKb7iVYLP9mfL~DVf^P2Pno6~ z(J;!qnkmD_^kL{I{*g$5AMffwt_tBuG;l92`wt{dHu% z2bh8QH+C{iYlI&^z}qy~JIEKnzsM%NY9swSPl^S|g6R^#^dW&rIiN1M#w7udH4^54 zo*+g{W<2RMG>xqbnrha1;HCk^I@pa${qC4U zsRiMXG!gUMbDSRuaInF?g#oaTbcf!EccJv9?%b?)JV%r{Y*8!6h=WUv^HvStna0L@ zFE;um9=pI;D@*u(EfTLtcQ?Nirm^0?2GCri!5%VH$920Jh%op60=n`orUsI^UL z?2@fc}9H-AXCIFrT&QpK>B^H6FR%+I+3M)3hB4GvUkJJ{xVXJa0F!FON zKo8W!8SC(Q^_wM*(R>7Y(#}W^M+2zJKDXAVS#A9md1taM0Ew%QT#MCX!SW&jPfweR zYiadok*4U-a6PDLo9(Niwd=yr8%Bg1jg5i4L;W_45{82l+#2zj-`&N=?nX&Y72k_4 zIGill^L#zw<|D!W7`PpD{c^J@?TDAF8R{qu$Pb6>8g13+Y+5qg##jXZVhrb^8;L=JvSOH<%$%CJhU|x6 zLIrqF3qmz5!hKWq1l!lz1Mc{`Nf@Jl)2(lQ4Osc(vi5?*+*KkRi)>R)Kw=IG6pMzo zuCJZFS7H2-Va^G-M(07a-)(>4GCSFa(qZs$`+_|zwx?E|d!9OlS~yM^kMdyeU{b(h(#WIaIs z_6DsEGD+rqmdQrj2L7=ER?FGBdN&Kg_J_k}8aZ$WB=Kiw7mJ=Qf`#x|=EHqb!yQs1 zTnhdO7`xzQeGXoI_Tv_eEOks=Ey*TkkJE!3Xbva>C z!>io+I9J_n2h<04xBwTR^8n+JRIWxrakiIxukXa@6%<*)LI-wXAZY@gx^1IptGrmH*J>~?3$oCCuov=3{I*i<-d@jBrkfTm zeKJ?7v=Awt_d5?`$$Z4Cx(NRQ9A53`2|6c*8VA<*PN^bZpeFWYCNj7pxAfFy-bNP7M1nzW zu21ovi|9tNNQa228?AAjTE)K~ErV*$^JseFdT0N3{q=0&&+)rnz%9D4UI$-l=y)#H z>zw%cFxwg7W1Rc;ky_qI1X+hvf4ttp!MEfblX(ioXYGv>_I=*^a7xarG6urst$J8~}@-QHUy2?NEEtZ^c+x}_((l1&a zPaw=6m=6+5xtd}rofi5zgotWGn8z~eIhwDe)&{804fsNWUgg1jK20pUMta-tu1
b@$!_0qw36#Vx4^KH0}4Df&POkJUb#NFq1 zBe|R*zGd0~KxC+FnhJDHTO!|;MDjkW^n)$3M7|TX8~txQ6Di*)nd}2ra6-X&YV<^S z;K=rV>pwh`^SQ8976cc=`5tXG+G9_wi^~8rZncyeQvAMQGxP>xCdXZNfAZMkE48)w z*CSn)?SGw}B6+Nm_)XKyr1s}KA}EF8hJQ%BIxV?y*sPOsY#;fn^J4>U*c$Lr zSh|FHq&r=j^O-N63G?Q~=OS!{+PWqFKPRRlWk;(tC)CSnC8RKv9&yN8X1D7~Z`k3g1AFspd5F2`~r&LhYI_!`dHUW-uR z>b!vb1(5_}sc@LW-<+V)k>s<&w{8&{M?V4VPs0#_$XvB?)YFVuaO6$%PGBG1XV=EE z3wBNBzP5~(;Yt(xy#zraCX<)q2-J+;zZw7LKuOtutV~4C%ZYEs$i4i=Mi+C)v980u z3+>{ZUGCJ1a*EjL2rt|fW^_vZR?%wNpgq&~IlYTJ0Kdjrd%#@6B)&Y?v&GJx{Q!U#W!iP7C zH*L4(Yt-l)C~32^#dP^=JG%H9Hj13kH0Afji22d-98uy2B@eX7AlevBxx>NH4n5gt zQ>78m5PLUelGjO3!gNF$4G0!4qINoUjTl$HJzz88)QRM6h+$!Bi`;79{NPuKHE#fN zyQu3TJA;sg3G8Y#Kg22BKDa&QUmJSr6CD)V3w{2koxEJ6hdhMsI=OOLU}vmW>VQ(4 z9T-p-?KgI6K0!JA5C`Lt7IbwW%x|}9irz4eE`+J{o9rRTnLJHC7wo}uqNqQ5r#eiL zX?;%f$IfPV<>JT1RP>8x=_SsiD$?b|J@z3^T>0fr#7We_4;Uosg$0VjTcHbq5OLzUsauSVL9~1fcoWh`Z)c$t$Cg}Y?VyZ1^IQxIyqZx?5KpJG z=~Ja)&BX;EJZ&I~aty9K986izh9g=YMB)dBvh%blP8QPnC%|zb-gr`jti<%!aF{Yr z2YFI?C`hI2jE+|E@FD{Gk>@SGItok^_k-34uFmWS0uauftc9?9ueKu)f5V=6d>Uh> zsE<(Dxa%I(@3eT3YVkS%)(IU8vDzuZ0dY$LF{U#aw5|4y!qJJI+Q-aMhTeh<;Zamx zRvr85?cLo!A@1M{kOEL1BF_e;UYTr1N>0cG`R%%Z<=)Lu_)u~&S{u%|PtD_YWe?jv8@o-gTq0&`9@RNx0Y2j2m(!yPgtqJUv~XPlkZ2W0TD zr1I+Phwu3(g-B`c2Z`q-ey+n5Jzho^%Q5A{v1Wj@%)2>x^trc9H*K$L!WRQqqb2Bokv0iNEA zTekpgufqP_UN$-B?R7p4Prqk5{^MaK%4TtOEI$|) zv^~IdlpU7hjXz?eEtZy}sfJKP4F?xN<=yDwBOMz`(k=_!GCtyCpek@k8lNzHCH{`g zV@(;w>LT%=4?wMg!!0f;ZrC5Jl?%ObyDX2WV~>b zc!>SRG6rvJ^Ntm~&;DW#e^gW-V5(eT)_>?j+b73DWA&C5BEvY zZQce+y|}dV3t@pLo6(jMQfjLnT^x#$FDv+#;l-0R4t=HfTe{zsC)ReyvvwlX ztZdbZEhrA>@erFiwt0iJy*iRd%8|ppK|{Y-p^+Vo*>DVJmQV4?$_8@$adM9a$@4c= zrh#TnE1!{zEX8ylA8&(Yf{}wV5us%-9!`_7P4-cZI=)c$a9gArqaS7Rtju(%kGT9Qbg?`ODdI*6~)_X||8lDzCy z#uhOALezI7o-a7p^)r;dtdUewNlU}hOa6xABq*f|bS*j|XvVvrYA}tx=}{29svTpF zk-Q0t_Igx3wZeQ_LLMB{=;JYiJM#68IC9>C^zF>dH-TW2Tuq|}ig!Dn!p-fYae+2$ zi}32R_Ji1+U}>b%x5?M7_y)n!=kM*l{;B@R?z{UoVJv;!kXvq+-rmb(hUe%!g4t0} z=k zJL_UAv9nx}dvYE-XAzx?mYsMjj>pRZ9Oq&E|74k7zGbBC1kk&i=2^+0ICKsmmF1FC>h(sJhQPJ5)b-qA2}}R)xe^?vhZx4koHWVfEc+<<4Xc^T3_5NH9e=?B zs_c@yWkj6kf6-Z3zhsKpc{2Hu&bjZ`Uky0nrP)n|N{YX6YHV8GFe9uCs(9VWJY(@I zG8>baonUJ=NBuC#_7U_F`-h+bj#CtxD>9Wb2`5#AF8@`gR$1sfx6mU`4?2L6PcrW+ z^g-I_F|2Tk8u&tDW(+Eanhi>d4y7r}akt1Z2Ict9gA&m!>2&R%-LvKr7w8Gh-Bdad zw+3f6SZW+1g9(Nabpysr>GXb?rO zlB|jvL>(fC&P93zDIz<_EWnE6_mrESPz~MIhe7VXTg>~JyF%Yx1y`0T;}D zm={=DvdulPNU6y7w?t6pnNDz1(t=?-B0CD{*1-pW#lcAanGPgUnO8bg@(?a|4Jq

zWn=@h1J5Yj= zw(mgl2T37^BnL6b5(0H7E?BBhm;b~zkcR>0^`bAP*!p?2*nPxZz#S3zyB%2bl*QIX86emYuy zG^=AEyeAky9IZ?`m`pexPBsbQB?_Ww>X6&VMR`1>UG8Lu1#z0@DIH>$xqX9Fn>fPX zMTI|OjkpPglvoLq8Ad6ofFfBzhIgYg3kp9LM3vdQ4&%^$9A}M1iOJ^*)oG(VxPbY8 zWEnTBM4ffr)eb~LXVO!9>6)i<@4q=^CcTplWo|%4;}m6j-}RreeLyq4pEjuUY~EE- zDN{)^nPk;vRmJC2`48PDDjnz(;EZJ3d}p@F$ZVGPZZPj=juZ_I(cw)qEP55~nDV?3 zMP-W!1*6;?Q5?YN-3;XVX4tSJx_2{&fG-LD`TV2frDX@AEu>g;=*^mnFL}a&DwK#s|T3}Jae*41&f!y#`&_Ivu=W2O* zpG9whlsM1nHW<2B8v0=+{oHj!P;!fIvejbq*VKPS_*(^evqstKeJR@1a$ehZw#8|* z7ZtSpg5r?j-}SSsAqWq=`%Ve9-KF@c(KD;{U9qR=93r8;J6fYBV54Ug>Pe-1z2ewR z5c)YM6$LnXT|1XEm*|N)GQ8(wjN3qnKmOj``<-huc~RwabjA+`C;a2bB#h9J=ixOp zE|b9msgL=`$}A@(&nk$LUu#-rz#N`%JfYCt_E?&>6tvB;GP|X>Hkk zu*+3swvBrkq&iNy8(g;AvNgRMx@c9rBKhrYF8@Bmmo81dZQi|x!QEx;+i7*{;|BHh zq0JRZ6(6?F4Vo|d>p8=ou3fuZ{hO;4MT8fl8Bmz>;Nu;LNaw?K;&&^+$^eSs$>Oiz%g}=&u1Xd$1x;yOgWQ ztVjofh(l&8f^PbYkg|$Te{s)YSN8MA+}y`!R+V=lN2odo+jW&N9}6uSI!JX)Xi~|4 zw0mFtU~h3-XIZo$S6m{?O@XiSv3INqV<>pNU4bY_t#bk5Jysm#q24K~addD$RfIuT zOlNRzjlM*NTTGNs0%fRzwNXJC{$tkk-u;59s=}W@d@a&l>p=~CQDIleH5CpWw6{TAdobd4yHm*g>a}v-aLrT5 zOBP)zEi#F_KcFD^o5xq4ZY-{Lk34Qlm854nWsifO3!ULUhKeC;QLZ&?a;K;n;FgZG z8c?yy^Yqd^_9B!bJK8fFn--uF$*%D7AoR2!3%!#D4yaWzcz0@vl~m|FJB$7j=<4yy zCs@@&GKez5#coet3`87q`iyVPh~p%9uht9i<+-G&ZwkxWO$f&`ZpW=`Rom>a zfY%olkp0=?y}H;XtZM+FOqkqZVCQ=VG&HvF{I%8@ZgHLRc8190q4AF{|3-<>M`CZL zk6ItseKQVHy&n=TR`2HF{l{oGZ8}s#>L^5ckdf!py9c#;KQ5xrY7<|{G@~Ts2gTE9 zBhqNQCjLlj%MS=!xPEv5_cu!aFLK z@k*gmD)^?4jH9r!8S%$;FJuNQGjXyZ#Q}{KKg1eYx~`(76Ih^7ct$$@#aFGXG84I& zJlQRGj2t>tYWk{J&ZqH3&4(4~_GGzQHNk4q>v~t2`z-S1EcL!VZL;XDFd4rfmRJ6W z&^Hf!s%S$$w}Uus{n}lx8@-w`?lpXCZu|aMnJ)FZS?=;BA{0Ut|E%#C#lO$!QCb%- zJ9e+>J62%kJK%BC8FqQyY1g3tN|KN5!8g)ST*lZhg3V(S(mf%yJ=Su)UPkkeRm{&m}#_y%$ zc!a2`@T|8g47128$;SxO(QjrUzm&?&ncPfbn<@Utcidwn8V)g^Q$$BJ1}Mwmi;r&f zG@Ii#b=9^UI0d#^-Fzfcyz^4LQ?Av(uU&wwf{CaLFa^twD+^7IqON^@`OsQQJTAUpPhOxG!4-GnB>L52B=p{D)7^GMY|eus z+ETO9)Q4NjWl!z|;FQ0BqpR3B4dff&33MtmPej?vr96Am=wwO3h}k7ak)Ix~FZ)bn zPd0>;hi}sIw>_+oTpg@vr#YDEcM*C(qFJ}G8e${!Lg&u=ubPlH`DX@t?_WAiq#uFj z4@k987TIK)K*g)xRu*Cm9<5@!xBF60tcjjA$mhk{j~G6?Ki6ubT*DRI=8D%{A7t)T zMz{(-@w?bw{+`d$`o#ZgeS5YCFV0MwIOxlCTz4x=E>ry31)*LWNF%y5CeVyW{T-UD zav2d%rmx(Af45|~gHU8puaj72d$^PIuK1@c%WYt!i+C^FI!;_ue&idi#n}6>exBtO_VT_-&44QJO z7bt}Am!J2L^FO`4dG#7D$fZelv;Asp9c!R2q7j4xgh{UsxBvFqc#M6=8<+<6F0k|3 zKFx6;e##qv3zonaB3PfnUgKdMRDWrWR^-#d8KxZcwJ*Mjn}sGA^p9mr+FO%wGlWP@ zB#49AE792{H`MjyJ!Jf2yq=?acy9atOtk^7MC0W1NJ2FAHttGRV7w7v z>nZM}Q>#e7@ga&!eXU%iXg&qI&0(@rO({AxTdZmn3Eh&eR=zJO4!>`ab!t}V`u0XA zYW`~<^9PrRq4PZk7gE=2w^~%V+-h+eP4~u=tW-!GB^zSus1_jw+b$>eVq_)PJK`Z9 zGk$dEd2?eKEi2J$kqiFb)i%)atlS#Y=@&vlzuaF;1`DkY%WPP)iwyHxS&xuZ=FgZa z&HdfTwTv@`t3Rrwna2w$y7myMPN372j9ky?S^U9f=a0 zJpj>Fkj6{1*{_SiYsVuHyVM+Hf8pVf!6cwidx0eB!|%W4Pf?`~2~KV7GiT$^Tj;Vo z+4sfAzX?2ElK?gUA#}-eG2jTf2G6m+mgV38!>UOu2Tdc;R8V% zNv=)DAHMskrwCy380w5W_=koeA|A>#(2d*uFgcX7myJm&4a(Ip9HO?pLe7xyp&-Kjz^Tc;sgr`k>|#b6Ii#trMePm2wo{QZQTj^EbxdFlOYbEFZP- z8d$?sn4qL*(m6DMVOZcfz*=X4gR*ju2}ZJ0uM({+aFNAe-EuH{;v0#J_3gvtw>jN9 z)FW{uf`>6%%zr#j`=YM%;puSp3-@o_Ksi<~gd>;EQTZQrF$4u2$bWbO{`55@%bKCNfC8i09Q2~_?T+J*>8axu z&*qA68v+hawAl5K7VLb4qR|q_4tvbT4Ml~@5+M`t2HAz77s2w54)9_b3F@BQwEj2Pi%8`PGO$TZq&MFVQ$>{4^&ivjT0v%XM@$Ml_R$+k=no(q zho}SQ0d)Z#M)K1ww?~H9e1#9K7la^q#p$l?XfZ|m$pVmgDbR$b+G{pHv z##)imxcydGZh64!sfZl~4%i-@hbQQErkOwf*_Q!h0zWIAD2_|9>H%we%d|jR(n(Q-ZxgoABx#K{+cQ_cTG2X>f zQy?O~l-M#4MmE0UEL^qoO{?$};i92d7BSofX7<=7ze zOQEd41NK)hrT~ExQsRtqmhw*aqe-RmcJ23;YsW5ZmD~?jr6SUT8-AOX)gb4zhrN4V z{&~@SI?Q~Z7l-J;?laL@>yGHN^Oo121Z_2;1;P<`k;rk`xB12=cTXu~d8+#*BQUqC*>vkWfrdLXCk>pQU6fSr>Ek#bWQ zH0^wdH-Lj=e-R;!&Ay!WBAMDDe+u4|0aS#!GGm$lh}mZ~NG9jF0F@+KLt=gSRmLcXMf z3bg0#I$X42plOa>`}Ct$`u<0$rcA$m7ISaR$v2khtx~4!`dZ*&{dKRV6{MU9FG-tSmNO#7}y9xM0xRUU=g^YL$48iQWYPJ!Nmpa~#N4?l1n06z(M@kao zMnZmIxS2q(l^gW6%vA?Nng<8jlab}`-3|{E5|Uf33y~|hH!eRTn_vTY1OiUEDAp_} zWQHlGb;*7w5KA3c${tWURNN>XQ2)q%8wdIg#if4ePAwvW^ThoODndi~l*UPfK5U03 zszLy(mcybF1P4A71(MT69Q;+OpvMG4a_tVFUX)y=SaXlPfl>{#=J8^ zFrjzHQvU|P;M^<_HmJh!E7`wy!1G)M)hk9F`#wJ(W@V3O))i*^>2@aqUL38$8vG@_ zE{t8_kgE{Pq3kM%-lS8vVCBmNuJ$(#E7zivczpIy{3uqUd7Af@j7wzPpOOSU4o_E= zMAQ~aU-RIN{=ok%%xNr2#!YdD?~v1ror|1}x?_PD=Nni4p} zn5I-D7QbG8K-X?{2!|oabD`@I#Dd=tKPiy{hR9FJ3Z!ESq+gYp*ravi1hAP0GmPVK zgEqO(aM#@t8R}zs5f8Cga$cEnWrwdW6dtP8VA7pR6%ZWo0L-&73y+Tx<{s*NRB952 zYEB*+LSU6UyZl9iqE(B4DJA~UusVcFOUO_w@eNYyjYj)1Yx{fr&{`*8ZpoQt*xJjY_ZNPexgWAzn7HklWM2VeCY z*Q~`Ka5C`Fr3>JkClGLr>rqqdkUo51BC7V~g&NaOe+r(%C|}i zC)(BIhE5c6_f8bFsI?nk;|ChBiX$CcmiS~|J|M4tP)l{s;jNVFi4nG1>=EQAztS^S zxHxaWm_cl{`j?Z3-^GjzzX_zBaAmx`SC|WIi?R9{LO0+KjKxiUzeQVD%k;2mD4&=d zh?~Y&@zGJSj*E+C&qG9xPHs*_|58XURqL$1HR~KV+dJe{qhi&=1kA(nn6qa+s_)-< zVX-yxnEI_r-Zv9+PdK%tXrt1-kfE^GfVprrhjzJ;1dUPrOY4Kb|jcp#y(*^gamtRFqMUwDZ|NIZReVxJ=J zFkP&Rr2-@^}BNclCo`Q2j!43N$X0RGpHEK}qXziBNXXbXgw<1Crq zM(tCdM;?6OKp)RQeLmLG=a{RSSHzS4OI|LkQbDo90U}BO))_$0&BJp z=mLyWJ<=vT?B0dE9SPwJ1~5{hf7)PHw7|PB_}tQA@m^u{bkFgPoLSvT{ub7QV_MJL71rqN#mDppR zm3omr&z<`&`juGPD}4Gmb99`wcOqp)A}bQl@F~e89FNEN8Agyps-D8!7{8YGUA11o z8u|_SNDO-$?A-0X+q~wT4sy9io)c(HOd6(GIuaXO_b`DjB_=-Ht3IW$4L9^BYiJM$ zUVUuxS#0y856xa_x}VZAd``9>LE_rvsD^Oilx*H7aO(@wx!)x5^}($Z@05Mgnc~Si z+L?0~e$s$_B>;RC;f#wzw%nf?YsSfx?~|J^g4@#!yXdoWURRJ4l-%K(LU9anVgSF@<7zE4q%9t;>IWFqyU-@m>Y;7ZKrwWo41n-9fkij`iLuRQLK?&+k_gcoi1AzO+KM8DHtZ2x-S{Ik-74IX?>~;AN+;11I5gtFK18Sss z4KLB`wqt}GwK3nc<<92de17l#v!PU|E~hm06MIUhe(;y;&0Y|^95)6|uvJbG1NTNz z6XZ%M<<@h=R34fXugVQ{#*%j}FkjX`iIgpvc%S)QKJrepKg)X#XTsXoGjQ*LS{S%4 zG^Xw~A+Rg|18ez%oe;=$suj>0POeA{X&M}9>Us2cFy>TnwYX)Mul2OJ6_{`R_^b`Q z)R*Vi56bQb&G%zX8}ypvurHfFm^}GipZ4*y`Np1ddXJ0qhfEn{|KwuiJ{m7R%m)cO0=_ICh2v|2K>O9ZIEnM_gm zhZf9JcZQ*{!wIizMrIET6=IfV7oIRJPB&{AFO3&G_=*0`WU5_lJk4nK;g>V<#M4&` z3Ka`Mri*ibe=_<1W_tX+Q)XBrbMt;n7|YGFOXe!OV#rUfTx;h3r#C(B0gDdg zd%~P+*|PRxcg;z0{Q>hz4$~h6IMZp@0QK#t<5mz%||Wk zQGaG1o^PFSY=8Sx)qAsnb!A@PXxZ2b*nD!iBZr=?{eo#mz1Ru@&30pLnxRj+mjsZvSLH0-5i!vW&(D=*_eoYHuE51GauQZ0TmLOxzqz zi*BgSjXcdRv$i;OXgzhop1LE>ULwvM0CIbavmnHI7|Yo!>{$f%JTdFsA90bEbrI8g zkrQ~Hg}5vP-p$hvilSf}Bp0rTSkTe^zqJS`P$gd2CHJzZyjn zk;5-9|Ng@>!7aMs|K^#r-tskG^i=Qe5KuNPhYo{sMn{#xp*IvExjsi>Xw)nUBg zVb!xImnRMrmC9pf{%4ZA4Gmt{?H#$g{RN&NN|tBWb^FWxUSh6sS2D+$qxp{_0-Ak1 zSEl2=xNn$zwl{b?lM(UEn2Te-y)qJ zBRtBv^cwNgK2J+}b#gRL{sv}~phTi!lc>fVWs{^S*k_Zhqlj<&#z05I_N|dwl3oUN1#v+_fyao6lA~+%I#yo?E0|&hhDpV;}F5p1$u(FfKms~V2}8YZ+? zS2aMr+rcMPo96qY%J$^LP7MLxv|Gzk64gQ1qb>s-g(-0* zik_)o_i*{F_c7tJ8QHhfxDiA-(Q^Dv`Gjyy)1Vk>M*cb+>7VkKnFI^v9p6Z-kKuD1 zJEoiE zB?ch!or5%}0;{j;(S9fhO-(``piw=qRH`mFxYS4XdR54e(wB`2UhMl>UsRhOfGWz%@HATj6bF z$gM#jx+_NWE1dEc*8yqjbD)JI2)We4{l6mJ_xB%=$ESA5jt)op4Cc^-hI$#oNeam@JTkxy=jApk zq-?PrQ7%kjloS!lMh-y`Kr_ne=V|$0SrTa*44AAwPkDCD3iOXeC%Mg2&do294U0g8 zi4y6_E28K7}~@C;V3xJ!;&K-GCYXLE#@hmI_ZS^2jSn=q_6D3 zgwX{(EX&py?R|EZ>x580u3uq+lbRfrk*WmRqCpNe`z36NP$AisLAxZ5Vw0UBbp|+z zalt$&;k-vstrF&QZG8vv1}Sk30PaSF!0djJdjEbr0Z&Ak=}UgIlm17oV59O-Y7LJ4 z3Sv>W9NOu9N+ClLiemAIN>BfXW@op+Q#40;NcAd3Q$@VLGb9XbDk&UXg^UecSEjA&{id$6A0nh8?UE_%WEDYY2B<%hVHDgC zQUzO)Cr@^<+&_p02}cF`(E|LF_tyOQD1MH5w@Kc(Mcy-Aq`dNGa41HKn^xcm_JZ#u zsfq$`?x!=nqU+K9BLWQ1$C5;<)DKo;UeIr$>F?FZSha`%&xvd)^Nhc<&hAo7qM{PJ z=qmdygUCo?*Ogx!;LN&V!$8AFeR^>QiUmA9Bt$lNHBmvz^3nHF>P4 z;)nm{U2=Yp%!zuqzm+v%0!QDU71m$U6fd{ka@h{Jk#DVc48L54OsUmWf-ta`@(e&9 z4QoBf;+Y5Do#}1dwhB~^lg=K54xn?;&@FlZlzf%hpgC;-={X1163&01xxIcaAvuiY zSRf1}C2Ali)XQ3%gosCgev94axvk9)585cqTA&V1i*L50zCl$Fqi$OAnd+UKq`dD^ zkof8;uzKv5U@H!)Od1_=gv~o-Br6KckNh~2&V4ij%Hvs`BAKT*L4&QcVOie@62GT4 z{Ll`5SsJebHnroRDNa3+mL&z=-_kCFB$%Q+gqg05Kmjxd8@EC~SBIpqs$;vSk z6wW&ib{USkIcC!LhovkLG_U18Z_@Su6UWiXV5E4IAw(gM3Bq%P_3*27Ks0PDai5f{ z$|XI+3MhNXWWb>@7{&gD0P$hJA9%pwy};9mz{{S%n-q^~4Dpk4Xl=r6f*QOrPoSBA zca-hjlZYXt3p{!hc!mdD)CS%{P5>NwiXl+WhJM*6sTmDop$lf0X5@qg5=RD;*;7z1 zDc~sMZe_be&=|Z(%s@T{v5vXxO+i@&-P$K;PVvyR$K1wKF>RFV?XX2R(vZW4xCI9qN%*T$OpAtOzYTdeEJ&N(w1$Hspd$q0Ze$ifByPL@7M?N# zO~i|H;+H%Wv3exuaFWz=`?_qBb3KxBvX=s4Dp6qqb8g{1Bat4xs!8fm?|85jLYS!c zy;1BSaPd6J4wCTrMDWyt{2S0dzM3qLF~(kboDJfM1wE*q1=OkwA){NPahwQX`St zA(1vJk^Z(WvoDe9f=gm0k@ap8yGD|}6+VXqg<`ybjwIYJPpLZDtL(x>fTvI_Qvb1RxcRy4WT59f-9%4QmVo22<5|+#-zZD~XD@@^tA!Wk@ z^6H;{x*%l@a>XWiMBM5oZ6GX?wBCVq6ZzqHVaD_ZmuUi05y(_*Q)|BX@RK6F(>R?o zDBT|y2!-7jszGD+N#+kpUy)@h>iNzTW?l7VnJ)H&j%_GDSP-)Z;b&Z=?b)huir~N3 zc)zpZ7|ls>c$Z?0%>J)K4sCSKgCu;sUl4Q~?9tnI=>XJ6j|2+`Cs3sz_win8P`rYZ zqRYWd9VvVGIRHEdNPry=!;pG75tujh1RqhnA0?Pp4 zI_7&t=c^v#uife1K$J~=r#K0ZD=IyyWzf% z3Mbcld)WP-|3*%3c6M&Ir?IQ6*zE!AMhAAK=KqGA>@EE3nVXx#&JAMc3$VZcK~5%< z{y&71h5wKyL(SN+5bV%PY@Z#rqXS!Cf6&x~?L=dnY_LrzY^@~rD<8Ik<3GH~j~_q2 zfB*jfE}X#s5l)J+rIOfET5K^nwvZTGfRD|`#eN23KLO|Y+%2UE{}E0K3k&~)oXqFM z{x9L=%^U1%o6SToECz#p>2m1f^Z&DOVrPXl(Z%X&VO12%&CQ&ho&PIuVrgk+0%iYinz1X=!L^+`D&AO-)TzRaIG88Hq$95D2WS z6jodqD=3KN<-~HZW8sY0JM>s8%6|zb#Kc$vd@KwPi-Us&gGb>k|3XgW2n>5~j z2mhTnF>U+Q{l9pV7&nOokZCmyaG&8SiNu`ikDK@rqAWB?o{Y~7!(QT15~BBmZX z*;keS`vjW;o*5F?tLVMrcm{f9Tvsww$hWj|K*WT2*Wy4G!}KSQgw zY_`$+X!FxRSn*sdrhaHrtFC;ZGm?_eY_P7vx=IYJRd(=WKr=~_;&{gF>@+6*?l-g{7c-M z zKw26klvG4?-ub@gtaW}lYwbT_uV=64-q(G7%46?^3(Di}YP%R>z&|y1;;9@Pb`t39 zoOhzoQbEkfUs=xO$+wl7`pEM-lgiX#qd zm_}JXTZm2qCu_#hZ=C;l6PJTrajj>JnP6_Ap?pLFhBvX#b2$VvmRt@Mx_5qaEOcpU zglADnd@C(o-w7!#Ta-_(4ZHZueO!U0=&8)R@xes_gkd|!)tTx%-)eG9?;9xc9Gkw? z<=LG$6JXJCvBifgJU#KP-^y$9h@`ovtZErU^PD!n^@Y3&Pmx#~hIsuv;l*SMwoh9} zV{!SQlyBjx1XYi;P8vSa;CjS<7U)h06a1j0hSsBWNy6+$+%NUubL2J;o97?^%IBSc&K^Git6E04^iX&5&Oual;jjBhb##3C zD0EWKQBaIDKhBicS315$Pj@+dYJDt(Da}X|?x$R*6&(;gweU;+<47wq$@1&$`jhBo zc&2Df|UR?A{xIUMNb02hD^^~#j5RpJL4fM|7LG-tlzI9 z@Tq6WQqEp|P(=8j(wo5N)5vak3Z& zf0Hf$?%Njx3b%l4Oz4N3FJ9=sSI|rt?py;%g}`mais_;apD)^$z9$JnGUuHkk7G~% z=`NO-$(ERjN|pGhCK4tF%s46K$Nn9RBy2+AVA|d(x}$*v41j^l*WcrJSQ$5Fk9ua> zek4ehloFm-cY)`265#|@Fm$5kC?f})xl|POWtbu<>JHA-Sda(>XQvtiDzNVndGO#i z+&DNEIaXEz6qp&mN@nk0W|6;UNu@&7ewqH$b#r_pe?(?2OTizkOPo3}t^m4B!qwV+ z6e5`sgHWc$@`3OJyc41(_Oh-fH244jE#96zVl3bXDsmKl@Psl6AJ_V-X8v1ok(O{z zxmu4*81PJ!-_>{DjNymow7H>E-VE+Me3?q|;rCVkZxy?*Ib5h90yh6DFpA-Z8ObPh z4HW{QM6CePI*z_+srMj`mMkL7vVS_iaV^1kp>_)lMKy&`L71A9nh_D?cc#_LdAu9p z|7OTkSMy0ge+S*A^z(Z`+@HhMSj>sd?o7m&bPNnsd-$5+cqc&as|{W5oo z6KB3+T+x4A^*J865X2ATK*bRI%~jz+E0Hq0^C|jiSvc=C6Xm<-abmg=l$Uqozqnjw ziW>#0P5w^f_N}2yf=2nETbenZHu|KB|;SPC*z3pZEo?zUk&GI8yc!rITwg%vTtRZ{@ zU8in;s%Qxq7rzfgKC2jlK0i+21N+8@8Sg?7a|xW_N3njWVVv-aaTf3{BtkV7rw}zx z^6>5%R5qkpZ){0EcX{RBfXd;n`Pikg$^6wU7&^%hekHeIySgxrh3Sqx!pmOFcaKHW zU@57{D*&R^-tGZGJEIcdN2wOb`4q17tCvs@9UROy!P$G?NItoZ@w&k2C>IsQ`>Z%& zzZI=dgqgf>V6-@?D#;0Kg0n<8Q<#ea&_cxy7`@0ac(F&4(3haZhI%=qnm^b5qP~(i z_V}7>%{eXJJwKk%rKJH*^~{94P}sxq_XUvl(e+!nInxUPP&C1x<2aE0c3RX85YUT( zSCTG>SupU*R|*`~Ior(d@dwNAUv$w2d1P9@Jo@s>*55}kqTbL`0kH|*z9O|S8x|(wsIcFwv#u%Y>3pYD=HN&?r)=dbS ztoOXiD(5`dVy@fKradbN`gJhUlKd!B56>7^Zs()pC+G{*Pga9HavdTivGAc7q`e)T zUwcQOM4J;}RJjTigIz)5>)S;8?{PdM&T{!nRa88li|gW**O0Zl9it@C|?l< ziGn(|&z%u6YXmD6A_V&o=C+da|FT+i;&FN! zfiD#i=>zc0w5&o!6F0cK{Nf+_k2hhal?v~kS45M-byeZmNI2dooCpknu_=++D}imn z`fM5`- zX@|qC2@;C~z|@Su026<;XJRl*d)TsfG@uoC0Y#46ZJQ$*G7TjK3PG6F3BZULDX5iZ zL1Gbmz;&f0xsXdVRZ^@}5)vngoJsdD8$ABTKZy;Nf*#d;0oKY^)yl9}%Zk>-0uaRq z#7#JbOpQCpP?7S&p|*$7L0ppR4T(+8T-sbL#vHIHv!r&Z)R%!tF=D#^_DunRr%4^U zA8&LqoC=0De#nH_R1hzYCO^vym%B@-qzV)!f%u~cavW1sqzoIoQ`VA#SEa;sjz#n| z<9DTAm^5JeRgyf!jV4tMupy-V7q|`4_>pZ1)PXU1%L(P0q}*^QD${-0*=}Vbaa}5N zXCZwN7~45-C`fMf?amZvVkDVsBpU!rF(5jL)^bgXo9oW{w33B$39fPWMmsC0-sxj& zWpWj=zV6n^{=(o~Yx?WgVP3K`$H;LER$eSM)AyHlyx3}cLfGao!cP}@ zEmBdYj^X_dxhh)ue-bjlm*D|(=F~86?QhyqtNgT51vS5)#Yn@P>l`CgKzEr?kT4iM z2f>TUoNn{YT20RT<{S8|5GMxU35Ql!SfVNN#P@S*LrTbfi(X8)lsuJ$3GDb)NTi-Zb^TGWGuE^?{-F!A*66aH#hM{$Ds=2u(vQ zPebx{bqAzIxv1e?jHC>D-0yxH^ORr#ORuOwH`0|jdm#Lt#uDuc?6t-UnkK@YasimI zOlT8XN_9g|6KPXZb5B#teN#QnE2?{dZvz<4^@>9KRnJG6`+9APV?3L0nk8qYF;`Y9#hVESBMq41ln$KyKZA$7~c+hxKw2N2F}7l4PjN*3Py3*|=Bw1Q5#%G&ud@{9433IlLS4dGDj zXcM~xm-63FDjWH$f47VmYPew}m%0BWmwB?+EfWUoJ+FNX+qrl-IPnFyds=sk;y{%k ze~& zMyKukVTE|YAb%lD(2{^9x#N^4PhYk(74Kar+iR25cdJ_OaHbRRfZ2~TvHlwPY0-9m z(CQ4vr&0)e*Ym#9w74@O3`T2^!)<^Qb}C5or>#OI&kO{ zIAHQaKBBn$Y^uA0R?P7aWhQ=yQdoX;ajRDn&=(HnL4p596D)APXQR%n4C_6smv*Lo zPcPB-b*DFKNT2;@hb1=z$b|RTASTJ8Hzl=qRu&dk+%rAh)g=2qMh8X$gZj6Es53*9 zGCM4}<@7-eX;cW1tq_upFp6Ke+`j{tSxl7^TcR zM4~&ifdAi`N@y|`0MT8G!1Onuwy%bmHX>R221xscq%Hf+U4}pv?~9-#KA3^D=76|v zkz{y}Ho*`p->6j{zzYuLBj{~E9lc)|daFF55gx2HGb&{{EJH9RM*#Sw0SQRzo1z_i zsyiB;JZRC}V5K{(*F0t;H!gQp>|cQenCm}gA2%8qt8y9jlFRdP{}2#9p>sC=8@*EM ziosl9gV(9U!tR420Q@rp;+0ki1@A=MLr%Qzc(VIMCBf86@^~l#Ad;r7YQscf>OULC z3Wa5Vp~^5bS(=tzE;q)x(TmqRg+Dz31puhia#CidhNf_9Bt|;Jr?CpBKle`G;D0>V zQGmj#Wtm_J-rd#&ItOE<81Q8cfY+W$v{Zp9ZyB3OE1Bh+lzo^1G`ILKlzK)30Na4= z$@evMmM0_>`TwiK6h}i+4Tz&#Cyz^JYv0fI^%bvg%zfB!4i5haXnpblHbZ1(d7=c~ zvV`4bz5)5*%_HV;-FBvnf}*r^84pL({FUrGdNf#-iCh~ruVKvZz|0H-7wByD|xy(qPKFO z#{`3Y7}uMpc)ii(F}QcSvD=@rACZCiRt)rgJ+CYb=72S(Z9V_F+2*@^d;aX#YwO=1 zzrK#x{O~$Iu!7#Vmtgd4d+Xyyt=?BC(b5jR?V!hw+sDrZe^<_ia*e#9YcYM(?Ator zU-33}Xv^Gi75Z58H($N}dK3d(OT}7d25sqVENN`F*li0ln2P>;g5qT$bY7L5-QMwe zZ+HP%wrv@LO?vci2(--5Sno3v?DhTJx$xMujojLdprx7X;mM>23lZ2@94fuo+3r8E z^c=Ca_Co0I5-J=TZtm{`v!4I}tMlNt^+Nb;wDN3909xUQFmQixeHybv$GXK}t^?%; z94}n1R$A@NU>`xsj#Ct@(ir-5TGop651FiKy)BsBGO^xSoluq?sPP?@dj?mw>}y#w zRF`eFFzo(p%kUEdHNEJwd4K9fbm}2@8u#q9JMz?mxli-^amW_K!W|fE9uS%tvO9Ss z^zoa@_iqy~wzmYrgCY+k^v`rXzeh25_*MXyJTa%&!QtPN&Ohf!y6+=W-(txkyR#xG32FcsmokzOrQekotG?o8enIBNa_WKd%8S0iVE7 z|7W1h@2ag!_440|gTGmOe>n|a$CY1;`@DaW*+OmL?Ot(5^yWVK)9t-a9sp)@ZDR8a zlYK<}XSVcU%$6tE3ozmnA^a99>?MrZf`;MXb6mGFUTF-Hv%Wd%^Zb)Hco`!MLR!Es zbpWXHTkTZFgh@LA?B^mJFa{J+GZR>y2_N9o0t7Jpl=wZd`-%n-d#ym?QuBrY!B86TE**C3P9d7l?>(Qz> zyT4$d^NGK`>1*bQwL8gbH%;Qru{*qX!k_vffKH@?*}+$0K*$v}A}Qf3N`IAWZ0fe{ z&}=v!!<&?tUE0;eksfVK7O*@W%b~O|O_OdrEao|$Sw&>&4cd{l{>!ng=SB}q@%>>5xYj2bxl-zGsAy%|M?ipzh6Bww~RmJ;IWlWHw_R_loi-wMx<1?(psm8p6z!T3VqI}QK<9nwHKRp2-0 zjF2d}O;_}js;FL`s#x0SqGccMY~g-R@@&BwxDmi}tjW@kSSfZNmxScHD~zGP-)S(a zp?5SGF}Nsz#`@wp7m5D`Xgen44!}g}$~D!956G-`exJ_MHzzIr)Zv}UQziQjAxV7p zx9#SFz2Y5~lItdQ^vB+;K$Ob2!P8k)4xvT;yW0XWZuA_APKr?um z0^rV`CdKY<93LPvl)z#Jy5?Gb`ZZqCI)v7UT(;C-cX>J7XY=Wo$dJF195@>l&!MRx z0Jg#N>XB=9mC9m%uuID&5F69ZH_Tw1B($3wWCuVHMDhSxQZ0uIF&wEJbu3A85v!l| zf4s?I<_5i+X$1B6+;?T~|E%^_SQy5>;Kr*EF0`W@%Rh2p*5@SpCs%1NNQnN`mJexsq952iIGq>&@;s_PZHDS{u>MFz8OZ-`)89+}{T;cFAlNguM%*X-;Om{un~{PBn4D}g>7ySt zss;XYT)NGg;B7dR-dz>;S4bUO22;)gpZAszrzeS*QWx>mOcNAl`EI5uOZokbL#HB+ z42&SbGd|$4xMA773YHgQ5OQy(C!R<@OA zZN|A96L-Ay%xHlxdxL5jUw*?3NBctDjDG>;(~H76Gjt8?FKi6x|80g-`8pLFe8`wA zt?%plp@2upk>!h-yl3EiaVU}lSOj1WQU}&amHlI47fMk-RsyaR~(CqWQ$vAcyU37OlsDGV_W-uIe@+ zWF3d}ex8`)fwcCMf6>)2w_(}OMK(71WUZy3&z?>G@qBu?boFq+_N@xpUw2N<>JzQ# zSi=g14?LzZu8%5PvKzjOosbOjm^f%(c~KKs{dT8WUIgSV`iXWB!( zEV-pUR&F|WRL$vWRg8n(4NmE&qFXYvU8oP9UK+f;I|JT5y!@WQCb2Qxrk8$y5$Z&E z>uV;aT|QqvdWNrK+ho*8Bu{J}8GB7{O|;wl`Ie**LJBPYUCs5URKE!)m+JugjSfun zT|}@F?Bv!&6Zvb#IBNM--$p)lh6Y;1QOfNGC9kj$dvZhy%j}SKnF0o z(4iBD&7A@d4hFv}dHb0_wpj4p1eOZMgn7O6WtNEDv+lb2TQ*rbo@kD+07TYVes5~d zP33Ks3H^JKC{o3-(8trb-S}`sGmegkDtUXI%LK{!LR7c#-ZeR$ZWuXU)isX zBSmQFT)cvR73Jo!aMy^_nUJ6Sb~c$tV(4P6!fgR(>|Pb&@9}pGg3qs%$vaxa0iN`p z`02eHR2qNYvzPr$eN%c)ia7*u8G_#9Z|wd_KtXa_J&%Y~z}|yln@0@6L+cTHXZY94 zw%4V;SweJETS{&=6;M^=#ITSe>N&gFNxNmsG*)h8?X?dDCByR$HkE%vBY6>46Gz!CDZ;ZROl*$Y{xws^chCFkclu4PpCu81`yNQ(kYW9|LR=mo zV4Dsb`FD>lCvwIDSXm7GdCrgJ&!64h>{^w?i}%**xq^c4K!{MHS9CncRt}AYBGe@W zvcc0+;D4SgUf|*4S8-x`%N-`zaa2)1@1ZPQvbe2DA`@7=Tv*PqMB)k5*&d1^oQU{s z-wgi1G_5i-IGM^2%eFF!pq1HhTZDv9IS`cE_#T|W1q{|i(%%g6pTU^G3cI8OyQCvR zXE=mOSTb;h6dVBhh$W%cc8KJml`?H8qXHXUL5;Bl<#cHYk;%kJWg#|YxR`RrO37?v z60bS-d{{e7m67f`I?x-;zc`{*BEe8o&a}}-aV99$+@4ubCw)hsqB%rsuBs>2`f!b0 zy#`quKq)g-wUHk_Tqqmm2$|Qkk|1A`*5HseU>19tEYg%urUo(T*)Xm|vkTx!>IVlt z4h2rSKX0qJf}d-Wro+4Pwl6uikPuV ziU_vSD>Z-jPH)v#AHMN$wq!p7^+yk5&S}cOL{$^ISsa}~Z|qcweLJ5njwkftMm}gn z(T%`MG|>ssB+@u)0B4Y+*^u7ZxRh$&3%`l19NeVl3Ei6Un~^^7oNUTO%yaK1&YQ89 zWMi45GTEb(`9fMEHJW8~s^w>L2BJXPd&p-^RL(|Oe4k4Aj8@6UWEpa*JWV_2El!6> zC)S*Zox!W>hY40gZS3b$b##;UIaBR5Q%Q0>sljax6*wu{*dhDcZ*R22&J=aXrh5sp zT2(onb2Q84bc)WVd0&#mstQJ!54Jpr6oaMv>}Rr=rU!3yqI0HQ(yH=BsM7Z*o)~cj z@X3F8E70$*>lm&(37&bYI^*ArQ)}0hpElXQJ9Ah)P1i9!=dV4-$2}nSaZ>f;XMeqv z<5ILX&D7CU&DOr&{_iQ$cD=Ql(fPCKMz)U=Y(t;|&YOzp?Ro7fzS)|zk19I)2a76) zGanbuRBJYL6Ul+(AA%ma@KFkBs=jb+hrK&Ld zObL+}Y7_qY71FaILn@3WVoV;N2tRxxy5+&=rLyFKREN)Ukk1L7JmG$)z$35Ao34Xq zQDeX_sOM@(u{j z2&?61xh4+jxLojMZIjQU2PSy0b(}wHxs+F)~vX&f5}B)k+WgbUDQ8ZJzdINd1yBaLBtCN)5dMCsGhC_5Iif6 zSj@$VcI&B`m0l&^Gm0lL!$>RtQ8bz0%qO^7cZqKiF-F@7p;U=ROu&?FkaaLLXfB?& zA_*9c^b}IprYdfiE|#ZTDGcZ@iWn)jS})PV#q$<$Pl=nkU**zyR_F4i@*IaU8tFEX zXn~6B6v7n%B)Vy)vKBzZE@J*uW)L{U2&gFx#F`0-K_nTiB#3PT`2mW#AxTMG?Jwrc z-a7ET<40xCKkbrFrn`IT(A_%Syl!prMWEd*)%icX#(x6oMxBgqm%{&Bk@U_vwX1^o zeFZ+t1eAFtY2Xe&ki@ExeN#Vv>jmOT37&bN!+I7Xj!itl5Yqa&+ky_)=Her_7ke^g z64;{vY6go_oWS0r!d;mlUTY=PoJ_|UE1gMT&uFkWPNE4SW^azz=vhfe`qpdFO-ePZ z(09g#6M&S^7MmE@?EvPHN(#G)->*b}nSC&%-Wr+bS1Mrlyst9+IP3NS4w{raMojKZFdgNW#B^ zZm^OcAc*j|W$6R=%+7WwtPmL=x6+vaN+|aFg{sFhLW-ulM5OllE6}GK84+B`jv;x@ zg?X@sJZ0=?_tiYl-xMNuiT2=VUf7^l?cJfFh3 zgQWS0!}lqN=?&Irgu9)8cQPgpx4$Jmhau7Tq6?o!)(wB!8hy4%@dj(GK($w#HG;wB zW=S~(gpGwXz3nv3^F=-wNJa{y8X*#xXgic>ofwX_2pmr79ZIa6U*G^FGz;d0kxGB{ z@FNcdQV((gQ19(TA2V0)ZEULsF*EMtVvg4(>c?gJR6&1FcKO?Oi_zitp`i+h`3lrh)62XS;_bav zk#zo+;zx7c-dSg5;`i^FR55!htJP&9@2qhjIlBQ6Kq&!&MTsA_Gz6vyNMsTO>I5+< zKz@t!IO#kz@tAdU#Ca&=#-LDAw>Ti7jF`6;0Ah(NPh3j`GQ|vRY2XRA@rLvg>7dM@ z!xucI9%a}jZ)UwRI#=#hfqXBv_){0wK}6}tC@l^G^03-o774DI&g zlk}}=@mf`&l2~#4PUM>j1H>0sClmVLoBHj1PqLPZPk}?6GOwitKZia`lrTcN2}NTB znz4V^0IwU?4DLh;{~W5T8STrj1J1fuehGK6q2Aa!tzf4HXn{B>Wc&u+LlnxDX;!gI zo#dye;kO+a@Tnz3?+4ucMbp=`w8n}$z2ZI5{07d}deL*h1}Kg$>mV=1v+HZCfq>~osEcH$6V*4Ij)A8jug>(8UM`cahTv(Viow_NB_S6x=m{h z&;carT~tNfg9*1d0C@tAbx#PKETSUSB@HeaJb&14R_Xwu1- zPgKQFIuiu~So{kz5YLl^Gu*8DPZcyyc>F!{V}sOc`6BGpyEaL6hV_Q8U2l1oo6Wm? zJ?_MshD{2o?Cb(eSU$8+#5DcYdi#1k%e#=kk9!IX=u`-p%My*Pv+gFqLgOp^?!4F* z*UW9=JHGQ#8s#3;ZgKxDayU~YX;ae-V}K>Vw@XWt3cYO?V@+&cBPQ6}I8+YqM=uie zv&)*-zniZ2p3c{Zg^>t)_E8?q8oU(s`u>2~q9l;VlA=tqWx{|C=Knq}{V~1J{kHZo zvq0h_;ITKwTts*KUGrrdwi91J&+VW8c#|Jrzxm>68Gho9dhnT&%XSZ13(Ni(v=k>V zePOQHCQVkUB6V|{A9gIg!emEfXkzn3F~+@0ys4GE|*)|EJ5Gh(}61PMNzeZ~Sbhqp7LQ-wo+vlrNEFR?$B zwZ=X$bfzJ*_HV`TOi?f=k4+1PM!Q zuK#!w85cEsPY1`K$oo2O?-FbW5Vt^9?67&6dCd+T_nAwRY53t}Q+V{+QxeK;OCv7T zBTHa(72t*`qZ;u8bsO$KFOhm+vduBgRm zuv{HHEfQ30^vjVuN+Tm-#^H}q2}g(yeK?Wv2g`JCu%=2J-NAe(O)Me;o>*ZTRR*}7 zXfA^kM0LqYKXZ&=Yf{+(60@b_=*w0%9Vs>x1JHh2Dxww7o@dB^d594SnjYA6-H5RM_XGeUb@yJITSI<+_xxHa=hM_nLy9#P&seY656klu$Ui#b^Tcxdkels2s8{aKN3#Ln8IeKGQ@R98rZOo z+8Atzwc2F5#33U!)MK!O$CeaWsSEM0XK}7-a;!9sdC-XcszzBa>nsp=^`byKpGT_cB%A-he7%A>N?iIYXP!a~f9e$^Cr|{MH6_aYRgf zs%|XJrKScyvNaR8B9{KD-~+xuwxA46cCI{Hcu4SmhydMx;>%y7LI%!6$=dz!Pr6~y z3tUmLdKkh=AYEpA**G(WGtc}U2T9Trjql?RXKth#r+N!ZcWPL0W4U3+b;*wFp;OU+ z2gaq?sfanhT=3s9e#T-noZ%wHlKao)P~^JtQ>{T_K=U6ImfUV^R5TF4hSFdl6G2A# z53#%g8_FJF>%SD*L5=`Q4;3CwD4EwL07`Z=Sl8-cBqAD3=KUMc?zq(K9&u{CiTC9_k4cMvzuS{?JTT$~ zK`rlJUIeppsbVH8sWV)KW2_BFyPGwcTo}dQjT^175y!lEj8qY@?doB-BP{#N=d8lJ zHlN-3woabk)#%mQQhVpSmVk45-JNWk{hfE6^!&{2&WY<+om~Te`Mu+KHx@Z!-}K8` zBDz34hLzD|!CC^l4I`;^{Hnx#02E`VZI&@IPB`ZspJNowV&(3;zCivTmY-6$x|)KT zC|0VOmwUE;a)?8GE8>Wj-IiKTC|hpM1x?ZTh^CXJ?%OL~|FB0*wwZ}!xMMT{C$@$F zKnw$B(>R{l7ti+s!7RPms2qwuG4NuzDm8e(fhdblD_hq9T+)Zp1z)t2s$SIGC||@G z#m3s+jj)e2*uBtEFZJ|}WiHvq26P&{NF>-MJ1DqNBE6NJ7dB?euQ4X|0|NMoAsKItaS82<&11)ykSPpsIb zM??dwo`9o`lT--Iqp`($LL8nJ-4#b#^kq@B&&=0pXVr{+8h0>G=f+;9kc}>5S*5T*lgK1x04_5pO>eNu$V) zFOXEcpB5iLE?PB4omEP({s)cxbJsIYN4bF&7%zJj`I`3Krn{_d07m^N87`Q}~`F zE#2>d8P@=dK5ve@+=+I5(J%D)-(M0oo~-2iA>kR`*o$V`RGFm$%QvmwM5Q*x-yTbb z9se|$j|A+!Uy7V~bX(+{Eu2 z-(jzCNHdvDNsiHfn0fEI@fd8b+V>(%#oE|7#8*#-x*iyNS>zuWZqtP?@N}Y_7k5`9 ze1f`)nX`UqaMww?CaR(c{SAgUB^kqm5BpC~)aA8K5*`-u-5#wSgX9M068*(u&qnJ1 zo>BV#F}!QLBG94&wUnP-MrocfT-MJ4?tdLPss272->k-lp4MBq)q z&z3pQPB`zmk_Nb{478YzZMdC3gLo{&aD z{{A_b9l9L%Q8`}GsJ}2Wz&1ZnY5Q^qp_T*R1e1}6CKD}yi7B>$hUR1MtRC5AQ8<(X ziz)}%5$c)+&Sq2zTH_QTYeHQFh36bu;Kvqr=0`u7@L+Ls@2xI8$e6z||BhhJEU;0B z6=pFPW)JPqFEgvq0qK=@wdC#oRc`-l%f^KzH_uZ6`w9dqE4d!AfCOx{_E*bpSIZ%5 z6_XY0hAdRNEbKkhB8`}Wu5Ie?bdXU)VKLgHWNNycLgwsUA!}L|N960BqL%b6KGRXg zQGL-KO}e^Ke!E?Uf5{N!l<=M1YJ_?hv(dA*qJCN*x9VRsNYjV#OIVDo? zIdO${z=~CXf)(DxtUhD;ano|vs#JEFnePFsf}c&aGhXF;8L?+PQ}<|oKq7s(<%DgG z_|Ix#-+i@kt5aa~3iUqUz=$FrK)bGnf2vH8!@;6;2t}ss$dfu1&4&U6E zeH!ba!ovRS-<~O$nR^?!76NXv-?Atw+|x?aH%DG8mESyJw05+moUpT5o7U7vf6x{= zv@?vy#lc!n1}r)t0rNm+I>(PWhptVBL#>By*fnYsjDJ@d|0Ua-mF=-SsL0#b+2E-= z4Om$^#$!$B3RgsHM1X4_g&+A3b9Rb3u9zK}5NKDnqPV?PuQ%`jbVGaIs55WYk@iYeVk3ihEO=e?wZ)3v*&<j)i@W{iC=40am{2s1!<^3Uf z*Z~DtoBSaT%B{-Tr_4ma4HzBf=R=CsfcC_=|3H*BVYNA~bqUsXa%(l2C7E0X#RbEg z{Rb8`W1NMis}! zAa_nvwQAXxk7uh=zp+9fJ~uEY+^#7+CEEF4ELI8B&XQq*daQOfxe)KPgJzOYD`B2V zj|d3IPf}6l8YKxH(eY3r zAUQf9{#heGA6N{)^D^-K55}ypH(QySctfGKDubpq(N{y?#xcWRnd7jahuALpr)Z;}LH4t9B4fTfTxE-;3Ux66J9^xeBE*w=`HFUiN&)pvjDVa&v z*14*InKnr^e;hj2ge-IZQpdxGJ|p~xj-zW70_V3r?rxQJd81_yx5@;)`_^i*sAZw; zLtM|LKgEu#B5-xEsMt_TVxbOuj(ns;Mo_N`SY#CjRFNA&Y-;e@BE7K_y=Pdwm(nid z0)`bWpHijrKl;HGa&<9)_W_de&D5Q&>#Yxh$TzWW$C3h{fwO?{XB(s6@;LE<}c75n&A}9Dg_eHI1d_V35*AH(F(RN}* zkv3IdUzZWZU=XhjwvYyxLy(92m#WUgX|f%pW7%FH|3IL)o#N{yBV~!|0~QHc2bEKY zc8-sFzpq*ie^MR2DS^B3vWWB`T8Px^(}pXvRN^|1Zi{482RoLV$n!RVQ?t2{E77MP zj&+spB79{9FGYTd@M!FT7WHm7JM8H&Xq{+LX`2QZ-T)XGuIMm9kjzqDDHUJJavI2u zC#k+#6#W->3ir1y@!vWV{lwv~)mJ0pU9DvF0cYb2)7Fiqn}9g4n8cCj3?V#zjZ3HN zM(!!MZn@{<5n6L!m(S@N`MZW>9UW?^-kKSU#3SVf9VJwYdTsRY5Zz)b2L6o>w?KPy z?ztLXpCHDo zK`OB!)48z~0O1J8B!q7^qu<&T6F7YRVaVvM7zHLJ(A8DHHFidM0KTryUp|+-oy~bm z9~dyS)bYfr({Uv5QP9ua_MgfIaI3UogdpTrdq`cf)3dij_fNBZ94_LqA;n@k9pkMp zzQm+bph};*aI252WPE?)=TGyu&y0fHID?2h17k^kWY7OJd)WovlQ50zQbqdrLWHz&RZ3c_N``&8bh1HWCDm~)1{ffsf4shq=!$=f0ek3f@E};5tN$hpNsF7_LL<7`b_IzT$NJDQ&{joUi&~K_#+KgU}~@dfjd!HNCE9#7HgLv z=~ng+qfN_(qF0dOy_(Bk&yHwSz71gNiso zXwHaQ66x>MsPY-OaE8r%g7fd1KW{mnN=aA6Py>`;?jQxKm>Rwyk_e^E8tDcvwaOn- z1us?CIO6meL$x!H^^bxYyME=n1(bKGuy!NZ<4VxoKSCK;zI}dR*#P$2#{_*IzjFo!|co@MrKNk{=!f&*=WZ&b< zzIr2D`%7A|0rbx6!G;?p^AIO57nF$K|GD>GEl28rL|$t{s7EjYr4l-lDy{KTnO9f- z&(gI4Fk-@}-!QCKWKasP;-IRxPi^B7`CRELam03z{Al?GM|2FK@es!a7InA$l}88r z#NUn6yH!!Ntoq`fV2$jE4YFVo2qcP}k(Jv?l$37AI6Nvc7s`9G3g4dnR4j?ze>{-0 zE{6I4K^Uwk*fQ{Mbz|$<$JG)GgCjPZ}aDWiR~pbBQ46=F5WR?UnIN?xpLO$CUiJ zw?%;->yj2x0ep92%Ui(6TT;lopcpRyIwpV>skc|tY`t=R(Y?gt#!}lW`!@fz=(Ddw zQG+i6B=_gS!#cj@6F@GnadYQlI)>!^=6{@OXEc57*I(L+q9H~B2^UTnoyeFBh9E#v z@20Dwk;g5cxtQw8m4Ci$WujYleKjz0XF;S&sAn;vi0$DE`*1d8cJh)O!YrDH$T_^M;@MC7D07vix7Xm$eOALW@T7kR>ja4;%iIQhta! z#+g}5XEtfWVDecjar!nR9XltW&_^{Cq7c9HtLbmAnpu$!XLJ^%t?WUp`T5DMRc-!zx zNQy1Gx{j6mUP?gUexv!z1^)8i;_}?87g7R&Rn*$5w2BEB_ZJ1X)*ELOXVj;@H?pN! z3p+|+7mm6)A443SnB>9&EM*llu;5AbL!fIyw)u6?V?(3aA#=NxtU?24rjvzpI~E$# z;q%Ry0E+(ZEN@Q`Pu}O3PYCajoZ-$W*R?Hdfc|9i{icgTQ^yOpMdbw5ojVP%_KK9D zQ8L&vb;SBRnX;;lObGL>zfW7C*H+T5J>p`eO&o1&BP6n!v1zsj6BcsDsRI+39F?vr49G>Ap%xe0RJqsLG=KASNLx zkMGXSAm>p1iiBi$Pg0H@thV7uLP~AThPZRO&Xey6sjZh*Jbyh!m^*hty%&9Oy7asG zVst>XFP|z;IGl$S5$-ejjI&&!Pw5+)<&VuR*{ObzQkXpz0@!4$_8O6S|M1;2s~0y` zZ0>kge2VR$nUb7%9_)2@BxLZo=ziK<7Z)907_%?UpX>4|`uGiy1CrGb&ibIj;Xoyt z-Wtg?i+Q9ePDePlxu3?;0m&W;p!mi0OK()yWZ*faYZ@tp-%dGVFv*Qz!J^(%1UQLp zuz$JSx^F&CxCTRms0p5AjCKGU|oi;9v3wOJF&~z;6D{W_wTC@%`H)#)~h(@Hd;0p-PGJ?;rHBs{gZ5t zbffvd^_PC~N|CO^(=M%iQM@z77vTNxyiGwB-HtJTXmLM8GCo-Z`_eA)y z+AQNCfi<<|lKhA63ER?Ns@ax+h^xs@kupzR@vYFm4BoA3PcoJ^o6Hn=SB|csftRxa zprwPiH-=Zz*-zgW7iN+vA>^dw(|RBZP6j_RxKw-(+YIJ#qB%%Oz*D{($yputymO7~ zw|sx$ACVvySwLG;93k$0r24ca?z{r7R&*I0Q|&SrpKRZUdJ`TOd3XJ)&m2FR^R+)^ z@Vdu2nnTAz<6}1a=IamVLJukSEn2odSFWefzQW-&`djFvQx!%(+*TX z@Z>EE5rvxygH+X@9ARDgXmq;B+~+IUp1WImyxx-`_pa+`m)r1Cs?!m0bkz4cqP?Tm z2n>8eU?$H)T92(;{s5Tt$2W^;6=puzLKUU#u-+9#*bvom*ut=Y_@=ht`gr%1yAPope(%;hdpj92Sf=2OZ2!Qfz=HhNBD~fUt6=4b$VHe|q50 zd*V-_zQaqW)=#DqgNw5be9@?r8)TfnzaISJPUk}?O>Be(sKSQ2Ye~gTqpf_$De!WQ z38J7g%6`hIeTyX^(H&DQkLnr#_9ddn+gD%Nt_-p>sxv0V!bu zwU46Qebh$mE;zVxLzUQFpv$lh{twM3ell=tg;SlV`Gn}g)v?bK?4iC*qevMquBY3# z1P539O5H->_?H1fjVVQdevj&e<>nv_vAZCEDjvz5Mj>&_#ox9e zfciA3%zxY0x>|$2KuVG)*m)yUg zjk`#3T&xq&&>s>0j^{eIAR+j39doOy0IZ&%H((ybC}@Ne%_$LvB;Zh-xFY1iy&q@a zJ6<^wXGetp6+AfZ09?Fsg-(Jj zuY*Y*hh*(wUwjT)=RWB~ak8!;Ejt*gNLVp3jh2M2a=;FTVZVH7EHn?(=5 zuD)8B9Si#TzUg2T^f_9TN`$Onh1D0JAd^xJ!Ex&OgQM_QmR91Y9qGvs6h@f%BM@B( zo(?XtWitAZ0!LZU%P4<9b9$AYcZd+CCvneK{#MNGEi`2(Ey!Q5O53^fc(mp$4?7)E z&KXFPy}~i?&(wrLn)sLd<|2?idxn%Q{QrZHLt z4ffzTc3Wr6h?GtYI_EElGYHG^)tOZ^grP59^eD=ZLidOkyW29hCNVC7J7klln=}wW zf^3n`3qVn}^!U5nV{zP$B%Gl%S3TDUcMgSk(7Fj%ch97}E~`P+lzdmU`7G2x)4N=Q zs=xFSPM5~G2?$Xk9P@#oKqL=HO&$7oSRhbO@ZCK|kE4Fy1XWHvO~HFQWQEY}Y6+uj z!#e?vA-NBNXuOwzyy9zuKj5O3*F?=V`KtqI2vpl#W<)9FPzWXhE8+oyxLutBx{$$q zZw|ym54go?B{J7R^?cC605V^Yze(iPFQZpWkA#lMS^mD4R25U%f-k;uc>}zb=pnn7 z-XrlcA9gg(Y7do`PL%mXAzXe<w?6*p(A5$g0>lst>8V4l{Bl& zgj6^Qn+#n`gLtVXRNi*?dT63Ve5CA^HE=-)3i`SyN!?J7oB8p+0`JV(0;@RH5 zmj3N5m8gG1M@*d+cO~T(=bHyg>4`Uf^eU~r7OB$xGCd(6KeE$X#;ZD^xUHk2P{@9& zb}cf1w827nIPT^`wE{kK#I zZ%INvq0Cn~xA73A8bz(i>%r2D+lganD-hrQo!{d(ALohDCy6Tlly-3CSH~ykVTOi3 zY6O0g(oHh+9IrB%)NH*jX?d&>%OltIfL|6XU4R75#;JZ7)~=+#Q~yb)-Su7{rIrjO zO6R%=Hj($qEmG~GET>UjHUo7QX&G*Y`+Q0Ft~{DsuOa-^zZ=P;Y(B<&$)NDwMVGu* z_uYg>pn(so+XK}p#l2&`q+{hmOJPXT{rh?PAMpB8ZVxLNWIj#k)gQO0$QU@grK?Zz zYA0(H-ck;;&|sS6l|<{BOwC{WHIi^;f{L_!j!!0?Be(-#oGL^Yv{>;r#*zlg12op&M_#Y0)zhflX1SV^h zOJgP2X>#YD$Tbvi2G*j{O?MF|o-SiXc}3rG!g6Sg{4aG{{0&F#=JbONtdSa=exKFL0*XLKOE&AXNYvcbu6k6iaQld&AAwcdAknmVzK6tbfy zl0Y5Cg6gj}WleVLY?-D_PMo>bvC{AHj-XWQFNwC~j~!nAV(9m$gikqhF+JuzeeJ;W z-0`I&l!si>!~00a;Zgl-TMsQUJK$a}dsLBY<%#R2teeA(;Aq0cYBJIQqgjA*e{pKh zKjZcCR4Nd1Wr^5WC8d;4_Qan_I`~vAlE<`NLemNDl!rPGNp;GXyRY!r+bf~`FE`xX z-Dl&Jr|Gd@&cro*Ep3mrX*NcCf9Ca zK_0*zZ94ea`iEzNGjoh;VC1LN5Gi9Zne(S_EyY6Ccxcf!N`axthEckW;nkjz8x4`h zjmZy=l36N+)Q~JDk9i1^D64N6_+L9?3opL~=H#!plAm`+278T%DV#+GI0jh+U*RFw z-h>*Wd8HC`5elg~EP>BwJwAE8saMbo?|dmtLdot$C5zehPD`3la3VF>?zeGgx!H6{g1?wHcwB8};izMT1x+nDBLI^HCMt$ zQ(9Uh*x$f4%*;)2!YAXg5nsH@8jUMA&dY*D%Pp+R=jK}%y|oS-xEQIp>2N89fUU!P z<>&bv(eoU?^pZ`_DxbP4-6;Vu?v}Q^({zER&<{@!<5ahd)I!DNw_eFG=16dY{a8z~>IxLhTdky2@Vy+00(Ie?!tzYwj=9_;?i+ zofnYKHxyoJyniCFIv>T2OZke9ej-=0oc8g9PoC)Srs^AyYfTql1!ype08UtGrM1Ss z=9(F=rU%U}UW)f-exnymrOa0ghpb53GN`(L=khl<2{w1IWaa(&-M-COoPMwP@Hf)c z2tuJjn}94MTxlsd&CK|Dqqfwmwlckwf3bsvJ;EW+1Y;qdhpRTetpDxZG4{Kq$fWh5 z*@MTvIZsHE#Cg39fvguw4b=0!&Pv_o%|#yUZVwhIROJV#c>n_>6-6SmJGus%*&EB= zU6|SZ(57K+V<7Xg(fhJXmqIWgC zNXSzyeODlrnxxJD_e84lV(vxf80!qF>CDid{E^nX5E9ZPjAq(OpMTJI;>xuT4r>dpq$y}qb?bf>9^m?)m(3iDY)f;o*(<-B$ILlzhuX5< z^GDKP+4)ui#TT8_@ep4XDg#VEl*c?lm5k@ciu3%^kjlo7){Xm0tC>$%)qjDGEkX$Z z?n;Z^T4nb2J$&h$6}brZ$DhAH{-}_;U`^s$w?4nwi&hycR2n{fCuFieW$7?&w?FOT zFyjpc%5W@u{_Kho%+b&}=Gy&tZw#K{xmvJDB@5P&{vR1iGfrn2-P>tvsZ+_4(2RD9SrO3gg*oV z$TAxDf8-92`s!2H9TT!OC^^v7}%nxYS{>^#f%p$6;+8mb4|xd6smpQ`wYy6Eax z&PgeDR>V$F^?&gucQY0JsAPz|i9xAJYlKYcSni!_l~Iq-d{I+Q{vdgsb*?xH`-LVy zYPpKVMi5+rB>fl6)d&96DjRWd9X^9yre}}INJ^D=Cf+6?s!4d_on9`ztyM9 z`3TUEy*DhXK!H%_58|7mxu&0ZJ8>t~rBv8CGyIGt$2iBzTQ&(KZEdY|N3z|FQEEKe z7%p;|Qrw?ZC*9x+Cw2;`|BNT5XlF;h-tdh7+8#@3{8!2Qa7X#Qwc^zg>Y3;DxkSGi%oVjiP|O*D`GQ%~{)`+?a)dIrewMbB*lT zgWKusIsJ#l@!lSn`S)`P2l=rifG+^O`r9E1tVm&hj8pOj^cEZ%_oo-s+aGxvf|*ma z>^{8Dj<9?5;?=2jYMNs9=P!nb|7lNcqrT(;O>lj8epz-XaKrsB!&g-oSI(O&7K_5%m^dAmwKk@?@KAdt}`CtAjY)jL>x!7s?@y6?WS7Y|kl24~n z%Yh%=+m^$(Jnbz<-v=*Cx08O}^ZV6$|E)x1-poCpy#=3T<%&X`@6Ery<@|6yHvu`y z?S&7G_+8>B6ji>@=Eo8>qGj{ilNArz_H)RA-!lF3K1GqrA7Lkdv^LUkHdO8uRE43x zT;4@`pgI)d{Mq-=KC(7fz&pCc-dr?9oVg`&3g&J+#@)TM97BaU8xMaBdjkKX|~71P-Jw6 za5dsV6q-GsrO~KYxl(;09 z*%ykMLxzk7^;67n?C#d#LuNZJsV#ejSKmU0(Nv!j$6nG>|Fs}f5c#A!XeN-HA*^A2 zYa)6)>pg3!t**4Cbf)E^fLwDLBd=2~f2uT&MiZrlvV1|YZC}JQvpwR;N|$|9R;2jL z=8Nx1eD;L_AH-Vn!y(4$Iw`*pBK@IWIp1|r>K^Uel}CD|YS-V=M|0zQAC18{2{i^R z8%7$rM-Sp&xrQ-4y04kzqF+={BP{w{TgUBme4{(5fP?t5><7o60H3Gc7xAmA?C><^%$se-5^V%3$#A5e3K60DMfy>1|}APgD5a=Mui z@zzz_zy9<7E4iZp!?ZxoM$PZ)1}o9t#a)cI4>YL<4`b<^_-LjYLgh$0vcA7MX$HVQ zJcou5$0ez)9FT6Ay?9y!CqA1Kq{diMzWLXq>GpM*s{mQc(#fkJ>J}m$?&=&&PW`## zyl4N7px6=>@u@a6d{?)_PsMniZNUDke6 zRM3sE>=8Y55;POQWU$^HY+r$JT&QP#0e#)7QCAXrR96OSv3zNl$NtCl4RNTy} zjGJe)pWZO)7iqZjmCJOUF$dHa8)wdw6XnNLtaA+R(|0vC1Yk zl9ITCu_x|e8YbO&J|iS%55IMO4Wk*f2y!w~d@F43HAD!+3~v|QMsQVk-dt3&GmqkK zW7}4fm8Xj|6D!(cvrr)34UiQ|f91XBAx*s{6%sq!{Ymiw?F&%9f;iIO8jASLJb`UQZXdqGKDd1!}#d8_q z`{ObKe?~|7bKMdj$%c+b@>0L^Z`y4A!OKTqOp0MIKhUH^9YVj*b+F4+rI)^2F;T;< zO*jAe^8*y;7vr@28{ZesxpzqEki^UAKRBuGluuymf8h5$)X%LR@pA^T%=9L5m9>hS zt;T|lP%k_&{bq*pEk%RhS4w~#3w;Ry5-E^r96|}@3t--`=f2r{;rD~-EoHGk` zD%d#=mI!c37-~!gi&q1j19G4#;ze{HBC(44%QZi0gW$($!N=UR)i@Fu974cS)A7Iv zRZu-a(98j)thyU83N>j!SRcUj64)KWf`euOXZcV!&rr4wuvbGU8#m;v3i^DMyrl{% z&&|&^h77j}js%CgXok9ng?bkg{78xEvIHbGNrXWjd&F4?FdFtA9KKmg#kOKu0uN_9 zgVo7~v0H?Ng|XN4hsAhC#1~UFpZRAoNu8r8*rcL@J;S)VAnyt+03_)WK5F4G@F_g# zwmjDdIBm~5FN%kckCO8YfU*;t=m0KX6s@lw`CA>@lk zko7q|qh0tN0H?|iPy3Ch2H*j_Mgek0St>;-wELl{H*`epK^#SA-&QZ2F)1Q|p zsu8G5Qk=&Tp6o@Oq)t>DXo~}cSeL$7g&b#c=eS9`;q@C{#kwOj7W*wf^gj z0Yp|h)R-cJZH%PLg=_-{DJeuTdWW#=AW&5>sW}843U;O-cmGNr zn}04BcmDN3glvSlW~w`YBat?t-`5jQwq?If1>9lH*E3-x+9sbnO~o*~$Ke8J} z6mmEh5RomR3s?*)EnFin5`YmWZzL2iyx{seq?#;7)sFFdid?<5JFoEUN= z>=PplG9FKBt4Cgov>DDVDZ2ny%mZ~O+Q+!!>}2-(`4W$A1l5O|`6eYrO$aYIg>n_e ziX=7L7-=GwTn0~Ghoj|FH1`L;%$6jJ0-Of@%Vg0d#Ztae^)9Q3IZ zSsfO-oGVGQCb{FzzGhM}G+*|GwH%NvpYkrBqXIzElH{+6gJ((TPsyQ<%0cf6LP-VJ ziscD~?8w~UW3ssiqax_;41H}+`t!bWr zkD}`tZ;je6RJ|DygZhU@O2-f{%V^I~v{kq~O~x=;Lv!sqc5~C3>^pVVk#%ecQoEtL zS2}!Uc-lP_b$cgT?P2|GpZaH}buTjOUM|!*mJ$av(mb-)Vei@9+3GwO8hl<>D^or@ z#?oGwHGduXX@I!Mr3Soq8~8=dOkAYjHzKs$n^K-P*GD!tmNqvJHMj0Iw^O$ev!`7; zEj=$=`XXBfN?V48T0ZZ#e4%a~6K$Q)X`Oo6IuqGCSK7KT)cSR|b(y+tMYK(WJ8C!^FDc$gO!dJ3oI zFhR=&n$JAv^2XErLP1q=xOOg@PHq~RBrNfJmDC>%L-vuL;UTwh zln4CgCRMOxIGI0=_|XMr$3g#+@Y7zx`0tX9p`fh?p0~%45bo=^1g8AeVU#J zcLnGqVXF;@(ovTz43s?=Vn9jV3=f(=K>Qj)sAPfJIw%RF1qn{#OYo9pRIa{Q-|M@5 zI~HUFB+N?;b|x8ABk5(WY{_mY%#r4L}=?GJ201pD>_as9ToTs@Rw6^!5?qvnKB%DhWb%=|#} z@K9?D0~h8kR|f=FjY!A$pj!}%mx!dQp6Be0l}gS2@d7(PHqV z#-ree4V~}cWZo!Rf|Hi9WS1%cmRm&l5f!9S5~Gc-s=atX@-u)1ALGHQdgNhP+`QN* zscs)B9=w2oZO2g~U!*J{aghhGSWBEW+o+bvKLir=ayZTF%Q+3;r)R#8r}jjR@;i*T z+=Z+=jf;LB7yrxb0WZ-kw0!d4q${eSe22rDZatE)r;36IDB zqadw(B+N|{7BUGlvHu?g5@B?dFrG;G;z<~MIs0!8iAW$dG@P`z6MD@F?av5p+W#m> zjS7U?tAvjN|Cb6&aQc{wW zlarE?;^X6EV`GVZeZ(IlAt52b!NGxnffx+t?c28mFE4_l4dMB7!jlJthYtz&R0+3L z2ue4C-n{Yk_4V=b@$&NW@bHMYf9dM#>g??7jWt-f-paUi;KX>K!C#uP~wUe zLZBcgkdhKeKz|SjBN-VvIXPKb+3VM@OG!yxy?RwbLPA_z{J#@OJUl%A-9KVwW&Kb8 zh=GCO{}DeTBPAszAt3>QKm-6F>XpO?m;ivl?3z{BjzBOyl^MS0|KC5d?HURQTKPMW z)To{NIaB`ij+zacA{>qiq~g&2Klw*frAD9ZzG_>B_`gHH_DkcI>*QCFG*jNIFc$-bH&7Ux3icgikgqKH2&Ni&DY6Msg;7PhO@2V?zMDe zP%MV}5Gc9Yex4nDYtJX%wzRIEd`EP}R#qKaXTl~Q8sLeIp*S+a#*&dJVB<*WjGsQUdJ+(KwP{$>Ec%|h@IU^MF@F-}t+ae^(}c~u z_)CASoV3IE?dA1|%`Dex+s${*B*oa2f1IQo428%){*j#!mJ55> zksBquQ=H3Lu<|_8ChxJWS87PAut%ndb&hUo)=#=@xdE-655@0GM55l)^$P-|-2}bv zvYKhT-SUQSC8gzNdpo<8xQm@0nhw8#!s^75SzC`j{dxP8K4B}2d_h@+Ug@-T>3-d! zOGr7Ua&Z0@d2Gtd?>USO=#Iv{x*MvL(hTuDA0;J3mp(DAX6Ck4sAtBp5Wr*QsAXFF zgAVWuQ^~i!B6@1n2v)t$$5*xYZXu{f7oN9Xy3Zbla)oX=cFyc*9SsN--QDawK2%Ue zTv1b!ilXz->n3B}+_V39e$-O=<O(a0e@Ia$U~ z(qfiZ3S05agvC)=_f#WZxL70RSKYj`qjLR*+p{QBWSH<1YT%~}o(z1RXeilg{7&H+h!a|Dl7yi~S z{n>&to=g$HLZvTH3rwxumffn3F?Yq&SrHeu6@ATn7WaK_n!=acHnE4qOUgb{t{NvY z;2VSwfN17YJ?`&hY?2HHX@VhPV-X#3{(eCXp;v2=6mDmEjCW9h%7nkjI72uu&CM`1 zLM+4!U|x({8f8>UPKE_J zMLmmL>QA5K$I*HY=X0JC{i9VW5S14v0559z^#_G4iz8x6S<3x5U+hJ?21-CJF33JdiNXcq zK*Pt_0069i5wVuNq+GQCMv7yOR+WbAN(LE*AegmBw5Jkx#-Nm$WgKMjY0Y_2nf^3H2*VOl7?@WBAjsB8J0w}q>4}!I@9muy>4elVP zaA9kDz#OZ_WIsyjlLZ2j;C*lte4$=O^#`+NI|T(QjO=kf3rm&AbL!Mb3I0>1Sm^!> z51t7S#Gm=+S>MHU#zZ>_7L*F~DG&QciW1m^=(aJ$ZvC?vo?{-4Ut1x(WUD0RxGqUc zD-i>(=Edj$exP?tLr}m+`-d=b%!uZoHW-6?N8P?Mg8;LHfns0BSsDPiPRSirS}k}1 zY_V8FmUakR9&*xlMm}WYraw=5r_z!ocyA+{^){CPNKBLy&+1Rd^l*=`99Ae(j^*ytuojKgVQd`K~D7 zFIz1jHzZBZ}Fst_g93ksCzzpU$uG=VN&E1sQ;uT6H)Nu zrT@6hnmHHvyjSZjwEJ28c>@8r6!a<1;aY&zF)96XV#x=qJ=O?I0_bvvagTGyJ*0Vt z3|5E|tASwHEMK$7;WuO~eZOg&Dt?wTe(gVB#?z-L*Pp{EshT$$`(_mRC3EARHk2&P z9xpZu*!ar}K>+DJUN}{pzvN#87&x;W2823qMgSO}V-sXFDpZvZp48hvJ3iWb^}R!$ zEs1l+t!#>q#c~?xU^Qe@4%oJ&dTw`D<}fuPP=10+ zaDamoHs;1?Js%f6$ze~NYL_Oha@k3Y2&f6<`VcMoPyv&el>LyouNAgEXDbFSYy( zkv3b9ol|v{IUIAQe=!B|ehMz|kLIGGpg520zLKIB?z83Zz8Tj;_ZJCcAO&d7!pIO3 zhnCv0e~zxbRp_Frcpxj-(x>o4VR8AdQzjS%{k)|?zw^|YN*U(-yaOS*s0y{G z*HBoz5vStX#W~;LH!v7;z8ZOTkMe`pTNf?qy2!R;+E}q~hJdRT9P{fAW#+f&FMb`| z%g90VSOW41W%IYtrF{o3zYEAU@*8U`zrX6tpElortMoYsxuS7DajNavWE@rGHz}m3CQ$Gh zG$bP4VN}B#1hyjsk&kUaIG%g>2)td`#K>-`%k*E*dV!QSxGjk_+|R$Qw0;}Kr=}KU zppm4eV*uAVfQ6C)x?nQFt+zXr7}DMVk`9oY2*QAD(n9PS zLhNTlY;3H+{yOsOL16`&QR|v<*RKMSS`-%0WF$Nv361m*5N&XH$BQBJCqwnou;PQ~ z2s3gDLLmvW;#O&j%zAcdY2g_S;aOqfw>@-zyFP55G;HI8JjH%x*2v@QDG1N7C)S4c>IrZ^c)_7rrpNhtpUf>*#xHth5=Qi?(io+2y*eG z`md}~<5eKBxUP6g7n2Xq{dpk3t4GRJ{H8U}O(`Cb{6dFb^>SKgPF%A|2I-M|9MJs1 zl7^mzq0bU6KZvk3Dj77|=4@I^hDVB|#eJ?Nk(-09oFwmp!w=G}lAUR(X^qT|$7qBAyi}6b3P;|J zq6rpGdKsGbvOXnxAWfRZN*GNUIUAPPn0VbYHQg(->|-iLuGQUMMLs8(FA}bH05jKf zdheC?tthQjIB}8DN*_)64y9jioN5uCInBbqvGxMft0-r6gM^zlUj20lA>G|}&bGE8 zZCD{wQI4eQ0}Vv>UD7~ec46j>aSmyKQu&Ep89n#}1)tOtC-1OFaoeko0u&dZJ7}Vd zgr%9s(q3TUthsda*#B^m{_&4kMRKp$NpqpGME{6KF^|tAPrxpZv5JDxDNk%ZPa+~u z{mnn<=jr zAi(8z4xkPHD@z|zMPU{}VRk^m4}Wi|_}f!Fkc+gL=l25Anhu+XY!%zwKGc*jI9XvRRNBlb0NKe zk=tRfu92{LmlSK~GG>&N&6iN<n&$sTP{j0E1S? zmtLDM?cK@K63L;~%t^i|Ta;4LNOjfeBWq{L0wl@0ZL`R@CDvCZ@FGInA0<{yDndxE z9t8w%c_lY6gIv&*;mFioyH^R?;UiS#XY(wTe43?5+FXTmyqmb~z zM+}`XO}KEI&?l)1QT&Ocq13BYHO+MLY3SmvM-%O&((LWVI6x0DL{lo^ zARcu!nI5$|^R;2r^$`mx7QY)5h3i6X5*<;b;BU!6qSrERe8^g8H2K|FK;5Xt)&$Q~ zAd_rV!hrwi(bThXU71U)y3um+tLZ@PR#n zJa==RPQA>_`ej07y~mK)%8(dLkK7$YrtV}caL}wc+jL@=IiK0OxZ5_k(6XeHi2T{& z3*9}R*I|+;slVGvEwMi zab5Cyp($P9AWS4pplL^zTgUuS9V>eXyIE^YDbbT`IX(nDY} z2Qq1z-_i7+{qDD*85B9{<*lL!9feIZ4O!avO|N#A+xu3E4dt|;W$z9#+!|aug#5vP z`+Pl~`Su;L4WBCx$43ox?{!5-AsvT7P%QWlo<`_kSURnLaNUzx!jo#ijV#u#F0ITF9hP^NCLOItYsdrJZxlwX5rOy}k zA3U=#{R<;|WrKgB#uh!ZBx`ST`V&m7@2Gt0Q zT$Kux>`3_VVi)_95lU66(2!d3{qbLr38-<~X~1M>b$xipFQPU)OB<`3A5`Rc*>Et%|3`Cv>^?--$0qmC~ zl}Q!&SQ3m-o;Ed|me-khWHu41%cU<4r$xVrK+SklPgx}Mkvqc*gyAJlb7JDN)uv;Y zziO5JCPTjV_K30Dw|0{_clrQxzC-hNvi2`;!BE^A)CxZQ^7jwJWknml?F3okP#Xat& zoX?3*F|Z_n%pVEstD75Zt!@@?tN1hdlY{Y|!}9vqd2m9qq8OaW(VjvXK@!|1%T7UW1xy3#NCl@7_BIySF-Y9HnG)yZSZvHex=3a{2_w`P*Zvv5DTf{enC04># z>cNumluXE#)wQ!H%j6zktd`cTW8(ExmOR_&EhMOPYj< zjYKw6`IuDn=uG+UjoeS}Rivbbhg5aDDn{gE_8w{d9_O3gPc363ZM)Ou^hBS{J&u%=yYI8oPQ@Gg#fr^piSKw? zhm4A4`|Poe?A>GT>PJYxgwu7udH-k3I;3*_>l=~f>>uK_Ka@vyuC*PYUmb#T_j{JO z*bXX0QSjHCJIwdD81Ao~eBVE#J$xZ>cysB;x4%EW+~ZOvXp=h`O+67l;;%eV_;Mil z<3PCbNT&D5Lt_8$_iuB$T)ZgavmqfnY)@1)89K%TpCJv4B9o91}_^v>D4S7%Reo^LIkL%18o?%nTkYAhz4XMen4ox7;`@~CQg z=i}8MeLqfXew=SuG|`~orXw_zZ_kEcI=FUbKM1fe^<kb?ccP^yB~u0OU|s`>OXHsv%Gg zl_2J7i_Ty=@ux}hYs)lI9Lm>@Nxqwi0C!*Io~!m|mIrW7x3Yfho^A|Q-if}bzGGAy zpuGN0WK}aKJ&gNr@L8I{w*GtFcPhcGk9G`79+f}sF*&xGj%0OqdZLXe)31JZGeu?r z;V>Whvh=7bpQ1yR_fOUsW-G-(tJLAl_=WZ;1qWBForv1Oo#qXEY3I zU5?zs4ivV(#v=?4Y{m<9bJX9N)T-s@Y56>f*0Uh&1^C@xkd1Dxc~yj1ot^85dw5gV z_r=6FWk$&zqhf&lm5tDo4%m)_a&ep;+ZyKyjWF`T&|_7LFc5<`Q^tw+$^O^&P*`29 z?QDN+-#rQW_T@i5zXf$WV?@a0HA7!qNOd+u95nx^?Ym3LmkG(1uEa8Sv-BVZ+U8zx zy?Q07N#lBa9-2l+b!1H!IC54*62b@OR*yD|tW;-n?3U7)`X*YgLcwIV-(C}RJ+i+# zswFH?Vb92)TlZpHjfbx>L%(FhTa7X@04psNWb65%IKbBOaFyD$#u-83cz5hp6#5Md zfMIxSAD^r9w}bvZtK0gg`!@+>47{8imxC%u!lP2UQngBx$r5#rfX*0U=3BYxZ!+RO zs;bFc+0!0BChABJ{-q;f(#!?K`r)n;qne*{Z;(Zb?Wg8<+`3ZyR6l4@obK@d6~9%HMT1*yrAkx zZshS|qrf|n3HrCKZX2mDI7`<*N4z`v6gpGsDN_DLWFCwMVz?1W=j{1|iL5vC)(~&o zynfBRXwN^M_**o}RaCS*dXZ066@iDXo}~TJ?aj_30Vn_D`0lrV8%?s{fh$w{;(q#! z@fT81b>P7$4=*;5!vIIz&tPD#t8Cc(TU$vatTFynY8F(FJUUC|;U4fLW*Uwcs^OX) zwE8w+o(tzF(&FbqqZix{wZSrsC8J>)_C^RDrkgB-72)HbxD1H@P`>L0Z3&3`jd{T^uhu)(SA%X;-Dc+*Z9H(Ojwfm11D*FbsZxw5=G@g4%+c@Pd9EMy zzD%1ZxTr4%iG#Z1{Wy*^1H8RcK38^;fJbiyBRhN5%%s5=#fTTKYoE1s8hYx9F z528pBnKK>-UwL$m&>ea2_w%c@jh{bQeTuwW^PDWyw%=Jhh}5O(HZAKBpJTjZhLBIu zpi^V#r1M1fsa2$0GTks$%EPpkD2sbKGMRIwFJ&88QuNS17UW$?WlZA8+A8vOj+{BDX7P34kV81yH z=VcdC-0A5xJn0Yf43xm=%d)Y|Ww`f$gHvS;Lb4~FKG(`98! zK+0vh$$580@nc8=rM&u0NsHPVlcVdf=ksXNW@84sy3)IM$}H}%nT%ViY2CH!=e~%i zLFm<$SG1NrhMqkhnV!zhmNB=`+3jv^tEz`r=Q2=H0Z_htt}v&U&tG~CwYenJ)dfpj zb*7I0)O7gX#?Qg9k{WYGZ!E&{MhIy_=9AWI9$pjCue^;f%qk3+V%Ev+EWJdR!x(T> zuJ--XqL77U5sf+lt4eQjcJ*V$?$$7a3ZDAkOS_#L&_srNHD%8k6&z|O9kr0{3I{$Kwr=HQkPXfLhWfXU!Cdv`A15P z=TR_;WH%_DpU@w9$G(^4nRK6A$dOl$z0y~als4F&qwo!v0L58uas{(;3YGb19Q!Pu%kSjHYwAWH9_e>+fxM%;1vHJ>Y>JQ&Vp9Tp%^bVm*@4W>Gz4t1FDk{%$Qnb{ZTdQGm@tR(CCKJWWMlx2P= zA25-qpPMrCKFue1qoOJSV*V8Z75`w8PE_l{dfYKWBGlw+Ad)whU3aEg$s`k(OA``4 z+QK_+FpZ>GS%?%q*PQW9Cnm%{Uhe|fD-zf9n{k+uo7=<7BjHKODuFUgY9umefSScdIjI ziTam+s_S2#YX;x!$FPNc`dxUzm)0+s(SY}76^S8i>Wer?`xmhB)nUKP<8&vB;!y%K zgrT9htraMS_4=#0e$%aDWIM6!!GwZxeLm&K3lC3<3Y|`B_nqb|6N|5}6PK-PGr9?< z+I>~{=(8qW*mLvH#}(cRmB$#TH{gLCQKzEYTs3w2eFU|Xs{XOQ4e^1O1Xo~;mMip0 zKLJBW-!ZuL=TIFVF^0c`L+rH2KoWVW)?aUiBy=0NkW+QoX!H5p=X;9W_lMQzfyvP@ z)`rX@*G$N%0CmC{vpX^h4}U$tqo>w3MD6V>D{?ldKtn2Kq0XeF76q2|cfm#f zRgLkC245BHKhzKi(|DB5$lw_z-!i1_K&CX@=lxJ!FL2PixtUT4MvZLWWN4J=zEj@? zc{nbnfE_lUBG!eB9NTIBQ>Zmm!~qymT}|XA~(DqbIhqY8m)T#ou~YuA~K1WKWvBx?_K(TRRW1#UqEX@;z% zUOz1!WoXpG6~~bdbmRSgjwN~Fp3>+Lf_139YCySMN`g2r9A<|aOF<1M9RY$uuo1)K zImyH+nOZ7^Y5`sX(3pnkbvh5<#^;5)4p^AEr>fXxY@jbN2Rl*jMx0lxE4)7*+fqb! znX)bhli7{G`O{xz(MD5F5YQ0sUmVMRsae52S&n|^>M-bLpugA1A%IAa7K_fv6Us;F z@6M_>G>w)R@whsH7#E;1s>2XW9xq_x?0|Ju{0mvK~y)ocHwD8JiwVx)NpB2nU)taMv z%L^vN5Dc2)&1RN0+g-k3_hCoSUsk-s>v-?EFN^*)eV0Pi+us}5QgDi>qH)W#1mY9 zw5GMzyZiALS`_R6yY52W@K~Euu7!k@_QV_Wu)8+#J=VDqw(%O#sR!}y z{WPC^KgF$n%832+{B~xzM<;t^Icjww`B5TugRRH7?F;wulbQt{+7&eSieR9X+uM~S zfNq+*-OGp-VskpR13+~;_9=ph&Lq~mINr~MfJzJ|dPxxM33VC=#V}xWjtIlV;`NT0 z`zculGnQYicGn#AC$-uQ9l*GcmOX4fJj=4Z9mq9V_=v+ntzj{@mF3D0#BvOE)V za0z+UFw6Bgsa>E*F|r6iT!KifCUO|KQ5YPt8-B5hu}q{svJramsb07dznt%Yn~8Dg zfcm6EUS7cl#gd8nVIyeLF&AuiTlA*040#L3K9er{c^PD!Ls z$39Arw?%-}X5x;;iiAErBR-}Q?qw!CR*W_PqD9FR)7M`f(+lH5wtMu)wAWg%DL0aO5Ub3@hBXjs!+O{|pa}q4Q;rNX`78@t+8AG2 zn+#gJPDr>Ij`$LKwUreuhh`B`W{q>z$#iWy*N+WO?}+(DY^^9_#}knlj3yBE z#1S_@66A6MZF7R2qqg!03}XXzy`p^XrX5W+QzBRBez^e5{#r@QN9-DqpfgKwbru3kbV9d0fR>-Wq=M_xkz4#yb$aw}Nl1?Zn!&Gj{1WEN! z6mlmua>w-U#EC^2b-Xj`0CSQIM%AtQ#U)0_y~9(jK`YSAp^&PMyn?Rd9D7WBKnMXy z1lLDYI1sfHDKq%AZO7NqB`XrgiHx)&FM{m)d&{h^J4III(~T-`605h#hX%TE0UJ;d?i zgf{yzI*rkXW%oEN6i^^7Y}kk4;xa@K|BwW#G<4O)h700;L&Fx zhxy(Qe#v~Rm;o9htMAQVrKNB)Yg4n8K2d}|Qu;pUYYkWZ1P;qkM;%{>83JE1hOFqr zJuNc?n@hYWXg|AwivaWGgVzrgyRjf*Dx4Pp9R-pl>6P*I&QG%rA&4v{pnpnWm5bF% z_L=JSnv2}W!2o=4oXZx3{JV(PhBx5*!Jza(<$A1^987DS;LP#(jG0EC;j_#OU(KvX z19iS2H28B6p<#nz-13sbiXR?cbO3ZB4!RQ^gNS~NIl1H1tM&>2?*;03t}=f-rl>z! zmTA(Ed+0HaWsId!wAr6iIf?l*0+;#>>W^4rDPoq5n6Q1P!eYRH8Vl`fxI; z0wYC20{_|=0N&%4y^Uo9gpEmx-C<~x*ch8wXUv&S+TB;C@ivnGVM!{>aUZjPt$KJx z3B#!SA=5^LsA^3dLjaIH$j>OS5(W;1|K}w+7spS2`?1ybc;H$7lcN#4@o$VFfkvul zzalTP2mv&=AKZhw$w7$waek+)mS0bI+a{}nV8X@!kxAAt5Uc62H@;kLAWl0sDj3Ef zA_ql}`Qf>Ye`i0gG-$|dbOsZo;P~f?|9m)QG4==XUD^kesdU6gG;HdI_y?q2HunCm z?f#XBhwwER$9o2){tDDc3#v2$s8nP1mSfCcou~hv9*hDCW3ohdnX~YLE>4fx=A#Vd z;6x9j^Pb`WrZLMcR{_(13ayC|yM+IdN$F5;6GVZb>KIon)q*`^i@&~W5J)jEMAV2^J3Z?X1Y^M_;($V5Wfa0lPZRHwg{eZ(~Vzh0C2SHd1iw1A#if1dlHN(~?BT32l}m*3u+e ze|f(N4(gM`XdupAe50ZLFVWPGzSBppe6_5+1H8Kq4Qq&x=qG4j4WjuN=|d6K@E!k; zB5VN)1Aw4ZLY_y6K`bG2?fv2-j$s@Tqe7S*??*n->UBJnn~}QM7~? zPT4f_7{v0r&MCvD{9K9b=+|*q+Vg-@vI7b&sOf*H`IUadH}}nZ!=!{ zs=db1OM3sj6yF{frzP>COb zS!$af6nlGexN6y?{;ofsTGabm?xa*3+DoD?Hvabg3-+x_yNDm>`4Dm*@Puys`z1QC zj;SrWEoAglS)FmsTb_o?lkZ@C5tELa>;L?tujZHXSU3u%FsHe+W)4%RKxk`)gXYAI zI)-P-gQmm>%}6CGoa6Sg&R;&2+o0!6;K>gu^&8YxPZNlSl_n}ZW7y4$$NAyb^o{b; zCnRsgB(3e_^@i10f{q%TQ;K=`SDu+h=}^NxZrfUbKPfoQY}*H&6?pT@D>YKZpYScH zg)8f_+au4lN)H2I!|Ywv!Wn>R5YWIGN(({omxp@UedjYbZd(|<#gn$cfV#qGU$Yz( z{@f|g;9c0Y@R%F_?jn0aa7SCp7gU0!bhj>HVK{ukTPfpTlUd9+F*iwigt+~AP8Q+g zuj~9#!&6~qtG8NXa$j$uf$&kgf$Dp-dX6o|9}%BHLRhfgGFNH0XC(dNIRT&vw63Al z#@Q;^`7OV|q29=?9ZsA%wUov43kun zd@n8f?I@XA|EJBwQK&4Rc1Ma>JgXwi{*gJ~$8sqxerE0o)mPlZ5QXk#*GZZ0*NEo# zcf)R4HLb}_D!S&6lh0l$j9)~g>S=sWUk4R&se0wAJ7NM-7Kk!TbcMTd zR54lY(LHio$yn6m*I})?U2xbkGCg=X)hAEqN+t$n@dw^^kOmu_{Nlc+6~*L1X-N7L_ zGC=5MyvoTXMdYpq5PqdDeK8;{MAei&PD##wHk+hpQA&Tg3}&!AA1X66b7K()I&8M& zOY>rZ4;sKU@1FH^WMl+XWa_Z0_G2w2qL`ZS=s}I%^u&Pi7`hlKZjpd1hHGDEy2a{I zp_Zd`T@x_d-uMWdP$J5*mW!=DWI!X5K%+bMINlH$m$nvHhAl^tk;1?6>)KAdrQCT; z;k>C<2-D;bMfh#a@hELEGEg#=(_?Q__z;d%a+n+K76MF-`d~eKjX;CQEU~ZtfPS&XV+=xBVqz}Eo`Qy}BNB7o068QciZUt)9 zERd?tu+D+JgbGa@rBRWhScV00cnHqse?l$q2tkJ}fsdVYt#v`Ix1kpLW6w!z{o|3> zjyD3!1OKG!BeOUjz>fig5_Apz5y&Ss0N|)uP+jU9A&k1BpJp9lf0yMK~ zDwPkAx1+oMSkRpkhA~coS#lBHVZd94I3&oKBHAQ|hOiR_;qb&s!`nMXl|}rYzy9(~ zqP_D&gh*hS;Od^4byuP%vlNZ#>H)7T#ghqe@Q~oz@w4{s9p(B!GI6_rEV|aitQy}) zwaTc=4SE0^B1_Yh=*yth-hD1?xA@L#hKixCNZ9utMe_QTfLt9#KLl{UVSSMB;tkgw zDk@&3Wx|KK4J?NZXjMF^OJ`!X57EP4Va_ffd0@YJfr0oCRwJ$Ij~g3cH!6j)iP--P zjd0<4jhqUdj~0=xqGg2QNdSI>)j1C2FXvDet3};r$>!grf^{YJol?x{C3eql4*ZF zVj#8{186Y72aSX25w*?rx})eG`Lq;{czxQ0DfPaS4L}=W@aOW>fV!=lTW@qFFukNYBBCtOHHTMfRh%6 zG|q6vjz4KBWyASHM9s*5W&O58FkCK3!o@uaZGf5bqH-VjM0}FH8k3wL3T4lYs9}R< z2LNjaX@T#;!i5??HhIq~k3Q%Eety#SN_YG3(8Fh~`-erlzadrUxR#2iGiL>-#rig##d9;GVXs{$L(fruQgS48qBp zwyQjpC3?tvr;L3BspiUNf)s4PUIpWCJPP|Vo=1vSq}KPM5V)rzME3w$IH>9oSlNN_ zGV1x-@pOmZ)Z>XHn4DJZ)PN(d=vPlc*EqYDgQb=8qSfO?KP3CX-q(Kv6z9rF%5XJB zTk>m0v|Gc#{Xh_b+-Nh3gutj6GU{YlYxS^X;Ni%U7pvJy?7Bt>00!bn3_%$9;@N&g zu)4CSr}=`K#YVp@1KFwi2oaJl)xM@PX!(^VasyVeBu*{Hpg*eZ0R{sfPBPvZO+|Wgoyt}($(ZVsc zr^Y%8d4FqqFX{8x4c|Gp;8sXyvm4H(#O9Ucn7_xt3aBXI!cCEOH+OL zA&aFh#5LW(t!u&t}Zw!r3)YB&?B*O6^=>#r@Bxf~}i9E)Tce*Oybe3e`5 z7OxMv?dQ5}ioci#0v1Zj`PFC0TFUi_X9YvoII{^1R}8iPxT%L2yh3y9$k>u~ebCWE zefh=)m|-BNmo^@bw%Hqi zLLNJjGG)+|om~l&76Hjc4Da|ihd%^BM!4k(w>^MI-DXFd7|&z)<)zJ`BRYUuRx6(!~ zFD+{&YSUfED3-E?j8E*7I%JD@IqJ6i7I;`G`rw}N4<6IvEsaZd05JmS0$I=@BdJ!G zof(p=1`&~B>93;|TW--B61Cg(wgaqo29#aUkSQF{=;j)49a6Ob`M=!J59O2Bj3p0@ z=TmYHs?&t9IGt$T3GjEf_hxg_gAnB-v@gll0RZYRAf{^oV~EBS0CP(T36c&_Ef30f zqrfI$(cLN}CQ1dRPKg~e(EIH{f78 zel5VByox*3k1Z3=er*=;pGUlwN@$4P?t`6gv4`KR)kiMT>1qt>3b0{l^(}RTBq$%0 z!SVyrfpS<(KKZa*AuYgRP=g{UFQiQ)%SAY!Lz~e#-L7C8;BI zO^bf1;b{8sC}Gc`%ykgPRuF)G-R3Xo;lSLH%>fy)?F2z-t84`gnQ zT6tFcOF=mKj%qk^lzePd9W^%UR{9dl^^es@PxG-O-^AL(lDopMf4(-WrV{L=5{dIOi;k3l3{qtJ+WK5o5GQ+wfo*Lv!sF7nq6{#fcW z+|ov+u{Xxl(zBtic2VSTSq5KYamyy@fMu@xUkzZ`DbIO2#va^O`R_hfdOe$~ z@6Qm%vwEK=EUI3bUgg*S`|)s7=KF~jga9Hi_vnrJg8TXK>t!>uKcyu*OOAl~mr~c@ zUpJzFU*5&zHDed|4I%wi+~8xfdUI~%$JPQceZxE6`Z%MbvO=FkqCHiE3_{sBQa;pT zQ^mKJs6qLm@qAzN5WMRn0Wp$~zrg!~q~?wU#%uJ*nfGgARni7cJdFbIs5Ehe%H-Lyx}s zOQ4VplKuOvq9fcgzPzvfx%iGva>c2io!pnyIj+IVo|3M<0cs)5n@j=fGXSanLSa75OgrF)X_G?QmYNep zdZ<}S000q=R)z*B8B2Dm|R%YMG)T_PF-^^F6KcO`+R&1wxm9jqSm zH{_$~j)Y>x?@PGSFg**EV^}X_F>pPK_mRF*M{{2U7XTyGq;hoxOZ; zu3OJ3cPn3E&rR8HcZ`T@oAi@Di4N3yY-j;vHCV7uYGHrsMG$%-u=Gl7uhnV2SuFe9 zB?jMsx;B>RZgLuf)cd=+{BHS^*alH-Jf(4R-)uhzY(j|?3P&8&h z-e%c2CpnMTF9&zqITC=7tJhfb*vQjh1HKv<`Z;gQk>M!t`&~JV|(ZR2w;NJo!7<*pdX9&X0X!%l#xzHrT!t87$Twrj4Sh!xoHP z70@>?-|u8x>a<7@RPn8OsZUV!yTgbN3oBsPX75rT_fP$M6-W_U>RKYA_(w+?0NGe8 zPm+)Q8(3s5AJ^_Id8au=6|!e4UnQvU{MTtI{^DQWkm}4*jd|Cr7<;FrklVS8CMEBu z+9)=zqH3jMK-PFHoJ(%FAo2ucSSAyM$; zL1iH|>0eIJqaoGh>0au;t$i&ORROA^f1hz-L&q*txy~8`N_U#ThihTywBJ=*`bPu8 z`-;Ln=~00G5x(uV2|-BIuj796w{>ZMJVGcg5m*o)S{c?pIlsn@gmb?Sx3CC(S9Yx? z_gE4ZKFu}k79G+os#Htevk&G64d{$^1X^1_|2~yq=QYAPsIAZ%5HGO z4hSq{q4aZgRuv<^A3X7e9g+;~DNRBaQ}iIkkid<$1Ck!iUn-CJhVS5ji<`<%~|DV#yPVwe%{+p@5X zHU#G}-e2Kf-nQ-Im8IV?7#|{kL4zbC*0eL-n@cc!A%kVg!mm#PbSyy zi|E^dJIG3QgWb*D~_1apcID9WKV^ke)x9FCK*J5 zFoWc>GUKNo5c0~k(?j#t+V{?x=-(4C|h6PMVUJk@_0*zuuO%bW2g5z}PErdPI3o^rU}& zmbsWYq@23P_gv9X4zD4PetttnW3;xYa_)0E^(M@ag#Rne#yNdD)+2bN;M%Bxxe>D z_`SP3I(!cEe3JC!_=I}+rdc#5UV)T4A2fm*88u0rh=I6c9MWU-b6l6l_^Ta7LimMrK9|pPn&zVoW}ie9uA9o#4Y2XUY_cR}FH5Ys?ha$IAk%6f*h$X15u? z3M+BeUhpZ3SeGYVo$WISO85YGr&xzR8-5|(FhjuNLTT3fb~i@>B1Ll-nfj|EDxq ztYany?d@*hmf}tz(~j22*lpm1D=l0qTo42XZd1n1ty6|^4?-8Sw81bY9K9}O7J^~^maDBS z14s)y<6`=IsjU_%o*pArPKPIXGOo0V2v@amIpl62d6@x7$TA>;#y|mL*Ib0)SDM14 zR6;LrhTspyzVVyp=~>?TM{feZ2|6?C+rBiToH892^2?jFI0RAz^$)QHG8#COKhGVJ z+7ZvlGjJD~&y4eQE5_J}i2p3(`fQTM(`ZX&K)hlBu2{U{Dud zBr*UD_ew^b;Pz&u@}o)P7jxK1B@L*~w|CEerb9-a1o8@M65aK4`S^Ujl|wkhPe@Owt3TrzDo_e=a9_|LvuC6Bm_YZy91}LQz2n=d z=;cje&0M)e_yCZ)o+rv}Zhs)-))n!l)+~n#(AB-){&rCZ@NAtO!1JvWAzz1D6U@3; zTI}Y%trd9-HZbCC4%z=+4h8|I(hnuL+qvI}>MYMtc;G6#Z8?bN;Z#m>I&ybT-|t8L zdf@zvPRc)awcxShCNU|Lp#WU@(^mL%cM!)!2a}A>N@^&aSkP^h=#?M#uE7e+@64gb zQ?ZYvNU}Ads9{YbT*CXVu4--@MzV*;IKDxk-1y|EV&!;>yO;a6dS{%S3eL&4;H!&p zKaJA7Mo>zjM>N8=^$y`LLvl1X$}Mk_Gyy~V6G;G>S)M$3BN>4I`2`ujJ&Mk*%e8DJ zcoMixr)6su*=* zf*ssa=PX;L^%Mz+>mtEkjPmGWtnu9qcI0hS$l>_?T~gHTLeq{G@W{_pvCPex zwh%S3RI?QN?UjHJGG+#D@vQyyUuYe>?$<|ttBFyt_edZR0QCFEFmSSht}qHB#~9*r z7v|jC{g+|}9O-^o14K^8==9SmQHqYT{EtF^n$sL<^`0}`VX1HGaAo)?oW|nrDJ|b? z#7c{F8e9I_lU4(QNsAee&%VxK39PK34FU`SrdAOE7E zxJEv!o2vyE?>XcULD$ew{_Xf5Z$(wM*o!vDG#xc|`=gOU?0ff*)cI(0wS>Bl2<$z} zKoE`?C5U+XJO%2!#O>#P62azEY~O`uUk}p%m$ESPzaxpxfMMRC>vAi_D<18{5_fe9 zZWKErmHkXjLIuMR34BTlWKG@$ZkJ#o>ZF?+T!b!%goB4Rq7VmTv`aBd_jcdP^bH+7%)>CbId7cBY$iUW zn*)@@rF4PL2;9K;)LMwU8$c-Po)_?`*351>+>6lXm0k3|9~3+t?>{^G;!V=GFMr`@ z$oPjvAmu>jNC4rsi3F~g&8h^Jjimch^1RoFW*bgeM?`wWL4{kVq9Ok^?hY6&;o1d~ zHZ@$VQ2;hYhw45&X?Xv`4781UxIZ{^>@q_-opRNn{*x}Laix?rZh&=pgB}H^V-RE@ zET!lgU~Ab}hR@n~)^T|Z9I%;^%!<0+E|E8lo{&Or8@XUyYDty-2-PUb@HzE1oU_8& z#Y}@EJE4?R?P6TKe)awa-KoRVMlJ*wgSw+B)J1iS%*I#hluXTyN^HfnAzB~n8gDrL zm`w%8kXXh-QfmE8NG^mJvOef`6p&28GAr(i5}%5sH0bSTb4jY)$zc0@%=xo%GCS3G ze3C&s8f@fBoUVnSIHAtTK-@QRqI;$-v`!zgLkZ&LY&^d0hLXHE=3b~_44*`3ZvNvQ z?U~B>Km52k}UyU&8 zo#H^inzW-vb7}Bid_?m0onIB3m%s0m= zVAk1^LReVB{*pjMvQ+g4LKE;tLXuo2>rg_G)PN8`6|zHbcOt1KDLJbttSP}GQNpgE z#wZSA{J0~n@r<$4|7i==@1=C@Qc8Yr00ck4){T*^ZxnNX&S8L&mrE2EFRjksW-Dr@ zUOW~nqw?(qI=7WiEqZLu3z$*X zm=`8QGby;R;fhthAFGgLazfeX|9x_jWGTH?e>y$B1@ zEh!z2U#Ouoqe%_jc{rECz}oNX}PmAQfYPQmlIR-^bp17>N95wOKwkX&9fH;sq5tf?;pz-6siO%DQAg2~4ltlR^IIcRM^9-HG$rL12_C*)^U7-Vr9x)@$i+fajm zJ58UrGp%ILZDN{Vtpw=np4+~sZ7f}cxLYDbq|8u;9K>jmZwQG!8VBRYx~~?ku1*}T zEXCht^;fnE>T?b}i_*5X^mqd-gYhMUyA$9E|> zo!KR~ndqFj=v<_&OnUiQblh>~miMd>4=z0XmfQ+tY=^RxsY~f$&O}WZ`r#6A`KePz zwu^m`vZOlLYLo~Ps8=cTu<^q2_nGrZD+k_ToqZVXmDT2TMF;p`Wh*-PG&Sl{$qGT- ze@h(u&SqQFw)-tMz=m}}RGUh4hc@GFKJU+cHZC~xEhNgoey_5dw`3B2RoozN3R9KDtK*`!)X7M)}c>mq2L(eRA4e3Vw(34?^-cta;4s+2=#w zfAo9tJ9z8k0+kEEYJer3FMKTcDNkv*EXhZM8ekn> zr+7Ql%2Iic}i6#Q%{`Yr>9*yRI3 z5Gu1|3zkB$y-k*Qj+M-fcV~z)Wq87W8JiID-Ys~J)I5xDP({Lw8(Ez51z;7?VgDvO zQNP_1Yondnj%yZ+d$Y{xS_AVLo7So*= zG6Xw0VM}O97wCmLF#?S&`kCgF^Q^DcThjKqaPD*K+pF;-A6~1PlmW&MGK1Sp06? z4CYBsKBLYnRAhYavzVVlUr?3DxzNVGEW?FF8f{}9jK~)nUgcFV>YFllHFapU*}M>} zOBYSO|EYuH8p;U!$Z6D{tl3d^@}y9^Jzjemn#fGOZpUXgHVz*w`!Yd{K5SIXp* z(x)~FlvKHrc4b6Nd!&D!F_!Yq2XcZicd(-PGuy0$Plc{|+8Zm~e(I`SD#|Nh_SfAc8qr=`sVOU4*=DU{MNFO|xyyDns@A zii-L_Jjy%?^tp)IMNYg0;&Kh+JUd_enemPON)?$$Ixzpu=X{7DL)W@p6xrqqLnp_B zP*HWeJLmaj6Lzml7+n`v)Ulxr?Sijwa&PZ|77r&dmx=g-wCUmFE zVc%t5(E28{<8N!n=WI^1Rt^TttBQ3)OUb6mKP_QhU4A4DF?J1&_U~KlLzxGyha@?S z`rDqYYb>@DZ76o}6!dk%J6KU2pWoK3z4fKvluQM-S7bxo#yk02n}p8p=KpF( z`1vH4%%!u+i#!BfBCj+)Z9ihpQn8pmLKN529NxUzZIHsu(e)M~hrZ1!;(r$mR3}NZ?vLim%fk69lBUw$jkNZ+hFNv#=%A;|j~ z{tPgPxI?*DKW>Gtvi~dRiW~tuuJ1ozFZsM444_#0K^{`vQkB1|5xF^ExJ~e6S+{ao zm~C|Hx?-|();K0sA!=BktubnK+m!k90QB2)>u=V*!=nq7gC%U0YLE;DYfkhR<85+v z?oREs9esw)l7A~N)b;Iew--p||LbQXE`iyVuqw@0P=pc60*G>l$rsSjpRUxEjz4^Q z4|v!P@%)aT8zaTa?lW1bAxQgKxSfMaAdqLp8eDN3(!|o=dUw969G9saGG7XrJzD(V z1QMWl$y@j%A&4Zdgl)X!mutpyGTEnw?n59cjt$8!K?HCqAxcvbH^LAfA}(Gdpi)S% zCqg{w^vL?|Hs#afqTb_4_0?rEz!$Q$?UXe@|9{lc<$IrLXS!?vd}jbO(7z5pgg?(d zUh5l?=v`l5Jkff-%DhG=g^BIB_mbinVtTefP$+9s&Tq3z-@6 zjU5h1URF-mNh}z)d&{fmS|L8%2WJZVb4?^wJyU{8`v3Sx)kZIkU9Z8CvkNVWIscxV zKk!UhZgiW>S5A_7w4xNGa2`g|UexSXxUkZbB>SI#^!LvViCn|_0G5PV#bJ47qFTeX z1avf8S`tX5TK)E{SiR;ExBItzogH=(z!t)=J5cz$(P*vx+ek9Swx6F`9xA>dK95pS zrgq({xx;}y;>1TwDWxi1sl)g#8sI?XKj3c*ubF9dX1Xp8mfOSX*KXckZf%Se7~A~o z{zJI;(f%pJtc)h|6EBibw=uTElsYf`b328stj;!x5fz@&8UpwYkuc@jwV^5Wm8|7; ziluYJImg}lMuf5hZr!2G78SMj9#=uklP-C11sat|V9w!+#!TRd6u=QZbRlntr5aRSZxY>M(q z;Vkty8+%INoF1Qhix+3RebYO>d%J>*{PsO3UKb(<=JO6u$%2-(!^l3*b8Dnre0os8 z^0-GhDT4Bo@3dj?s`I;p{7+t0J-=7X+Ebhth47y3@q2WsA)ATTxZsDO`1i8gk*>;* z*R3gfL$;E9K0NuZiNF70c`FkfS+ZW?6dAfim*1=K!>I4B-0sV1qp*Vsw!^l2&SswDPMT>R*Ge zo)t`ooh>+ZJic7-qj(RQDB8vQ6- zhqAnY*c3O!ay#In@4P|E*rA5#HNmM~TatYr)nL8#kMwn2%)ETF7cjA8(()xtvpF1zllDC!i6O6UiB#W-4wpIQTnGlgl6lZb|kn*c;@-&&b#3yH2%z$t_Q7c*g8uZ+v3Wlsi&LfZ&p@*7QmkMUN7Nfu4GuM z%;4euR~`z?g`-+kimk86BDyq+yW*DqtA9xll%E;%fRxz}!5< zvQBrMiYjE*>TOMFeQ4HeSAvJ}!%S99m5a5;1k`ql7gnhwmaYL6ukAkn|M!pFMUy^F zi4Z{R08r)LC`M9wPL^}rVjQm;Sx7k-y~gD;?tfA2WD{t*{bFsIt_BVQ>|pcPYE+95 zH{spfE%xq=ae%rXdFVAK?1bphH|aCL%uRz0zmq;PAo1FM?T;0wC?-~ZXO?6~4@>*C zSX<%tU@ozxm<4}l05xht78V`@Z=E>2*G_^tjFj!B=BR%%t52zpE@RuX89@bEQTXS2 z%3K^A_?(kC9)tS(z8lt~x{pYLTZZUu<;13G9KNou{T^6L@zo^kC)qR_ChX4DRxlVa z0`yz=o>dse9FsWzGlPr>5F+V3)yPA=%FL8W;;;eHAp!bpS{32)2Fq%@>8_#$W zsRa^sAr6vmxHi;c`!;vvYGZIwlXEBE z_uN)sm5fXw+Pg!fEq;N8-$?(K)Sj0l7J}}B24bsklWS+ zow3lltlqPnM?HH+PniJ!PY$Zd0heh^S^Xi~r!Y5FdEU$eN}!>)27bDXrTdUh{x9>- z!Yjwe9qeQeZDrps?OL^?h)amYFOl$5Uo6TX<$-0hf?oz;EVj}aeS46?Lb8)i@{c2q z+;5o6tryN8cU*C|!-cawH#RO*2@`-)=j5&)s}RV%mv~8;o=Yn~VJL$2OufSz*8rpY zH{g*V#>r5^AloT z%=&BO&A0#tNL{Xv+DoJ+C=)C%82ziIiM$*ek=f4u>*dK@-Jq#Z-M*#&<5kn76K%|IB6#?nJ3Za7_U8G5qE-D}*O39P|UT3efp6BdyPG00? zW-^nRB-edk-;V;&4~mVs2QV*fKBOPEhomQ2vQZAr{ zPE=cJC0Q&w+(otu)OHyCBp^C4n}6`mS>Czi7a#7eU)Ww`s;)Ut4w_?q(w7zl*n#FM zsen<(Tsu0(F-R>On7m9s74^8|a?rfU6IdVt$#$1fnx-C0&v10-QN0JH#pTzzg|(CD&Z`N*_t8iO&O7E2IGHHRBeZq8kS!webdMJ#gT1ydWwsKDM?{$s zBVziArK8jgV~%AcBGnOEGc1y^D$?7WOiT|X`ZY%T%h_ia5t`xBN0mN>MUh_Vvajv* zSf~J*UAk&>KJj#Bs}8;r3~G2%KwVvs+m-J(o|Z9}daQ_#fJYI0V4;;L<#awRVmPA- zjehzg<}skzn6B-z#S}4qwm;sQf*Fm|w328T)xc^P>yLK4g?O4PE|CBs7D$Y#$$dK0 z7|*c$bXPQif*-BB@jl;0(`ARapNlyin698oPSfpW~P^W^ARjAPEyBZ1=B>X0ND5`YgRA=#5J$j35wK(~yM zjC%>7XxVdksEJsL$qda05g+Z--=!n`gBfM`2i-vezPj{+KF%0d`jk%WR3$p18XfM3q&I&o zD9U+To<3AJA%fkPDI^^*Mo5LB(8<9-WpFYwJ$1k@{XzOZ37Zu94`4*8TfVk<;isDp z*rgZ$7m(Be0JNI~jA&@4*o!K)7e2Z#i=tmT{Xw@_2yJ5T@UguJ5P&S;X>tyI8nyYE z@AE+_sn@agocxmA4wBjT`D!s?l9c|;N#bm;wOpPO1%}ftvK=S>>-%`a(zCu#n6t)S`<~$Xn|KUy#YW88`13{_%$vOTMu?XxT#SkJ@ zvz!9}xqx^M$v$^v-)h2CYR5;)56Q`=kjKQAOW}&TJE7!VgnjY-<0cBFa)Uk7y+2Sx^vmVnN)QIxw6tO;1rbE=B$5O z&zsxSg$!eG$0dj-2GxM2SHU5z?I3nJG+!&Te|$`M<3g=Dia5N)85;w+!$B?tc8ih} zic=mIzi2K#enB$}P#NUV%r5c&gAj#XluKyu_k?&;^@kL4E$HU%NDAuADT- z%$2(s=?hdZu2fPT(;+126Y!|tlp3mWN-F{N8;`0PwPfad{Db+HwiYMnqe>fiHNSo} z13g4Iwp!d%uzVEtl|Z8!YNv96Q)aG8ma|&Gs#@e_wFC_y>v%!#3)x;d|5cTJEe{QF zv7~luHt_PO!+91*tv40bzI8gDHAqFu8xy)kk2sQ2m1wxD-{9}ra6h);K}o}- z!G_0Q8=lZKhDbDq={H7rHb%uZMwc|k4mQSrZA_qPq73Ph^_x;Wo6=&NUX(Pwv|=*s zZ_1`=&Q-KX8znG;AYMYv#U;%pR_3nj5j^Sh<}v0OcQIjFE*h}AAaS+4Ch78*>E zh%kCqm2K)c#1DP?5DeOK6l^2p-+vO=>rM+q;?N0L=uKlp*I<8*!CbZZAo`^fko{|IS~TuuD&dFR7o z5Pkd-46=dB1BN%^hCjtouN$KmjFHl*!+QpUAkhCV5p6^Mf}+Tj$JrVA?DUNCeEJ^} z(aG=skcbZdEfJkjB%MH$apR{3^WETAD%uh|0>!DEd%QQBh%G;hQ&a z3JMDTQy(Iyr<0SC$Z@{p(9ll_p_!SPFJHd=w?UMgocwQtC^|YiDk|!KV2J!Y$)28M z2UD_{8QEBqtc545C{+8nQy8L$4Tzu3x`yYHDg?Vq#=uboJ_00|NtHU0od=9c^vxe=$Vr>gsqrUR71~UlI}d z(j~HtFj-85jO8V>v5@I8WE9;$3=s@Q27?EAxG7YToSfXh86p`O85|DxFNx^?$q)$$ z2=M<;5)nH)`@bY2W@hI9#E8&nGzx{HrKP2zp`oUxMk0|21cDh1hQr}hR8%k+3<~|< zB%)B@pU3|p5#<#8|4T#`8iU{noa6gU-5Oza$OWD7>4BQUk?j8$iHN!QLy2_V$=v(8 zl1~+OT`}DH|C2;y(`Z?_{dw@ydRz+uLc?RwSh?IqWK8%r*x1{CPQqkX&Pkx!>3yo< z)$+`y)%9UP)i55hhxhu&MeC;QhMF%rGLT)azcOs8|2Efn_v^w33WE3UiT4T50@g5W zxjSCqzRk(e{?v!;ny2SpN&ngos%SY=gtYu#q$EJeM_1cg|NPvXD7iI~<-dDKUDtJ4 z^vN0N?;&iZp*_2O|K#BGH|Kqzo^>G*CS0@>N_%P3?$Hma>BS(%`kT2CVBtW%N1WxK z>Ba@7=QE*OrTniQ@d)4heWFvDHM)(4zz& z7zGk~W^ie1HQ888tRR^;eXrxWxl6J0bLx3*0fIs>t8jqhvp+)Vu7^F2NkOOm>o0wJ z#au%q!8ih~#%l3KR?y+rMmFJZ^p$@kBDWkFS^)oITzb|mgGrsE_%4GUwYAq>hc%Zs znE~5dg+U*qU1?ao+_#Gj{dU3dqWalwm=rCUuPZOr&%C7Uxkq40RLk29Q8mxdjL|op zES@`6nbk!kjMSxVU?pP z3uUF1?x-JfE-8C=dFADg2DkkZm&Q#n{x%89>Q(t*`~BD3wa9YCini4;tBUsIOQO>E zFh3BuW(e=jULTemD+r*@m*#Y_TBTK`OT5(e?V-KRS=z)M<@NJ}9Ov_0=x)d!y7mXk zHTojB$&bcNw87fuy?A?E?u3z5Y3(p)w$=VU_fH;K!?dTrz^TTVcLx6$2fD=NmQIoKB6! zH4**rYxpR{ku55@)3Izc!p%T{U`On_)a)CnV1PhBCMrCj?Pi!^>zD8X0T)gLcnERY zDlQ-bUbu?;2^&$Y6am1FR=8_*pfoW7vb_VI;g33;g!SdPuLe|unCv>);IA)#*fWeT zGAIb`ysYx8X+P!b-14V~I;!{QO#-_VGk6Z@p}a@qaA|;a{uTgeia$#V*bfydPkPF| zTJ4>7;B-s2nAO9!C*zYWitn!pEynUZpR?=~`wiV;KRuD4%`KQXRK0KVvme$A(y7`C zFp8m|9Q|BG@cTV70x0EY9SxekY$M!zUZI@rbSeC@iMie{%@y8Tjv(%x-nQNbumBuoc zn3OGnzKd-x;g;#SaQjUvDX2rlqwAgUThmlxP=?UE-Fb*d>Dv6zaoA(L10shMMb9*D znyzqIC8M_SfB?ilIO)2lT3di;_&s#R0?c)Ui;^nxNz^TZ@RYN`1foc>_ol-*<1qa+ z4?zh}$g)On!2Z^1b$>q=6ofF&bFBpod+?y|Y0xUkZYkR`#JJOT(;gfF0Mpo06d2Dm zhv}CD#1q{Fea#EQO9T5JF%Q&l_|V0=+{q3zd|8_&{3D`*`}tUc8lvIivfzk>0f?}Q zg3@nebi^W)Oy``_g<|(Dk2;s2+ygEOyaz0zC8x9AL`SnI z%JCTZH|*y9*&4Xl?od166C#&`AV}|oq5li^>3{N2s$vw#!_IP)K4kY zjz5ek%>2^RawV|}*e(WpuoP07hc<&D4 zbrp@C@(TCg#6Ats(HAVbsb8B4|4cw>c~||<=x6<}mQiv~adse%k|?m+ImKMDfg+Day(M>`AK%-8jO@Zj5PpS$rvm2@JpG}d(IxnW zsZk;-U@d$qxzo24n-=BZ7O}TZ>Qv^#uoG;s-242iys}H1ylh}NE$QHm;^~%gLi1!H${+R| z54t|mJk_A$kD^_MaOptcPp=+UzdYS>GisUrboH<@;ng>vgqHcS?}trur{6s)6c>I! z{S7yuoae8#Ed40|-I4v7icQsMIcS|(@U)ZrfEall&S3iJdH!q20Oa!br1+FsrHveN z`pacnAK-{L;@l&6FhGQLIVlTt^`CNfx3|p$qE}7 zMQ85@poj!IIRX)W+YI8h{wbu7|MsfOZ7mU`=Ds`KO*0JZMPwd$ zwwLx{j{6|rg%!B?>PCnPLPY5`^~#dl2*zEEO#$i3qr`N{aU%3E#2v>N)|iJiBDiEl zGAk5?Ji2>VbvmN6Q{(y+YTu5g<6b!DB~SLt`Vf0}qoYtNp$NZgSV}#9a1`y~6EPDW z2JWEjtAyAdMde*~*VW;9-Nl?9q42g#p&X)Et)W;?4pVG)#N=Y>puTh|qpZdVUS}%C zm+6>S<`}~q?*Thd;HK?#S5)?R7@;vHyV`kiS!Gv1^}tc}C|~vDiz)yGz?yifaLQZ@ zN@2A~n~?O)$W~`xbQ&)Q298KUW)m?M=D4^0F_Us4rPo2z>G89T@$=L1)BP%bvijec z;sCs+78KBVt!W^OF>=C8;gMi^>M;`A3(+v2z{?N&*>v&n+JSJ1qBKJ#f^1nW7D@(tdoP9U`j}0oBokB4;iFOBk!3bgSRQgas;I z`X#Da7h2G60_a&n(WV&0BJmQtAe_9FsL+&*7Sm^VVWIfTpk-3OoynlDL~x1_5!1WgHyDZ2)x7}QT4*cu;R_A%krt&VLml1z(RVe$BXzSB4+y_ znaK8hPu55pL|c$Z-9qB{B^Mzk@9?t&@WR6hQDE!nxLk0mtXQg3Q@YPe%%aJ)%R)ZB zO%{!{aw@Rvl8DmW*tcQXxl6iI&>j#xwfHA!(eOtEy+v+hr?bWaQ=Mke2| zNGrJZ9BGs?31l-{=KEuW?9f-B8N!s2-h;TGCcrg3+(HadJd+}P-DA8cy~^U1@=E$v zN950{G~d8y&mDO$X5eJS8M{w#1~nU16j~!{u+0gts9wr(V4x)Jj;Km7)A8fbhF9h8FLqMU>Ui{m8=a= z_BX!l#4p*|nz`%rfC&!nS?LWQ&0c>X#`0F3?QO2iY!=*um*+hX_U|jfx6y}U7zrHw zP9=pcL7Ix?8Fm?;_t277$TxV)!{xzqxtT}aLtg5A+71YIcL|!SWhU92e@@|5#msAm z_dLjnbC_P96bD&u{DKOt6;$LsO?ZVV%p1e-Uf)(*haiO=J;;%T~nt~;&P1B>_ z7I|Cph+qq~N6{bf>G!t_%tNvsHNQ@KSkiS-CLmNKYP_UvRwQh{q*I}^I#2YOc=4Nz zx2t2&yQ9#EQS>WJa^N=W!wj*Yn38F6_hxa79{<~gX2BbNLW>IJ`s#`U%{h4kZ#JaC zemJ;@9c_SUS#?ICuK3mZjIyJQ!nus{?e`UD8F8B(rAC#|(@I(ldr4u8{6__mPZ<@c zmMD(M^4kg(pT(*cszAOtxY$2#Q1*UCwZbC|WjZGwTg^yQ{Wt{VgM*9bP@VeFem1LNd6Y#XAtKmP(>PnB zCQ-W(Qrf4GqKku@V1QRZF))*#*`JXjUgzQ|cx+jB$+N)Is%kX^bO#5QAb`uMOAKgg zqr|Geq}8~#)Lf^jH1tgHR?J?nsrzUR9TIU*)%y1=b{ogn-Ue9QuV9SOPUodc_KLhgHiMV9+dm2Nmi|7>V3l-&uV(B zreej$aL&fA+$ISCP|rZd%~jh*ymoGB8Gfn!?rTlEM61`=mae^KVdE(4w~g=T-1FvI zN64PdMG}pZoULmu&5LTS02bjtn`%Gz&V0HN!3U`#p$-Ui7TBBu&Nc0>!H!Kdxt?!bf-#H$QnYE*?O+yJwi_)RW6VCHjY@}9aY$ftlsZ2e3@aVi`kIbX zDW@VHE7QKq;5{8?vAI0XR|yFj1i$L~F-U@bc+Y8=!~JfwMREc~wi)j4DE}^w88`UA z|7zqDZQFU}x_+;b$JUcthLdp}rG_}n&S0+?_qcNWEjBt44(>@P`^3$X@%xV^b(G(g z(-->Uz+id+?sdyZd4l~?v;ChBW@WkN-V-XXMg`uv+YA)xOJSfbw5t!MEtoQ7*3tXzya1I=1BqpPP`_tb1cu3joRP@ZtvKjfJk4bv- zHnSYU3UFN<28Hv@dO1gYH^=p5yv;C`q&y$V-BZauS9zMlM#f=uVrfyB_8FTN#i6;6 z+{2}YZRM{%u9bB)KgPT-o`>#@tbUjYrkmVS&j0k`^W3+TAMeKByn@^%QTalFviG!1 zpGP~Tny#G+-*~sEGQBuCvBZ3~I5xmWkcTT!(gH6BM?WthLRw1Z=NN8({`#TA`oqF+ z$xn}SA$M^w3Kk?hnlR|OJQ_Q@5VTUBxx$k+c;R@RQ~%nLFtS=rLv}>OWfAkc^1FNuTOtq8<|f90TnKfzmRP<*vXGK0?(ozwyn#xZH%4HJ_L<@ zRl-!2&_43s3{qJ^4-3<`ZOVPx6!^ROw0u3kjaAqXb1Syh8n)hZ`fi_g+thYMBX~`9 z;iH)fqpvvJK^epN`1QSott+kOPxUO8Qe=v&zS6TJTV+&9@Iz>BmD z+biuQt+DX#V6rzERQDLOzW+7YooV|ng=V}d_615-1KHYcPuOCJDqNEDA1=kj9%Ua`C!P*m1=%;I)*vDN;;6E3{(_h7 zN5A{^;?<6`5o5?z3_LLX>p4zQlXBcncF?LjmKAiSx(jp0uP@uqxhs z2<3B>r2@2;=#DGVb2(RlUD#$$@CeQa7&Bx5LY>cSu<4`Ys*$uBg5hi?E1EIPQnuac zCSSCkaw`Wz*-ck4!)iH$>D|=YexGL7Mg?HfN3rTe z2K9O8KR(;GZI4gSU|i zkBx#_*O)eA+c~+GfS02UkbdbxLukHE%DHdfm6a!-n8Kgn7#90w&9#7V0!ti3Q)^=Z zY>v%R0YtB4ggYG-(g0c=!h9BiYFC@KgkM*x)12=%&fA`xh}QTzb@zKqd%Zp(UjE*6 z=>-E@2478#zPMC%>G#<63?2v4*hRh_U1uV{ov$_((79CjjJJGAh$}oGF^Y+gWz01W zkv3SVCsENYqn~^!sQgNM>nhC?Y95W~r&qV=phK$EDvcwM-xsjkR}#6ip#Cc0}ovY%_a^p(p*Locm2 z^7RCp-D8|w@2+*bs;BCAaKpm2pl+&7(k5l1!`wUOldV6Uq@vJzqB`N?oWTuB#KG^Q zS)7CaB}@0hf_i@I7ghmM??E7rYtzcqpxseu^zjKob*mqeRS8Ub_pzip75k#Y{vFKg0d9{>Jzb0+qf<6ETs zk|;I*@ZSN=xp;Y%7vhmZk@p?aZbi-%##}f}TaUZ*o#7hvO}apIXp*|za;B%S_Zrda zsl0nZ+M%0E_asbet(csnm9S|e{m~wEiGfH29F=}Xdps|?ec$%=3oS+OI*?EEwfM4i z)b~c;RGmqAzeJt*;AisZZHf!e9tq|1sXX%TLZ>x;D_KKb@=0cgfAVc7bJtH3QF3px z)q^9rzC?Uh{A=H>E%Mm5XXB0Hr{VVJ^H#w|Yz^~7=ob71wcHb{g6cJ?)_aRj(taKE z-qe0^^sc*nAds|27ibqvsR3lGrH-8bjD7@HdGxJ;6k;p!qQ#AF~1{<8j z`ed+!vp4wBpN;JDMUfxEwel9jS9cWqmS?Z$_hyT8ZrMcOjIT2JaPsAl^$)C5ivS zF6T7>`zg{JTvy@O8-oz}+kxbMW^xrFYsHu=r>&s(nmY;$QrX92_)fkUO;HP+^@{e( z?Bn>v5+O~3)#1Ui5V*JCDyJ?&ReoyhnbCC;&v)r?+(|wZNgpL3?2y(%yUeTVh8Mrl zq-Rz?o>CF+EO~7pMAiqN+R*KM?v}2;)%JK=`@FMMh`fQrB|=({rpvj67w_Sk_I71K zcvqPu1G{tN!1otQAQoRy7_(O_0Ei7~6qi`sQ*WfHym z^z1uGg%m0}DGl|no_NK;=Zr9je(zmBncjKNUB8Zf!fE*VoBrA@!>FbqL^=XlCaZQp zoqNrE{drNlthh{z`~WnxCg12|)_JqB0V4*%=i-WSd;))Jk*2#Yy7&o@U}$tOo8x25 zPVR9!N1wLZ$FiB@2#I|nJQUiIVD6v)q5l0x!G|}j@0y2b5~tC^f#=I`?~7V4{Wa?q zH)JB;ssu4>cA%x5Ot`FrdRh0HZ#MV__?}Ud7}s~9(a;=5Pp$=fn&fE@srsr4e|CvZ z--LTddDTFoz2d5UEE_?(MCHKCiI9N;@B`hR=;iZb8wVGKF8RHh36El@ zo!_%fXlK-to)wqu_-f|e`0DXf;}sk@nl_L3JtD*Y*1YVL>0q50)&8KFR|j`gTKAAV z85ogeq-TN}V}gWy#&}v65%8J!(wx~Ldmb8Z)XCxRt|5Y0Fy>{tM>AJY`@V*?JE-HTU=M@vH5UY$QWePW(3 zaYrRSXz*0=-<;{>U zrPTAC*b}Lbj@a2af!WXfs9_>}c8plp@_Cmf^w?-M*uQz?@fQ_$9(TUbFlR#9qNbMa zU0u-3xg&M%^P(rqSMK}_5_q?BeCgdSr9-MOV7txJ-SC#v;WdV9PAuz<+VU=AWJpZH z!tXohPq$3&_^kYdfmN6-ij$MROzJBv2ss`9C}>aXjuqU9`yuZSzfdZM1^6$yP-XFw ze}62`SeVdOwSW8Lc~9TFJxYv77lSmXY<{qhd$zAEqRB(q%9a<5+5yedMUS@SyKRGz zXfTO3R2RXOSZ@$WIH^%VI<>Qu$l{X~K$G|y0sOMY#pDYOZAUWuSOjA~mqQNW>)rOf zIU>z-7GR#l=2X5Up#rJx;G9R&`GmFTBB(dx9F3`&CskPvF8u5wZ6 zQ_jvKPUKh&Se74Ho4X)Visv6fu%5KjUhl+tF>@%9W;7(kXpspos>tCv=Up~iD)LFf zaa{>mPV!e}>F%z}+a!(?5_qSpSd^a3hnS_u5=YhL!#hQHR0V?6a6?_%PMk8`9hg-O zy@Tj-0mSjk`W*dkkyUk^L-%=2bsfPg!mqpJ4~QBDSFZ0MZa{(QTvdP+0#H{GeR|BC zt~@R3q8#Cw9`t;W>AFDM>--Z5HphqJLx%RkuYKt@nryowTV--`MM<{j#!k1CCSLAk z%z2s%ypknVo?5a_RrE2v?y}l0N!_Xkq_RP+xKTBp*3NhKDv2#xn)iC8S9?Yk`yR)2 zD@$r%RvZ15qOX*w16Ya6265K&M61aj-=CeftJ-%HCozhXeZ0#@ZT%DN5L%s- z&1NCdJOi9UOp$J8>p)z;uJE&7O7iG=t!_%DUh1S)MtVE54=H#WI&<6~cOY9gu3L0) zrTDtuTP6JxS=kgh0!%Yxa}RplNqp_}z93USN^rn3M6LR{N=>PL?TLQfs%(bOC8i?| zN1(5Q$-uAV-RJ|owoH}wR((?DP!ChXDQ5^|FyyXUCi_0>%Q=z#pIz; zs9}cnhmqF?AA?juK5s;cckWLikmW9o+yfE&1cC076PZG*ZhF z_e06(;NI{!m(l(~pRTNt>Va-jBj|7ko=~e*$)!E+B|cGV)R27j6VqsF+=#J#*x^o; zNR9TowHnyD1VYyZeT5hcH>AGN9pW|Ok~oSqH2O?y)Yok+G-=%HW(boqSy75+MvT!5 zjZx7JGCm$=O6g#(>tXq9%=>L@DRcN4CS=n+@^^PHtM~9{u4t5Kw9XN{%no#YiRvL6 z{5m!yd^GgdQnGDjXgC`|do%J84z4H188OOi7o0Q-_GzRl!-ZPn!gvs2w{u{jyFh?j1XdJmDMwN6BfRCpxJjXN4$n;4 zz*Iki8jbT=#sM|y+-xdPBNhO`0MC=cH zWDWrRp((kcPj*27TWAmh9L*Ntr9-qJB*sh+8rLFr-= z392Qs28Mg~M_H4?>^>52;$Xn$4I&=uk0qkb;rf9D8abFZ!c1o=Qk&x7*ijrD;<66n z3tlW@kjCR9-m{<&_U^q>9gz&lshDL)`=nfxql=E3L}*pQgLUA>(+RQD5U=$3Kp_Mx zCdya`A+Q_ycsj~Ey-~6{%54{{`3DwCj183|Mz%0&J575$zUCW0k#})64j*!NE6O1! ztToKUyQlRJ6OxSprHDA@2#9Kbq-_p$35j|Iizwfv4h3kcurxIQ;l>dhizP}NMLB=A z0McWLI>ixmvj=z0<(N!aBP^-DA%qhzIZs!L$myAXnb=bLiX6%vHrsMq-@0bJ+&$&>89|LL zLHU9A5H*A0=HzbfPtO9QZj6GX8wq-ih@(XG-%9k!DEe#{9g0WueIK z_=s@OjZfbOa|@Ke(%y=WAPOC2T$2ZV;4;|bUhL+MP7;b{M}}}TC2@fW+*?V!NCp50 zcwizWNTF^^mVh0DNC<kv%F`LkQYbd?wQEN|`qT8{rP zNOTJ)YfVS#%6-xD3AZYu61{CBmgTT}#o>^-*H$CMK$PF5F`O2Q0AbQmKR@#>7~Nt- z{!7Zyq=Mhxj8Lsk6iszh%U@Zb`!X>|&@XBY-VC3kMPGJP-c?#rbTLf=BH4QxbhDf; zm8@PXGqKbN(NC;LZ4ZY}6S$#{0^gUVFF7&UtQGzR2ShBKcZ)G=bBHx4Q974bZ5q~j z+7NnRC0*`F*|#zE88;=Zd-b}=nJwK~;GvHsGMsZ!5O#JK*3wiAHEe80nTE;4BEHbB z=`XCg2P`H4kw)Oipea|oehXR?=R0Swgd!1G^Utqv>s=|XU#S6Mxia!g*~l@Sp!jS7v22Y+|;M03!5MpH{-Ns!{;QW#P4mm)o;2Q zI3!>}*Qo%OO&8LUYrIybnHwxP9hQ4L;s%9)N@h>4cUM$#@6I8p5qVzsLr21iy95YF z$>xJ|8xK*@Hs(;GG1O+sB?ncg=VRI~=T>;zqYoFNPT9H;4e!oGU^5_siAMFeJu9f9 z1K7Ys3^+j4v!?zv4ciQd4-{&<&3$gQ_v%(V4rF*X;&=pA9VR|W4h8pn-VNTiWkEj3 z0TXjVAFz3KzR9;W{%<8m=UY#}+RgHw;(bcP~8&$LL+~LrkPz(LX?r z>aPtsmG5IOqN4L*UtWR6BX5Uab>mr&-G1Yo-}2OTYUjJwR^Pg`UjafQF~Tb+((EWi z{Lj|m)t8=b;p~BMSV!nxHrL*%Yd_Auy(=Q9BXUmb9b%`yl~3)`HC)=e=OgkSLg9Wv zso^$_yVI$+kEbYBV0dxccOp-Gv=%)B+9yxQ5uA;Hksx|GP$eI_FIRn;VnQU2=B04Y z{~mr@$ns9a0v8c0j&2)#@$OnL-5L9gK({(~pCZV-OH>bXs5}y*yo(lS+;@dsOY7FX za5tlc+}xcoP?wXjj1X7b059omHNFId&2$9&?GPL6*I(b=o_IC=h#0)H#)~0{-h=Eu?XHJ0^Y>R&_H89t;H-eqI`bjFSGP}92+)XA6EH2 zA`Nmp+u{*;7g^c74TeI$r9)zXaboyxXn?uD*_{jW75kt9Bxm;a)$)Vz&AZsXA2{^E zGeU&d5=F)V&XK5Yng_VF%eb-zP-3O2mm)1~b)$D3c%TQy*}wTEqZvrB;Kry&(@|Fa zrdKZi{!<(&D{>TC7-^BcUp5u+6bC}hz9g&dzP}%ZxD^GqE4=ST{^@-=nimJTAZJG9 z`h)O<{bxDU#D~u-IP$)+qFBR$J@2nLETER|Y*T1Mn*lK%K8pSH;E}d((jt!;03%jH zEnNS&-u#`)Dp_!mYAt9jaKt%|^;g8kgT&GGw~H=>-w*ygh=Lgrc||v0;(w=+Z^suc z9a~Wm?_8y$YV>kF&dh%JXknxAhwEkZpVIp;?l#&30Q4R{@U`m0d^qs)bi}Z78!$xh zr#|F03Nq%>Z-Hm&a+73Gun)P1vZiqCV zNG3h(8{tt7j0|v#avcpTMjZDP{v^lRg<{|Qagrd=Ed&95kAozmS&m@A({LVuU?v*j zcmMRP`E-2oPdF~5QlIyJg?~5tY+mH?uF7dR0cM*H3N${G_L-V`63i4E+`xN$<$b30 z#(@*^w9u7&81-=CeDvKT(|tI=W9)zMpAr!@tBlv?KN1mxh-sjTnoV*vtLolN z!181}MPi~krxUnL@2Gm=2J!8M0j^7I)Qn077CCE!FQm-8*|rvo!<+H$pX~`OWrOIR zXE(n6y|^=7?fNBX?*|RQaI}wL+E0k>Og-;-=bZJ)kG&8$we;7hI9-bu;wwWT8a;FAIn)}y@<@4aJRDW&Z&s$|r4EUMG$xjW4p~4@*=O%jcLMb;c4XAN& znKucM(`>Fr7o^(8$giha+#Z0+oJtDxL!6qo1mXUgksUAn1CVcCJ@AVz%zB*4{wCXS zc6S7$6N&9mt4Id}l!c~)y!<3R1+fA~W&ROS*G#n-C5X&xJvm+~d8Z_p#XkCN5zjNK zlCtK%;-yvZ6(q{)W*u6C|`(UHD1VK0O4M+mhq_k_0oyjDDM(3oLXLyc9oX^M!LPu)stZtZKvCv zxsyW%mll$Y$MHiB?6h9aP_Lof?#{<7TzfAWuNl1Qd4RGMeMV%Eg(%!WOp2;MHRu{4 z%RcP}1e!LRPh^H_X1+kwRHyStfueMQa(weLpE0JLUT!{ugXP1rzZPS+rp&2mey^pW zW-2IDuO*Vt()_~eXSMq$`RHl#Zhit739{F{{O6$h++(S}lS}iy`6(X+p(dg6>cx#e zuh2feWtS%RK)LJF=na8a2g`4{weWnZ^kJQrmxuVGxT8H?>Q>Tk-TrgMn)4upK9^IP zPVz*$`^v@R$&LE?vX(OiEy`GqM(FwOvyl;`MXWd${9^K{QhllQQDluf_p5PXpXzjo z=S3xLh73-T(}T=w0ZJjfGMd%uR+)ZJm1;^=Sa#N4J~`7c?^dU~SY-`L^@-#(QYQOp z@%qMP7*{Y8CQZ%pPXYio{MQ?3;jC+j-?V=9wPhb5QV!gI`9(XB3PQm>$%`;hPNXxi zhVV|Z=DJEy?nC$}3Rw>#=>709yA){MTsID@)4@JoX&osu3FpBu)9`o)LrZxLQA^3e z_rU62V|dPW0u*@dBW8GS1^IEmJG9h?Ux}0Tk4I6DlxYkli^$LRn-8VWW+$qonTe)L z3t9X1g#qrS4`fm1Nlb)jlOc-Xe58Tppp;#o^RYt2`VUV+xN>k|?0D&?n#OtD{#^s? z6{&qS235i`9U%^>x$X6brzcAVyb@NoGQ`yQlk?CoHZ;F8c1f<(6hUWXZ#b>La(uJJWO2hA^7O5)MqSMb~m!KIW6f>N4o#R8~!2%w8|-{ghGE zCTyvvhZWW@i$FK_5)k?XDM|CJf9Hl zn+A5!`D;Uu78dpD`R~$y~(`TD#kou-{FOn&qiWuF!p0 z)>QvEz=C;;<=c$!kM}KID6G8sh}DGmcs}a-ml!!I1H(R5Jm@3;$R?-5DD};=96C_R z#TIXR%?nO{wQ9;?5R`tXy59*#I^jWIe2UM7$JT8RWgdwBID!k#8VKk*h0*-jRp%Y= zK!|TtzjtBpcBmg(tL^qhnPOybe;BfoZMilU`#nEH%uhpbEwRhbELQ2PA?m2#yQ8KU&?<-3OdQB z?MxkmL{`G!o#*S!4r{KNo+hhLA5DSTLvVM+zmhFQlIK3VNNY(BC93ntB*l8I3M@13 zIJ!b_XxKGiZv-iOex05}B?YKb(YtuEE{PiHY}CU~c2w?Y&eJ?_mUOky|5M7jz@nDY z1rhrJrVbJVvE{Y>_P!H|f0Ikc_p@({jy^Fe=nK_Nor|84hTbw}9?Sfhb?aK0BWiPKF@1}#H z?}vW)(Ix2a$dK?C9qV`Ez*0#@-q{Z~NU(ZpmlK8u74%-)}Wq z_(kqpbcs|XYMy-Iew$#oCh;)vsqDG00yk^Za&P_^TYPuGB>z}lQ{U1u%dD-Uk0^Pz z7ysqj!i>}J$6CN=w8x^#&xlkoH~@XRz}VUuorbtqpl|b)Bl{0?Rj;a#{n>txZ45u_ zsVQ_XSzjl->Qy*Iv~KbA+8tGXk}Bef+RPJ}`Jb|EO-dzSG!)c!_1IZwT{q%kv0AD< zxTIsz7&?Jlwj>Ym{P?r@`wBD~xfE?N3)X_ZWx9pzHH4gfq|$>j%4!Q=&w)*Ko98A| zeP1NKuxxyc)s%Yy=&>W;*ilTgx3vV!TXN1%y3acn-Sj@A!dS~+Qa$$alXTllKbP$` zc9%3pU%Xm=kp)|(KNr3lkvmw5^;BNU?|`CY4Mp(wOe>n+pINSi+tlSQb5Ytrzs$7) zDJ~F4F*BB(KinHr@_2Lm`iJm~jnD~ddRz#(8 zHJ$L%2Vv5J)7%W)H*zUjUf#7S?UToIK6IiM|j@7ST$_uKPpXWn2-_)mKl1< z+UZG<27<7Pj|(dV2twA7Hmt6GtBt-N=uoc#dsQ1wag9tQ44N=-~`oJz$Zw)$xCQTgVws8S|3BpU;&7TvdmKjqQSfG;8 zsT#g&o~m#0jEvEkTD)2uGW;j?oj(`zf|JdZHGe>s>=~?|NNa-9MCf##+v$esbV;~@ zSVz?_oy6ZjhC6@(M+IRgmhL1UXT87tiYE|pr}ZW;mwf*>XBOQIvhdSrVec81(SbGh zXA1$~HJfu0p9t|PM7kM(1Xl_>?-PsX0xO)%Li)QXe=`(`8!8m)i!upAX`1B;IZ>b+6cS`Y~?%jzLCyDlE!7rXH@h!Ex1os`cEg`|nabl(Y3Q&9@Vn1?FuyFNYZ zPz}_0>LDEBSNQB)I3zICRoSeJT~M9h9VJ|x_1!Mw?Uj5&$9EXOJ!Vh1Clgk+7&AEpF8 z8|uy~EMc*EQ^2!0v%8jwFTYh*a8%YdQaZ1AAHaDeOt@bAFeqN!q|2bJoyX<^YV8}c zDtDCEe^A!^&{7lYrHCk1?6dycC9A=^(uNPb!D%+;7eJ}Y_Q*K&b7|R-wDo`-r*c%c zItf|5u(jX^8x&3F3$zf2o6^DLt8VJ1ON#HY@RKc8(CR4mu{ z`ikWF?|c8mci@`Gfa48Qjm1*|sk1@=3m_Ej?pan&mKuGderpPc3~&ZaRD<~*d(rR_*$=TQW<+PWM?{A=77}w3W(3`gwuLTs7Y_)rZgD}?4rIURYZdqeiIVj?@ z!lDJJX$X|gA?j(XV2Rpexu46x&2oM48P{&weD~__VNFf%+{za2v?@difnVgHXj(3W zUyei9kLu~cJ9Ai5K?~x@tbhN&jCn{{p2=r(!mQvF7<3Y)$iG}IY1voWvxE@7tiO@*>Rg%mQCMr6?vwn`d zGI8W8tQfW5)lthb?Zp3sok6CGVS0%=XG9iD#5=`N`0eu|Mr@c!9g>fAIc8Uc)mg;X z=_+qj!0iS047y0ru#W9ih(m#i>`ZAatx_?BQF2*WDp^FJ=(MH0&LA}iua*5H zvXF{Q)3snR`BBW{!g5o0UrB_O4sp=CpvZc5$yiQIr*yhrE}XnC|D*PSrVFJ?-POyZ z^=PGCk|UMr5OE1MfB#S9n>jO4byBC!53-rGsjt=H17Umi#ox;d%seU(^|_E z8+Dq`&ooZYSe`rJk*+GFY&~Iphx+4kj`K*UnR#3Bj8wVdxn_gjVfj-!!`Q#r%ytcr zImK?xi7mzZ$X^*_U8W-@L>?BMa}>FtxO&Cf`(%*VG-@J`9x)K2v2}aj>ARi3d85fF z>LReeZ>ohpXEt#)pKwH_DAN1|;6YgOn07e2oanp0H`1RJ*!#s>m&$PQ{6l@SaQQ2-}GSVeR$EwWmvKinMY2 zN&W4UPswvoa8>QQFGOHJOTH&8@kh|tZHSUSmpWn)j!|VWrc7TxZv8tZI{uu8ysk}d z_Ck+e2n!p0VGvAVPM2_=cC|&MzNXQMB89mTz6Y!Y@r|oSz zXBoQIUq-}GqW@kqR+IwcGhX*-i)Q_`duBkI@FX&puK!dNG=F_=zAXOcl_)B#mueoM z2*Xm4)qAJeTupMWprw>hb&-HAV92fXt%G-IBwpjx?Q?*8-nNJFHZ!UkCAp|1eHoCN zeYM`vEqAAs-X>*A=J5)LK!_g5BnztVRQ%m<9r5U0vcjL2eGGVr6$SE*ydRh86XkE| zn;`0~$Z|j1-^h=LQl6VqpCs-Js77dMl0mwap2S}JK(4g4fICAJ*KrH3Bw>HMXZGn; z&T30}a^^$2)|q!mSG1DfiFAp?byCr1MUT_!vH?&E*+q$G*=Ok~0k>h-*0J*w1#)z2 z1I(?Ys@gCI>1^}0;N~@*cUAMfwwCPXr2NymN6j;Gf!B>*Rfk@xIFC51X)_;<)9Y3S z#Csi%x5iO<5X?0>i*?^i6z-vF4|lsSC!)0O>Scr!O$nE+OBP7BmPQ+#)m$Op-vx%+ z{cTY4zAx!#3~lSI1ACml?HrvS&X;}Z`Duu6<(>BXbJ{~rpO5| z`_O-HuCG1n1Up`~8%UkZ>GFJSlWDYQ)yeV8D6^ZbQ!a!!j=RZb(Ea^UMWLn1KV|U^ z*vor0_kLcrpK2ZDy4-^#1h_J=dg#+G zh}fKOA_%}P)e5Zb6Qc>jV*HD}LV&~8tVF8|67UZ66rY~gY}c!HQdn#lF8hqjHpLbr z^MzG#F}?L$)xw5XqCn0=KAb;4VZqx3{Xj+^>sgdszr_rP&wLgbgcuXzlzFv&P9Oem zV!89jV8_?#>qWAIqvZswV(ij&jg!F7C)mKjh6DiZyN`u*4DsvKkIFQSx|6`O9Jz-S zg-dE7LPhDJ|42keeL=9aF(d4NT*V+_A@iBAsb4CwOd_s0QXkfl@$64LWmAQ7qkTny z{zRz+bMGCG@Q|!Ph=~GQtnIbeye=b_cak7a31HY@M6HVS^HuTbsJ-5 zsn+H?K;gKtmGZvY%`u@r`p-tD>~E(H_RJy|JZG18nTZt^6F(JyXxr1*hf*nIwaf&`E$mdm2eAfYV%Ur zu#j?j^Kre+VjjlY-^Kq*e}1~X;sRyGK?8HOJ4?4qvqHXay)F8={X4_#=K{CvP}(P) ziXP%0->8?s>Ty1CB{^F@6)0n3No@qr+tQ7sQoFXY@uYorCTtn&noy^8^KQI*-k-8= zmu`6Q_h^IG+k;z;Vx*k7b`FXKe0iL|FjF<3rdMWN+4ngL2bAkivcEpBCQ;CKEW_>j z;y?H%bSFq+L#?;?OXjazu4P~JVr{WfsK?o?*#~q_df}KA{?+C?yUb^+UL%N99~`5! z>vR_2Djdso+2Hqg5aqJfX$4ECeMRh>_kh|E5BU1ZIVnr?%(1nA$%J?^>u)|j5G?hW z8LQ`pX_T0&42S0kwR1}O%@5U;w&%z2Xn4?*Eu|-T!T!}{9UgvC4O5GUAb@$Zrc?1F zUkSGN*R{?ipbP8zrC$C%n9h%9C?LYnDlT;A7b3^NGLe?V~U~F&usD#u{>0htkm3`V(S0T?KfiAcNPaU7 zA+2MXXUu`r`t( zHw&BI!oxD%6On(;-WN^&Ss z)=3LX?lJvz@D~@l=CTtO6wXi7;m$QKlB#D8PVvfrVDz9VAqmrWS+LGmvF2|V#!P*X z`+)I)q@3?88XtY6sO~a_jz}3}p%M-c;X$;v!qfu!JcqV)h#H`YOP)@QieY5 z5y}kTEq(sxx_hdJkNmG*^kJ^r3%1Ke9Q`Fx%w(+YCQLW; zDk+wEpOz@0P5svSk3pQ9`;AebOHv<4G)E!k)QV(zBkMG3{EoJ6=73h5 z8Kr{jacVA>$;23c*R|L~(1!tBqIS}522qh{ud%vK^UZSRumLeoIA&Gz0(ybrtResc zH+Qr4T(}G2i|UWwvM6YhgQa!@ZV>(*E29$fw1~C9T-*Rmc6)>q7pvV%mWBM_k@Yik zsr?21{sLOsB9q*9jxEFpdP=1q7S3x)M`-S}#<&o+kxWET$G;Bm%W)NNBi}VCOF;yg zxmZ1^ZG9@;Cf)t6vCjGPTUkL(LfnNH_!3$-Ht%9pXK?zm@4~`%^41NVK1N1K-45>C z?b30ho+XDfzXQFFGlT4kOSa_`eJgpP8Fa!Jfxi+bBjqU*H4@!WFSOg_$oiO&JbIu< zkul3vGlQo|2seiQCz&#_8o<_7UTzd~tQVS&S=u~@eo~}F24!r1qiGo)81K`J zfXWe-D6|d{Cdw1a|$;GR{^eDP8aSasb_I{o0=VCFun_4M< zPvb*Q>5Y&4e!!oOJqv@+)0}UCM8qS@H`(4pY6gSaMgarD4mTMEJhg4AZ8TNc_I23| zi@mDedEPnKzAJ(FBNAQC3S#a>E_qBTm-ZT4{1wYFceCW1J_8F9fB71WxeMHnu0UEm zDTlXNzo1EAFm#e5j~$N|?+678+tZ9|)m-bG(9$=gbjPG1v?jhD{)sTw70~3g+*&S{I1TVSZxY2M2 zQ}}5P%D0>cVu8X&s^F6%5`(JK-C;K@aa@1*H_i^B9fG(fRd*RI*k^s;Nd-Bg>@q^& z&=NRUM+;aOKjS$f*glHvJtB%^an-OpF=oLUup9rTb?X;P^y6szp}moQH8I8U!w(LJ z5iFJ=F)*?m)gx2z(j+O~6n-EdF-Z*p)iD`aA&CbeH_zb-2MqM#6VVGIGVl|^d+`(x zCT@_9l%Q?mF8k081~CG>j55g?%hYZBhfZI;Lh-ChxK1N;IQEOR9VjJ+!SS zqJCXNQ8q=JX-x2$og}`7F1G?Z{0Wyzut8%bNSB{Daf>!Mo;LIe!`uO!B!sTRk+DIE zrYf52Z8cMx*)AjE&jx~FNeE$oOmP?sJ+&v^7GfspXFM+FN^x*M=w{mIrw4yvfC!TX zqv*Pn87XR6cgHFDNjbSzJTLo9zvcWCbSkaXx`7JABaabs!W>FOYy?hRt>ciYUfXpT z-90A;rCN?vIOAL}t644A8+>}+6Aml{6@TD$Tn@e%36G{Ay9bIjJeVt5n0Jnt`-c!` z+A$4t;Pp4e4ZMUsUz_Kt6It-dvg{MyC8sOPuk3Ed^z5v69}L;iqaS!o#`q?_B3@PV zFAEE1$MAYNah^CbRrLxm0r%!O2#P*%`qpxlJH4pZ7UZwf`Be+|K>2F$^KpiPjw^(w zzFyOx3cac2U^DuMiLqmbHp7|kiHP6ui`;zRB<>b?SZga^heXwxs5sv{CzT8&<#Y$Z zBf9Zj6zQc6=|DQ-na(y)5n;2u6Z0Y-EF@>V;Tz9sy@#g|W-=~KGERdPrcOU8qf@D= z>9>~CqRs)g0zH^6c&6+VMe1pZD`Eb&X_<2y=(kZ1n_kG>YOZ*#)N~!vDuDT(0H?zW zP%+IkZOPH-tT7~f?>(t3w=kX6D5+g9-~=)rn?@??5}@bE6uk0g9tQK^bO)8fP`e2- zzSE~1x}t~9HkS!ve-k)#nd!fsJme9%k4>hisL82P%QPm)1ZAs5M?M%l8MwA=AeBdjKmIaowhPjn=Cbp;4uoVWnR*eWFC1G4T+ z%D?`PLjZRn3kYY6=#!9QiY{tG^kMD{DD;#=yN983WvbU2IpM4^U8hmwz)2WK0~h4^ z>rkNE{W$aNL7U?B(3?O`f$D;z6ep)#cZP39xN1+K4^kR*Lg9}x?W?6kdqHKTJMCF1a zQQ#9Ze1JqtVOGcfsmQeMeYXbPqIVi)PgOqFUYw0{+aZ4C`DNHN=vz-4EQoO91(U5k z(U?BxpPQAp|HYe)f~*@N{eoT}f4u)uY#ZxiMAY${_o9Zo4IEpf+&JA#AA#TG-}GAQ z_0B0U(N;=!S7TLO1&dys6&y%x0EmS}vR+JY@Z3P|nQ7s)*`=5UU4tp;!c=OO!!D3I z4h!28hZrDzK}Biid~SY9p)_&MbNkUE@`G{DEC&>6Sv$z3fke(DboNC}hbe5V8qL3a zG%ajImOL}J`gQd|(Kg~2uEXXFGF_YWBr7ycqY)8@#e$Q?#5b<#q-PYNWE+KCmCjCC zh`|k4D}`@%AD=n0>)2P-+cV8tOo?(3CvcIjm?ij`1d3Yuesktcwj12A;ud+!{+t<| z^w{DzbEq-49UpO`sH5UH$H8YVbZ(}s7cOQZ?`(V3=mCjPWAI6#HAB3OwVP{vvg2%m zOa83OJ2ys;CXT3r69-aG8~~449KZ7&jqM-j=q9_5RJva-Jno5j-qv#@eZ6pJ!TMlM zoM>p8D5#&@;H8x8>X_u=ru=gFIms8d2i5_GZY*FVF0rv2`7!0zovy9obA18|jz3M_ z+{yl+6=P=<-~vc~TA{LV@ZX&C>2Y(!G|@VFocn|8e78?u3rKLzyE&x+j+t?R49|Q_ zUWA-d`Z_B6KA0y^Pf^?|m`Q_k>LQUp5fI~Veij#jeMvs-mkfgvp$$%<>;>vPE1nUF z9B>34G3Ivj{2=Di&S?HO@g-83`gP_!f3CaAS)8*4%8yeO?-M+#i`pOZE~M|$VSxJW zRby1_aa4TJ#r5iIi##9>kepw!{GAd4Yl*q4jx0Ngc_a~g?oN62LN!a1CNGvlWn}<2 z$Y5JCX4Elebv|K#K7;-aqlDNrGP05mTrBV#Z>}HYC6SL zurke4h87QIy|i7ykE(bOJOl)%|GgAVvMpuMnnzZ`yjA*q2AS~3NBc9n$b_P9>s_hj zRJ|M-sSFdWm#1?c$EgR@%=CMTw2er01h>M)n%NH|q+2x$J1vLoDt$swmbo~CD(yg* z7an3r@qHESVEn;;joLw#IB_LYA}uR6IbS9%KKW0U>NU6!L}AZi) z!APcYp;stNkLT@nl9N@k=XP>{Rf-@KC^e+s^QT7`aindh#(d%Y{=IgtqO?l7%%Zmn z)h%X-U8~3fK3c(!>26j0RnwA=XuoNTU1RB&VPk7+XH9RP@{*kKsvT_MS;Wf%kXc*9 zSw{~ZU6f?sZOfxp=#6us7lw?OsaGp9mwM-GTy%?3b&+o?eGsinm~^83Liq%324_a^ zpN7V4)F;c4Pv|I_BEYbyIKRl}A<6gLa{x)+XjB}*!x4i&O|Fl9-pzQoQt$(WTTh#4 zf8Cqe+RN{q%Bqj!agMZMqHxa#_C$9LWVi8zw} zRmOszIj8pYDcT|S_HwVq!P)DMLR6jP=n!b7F3!I5!Dzi!8PzjI4*kCAab6B%>qai+ zf(HGoV!bin#W8}kL5OrvaE4YvWNVZxP9<+!V_91#Z~Gqo1X^+8P2|KhZ)=Tr3-;|X z?o$3*@}vUo6zsiv9d-}-Vn8bE<%8huupVPIfH(rkRB+e2g+r8lo-fWJ4(o2 z=UdZ$K}%2Dv_=#syV_h0p3M3XHp` ztVJS&^~ky3Z{$neJbu4xUKw0mboN=bFxYhKTt#dDw$0jn`E!#%&cli}+~V4iis6y0 z&(>7=mdD+u`p>Wjo$Dg)wYiKyA>(%P-R{S``RH4p2A|z8Rl8+bUeR|mb6NZQdZl0F z0rZs5-mvG6mEJ~){O+p!K@rX7VduUk<6*4){_Nepb=G0a&qGM|!K&0Y9n)T)JnL+G zq9VhwVg>FmPh3&oQ>m^~IrOQb!kO}$Q`;4|jp5l7h4ZIOXOGZl&(Y^b+2`sC7gk*t z7CGm(3V)t5{dw2*M>+e?dxc9Grpw?r7)oHtH3Y}NxFeX`dUVn%P^dE^Re;}G(#`7;!xL_!r4gDxhHe9%H z`Fwl0NYQwvtk-qD)cSH9=Q2EfkfqEiwo~~&c91Uy$!n(7>URSL?$0~S-sjH zMYs8SPoiQy5K};!64hda37g7rF78Q*ZcS#XCJfkIpRLc7PS@J~BN2T~viMQeqeny^jHkNwoOSFq0VRgCUbx z`8%j-9E$jXX}k(!xao(70>h>W8uEB%iP{BI^U-Hb`WEgu% zh%`p-tBp_=+jMurIKQGH^{_%w3a1j^-ejOUE|Lww%j!?D+}i=|Ad1$o=^me#e$HPqS8CuIys!2IRbU(H zwJ|i}>mW_m@9`w~j1X)fT*gY*e^i2u4N^au^kF5EQPF{!NG#hmqz=<-BMXT3T9Wkh za4{tgQHkrvk4oaRxkL&yFxCgk783S^$(sPl=i_qNljn0ru|&uPi=qw;J)SbH3VWKN zxFA(SUNa~gzLHt@Q{RiIah@AuC;t5{8hZsKQ-Nu3rW;oP9gQH zu@K*IEt0~tm<)f>Y1-CpH|aF`YB_zv;6~9u;{*)z8S4u>be^+iWLvi6B;tY47;3Ox zcN|SnU3*MMQ};A4W^(lzrV#K#XGurhAuxw=R!F?z1miqWW*jAY#zAbX{_y=VHkNv0 zGVy)B0(^A!f+9Idlwdm%kUxZrGVdW+Av{7HVf%q1{g7auAb)X_9@+kCxN?2pV*vhH zTy#sGnDWRE5JX~8%_9NRRVEQhD8=0>Hc%WFED*#Dl2cQni+~&b4(sU|s)kX^9x<4g zu7E}6(}}Qh0+|SzQRS2O(Ra*j6kU>G6fj|e)1cnB^B#Wkd|`6M%xy-oY#l>RsgdM=had`UMp=RHR++M-q5NN8WIoXFqpj^;H&uE0 zHG#1J^eYEUzzBrbOnzTI_&U#QBfciBwKIO9i zQu1u``_r~cmJrCR;MWsZFk$4=QXr@F>AS$EnFjbZ?_N`wtcJx2tgqQ6D67%fu|`Ds z5n#v=6~daj$q>f%-0dgIl0i~gn08Nm$gri`(J^6A4i@dk0=Coz60A_oTCnnj`w_{> z*IWM!ZFEb{0K2UxTLma)$PVwmBl!Im)0 zVQxLV1}8rc+h<>YXS-AUPPMmY7a$k*>Yd1&gYSRZRvGL)uF?$veI#wwBo>urJW&}X zH2~>U57;H}yAe-mw>S!c5PzK?bVAe?X1?_%@z%d~P42k@BQXsU`E#69TK!}su$#k9Cu@2!p809EW8545~?K8>5n zqfc+o#x{d4X(s(wm{F5LQg)2%DIG?lz=6Jj+C9^+fFzD|5+R_lt2qsF$yQAqhf?V>~PJvn1S?G#cd!!7X;K&WJ<~B{q9V%;jPUkZMr4}8#MlgVRo|Qt0 z3yW`Ym3vd^&Gk%E^tsaE%^t*;8Pb;7G7uMIIsNmZdG5=N7aHyLeGm>Y!Py1~93T!i zZe9x@D3v3}F9+DyZt#f-$(^uUd;!D16}IgcF)%sc{}SZL?e>_hd5FXOFxrXuVuc_i zk)Bf$UTKI;1;WjIPKn?OSVjgwrl9M7uwMYa>L-FNKiE2gz&Q`T-*9i%0k&-D-|8R8 zI)swD3{-T73kwD*y9Yr@u*xTi_Y4V|!Tc9m#4}j*Pl^L|wgQn{LH8|#)S!T|AmRE6 z0hv1-^I6{KA0h(?AVIzf=2alMfIsgeYT7m42v2rj*>Xh9NmhVfJRRhvm~u(KuNISEYS98<2L#7l90dBr_yQpG6;yPOBl-g;zDnZ5>ES&U4)hcxJQE~B=74A5 zur|0?STzxSGjuI14zDDx($bs)8+w6|m+^xYz;V2gyo~|i8zdeQfD#nJsgU>!TCUH6 zV^zg)l>nj{fY87J{4)n1G6mW2gUI+n5RGvX;R#YD;TTM$77UbY>E!tlK}qoKSqWk( zJ`fy7L!W#Ib%1*v!Hf{kEH=O{fqd#{_;5M5+TwdNUMSfDr%pDp~laTOjY(3SKTyBi%%gSU3dt3<5b0C6(@KwSSDGT5U zf{Bm0liz;RB}+_&7!k{1iMFSb4e=T2R)sHB9UN!WNdeM)^`MY+>VeJ-yqs6hN7!Q z0U%bvJqyaL0;-=RMmxkdEM#haOcxvu!f4v=)mcP4IWTF)L?ki%VJ^knT(Mf{%N5xJ zxGmLAE)#wpjWPa)A#4eWcTJkdU7D9k0{=g>hzplj)Dy}G*ge{_*1^a3UapM#$N@W1FH z=;`U%{{Tk5V1SW;e+NeT`_Wxp{}>~E&(Upm=nfThn>@Nn6kX5%AI8Y!6E|Wr6P@&7o(PfxrHPL@JMlOojI?CfP#z=X2`Tu5&BqX52 zY${Vy{;#@7OiaxGNQ*dHqRq|Gub-fGbkOQ5Xk}%zoMe-;{eP!L?CtIUCs*Y4>(~ER zSLA<3MPy`T&=L}8A$~L$2O2?-rlUhskfY&nG$8>R3Pt1Kph2K1CdU8liinAciHL{@ z2?_ldT7-v(hnt(5larH!gM*!&9ixjdGczL)2qq>bMn*;k1_pY1dOA9~|DubKl9G~; zkig;a|En(YKhYvO|D6`WGMxPU|4)lpztbWOrL)5jsDMJjiGVkqvz z_vDTS$IuUlNG%76%b0@jC%~OYJlkxqfDmHJW&gTW5s-K>-MM-^YH2H@X z`JJdcerD<|M_Lbn^-d8t)_5TPJEYubM&qj=_a zEB{>)*1&p>FvZADS@i&#$NG6?satU#|BLR8%61@-j2l3}4X zhSE_U>)foZFA-W5-^|PQ8~u%C43Y@oQ@#GUan&D#23oH&>M5jm8QMr&WzySMdt~Ob z7D?A_JO5tn-plpzgt7qSa3fI5#xqM02|2>@ULZ_{y2kem|Cx{n8E^gD&YQbk3@y?% zSL3QjxhUxWJIgC)m{>{1c7VOtJ8z8pYkS@ouZ_t?t{@3hsV$bb=kh`fn zPwW19{PgC>`8V%BXxn$)XYbXQ?|p*efC#hFGU>l#MI*&g)~xHU(9rgx9UPP(pOGN?Baek2r=rcL)1H6+A{|AZZewYQg1S|)_zoN7eMaGW_N3b zczRcai4DyIa4b#QrAd)dOdHACIQNbQazyI%z6i!4DIlBR$txfN_Ph*rU^4BPHoX_i zWNd9AZlk)skN@-~qJ2A_kJ=yi5##{2INjYj0sy{R4i?o=H?FjxKS*r|nvsi7-JL@? z#)>2Fo(mSLHleB&#G*Zzg7}xSP#YhC*!Dm;foDC8VQ>`Jic#m#X9QDha}NdeDhM{j zLPZ&bR77t;3YLBkhvlMv6(_zZU053RrN>?biqw>UJ$NEttmDVfIP_V-^ElFQF%OG8 zPZ|h|wh6jaB>=@mc(@}Gt!iMvCI@DU7etjS7$%}61h<@tvwd|LY6HcR34{whRd!+N zC+8MY(JuGB3-4FJ9}LiO$!A=b1Uunq<687%GvvF6BdY;IuS9H8oK z0l6k<`3`D1U|Me^ z8rOadh0tqOW%ogZ*v6p{%t#1d%nHPl3xzP8gs_DH_}&O+=IV?>6^ZYeQ9PSTSPy8i znAE<0KpiDxNtv9kC_X;TjJ16~84CA7PBV1_fY>__Q0no;hJ}YPsX0X2{YZN_-q{yV zkq4FN2`_vbK$F2WDYFTFaO2)hXU1j1b9nqg>#+&KvUm^zREN1jNr1eS5TvPNr2NS7 z%ZBx0{mqw5v1yP39M&RlSI3A%^SDAR$Jb8+k6=RGrm@%_A)1g{z*!axD7D;`)Ev+S zsW%uLN9mc*I{TTN^})55Y`)yLj+^Kiq$tGH1wcN8y@M8zcT+=gyZ+!iqOtr4(Ez6u zBi+0;xha+`^O(=p!^K~{gO%b^2Hv{N(RB4dlO+xxfI}ejBFF?LdlbMnxzg(iXMrZ= z7)gRwf*&~a;CeTQ@^T6hGuL;Ug+@_Yy>iiuoOR=PvIP;*fWLGe|D$}G7|T>WRXvN9 z16~_q1;(ml75I?2-Is$*KsCWr!hR?kfdw218TkvcFn~R>UxZjMlBUl~4ON6Yt&#;< zOs+AFM%q1sV97vUu+U#hs`6K2u#|FE#tLd>@$ejick}sl(eN+=SCUxYeps?<$Gw>X zJ~1AhFC%z(ew^2PN+Uhh>x`{q92 z^2k1rZjS8cYC`;hkoq%krfZ(N3fn5F~YzAwSy$iqZj1)@6iTLBWV40&!0Mo5(I>%@hHl0 z{?(l47q?!ve*5q2^qC6JIel`fqkJSmt4VjGDQo%CHPPVv9qy`fIjbZ7abFoXkiU_a zlhIzL`8%}+E%UZS?PcZ-4y@gSj5xwLqeEnyg#)pj$J5SWBRxB}qE|ohdi`b2)~LZq z>AH_GR+EL^dtuqUM_OgydllUfYwqWYP}}U5<)VYg$I>kOeL(>xc_m(hub%q4UG}H@ zBz>ZD@F#$TdBN|~<_kg{+)y}T(kmBCg1unE?tjrD-LTH1P^Q1&I73kXKeWibzXa5) z*iBvCv;qz{|Ii|s61|kx)fI%J|0ZppiOdh%q_mT1CyRrR9?*DlwsAlgkiX^RF52)wy<9L;Sx#)u)PT2a1Y>03E*iC;F}K+xC{`a4iuIQ6nzoM1qJ(95PBL0 z%FbhMh@dyg{I`F6?_VkuCd1PPtgctAuKg5av4MC_FWDzvNUirRO8S2p>>HT#7_I z(TyldiSkZ}I1Itx7lbu9=-5+524X+PQ4Bvf3XdgsIqHu*%*A$H(F+!gT2y-)-sn=O z6E@NugAfUtrq-7F!#GSvDb%Pv$tpKvA~(+p|K2C}6XT!2|K*<`sJ~0H^cO4O4J-Uk zF?+h=Hro9rXFl%YU5uh7|G`iUEjK$&I6NN8NT#bum8eKJqsT;#V%0?f4k+$=l(i^a z^#~@9fD2t=H$Mgxk@YXA(or@hT4zFC3B7)rpT65;d+8wOSHM z65(bA+E(={wr45;T-8}u7297G*N7+)0nY`95**{w*b`GFm~ip*UktFphYB8#tv{Y*Q~$!I8dpse zMoRp^H6gJf&M`GXhK7mT5aLrrNCQvIN!6!HjZqFyt_+Xgac3xAOAgjcZ?sAYv-QJEg`hLM6Ef(v`j)g<|_}F_%Dpl)pGY9nEWy|k^E#LYYt~K zgxQhjWiDhptfi9a9sekmDV|M=U0yBIj zPHFImZ#d81e)0;>M5W~DOBd1pDm3I_GL~jC^%Qwt>h}Jvgzklps}}TDix6k>6Tft# zCu@-l`g<{jagjuXaFe^`gPl)j=S6u<*^dk%IvC}|0WUACB)8Qe@_Sm0XQ^~=af4&g zaeUE9O;PgO5)D=}QaHpl2V40$PJUXkuwt?x#?GWIuQx4S=_x&0EjuN#`x) z;VU^bzl^^<-ALW)CnpY(2WD*&c@m8CyHJ6R=D{ z_m5PZNtZtuPKL0SsFEQFbV}Mi!_jH1ooWtV)}L=>-N8U}9&g`Ct?3DG4_2KhFUM!J z6W?%eIUi50H6EjkA>^4B&^=#yK%3^)Pz`-q%h^`Xl~fzx$Q548tu51#Xw0qa)$rm6 zx0H2d#6W|nBVgxHraTE7)xz>Ctt-BIqIOgEaJ1e|h7N8Gf2CdL@`K$xfa6_y6M2rn ztFju4k-CQCIy(m-c@j45(WoC;QI%I=KU(2P(EMe)$$O_k_zCdL5F&#Fz>s8S>-y4` z#)X~wXqnb3w$@~EK{osrXn13GNoxQo#y$>E$LJzCHetLi%XqDk)~y9U+OB)sn1Wkx zRazSRTGb=k#En{9b8vt-Jl%-G@SD8cAB~-_Itm|k7}VAFMYjJQ>Dc_vu!4p{i2Q&o zu^b=Tj@D70DC-WF>*lPsj>^dF{&e`rXuIZ-8x-jHc~khct!;j^6Nu94_IlpC>wNmi z1~Mk2NYzOM09n@_*K}P8b6q+YLT%Q;0Ld9 zd+*Y9S6OKXJzr14kDeG;20}u>W)jx#kk!Q7*HTu~s8X-{=ng zqp^12sOE2Yr$y8Ns(ipzbzpR3U}<+y(6JAMB)mn|bC&mHdkwmy$9g^6KZj*}j%^>P zBN@aJY8)|a)Up}WZ6A8NIP`jKpe()r5srfdArS1y-p+flHSbh7*6#dxrV&{5>^+HttHoXHLVH*)4KvVtc+rlW1{y3HXmpZ=D zleY2v$8->QFLr#NjO@fjM(5h%$i-gs=3-gj-ca1%$q$56ubG?i1mPNlr8o@ZlZ%A} znUe$&6E}}X8OJ6D_^9#VjWU98@F=12*eJMSh*7;2aoco_emoujcr1ar86pS|CP>8O zatEoW_hhC;_`Zrg{)&{KA)2g_&goB&)I)ZNF!0Y*J(#J9m_b?0sPIuw($-_I;@tWX zHl|OB-G0Jn#;)!rKKCQicbL?D-SO;p;Kfq3vu#Ykld`6VaGjThTDM;@4$ZG_e1mRm zbHN1q=t=vfV#nJ-v-h(vqsRPfN}eJB>?c@kHoXe_a}Z|yn$L~lOKp+29q*RrVxzzK z`p@wq;X%@q1xxdQ3XZH02wX!{C`hoQMa1kjpUpq5a~o6nWnN-`lH@g6`a`fRA7Sw0 zIa+?oBrW)bAuKls9H9mKhWVW=HRrw_Ev)#GpSkcF&0Jg}2REUMAG!S@j{if3`3H_a ztcnX>bVO+Pe#t(4iM3;C$7Xr&FO}6uUs1;F#+NP!Y2q?Lc%%dIG5<34;t$-H-ICGE zw~I@rugU1)g*-_3dfVu4hDB$Zpqj}AKns6=i61{^Wms)lb$^BZcKO_vY?2!cj_(_c z>!J~uA|xt$9S2LmY>)+Eehw>acC{Rxvs_s-@Pn`7LTRpXSYXGg`;}A25xDb)upeViZ=y8Fcnl#f z-5~JPH22Tn_yp570_Aq&ORwbD`j%EiNB~{5A>^?ZyhYZ^D`w;3)5g=gO{R)?;%-Bz=gXtJ{#d&mtC*dV%K40xLEI6GY#1;M%Cm#FS zY=b!V=sn{xY1QsCJ0#`3Lk`Wud-jKT=$d6*f4p1xQ@Yq=VB^r2?0K4?0}h0A=&3((1x)cysYC$v+DFo_TJMs zv*h;q#{zq_3KuUiF_ozVXTMD_37|x%`N@x?F`>z97W)%A>@$*+%S_cCF9f{-FLC-bXlPJ zcU==}6|~olk8;4N^CSM+gFU&A{R$wQLBM4NVTDMX=p2~2Lq~GgUXm}DN7a(;o0D`H zu*wU9td@B5A81wmc^3Q>7mW*SpOfkz!Nd^o=SMK{7RZ%@fMqxAs}TNzAiOq*U?}_V ztF)_$gT0E(+wnJWe7~;{e=MM;{0#{JCStswqLqunOcwe6MT>+HF=^{ct}PQrG00&# zJjL(6r-MgU!F%bS$quD_Y-1CA;lfHOriDyQjgYkyMD zlnPrcKc}*o<|E;S~JzFL7 z<@wuh>NOt(mKwy+O0{)l2My6)jR)Ua#fEC~l~w~yZs!*(Y;O>U;qTSw)Itjp!-33s zzgsPt)5-+in46sv_R(?k8~Ys70tn1778*$WrBwgU`}%x;8GS?BU~@h8{N_1P_YBT` zbqS8W92OvWeru2#C$6oyYdy-TQdI74inGu6a>@b($UB52_u!-07_jjJ3>g&wz>GFf z^cu@AlkkL_<@TsgNR`2DeX5gAea&7TOOx(vJ3%LeNX}e~#ASbc=`NCHI0U{+FKUR*Cbo&KRyPx7rdI6gJ)&y} zw(izzN96R-;JU|1SWGX%!Aa)O4XoW-1_40ksvd+DkER`$<=VNk5_Hd{pPMa#`8({r z9*)k=yhBB|eOayeM!B+9?Gw_(cvyx;rz-3T(i_zOqh7_r)N^{I5%l7-GN^>QC$64i z6V!oQ7ULyQ3byBulloZ^JU;nEO71BnxBLIKmt9z|5->{SdGK&5v|0cgn!PeoBi(DC zarC>iE$9AO!MbNsFm-zun(20{Xr>_A`t_CnT`iYAf0D408`DfkMauNPn%fkT$})+g z=26^6=_{z*(IP)-16pWGmitTb(4xd$QNiE=O4V5V7Z~sB2;lDHm+dMa@*Z(T`Lr$i z_8u))+>!-8e#xb}+CwPjbcilN8cC#*?fJ0~Dc7pjSLLLA4H;$j<7gOpUGQ~h$YrWL z{5|homz%1s{Vsu5wo}mlYYp}Cy>WIu^_cn8Z%sZrf)D;hE>$*rWe(DN&XkeBn>c)j zjohx!=hFrIBfi&VRvh*+yY_$I;l8i2k!9VC&ShZAjC}v{IrHPBsua8HtBr9%&3o;o zF;6UxJJVhM4H4mns01L1RnNQ?wv+$eJox?L{MQE(cfdczSABfbp+~=1fb^F%6{8-0 zi)KNDxf`T(cwv$bXR=$Ov-#tkR{$ zwjkwzSGB*UQ-c3Ko$gG^EbK)iI`VYD0t=?@#J~G9R z6o5N3CEX+2K*~pKq<#4B7@Eo~sa+*4&&-I2%=flsMwLxdKZesTB1zPqMx>$40gQ)v zB;u~PaX-VT;`Bp-psTcWQrH&AEeXzktlStTB3-eC*j4hwrpW@J;L3q!9oueV4F}+S}mkXWmOkQ)XL#&rBp=Hkip^?SCtJ^%N*6}tm-OICvVTSsy&5z*gEQK^6#=xqXXIS@Qg?+A36$wn1{|io7$<<5F?$;4L!$<` z6Yc{NZF9EEfN+fLo=yO;xOyj27xXCr{$OR{ z9>v8M-McF^etEX8^2t$2VFizOHl)wD?G--jz)8_5=83LwmdBG|w=b;nb8oodb3+;T zS0h&5neMOPj)Ege0#^%Hf00!`g{;)!=SKp663d^K!j``fLIP&iGX?wMbQdmtQf zr0BMgvbschRNIKZeXTIJKa~ON_l&a*P#o5RoYLeAZAsF#)?V5j{180x@V&ZDd z$c03b`d$!s?dRvf0E6;mN_FOLx@YuhM02UD7(rgkGfE(VaDvnEBT2Ot*m1&2@6HLDL4C`_41b+d z>eIZE2}T!r91p(vyA?_jb5#65d&)>>z4lH___x+L0u={`hYnncM zw;11Xe7l=pN=8Euq3z+|C1jgQntw}u|626+(kS8nN9iW~qGYN8LoU|vAl*!g=fC`J z6Ql0GFW(VW@DshNIg%atSKi%v`7_F1c6E2y7#PV4IjE$a8`<4#)N3j6Exkl!~RV}()<>7TGw z4>mLp{`op6B*sF5sif!YgL1t6^@ePv9tF(9K82={*~0~c;SKTd<>zo=>tTGP;c(#_ z_@-!oN+Iky?x{-GQ>;GJgH2mjY`9)YJIiSpmYqolLf(`QC}H~dvdCJq6tOP=p5aPt zn**#B2my*pY7h&Y0kOi1(B9HOY-yUyk@b7MBOZLFem<;Gl&KkA!?ikMhrpWN44w_c zq1GdH13Ul>mWKvRQHZ$e9lD2x+w+Y*%o|lK8opH>VK62m05`Cru_XR)ziN%zSdYGN zAFUA?3+c;LFqZQ+Mu@-Cfn;YAuOKbehzqQgz=s1roxoqnC`0vOc3ZkyYPzx22zQKj z{S1J&2rDqb;?~w0gvksX8S69PF`7uTN=acV8&AaOFDO%*WyA13Hwa%fvXx4pBnC`@ zM3{6@qVC4;!`{G#@P&ql;Fb@hm*{?$@5o!zoWy8}Vt^m)g z^{VHzYO)P#Dd3U8Wc?X!SXl4<0nodHN$XceK{p1`Eg&p}ARY#4l{2bFe5j=u7nA!~ z4G?y*2H$<~SbEYhatE6{dBu?V+8G-_Lo`6~v6$myd-bSOn@&x*E_pV%N1u43u(MZ9 ze_m|z8A5~FpG0rw<0s6-6vy~9gWil9nQJCG3IoOqf+w($$$SQbx`{C~Bo#_X=xR^G zTxPPerTcZxWL3?$!6od+qN!EP z^nSJJb1)!>K`r$KGL4dHZ{2t?nP$vnCa@f2wDxd_L!PF{uVuZ_I$^$qkq&%|&0E zGZT&Qew%ro-7&E>38fsZHV3E$jbJ9G@dMw@GQpN_n#~pGKih6u+8bLE5zX?CT4jcR z=r_UwkmjWGS&Al^3Y^vi$+OBwmMo+19NNCHy?xJ~gT+7Z!$?^$_*iL~kQ=LKZh9*q z+Vvza1j0G2^xJ1asn|GPlhk-1w-32Vh>aMdB}#+Qcr->8 z%c0+EjQf0yu~B0D0vG#i46<>$P;?fb-wU>OO~pDpw__#%`V49E7hw3OIWO@!rFmUH z8*Tq&Ypa|E)l}>(Mi(Ol2$dy{xi{}!JQ;43qkolN;GSZ&o0bSkw_+hc@1k7eN#d4L z#iXzVNKjZ;dK3^4JI9uA}zYgEB4PQ z#ggjprs;u6BJ7EnW-^9ead$gN-d_rM!l@1ZYieHg* zx=?S2JVYbMXOU~PeBTm}zDCE)z5Avw7t-aKXXicY*gNM~7oMWmm3FTyRUJ!;?aHI5 zq@X&bp`oQk3+2-jAQ>EJjV4IY&BzC^R@S|YXW`T*iE9MD13-yoLJb!^n{OBhAXJNZ zPHq)E_JK4l^M5pqIf=Oved;=$BmuoNlwMYgUS1fhkU%ecm3{$2igo>`I$4NXDtzAV zaWd?IKb`l;w)u>nSUXY&_t>Wy^?n|H?HU)H$&AE=l#$p&(6EWLiZZYTl+j9y5n#?} z8^LIQS3*@r>^_4MM-s!*Lb~Dv%dY5R{B1vp^QJCgC{Drz#-nRt4Bc;B*fO!}Ac@1N4(=E1O5;Ons#5R`6 zuG)V?^K>Un_eJ>BN`$M$)#ebVI932GU=r^Vu;7Q%t@5$KCWo62FQs$T`z6`FzfBADOtHZ12gvdRVtym(c zP9-SPH0Weo`BCnBRQSPty|mIx>!M8PE{{3q8ru)G7Aq~N3sEow za%5Qd@U6|^%)uT;D0Ngkb3pw;P8m!%$7AA&KhPuo< zd8p0(=%0V}BGqw;#99B?u{kvy=XAg{|C#aVbjsw@&LNKwl_%gQ2h-10fuFT31bufD zi~j!Wc>iDh)r;;#w(BGg{^7RfL^j_7P0fJ?t$= zfsPctW^ZzQQ2bNh9tp7df(5`G?Y@usT^>Q%bUNyrnb3tocLDKN8pt`>t*u@EJb`$HpAc)82 zi^I|lAD$(Ai;a6qL+pdzfDs#AoOvkz_SD<;G6?q%t72ci6Ie)KB^c+KSXI5Cq~AdR z?276PCYzNQD)HNx`RW*Yfw4!b<3NTpgwz(%v2h)E?i2!XDG$jmX6I)IbyFAjm;l0E z=!yd-P3o&Wk{BQHEA&-LXc|7Meyo|keeDOQGDXL!5Q$b(V8h9!%5S!0^QA_g+JpoMc zkFUYEEwX$7>m}J@ud|*dc6918>_+0x7=>Cs?xEK5?W+rFP(oDp@H z#qU4!6G*eJYtI*x*BbYR$N!?^Q-e?Luoa}_z#UqXG{F4kk)nUYySQx#K;f$5zEYZM z*TM)@jIrQVErh^nJw2%_J-Im*X_7d_{SE)h{Li-^$$|ENT^`(9(0nVHNB3nMt?F+# zPksNj;87g_CnCWHr*HO$+rOz0c`&s+ufcp-=0e18;HO@Wro!_FTK0%#s7~MA>(`%0r?*- zLL=-rw|nY^$b~RYT`7814_S)XwTh*l@&6AA8F&@&OJJ%(CGPBS@0Z{V4$l6*niRm5 zmkL`a6;JTmHOe=)FnmJR+AyC+P!YesXtquYAZ=Jmp@SUgz4DiCa1m{JJysy-cHI#4 zJ5;ihH*5ds;J4)Z0Ez@pze5iAhD$|%mjCy==mg${<|nVEkRK>)bdyds=^8QRpv+@+ zBzC?&4!}n0`N@C$KeWh~u>d8@w^k{@Cy$xyPrVlE|57bFRS5cexDHBKdyJbt&24(v zRFk`)Vo<33pseL?5E%k!94?d$yH&fcZ~O}iT9mMVR%zTJXiH;_)@E!pJ1hCP(Mke8p@_4 z*ihfl5Lm#xCo@6our8BJLRtf-Vs%oZH?GXh!0uLMnhLx!y)!1}iwockNQPMJ2te%! z@q)1F+}e4)Nf)v}fSUNDOjiBNOjU_)wvL8;ay*t`0DN_rKSP7RN1I=n0aQJFTWkD*xjMQON2{sIv1HaM4GUk&rYd zPGa1`Nd3aBkrb7qe(6lFuS>i-Bnm*TzR8n&E+?l24xm4!rlIQkcSnnSP*?mG^Yz~) zQIK=E;(y71UErsp8enXN@$~FXo-x`naA!HW{VU^|@0yBex>d|J>0c8rOR-&D42nhtG5P4IZVd z;14dohQ0In4sOkZe0PpERF22d6jq8sMefF2@aB$=)W(#^zZHbMy8y6Za|*-OYDS+W zg@X0ZFyXRct&P}0ve-}z-^U74Gi(>b+3RQ@)Ff~1;KKkVAn{h^fBzz1Xy>wyacP=o zs`JPottzzdlLjpI-sO%GTEvvn6CL_%ZRD^s18)Cdx=^l@{Fb6^vHV9HF#~0cX*xRD zq!u$KD0kAZEidN3&-0$d3XLlpev(=)8-WX@eIHsXWvwg-_LXUNy!CI(*Wck_po;-w79;hrfbF=jO8P7e=cFV5* z43(bnvgJao6KDcwid(Iv(hS^zngD|J^VZsTbNaMgIv*eV*Heisf%OwS%^p(N@IFIi z(EeZ^FOg}l&y&tZUqa{WbBF1OuQK4L#Z!X5)xc8wF-CF%vm*2NmQd0LeC^D8;r2ws zYBsBSt4$HRXDqrj+W;cA830+N5Q^^SfERpva=yIb7mq28ucksvRjJemhZ&%VwilDb zI|g}PJr_pj9}UZ&#zsuvVjse<^GadigfCGp)h6WR`4rw&Pl5*~slX+u&gOQ<_O}Zm z^g9dLJ|%DZ{~hU2SUs!;rf>n)Qz8goPNar1w$ntwrTYpp3>GkiktfSKA|FatC9-=d zzaH(Ckgc8;{N_zNO%r0`$qWS`$$v;4MYca)8C0kSmNh#_SL77}%?Iyz4p{74r?E-0 zoB@PvxOQzo;lmp1zU^cw45w$A-0CLVOZ!y$!xUnGm?vC)vZ0>_@61UMbmnRR3l(PF4<8`I0ZU%LVzOTVChIsTuPxjh^;>qme&e#<~ zbz2W=uso2t!uEBYMOMnfr8Z07+T=jj)(_jbq80A;SbdUj)A)4626ruTg7a6`IN~>( zQ2JH6#`P>F^6!e!{L-_>ZOB|NLDeYWScV>zQV5L!mDNfPEO~qx5=Itq!K0D`|SfC#3XAo2?7`+zN zpWt)pKB|i6>xf*36_QB&XUcx>D@8=A(Y?^>HHCjre*J63xz$T+R$aQ46QJ4<030JX zw6E|^#XHkITR-zckb5L_DM;fIHNMS_&|e3!ZIA?;;{kxc2Vmnb0#+H*oP6C^dI~Dj z5zi@*bZ6@%n)@x{?r;MCNyRv?K`ov% zSiel1Uut$aCx0}i*}8X6C5Hs4dxC;FG$oDVw+YHl-b9kP zxL$Ds{40%w$6G^#b&uh$Vv7G=@wrqOD3Urb+%G z5TPa0`;byvPXw_&t-#6GK^)^Wz?rtOau&0Z^%lW?ACX7tkWc$fz!Ssd?c8iU+kJM8zVdvax$ng*Z?7=kQ$etTIylIooyW`o*yH z$2I0h99ba)G(8(w9bV$95wS!>jSJqfHiWG^U{f1Aq*;bm_nnaJ@se7>Dc+9I8#74z zJIh$I$_QJj5O0az;ol~kCV=v0+VYn9O$`~)`Sz#|7lY#cCCyu?_Swk$i@TQhqV_)! z_2m+6fi)>IUj05V-M;cU0%TvrQ-%IvP1ulbr1xyXgq{S?CZ!G}F;&1n-(Uy9>dWxA z-YZ+$C)RvZFMicHt-|DT0|1z2I`mFF-_*aiq1eG^4gtJz89K@*)}#E$0jV-n*)Dj^ z_bJAQl91@CtJ@7*39#F5QS4^fg5Y) z41?0hO07hH6C59nFMC>#W2J4qCcMTR^xsMQE*t}s+k)%a!{oZ)%=ZSxywPzq4)8u< zz{p<3LOuLuN^GxQK9k_Y{`)h>Ek}y|lE6JZhQUjUVb6@J`*KE%70~Llz`)4*8sgNO zS+{@R+-{SRvL|pKAb_WO_)Kd+?TP@P4RsTf5{Hf!P$PN1CT_;o( zKD9B_p;{L~AN){ieL21g5nSWb{^_7y_@(PTcW^Fb5;GusGejhY;H@B>xYJevKmd&v z*b=A)As}ZFLJ44G#e{Z<8h$MgYg(gvH>zAmf?9b*b>#*T38>7s{Q6}8@S~k~Rj(4y zM3SgdS5g6T&S+`?9mUpvG)sgcG=sE#L#j$So(w`PTf@8*Dg1Zciths@asemcnTh_F zW^Al5jQ|s+K|~DvL(eO{Iah~Vp+z|F05EMOXHbk_+N(%Qs_%{>8tRj}qm}{O(RY9g zp||c`ycQMXDo$<~LW$a1t{S12G8ME&%H@J|9q3;EIcVXMV2>5PNC^I+g?}awmRJb< zVOAynNdvKQNhl~4x_N)3ctLDCvhI`P&k8xA*96mP5uu!PjZA^BzZ3f`%1jBcZ0`jk z99%N@_kS+Xg*AyC9C(I)b=lUu>(C^|9RX7($sTV3k?#u{k8dS(X#g!6wp(e9)wLn< zI!zR}RKjXuM>2aq?$?~6?wXe0f}-}z=^ZiHN5G1L&Cg= zOP_D>av#{wyZYaDu>Rp$=K_TSG>gv`M$W042$C>OmxLcAd~|Wu4ig9e zrh-9|BcG<+iKy4*ZwT|ePl8S)b)!#yH=by3!K%o#msB=&_-g8p@C{V-5q}%f4t^dJ zn^h12rh8_Z`6Z;K=%jX;q_rzx(UgS!0vkGqFCF10v~P|{cw27AGAMs9@hts!rqx3H z?j-;9vG3<#QXE(sbO6*I`93K|<|NJX@Kn3)gsZ1z_ijt38OVN@lsEuUrAxlIh1s#7 zS)Mw33lFF*KP^m);BbOuzmcnFIP&vev6|Ih|r z_|^*uwy+k;yfzrt%tH%39Ag!Vv-ji@GRi|I7g;7*VBlJtg(4sf+icMks6GW5;uVu4>Es&VG z&Fw};5-P`=grJi$6(|yykwon4%IVa#8TksRkVH$$08U<^bg7B;cw2=1WHbo@lzbwB zI8V4J!a-fcu&GU%S<;A5PSA;$4`6or>D+DZoO?JzlQ~Aa2q{H5Oda$FPJ`SsPx-yk zrfGJ8cqVHZ#Ut^T1q7HDRcbeSB5(9xoBhjZZMA_G7Bpv24E$pl$6OfWk8}QXdF|j< z2e+th3*ZT#m=htfwVi~sY!nL#EQnuQR5c22y-diAm$LD?w2yLkpr7;%S|9>Yi}1y| z--~rOYWMnkswRt8M7I#%KrF&ye*zWAJEJYbJVgLz?FF%JWw9ZOmu`Lv05t-8`8F{@ zkezB)%Tz}=b-P8Wiyw7Hm@4D1OU^LOcBfL#aBjuLoq@~jw!;1P!I2JU+0NiM#?fKC z9!4v?H`>b1ot}Pin<1UF?9DccPM1|DWRNdDn!gi%%ZEJk@7=4U1U&pTq*ySaI8_-N z9;N`CyKu2O4yyA`2#QT5REl;wXOw`c-Dr>T#D|GqDS!FRMc)K5yi8$4ZZQN!p<}Yf zulsSts~o|r#3(6rRGj(F z0Kx?*^z*mYm3$FNe6rsa@&iukW?22zX+hIy^t0K*ux^AOQYryu#%{u8ooW6qKJY^V zS~5PdoIE$kHVKbr&Q8E8b_+gD$Pjb_TxGf7M?vc;kx6o{UlK~9{#^CAr{ISj|0)-9 z%aw%vQIi~&?j7|zlvgWld;Yxp33vA|qG8RC+PRJ@kA5WR`Ca2wwIT@9ihp;OP+z~; zOw@_{a~`3U^QOnCNEzV$OYzGhDaBKPyf&L68+PM{=Cq#Wp&s|7j+ct_XZz1KrJ z!1ElgN~-y$UXc^jMridR=}uU*K2Y+BvY|)XsP~Q*2io-yUH25mWp^fhp+rhNq!qec6)X0J5EKaF=LPL!TaPDIF9rExf8W;g$IL<%-&mziyy`%^v&Nteq*smbR~#?$h7s z{te45HO#$C|0rnRDVp4@c2AR~(@p4?*8P99RY?Qys+X*irluKxJsobSduszudOQ9r z`Y=T*WN1=*^m|5>2$%W?r@pVu%3uG(D{D6XQ?RI%#l2nECi>p_R@-dMk8POADHUWb zgPc$P@b&KlYUM;~wb!G7u8yD|)EYbZj&H*w^zk}Dy+j|o^~E$b)|z~N1|5HXX!PYr z9ywA>bx~u=D!Gw*l$1|I05EoQ_R;~~KTD10e0Q@pe(yh78;VuJ6PlD?nwp)m_jU<& zD-YOa{B#K2lm-6$y<~o%O4c_f=}3t@(DeTM=Q$A!bHxmVX`xAI|3`~Jk*xSoxgw?f z4a8mQ)OxNf!n5-Jdn%tTCCe&e#n>{CdAtRmK`F08e^Iyej&V6%(AwN1sUH*Rva!UB zDi)BzO1*r6ZwX%iy?dZh^#9T#vRSS=S5j5BIqGj^KIXr2gJye>GnIMP8KP3%XJs(# zaoY|(N=IwO<%>TwafzG0L~8LTfMnAY8r#0I2(L`kaAXXH`%f3p&~?n?0lNb_)d;1- zkmatk_0LGN1CwtjKfD|AT*kRXPM)c=wnqF|c+JpZJDF>jbb-y*4X;)?TymJ5QCivY zc$SpY7}GPj(CbG%(w|(-RQF%k9W8R-MVuL2Z0%jJCsQYd%q_39)&Ksf<{}Zhfd%z7#c$lNPodqEfcRflVscC`6{7?9A;=O0Ztj znf2W78W+~Nq_8$GJ@?kncAEO5M~x;1Y*!@48)VC41zr~NlKpKt`6!U;2vz13X`K_W z@Z+%&uyX5(GDnlSw2N?6T>DYj1-zE8v}IJ`Wl(332N%RG3=A=a3zfCKJU_|G8b_NG zA<;_a*O_0s9`n~bmes~ce8m8r8SR|%$%g9_Jpqf(j_+Jv*xi9DBn2ql=5cB-(QkL* zGIA~OJaI!a-YXMWZDMPjRL^_W5TtB5KOa5)b`oV-p)!g}6Q(Nqj#)VR&Mi&>94o>I zfVI4NZV84`3N1_>wu>D?m$yqT`rUKL-5ZyE%b~k`vS90yM?2*yp{zim!*D_jE}6=4 zug1yr@m}4dShoH8u#(67FI_qu_t?!5aqly0dcJek4FSFeOGxVayGY#%cj6qp4JHcg zpTNCydQYdEj^F)QS9FN+K^@MR{?Gg2PiXSHK>;(C7`8HObGo614i-a)M{cIuld(3S74VSI>^U5o2h>yYpBX^g1 z1?|(>3sJ4X3~DfxYm)feOMDZ)p21iBIWkN@8<%d?Y#|1eFjw0Uo#f`;|DfbYYOuTN$u0@ z6lVKsIHF@UIQiOLM&fgLs)ukmbWhd8S?X@h*BvfrND7!;Z6+vvCFu^i#%1)E6#;la zlzsp>4Ls!`@9IgSMg^82{5wO`+(1suoXP$etn)z|$^{2YSC6L!WhhCfMsy=I@tOH4 zA_6)lQRZ3=Ls$lhG?4!ujR&A(x-+vRNw7*bf9N2*+d6ZoyR|gMhy;c#=R>bhJQe&6zH9vFKyG1IWQu3oLFUnT3h*fRQ zzUD(8t-W;nw;$e&wv+jb@;GKs+47K>=svW3NnaSQ4`^fzd|MVYb?CUrFUi0V*}H`b z90{ZzlRpm9y@nXNg!hs?3NR6NSOS@Q=u^)8j9Jcd^Tx|}*sj-n2C&e+baP(sBg)Nu zK+?VT&vrY{{;0~N(Vs*Kv(vvcFKH}!&#vme;@hP!sa7YaM1&8Qj5z!AQPRf69DOn+ z)K4=W@1E$pcPzeS&zSY>x=iGN_oI(>?dBaV*Pcd&`n^{jaeHv3##3p&86c$w z1g+?6K||e)W`rvZiOuBa8z6xc8sQ@vGv+i>yM%Z;1b|2*FHew5F`J+f%Qz0;JS+$I zWMI;wi)f{?g=H@JzZ4H?2dM5{X?(xY}||JCm{q3q&}FT1=wAUQ`4cy zZ5a?uol;;qI_sw{7Rx&R}*c5Q?>F=a*_|x z>}%Tk+&^1%0qdL8#2yG08X3i&w|yQo`0yRgvF{z_)0{v4>As)3NZ%wLmfU3zsLrO% zI>*UyPNEbK?A|&RvsDw46V)rdtjZ_Pw}-Gb?hY~g=I3OvVkmymV6-MeW81hf+tBcY z-RoxUo~Hhv!F6P7gKWi&e{EVc7!SoMUq;)~_0QOjiQB~2P=EiQTyye^q+*a0 zi@#;N{b#L#1pVXnU~8I)0YCK^psJ#sf<9(}ajjDT#$a6WyO5PnkP7J9&yPP(FhtFR z!dI0yV_}3*xlU7IdwEr)3U@7IOHDjV>wGv|4}$MDIO~?HNt=A zdX`^9=?hGG`EYIxfbX_5CxK?an++&QOo(4sZJg;p?5Uzaedk=MWJXW`9JLegA=(8z`_uv9ON?ocxfrT;p#&W zN4`-j#MU#Vj76G}nunYkNH;0cONL~*{!UjN%)=u_wSu8PX!;#HOP?GzuA6UYKPbFA zNN#<~;!s1AI>b0lBaEjaVGmsx^{o zZJJG$_Mdz6NrwfJmy{wN9W3rz>3+ z<^urk3QtZ;GTuoGUQQqcM1kQ)OA%KXyHq%h z)*FH6mV#@aXIb7fset9lJxK~SCv9bAM+@Zfbi&G3x&u?fu_+mm^t?KSlJZr_N*-f0 zo_CYh00Emy45sXUG6H>Z&cjg@LV-;>o*UP!HITx`TJ#+^WVr1%C=QB z8u?lYQ^06u%+*!1)JLs&izwQ+zJS(|+KDoPd-*?jilE~%Ql#hbVL!#ND#hoN&6(~X z)iwyeHVAVftM==c#)WM6HGPO2gSJc2UGE`69!1|XIXf1vA1k60!=RH8t@cM&;rW)P zTeQ9#kFH5{lY-E!iX4HAMb_mT#ItCg#q-79bM2*#@0#KWNvNnUxsbsx2w5Zeh8f{K(Y;I#9 zE&hd{PEHttqhzaN`_N|gHAfrF3|6l{*a2 z7-DHPZ&zb&Qf_5m-!6iccVr!s%SWjmXj7NjeC{v)Y<wIy_@MUFxiPOmXTJ?n0IT$Le*!I-whLuHEl;`{fI>>3L5FTOGhc4bK9E%7A6x zQc$BrTmOXzbG`HAyf=RdKYy!FYKOjC$DS{v6Dh_r&R|dP)POOp7u+Mbxx=A zC)qYkk5!S5HRB)R#eUbi6HE5f$v%dAb6+xk>0tHhVEkvJkQE!0+8)H;&V%Pda;BIH zn$A$YfaoQUxW<(PHZ275&vAXQ3Z=C(?1>QSveppYz-2>Uo?r4c420or1D$9btuDRu zJKP)?yXX|7Cm*^$jEy2d0=%WeLQsSX)sdTiAw+bsss(=EE~BgvK{}->njzsAt$~cY3$Z5c1O4Lc8$k*;rOkT$G(6a~vyqM<73{+&?1TtSX+cG+ekS;oV|V z*yjY<=)~uW?t2|}tZ-22cTiiLe)b|-YSANK@t*u*9DVjZMo{9k9pjhMD0=whKzNL> z;{9#A*!tG{aW?np!_2NaAF!T2c+dfjgcyVjfrJ(#AKE1xmAVOD-N)BlghQ30`Ii!z zhZKwk*}lKG}ll!P^oZHWo9kvNYxJ zIGeV(^ec#(Cre-~-{X=n`L3h~EXdTZP}Zvuv~@;4i*`tS0yB`{#8$u>;8=^xe7%G= zQNorhW!c20z3cKB?n2XU;Bp5cE^t?6P~aeA%6H2Y7nXbDaXvq~JP%mX=z+4WrF_va zXeCT&^deKUEGKNKpnNfpnl<@tJP(_l5SLI;I> z5(g+~i9fuU)Vldts5{5*QK^X?`9&uzm!%}kv}C>nYQA2KhuiRi24wenGx7F$5C5e4 zC6or)6=png%y|^TypgBo!AFJkKZKFulpoh8JSOdaY}K8&tyDf6Q|=W96>$$xtRlc* zs0`=nY95t;VSUo6R7T`o_RV2wJt3BUh&S_l5i6Wm+Ls_e*s^sTkG-O#=o_ZLkDfU#JrjKV#Etd&%XS>SQjsPPn=lVi$KvkcS@q_h z3X8;=tR+qPm709oT0&*$iXT$glV}%BMxj(^)l;|V@We?u*U9k(y7)yhJ=Ao)IIkTF zgpp$O$fi2RE)(ivR&aRM^4E#xEh-3lPha6G03SU+o`J3Exns>STSMJS)O_OW<+j(o z=MXYjCcG8OxBfKe%j<-dSI-`|BtOo2E%)Nz3il^Fk(a;IQtTeGdRB9))K0IwVP}8M z&5oPY#tHTg0KP_$!~NJ2ptd-zZ@6m4zi+Z0cf5I=_u#RP=-;+(+t#d{=VtAwzbU5l zJb+jj^wCPoFURiRkBgI*t6o0t{3_R;`YX@W3Q7m7cmyj5Qf<>ps;Rl|mi<#z!){bx z-c05BG(Zxnfb8FOCwZUH@wT^jkiDs#z3gvK-{4Z`U&b!_3mlyz)Eakx4Py4lsZW?K zx8*8FTgm^T+&`#h@zN$bU@Yqd1#~YDTmN1Hjtp{D4YH6>E+ zU0mu-9>I|vf(OCYgPck)-?bd%Wmb;OE3IfJuhnxd*1W}D>~a$ie)#(YRw=?}S_z?8 z=isSaJ=g|KY*4MPS8}^Hg>i11-45Ih%DVq;NVe5LVBAbK5a&TA7?;u+Qn!$RjOq4U zNb>eewQUED2NygaI$nL~7yCH&>f@ByCo&*8a**qNN*5V?YL`OMF8@D|wLV7?;#(;7 zU6Q`aW7}OX7Dp0PwoVmGLjRd7;pvYf{P$bGt@{ZZ{Xd`SCZ62-oZmk#-}zaZmMBK~ zMK0%y8s!`!XU>>%UWNxWL%@_fK)pM7?fZHm^z{@;$AR>%&!Fq!q{h+tM5uyZ)EV-q zw31r)juv@v;qdOl<&GB7y!3exrb06B#`Co!WWVwD>rlul+0g1t2<-}V;*PQDO8K_> z8nS*wD(|N5^K^%DW9QR-Z^N*CtuZcU#){9iMHo6%=C@BX{#=Kg1) zd$I}NsGi!8q5{a}ZmLmj0oEDA`yqGr`FS*d%}uufKqL%64`-=3l^hvJrTD+JNCt!G z|DP6trs>}v;@fGX_)RFi{mv3b0fSi`e5bl|Di?1pH`^0 zK2+C2Sa&B8{Cf7WpQczQcK1qpc%p#BvXNpv(&tlwvYB^7r>=?^uwH_KR=m`VeAYSU zkBn$J5x{fuvCd0dh*KI7b=3%kTGz? zbjyOC*iCCDZ{bhBbOHuQ{Q9cN5Jgi+82Hx>Al@ek^5}sWATLQSkAJc3ygY&!&xLhI zkqKZcTxTeMd~=~)k@s+6{2Wth#mW-{jgL=8BCz_#zsTqSn3Io^%wlsB%7ow%q#6>? ztgot(I+O!zU6sj`t)~Gmq5cmok~!z@N=?@3VPQgcv1MlQQ;y%%W@_%crirw#BY4Jn zlaRu*RuQBAf+k`_^mqg?0N(A3L~#ES;-O*rqb7slzbd;jFVMRs^~a&8_I|h+5y$x$ zWE8adn`&t3GgLp6VGYpbI`dg!i5P9SXC3UjLqOapFho+9WrUOPd(ly53VsOdU0myw zVbJT?QOCu~0r~eeO)+r70kTwSVcf-=gVX|J5^H@yEg^mlk1?PiUno7n>8N_mKaq2?_>1c$y`29X_J4GoL^=Y z=U=c64B=n2=gEoaHCHu>T_%30UNC1v@+mgjRrFfnd4%eFi;q95LSokvwX@>%1KmR8 zM^cQ`lt!a|JH}7`KaAanTT@}1Ch$WNNC+jNcL;*?5)h?J=m;o95TqHJf)oJ(X+j{7 zgd!aQ>Am+NC`#y6KvYCfx_}f7D2j?^`M#NNc4qe4ojw1;x$>Tq=REiQi!bWw!UUTv z{#Z&k`|SH9_>XMJV*2eXp6k-o@TJzR6hl7MkCjD@*iVAaS5&roWBw}c=}$x|?O#tU z3>x&-?yfFfB*i0Apfe6$3gg)soQVk zqHu9ok(qRD!PBGD*e`~?zL-{?)W>++56{0>4Ap}5BNO~$MP*7(_e}fQuONj*=1sUS z&<=2q`w^7tOPKDE2KaaUh#Gq(h$z?~3hqzRlPP6MA?b+*mtbL+O4*8FLlVaR30C!` z98IJlLBhVA%&86zhZ#`6u=L3|%dB(9n-8N46&_$6MEK~phm}F-VGTEaC|Key>)35#06gcj^L z+)_&%xDxXGRlz?06^&2vmW#^PToS*Bw~j3nTyBOyq+Y@N=gU<4(gu~* zN|^0oeJW|khSo76VB6+0!TA*(KTaSaD-zEtAC|=J>z^F8?Ti8gL#jJ{45)7(Yb*+G z-!zDR5SqWv;q4+}nKf<|-BZl5RZNs?mqJ=clnL%O46hHMRHaVq!{p+g840g0hPzLLl_Slh859!z*g5DY|mL} zSTtLh-l15>{?Cprv@cP{!te}lOkC7^8&u-)P~>+w&ce+V)jBieh?7Oyg0b_465m^R z()WJ1;so72j2<|_0gH`Mxp_KVXZOC3n=~KbaBRo~35bh2!5Qph9zQvl{d|v&51>PT z$FyUaxkZ04{>CsqSUIrtyt=rs7aY_Xr%8#4;sandD$!gq2~IG*HMP=^J{^DOVGKqH z609Fd_==CBNUAhS3|TGN=lW#2aPCyo6k1;3dK!DMa6kP&({NKp!Qg6@=w%4KdxP!9;rw zmX^%Fz4(K64d*`@LyN=>Y6Z7&hMwU0CJM>tK{QmrLmas@b02j2DuCt-dKtNBgF8@; zI=UD2^KsM!C;c&*=_ZA?hs-2z%?GmJyj6mGH-e*xM}4~$bzH^wYb469kHe`2BLD-0 zLbw=?BXccckffMetp8XATw*?yN|A!7AfY+9Ky5rz2wt4qM*Y}7C>?a+`6JDlBmHQj$;@;20-b0h z*9;>!-^McgF}%hEL1>8qM#SJQ+Bvk~6C6V~8Yu!m%+51eTEIVY;pFK63mBm1ar%oU z21y`^Ii$pSQc4Iz8VtywAn==1&~HCiv;;n=FFx)#o>YxU7$qSM5-LY|8)^7jwfS6E zqaU}#`_IP{j1oIxfG35?ei(l-ga#85Pn#2e6_z+Ckq7_@9TExSqe+)ZkX;NtI6D53 zt+X5(vPDYXBKaz;Fg5vIk{SsBuLkt{!#|S21Hz~N5n?l1Fh_yez6-X6Dm@=nh_fK{%$x41Yw zQ(^DKc*oKhR@0tltAE0XXNn`Ev(ry&khtEF+^cAMoP3v|#lz5C+ga=P&D%09W zbNuxj;usP`PGC}?`G&N;h&mJ7thq*e4a~wIX2_K(i6p#3=BRowwB$yg_x^agmY-4rJyL%DT!2x;d(Nb$I$l(0KjKrAk-Duk5Rw$8W^Sc zN|_|GB9v>~Gj}pKcUtnyY-kGL2U!?GF3Tf}2RgUrk|lK^Ez& z@K4!LdH$n)&Vb0%fMxz&0o_Hz(^qNiifO47m>s~Gy29+~M++auh8`5NsFhp*(mtlr z9>n{?kQZn#oUfUYNF`vv0$tp!yYO(!aZKW0Io}hW#8ly4+AqS6a&qr zvcF0d)XL6>m8H|?o}vPei5x09B@RyG#WRxCe-Nwu<>2 ziuo&whm=%E-Y$21RL+#<5JIrKS`>qblDXl(${K3q z@JL;B2fxx;FEqqqaJ48a`k(E2xQdhmno2aY3uoHe2OSvUTCXkn3VVKZsr@M_^oY~iVE z;hSg?*liJFXcd-j6)|Z&>(wfr*eY4qDm~FEyW1+y(54{WcFv^jyjPoYVw-ARoBD6_ zt&uh@hSMoZ>qAT!m^dWPn{>H zZldSKZqKkkgo;AEl13b3BRa|O>%U!Io700^=#FO|f?hraId_}5Wu{+(?E^Qd7{qHY zgwH|GfpqWJIxZ*FZ7p1{mfxNEy6tD-L(i5Np8Hy~Z>U?hJ_*c%`QRzcgd+qlwO7l$ z@SAiWn`xiO0nK*+$0!U3pFtM;J?&QaVN{@R-+fBklR8>U2Kh6u+V;ur^~=|@l$aAQ zHq$=9-p8xMwP&CoDG1r}t|Vz#%2Ol`g|M3e?YMPAllmDLfp`oe840n$z+4#yti6Zi zHGpI?({VBL6ZGw|VcU=+Pr;S{juUMU9A{203>mB~iV+sLs|u z+-#{fHdG67)TqM}qm0V*dum4$`M#7KogsbKI4AFr>Gk+HF{k&%(1p`n3+ zfxf=JuCA_*jt&Nc(bCe=)YLrHf&R1nqokyC%Kpg9%gf2h$;!&g$jC@bOaGtj59)t1 zf7saA{{Pt@2>2ft2n0Hnh)(lPr2s%fLjwQ+j0(`e_>G#2`|vO}xI=LqA&H0-G0rz? zDIH4WK6m^5X&vN93Q9MD|59uDScb&aTF52c3DCdeKVsTo#s3-qDHd@%#edFMKKvi? zADe&TKNFe%75};G4l6WW7s}4c@q*O;6aSGu#eWJcl{_;m&5BGLo|J!TQWBde{Bv(m zi^t~f?*GPr8Z#-dg(&*Bn5ld$UWw_E36!GoD{%7^{~`Vp|7knLe~R)8nl}!%pAwF_ z&OH15FZ}0z?C#<#n@Fw7P|HuA36kwx;}LDTxB}11;QAsV6m%==L};!QbBBkl3V$K zbDmoTA!|Rid4x7To#H=JHGrwbtj%@=aX7oW^s1e0MYcmU{ipKGYqvjzq|a^8C_77h zU59-i6*fmwy-SekASM8htnb|UH~eR}z8xN|-_W&LD_w_XL}JU>nh_Vn zBu#VWcK6z54D8L@&eeea@e~J!wL}>qS469xsLs?%TOqf*x0gJ%892*#eTzBjQ4q#n zsY_>D8F>>6pZ{JnSxaO!R+kM2ad}hvoGkg+1m{d~`zfKXb+4oIqzx#vs}JyxU%ImOJ;o(D(=bgMrE_ji`P(4LKW$ z@85lCth^sMW2z;4^qNWU^3j`1=Nxs(Q0XMfTP*QI(Odd4>=h1>JKw<|2Up;jZFITt zJs#UGO#g?Ft%e^#2rvKQ}UMe1Cq-xz+e{ zGymS_pIhnB{*FGkM4w-us?BVEY5SdIOz%>UGt9W(hcWnSbA8D?80L>c#nLK3<$K0u z5O;bgoUntw>1(e08n4x~{ZcmE7OsjcN8sZ6S%0=d3U5 zOCi<%Fo<5wDglNYVHWoQ=+Of81qg|4r zj1##px|yQM89`=6E zQ=m!!Mr5{i5>)9qF7;B*xxX!!;(^&xmV!^E7KFImunxebEzEx!zS9#Cn_5z|S z)kc?VEwjg8m(ihwMLY~ zpw0H#wi@p2mtyo92T!KppbiR*wKrdt?unWkz4|(`AMx!5QC}v5Q$mQK>irPpOrvr^ z7^$!=f`F6y6#u3{0q!z(@K_EKz@|*W2U#|oxy@j&t`7tvVH!R%*@6g^n zO4D?YP8xIgP`L%pFA9F;dZE1_5G9NoMrX3q-`fxo)MVYgrTaVO<-=f9_4!e~fmyqG z-eWRPdIQ#j0a*P0y$|_a)^9@80XPvB1mD4!%V>@8XZ8<{aD`fP1_2tWLj|$YBqpfVIg*;+3V!ocP98-2Ijt|NuHD`}X z#qaNWElcXIFuL2KgmYmd#f_c?m;Km)#^NE&BjKso%+SfMsquw2u%ns%a&_jOKrRSMHyHYU^?!x?cEQG!!VsyX{c7!d zMcQsg15%@mSEG1`;g=-6lxQF8cbqQ&L`#C`q_AKS1mOBC9FKD7&(wI+(a)7E=yWfx zkD{QjbekOGcJ`*%YSs0}F%UQQW45ifk9fgtW{NLt> zMb3C7-Rof=Sr8;mKX^W0)?1arGDEAys^B)FRoDXK3!hg`@p|#Ld=IFtpt4SzOe8Al zCL&CQvdupWTRlH0`1@!})hrx59Vu4)C1v|d#@+cc!R^%#N}$hV1eU$vp!deTx1-m8 zZ>kre9t$Nk$=eluSgiUn_T$ep)09+xqvy!=kCD{g%w;l2i+a+Y5@{L`CA9k%`rBkY z@+3_cP;0+<(rl)7oRjkRFW&KwJ4Cenme6NIAKCSbB+X%Aw*S>V3<EL3JR&S2Z~#(bR^rg!OwsURal1WtJydqdHM5+;*wNDm32+uRAIFw3(f(ql4$g!HYE2yfm_ z7|w|vQW4CS5ctf_>2=HbtCiVl@!{{+W>j`_usbpjV1j5fJw$PLk0uu9$ZuBA1f`Nr z$dLZ|IKyL^tdJy1m+%)AOM%zX3oO=Gt*s9-t?l1f-{83BYJKfi)-~ER$lzHd-8=A# z1ZmwU89(aT>U@f;Kr6eF?;0i5bEojerycp<(z%>5a1kT8h=^TDPi2bTWWqmAZLInDa)bF&3fW11LVV8r!E`88Oo{D$+AYf%2m_k!*rMKK83+>Fnv*-yBO9MZtSWV+iF90W+?>MpwU zsp!nFvnQ$o6ELC2+(ILg+3fHlM+@MpdC@dal3>E4+U;y%wNkZlVL%G^o<0s}EluUj zPQMw-G)l+fSM=5*Gs-{n8_{CM@3vC<39;NTfLB&L## zt-QsX;3<`ZudQia@M}rn-?gG)JgoVw?S9>^MpL5TXJ{3=BqkLOL@ZQY7*A_^QV%Fr zz)=wC)H)kup~G3T{w0aA3nl?#pZ=u2pV- zt?|%U{6JCuD5l}Vg<5(Rzyb?30D#)@+6JlQrZCC6(8h^JjkT@PjEl{!0n*HTEl*~p zf7CYVO4ZZ%HShpHJW#N@Q@eh2He;h>vMW(GslD*DUGabrR7?ZdSBg~^McK7q3l}i- zs^SiBvCnHbm(~XIuh-nHGl&nh4)5@g4%St-mrQIo-R<<-Emc@;=WA}uQ0r9kvTcEu zdM-Y0OX~>WdmLTYaVN1Ycm)DtY2MQBFxz>Y{M1Wi7xrd_`SS|n)hb383$G*BmW1(c zC+RMz_G9PWmXL|AoL^nlUTlqSbZ#qPt!Db~sgU{f6nSK6wPhDR@9Ai6J1tEofT6i( z|70(u?9KJYn(!X?PUdKeQ`g(h*uo}ikwo@UTWw-1N+R7=~#sW|8n z+HM@j{K=0g&+j%gOVCxb`*!XU}z)I%tFCPFde5qSWWPx55?bqMx$TUpN)#Q6urWYp+Q8yO=8j{RE^Gp8R^>9^5#kQP~u=I7jH3UnI1v=M{f z^9GIcdrjXDUVhbU-lJr8a!%Fj9A7O1!f()0V@MNE9#0r>NxJ04;8?7W6rdnnkhod( zXVVN%988``F?N)hl&#--V%kl1_3m&dFxHqO9Vv*<9ns&x&x{#H{F6oj>dMnzzMiY< zJH<=G_drx=HOd1OcTwKQ*}>?C&QKe&q~xsz-dE|FV%!D#w_w# zxyy{T?HE^4n2!9IN04+Q?TkAZ#D^97PWAEX`cYrg@q#>Ll6QUi)2`IX$L$(pZH(NH zy(WL|bid7SzhW}-pof(GWBizFA~T@*C4UOeezGcQYBXXJKmrq!?k~KiyPqRXwnu zp=%hKw0QBUei~IUTIF5)!5E1rBf7Ar;DVRDAIQ)@euMn8WABGgBbkpOlxlr*WG5LB zTRh9{gH#~HchHErRN4%kDOt_V}{r&utJ zdoTz1mG|l+dsSd}U(7^=#=ZmKO@7R?NI%y{IrqSsNq_pTaEO_gVB#STuj|;?4fd+Yi`pxnN`g!wI#RZumuV%`>*T%g7Z!IB8~#C3FLfk@a_4tr1WPA ziGHMlMUu#fMBIwBBhtWLxRyl zTS~fT#$)y0+TVU#^>lM{VUz3fn&ID%I|d2CSP+!j@=B9wYk{x5HDWz->JhGR%h9(c zY^fsKm(9tT?ae_i)E{KwxscRoyVkRmHdUVyIihiK`{Kp7I=0XtFJy(}TP$@#g!7rvB#-d;c1`yNR=mh1WD`!PmPh#pf^;<&|M`!0$1^Myi6?i0$pywAIh zpTGCz2U5O3g)?a`Q&xN_m5m2J;|GoTE4_02hg24tvY&K9L7H=IRH+{<^WAiM0H6weDaRco5@ zsY3wGZ@St_dO$I)*$DFxmKH2bH%(#Q1{l77rJXfLe4s#WtUg=F$Lk2yGc9j4d=|Xx zgj!tMzl?a}D$hswCKBIn^x&HjutKwggJV)5P3FumOTdjUz&6c{vnZq*5>bSLq@*Ie zyuGece{gXhpSM4by>s;CfIxIYStlRrE*!^{n5LdZqJOYnN20AL2)HEl$Bfp^6~xPz z^l#C~Mhv6V)-U0uU*3~ne#`y#m_o5oA9R6qUS53qHHrGI-Py7i0Z5)j3Z*h?iPH=I`d-lS^S=BK2( ztryP3%b@W*2Ikctb&#Mhqgj7lZ*xucM(k66PE-M8;?0p#PDZyWOds@s0*s3C;vowl zoO`tt40(_Dwy!EwC>E_luj++vjxvvF>{)L-mo(6)Q7;{HVUOHb+>czn#qvo>>2uGw zonIJwo-EQ$jIRsYNJWfMXLUO?NATQodn4q05R^DnX-848` z3O@*&(%?)4r!}E}@UlsY?4_0hY|qMYT#=7#(<&M5e|a~}>V#DC3OcP^eU94Z(I<&s z^Muj?R5E3RRj3iQnb#Re8p%NMj~Oyb#!o0-y{!C^y<1lMsd=~JS6+@L%P(qgDwuYf zMdI+umUtmY80oGm*H5Ya#ICh|G~>;M>(E>fL%%L>$W+N$82))`Wufn1zwK97swz6| zyd2Xz8|9QwTCZ6=J!>}Am){JAm(FFr;*5mTusQ5%=zdx7sLFio6#ivMxy1X^LZ|*c zHj|D<+$UacQTDy&f!N^-;4j&13mn<@YU?lFDuqc8tGGU>d;hp5Qn>SInOXmDs#`gT z)Xyx=`ioxQ;N$`KO<-rTYyH8UVbxpDz2$aX?`$!u-b{tQiWh(A++Uon?EW`+jZ0zk z`mGvjRi#>aHBUe}@4ff_Hu>PyUMFUJ~`;|~#RO?u>uVl4@hXAj~qmt)c zx1askm1QrjtQhr|=V3|PGRLo5@?M5{O^okR{w29ND?Oom?g;d^6%y($r2t=F++mRfVL=~9F4A5=-~Uy`}V>cC1nUAOAodr}j))X_Pmp+JbKhf`;%|hN5)k#fD zcr#Rj!r&aw3fuII9k6Bvd*-?E&*F3`Wv2&b#iW&_{R&ia!mhn8w^hiPsQPjs1sh_8}PkS|+^G&sio#Yj_ z1uiqriW-&B+m}nFSTbuE&uG&OgZWDpz|EJErQ-YaO`Yt>L~USPk(o%c24eU5WVl! z(nUi3IP(P@OgG9Oya=!Fg19yeyD`{rru%lYlr%Uh+b@1He%vM*tsF#-n^nf&0R2uzq)|h`@fb_?QKYFN_-NK+!wjG?W z$#V3SEN3iXk?+p{$A4h4KIslKpE$@|o%KKIz5%1L9 zD5pH`=O!qGozG`wZn7O3ex?v`x90|@t{%8Y`lYpd5RM(6)40A*ZHja4+4x9ro4v{? zpgC4w^xEkv@x9>pYl6C2 z{aDVsg?Sq5={eU&JT~hesapb)^Q$nHm+zm<(0c6fBAO!b;ZiW^HRBG;~ z@3jkqSZE661;uU|*ekcbt^HPREn8wGJvgmV*miYS=FRmHNdK8uU1rgK*sJHYbKQTA ze81$swdTsZ-Ed{J?i0V4`nkNhsm`EgL;ytT<-YLByAfS3+3mbSUVOxb;I5iD?^p@@ zxf!|(PvROrr>|tc(0DLPW4+-OjOS{V6p-o~dUoe>+HcgRZ*UFu-GomP5|zT*-FNX= zAvW%fdhe-{*ev|wPJ)?(JP_4M)-t6e20jsIxukb*wbGwY{ZUU^W61cqk6&mUAC2cM z1!iicN3(oVJEMF|tCfQeNYRUiadfq}^T&=l# zeT|~`bEZSEq|{Yo!TLvQ`+h@Ue2@JZ@#d!2mm)WdQtX%QiQ!6ZrzJ*J;rmfy>UuDr z?fBwR&czQGqVWlLnx1QZCJLFpb!_}p&hY#|uqD6htR<+T@6vwgtvicV)`6$^j|t(6 z(TBJ9@7ZPu3Ts{4j^SfGCYyv(Qih*wx%cu93H|x__*PH2))^{>CSM@_VQKBi<)7SlED$OuR~Q zwlE_nqdLbV4BW0FveBPH!H6;TA=>*ARM=iVf~~wG3PE(JhriFQt+TK1_ILg6hdSt} z4fZ9XX-VB5O3cwkYP6ylRZa()@hX6WdAn)EU?OSovgja~amX%-WWld%Y1+nb z1$)h)7!QLxaSM`2Lsug76KDG8+lJipvyaOZ&i3dk)ayE$!j|$#3;^M3I>{wg|H|I* z_4hhA*$rdKL!OgEca;o@B>9~T7~LycXb#L*&)`nJp`X>T|KLcB#E1uEz;aMSB7$#O zU7@UaBq7xh|7|eh?r?-s|9x*A&kaL$2a+PcELHNPcb9?es%P{-)F}K!k1#l5P#WtI zLcE(pi$cTP=Q%7x6fekVW;=8yj1F8Yfhk!H_{fYVPh!qM#{9iSU5@dh%^+uh$c$pT zx{|>~YS-sicXCh@*Mk|ClfbrBVM;?ucLy#<4-{IR&vA*4qJU;G$fKBH;@*g3>^R}QKoHUXjVUnCQAsnII=wOhu6CKsXQiCA|b`dVGq$$9Y6%PxwEm7Kvrhl|22iuE= z+$N9xCl6U@md0p)OGZ0(CH;w?9C1MXS~VSVD~5$>#hn(fO-g`IXA+VyZ6sJ~1@BLy zWn0LKG7=VVeX%(B;{EFvA2u%Y*?~`4Kd{PZiNOjKOTsVdO>J0Rk>GvNZ$CP#M@~8u zcL%4rvr5yqQP_Vn`TO1EzD)7?!>M1NrYKe-(}6`n?LuPaU1BRm2cpvy|LGszI33;> zY%vTz^F4a8Q&VLU7D%XoEs6OUYSPmFQFnw?K5T%8!BpyTNwC@tsFu=j-HF;0Q<6y+ zq1-L{Bx35%$#Vl3@A7tXm&4Doi{DK~%0R%?<&XZ6Yq zk)=Dp7Z*&4Dfea&Y=+2GN1xj!xO-fxvN9LzXe46WG&R&KR`coIE$Rm!n~M=zpqoIJL4)SzObFD14@W&*7-Q597RTrY{qS z-_eWdThs+SddUU46&^TEIF>+PXdem65(7zD+7Y1?7Mn(XM}K z`{8*E1s8;aSiG>7dvC4!;FXv=xg!&1GGryK`3AuzWmYXFho%dhpRsp*eM_^)qhikK zy!G2evO^i^ntL{<#x;Y}|BrsO0o6o*zqsANYj+=L2i~9c5zqoL0IYk@;<>NE$r#%T z8-@z~sE-(&{u^rhhPA1yv|#;f%6xYmhi#|H+#P8f(i^q-`xg_k<`xIepD8A>`DKKB zw9W8ouRkGOI)>Jo(^$+CLSaygQ&(sPX;}90H>C9<|#MUMThr`lW-F zDoam2B^qkDP4GxapacnFL^KJ(!C`UUGY*&L=`K+ScT{LOBuHQd7%k2Fxq{xe_s9D8 zm;A$CCX~xN8l}AqfBzk9{~#oxy4eBW47aBR8dl&<5-`hR;;n7aO>IJ(QDTg3Vy6mB zk(YV@!4-$|@yd=iK@IbL3A6Di-0V25+wJ+U`wQRB!^-kyUm{IjVVK@vncm_abfV*; zj-z9`VxlmYmMAxtRbam}89+-;;6ho5(+Z?wfn0lah^f%~{&m_-83s96h)SGXD(T20 zr3HuhS&aCNCY{V9fbA42IW`q+bMs|Q$Z?cL@!X(C) zcEyPlLG{-c&SlvQTE;T%)fvjxZ1Erj2VbzkK1EiUG;67#gKQ zG=)tPMza+6vu@BooR6ll4Iu_#Xm?~`H~l$1Jl$@5*TDK(e8{p3c=Y-gmDiyuD_{D_vPlg4VmWP3aH&vxUt zZ5lq$`J>eZJJ5cy6^RU7U05*k{dBotn^b+Xaq(0B#irE4t-`-cOrhXwKZl4Y!0A;S zkK>Ea=+VBziNDUB8_b=%t%WmjIH{bwiM)>1i{?dTbT#Jn2ej9Tf zEnE2%YW9}tp3g8zgQ+W-jXbGOHX3_)aACu%LFs@^+#{V7XFCIRmN>L6roChSfeZ0@ zmD9IPDe1MGBB252+uMMM2hLEw87@$5sjFL$1+;4%ayN4P;1o<5g}hpQ7o zu|{+jDkKZ@7aPcJ?2U5xCE@@J^3*b+ifYpge_UweCP(CJ*guS#rJK;$Ux55vz5C%QOkJ%T0JZG}fd!;_H&XXF+KH$m6%c<4q)FNrqB=|8h zhfaTzx_*s8f%E2FUL&ECUk-caNmNHIm^2RB&h_VpAk50>^#$=rtJGg3MQ$5J%h)u_ zE(?6VZmfV%SQFxB^9@pvE$bhx)C)an5YoM^n=~|7zkZ1z3bq@)O)1glq29*Sd;A0c z;T67M^a?97ntDb)_(bJUbUf+o)z-m~L1sRf6yoRF<891D{u!H{J)ZQc>0)jhg^r}?C%^&&sSg7HInxFUf-TH_*b;$45I@SU)~?x zx0aM^5YIkP2^s%UzTB&>NreaJ^d}dv^Fsf$#@HoxF;`Bd7%1$bxl!PQK(cTG z|LvSJiJXn|XOiHzZ3lu?hk`|tTjGg@p_;#rMN+jB^s{t7A5&5hpK)$DbO=qVp(aBA z)g}Gxle-_YqRU&(QnMYyexA*7PEZxgb$=8p_Q}fBme=i+(+CsTju_CZVX#Dk)m_KUP%G5#6X9FstOUAG9LVN~irs6m>{t zCt5x|>^82l)VQ{`P7tPZ*8mmLFMD!aYEakMnp4*(dALxQz;pp4axXQev%2N9wMwSV zxkPzPqm1#z3B0&q{Vk%+K>Os>0Pg37_ z$vdyRT&OnFBw3t3VUtE&+i3YB(EY*(D$sMg^#haqyiBNZ6+^Xldwx0^8i%g%pnG?m zQ4C@MW-6ne{ZxJY>&yuzx-|Z|3G^02VersqJ4o^GcAIWkk%XOfzczzrU?1ePyGY%s zr&);%q=K$EzEH}@?oygQIe7EN{X-U=@4R-bK0At4K!jU`{i}^f)wA=r&;M?RD=791 zv~ka$m?|xW?*1uzdB!>ZYz2U7zoOC7gXtKt%X2$gvsGTo0?g-GXlXb;;25-iBQ1Zv z^A_Lwxs_728Ep2^mWKQu*aN0Ngg^bOwpV_{H0PI;Sk-CMm6C}U@bv~P0I9ESCTtv^ zp1(O5#XIqSQhRpSZRdLRtFXN{_ECSXwMAJ!U4JYe_2Gv_?n)3dvVd$9*pZL5IK1BR zCGz;=XRo_dlm7Z2$;@`&2e#!D-)#G$7~M6>BfvO*fYi4 z9lpBawnXG$a;gYbwTMwASftpvmGNtA-vF*w_j7>A9$+LlP2HU4ePN0U_ueIzy%_?d z$_CxNwGmlDaXKF%iKJieybYxC6eSh2HX;dPSTx$Lr8(hRyklq!3?i0Rj75C7Fa6vx;;P;k*_9=Buj}Gj0sSC)_9L& z5#Cgl_w3Ph6Q`Q_!_iXWE&erd*oq~Au6&iIJAhk#yX4vdZ!Fm0aI$bRqj17)^Cb2V zZ0ffzI9%)=V)yPvG%Nf0?QVm!f|m4Nndkgn_A1#st` z^Y_|{hPLt0R>?Qrvv00jotVgFR9|f}_(+#Xn!4z%J(thUf!2)^vP-GhVjPvT<)?7%IQFZM8c_;yaiB281+j=Muf|pQfjPZS3Hd zezTKqxN{~1!^HIwDwj%+JG*TTE~~%uxtPyUU^%2EY|)R1@3H*mhi5~q4qgCKn;mtyz3oR)77l@Pq=D|7jy@3A`!tZ z;^N%nW`bk%tSkaI*!#WdYBtVhd@>b$Wz*;IN71-_R9}9)V=}o?CMA#@Z#(G17T5_7 zI~%{wf9Hwx(QQBZ(hO1`@5Whg63)6@J?F}L#+x%o{$?;wBR#3Znv~~3+R^-3re9}g zg6J->C4?r1YP%IATsmKJzjVjCE~{K7*Io7w&&=4`lZ6i(7F@P3lc?MP4&g|V$^O#g zl$5{H^d-Mc`wX&f?g?+p^DAdc4MA5#)9x;~c3yb?_>*O5PK=;Ncr2Q%`B|=M{!H;E z(N@`xCFotW<6h_2re}M5nJB9g#*TZ>!!1Du^oA$|0XheXD{ zf==X`zUeh+rl!VwmXR-m7KgJrb}p6YX;T`tKO?_=jG^apkDbwNyc}x&zeu~!s3zKW zU*JO$NC+jNcL=>p?=7JVBE2Yxp@>uk1O;gcy-Du^(i8-gDov1H1*J(>X(CuK^dgYM zv){G%dG}doo&Dj=nstAe&-Yq0_chn`|MB^&R5V)!{C@xNE!!%y$+n6xWh&KBcE#{( z$-b3>2N@Ozl{en_Pb&C^GqI&lyWP(c>%}P-9&ob>-98z!{sIY@@B58Rm85Tc=TzC5 zMTojD??lJA-zZbeMcjneeZ8XZY)S;N*?Q|S9eXF~E!|oYJ_;rueU-547CG=P=*^h9 z*iPRw?S``zu?7CH)HiR}c3KHN2yH zzk2rK>TP2jb6TQJ9C;D>>t!t=VppbqD$Nxv&49^i-B&XELGCWY-5V(Vil-dR_z)cj zM2UHOoOUY5jWlrm5rMBcvLAS+qb50K7(U;`VRsXD8h(g#6gK&H)v3v$8>xMnf)@8gsmL@)Zh+ZQMD8pG> zw}dOakMB%N2pg#|bnD0TE&XeEEGuzBp1rD(5kjg_7*`VMMz9Kf@0O}I;?g`(jbwKP ztJ#2ATp=dvH`&j$)Q{JV(@Krh9GGaoSyf<+fL@NaYiC33@b(f_G66OBNX7uLoW(aC zi!a~qeA&QjJ6|UX074{UIV1=ii2?xu1mKj5KuErB(Tv_zS+p#y*OnE+v>w3+!wAep z1Y`SdDd$O@MKtc*N&fXhANI{>40|JFfFxxoh#&i1ds6&EwmDqDNnJoU08og;OPjpV zAr$^0c}8%H^miPiy+ogWBZEbXCVt!w~XtXTD5@UbTmc?qwp(BejJCXMk}sI$FoMN zt>d*6d!C~sGta1=yk5S42B!Qb6zKYlX&j_<24+{(7CEDmLS0X${&pMrLTUx|SIk&T z`I$DEyU)ma(Ua+~b|BWgUJU~`lOfnWIgLju3I}W^C_~1FnfNvj7>w zK)zev>n$yu0c^BFF}_>F4qWhK^Qn6uv#X~4_Df7zkEGZbMFmh~P@Wu3N+NVuT=IJ{ zkEu@UdI?We(dts#u3ox2gnjdl`g*U%v6gzZgR!Sa^JCGL*DFxjUMcOD7)ZDhmiQIi z2j&FODj8MkoBSvMNN5vE{IQW_z$tzPW?rw%If*RX-4de|#3&0yxR8?OJjIKcQ;FX( zAK)t;;Ptoag9?!hieO}`HSZnv4LtlcIHCtrjF7hJ(ozK}b&Z3%zw~4Gih2j8;#54G`ee84_{FO;cBq84M zx>q!eV)itCHdH*`;?>+pY%S7I-_zaVnk!6IOO624y>>v3_X@!nj`Zcsb?B1 z#@C;kk}C%GqG!EIHj)bUkx;vChBGZbI})k@oS-L$DiSa2P1I_#hxj;p_MY~UBvNV6 zYo2F%uQfV@1-IZqtKfv&knfAYaj%9Vi0bDb3R}qU3nLK=v{ZhCT5yE0Hlr^44!|a8 zvcpVT^ihHmM0JI_|9TzgAD{gRKE@cI$rC-susUnlUHz6F#>bNS8C?a(pe>Ga4B^A5 zsSmu$`|-(6J+p7v)gBE=7Vc~m%4wnJ(7~yxj~tuSj{AJP%)_7VOMApB(6EfMUCcb| z5{%e&M(qk@`5G(%?VI6(!^?Uo9KB)+U{f!;RxtO5z?JO?W#1NOn-)`87Wz{HyrqzA zyj7gbir{XL6WwLAcK+g8|L|Z#NPCa_dIN=3L%%)ofevLiWCgU{?*pC#9NC{LG|MP1 zT8qgz2z_7lIs-EnHOLZWEH>-QyX#DKNa-RM#MveF!do-qd z^JyD@RXn(kY9zC7)RM&*&GqnW(y=H0!COgP8{Fr=?IVyNn=5|#x&`S!BU9q?(6RM1 zF4_+=MOUg}{+xX<=5kZF_0-ieFrH=PvLk=H?WfPyXp+(>Dh4t&(?s5mD!I=<3--^Qg(J*;f~KV1(@#q3d=lZMvH5FL%Lw^MOs*<8V*J zLkIe%^VByONsQ62LrZ{_UbXAKmX!VXH{hCwx7k)MH|<^iX4mm19mz*yrXE^hw{QK0 zkX>0cwmS;Seh6{-<I-Wqf8`1%Q_1?S8Urjf?{PabN4Q?kk1-oP9R+$pdWhOp7c> zuP;4JlARMc-48F;?I&rG)#GdFQ-2&C#C`kkgJbSqjoO~)e*+7X_h0bV6@bw|;u8t> z7nXKPW-`htKO0i4XDdA#f4wZvA2@Y(KIMEKm?9{}?VObIu2oCjqjvD%Rj+TI%0ZbP z1Et;7eUTss$)KY9H|Q%desgtJu0&kPlxeBfZf(qih}om+#Tmd)OYdn#i?L<%Bky*> zdL3De6Mc`Bz72iR3~7goT4`I6-ktc_ATK3N__oT6BbB=8T)@lUL z-UK~t`csk(U0+oDqtOTIw^r>-c7F9Jp9{CP?N@foeVcsdwYO8C5xgLW4qc4s zX;v-28SLex+O)<+I&E;pqSe?L{XlgvWjFXq_L=8v()_cAO-qz0xt#oANWtB!(h^rNOHC^H$sY|P688+ zZhma4lU@?5S~NYm>8gIZ0A}P^aLw5;TY}^tGRVc~se(^@_5Po)FY-0;m-tVH>qNM; z8>>!5eY9Bye?byNDVF%PMnFrUvCgTFcc_A=BlI`3)i1q@J7d=^hH1SPb7VdbWZLe~ zd~|%Uv+?O|Gw)>6wG&o8HfEfzK<6KnU7a$Zu!kyWE{6>SXoSch{t|07Jpi zEwg|dFE=fJebOqn{2}{9x4kamYYCv0Jm*%*&G)P0-5v;0sPu67P38T1-FK?aq=iF_ zlG*A7ZM!wE1t|s>Q6I!Zn}sO*yCq3&Ry#i;z8))gJO&0|K5OKBrrs^0>h@{2^Vy%^ z@;UOUd#}k@S7Mm(k<#5%D)A|m9ltp<4AJDgW!^GP$7@5Kl-b~jawkPf)4mFMSvY!3 z(>#JJ^fj#rUicS|7!E*Z-@n#u7DyD;V}G*d*%xncR@a~yAo87rJN25cT+6s}T?;Gt zZ81|QoJ9l>{DtKWFE7$g?YQ!cQk0xTmz>AeDF zB99*FPEs~ebQ^3U6R$GSy1%}oc}ei3Pt;4UxIN|NdbMw=$F&>I=zD>WC?b*OzFX)N zToHS{gW6vNr*llQL8am$T}-VK>ni-I=AOTZ^({L7Mm@@}ebZ*8H&@(PNTZErj2viK zwdi=%I9$^nPF937-WMp^v^av5{$LV#OeG9rE@&|t_oj(r(Da{W*qb%XwP<=}5|Gy~ z8@R)eHXozRL39Ot`7X~7j|t<4&tAOa^Mu`|U3|ksQdH{{FYcvdEf$l|qv(|26Oug< zviHgja1K!BT~F76uoQ=q%&j~Vh20d$xI7+oyKrCZ6ypm5x97hYTjh_ouAFz;tg_u>4{+To_hzv?HfPJcDdZ=Y_Gxuay} z0!#(qvB3eX#oHZ6<|nAE)?+AHxSh|pBEtX!)f8Fg`%626|BnBtJ^=*=YVCbw3yUb$ zLQ8z!pE5PRb@1uN{m%!pya?^>J6jun%VlY6x(+{ARfX_%kqRz(N4URJ`rec(K|KAv zK5ymoOyHsYTQ8bMpX~B}IZpOi8$%WD z5)N^g?*uW@g>NBbDT9Ye+MOuCW-r1xTg|cp%<1SZoTC+A7E^HyRq2F`K4RO~r})sF zZo2e7MrY|gM9n)&^o*C*`f?OYpgT#%#DQ^+$DwD}3&9CIGTLNB=mepZQ0BE0vRC>An6KJrst-p15@wk8V8&0<5@di=y{wJ&R_LT z&$rN24Und0KxI7FG_BBQZZm9#6fu7F0j?_Eylk=H&pz*4H9ip}PQtRbo}a90t)eh} zSy$wg`1uX4y=7slJa&X3e3&6vNEB#4BSlGvSD$<9Q_bOS@LC2?ej%0AEtUDoh-x#8 zjNF1~bXCe~jJvO1yDl;QlhEI?RAahBQiR{-&}DPW%sr?#HR%xp1zg zoYY$#Hz7feX*Fy=#qN@@S#)P*W?;J(HMHw&KJ}EvpsA9(;)EB?n6($HXJ{qq{c+Pa>34=`n&&o2&C{`8?nezp9O75M zR$_Q|)>%c>wgYu0ZzhQ~JAI}iClRuxcyKklWG#Ne>eWyC*F>_+=8}U~Y10WW9M5~X zT+n~;TC~dvwaulczhgaVEK;>-aCwi%UfK0df4z(&tJO(lGmf1QfFv{X!kb_b{))4G z*maXU|6aAfZJ*Yg?xK3TbBS_#916H+={{M*mO#Ng4sHoOnZ5|cF=!QCYQ^nU&kl~fDq!IxgW^6 zceUQJJF%IsL;N@lOMX>-lFoZ z*lU>{1nqAMI#O_TwVCtH&GP83nZ=hDd(Fd@^ayWW%8{I0%(_YPrgOKR#qnT06;Gl$ zWgkNiYDh-k$J;=rl47^Z*pGeNJC;p*RdYgs=eU@{)p3dENnb;j#_}?0i`%EQq zC2$jaUZ*Nx3$o$B>aNbP`W63S7u5Os z$0Qn;!zfk2b0ha#@S^As&9Egk8zwksb?U3vOp&C^gkf~XI914|7Mro`5c`kRNc?pL-m_q##*K8nMvp{VR&_o&{^O@=;*3oa zp>*DT5PPZj=AXg$|W z;IUme6i}o8U`FOVa(u_&))PhfHzv!=T)PecxfoZbloraWjy)&3)EvTA&+mB(oqF~M{6X1?nd~M{PhKN4T|W+8 z1!th3nJ8AP?q$s`mW*x?e3fQs#hwx1G(Z6F0M7U-lpVJQSqY2pHutp@NuF<9``ncJ z-shDjWrufrj}d?k|M1OPR1RgcBa$+qrugimc-s|7VKHmKGU+DrMmUaB7XwSfGAuZF zH{GY(B#@3KP;6sp!gBsbfTq*?|-IXJGv?u8L=lnEBY8hN~r zpm#GF@f{UvqfXuxdfkI#S#aP;aiAdMVK6ggfoW1V6?4AE&(ZtXxC0ykJsc=0TK>9o z&v4qe;zHCYV>{s`N=-1)d6*o6CDJ3-U!<~nd26?sT%p8;1ccM~m@rSd(XP4EdxeVx z6hmA*ajaVK>Z`1?CdZl+#|EaiV@)+G0nSj1E*ORERU3~QyH%Ev&<`DFJ8yDw^n8!62v@`Q)- zx<^2*H0|FyJ|fpBdYndxqzlp*o)w)YI5o);^pgnFBq0=WMlOp>naOFQSZN1mf0!}< z*%ebMf$$ih?vB30)rf*0OhcwRBhd%a6{re;bGMkok4A)zPVN-tlfykDFm=UtFQbK4 z)&aET?Jy-m1}a&e(v(s3d7y|8XOLJyaTY;qv2^1OQa8*+%S)MQ@5_moq?WVCwBk+sU*b<+J)ywa~2hlCuvhNO+s zG?ZRTN`Y7oHOrqKC=MZ&Iz;cssFZVGoCT)vyD zF$GQ3;iJ_hnPr^jVarg}SrxtCvsGE8Nr%vdQlaTq>E9J|epq4Fw9wYlCIM|}n>Na) zZ^>)y@mZ|1d-X{C#!?CC=oVC~Go{f}rE|{H>Az~!h-@r~ZB(@dfnBv^Yc zD<|Q3zzRww^CZZ2XxeJYhqBN#>LDAd zPdK))Z1z`uYso3cz;?&q?!Zz@@ql&}&)#0l;8~A~7le50-tCL=>WOjV#MRT|y_9{j zIE(Hw$~&~aa1?KHmy~z<6c(& zfD`*;+1C9E@W9)eau|`tWqAVmZE0e*|UQ zEA^1r#3AiKBs{uiKJNBPM`nSRti0KJ!p;7v3HRxGF7XzML=uiN%Lk9-Zit49;J8(< zmjINs0|Fy{^R+%4*}5bn{+ZTy9GJN6@a#Vv*zNGp7Yw=*%Z9eA77n$3Tt`<^8T=Eb z?m4{)%zosHVF(rvM;>!C1<3GePjYW21eDT;FumdKxAuLn5O$Io93%T^>xf$tRl@m+ zFBZo=j%-+G694%oAho%7{|Nu6PEI}>uc8?;f5eybE0s^oK0yvIwI4*xWU%87i2O}? zpUE@)dp3_`Iv1G@-;%$mL1xgCN2`pAQCf5S@xZ*S6)kJ21G z{QtV7Dzqx^&81NFq-ybivCfX|%o)9N(H|9qe+Oh`HfIUjM7^@HBeH^hSY|WD{gQnC zSQ;MQQ_0O)na;uIqNc55)p$Ux5q?iw;|^>d4c^Gnnag|6^fZi_8dobJTmJb!ervc ztV^>B6p~$|;{k=zRVGUni%#Tv+@#uRRo_>titw!JI6@`)Z4pJ9Q0o|^X>OJMx zw#pTV8|nOPcZB~=(w4mF+U1tVX0P2S*08Ppp8Nc{Uyh-zo$=dD3P)IF_$?})G=70- zWL}*@TBiTsO5VRsgL2JoIVhVuG$K6^=c{m9g}gXh6{olLpYkehShxDHy(BqG|2StY zN5gG`7QNousb#^ZB@ytQhFy$ z*Ph)I^Qz4>?10-FYgL3z+p^76nQIXYP7(KewN?6x%I*zu<7tu)3%BeCa!^|*hsvwj zr!}N!p>N;zsvY#c3PSNM6d-s2+4s~*%dw_^+v*Z}gmVW^%zD=%dT+JA!UnfM9bYb5 z1HKU$&fFyPvpQqDnpC!T2}>r)>`h>laTh&FZ6CES&|hjdT7I)%?`d&OuvNoS1L7r< zG#kK!)WLkFZ#OcSKjOhwb(H^+LY1$+ zVUT>4Owwnx>}mP@+YX}26hdt$vi%Wf$3(8z*n8Hk*O@3!ET)3(JH#SW4$mYo|x7ZlV#zEWNPSzm`nAS1iz z=T<^`o~9_GN-mt2911>^FKs5MPuCVGHGbaMs;DdCegkv?0}ixiUv#INnP43sqCz(4 z3Rk{9Z7jIhP&y#l<-Q4^8Hyyk`-84tuV2!?EfeJbLbZ4pVK66V)V&o>=X70>K{93Og#tB*~cA82AYd} zqD&M1N9A@z{K&5f``;8qtjsf4#bqj&WwOdJSFuj7x3|4IZ+rCKK9dUjyLIR_0u>(` zTLOU3(@#DxQ31-aQ5!7&4C1|h(d39hL?&}uV8h(wOK_Mj7h3l0#8J4dhU$KF#rVn;Jr_ezM@a&qitbr zEU`{W%G*P0dN3D7n+P>>7F3iUi!f8#)tj4a(LUWf#_DDlYsTtufPj%1#3`7dHkc*H z!8^+&IQQySvZtQli2+7UwRhxq^LG`K=-X|x5&)Sv9XQ2k{mD;jZ zF#2$r5gU_n-gQdJaS&k%YGwR1gA^y)h@2k1N&QLb?#ma2@jpz<-uZtod~7dNai>mG zLDc`v!l`?@lCZz^U2au#Due`O&>iG{B9At0RU;S-@Mbg^&^{nu*1geoOT1T+*>k+( z7584i@3pKZc}!H^djt1)9rEQdbJ6|Q_w?;M^$7(=?F*mgnJ!Ld?U+X!8>pp6s4Pfj z_G>Lt*cYcCP_ZC$4e#~Q8nX-b=@nO926|7jaSuKmHl!co4zerm$T3w-=@+UQ^?jfI zlAV6wr@NTwSmS~i$MAzVcKVO%GzLX zm5n8G>Z0$jJChDJ9+Cwr7dFinD*s@q`XIeoOQa6QzYF7gJfFpN^~5yIIP@%SOr`VD za$PfL@WITUV!K{{^Q*t3FTRHc{g^b&KR?)bW^8@JK0!b*Nw*`y&UQZzGg9rEAs zpGxm2G0$R(+pzzJ{}dAVd20=s4oUwF|LNls@rk?U`G4R)I%4klI}*bsOr5X+qGY^J zqO({j%g5LO!PnQXh#c$DUV#ms4C}#ss(H^gT=i5|rILM?c)7$k2Q{usri2HhINgd! ztExue%^HT_6-{(vm=W!V=I z%M)pvfyvBvhvzGvO7AUJXrn`$tCdU#Zr#u=*pL-9?zrD{2E4b!xSJeOI^{lJQw6w?%sz2R~ zACqks{++(-eSBFGy_kBo83aQc`I|)2Hd>J1+0>-?AMqdK_{oe)zvp6JFAZ&H-bm^AKMiWBD`0q@wf@Tmq=L{d%ry#*M_Eb{sIFK@JaMG`R;5NbrUMAf=um$6g-?hk#jW# za*HSEQ?=E@nh;X73#s88-j#&qH&#!o8g(-wld;}1v)X-cb}>^=e8n;3oj?JIHfpl(4MpdXt=bLNds0>)d#OKQsg19>P#*x1$ZOq6 zjK|T;Vfx_=kt9jf5Iu@7MFVDmrQ!FB94VBMU__{SoL@#UnQy@0BL*2Vqdt9_&3J-3UaQtv^DA6Evw_qZ7RC;!q7p zGDm1hL_n}6EO{t~c|FaMOobT`5A{jBONnFssyL{U)Tg-H6(N$(edilihn9d!cIUp) zZQxRu;2`F7t~)=VI3oq97ExOO+~hSvF-Dr>-y~uJM@8&?(cBhP@D8W!OUYUKneSlc1NP7_5in2T& z#NR1PoZ({x3R=i8b{NW5$sklaSyw|k^0!;U%mQG7SM8}q*8a*6d%&UqjD&3aNt7)> z2jZ<-Rv7}5qs+bQ6y6n60bu>7C~M|Hidq%25Xgq;Hqx-UljEMx&%C7%x-C8Bp9wKl zmfWT20rZu7S&472(Fxug1@B7vS_X?KsvYY!2bbm&&IH(s0{WH8itl}~SY^`~daXn} zUiNsiz075e8j^Mm$#$aSqr4CjoQ<~k6J-w({lyupXjYs;jq71kVE`$)7S(uZ6rgb4 z(6qRFeq|57Eda-l=LWB2b?kGqt$9aTjmoCXvj52W=4?0OQc*m@n@0wQCV5WvntV^V+SsQ|+hiGZhT&*OQNiA*kwrezXY! z*MxWl-G-gs!j7wl2Y^_+rErq>&e{Ip2DLhhp=$Czq?plOM5h!Wc;Bx&*ZR!efun{3iIQZ%co>8P2WkobaTmu?fqN|%!K;UyrFBy|4kO7C z$(PiwBL$?!sn}+jy9P;n^n$xE@UOMHDaG9EB@f;?AjZ(hl4Z(aLF$0ZJiQ|7=~=eV zM_g)O%)-`N)V>u(g18)v|=hlD^hHW{{^3bGi|yIIg?yq zdQDDxF$3IEn*X$j5MVD)PO*k^?5mg>&boS|MpoayJeUgqeHk zxx(N&;RiH%IN_W!rCc~ZFPUHX#vS3Ddg?sdlzUQ7OK%{blLHbsAp-&;1xTh5yluKc zebAQ+UdgRL$?m&~9Ei)0taoAkF7`7duW3rPyLhs?0b zB1!`=6`EodOZubLJc_Oee6tA54ZU3pzO>-it;)mz*V>woa^@88YpH(L{(s>= zi)IZm4Jz*&)NJdsB_Bg}K%j38Iv$OB33cd%M#J}wM(<6@(Buj_L@Hl2vPT~=ybP6N zh0d8EzM?$y-$*1|+SMvUM$=j8nHmgzHZp;@6jw~PCk#d4?`nr zUw{vn$4B~zp~^^T zM?iC_VcT;RL0TljS`k_99h#4&f)tZ$%v|Qo1<%!TVQdp`lUCs+kpTn*RuY-sCHxu5 zD?gn5BB6b_s+}YaLIe;WDG-O~;Cgh_U4qjjmK>5wc8JRY7dJwx-V$qdq)!luj;G;#bA*RDJ=tsxA3UYC=10Zy?QUJ9#Q<9FMztJ~{ zUC`r2@E4^{8nJFVRa!1If_MX&Z$br0C9gMp3tnlVFeR^{ct`5_c+9etTot*t+)00l z|4{a_6q9c)Lsh*=lhGkzi{u)T&{YCL&5tzZFF3Teg)|jP@Fo>AF-{BW60Ytt6+omA zz!m^371?W@*neZxIi-l|(3`ps@R*#Vvi=DpcJbT3t-2kQSJOpJL^Z7}_AS2X0jEL} z-%!6tLT^?N22~GcqNsx@hwx%Us1?}FWw+l&>vJz^MCU{7Z(@A^Rx5wbK==4@$dfG+1cN}e=kqTm+H^O@$tps;rZbq z@%Yyz|8snNe0ucHb$Iz?f1kLwcfPlGyt{j`_wC@|;9um=rT25Xy?ycfGl4+(^XJdM zjGyz3jf?M{KmSpFHot%W{_WehwY9bXGJd{&`SSVm=cT2kvzbrCh3v(}#f621`T6jKUeEj3bkC#Ny$jAuc?c2e@!Al~jr>Cc@tE;oK zv!kPFqWVooHx_AybsVq3J z=AEgGs;;g+E-pUJdwQ0hewOaKo0hhd_+%#`aUw14JR;&e@cwTc?(F{ki#x_Y-P~Tj ze0gaIy?F7WtgP(+(1V^neVUV#bLj)6rKKe&C&$OfU&=sHQBmRH;W!-b-*KRTfPnui z4&>_U>f++!MI=8ZbpBs}frDkqh(*JCAjx<^$mJ z8SXz`R=lYEQCZz|^9Pml5^?!Qb>n1wI3UHL{OtA4&VolV{prH3l2k@nx4I#Ls$cbz z94hIOl>kl{@H_+epjSOXl`){y%YPL?(W2Y=EIBFNEt?xkc$j=qifCi7KJG_;y_1VSkvxeik}cHYx%_$gI&spg3O^t_hr z%!_YS(M>~OKIJ|Le*xCeY3Kva9 zpr`T@>qkhVq_g;a%c!9&0=VVVpS6Qm{{Cv5z4!Nb%lFqRzXVc9^nP?fCC&(aO!v=r zh6HQQc1IQdob8S4Nu2LbTi*}a&FcDX|2#WX*hgI=(`*dwz0^Pg5Ng z${LAg+|55ZKmMM)yaAioL1+MHF&f9FuRO^4Y(+ih-)A-9*_^vvk%_2@aCuqso3*Yi zE!||VFUM;GYdszQ7Qw1!x@q!K-1t?C$uFm}8#=~Rf8!a4DShMoV0;V{%=&B>bz}e~ zFAMmk)g}KWN$o|hO+Qz0J9K}rPe55p^YG^gnJ>DZ-NK1kX`H?sKt~w+T(JOBa8$Zv z+#noQ^niw!g@msr@C^;-Skst&P)2WKvr2`VZN3r41M*4HM0ssO`KWQ>u4iCcz%^Qw z%r_!z4ggNkWoT)95@b74(lEG0Kw)@TNXJw%$TLcDfR9SX%LCO0u{m z8XZoe{kqJI+aF?l0W8NtCA~Knj#<+)sQcfjbZ5}4!6kT=c zG;nbl=9*yEwTHV;mnj9MHCS@g4qZ78&;#Tj`d-<-yPJ$qBzX;A9U1O3LvcwiV_f5i z$Vb$h*rUv21Cl7!$3qQ?%UTBn z`mau=-AfDWgOqA4HVj5in@b)gl4~I9&AtQs+6qRd*Zq~p0}e7Y$TL6CR|WJB`(Rne zhtQh3Qc3F1KPo@><^q-#kZ$7=+(L3Mt(sY1RvX0VJFxQxhjTL;)TYt?#%U@1!c)>) z@UZ{F>O8x&+AMNPIj1*QFv|F(!1f;cdPvtbV#<@Cie47hWdWQ0c!RoC-||DH&4(z% zif3&T^#|nck6!psd$un_iV8#p{csV+n-SEu&t!fz) zZ)jg&ul*tokilMi#~3cHvMRKY=np~5R^a1|NFZZePi7#6%wM&aSplb|UPg|y*5{>? zSca&(V3B&uy|l8ZepS$WWBOlCbYkNe0ofuFCrNPQPhNc^D(xGm`ZFr$pDl4=Q8%D& z2=%F(-)vO(6CW-)u`;pg_YzE#VyXIQJ`csn^CVjO{y6MKHPPPxU12uJx=bx}y)NE* zbd|Am4uH?EiPYSgVS@EB91J03Hk(1AErzHMLQ$A%5sgDoDkU+N3ghCQaxQRLOlEXV zxJY0Z5&Yiu_P{%~dGrqR6K17%a&-xV*EZ;T6}hF=J=DmgAR(G z*Mm;g@(Yb}hG9!UvTU-6g z2D#5T8Uogl_eb9Q9jcf0y)CjH9J-T)VPE>bJ<(X&bxwGp!r???eA>6772!6w#^v(7 zu1ewEy&th4_ESlyw4XQ9xXg*OTamQLt1HoOxs)vrsZX9Kh2Z22`U)j)!R}KtzdPa> zu?iSe(e?I&33r%Y3u{|tLg4zqF4J_6g+u&4po$(1{<+m1yaDwDY}?lueH+^=7z)J( zWiIxq6hdBfmZt%-PI%ol*NT#i)y_x!@uvgUJpaKzEjyL9<;T<~I#dmDh zmeCZ_Ny!_rbKJJkiI#FW%B;6$vFdH-$n7KDCq4`sAR?+Q@t?iO}|4Xy5mQ| zrwV~*gSRiBTw{WCY(w~S9nd2r;tv4ceiTBm7Na@FiBwz_zU*H2#h>AWcQB#mjJWhn zeA)nmT~}ypiXFLYI7NjQWplXprknV&&TmM>A$J4;6R`!wDQBMLNN_ zs&$PSjvpJeJa}*%VPX@Z|D8nWkh*<2BAO_4%^xNlloOK?8~#XR|~ZL*c^}9F21v&J2t0G{jCGFs{X?M05{QA%#gDZl9_DDgRz!ZR;CTPZPB6u1Qs>r8)UAd7TVF`+ zS9RLc-Z`f-DbZ15p^wnsl{Sef%#jqcxFegiYZ=KPl28&f ziP(JFm6J3{mUOYLSZJz?>`aORG0O>5=LC#9X^;UJ7vwB~9ApZgl4SYjD&(%uMo&&B z)B}DrPOANgl(i+JN-*uYb+SNfCR;=r0EE(`0vwgHoNr{g2xrk3xqpA*;<@1hBDo8o z?)tmj4R~=E=ptVvcq}6y(JI|LkBNQmnk4N2JobiKN_tV4WHJl0*$O${9L`M1&EyN@ z#0F+%1?IZG%mQ%tY@tBUjDLfbM{|}(lK`LaGQxRWQFAi;x?AS^rkuHzym|+opWjIn z2-J0iFz&0#=`6YLgd;nY63m;^q;KR8D5b+q?|HoR|1seEo00Bg3j9?UWqoRfIzx_u zk{c-w`smUpi6w0lMq!9ipuQsNqZBGDrrtu5e^N@V7xu0VjKGo8{fvR?6Q~JYz{&|1IRj_~pt#co@>))T)EUSE zHw6g>d3!lKH%cs|pAF1%T0Zihs_-cs_KDr_#|l1lzKcZR5C=shq(8EmTZ%ez3M5T| zknw^z0(Cu#%P2QZ&=sy!h78-hb6FiTQ|1-Qi&SNeC{&Cf%PWG%M~A;e{>+AwnMC1m zWzf?Q!4|4YEafHQlI@MGqNm?T^yiKc16H0ruWd zRRH{FnVNx!ePMSRkkm(qG(jHY5YHvaa=a1gSfnhD{3SWX-;}~_mgj*tD;es`CFaTx z@Cm;i3h2_x&IBsRXkL)vV1FbjHjY9aY2c*Ah!+r`+B*YIL)DwY{m8v?=zjsGKv};k z8>kvqs!AWMiXN_dS=f1<2tj~|3ILuL2)Sy4HXx}5Ar7yQP38a-s35Eta;(XkuAUT} z!;+!`@~r0(tqTIHd3UCPp&%fr2M#a-?+_0iu&u_3l>$KwO$q?2@T&;n40|)G?5eH~ zTOi9ydGi6U;~}q(_NYv0uYYG**2)6_APDb33($wLSD6rHun(Rf1CdY<1PTD9P^IR3c|Qe$c7OpN z`wq5HSyQVq=nA-iE4ZUlE2LYxvjQu!V!EnpEA#YNNvpK4yLXc-d+=hn0znH0$hmy$ zxqb_}zN@UgD;Qu!Z;V^Ka$+ZVV!Vs{wyhbvvg^DX8@HB=xg8*aB)GQ$%bUNuy=EJ{ zS_npi{~EsHE4M#ty8r+P?Weoh+qYxOz3vOV?Tc;PGQN@vz0o_j^;-}ixCb5}5VMfG z>bsll`@RIMA>IqA^9!W-E3FGWuZ7ZvcMAX&@PjlcGmu{TfCJLvk0%hE!#l$C`@=rW#V4G?3jh!AfCNaqyD-ee zXxtTvw+@zYOf!+iA{@tZ9K^c_!2^K>j2MprES?!0i}9PrX$)=$@Cf;E1JaTX>Yxp! z|DaR{!7@AHGBDFZC&WUM+%}Y4$!v4Un0z*xyvbyw0DAjXG) z%+L(Y*(0!)_{Xm-!=d&7GC&5UkPe1S5Y@t=1mVaW0LiLs$su&kXp_q7j5X}s&Lou1 z@H{qV6Us|-1@9OE^E@^049~1Qz}Fnm2a$NrKurUo0sr6z>;%LPe8H5<&7cb9~oFUB(~c2X}C}1o5Eokd{zw#!4*M0ZrIvZP$jq#q%5kstqCQrw4NoOp5BS?rk59StXyF-mkdcNZs5PeA4`3sEGO} zwkopsUEF_-jBw50gN@v18p7|r+Z1lz@O=k)-~fLDwH3}G3$DQp?%)pV-_D)e?ET#Q zv7O!d9eG=Q77kR#&4myy;w4Jr0S@4MT-g87pb79DAX^I)uHfiR;~qWZ_czu$zTGe0 z;q_qvdC;AqI1sh)4pGbG@sZyrYUD)jn>L=~L7w1C{vS};2L%x2cuRd>?%_ke3CY{6T0VxuIll@j$Yu1+419< zE^#03$ENo?xs^Kpt?fPtW1 z?6kh-%Ko>^E{~T!=+2HFig*XXF6_1n zQdjGwz3%M(o9_OI=kD$JejYB(U-j+ctbXkP-S45B>^)5AB_8mpJ|DgP+n#>l@Gk25 ze%$=d@R0fMqX_X4pYQ~K2YR5^{59U%D)RZR5ael|=n1FR|Bw&gKnZs0@E)IsAm4Ml zF7GT49t7^Od3Ol?`maBa?$m6d7^e%-a z59aP+0NiQk2=M?0Sl&lZnQ6MFZJMA(kL%>V$1w(1~&O6?Xt zT*%=c2Z$9dUc{JD<3^4hJ$?ikQshXIB~6}0nNsCSmM0}rZ22+8KNc}LlVwn$9UbVo6C>lIce9GBB>EKO%zst?g@UM0+Co;-Dtha*@Xfyo8Xsko005f8 zha$w0TA1Tozkb|SEL4Mz-#=*}4uTa+79s==g=fN)npp8-#*H06h8(%%%g8fpO70jH zvqsIEGj{fD5wv3}cf16^IDpr?ETK8)biHt<|Bb>NAV3uNYGEdG6%#IOs4)e)9tYPx zo3g&6xlIfDeu>`!JN%s)%EsN1tB(diIeiL$=)h;Ar&p z>%*3BU$F-}cSvM>;vIM{kPiU;;QJ>9jEIS5Ayu}5=#*?0B8C}_==g^p4gc|np928c zKpJP#I>-`q2sr40dL98_lxk%A=M03{V#uMvYCEhz9e3ohM<3C9@3Hvu!>_#qT|3gV zB#YYO4lXo`WB?GWPLAhDhp(p_*ZG z0DyyOpvmANP0ZmA00ig>GZktULg61Y{{WDXLJKhp@<&G>g)~x0L29(IA*-a4y(Kr> zRI*NOBH@lZJjiGPVBR?-)Ac@049kq*$OfNnE?FoTXck)IntZ;Y1f=8a%;tp?hW)Sx zd|I&qhhf@50RT4q0c8dYrF5pJG8om>X_ZQmHZoUub&P)CI|9JY9m_SL4@q09A8OloA=JU za?3COiSnqqCUS7NJ^#Gx$4c{J0F6d?=baHC|B3aKB(GU>%x9;)_K#$bsc)A-7hFfz zZz`N6{`}hrk#}k_F!;!RKM8i3ako8s>7$39CEbVa+;`<6V_u^spWNt{cLYhEcTTsL z%K40|pT2$f?`B`6>%T@n z0|2yQ9Bd%NG$51_9EJ{rXN=%t5@0l>Z3GMN_(cJds6*~C(Rw1p85F0uM?M0{fhJjp zB|e~!KOCe6F%k~ve1^s}GO{Q)9Kq6zP)lh})0@fc<~PM@OBUd9YJUu6I@PJ31nPhu{AkAu zBax4XRO1vD84r0ZAqRf;)1UtYXg~!zP=XfJpa(^0LKV7DhBnlp4~1w%CHl`U+@TM1 zIA|l@p^J%j)T1Abs3pufIdrbmq$ib30v{j)GL#}6H<)KV?^%&oav+wo9A{2<8BU${ zl$Jd8X-|O~)Nu}#sQn`WF>NtETN;(9-gN3yiCNAp<*}qF#cEci;z?(?0+p%+04oy- zL614oZ*+VNCN-#qjsQ@A57FdF;wqDo#_pl+OV~~Xe01XgHMnyJqk!HnS zQG|#xjwGTf{}7pLNg~@3PFBp5dc|yJ<5!9_us{c;@JAcEC=M`6V~iLnV`wHjlGU=- zjzYm;0`PFOjui2TkbQ0Ia{IcvHqbno1#WO}cUO+QA{_ZhhciSAfEcc$9>_Ss4GUY= z!&aBNKY^qqJMzXj;ufv=Lr-PHby?w-cb()FNosqC*u)xkC)G?`M=Dv7)`q0Mgstj1 ze`{X;_7}aIobFi*$le?lMGH0k9YWhzPkn9cZ(ukaQ(Nx7mlKZ=}J}s6S%-0 zJ_%AiVmw=j2Esf!u}LWWEe&JX#R_aOWdpps0b94jHqoHGIud|fydw}MmT(V){F4=X zE5MZs|9C_YY)kNiF}=i5H*wAgtTUul4dYZ3nbIHbv!9`y5)E$Q zBLNT}`3`;N3-Wp-jFyz7S3T?}wt918b~2x5Eo+s8$_}LR2oeG~z+IR6alTIPsf)c| zVt3np!nTNd&u4AeVmp)OmTPX;NZXG@DHfkWw@DNoZf$qc*xtr>-oRZEaqBPMlKnTp z|H-Y}foFG;9jO33-q8ej4}2%{=6Ag_5~@8w+apa75VbJ^@r`i(Aw++a(vd!P&nTVgb%Z)pgznn3pS#or@WKW` zB8!!EeeL$WJAUa#akBT_$b7#e&0)Rln-{)pXLA5Z7TjRFw;d&3hf#h>%5A?_e%qCK zwHZ}j^Eht=z9jz$i8%uKt>=BxlD8}6Ex&pe13q$@H?!l@E&JI^9VDgU!p@1f{~ADy z-t-b!ADsnA_fV)ez5@G(_Y}=9e#z2e|+vIefuamds=^= znemg~`Xqtc0OGD=kSs0{=C?h9Q19FB*FV_bZ=UkU9e>Re{v&3~gTw;~7)YHFfWOXL z46w@@{IkCX6eR{MiSPq21l&0O(}>R#i4Fq3@@qWoo4fwFil7AYz=s_XI|o$3 zkVrnk>p$l+JkBEtoePNyI29y1K<1O14+MZv(1u|-0TCdLJCAX|BrjZihw)0 z1Bn6XFff* zUeG#5^fE`x!WXo|=JSZ*0loHnhxbb~4*WUnBM+>&2oPuoOW3+^7zIPb8Cvj#-owQ& z)5TuoMVyPlj0gZ43<&^=2Lmj|O%#dXn~mB4#fzwhQpgBnFa~M78A9*{54y%A%SLWY zHhq-Ak8rjrY`1ri1-vsyg7iR+(13N&1dKQUZb$`rw3!j`1z#Y?|9gC~eC)<;%*faa z2{mK4kjSQmGe|XLG9E+)HDCcWaE5d!0RR{VcLV@XXag4@17o;{8-Pfgkp*8M1dBv6 zjNHed6iQ#*2!k6564Sj7B+0GeL1Qq7d?*KFcmd-GhJ#QAama^rScWk`K_t|XEbxU| z=o6p3Fre&5ZPduK+z1cY1L6^h1u!CO1c~5Fxhu)O);q+Cv4CChg&!bG3^Plj97@4d zOK*f1TN{bB;RWg&$w(xZyZpPnte8gd1x5JFvh>Pqb3u+=$_aE#05F?p8;JoBA4K59 z&g2`&}@iIY!oDFk15HweWn{gg!V+|P{!#*&B< zdpyn0UBvbven^^D#Lnu^3Ek0(T1RM~9We^7qFb-D$!n~Bg3KG-0WKlV_2=o+* z4p2B84AV~4#7~_(yTO9jM3GW8DLpEIe@Fx4pb;?(Qt<=UU_~qdHHl2!R8EanrW8)Q zX#idDg(N`MWMx1Z_y;;si*!&2Z7792p{d%qDX9`FV3JpzimG~DrhCO#W}??zqC^as zraNVgqUzUug{p!z*r{UDmTS`jp-jshS9O9S{{mQs1~~{!a04BPgmORzd;*w#0;!M{ z*^wpLk~P_rEhtB5OFxJxy6XjuLfM#=*^?Ei5G6h{1(zo91zljwhy^7mYK3r^KUA8^ z8-XQRO4x%%rlfr)ePvo+a@wcOC7^l$c;SKvn5GUm6+pcQ@iC)+k8O`ED5cB2f6IqX{|nCO+CEXf%?3~!>Jyp_@BwM=?0BYo1)6KBr1DJp4l@y2u zb-;&jKm}QyTPqD-X{|A;>r%y2xCd1`+&xCX9bUVk$ALuNDXLN-y zjk-xSwZO&8ypc$XJm1r8SZJl+YXjf#JuK1@w2}x(U;SR&O-=ia%*xrxp4{IPO5Zj7 zUjQy3T^)%p%~k?cU=ST&yFpW07|RG=pb5s_3NE(*E6MK5)5z!mz9du< zF5&)_)b$mzN=>8e%21Ms5;X<6{|??923CnO00(SPh#Wu$ICudz@P>{B01Z$FSfBwM zK!$Vh30B~SIA8%XSS~Y31sl+WHKAfI){%$RVg@o{_Kj2PjUcvk%aQ<~LhCpb<}Ecw z2@UXuHaHH5aD;q7001BZ5z>KwkO2U&fqiJy2+@XxFos3Bh$@bZV#S5uePrp0R~hc*_W9*6X68+4@ua0|FN z2)UpOyEuqez=vr_gIsxr|Gx-}?+}cKsHq&WoWhOgZ)4=zt>+mA<5h8lkvoY35FcW+ z=en&?PmVz1a8~3{4(4zU=#Y-GaD{(}Zq3LsitbFz5u1J>a5o4t={UZUTUre>#*)>qbX98SQ}s{-TC!m4^9jW z(U869kPiuw5m^WmIaU>65mDHOg_wYU5G{1Bk#{wWjxG=aFir$EYT7|+#kguPfP%+{ z?8uhv$)@bew(QHUY%q`m$Hwf=_UzC0Y|Z9u&?fED_G~M-1JN{z3NRu%OzBBpQkEtO zH-Qs5p%Xj76FuRR|AY9GFlmE-C|WVVX+)WjgQ$>2W@n2@M8i$&+F9(xxau!Rg6XF2 z>bCCd#_sIa?(NQQCXfRr;O_7i@9`dQ?*?!3M(^|%?C zgscdESzdu57=u9=06+m`n1^$K1#>=#T#@35k?;aBUI8Cuw2w+rUnab}R92Uuv<&A?^Mphp>{^2&K`snGH= z7xWMx^FcTC4lndWH*_ax@6E39k+_0)h=(jDxHzw0si1>o&AHK0EcIs_mWmSCglyP{W%z?rc8om7j0YZd z%lY%CK=oH2bXR9~GI#c8ckwgd11T8sH6Mvj`-QZo?~Qbf9tR0czz2Uwhf#3X#UOUc zKvS_ic6}>#1jTa5SaxX-^Ju5{Ew}f34{;|z94**^YkzdbI~6It^?rscF$H&yFab{3 zhI$|d|2B{WZ8&grfA{s+OJCT5cE_7!FN%5BcYG)DkB9b<7x@-%l0F!Mf1h=ch!R`i z@yWx1D@c5EX@q9OWLMQp85Ai8Lb1A@Z zfES5Kj|U{B)Q^t9Isb@uaD_6chzS6Np0D`zaLru~daN1xpD22!S9%s_`xZxfrYC}a z&v2;+2@2@3H%km$KX@8GAfO(>if{yOz=v#jp^P|pJRf`YaA#kD=d<6=aogOrc@mH!CG;sxKl`n67DjPOAq6heqV1AgEH8yE$BK-Y`t2O~TP z{}Jei2b6q_(P+s3;K!tVdAEGc-~7xseh}yUl6U$$m;w#Adynt|21D$E*YUrNjlb_g zj4*~}ScqweRE+Qk+&A)j;Csh=m8nl>f7hVkY@4*xjd?CJ9-P=N$+`N9(PDAJ@#mojbY^eI%FI(bHYsF6k0 zq!;8c+2Qpo*sx;9k}YeNtPnXu&a!Rm)@|CgZ|BktyX6iZB4N{lX>d`{J9s0q{~Dx7 z_^9E-7d8HC{4Z3&H;#I^ktS|KL4A-0WoNP*0N{Q zu5J7F#nrU0;*PkrYu(_&_o^Lke0bdB%EeB(b7zWJzJ4XbfcH+2?8LntYTph(BS()3 zLA0}!d9%RI4xfeCuG_o!9lmy1fN%dk{`~mg%jT_r;BU(b$X0R#8i-bL2O38N9(Qap zmUI#gV9PtS1dts={|(gLb{eH1Q8lF$gpx`uX($kXC$c6$Exu%-B8)N0I3q;wrGWrJ z2&7S!e;Nj;Adov07^H$j5;@mhc|j;gUlJkm4lsjZSdoSt_U2(k8myy9|3StqGmtc` z9F&R%0HksznrG6MB8^oM;!7-T$~h;U_Py7S2?UAI50C#~b>fdl4rrvH%Mn_rSZ6!n)>8 zbyhWkFTF@ePGwfI1Kj^Yre5Hl(l{9-Nv(p8`THx4HN=ZvdznH|4)JVG7HKryR7eO zu)yMvF*3vAN+%*945+dZ2M4Xs1VS9NqR>^#q{Rp|5zjmLYMkMT9ryRohgmU`2|<{A zIoruETQov1zU=BX*=5UHt3aTXnOcwkDI7FhL&Mz`(9RN(2eoEdi%0nRemR|&jFSQ6DJo3r6_FglX0006y^>j(w%jypySj{ASME2g_s&#*#J|0~f1ulz$6?BWXy`1}8V zQ{JNv901@F*dTx-wz0Eh0f&3!^PU5>2RA3^;SO4$Tlox9op&IjH}0Dh`#MB5!l27u3{ZRrc-8Y$!g>}#2@dgS5RBFjx^Rcp zVX#pJS->qSGyo5VFh3t84E&rj24ZZ(8nBo_ZMp_PEcgN!$Fm_C(}}?=e|9HncjIy08PU$|4WXb{l@QF{* z;Q(QDp&Da2LrW6VhWt6f7ziMcGSq;Mp|c|?g@igiqVhmVyn`257s#XmUCEdvla$po-9HBeK05%Cl^F!U z0BG@!TP#4Fi@Z-cp>j*5EQ1*$69F@}W-?%=u>eGY0zN~kys03ACj&bvGWLld?A5Hzf#sFh5DFLcpRrP7sb`UGVV zM;T45MvSk)vBDkf5QVx}%bS0z)I+_MSa6LnE5p#n83Z7JGh}03@hs+0ic;6jy6mn9 z=|nZ=k&a~0U?37`g*xbgj67uoh&F-6Pyz>HScW*(){1ekfeh1-hE-h4 zz-WTSuM2bUTZZ6;J9MF|gmv9ba|+Sn&XT`VJ7-pA00%h8z&4)spM2;u-39w2Y{;{JE=;IFpslh)`|C12wt+b!ir0o#l>lQ8CK@Wq~ZC|bsR-XEI zeZgg9aqY@cHL}P>4E}MQ-t&r45JVJFjff2Xu_`wF!&L$iM@k9;fsSy%2LG6W0&UUtQoacP!J*!y?d%!K9 z(Hv(pz~GyU5Hq3^t>`dkKn@vLG^8WF=te(U(w3Gq3v%3)G;vx@m%V2p-~{ARx9L6Y z0OLSr(2j@@U>WuUKqT@(kZPR5Afa$fV=N(uUGuuvzWz0^gDvb~6T8^PJ~pzGt?Xqp zyV=h6^&A@1g*iN14u8CNGrlowOG%()>5Xjm9c#3fe)O_Ob9f>6RzewE4<+fXSl=be3v{pq2Xbe zgF=A;1A=oL(vsW_09PtnVu)-Xu76^wu3;-I0Sm=3WZz)k6K^2$fZh12fAeh#{sNZVb?C zq<852Ec$GZp8YxS%fH9<$1zJ)p_(CCY zAP_=@2QCE&+6Pso|JeTlR1(g`Ko!(*1On46LMyo-;n|W5E=3NY12g1J#*z|%&_ zQ!!;h@o-%bo*`1OiDWsTdWjMV24JDUp;y?}9nh3oCbETm(U*M*M-$}2LM4GT zC14*`q3&HFb>$y136mqnqEEcXCe*_z#6cXOLOn#8L}B9fX`%@tVK4>>Y-x!sbcQ1Vp4oVD7>A4xuPYJ5iTf`EOw(syazZ~;y_FSI7pQdilF}uW9zBo zT=*Go6<}aw|3Th4qv84CDgvTYY(h2oLp5vy^&O&8Er28?fj1Upjkpj#6j-X^gE_*- z5$;_lUR6Yr#k6$64;V)xz>*-eR|}?Ml{6q0NuyHGfGBvwJ~V?kh9O=HBV10C4pcHkuU$l;Ojoze{lAVA72TqH*hW$u0CQ5KF!Dn%Krf;rTK zF(_X#d6X}J6je?oe~a>ZFSK-GdAV9=<~@XwzDfUp+#jcO<1x zkfceX|K!>@B{4-;U%KQFDn$`GBswN0FfPY6DT#1Af#2N15-bT@GT>Vx(jO9rKTyLa zu+}vq;yoQfT>VyP8svLW8I^6o19)X`fF%GC>wgGBVl7Pf#!L3<9kQ~IgG-9jlwu!f+w(pOq!K1@?UCp=x}@@R|!WD z#Ev@v0{IB2QF7;H#^tYw=l`&qf;FftzQ;4D9lJaO07wEi_|%3TribF4Ulrqv)x{4O z|6n|9ps0rD508WnC7IR zBFP=(flt0gn!-{dY*VB@V|PYGC;Y=I7z8EY8bdlnBu-)_0wia#oLFfp5b_5Ln8Lr5 zLaHW(e10W;va0G?Raw$S5U6QT+NxzzVXi(z8Gr*e^lCv+LOXok3Gn7Y)Z#7X|Kcv< zWk{(E*eUC>DrjNe-L*pJdv)Rf2FDP@PNN!>n@(Mm*3vybga&v+8$g4(*4wH@L^u)z zIm#0Iz3t}>|= zh6e|Hgh2>{Dgc1P`YJz&134%I0VPC262uGyt4c~&aF`0T?D#2HA!7^uNAv;%_1Sv>_DUd zI`lxg#BE`G1Cb%bRc7TUY-LyW?LA>2{{XK2y@x$uh5NaH(qe7mYVG23B7P1*AJCVg zw#5%10@LIIfWp|L4(P33iVV`hKkx(e{)0d8gD)Y3G2CTB0H$CPrp1O-4;q4gbigbO z#t6)UyTLB6fTQQQpCk<5$Y$-KZtb%C(_I+jTr7dW(n4%9%;gs7@*QH3;tp_nZi+ib#S1%yf{98jo*VkrL6X;NK58BNiBAaP^(LM}9MA)k#Y z=WFi9@9x5lDM@Er7{MYy3Opb}3qMT%g3!T|6G&d-3?oI25`-h*sE(F0g9)TBECGJZ zLOe8v-&}Ak&j=s?#I!DFwVv!POXM)pp&gz@7FcpET!Dd{|M7OlF!Lt!QD7<3ZfTe9 zF}{kFAHzon;6h`R@A+=?6X!D{|KcOt@>zUheVs)U!~)X*127+mJ1;5P#wlU!X`lXS zph7c)H9=g>m3>6QKj?!%XD~s(Z!PbY{31%}2q`2Z!Z%e2c1pA+zjGRQa#eKdr-tgN zmMR0|^DK+h0F)uw1rikX@PAW+CV@B-NuNljCQU`TGbLc^8fDHakUv@C-UGq)VGF&DEr5e7JT4nA~)1V}xzH84X(OaL_qLm8X_GH8R=Ap@TR z0H}+4dXV}+pg9MqIjJckBlZT}{R8L1|9S({xwP8(e44C||7aIeOBVE2U1KsX8@a*$ zFLe_}6yt+q_=EIPF92+SG&sZC3WOz~12;ZEJv;&cv;*|=Lm=}*B>(`K1Av+Tu)AB* zKHCN={KM_CJIsCjQP8?=*gEg-cqC(iH9MUwR5m9D`=R@Lk}HM?$N?mjK>;5y0C2!G zK!fHCgeI8786f~YL;?WV00Dc#Jmf%ooVY-Q$$g`GNTD(=sPb)?!#@y%$;Ud%2ZhSl z2FvfeaX;tw0M;HbLUYr?@hYLsvqo7FM%{nlq%OtJ3Vk-bfV%op4d6p7*Z>X;LpvBE z#KO0!po)EaJl5lrG=BkZNI+wN|8Cf~`{NTt8Z3j?uPy)t1Fn72h{1cw;(0oHg*ztr zEmZEw&V6d!eO17Iohx}#{OlSqpKG;2G_=DyJj1IG1gK}YyTD6MjJ+C_HEl52KbYa= z@5jf#0Vz1I=LZ8bsH@0~zHrxiju-b+4?!LzxK$H*&A;%G54)t&evlb|8Ud#+kbhKg z!apQK^JD%|{KNFizeJQhZJa$hm+%!>GC;svWMoG{g9i~NRJf2~!yQ88fN21LVnvG= zF=o`bk)uWhaujqFIg;eak0DE@RGBfwzZ5HB#*|5t!#@r)apu&ylcWG#zOwL~iSOSE zp+}J>Rl1aE(~LE5=KM#e|6;Iq>AJNNkr4t1uQvY8P%xHkS+i%+rd7K(?FTtbgv6CQ zmu_9Vck$-E8%9nTy?+4*4jkrBBX{rK(E=lwapSyv&0JtRnQ~>y8RTTJyqU9Q%$hrg z?##laQ`0b^o>skjWg%a)SZ5^g?_X@&w{hoQomwhYijU&xptG&o0gRz&C$}Vrd2{E_ zp+}cKoqBca*Rf~UzMXq_=!bqG{#D0&dGqJdr&qt8ef#K^O6$JOTYi0~BYOFQp&Qme zZ1w>RP{0A{n`x?yT=<6#jJoLxva-)`5 zIFh0Z-g3ywE3v#1A|bNu(n~9cSOlJT;;H2hJEHhf%{32#NFpf#I0;TUZ*0j%IC)AE z&piQX!k1kvz-HMhJ}Q!4?<1+iNM+2f8X zHZ9d5Hz$&k&LdY9&`v~gQWRDq1*pXrKyZuZA8=;v)mPkP9Z7>R2Hj+g6*NHQ3>Mh1 z#v2GC{U=H(DK*vFg)+U?)FosA5fLKrxTA|7v@Q3ch*D)0q&e5EGrnI_3Kre~0r904 z0c?YSHb~~}|JPrn5MB_Q<%u1(xFZiI zD!vv~c2QEdWLMw)m!p7H#?69Vd}+eAOK3B$<(qM)$tK+%KC;@7O{EyOLyIOTL<@J&Lz0}gR8bf77i5FadYxtmwAhLQoYy3gang+r}SegceKj- zv~p{b%w zNksrY(`tjP<}Ss#lJ4n(mP)ZDKm(dknUGT^=CltwgQ!kRA!1Cx5JW?)z%(iFQIGh9 zqCQb+y#P**q1PmUHVd(oc6?KzEkzPSPvg+~K(vGsRnrlS_6}QIp&?Qbl@&~R|4)y8 zG+iOJ;z$!$(rXU1phu}e&0HGQnJ9H7GL;WaEof6OT>*~oSVRyS0xofR(w-gls54a= z$h1Opn*PKZRdGoGTcz|U0`R5{q?%XMz|=HW)eTmgDO7C*0vPYGsFgaFhk6FptoTH0 zG}Q`Ow#tW^Z{@3AGcwRX356N|SO;c7t1~U$#;>^nEc>*2r5_ma9mTZL()N%)Yzg+P zeO#+Z1t~yRjyAL%8NghH(gWJ~rnkk#2wYQATHKsgdZ~2?=rYDUhu}?b4RNmD9;+j1 z-e|i#bL&Mq@sCwx#1Y)UM>gJoC*m`YDZ^PW;|6O+>?0kni zItixJbpZ(0rLALaD_PvK@VgZ$130iT-ix4tADpnkDD;s72wrx+zx4$ncCrcD=$5{{ zweLvqYa9Kpj=u>ZEE4I5SUZBuz>O_scDWl_?dq7a4F-S)ywL_|NZ2CASVl#r(TWZ8 zw!|38f-iKj*_niZHm_)MiBBw&6vt-8o@?}Nn93EpIU@}C^H5>?Q~-NvmrM&!L3dSf@uSpr01f02bQnOU~c zmiD=*eOqfYn8Xy>Kn`%8gK7*z!$od40HmShKy#SB1(1a=kp4B5i1;5{>9~oBemP-7 ztWqz(t|sM2W=(UtOJ5!ujtRbCR{FRit{z4yD1wH4aH0mG|HyE;pH7iQARX!IF3GO{ z@rk%YoyokMI;5*EZRaKeF}1K;mYfZ3R87w&QI zfG+4xivf^C1N~s&!}qS&k2mV?Ya_O#wHkz2WbBDu;b-IBChQvej>~ zUUbKmNCaRF+B7WnpdJ3UTc5et57nkd2;H*1#PToYK4iNOP^kd~e%n+wXV1@J0kny9 zf{G*Xf1aP2&QghMBIwQ-C4HY;VR`=ifwd07b0?z3T*9CIug81Yic~W&vL^f;OZ9 z0c6nmXfSx9Z+ND!wuG=C?hT1l?n|^U2wx87imKZ7iRMV^3QLR-7%(UuK2fr=^cOVN2ix-Tk|G4gN{4lFV@cVjC5r1#|g0FJekiHIx?r=fMehj{9 z!w#(w4^=}Cn}QE@F9c6cem159o9F{M=MV#n2*VEY3~&uO@#(IB0TT%T9w2P~q31MF z^&(M%vQT}t5W)Tp5XR&d=15I$&r-OrV!SW>{}$018!4*`2|z62l^=&l#`LjkgZ zHq>AjH_^Ku&GiDW*hq*Nb?O+!@P1m(5W5f&S&;-?(F9>p6Ja1fkS-P;z#C{I62LJW z;p`VFC>Yg@(gI;jY~k>}L<;hz(==rnC8ineL;UK4BK-~tg|8avt83_P4*x+C{t+Mz zZXBhr9APib4pOH&NKJ^K55xr(-LVWMvLc^xB5P6_AJJcwP=_qwCy>q_{=pwZaso9{ zCp?iUK(YG{Ob`yE7BWpueju^>&23Z>wGt5;jW8fF5)xx^?=BAM@N6iFvMZh9D3>BB znUS^v;V@|7ozw)j+L0>XaTU){=F%|o|LSoUO+X&#ZWl66ETxJ91@eao@{$A#9c#fY z7xJg91tQI5CgsB-bwe^cF(>kNfHzypH>pl0NeK{jN+H#xj_hEglyfevG9DQ*D-CWd zb+RZ!%M@s19X@~}iVx`m!8;YojM88k%z;q^U=+;Z9-LtY9A+@ns4zk8X~^>y%=1e? zX;jL^F)y?^W%D_6gEC`kI^m@{|H+3Gq_AWLApM}Msr>Vr%;*hB0pW;?6WT!zdO#V# zL5zY;G=UK~g>eV4AUurGQjjTxm@R0Qlf^U?Iyn?KJhZPs^mph}uaJQ@i~$NOA_+Qk zMa9XQmP7!|ffFd=1MuMy9PKy7QwW{_V{$-pw3J1obV(9q3@RcTh^!(Sgag1rEM{a<&0<1Kk|CzNp{y-ND>k!Vv5AMegn)O<-HCwfHTe+24;X_ZUlTQ;$ z09@fd^OGao(D-;2mV7nsf^}Gn^&%cMQe$;eE!9-2`_E9dbDY1P)qfRX+I6iNaLXt84r>0`YVOwVRa%QQTtZT8~9 z5H2Mufe>cJb7o-^K7kKhLv&(u=>?KwK~e%6kxmIX0Du$NAvluZMvoTo zqzw@eqY+{jA>gtP|D4@dR1*)wE&K^336PLbr1##WC{>D~C|wZgf`EX4i1Z>VgpSmJ zARR&#klvMI=p6y+0)o5?cNe=~`8gQ8;+@mX#e8%1v0}i(qsYHDNv1bN>=?v8&iRy(K$T&x;6)%Vo zZSjuu)9r)bzYebP9=rZ2rEb~ewpR(?5DlWG5669Vi6Ccn;Pn3G0}1z%Qk~w~NYdP; z_4{2Xk~3kVM(d!1dyLOz4W|c~aQv+fUbc0(eH=4tP#O89Q?`nu+8 zx`e#Sc+7Mk>D;IR;5OJ}l)u^Ky~M=PU3vKTzxUT3&rioan3|ZujK%E>K;%B6h*s3IXQ;sEwJXt09H76alOmwa+hg1`RJM<>9@f)krIeJ4PwKHT7bjO|XH4T-yT0aLOqy zCnl?ey9I${XOjyL<8`Gmmrnv8Qb@%zXbUBUKA81oKD~!G`FLZ2!FcIJe;jvo6~q#1 zB$e%(;W6u`aOx4_2tC@P*Q&-;@>pAXCTPp1h54r4CNu|D(@qPnC34d^eiW=|3aFi} z(Kp%hV~l+L(d9{HB;&T0#qsRGN$9W{dhA7*v!B#V6FB;B*vlC=X_P~CF3EG^c-!Ud zS`C)riQuKo~6L0DCT;`@k>PC_lFvlQqnr*AFJS6)nB5<$hrMR*ES{j>&13 zpQ49{?&*-$4WS02!2(sP!mp`eZ_NuInx}ATQYVJc?&Lc^mwP{mD7wEB@kKCFwTMi- zhYlxHaC_I2YOFY!x@6k49Pd~3(L-BoyleFLUT=_ z7>5XOp0a>oUdu@Ip>#*qn=TTCM0WpSCI4~yje*j)$Pe{8AK0Tl@bW>A;^}83v5Z{S z(X^Vwx2}(+=T4f}&z=eNiP6;9u&voJ(Kd4l1X=HM^0J9^02~kui1HB{-U4D2P$8ZG z(K!MT%rc8g2hCj&{E;=y8HjScqC<3NmyWp>ANKmKDx(`MYHPMeOg@LzKd13ij_?zz zt3imvV2^ns)_EZGOWK>&u{SQp+)D&51r63vW_MfS63At}XN@B>;X&*4-K7IqIN6K! z!(G$}^bPkrP$q!u!-x>ohPMo=zc>d4;~^yRiVs@;8g_o0Yms4Y9lnD^hTtz;IDe2O z+}W?=rjDI9&pJ%vnQEs7T3D@rj2wuxi*d3(yT_`s4C1rC*3cezor_5y^y4gs>ncWh zt&CTr#dn57&LX!yp6hKqs%yP=;PqISLsV@&Z_;;Vx+)%j9XU~L^JM3Sw)^038#>&S zOH>ETU?7vdD~Kg&`Lp`tNplywJ1CZdbS{r2=CfS(rgj0*$L*IE^LDXQqC|2~@DR;9 zxFJY76GReIpq@QC*f}}=MWeQtrMq$!y0k$@d$ahqQz-ky@GkQRDcPjB3S=XQeJ-~_ z@CS^?1~y^MI0qv8IQ%VOo=XT-gV5qC;rV7rqVolpTSNuM|w89b~_yc5zhG}uK z?$2|#+0d#HEz^!ou+@6r;c*}-TL#2snG^IUY@=U%6* zH4~PTSVVigmG<+e?y7F| z>h$J&Ww$`eQ(JQCsaT;Y{Li;M+3g1#nal>tyhmjlwacX73zC?8@IC>u10dnKtf9$s z+RJ;Y9J^B$yHyXl8JJ~wti8K)ald(xc_ur(Y}q*SnzxuP2vVIi_0FHx<`Y zKIQOK(vG7^y|ATS*!-uKFYxe23r9qMT$-fwT+5rA4!X*Fi)7x<_Ft^lyCA8KBsnRGVPV{2w?WI#O-lY3zq}ZUKW05e{UHdt zG%}+uI$!(-)t$gg%lAvc9;Q+`zU!Jz-~5ilLcfP`CWGj2ARM7%lx-)}B$0gCO%KCg zZu+tX!pBK86!tjs()5kzt9xn19``QAO}MPHg?%U6Ob-)yTJR%*o(vg_I$Ocosm7jg zMFaOAy(u))TEIQlf22i#_?CJkN>LK#yd%?(fh6}ch&T(@K!!{Q<2}o zoYI*+Z34%BC}28=@{EvO4G2YlCU+pKGHIst74^P7ad1ym-RlXKHDL7Np2L7o3uCDA zFL{f)V%=!x?5aE>6F!Rg(P%Mw5uL*XxWk_+S1RU+KKWmEV`kTU=Owy(IkdYs$Fvqc z?A7X?haZ&4I5#QF6S>o<3_ln!@tkJ5w`(xcx;xKEx8G8$;qU-ka%Wr%Vt@2aTSmU- z>wKDp`NW%GT>^}Q<29M)T3hp8KKdP-IMb4lHH+w9pbmZV?(tT`{9L!oM{lnPbD4=t z{8@C<%RDIUn`NNSBW1JHlm3%N)LxIQog$<-ji!r_3-*UBkhyY$2x{R)uy<8Unhriy}!*>d7IZO2F4&l zXv@$Rz0Zzc1CRV&s`bL=ixJFIbEB?Pb6{`*u0P+2@iBg+xmo^k`fz zqTZ|X!m#qr^oM)Lj!BHU3%TUd64<@W)Q_Y^l|d~ptlgeMMJcbUB!l+vT!&V5%^6=@gbw$z0D&oX<`;W;|&ht%4ax#46-~Sq6iczP`^l} zx|s)#)!s~#*C-q(PSVFwlVwk(J}_cb!42e7RnO}`SY7*I);$m$Y2cj4xC-A| zo1QXC{0)!W2x2bajDrhwC0EvkvRskR;K+TdLa&$EAfjiw_@oU!pM*Rn+m6URU9L_l zFS8emo*jDXQ=7S4=5U*0ZuIFC^;6w6^B)7OC_ndy#n-qMlt(GG1=I?7q&Cf5qrauy zuql=84whfM4_zd;aq)G0Xpkc`zarFFtZrH1nQuP%;fK#BybZ6gcjX78?Z>{&0=nB0 z)BbZ)$2~-$LJ59&s2*ULPfNM%U~}O_6E(~A;6d6v-G=jMsF2}jC@GtSJb(7MR&4qD z_2Hy_gC+5f2gKW>YA>rd1zd!{SWFVRy@+So$F#%Di{x)A)3f>$3Wj38S|0e*%u}sx z5`_pHb28q~1=C^M88-#mL&#Lsx&+psik8!cUN0h)j>ZL9kKGcIk8L8tne18vWx~KQt z%CFLb$;=)8<&V5X>M*ZOiN*3Wjie}G&pIObZsD-2E&gaMQRD}2bWwjyX)Q_q(0Yq$ z9sQRry zh`#MiJ~esY{HQY9tBm-jv*rEstf@sG<6Fp^3^U){79K&XE`R7{D|iS!@1p&b)@l{{ z_iva7-6NN$v4sJ9=N$VIU0tnwze6vY#p+ptQ(w&|^;`BlAXj(nXI2~v$ES>Zm)h+< z4JNf(B8m~SGVP(Nac`Tball~>4fFIF=MyqBS9$z@;WMvyJ_a|f61RB{f2jeKrI$C! zn?G8&!K>Yf?a4lmW{17uwR@7qvT7UXHIP&8_0FVq(Gc+_``dHX_o|XZRBZJISDh5D zH^QI`H0z_WzZ|`}Uq_AKb6BqI^AZ?j{beera%ehqQlyvhYpJ36UOH-{82uJ~c*CEs zfA+cA=Wk-al_UW%orx!#6-OM3!(FS8aX9!11`hU< zeU=iyNaf9QfIjMZmAv-qR=&54JL%_ZB0BEeP95AQDS=!Yd}ok=i}&# zikGLf0(~`QO&GGL3I>sYmsf=-Z%|X`x&YQ77$ltDAmC0heRT-w4TEP|HqXJ+q0Q>S z&X0pHBZ6P#2CJPQq{R(b01(U_h{qsgFvy=(WDrjBnf)*aS?ZHD3Nrv2wxkmW<#LMj zW|#?(Y}c*F(RO)TQ4)pSmyJ5`h!7<7J zVXFqj(WLUU6k+<%=Beo8pf~ig(u^83E+>?(#WbYqn&cfX3!r`m8h%ddLIJV{L8(Xt z2eF+#`KEPbLu52KH@d|yh8aZK1!ZqS#f0I2ZBzDshL@L$f`O4Ga)Lqxu8!Q&h-Z)>>Jkw4RgO73#{9C0-+|DMKx1V&HCv9jt{kJhH@M#y zN0ju@eVC!j7?sRED z%U0jEf|4E=(J-IHplsxo*L)|Mk~GLLeUB4MBNLr-6W<)#RU#=*F_a_NWP({F>V%9N zg`Z;K^^plrPBHSRmOTLVgp%P(HePxqry zeCsQ7zd${zV7jE1-DaRu8ry?=)u+UG%umsXbb7;_h zNs!HZ?x%Q~#w7;nWs-MVMSp#ZUX_%H50q33<`EDyfQ%gVl|c35zVveUykFN0nYv88)IypRxGG&GMC$YEkXFs2g?mb=4Bl40uqWJO^pA zP3H3keC_9nGQG1hEBE^GttuMxI?Lwruz`rB({g!n5=(XN2X2CoFe%*f_34K7qv`dg zROJ)3^$)h{eKRW6KTyTrqVH~}!MTx;u9K=h@o zG>W=63sTj6EopqeU02pe3T|=|<*XD`snt&DPsXm#^68Vlb(dTz{ z$>(@>91t84-QrnXvEE#jOQF0Q%{4*xxo%T^0!I#32G&N&&V(Dz4j~S;kUlVORT!6@ zQBfN1Hj9&~Uy?;ywT(h6696 zVc=ZQ7C<41Chl{iv}^~hqhPZ8&|@?i_ja z-+;f{GPcZs4GppEh3cUC3H(n=On+Kgf5uRMItxt}Y#>);ApfF2{~3PZz0QE~YTt(# zgSqa3*qs4_PrcYp&$LA7vJtKWc^C}sb4a{|`n)g*wp6Vfu0f9kx~ zkGU`86*4>%`HGZ2fY)@w z4a&6|)s@l5W8l={U&uI#exS%93B=z=5tleP2PrU&!DGPg#IK=1V`_A>-*EZND5Yf` z`~nA{fK~DKMdS8i=8oW~8lm@7&jtiGMv1`*gV1)+1P*2+0h-`|*}H-JuyC6FiTiNi zfeW$G>$t9%NoYbJY7C1z!)3PidwQ>Z#04;iUm~0Z zm^t7h91~z0vJI3cLLU)dl}zM=U1;fkKu zvmv+WnK8t}S;Uj#F#QhDR{&n;j!d_vtPBQ@^lx>u&=q2bhG4*r)1l_!8C-KyYSyfC ztWRI7I+TUlU2$P{pJ>912yH-oGKwdcMiY0AQhNLbt&78Cm!N;#dLNO!d#w3xY^8T? zA!p;dzj;gqwbJrdY#ZHTRS?y*^JvuMSMb;<<@P?T<8|kWKBfFCBt|gpwhlF6>2#iK zc`JI^MB(S=?xI0Sjo4MM#IM)10f|aiKc(1~RYuzOUU89^{Z#JzX{NKHxVWMd@N<{s zJ74gMrc#i0Krm`C)4Xj}FMIWoXuyMjH=@s1mENpgV_PN7T$5~Di+%aQp7OIpT$IJH zGOtJL)=KMsZNYc%t=dtp9|^20FRrO7ZQOXYanQ4FTk$RMS8fnxst;u&hHcaTY9nbR z>dlo@z{p1H#)f6UhJM9tch(eDI^Hi!AAX3T>_-t(D3eu&A}Bv@j+bp-HGF=`w$-b+ zRX?{lP>vizk;!s^2RSH76Oc)xl*hWW$saeW7c;UJ3lg6th(C6!Ja+zaY+Xq$YQf+*y6ma<*W2~4Z~WgEm49D;`TKhBZy@3%NbDp;?Hb~B^Ps*zL_9w)uZ zKkmdZN*EAyr=RK=7Ueh|#`|`fNrH%M!`X5Bz9=#KnxvA%C&NiH?uip0J?->z*n+^U zr(ZViYmw%X3Kwfxw0REpAPdht9E~zfsz+iz)|VPrUT+WQ{pR*;HraA4-LRSNhgqZB z&jxSjch4wU&C+;i#$zl$R z^QWF0V}*L}A1$1D<9B8Wy8w#|=f3;P-SPZZY;w^iOTS*z{IPZ`ayuzbPM9y5Yw_xL zME^Q+HL|CTyuY6Ptj}!+eShM7jRpkPwq^9Z%I)L;-IZ8pb9f?NDME71u8M;uSfZEh ziKIwhvg@yZraO_;xtW0|aYwlG!6{!!)h&xXRX~NMS}jE1Frhm{pdXy$WiC-1;keHk zK~v*pQPs|Nhi6QU5OS&R4j%9;V)aR zldHm4RjG240}h#G5){m~@1sM8E@j@>U6y!H;&;*(k;JTqfG1Cm)^oQoRvH%DaB7w= z)4MEiabaQ>{Ie@hkx(~l!H_WNM{Ywj-b>cY@h>D9ci;vaNLt|DTtYs?9+zO;%N z&BT&4l`s8W{A}9>Zf{{}P0kS7DOFm2&-WS7nxaGm`l2`J-Z78=6mfF)TXe#NFd^?^V) zWrX7c-TZE4X;W`4vzt*2kT6N(NSA0`U^l|ks(y$@J_87eRDfuID#H~}sfvgVy&uDAr*x0%pu>Tnr`n zvYd7FhTggz(-3EA3@Ocq1r`YjFjch13LVw5Uja*>+CXR)9l1!bA&7Eh0mmY28nOg9 zVzlbG&HgYafv6lYq+DG=ND?&nKIa>kq)vu1Vw`xQ4F(s66DHZQzEU#9Af@;5LBD3v zw^V+k$;uux`+9J~@SL6Hqx%8U1uT?|sX;D%ARw5jTME_@d<9wxR`|LElWXcCmcAdP z7xRO*&=>ib<7c47Acv>jDCOxgDJfnyL|I=MK1ApxTfH6Pu5mB>BL`+b5$I+RcaPVU z4F`($dzCIYr7o|L!11V{nMh4SyhtQbmrV>(0ZoH<3|GFP93SYG?~26Ty%G}O z2K^lN1VQI%ye})^KEvLS*LMzz%MmioN^^Ayv7?1Z;6>%^deE6I< zC6fdYt2`YP`FI$UIIqr3&ZQl)R4Y>?tEGx>=LN7!%magiEZe3S`Nu`qmaT0b8=&LZ z1bERQV-b?DjwmPDHL4ZAP)eTMI5obz`ftm4jz!;SmX_5Oip2^tR{TZ;h}$yuJ^Th6 z$HJUhgs;iGURB<6(yrW?C=|aQsTU+n)LROtQin;fdljUvLp2$Rvfd-d;Kx`lur`>|oIH?t4R_*E$KM(e;n z;GLn_~yE=ozr=1HhBi?(+0K@o`*hl`Wupd78AEdvP)d#Q*iu-aS^faKJ74<$UlfED3-OPedM|{ZT}~^hU4C zImqz7V?wOue3U1}a7hnc3P}9 zu{3*I!+=6JH=`LCTI4ff#Wby!Z%CP!WRyEF{p-z~&VzLnJIM$j3&MErBXmdU{5m?- z*)teIWaZl9WH&e%drCd@^AvZV z(sxlgy9KdyJLXMu26R$@5SD-uqWErvHg1Q-Xy?YUIn5IAB)p^r0|n@ z@5C7V$jzHObA^n`aG+}ioYFq@9Z*jnz8&Y8z;D4BJhvkru4oy6P+aQC4OPWUFz70T zG0`WNs4^R++46%a)#vWAKx%`GB5f55mMpA)GCvcGSO{&WW^IKI^t0cv{`czwf=}!E3A5)fb|Qa%27XZhEw2cLe*l5u*>v ztj_vXmPg%?_}{+o1OAi;zTR=bTb+Mf5BS@Pf4v`Jb@7uw@N_sZ;OM>8<+elM`2s%R zgn&97z7M?I4Gg?kx5A&V2jVaBfdC9en1&+~K@lsUNEG6%G*RGZD99_^PbjJIjYyhE z7_Z>x)C>Mj?#E=({43>ILy6=a6E;5C=LnunJ<(1@SsjvthaW z_*KTu6NnTBWS<0@Qodu9L}l!C$5buStVLPmAm?>H3H(M-U}UI$Qjn4GU3V6BkCr&N zY;GunS_ng!s!msjGE|R4%{&w1JR#FQ))OoqF(RZMu%jO6MQMO8A#9QAYVgpFMm)fR z)HxyoPk?~~6{b`Y357@vY=i_dsK-z3Sxc|zCz9M;5NmO$+NpY?i00cNIB16C`Dlcf zHTZ)>nX9p>vd&3_EeK6d(!!Vtv$Ku})F6+oQ#bAC4UQz~eHh`$Q2bU$tI$GgcAvz< zTB|rlt0Xi|M}U|f6Y67HT{5p#u`}>ppVSivaXkr@|E*Q4pxq0F{_oT<=l_u!KK_Rq zCiudqr&lLO1Z0>X4F4B9{AZg$4HInPf3)F)ga6Wof3Nkceud0pSOBlHXEMS)t{7C zTr^l+)T-m_#I7o@UzYRX%jot82L7iu+}GFlA8L51KAWHox3xC6w6uKs*wonA_-}By zrmEs!;BW;294;>}$CrrVi-`X*hfC4U_#|Cqy3(L+f|m%+i8zK{2Vf>*qKE}uTVv^Lp!;!s#vn3tD_#bR@Ear!`$t{lL`D8U{?^rv8~;$lLj0>jB6v>rJ#L;A4lX=1(+V@|Kj82+ z+AB)9rMbC@iHVVs(Q|F>e>=mvy1E2sSW{DzKn<&@s{Y3rzIE%CtgP(6onZ+HiT`J3 zn3k6Ie^SGgl#~Qs_=*gAMM82#M1%(bHUc#Ke@P8n^L4-ZKT*SJ9sf-Yd-4U*u*z=C z|9?`$LSHHQp%e4Bz7Bn^wC;>z)ov)8t#$lbYB|_Y{*CZ-Igq8@Sh3LTceqvP9RA_^ zXS7ZBjCNDia%Uus@S~xoYTHhJB5k_VA32QIQVh%HVN|tGMuZhZ7DfE)2F8o-=iPJh zkaCWG^gw5EZqrH#;52k^=D%kY5%fH-^`^sCA&Px;KXzM9d{p|?%n#ho{$A+h_Drqw z_mS4-zk5raCV1A1m(ok^{IsL@t=kj{!tlbN7&Nf$GU(6Vw=b1eO8BeYO9<9_60U(^ z{BGfyLD}0!6~eqg%RS0)islMon#<%uLe^k!LpYA@xR6X2ULKtSXB$`~1n*|O^xxF5 zl+?rEm1-Jx8iw_eDFfk?;#gb(!?*?1^PEJ zEPtN?D86lR4t>FIP{WuT#G17OQP*z~s9~=ur}Zp9$^z~<#flXEfPgEq)x;1kGslDo z@-)XlgElCI5Mbei>;}4Z=BP(#MSK07Suhuk~c@!(Q9P@wRIlb6<7)XA=6M zJ&*;de16A`8!Y*q;wlQWRWaE=Lr{rZa>F+cJ$_K${xd<>S3gT$=hFC{lBYsBH!`fE zS-e-|aA>>ZVSWn$weElusNuseD9H7rQ8nUNRYqCb@}qIp3=WhoH8aB>^aEm3??99D zJJkU`7oA_G@h6>#4raBlL)9dk3hnTB?pq}&Y?M}MNim&a#l7|MvcHS3{^BhQh9!Tr zcoMM0XD7?x2Ph)aNSTp663%&RqKVcYX@6d)?3tWqrA^oUdCk1R@riN*m&XMeS5Q?} z$%_mTPy3ya$Om-u+|-wJZ~v_yoEkvHeu5l*-uj=pw?T z%8i?S7DIV;(%V7zN&LxGGFG}%6K2+D)B0p zI;F3Rmv;;Wv;@JoLsgk~_g~z}{EBR>xic_4XkvDebNuRW7hn4C7{?twMi6bc;5gKf zO<&{MB{jJ-bmf}sw}ERk40rjx6Cz&o7;?a+`arDiuFg97T=e~Y={yFvUCQqFFz5%r z=e3KoD6u{J5s6gbvWrIv738U%=HGt&JNg|rFHi4Gv%2&_a@DIs;awU{CVL&e)cGhr z+aLWQ=mW*lmIT4mNUagl2PWMujKVKu22F1rrfEMbs(Mn4wrbnBW>eC2`-kZppS~dG zV*xO!0Ep73ic5)7_Kw_^M651r0nNIfy0DgwI&gGAInxwzD?Jw<^e(77i@16X6GtWz zJnop9tMer5%1@(JlO`P*yRpYMmu(Kl0Sv>%cVz~~;vP!^WSb~SQ;?F(Ga4Y7K=Aev z2ww4g23f4C5^gfev49hth3kdEsG+Yc^1uat>WYd^!KWqGkn~YBII0@9pZ11>NGeg8 zUV1Xz=#Py_tf?`7gU;vshI!WT4?}IYGR&D!2uIxy=FGpib(FmLzBU|#-3~1p5-=wtw^8QB`SuO(V}I zfi&cK_h{HpT|%5w=;c~9M}qFSaiO$jsnPV)0v;7G#;hQGe5W=KUg@_BuF|Q@#GuAuaD( z4|7A&mFmb~71Qv9Gy$jH!DY(#A6nLPpLm^rjp-!fXxNQ(Ra~b4m@c^C;u0c{_f9PQ z6Y>qqsl;`wiujbzhBD_s%&!$vB@sbZ=M}*zJ*9HMlzw zK;4k<;9@h<>>nZmu&;5(fI>6$qJ11cj_K|PLtK|0OS(vT>c02w6<7pD8@#qJ_YBED zk$z-oXcbh-aqmPfgApJ5ydekl${A7P_$kg#spjo>l~46S`$P(BxnZ&Va-DV}r+vOk z9^PM9R^WQ4F&v`qXY=R&EVmsw)UgpSaKuE?GCsJ^A3U=kW-Te@kc}=}_wuW}Xct{K z8mGGcR>V$$Zkp}oo%eA&rB;`_gCn1G8btXcIwLpKt*jTBoBl$MC5ZizJqqB2;|yZG zUv7E|B2;=DVX7B*eFCW#C*zC;oF@;&f)lT$i^d~pA8pCH7Jj>?cSd>h5vP~0!3tdR zv?_$^a3ZXV+YO5Zr}Z%R;f zL{Qzz>zl#4*40h|tGY`(_g3ugZ4}(wA<-vRCjW{;P6OnLROm_>bdRAK2mt%*Qyl8s z9PmGn1`{nUkvr@Yxmuf$f(RR&O1v0V@5DeRhOn6M*JKd(_-Qt-I|jTMdx1g&kyQh6 z-UpKQ4`d4;kR}j&^CBGuh;K%|qHzfMnjfHKs0QwX-26*SE*l8FPoA2G?E1^EFAx@d z;%+EFlSZgItSU3m(0vT?XTvi9*N|@#W#1&3zIn&+Cc+2#t6SFz3iuV8yh^?vc+GTL z#gxPbP8i58;DEnX4k7Ui7@2lRUM2O%K@Y1a(oEfd*Er6h$-B{%lV~ysNN7o)au^MM zK^+;=6eHCcM8XMi|927zL!6Ko#;YGmd|&&TIAZZ6c8MYGhiu%UDX5ZEW>4xN5hrvOhAHFR8heZ4E+Ntneuul~&XBvVLN5rEAJRFfB?!@xT0BI27 z1VwI#A^VFW{QFFtrVn;pB0uK{qA!jeVo206e6;OG)>rd9uF-lyBaT1~ulmLDA3u5s z1}yJd9Vc6z;k&I)R;~D#5KR4utL}I-ZFC?Q^Da!$3=1(v!VZ^6pqfeBbac7;$TK9I zIG4Pv7&!`1_~pfLohG91@*!`@es4~jEa_=Vgh1cZtG{HsXAi~+qgJ6H(~r6zKDl$=m=@I!(}OTK3k*?48-{UmvsAPqPo?a*k%Rf1Bl;q~+|r$XWgP!fYSfS(HQcDW_fz z3ogwTs&ecajR4T(#!e{}rwLfOT&*J`7zeREA!z0Hj>N`5!xVW%LYIPq@CZTdQABK* zJfTl{B6E47XL(}g;I9~`bet(0mh2ZcuMiCv(t-_Q@_4Mtm&Kpq-FR3UOWh!gb@O9tc?WI!egasx|TGKzRUnw+PZ8@?sFI%z^ez)JD^$}2TAH7~LW zNa=!E$vgj&`4<428<09zl5&={ESGcf0$U(dN@`wOtcBf3D=j0>d9RhNh=n}TC%N|* zRQ?p3@BiUX8aCGf>4AoyVBsBp>R&jJSxfM<6_^M^I>(FR5iRfGTQnp44OCrWEX?&M}j2!W|X$?dU3 zUQ2Ko(yT1cs8-&T0i-ds(g2ER;=F z17dc$x8eQmEF7O&MtTqNcC?c`^bkX_Qrbk`-y}{`7oYKI zn6J^I&eTb|mrd|dx@ zt5b61yyeSFNloI`iEolWrfoCMqqH-Ui~#`2;irxlZ=u<)=zG}a@wl-<82QJedB<5C zbW?nHTXv+jdDb}<-{6kd^zm^D=mi$S4FJTrBqMYxMN4c^bn!q&yZDZVn27zv z1n$L2``o$zl^{|Z=SqR?09YD{SUS~SxvB23$v*ge-MLc+c9+quh!+L`Q9dYzw(gf* zcQU(gR<{f5eCD|5mdn)2m?kAoaDRwwP;Rj^E$e=!zc$xTtW3Cd=yrvH#>~N?ogUW@0|!&xu$}?@IsaHA8k5Xnxrtdi zo$4cnFF&7+b00qv7IG7oQRbw7vSaT^vbmY*Ino%U6n^2wS}D~G%q z1;#SnL#HPhjwizxdLk`{*;{AQuk$-(G#oVazHXU))H;-+*q64@{Gxm&=91f60EGV0 zcWN;Qemz%weOiEQ*hzP|v~^DQVD{y4m5cVQYwLtd<9LJabkn7$yTZ3t%c=6$+?B&T zXdrOJa{gV`yjtcQ<*S7S{O-aHqIsPk(B7eM!7lU7?-x>A=gp_*3ohr&7G@oGXR3yI znyQBPVi$_a7w-%$#FH)R>dfD`0c1NP!{rfsu%(zAGsBVd7p#?6tV?aI3kTPEyrHwC zpiji*OCLfPW6zf^hZjB97l}ldX&x=h8cbp>ku)xStl0}3N;s;k5Z>oMMisdoEs;Ez zE}{YKY`&kk*nV=!{fw~qDfxT_FqkxPL7p?i^tzXoMwYe=W>gkms$Pn5ciHlEYv2h)%H0@y*u;AYUbAaY=AYGxr=g0 z983&?jPFx!y1^LnBr=m2#G*c#xbmufg`Y#5oqpV!)5xkn66|J=)Wx~_im#I;_Ye`1 za|}V9O&hUnG|)T_0LMW|#7RvA5Qy9gePTI%*cy&a44ELI4<6Nr6a6Oo<3=u1MRu`N z3?sN zdwEg`N!UAI+#~xfz;A|3;`$elivwsde%*+ zy{PB0^(V~~k1f9I4K3^bDw{|QMAc-g)|x=jQWg*J zz6gYJ{K3uy6jgDOpkf%+qL6YIKlShbyc@@=7(nvBQ^VIS+d>&1taZl-taha-ha|PJ z0LE`TAKW#U#PDBb>7&$xbc&E~MO}mroeYZ}l=Rg3Pv(;-`I~!LNV?LY%gi6XllnHc z@g}YdtE_gXE>AU*T2)D#6dfY@OhW5I5x{}ljAT4;PaTNR%z@Y^NjBi;L}>ayIt__ccLdvsW9Cg33-! zIZ|sO%d~!iMM*H_-`Ud`U*y}rF}_pUIc2Gzp!px{ekuy5aWOV zFDpxSjE7dNit=8I_6ADI$jHRL-pIr%Ov>2Ip|IZgp=-C4iKXvqy@{1GX%|8f2ueH1yvqT&3ENKYk_qBf_DGKn>d;7bi&?&g9YtF76Am zNDoBb6^(!D`4N?<{xE&Bfb5xn;Y)n&iGZAn@pG#7Vw>Pun@kt5{IhDo%k+F>Tt6g> zP+wmH8BLX}r&33K+TR2)GqRKVlF3$2pQ62j7%wDE%lDwJALY(8#Bq=k(5xq-GJ9JfTljc}*OVPwyRd zHsO-2dhfYoQDf++ETQqwhVY=&UzvtSsNk$z;hpe}F!fE5Rfc+}d*2=<-_(8WX<<2^ zX@0GI|6@#%{(~aW3D-py?9uqi2xcd)ZkMW3E&A7|WEXKmmzJA*2iKQsJAZXHA3mnP z*h+wC+w^W-WXbH)O#W$E8Mu<2$7FlB8u%xxfm5Lv@t!IJDHs|LLL+bQT*?Y@l=|Ns z38lBG>wnq1HR!d)<5Qn;5E$Y5m=@>b9))1ohh5QGRShoOecJ)FKFtg-=5adZ)>Kwf zLzyeV59m7Kw5U8J7>lG31Efr$1yCPJ+wJu=-5JLecqCfHl8koTnHLmTRngS|4kCnD zer*m}M_r~LvihB+g0|Y_Y1#u)GMX;Fv3|wVl%&2{f}YQG*?-|$^i|xPBY!9gQPUln$M?$|a`8Mx@4&nK&)4%C6Cp(BXdQxF zrqLw@8vB)UFQpYl>Ttf3^y&>hxi3sKgG9&NS-QJ{aqB&?V(q!j315|Nso~{iY#fWl zSKzfComXjHHSae2)hJ;u@XDRte%@Q7qJE*cc**>b$4B=ak$Ep?e))Sx5B;(;b+xr6 zZlmI43Ht1XyuvrN1ze4~5%$yN?1vQs1b(IwJ*KIoTO=H`L~5K1Imx+ojeu^!bx^Ox zQ|kh5)v;Q=Z+63_Il(_^D4|Xe8A+yLQ)_Ix{=C)maj#;pG8ICl5{)d}3 z$aBk_la^E)+DZDa+iAc$tJXZ)&*~-eR{BJ)1o+UzrrN!yRIj{_+XhGPI=}iu{khwW zr@eTbTV?oNw#rI#Zs~#dZIgscv3N)8KT|(JbGw$OmJMh5deGjpg6tSL`}x(7k91nW zcJH~XpiD!TComl~xY|RQE2`=9s^_y`TkmSWh}UxmD)oqM1y0UUl~7FCkIKh=YN{>l zc@E7;Kmz^S#A9?#TK2xzUY`)>Vc1ccOHFBdF=ykL3O#c3&~L0W^$v#z|4)oFAc5dC zF*xWe$;zYXh-Y100R|v|(n1P0rseT|qDir{LCZ_~9Dp`ASD*WmVfTRCj6~ozQy!im zh{sKm4I?jHx}@zl?6m-r2sX2&XJC>MYr(gri;B2k(|0H6(&@2&Yw+NE@_0Pg>ZFdo zio{iBXu`#qB)5y%WBRCjMq+ZCTqhI~tdTqANzN0`P`sM|`$eQ^ z@b^nWpzxVo#3ac|T24^J%p(LEzQ&yG^M z+7vlypO!v7T^)TuHvlRnu6no7vvjFqpv&voM)d*l`D@OFVU_q(ZOdbO;b(k{SxdPv z*NOPmw*&bpRu!HI7Ui7Edwb%q^r+`kUv#b|33TuO*i+YkWiJePBW?`|xcB_|is609 z)@Icy%e=Zuo>S4_YoVhY*5XlsY-AVS2blh>>%$iQe&k_8>{q4{rV*hWpJW}4UWbda zPuFu@vXgAnSmmev$Er~iG^-)sGkUfkdRKr*y+rtz#a$Qnh|BJiy z6LnjpT#I?7oE7@Lrt`52?Wt*%X&W@F0ecUvbX7}F4@h#hmH+cf=6Xc^?W@3QLR@NDg95qBT{EgC&RPCRLu~d}GPQkRXUUWrz)XevGJ% zUYF%bQstqs^M7Regph zeV)FRqj8WEIHeSkps<3nr52;0GMR0%(H;)GmSh3YDq9D+wh;i~W8%_U9GwW#gP~M7 zx$K9*;xhzr=5_85oP{Zv4w2xcOZY2+!1&hsjRG?YfZe+ZS@*_Dd(cpDyql%wqjQK~ z1BGV;5EqqXZby&-lpRTZ(=Vl=4o>O)p&rPsaXPJ2WD0i|NRELMy5oS@s3aQ%%o3Iy zBawUuo`C;F!a{2y8R6M}>6WBFfswRL3Z4ffc@kWB^h?#fv@@Kv^XxkoN{Jy6!&pvI zio6PA9^p&@ah@w>q_=W${l~&4&5(TQ9j8=&!xpZY2`Gol5T(BAH?ZtBjOo0slotg< z1-2$(!d$m9ESu{@xM{M#0Ksj)Uo2@C#-I23=y-Ni$0j$CZH#^=ma|brzCA}>WqPWz zPX%NOt(}A@tO51l$sVvG;mO=vOi>v*Gg?Q3cAG)j&5Uc(j;rL|$wwZ9tO1d`$DD-G4IdMOiu{AW_N`sC1I_ zQg@!nX};ETv<{2=Sk{my@XVvMPYJ8dV`%(5tb8|Bi#+4mrQYzvlPntatqpq{`%TPq z>}Jr?W{faT-5SVe#154T5{)fT7&ftWP40FUW`WHogtQsM7A(RQKDyW8^K~N`cIZa|XZ6 zzwulFfX5#*kq8Ul851+!T)yH?;n-D7>T3156*9pp{R2+TifD)!x|a7UT$WobW68d& z5STp>%G(eYV0!0cLre60J`63JNJK!kdg`${-eV9aYZGk6VJ`ay?_021!l7CP64suvE2X>>9b-~2|CzheY7bWM4n6)*u&X1Ws-=D^QeX>6`@UYY zv@y#@W<-}_e3je>16pk*J)k7C+5_Mu!2hAVu1S(;7;q1Z51dF2y~46>Q{cDKpOaCO z__RIl+Ath;j1~FVwedlZ8RJ%JncraU0=KD;b>548|5hR)s5_}|9^;Xnz!;nmC;-LI z10sSGnI|yr5`+z=i2+p!3b`1;3~SjiG2gBTQ~@JE z(cQu+&6z0PF>f9n7z{pZz#%3GApo>gR3Y0HArk=2vX&fGp61_>ma+#kR?X<-mIZ$0 z1{qHu2AF}ZM_7sBg_KR?qq5@#t_@B^wg>{iplj+NHXQLkD6cD;NS7dBYs+{GYJ3F^ z_96HQ2KX@Q1KJ>w^SHwuK<(A1r#n*O3EOzJT(?8!5A5}D87(E8w5?p`R*xYGaxjSy z{#jHTM+qY|N5j}olH&G~16+}h1_^z2!T*Ax*gdET8mDlTJXwYNg36L?q4!q(!YH@d zL~Z}2dK>HX-d8N6@ht&W^VHjhbL1^S^0S~t?X;Rd)hY-occ29A@zB3xrl za0$dEBVey=-Qvlqy+#Z$>^=sU{M}l6s==DNC^W#(>zqw^1ZKAWav;oBHLB{l9 zh4j%|_OJo!0|!_8K#$uRHoAt_RV&}Q)S*%sC3mG9r$hg#*hd~U2#pgHvwd*B=a6@?~! zBmb9ts2b8z$E?#YR95Q?cQqhuaqxBHUDKp3kevxMyJoQvHLrbyBlw)psOJ~& z%lUiEmFEa5bri7aTSS+QpG=@yE8VdEvRAM8Jc`f;HbwvH2(GB(x`jE+d~`&AXUvOg zDl_FZsJg)oxRo|JsePP{aLQ@}d(I~Z?m@;F$>^b(fcoQK?Z-PeM>TAeZ;jA@jfv(L z1AtEsqyLdoZ$bRm2=8=*$<;c3kyA5do~&7i>`VDn#4YOdk?A@4XW0J${0i=fTiOpy z`H$U25Sm@>Njx~EXxFz1IQ>=<+`k)8z?*GZu}}{bHAp<7;CJ9KA)?-c1T-YOxhCjM zBt5+(#S;>e8#;%6^9?;@JGoDn?Z);a*Ht>U%pV!;Nj9lmZBF8}bX z1De_L(;_z{p0;sG_*+QON0|Oi^3DAvH?knr zHc8#Aj-7cg{qeIGQUmALX|I!DGF!>U-59fZ!qx*^T(CM0hKZxhKpvCjYR$T3mAk)Q z_7LCNw5^lRJRbx-c~^Pp!?9v0GiYoH#bqZ&AHW{Meqpvnb)zsB7n1IHrq z#IMQBo$urb00`L~Ba2*Bb^xj(>a>3EG;+;NHW_8g z!0*uTM>9~xVL}!HJus~f4B`_6N)I`yJY8WRV|g-vnu1Dv>!@6G$=0RiSck*A>q2oj zD7qDA!8mC_d9%%MQ=IjPA~@hSjrBh%uu6s{B;{82>f4l*NK1OF-A8=3>67lRjQZs()fD~wl&g5Jn+T@_EG zYo*iK)7{stA5bQYM7=*)Iw}1(x$1!iaggM=u4@8-@@{d2{gjl97P zWoR(p=gHNjPVvY!;#1V%i0-7!3C^0yn+Ac-2%Yd5mTWjHRb|S~1XXg4dN(J^J&+-_ zPw#KO^0xu+4EX?2!E*|~mYJxC@O3~0;hzo8Y%+X#b@l`LJ35}UrV4)q>T>jz1RodJ z>-*A%%R~!4sfd2>TVEEZB-G%#x1d#cEton_aW-Q?fN@ZJw`=L*yqhirX#{1IgbeVq zMGO!ti?rJWJTWE*xQ3DeF+SWmr1-ttmp?vA!c?Igu3y{KLiJmddOKBFtY^3MfmrW; zfGskG0(6pH!Sap#$p&jy%Gpb8Q8_EAoV zZIhKLpw<9Ld$&(=oF>5Agcv{zCI;~56H(!TQxh;W&u>bZ3_+;kAaGXxZ!L%*+_Vbt zR`vR?^gNP8Rb~MdIe$c{C)_WyWTgC0X4y<#6w2nV8!NkN=WW!rV*enci`LAYiU6v0 zUVc7@V)$GJ^Lq8~-h$7Fs{F^WX(#zjuV+=o)}EBLWU?(YRUb#$#JdJdO&A9hzOV)* z&+_qiCqMyrifI;vwq`~Fmteq$O|p^pDY(f%5LRwS;biy`t1`|vRy znsR@G3v~XV>Mb>Fh=|%Ko_6%Zrd&}0cw?L9QTGTC7Rh(e$V0@C03fnx(AYz?LOdHN z0dub4L>Pi@mvI9Dk`(|f51M{3Pa9G}@$j8g;j~q_sPh^|d8OJ@3|K*INn4|W=IyCg z*c#gA1}*+1BMRFsBz4uixD}@+2{%&1+lQA?R*JyQDhDY4-7Ldz*@HzXXANc(MFrXd zG1|{_!@+ipdv2a|ho&eZYDFNXiHp@=03~Bxn5}8&gLCNP;VZ$78HRS`sjSuUi!))x z_l8IifLg|XS`rxBK?XFQ$(VA9ak{BHM`+qM$xkDA+L`E#E2GL;JVDT~1-{GZ%tRtZ zC)K-Pr2+qDr=yx_7S99>DOhRu6nL(uW$O35tTeqw{+R+okXAC?V}s;jQ)e3S;9{v` zDX)EbWPt>gC+YFlt^~(0$o1kg==WcKgvlbEjXwZTuh<~`*=|<X5!DwjOR_j#N? zZHm)hcSQ@mH}RHkJjPd~EW6a^kC#J*epGEB=G(|)pv!Pj8-c`&`Nfh&T25>}2`?vh zHZ?l0MrF3%E?x~qLU>a_3-^{)zgAJ|AIY*EFWVldd&*@VlvCq-jZCoG4SMxj@sD*g=aYW zvAYvcBJLE^E_M0Hsf62;TUjSDGhb9W;2Hm?)OArmxpD@r&yMm!lsSEV*2XL5&J=tr z&t?$hq1i)l5_xNTfCptpe}KfRMG4dVVYbEF&1B7Xrn%{5XI{^Nm-PDjP9RNr0NYbR z*RUpN}6n|`72}KU5 zXFLnfO3fXyon(ldZAla|pdFwm=!U9E1d|C{Q~d=o4swcP+h4LpZkfWRgLOhaPBUFC z{z|<(Y@;v2m(9NAlk8k(JJh|oGA5%)f5lvvD(x=vg-IDTrZ?fkvvi>LDHf8$)0n~v=lODPW;+^O?S zwN#amo)z_0lkCPFWo0DZ-QUy7^<^Z@*%m+H&6zYnaYUFhF0g`#xscq^cS5n}APMPG z_jwXcnbr18A4q)Rp=fCNr*dDT^Ze1s%D_rxd;1@M6@?!=>s1v{gZ@)gF(A$GzQld7G30u-CEL;-T`Sl{qT!+$W`o63LN737i zU+3c+HhMp-FLl_7&w6oR|0xR-i=m=s>_Nf~#Bu^sgK3p2b~zZDzIW+b5iOBR4c zxA%*XyG*VpgCC&drY&jQft|T5ANRdFMlu?XM2(UD#xcK;v{kqq8BXQP`l)fr_~W8J zkKlh|s02`^gDYF#?z&$0V+N%ooN&lz{TKJ?(p;a4soYOtl%F8HN%(mG`BkHs8hP}m zQxJ%@ma*gLDOOih$qd3M8m&Omc}@F|D|_~>BKm`!U)uf9x`2d!6SjJzoZqJHb%+8*+W+4AO69Yq`3bb57A-yHCeW zfu`s-r!RWBa7=anCnbHuChCbVjacE+MQQb|@`hwVL+{jRpR|5k{+JOmm+PHCjuh8V z2~?pJehIghgH12$#{3wn zwvKV@NvyVy;2{4FWN@T@BZ_&pM$flc(@4c_9nOV}snLU1Q%jBTG~uRl7~FpjyEoU! zx{sc6e*P)wei`wRd-JorwHZV3DAg4gvwq1S3?k(|s^qMxTsU(riceHGyajX#-90^w z778Vtxz#mB@3m1}`vbt?)e¬=peX0$g~EYZTS0)=$@!^))pY3%mq8v}Zo4s=0Yk zX%zje)e#!K*J-bw&ZC!UcqyizYRt2ye`+`DZg4}pyY0CPDPo{%}5J0 zihoZ`YJw)!{?qu;ZZ*;5jYm6#*J#_8i}kT1Xz-o_>hW*Q45MK=%dwV_T2gjr1*n6o zl-a-q5aphmB09+Im2PKkXW#M3qxVyqXr{y5vc*<>_3UGvK>WDs%qP zb{^{+Ue`cg20K>%lHvl$NP=wruA^1mCsk5KplC?cZhtDyrr??$z%P( zuT}#)u5Xw=Q#tS_7BbByq|%LQrqVC0)LTQ?|4EjHr?UrLez`Y~RC7cLcgD+ZC9vKG zn{JUN>u)H=I@hOPkz)MR?JU6ii;gMi`5^~Sd$@`9n7whmRaNEp_Dxuv-P!)|S?o6< zjkhHE!#4Tx#53*>0|{chm^IGw-$_<}Nz7FgMTknw$4}Ld|Kp!1X_#o|1%wZ)*To|( zho$;mHB?+K7KSdY9?`6FV95|1M*Im+-S2d;`D%OH~2Va@)abcNaMr6Bvke2bvJmy4e+!|LLNJy2SoHfx+gRF)LGbu_YW|K!VUC!E9 zgSN5kj*r$hD^qE8vIfTJlJnu>SAT0y6+eW0_mFh3AktDpS$C9}8cR|s=y7Nveo|6u zU46NRx>a?b1!!E&?B`1*R&X`Oy!pl}>Y6OK5C7|GcVv_3M^FJ3swVb94uXULh?)Tb zb?k@&52}L)Lhr}Pp#3G22(9M)og+|3w$u4_&d{!{OB4HO13Oct{_^OdySN_>t%#MV zMEx^jzm$Qe2BV{7ZCPMOEZlVjy!EuEewim5k74FXP@aE^*ucQ4YdH0VJQ8heIfd(u z(^U<9UJs$u|FD&0l+bK^edL1g0lw~k&*NG)_Ai0+l}2zz)nvkCO?9HX6R^V zUhRW=zVK|hFmmmd=}lPrkLg9hI5j2nYa$@Nw=2A@vuWBmo!@7KsSm}h3sUk2A-VYd zKKm;WmC;V@(1p`*c298|a!w=(LEkrwHO%LnE9CD=zQRE3Am=-DGOt0aB9`L(WXu>k zuqy-@1O>+rvkW4bC`VMc5E?ihz06yr+tb=r)QAdTc*wm|$j&JVATI~X_ysOlYkgZR zdVgu@`q@T6bjW;HgQluFU+p+0`q*+WKyy&c1O^epqST5A!1b8i`Fcun*Ezdp$ zBH@ff1vk%SvbmSMM zR3QZkH6Gn{JYg}Gu)yKPt;6~1;_GimbbzdP7sXrNxIwY*DU}1zSWDZfXnP3xewe2C zVQkB{r(b`iILX;@p&9A4oc(`ry)khf4Wh;dQ}h4(zE^a(ByK6`eT%xzj~Lmv1E$-z zeA{1+wprJF3f(-h4^|ApSMHwiY6VmE1LJ3oE-yL}jV<{c~< z#?~h1yDE0%x__f13PW;-1%1@-pfvB`Gk=b3I@Rg}h%6^4n-r z%fLa(LN#$B0EmVf9I<;cOa2#3 z0zwN8f@;Y%B?U$hx+6mKQWD2&pp$Kyv`mUCaRA3f89JDm2c`HofsJ%jSY*lWuW2VU zL^A9VDze?+$X||a$mL3d4q-Q+`(E1{Lghgq?SqohMG1`xB3(6hCbg`yR~IL{@D-vGlQyl^=^<_an}=aO&Ipp#Kn?FjpzoVCIAQ+ zZsgIHEMPBz=hlZMwL{L3&W=Ldb&6q*+Cvd<`2T_jnJ(REv^+>gh2h}S{u6o^_&<&XgDHeI|?xbixdwr(W2x; z79|1vLDzD@B=Sh?oD^FmHsXmltE>n@UPJf_Whf8m(@?&3Z=2%%Nae4)vk06hap#8r zAe1RVMl1OWsRm>KNwPI6$`l78v`PlBAY(ly3g?oY@#zY(+nq^c1ieGBq=pw=K1-PP zN65&G^b(KqmV-$p5vni{pfh3V45cp9%nLv}Q$So=O+xrD0<<_~? z^F!oo7&*g{W%etnf2e&Cii&qV6`vF`HX^JHnFzB}J+!vk|V*8EnIJH!}nZ z#Lblz{T4TfG-rX3{sqs3M$K-JX8r2^n;w-)sJztF-NvBYPJxtqeWk0Su{@&y8p>)- zh-%eQ-ZWJ1`Zbf~J@zgsKvn{*6do_*iXuh(!qx$5O~Yh60Fh4o$T!jNDz!su!SQ6+ zc(v<@X(v7e$s2u}gr@P7r(i%LgQn7f9xusrN?&<}xwf3)l94lC{-G;wM@Jw0i4Ngu zGy_!5V06bia48eSGWvTKHp-%jQf^9+X4Nm63)2H9nyQSxen$(r$T{UolK%_7zEm## z`(SVct3HphcqprFDd**MPe3c*DocL!i-gaUU)(M+5m;Gk0rB&|C(|KJVpa2=QRqEg zg}LdJA_^=t8_4t*%%6=U_8Al`#}IcTWy2E|>Hm7tVCT~~BMl;QyPDbi0{H1Lzk$#l zqrT`T?KU-l zba)XK`;t99ke?Ijef{r~bnJ#j-_kp+Hx3iq@A6kXV%=g!)O8oXcuyRBV!1~c8cH6D z@-|ERV8>OndzgfMZUMMa{HM+OqLRWXK&(*>6 zOc%rp(n=y1gwiQ>Zkg2R#3=I@VS`AfA6O7roz9r613wAqnJ;|t zp4#MY|2kV1p?U1_h%87rk^Nuw;Y?ZMql$`(2g{%rgI-Ce;x3W5)UeLSxt`1Li=Kz$ zzt$Y${$-#5rwd_sS_>V|ckV-Q{pD#h{pU@!VndT{1}0B`vZkMKE*d@;DSNn?Z8}26 zhMn)YL`NTUUF+6mjsD38pt8i{=bvSlVma|Utsq|e6FC--k@jY&BG1$aJNI9)zDY~) z;sm$Tb-NfP8}@kg$}r|kUhHBEmD-ny=IL?l1f*;4YiOPz&ci*^ba;5psb`M_I;&dl z+_ZbmD(+hv%(8uBey+^_ctdnb4Olx&q1rGp{dx!PHfK;-Ns?!%+9Mp+Ed4`dZ%*Hh z1)!q&xdzdtEJ0>vd7CfFn7p`xT(qiNt)$_KdL{Jg8NN}~Q+^u2>MpL{qieS56rlUL zXr@(rlJG*!ECb+P5^!1VwxVRE*=O(6)#^vVLYl7VskPs|6X;87qfHjx`N{=}vT1Tf zC9c{{!vNw`FJOD$IIK2j-`PcCX7NjoN9JR4{MH28L?o(zia)>4Bd_3JxC(71Up!de zZTj52HkR)a`(Y7O?5t@kOt~VrwYGE5;PLDyJ{=KT@pvbwZ>rkGAjm6|9y89zw3~KS zl_m;~ma1-_>R!w+F*X3$p;J7YBX8XJ_8Y%xmJ0j6B~kdA7q}VC&24!A!nNE-fO_r^ zcfIvaz-2x=e6g81wWrivUnz@(dgh~5L9 z6{QMvjs0YtrSs`)Nfcp?3J1!e(EAzSp7{oLEQ>AkPz zk#UQm@d`G=SDi^ZQ|C`DyzsFd6yZRx?B_63BfxH>{M(<6#GfqgeL$J3cnMy7(cq3R zDkgB`ulpNY_4%#4i^#8JrMTH2&(u@17c+PDOCB0Fe!}nV@yo9nr9E(b<^)VTNu=x2 zjU?Ow?(pdJT;x2{E`60l5QasnAn&+LUO%#@2UKbYCz5IX*&=eF8Jr`NxcfnPD~8oa zS;%f*jc~_FB5IZYClMshVZYisPM7L;wO*n?x-Jd+l!V?#3-IeIStgxPYmQb@a2;Gs z;xa*XOk`+^UHm*eb8o=X_faW}js}E3^#*|D%j7h)K zRw_9lD24>x5QccHf|Vyu&jHgZ$}hL~x+wM;Ny3Aslp=E-p23O|?tQ zck#oGBHjw;e<8;v3U|A&R5Vwb&d@zb>s5VsPmkuLeE{WHT`Ge#)x%Q@ZSfj~Nci9k?hF zXe?%?2|;6M+6a|*;&En(<*2~~c5gHN=GB$Vm!$M<(in`5Xw%fCS-WqvL;jR#G^0n^ zRa&pOmNv5F^n(#W_n?-6U#zH5-o z<~O%!5i;WvG&Pc$pRtFfg>mwIHH`B1-hRDt@3yuLBudGPeXv?ErT#q3tIZK9Oz|7a z8r%sc<%0REY)y-?K7jFC za)YfntltB!j_#hME2tjty7nyT(s40xGsZ=gC3=;${mAv9O5@|qhzmy^1pCFEeBrp+ z8VAC-zGCuwmOiM#AOpizPCKn|A=3=vTRfK2WNM`&@u$cA01nqzY348p+4UBdOyjmVlCU2hf+szo zhJ}Jx5DAB#hnFw2;zHhgsi<}G#cO-^6!V2=9S?;4+I=Cm(bB5b>XHR}{^&Fn1Bqw( zJ&_dl&N&i;tGe&lrKJg^1jQYLOG~UFFj)aCSj!7ZS&~c>JP6kZ6?Md^d;T<&&YoLIFG#^ zzz>`hEuIbq4Ll)4qzzui6Kt81-7S3kxBB7U@B89U%?dK9)x3A8aNolYi4MO%O@BC`!D#wsL#Zd^$OT6e|C(##{5gj{JcKpf-xm7 z*A#~~0e%bmJ?HyxLlY{V3JN&k43_W;KjH4hJxbm34>y7Zw7%=jN-jJ}pOeT~49+N} zyi+-U0UKmAyo+s^uW1SDt9Q=I^}7=8hjExd4!+11Lj8A48KUK0G6xhEZ^*&PBv)c znB%?gGtl(2Xvq>sezM%57)5vNlz{VJJB$-Ggr^!#5 z9JmQ&Jqi91Lb54nAnw5BtY-)>7OlyMEi`Sk2rEGi&3g=a44i3zb7iLn)ovK;%Dw=PC=*s&CJ!>(0U& za+@Hobekevq3O@|g5@(BLc9bZO&5+N%#&ium*7n! z`4hxWzm3E%B1L6T(qYn8&qc{DP$qc@JThGK*j!UjM%E>-eDnMXEr8k5gNa9DHrFTR zgeLJqT4cOK#G-?VES`-(n=t6EM#8*&u{m#fXqf4l0JDkKouwh&DmKenIswo!=@!=ea3&ER{la_UuKb}z>g}|LpLSdFyf2u7ZM?($ErC`^j@Z^TX8SN$G`8M zdf&4A&`}3GfhKLrAvFg8lrU_2u7ufcT>Ub7DZ@JLyx_(<3ir2eHzx9_GQ4Xt35L0% zh54$We-cF1FvSN*acl8cBoLncPO)tIb8} zY`n2dOc4SDGQZ>^5?#ZDc4^!3TL{@VL*PtM3MlQHsjQU^?E@bx8P+cQ{7h~#q_-F6 z^Xjc$g(M&`53D*NULy9x>c2N<`op;5^krC$v_ zh*%%JB0fV`G%wq_OlSPr48!1+`*IPR1yF;pO;w(n~2ODN{@`xkRF zF1I0HH!?|~ycN}-KWiA#jHwxrI(N$Adbsqx2st?cW$U+7qMBL^d%CZIcAb4FJ6 zcfMS_c~ix1S<5WrDg>#jZ; z7+tAT186$$3QG|&cAJMiNebK7yQ_L2!8lHl>p}TwCmhKYK}PATJQAY36Y)=n?CQ{Y zm8)3IBr-24GG!|A!LtoHQfkYwD0R?%WsjiQ;0UvMx0H$djmea{?$s7TfQi{@7*&lJqxqPEY;;L*z|zZrPkUs4k+QwjL+|6Sgs^cxY+`>4 zIG}2SUPoRlEY@kS2I0qEC{9@4H<&}q632d+hzCCbJ6g)}xk&-;jtdm)ead%Hwt4X6 z7)CqsB?eh`BadbCz#fO->PSDmY?hG!_2NJD`#&?A8*H;x0;`^9)3Rn%>C_d zS6hkX&yt7DMGiR?{EdaN`-K&}U6x=vz>%CLJczuf%;{e7M@7M5MgQ?^{Tps}{dbu? z#W0)I+?4Jl{x995LJ&&~%Mp^*(k+Exn6&&>_Qf#0LBQ9xSbhvKA6UZk(|RN*xZpM@ z)+*+=z|S4rnNJHJ(X2hfnBAR(veP9*eW0o^v92&sD1A$ec``h3LIMciV%&j4H>y~$ zGyoX{n`1RJw2EtB}? zb8}VUldY$&BH5#@3~89%(WQ{Y=mDIPkY)NU)4UnFRW$s*tnYW|5>g@9{dyGnd3_FONma4`t;_HBVLjBOU<;< zEL?(<4dM=7=A>nG1(_pRC||*AwrL?6TN5)g#9RnPIH$(7r=07Mr3VeGCz0A$OLd3( zsXyqUo=!!x>~sX?2E{mdY3=a9(fNa|hl87U+1z`LMS+ZUC>LZHLkra)?5pPZ7ZcWyYt!WLt7@=28ro z_%^FhD)9RdKY<3>CMT2-)B{9sO+*iuX#qA2Wy?AJy@bE+`#bx6LGghRap6?!kbY zL&ob{Y%JU>jF~E6f@R8e@(DB(K&-M~GG_;@H zoL%olD!u0KE$OTq`hf|?`^UY!eMBg4F1sngH~`u6O zOEPmlCIpf3VMv$ZOdH5)(JviZC_ocZc4Mf0-?Qv3`{A89o!vjs{#Q@#@S4x+Fvi&K z?Z)wls)cmT>{mO(84=K_D%!>B@9S?^w6}Zs9w|{G+(SaXE$rMomOXnF*YHYtFXzVf z0!@{hFjDgG+^y^=f%!{94U;V=S1N|l)n#n~LUyprQE6|f?Oh+ifp%A)e(-7S6^_JE zh+bm;N!p94obdMyO1=rhOgzV&f$bS9v z|4$7QCC`@(>zEWdoQJZx-BQEaSn_25TWXjn9|pkdm#X-h1K9`!9C~Ajr0ZvjgzV;S zsbT(^Ql$r%DyPSg8FOFD1A*ORGJx%4{rG5bEou7$g&6z(=-bvja@$wY|5DB8UbnAm zpjFf8>j4gf(8sYP@+})Z;XkI9r&a8S%!-F1Pm*VEZUDP{6L9}h{mg8P~ix9}m3U6dCIv zr)x(%i+ZL?&$|ypzvHcMq)xV`mL-LNwS+TOQRnnl__$!HtKp&`wdBn+l|Omk?`Aoh z6e<4g<&3uYAo02d=Q60dgQsvs`%V^>g$d({d~(CTi0YbBI_(XO)4rOqAfY6U=if|Z zE+|^Zz(DitF`Utto5?OzKJGTKHmO3@z`CnKkwG}fBSVfDSMvawfvb#Xjvr5Ck2M5N zsthTddPFes^-v~Dox<4ir}TVnQsgi5zZ6Il0rZ0+eTY`+2iLd&#a@+m4uw2Ndz|rV zQhH4E(Ru<`=Y#&1aDH=4Ym7Yki}?)CAltW$6jpRT6pb z#SWOYJ=m-AH#P#)l0Z&3%bI#46t6iuH^g|fG@T$h6DntG86rhMdIKlu6g z(fe?{K)MgSVSbTIodA^X*GfDgF4F#Qypq!=gbE`kg)syrJ(ub++FhCX1adzve>&pY z1i8)f=bI}zh*Wfd;ABI#KJA)jB->IdQdxtI2Y&dFYsN4rXzZlC$P^?&}ypQ1{+5~#L`G5~sm2DF;R zV>yJZxfx+Y^CFbI)f3u8Vm^ia@SwQI&zb1Hh9_cVFcGrX9BYOR)c|%%5#gN~04fim zX(SPkUl=Z)(i~x(yOYF6lqeg@^%~H8;8M2;W)K-ou$%E}LhFjerFZmXlCFq2L&J;~fYl>z&#*M3d56Ox- zsO7j`0}he8Wn=#zU-uae*ZcMje~%fAK7&MO^b!&^N`%pS4MLP?Nz~{i2&0caN_5dX z2|{!ky+;j#APG^UgoJ4G%{KyB$^z3E z{2($rl}()jxgohXte4|X%&@jo117C;ok#w!29Gib9Mbq5Z&QpIRe8R8Da(E9G0CV= zn`nCDNinIf-&>(r5ouAGzS|+6Z&>!Q!{ks(;ys~kq-_Um83o~D`6S~GnqJwnHDwZS zW5!*a9^|0VP}ZHbv3qs8HJ+wB5??Q33BRL=asl8gIdj^&XNj z!=W6I*x4S0-iC?g2O47$a8mynX+9Ka(>$&iL>bHp_RPR=hr3gxk3n2O>W%Ez-PwM#ULRZ{(yP# zP73|T5V15G9)9Mkk3OOKw2Baq3>%7n`j!8u1DWUiPVP+wT=lqyk9l?J{EwSL22v0X zZ&1AYf{FdoRjF@eoJl2RQ%itAPk59)Y-^(kIq=jJ1Sge`L{1jmy$Z=m=w=3yM{LY={!IdY2{t%8h0jN9CQ)nzQx|9 zmr<#6t@pMuS3Y~zFB2qulk+lvRFn^DR#&HxjuB87=lXC;=9Q2Tw>dfRu-_xtTb3088OF~eK<&cng(w518d>HJ)W>@5&HEXo=2b)* zT56u;!g}7jBuBb_NqGkS_W7+9K4|3w=MU*u43(O-IM(ERXZsOEYaiG9FS%dCzTBda znG^{Piwg~nqvuVZ*;;DUh{(44m9HO<6qjgWW{r4GwQ>muTHB(Vd_mmeJR0WNO)`fpSkozam@LRnq# zcduMi2>j{bh+{F1p}75tJf=^NO@4>%(e;EIfmp|0{eEBh(76{MMzvb@ttDxG_nwmU z%4-o}4tsktLb1%RzB$eB=D|OQtP73QWQXQ{c#xf+-&?|5H}ADwm4t(JHbN@BdS;s3 zV|PpY(e9Aj%R+Wp4`qLhxA`aSUFC83ULsy63`XJTp8c99%$4OMrX8L5bJD2t($zQW z?^_?%Z2m$2U9*9<8Nt^pl{)mYDq{rH6rw%BoO$cTmNGU(l>1>1eRdx5Hz$15IlAw5 zHDQI5nE)~W=}hR9c|xVAm^RcG-(sm0hl4It+&<-->hv^jURb@L%;4LzoXzBASg4Lm zjSnw5B$;CCq0RTkm9nCAGK|-+F3#6ma{V$6WFJLzzEI{``qNtTGF2gjX38z%1gg=F zk(l-;;to-&rFytWDDh%h<+0zL=F3kn^fCz7ufHrDT>bW;JzGzRK4Xnuxs8Fn|CFzP z#qZM9TlV4pnV;VEYPIZC(CXD2sh|V0k00LN+rW7_5qd`%D1(b(Dt-Y&gTZ=@D1-H2 z+2bIso1p_Dfh(IKJ_=r!84u|ELsp5EKo!hAgD^q|f09B%u?J#o^+Dh3!|0Fvy(B|D zZ-yH@c*!yp>Q(3yG6&%h1|%I`0`$SmwBEC}C=vq*E!|rDdgvzF2B;E9hg~B>#cZ7yudeFcCiAbn@h--L=g+p}L z@e2>=O&fn0R}0K{n&nGTl&=KZ|2OJMarAB4$QFZ8v5inaXv}tMbet(ukSQ#<0#;ot z5Y-)}X^5WoK_@B2P^Y3zjAA8C!oAOM=;WbTf79qpqOf6`7;wGEC&MVHM}$_|Q^%Hw zk(n6MuTc$tv8GdKz4x)T=y)Ho7~66WuN1;&G)#qnN{tuYS>c^eZ(FE-uXu~$ai-@o z^rliO$-*J!0fNGPjXJcB;tWOMfkHgYj6XuNj`I0qY~+>7VUgjywP6WGzv4*X@sq@f zLXz=CHX)ucVlgDRq<~5qMeTs4%5w)77f>A%$h_rCVyKL@GR2s5N1yuplGGDk`UYW+ zlF~dG>LA&+o+3z&@o($TBlq%!w@u*kN8(;Bt1ETswr5H+U zN9x$&%)}ST4h&hXS(XYh?srIN82qwk-osR=sUp^53e6+}%wWa*;lVM?BD3T*C~7s6w?kxE08|cBmS=x~q$=$i$zS(n4uSM3$Yi&}8t*NK#Qs=Ys zPDxB#Uf3$ATZBKu!DQ#0zP{k)SAV@R3?6Z0xW$i5lcww14hnG$QMRE~FQnBrpmwOE z%C!a;>L(|~^?)2SIs6@BsYgHrp~c!9#j=>!hMC1j&80~3 z=#1igb%C;>!V<*_m?|JOo(hk|vNR$*=?zOYJWI_+(7Q1-{bwO|RpoyT%C26NW%m>7 zJqlPhAfu~CJgf@yIQJEIDtDhNbqp;hr7H{6tb9FHPMr>OeI-L*5A{#9^SDU^Tnt$GHpw5+K4E}+06kjh2M zeEq8?w+W_$g#S8(&d1gg1r#ie1a$ZPmso)l+D*pgOZ;gFJ zT2DwrK&8c9{ztR)GpTV|)mzT@Ro9GlOiXNGEuYJnN-zli`N*WX4SIQ#Jnt_jIy;z_ zjP;9V>}3_2!8w%K`JG#L4beS%BN$w`7p7I9OdH14$Wwn@C3Z9JQKi7E3C9}J^?J#` zchVO)mqO8~SQ`kr0ko3f?St$Ll?xWH*v3AAcV$xVD=O;s>BnwTqnS`w4-cn^ZKGBNrAE_G5ejgrq!!XXnTR+aSuA0aLk|Zql3m|FVO0qI9 zAOXMoQqkBm(ipnih|_F|aBjIz&Gp_PA`T;P!=|~Wr-2mRT+q^dH=thQM>ElIt7zl< z{OTH93CS9YYQ~)??NzJr6xfS815yu(6J}R!fW}p~rD?GQ>{irkIg0P1Tbw(^JoG{_ zROu*i4VE%BGFBph8YJAI<_JU95!MTf9V5t-P{D%l+A8MTKA*M0_&QruJ5yeCUhLwi zPsJ&!^r<2GlzD)SYdb5*ny~L4ixv`!ac}$F08Oc`J-*jUE9hv`{`QnCxNwRDham-E z1XWmyQv_wzB#6g`=;I{i9+uqBnpzH^I1{FXkeBQ(B>H)@U$&RG^#PaG#5^FfUkqK{ zfz)6O_OuupQwOcbkS#0J9wEshupKnoZzrp(URHOrnYKT(AzF2(V5bc22flS?C@e=sC;jL9^g3rACWWn|0R>6yM4A{FCn=sElC#BAFWwS-g3`KoNF@pYS#^};`qZU>Jm8)x zZI&KmZ`~xDC={JjWNvi)8nD zk%E0Zp+m8`qixJult>64f`AW6%z^^psbQg?)A;OC5uq6|mYL9!Y4L;^>Dn1-*O_}i zXXHEaR^uo~ry;w}Y@_|GT7p_f4P6+Df@%#n!3QV!iX`PJ1h3#ne(NZlA;6R)wbUV% zBtFj9j5-;9Lzb==hY&If=TfFLQwm!A-6yPLYq+vfCRGCo9kQp)L5cjw-isUyED zf>(dZp1KqDV<>1QKTVraTMNzEQvgqEwfBqXob%eHnW1M$ymZ~Uc5nV$9QxgEiZXe- zUtV{`c)I!W4c~tV;-!BGVi-RYjA9)4#O*<{iM9SG%dw7@!jhVbWr~IZxbbqx;pJ3j zULLNIr0#1wR%@~J{udec#iGo4;mj`~29Z+rAQ@mq21!u|++jvgOdvtL_|!&}67-NV zZg}jj0_l_mIg3vI&6l6Ye&VVM$s((S+Lx}Pt}PMgxi?X+D+@3%oe@E@E%>aCR1yQO zo229c02XV?It(~epURIMpsy-qc1oVhT|L*SykuFcOqeG~{2eLp{r*?x; z{H&w=c-YPj>OF(a^TJD%9+hzDers|5)?@l*@5Q=0<(g{O`o)X)N^&hKw=sgOemW}| zMqNBLdHMR3ZKFcb-j*Buw}0^I{-AGf)%&=ie{18R)el_4#^TkFWt}y%jSa{BRA=36 z4c1PN;BT&SozJY^`LZ_o-2P&+k{k4K9WA$kvg!d0?)i_j{U7OaYmfFH zMeJ`4qc@}XH*Y0w7qQ}YgjTlly6W@aybcKNFSeSG{rCfk{!#I9E?2IvW@YD<)sD^n zPRH%tP~F`o%56@8ZTGI-)Ro<#;JuuwFZ={a-H9)&-jvq8-i)H$8NI!k-Idcz`4hwc z(IvL;~(40`3IIx(C0XADkv0{C#t9@#f(0_Q543 zepKcVI5+^~2j$%k36l=VCJs;E98ypnk>L*EdPfBEM>kdvpB_?Ku-svR(VCI`4>io~ z_KP>^7yo~#VWERxcc_l>)UcS|u>_tPPCAyBKSp}=bQd0tLQWL!;7gt-DsCrgNhca_ zPqZdZbPjMQdQ`s+?)?5QHEd@?bViVA_P?lMowq+7LxHCl0(WmP{hiZG%2O}5(^IQc zzqhByuTKL*{?UfL@Y-2D6( zU$%+A`Hz2PQ=Q*g1@Q`d?7Z7|8vPk^v?n=rzL0ZH(0*RSc9Hw%+|%R2J^4b){9;4q zqI|!w`_84R%q7rp5$khlcXDx@eEDqZ^5g0Sd)uYY(WQ;V6-(gNJ=!ZdgR42VtS@iR zQv|NR=POadNULKIKa#FNMb|vj*KEJ8w?nS?<#8AWT$?8jmz9FcY`|SU#%)u=00HkR$bL*CvPW?j-OFUm+_=g&1S4reDn_kCL!^UsyKTmIHWr{rcSYkHwLnl|-XMg?k z%%)y}LL?>kquDKk5{*~4pDfO9Kd3M$)h&JWX~($6tm*m2;-}q*bvFHp+~y`K)o!O9 zF}9coG*Uq`9}iEIf3nEfON9BJXH=EP*zD}v+V$c9NK3tWDAS=yV?p2xXsOXDT1k)I?CQ z$ryuQB6}s@%#1F_G8|LhZxcu1)~d|N#J|_D+-t|4{ir)gC=K^vFqH0MVQ;j3*9+u3 z2K;Ec8UVo%F^V}^M=FPkYA8jDrocDxynx4@yMR^2W*XDouf&Pz4vp|ZNM3}YrU0mp zT1%)Ef=cz|is>enfqcW}+IYhHUTa$zdJW&rkM|s*-slh=6#`8nSspqK71Ddr0&D;1 zNol1@pIrg}p;5EP{n;o3!tqxb$79Cd>)8SU}@tTs-(=kS985)42H1?*F z=S1qnj~qjV7Xb^qzPf1%f4V83Y&|kb$V`#%CEH1_`%C?J=M)?st+nKf8D51 zO7C6uLZ%$2hb^?hdT}W{G^W31w?jB|M9!DB9k6n`0T$PEC=V-sb+A#_SNdpALu)&0 zfPig?+Hbm%$*uDSTgA~Jr`s)95YJRpuB|B%aMRxYf*3MEp=RM7s?H1b90n~Q^YrO6 z5jR}-!YzFl9||y^^zncE;sNkYmg#|1>Yo*0uyN&2BQ#~==5mO~IVB!{!!mG=xw%s+&Q3Dmdch44kn|M^O#cc_eX zIEyABG9>>^vCl*9jermqq1de<7pmcXU zH7pJ(gle2o(G=-N;&vkB-h-mW#O;_|9f@ucg@uPK7jVm*Ab=#6{ljqfJ`R|UofxRTCxZ5jIQyv-jOiOJfn}YYDI`L?La_>Wl=4 zB*D+zf=~D{kBPi8`|asOQwz0$pl@u^>pJq2MyjDmgVbZ;M$ zRc5>jgC*kR-d2}>8ulC;21xyVv@kG0V;ujTP_AA{_-}X8KXR{ckA{?BR*dJKJ##ia zUhY-Z>T+~@88%v~9rb9oxS?8ULKF(#DU@_R`CfJfE#rINEPYzLUP&M#pdce`>;Uhp z3V7EyLgbnFl4T<6o%671FM~0Vdjl{M8hQkBkMXLZ1x#LMSlFmPtfzie|uGuKfNVP(h%N@t);)tO+3dr%Wnuk7k1X7S`iV&0__AoQQt_O&2wad3GcQ zFfvHoJ+ueQtkqIhfa2b5N6>$zh6?Cs(f9jH3s^Gu0M^t2BGJom8hd&>-UWqd7DTW5Y^g?CInH7OS*M`5CKZLWUW*Ye0Vsy` z2a`5Qc|@{$h_dx>YK;YP3XpM)J3ki#R+u-X=gkm9Lqv?;7;;yKD)0}K3MGL7)yA9k z2|uVfK%_%_x1HgmXPH;D3o6NY89`j<5KYKyxvlj~hC65fq+H1r2C5g3bw?6A9d~TX zU6_raRNrMQSZ;+u)rq%Igvrr=oaI(`ZoNX4aC$YwxUVbSrmpb~PaHGK9qN`^#H{Mv z#l*T-MA9<98{R-{OO0fL*~VL#vYvVFdk5NmA^6-UbplT`$n|E}oE(&jD$Ky+;8|x! ze>4wkpC|slSOw9cNrJ;`wbs!xiATe@jWxUXcV4t~aqhdJ$a2?+)TDqFSb}d& zFM}6ceMoI3CFP(U%U3S-ru-&bU`esusSRv+iozrKIQI(#uFqFRL0PmpxbmPp;8Sg| zPt7ySUGvR=`Oa&fx@gNiJKn(0x2Z%rbYs<)kh`vg<%ojdKuEN%Pft_RPM^nh}qzE*OlV15C{R|X#o+%n03aJ zOM03`?BHFQoB+H+bv~n)dUp*7*IdIXQP@lm@;f2W^L=IHR{$Y}z|og5?KRrZSP{w) z9M$eBl5y6Zh;e8w!5FGcy@5Bx_J#F#$o@kO=R%1qqO}Q7CJtqWQg=cTk)aGxPg~er zg`v|-=+kycC@dnR;H|EdfZHTfgUlNOK?NFF1<+V%h(GboAmW!pZ1(Pi3rv|#0O7(+ z^gIEIj23+=7T(IpsAWp5@s~KzK_N(rm{wbn+oEUkUU-N;m;tTGV4X#u+r3cH%{11{ z0zsW#lE%XD=P{re|XJFXcikPx&R>z0KF6@WQ0a|oJCV2_|FcE%;aM)Sh z?GCZfGbI2Eu`3K^se^nGQ#Nr?d8m93v=HGsNsMQEU0V6vFr9d{mlFgmT}UqOys^cr zy@#FmjRfRrm9B~td{9yIfhrF1s*d9Adi2qb9jY#4s@NHb7$V&lDdbA7hNp&`l_EW{ z(a!=J%d4v^+~o!C;^gx3^5WtGcYgK{*?V^O zFVlPe_Y80Mp5x`-v$J!&-Fx;EFZkl&UfjQM@A2`~$;sKTU)Lw!@s#hscJKAk&e74) z)xnQ{1>b}H{j0sbgWdJZ%}w0S!1a31&!0bcc6PS5w*E``Uf~hnPjk4bslQWG*DK|? z*_dztk$wNS=KH@X->Io7+{DD+$;rR?>%`c}#Kig7_}_o+-jCyd$NT=}d;bm$od1vD z`(M7d^t`+Byc>-hbH@!>Uv|0TK4_jbH($IDx@^+HHH%-@-(H;fXN`}KkByCujEpSz z_YV#Z_Vx93cXwm4*niaCuC9O7-nO>p|ERr=B!M~O*z z%6B|1a6dBY%HQ$I$?m}a#jcC%^<#tU2Rb{}HrqzV|MI<=nVD&6Y01gS2?+`R^1WeU zVgG--*U!(-$H&LR!vhcZy1KeLIXOLj`qa+O&f3}<5BFMGS>f&8NB>cHjf{*84GsTQ zczT!q@;vIBIV`f<>cgKWo4zMrT^b*FE=+g7Z(=?2L}RyU}IxrWo2byVPR%w7Kg!@ zn3(A4>2Kb=i6?t$XlU?iFAN5wqN4hj>?I>3`!CargMjgH?+zGDj9&miL_|bLNC<&I zz+f-|0Raf#kA^28aR3O)tX@~p9S)@tuo$YtZy{iunz`!rMg4K~Vou9L^~Hlp2>z(^ zW>UP)_2ox`9k=ZoljFh1Qbl2mdSl?aBK)%Vr`26)_Ha@b&BltUV)ax3%aJtpFtNK< z>Uo+?RiCO&-#L95X{w(8zscU8rcBQq81I8A%{ADYx3>Ie#?z4;e^q~4zY}_egl#$y zg1FwMA|);ruY^nW)MrLB#hh2hTHkF>P)uAh>9jR&&s039wi<71+MTbn8-1f^5z3GOJPaP)dz z9eFm-5e^=f-t9$ zgW7~qzqw%(>0pWeYR357)Fk?0%+qj#h6)0d2a!igBC<;P`?S0(Agpy8+pzy zkfqjk`jGXj!zGOJO~>_Qb)L%g6z#ia>tq?7hZAI^vxR^I#P|hwI)UTxlMIt!5>$po zirLf5$JsHMG<|A9^}DpW{>#W)Xs=kL`w7hu=(h5)9s&^lo`*zU9)p2%KmfzLMXwy| zc;}LLyCluTX}dJ@Y1MXF?m6!hEuH#G9*5#!ld5OszUezps~ci}WSR5e`gjcP7AQp^ z`6wX-5+i-2vG*?f#HQIoDM^uq(L6G+V)+zaZm6y5t)GpvCeF1=h)b|*#e?@%Sl4}1%ej+P)zr@>GuTbeLnpp(kJad zo5&^i4trr#rS558s#1=B-?$Hkbrj7FsX z=r(WgFM#yP5(qTx_7rH;1o31qovS#YAjZ8@O{~9mGNZ31^n2Fmp{oQT>)6-sPZoaT zO`W8L?P&{|$q8wnpT%9)E^;$PetYwIYqDqAI$Bg2R=hP6jpWG1iD|(?`o7ZxPJ7^3 zsuH90y7y|5`)A)V&gmzHT8}>;P-Q-Q^A|tsxBqvuz>YG40U7c9e7n3IfmFmNLbe&a zrMc0*=M+8qCrzVpVZc!mx~_fiSf7Si;qDi^L|yRJl#bjY&~(<5taj(>WY%1~)$kQ~ zt%pj$Xzlmun)!G)DRYFI-29D-!*H^idAT#qo#SgwA5Iz7PQX1}u; z3itv0HZcGvJ?!Z$@!jyT=X_MOnh+&X1=10>V6I+EfPolG8E_b`OtWSnpccwzw1y%X z8~gBQ151`T9{D8PX7O-dgwZp~k}>x+RAH!>^}J5(o**d+E(EJMfzS`l;J1Ol8R2I!7(J&M*{);0if{QsWtoN3tUXuS< z36EsVFy_#Jzcm0!X7Uh&d}NOay5LkKkHILvpN!(vn&D!X(t6b6>DoN|cwMG-*y{XO zbjRfoua_imL}mj=g+25Z)whu_=h0zC^C?G_$g z)mKml1ZSu|XAa6_Plc)_4-|ksHj!2Q@I=+VVk(fM`dfxH&5t5+E83Ns_o2F*L!rd? zr6T3R+&LbO)e_*?;4e>t3(=x^`+yYLx5@w8XBg_kL!)?z5Vk@vi+DHX&?%gh%)zB%Z1exSSq z>$=-lvS@)vfCHy<4eeQSFf__?jwl7GKlPY|8hhSdQ!pRb!(jUzd2a;lVV|A(=wTwo zS+`uM_;+2xWYt?OUM7sMzOr?44vA7I&WqrZXTt)%?7Eg`nv;)+W=MB%X_9Cye~WT& zp^*jP*#0Zlw{4{^}cr6-(hwNU_oDx z1V3^+mZUSH?k{Yf30mtM535VT3sk#p$tDT8@hq#GX<1Q6>2&=hB@c66}nAT z565>*+Rs0g{sD_(;3TF?=W}%{${0Usdwe9?e7-^hlC=&jR=~kB&W$#dUJ~5xnd@Et z{XDW<=ckkTQpdOhVIc17icVv1N9mC2OWqD^w##sed6U`~<)PM|#ScM0078&eA-U6I zsa}phB1xw&zcCzNtcqR>V~HtkU()3EB~}oNy4To-vt6!IZVF?B`0aZMF22#b#nzEc zll%Ctv2CW^xaWM2_My>tqFXq9f%{9{#V&mAS&cw6o4Y%a!5DkZvA!~urp+9_Eu5lA zIGiFyOx6HhOnj^0vFp_ctn5zT_Rrl~)gS{Z?RcXd5yQ-hY?5< zY`h<~0-?1k3M@5lR>W%|szNL#&lUY#SNgH`D%=48C|MuU1d?8%xGk8ti6|`dN-b zRG^qL;LF6JD;dha%hj2O)NgI63-M_{_~3l*MgqF#L~#EaH9&t2M%z>Oa|plT2+V88~*YtHh_^I3Cr&= z;Ya+_CJg8#YxeA;3Zeti15plZ|8|5S4U^J7)J5I(dx8W#+tn75dJgG#51%NA1$AC zaH6$N2wI1=B|JwePI)c{eiVa%YZgP)i~R#jx3r%^b-MXxvK{|_sEeMm+btgy~#jj_^vKxTK9m0uYFfu+dPU;D}Qpu}a z$*vej*SUG}0wBHdHY-i8OxHZ)`-QRrOXG?g*^-0~+X>^) zeBmC882G1Ye-OmSug{BKjQD6a>PIgmg;^TxUCf|1OV-=1i&G|wLU)6 zB=^o=)caTIh^f@F%q*6AP=r2Jk1&w$n7YK9odC`#Yt5T4%A>GJ(_wi14Y!>}+D%@A zfCUeGzSHmnCc(HmBJ!`~Rg{F1_pKt=U*g#jwv8&D^mKN z_pZD^ZOYe;H;Jn4HQdS1zuYhA8I04N>Sz+g^eD^cNfFCPKBEHon}5_CL+-*0@!KOs z`XdZ_RldTDFHbk)PG4k!)k|L7pti9lm#8RFm4SVvPgZ6qb=VPp;FS1C(bIDwj+(Dz zc(~M3ri?C>U@C^38&Rg=kXW8oh6=EFMoQh%Lc3^6%N+2~yUHAdBL&QnJ|=_Z_Kq=p zJ0${)6`3R4&ZLp90_BgO?c^M<{$ST@sd>|`h%}bd|Iyhhp zkZ*2=CA0;PoX3yLyqPtuCK6HRg)q*@(B4uGT3rk+Jy$%>B8Vt>p|V!1{HUy0x?+9t zt(MK3v?^}G5`sS&4CL!?js)If1>lyb(5}NY?zWQi?4rw^w>O<>0jBKc0Pdxk`@$GkV9nEz|$8XL?;7r2MAA?ZAp$4Jdau?i-dZ`=+2CcF^NY+xg43eqw zpZQVFM%5gdlJ!)Q93O!T*dtip2?8Y%Sc@lir30I+PHLEv?-NXkb6+$WrAnBC-*YV? zp-YWrv9+`|fFDqKC{VBCBz`Zh$@E^cc3Ztxb>PtX!@wo)mrQq?C2GVg@ROhAe$Gwa zIW0C1>sh*+qN*z#s_T+2V2g}-1CtSAId478#eJ(=ZaOz7YBgm`w$=IBdq-RQ13MPYVFgR?#&?xhaptJ6=CDVYw%-Vn^izCTcO<&KbDt?B zo~(Aoxh+1sd9A&jS_I?|%llmr|H-+9#<}w7q6@OzIimH!F{d39_W^DI4o8KyBMNrR z^X^`RLV~(sHrO{ZCEs(xX~t4RavE;Jiz2YKk%;b|YS?Wg*{(3vXKNz(Oe=kE86$HK z#~8LntBo)#T3i?!rB5|jm%5$P163gS3XnZRfvf3yKi})EH}7Rz#>jN^{$WykK~F?w zL1mBbnahDytZ^*d!|J+p=v(xgxD2o^ck`|FTJL08kYkHlDXOf=wyi1fgpR1}fZ(G6 z7VUcm7O5}Esen?llu>cV%vkW)k-UrZkgPSNPh5{C9avJQ?I z9d{4v43iPELXvm7m&yx;DZE50U410EoD^o6aLy$T0D=Z~X3IKS4TOZq4$1m}j)z~u zdw6u$?R5zhK(%$0hwfy8hegEkv$=coug5-tr|?gJFmtk2Y%Nb(PB zV`&MfhiFrd0;*sH>_j7If6mhlXL_BPj z6j(j~;zpomOGCF*z)sSKA(>D3(pYV;O+*`wp@JAtM1AEe3w_dJ^7Ur$SNhjq8N0qR zuY6@)aZDD5`oTzkBdJ0Tzw*8QW>)4rVL3fb4eo=HGrnBgZ}#YWijUM^qhkHK#=72B3B)4o8CTep%I9S!YRKr;eUWw4Br^Bw~S3bMcf*lDC9-h4HV-hakCtQojHtOu+O!={LNzfS@QG zFN@Z#a--b5{qqxmYV#KcMJEKO?k^K0a%UsSlj^pI27^8lznmrpd^;(RP-LBzKVq+{ zRTWIz@2Cu-xF6y?nn%HASn(ol+7@6V3KGKL$!*5k|htqlRnA;DKSB zH3dN^_^5zXevRZ3=1GSBscu7(a&>4;cO>1huS$i_`&eWufG~_7y|<$6HDK=Nf(_)-s@vPd7X?V~HL8akj$i|_QB=pgAz`ECoZ@5jRHv!=&mGH`C)6RM5zB-C zlH`%g5q5c>&VVD<7$(30V=bU8IRtLhkuD)=q%c%D?f{21*%$&gCCnSUMmbJIFwrAS zh@CT@{KKGj@@aYRqudcL2UaKxeKy zRnFA^su)GVA{Rk#@J%`PhLBZX=Kqkr%Fu6YPz>GU%fP~d#IO`0P=)*duoA+xFbP;z*lD9aek!?r|{;hx3inYI0J z8pRwvEe|R_;6(SN=~AlkK`CoQ?oC72bQpjryZ;?^ID?Z05y7$dAjlg{;kU0VK^TE0 zg-4_7H`85?;37K1dGgV$mNF-;Q3g>@0TxbBzF0X%~KEuw5y_r@0=YbGNtTa zj0r)VK6^J}lRgc0n#hNZISmp5D~Hc$Sw~EHa!CO!`)i}1!-#yT#A0WeXlumN%n8Bu zIwdN3$Wh@Ad1x+-0Qz1s1ho5E$RcTD0P+otq?X~_YLXT0j{Zo<$+ zhefmUtR`}TK1ToP;r{6G#X6pRH)=S%6$YP(CesQBH#Jl z?GaMMTOxq8k~ovVecgSqe5ht84Uj+d+&SC-cc9o6MyjF-I7nc)rVAZK!m7X zEb5~*y~OxU9Tgvw9syc08e1+8JlXs9clBJ?^G`<)tzSKvS;Bhu^Ec=mWv+FcEQ0BD zpT6jOFCo-_QZ#x0d%xu4mm<^Ycbon~yGCWX;a{7vKN%7*Fl5V>d=VxD36 zXTQ@E#^fL2Gh|0U-_hoFFeX21R=`m@^@Xs4)}|(j?o(^RfE}e!1z`g!O)l36okF%b zL3$oXo!W58KAZG{-xUX02kv*oZAeCaF+$`;WJIB$`#bDlx|@3JO{t%V^B=smir|iZ z*jJ=bGL#Iv>*4$B;u{Q97pg$c5ec{}-}hx#P|WfMyv65I`Fyf+L?6W5@kk#3WV(nGaXZ2)c@>fw!VSsznB;kjX^xs*q(4Z)5k zShQ+SbWd}n3tHUv;n%VFh!aJTu9fhDCb4#DYuR&+41~MQO3E6FUSrDTtGQ-y2Oizb zM#!^i|4PN1q;6@wwB_W(Bo*}JeL33@zR5X_WZ&2Od4FX2-Zs2Ywfm$LzUsm$cO)^{ zZTc1l>gOBc6G#qwO%+c<@wDZ~c8d@DNwM%)IsYk1g$j%_gdwuB>n>w*;auK?V8U6?DqW`#W6lcF>PLYA`#4u2W2MirGb@|Y+j@Wg|S5Bsb)Pa8GdJg($S-7r#O>`Rq<29BD13PK%qb%)MW$7efQpXgU8z54VvZsb<~^dsY{ zu-UjNhDz2Q19GxipDLUmp`dAZTBwQ0*S8ruM%KJ&EM&!#H&=+n!BufQ+x`I`00j(` zH%xmJO$@TH;<(Wujj_2uZYi}IMy?u*M@R2buYdmZj%|s~bU)6waJ|LYJ|?p?aD3rzQ5CBBMrW(7xNtKEIhB` zrejE@l&{DKJg8)C2e?dIsaK$}5=Gxi^`#nb|3D*bQu+dD6?%t^-J>UB`QlO*24h4- zh;3gXI*($zv6mj7yYjz zGX$i&_1*?*#1M`5vMW{@Hpy;wx_?Hr2|doL*IM{caLDb0QNHj0wSy@~eDL{-NKxAf zR7Ns@*OziLg_pxIMqh>_JqlWuB#B<{?4y!s+sZEHU)Z=QF@;*JE@bZ9Nk=kH%*=}A zc*tgcY8pq74ndCXc{V860s_i;Xr9D)KuqYCIN!W~UPxBG*F^a=lxPa5c-OwUlit>W z!rcFR5Kcn9YjNIT;SzX8r~AD(b=K$Z2Q zq-3ly&sqrNg%*ygtEFAdm=>3BdoA(q+K^KyFBj0@emD8fi6xxovU}juJ?4;}&FEn*LOY0{IsoFYf=!BYwFe|Mry0g5~Y%O3Di5wokrWGBAQ3P>_K~vorTFx0pit zudi@PI(XE~hss;ag^&#ko@SvX$KUs=m#1T^Qcf%mQ&sx>#2FfcvnUkHfKb;&wX# zTI?_zx!a+U^VB23Kc z0F^i+=2)nq(-z^g5aD;J$BU(X*!X+GsBo+-*+O^3nPS9YszC3}OLoPC<9rhbV%%M+ zR>G-J1L1I{f^at!QE0IuN4pZ|s1nzb68COzI6alEG&DNAML0KJKDW{DNTDWAMA<2d@{tPK#+mS~^3QlI7nWzoKL##rS5 zrMq|DNheV^msZE+^CgA1prS+bjV{G*#rLp!_d6GI+=}hD%~7$oA299^e>NtrJR3HK z5C>2Yp9d;7xr(keiiWpTowJH%G*zF>B5(id(|5V6-`8I(TpNx>MUymH*Qn&gzK)u_ z&;B)POkhyxbE^lJ8bXld)rFu#5c=u5s;sPf1U{x?GUDJeO(|f)M8_)p}!6 z4aG&nqt9*fOHIvOHH@nTT>=fyRZBb+3zq`fqv%CwHEslH+{_(XZYNUhqqASkNpfk# za1AT(X_#CNKO-M;h#z_;h8|=P&tM)2i`QUrQHhO@_BtbaR2LdQOGhv>oVToYUuMvU zR;A=vGpnL06O5wQ=kV|zN?jJ}J_lXI;Y(!U@`x}g43Wnnpd2cW1w`PZnrz=Sn#RP^ znVP!%vvrGke*?W`>k93Q_YED;aQA2(>}c(B3hVBu;DuIqT8sJRNS+j3Lt5BJRA1xl zSPs+M_b%cN$?pAf9|@s0UATUY-4=2>{$n~>d6YWg-4>99LzFjG9XULT zH5K3F64|0{8lN5aPK!a-C;--|)<;5L_da&ls6|yodJPeKRS=#(`1n$zsmoUHx97xm zn(oImy^Nur7i8kr4ua(tBgyt-DzcsP5Lz3~_Yljsgg*K^ed9#6B$nb-T(-lXw8qFH zHRxVxxRtadPThr37%awfKVsGm2-2IWiE*5b569M(#80ujs=6L)O^j)NoGHmvD+Eu_ zqo&Z}CyenGM^Dy>kV{NAyb_=>!dj{WJ-f{iRi#K;S33 zObkt30k@u>zKWPoekqw`a9^!cP+jGLM(ON>FKDk;-IQ;UmbVObe;eqr@M1LN4X$n( z{(fL2@k#s&4XH>C$4+y@G_es)xAP2=z9P+qZdv3RSqT|mr^N^^D+21kDT!_o*W4?m zX}v3Yb|aGpTNBGj6QVE1@tMFcbpvM$!LFbw7nY%{b(18KUbiPz?mlxCo%2uo(T-{G z8@18?eRDz-W3G9|7>~ZGl6h3ayeG>%e0)B>ZW;hy;Vdf#P?5&UKSgCe(V1#5#6Mby zN|=tm@i~s3UtclmN8^IhhCy!J!z2v}`@IG4^99`mBaFmMyt)RxKZ_2brXR&^JLB0T zME~y8=$^gO8&1YCCuVT`?R6=x;>OGv{eBZe3T^6ga-r3a& z(R*9H_ZpoDB1MnRuGNX&39HxWod~N-)1t>0k?5kgkbV8;d7pXTKj5D0p1J3qx#m1S zpX2Zv!0&`a+Msb+0#UD<@KDkQRy#;&Q?zd!p~X7B>;O;cNaF9cL|^tg-t;cu;49W$j8rmgU3ZCh5}8XQF7W>0cr?QBiC7AvzVQ zc;?XFQdO{l76IxQ;17)^s79DC#vGDHKZNwWz_FG_K$Lr8XIx^GV{eBXA(=i61O>f$ z%ekpwl4a-QlNHBKG(+#GT{N=#_mxw?5Fva#rlD&MWd-z>jz&QuJ$GWm*YVkb0Lv}{ z4=Y@LZ+z4azOgh|<~kNnIWB~nlG2qL*rZ3@&q4Fsgo*4atvy)D27oOch)Q_xB+9z@ zMS+M39@~GoF^|T778g&1#(yG>5^utLWd*Ukjy)4Z!SN9f<12oAr@u@ajZUE7$D7oZ z4*7e_Y3)xc)a?_zto`|7R0Oq0UQWv>Bvj`Tg;yukjVHX{AwpdfJz`93;f)THjw8B` zT|RU~A&AXS@~NQs&g)y6M^NF{PwDP8IA4t3dpCSU%t6Ew(rT;k-=4|BAzku-2~dJUdbK*n~@zy7=$@XWR1nBul6 zC1aNS-!VCW0)o?o@6P+MbH;aVvLir32nU}v!l=!~wwYDjuwR~SkKwJvrq1I4XdJ4i zT#B}f?N-W;DWFRVoRXBB#_4Na(E-u~R*Q}(H07hg^k{rWi=g4ym>sPcF!J2pKimDM ze;nz$0|4CiRN6)%$yC)`a-l`1X~U}E-?PGwp|XEl$(75Wqc;Gl5A1lWWZIvOqfTL) zO#D9PRrAGhm2S1kYi;T!l!0A=tQyZ~TZ1k5`t!;bVf)&VdpwyQ6;UrlsTMKJ2%6Jq zs(zI=TE{>^tET4J-Zi$?wcYs9{|dt5zV&IiII>5H9X!Kd&c@5<34A>I`k+rk+3@%N z=j46Cif{Fmk3Jsl`TyHXq?fU#ID`yNtm7RXcpuchKExJ%{V#fbfhw>|*XSo^?XdNq zdm@6s3XuFQ?+_CI-^%FWZwuiJ@mKS%8!t+qKeR;Ji?kuQ&rZXSP4wgMWB$AlT-D=n^V!##Jv-!Fc@TQ%6f zn}3z1ASGZ_>ht?(@A9=2e!O89L4;PUiILm{uh&ksIp{wYJf(x9qT@t;gwsZ3x6V(z zoIm((OK%;KMvF0lXgn!t&@17ct?T1$Eenc2%#>q)=mJjSzhY=`Vh%fAkN0of&x4g9 ze_k9%QAmSXrUO%s3MlEQPJC=AWL7P`j``YlbdssS9O!$h^sV!t724o)Ou5NbyFOncv^NH z10e7^j`ijZ_S%Vg=H)NIa|sz-PP<}&P!FQqFHwj$As>}OBOc5leGON){ZFr(KK3^A zgpA|31rdp0wARRwx)!%Ve)?A8#H$Q9|6i~f z7%S3~`_OCjWmx$h)9e4~zt61mB+enidgglcKu3YIksaAK5v@sHRayW)y`9e|nk-=w zk!%SCiSMG*QM&rF&%=(tu)q1SwO|;-^2>)u&y@tmThG*1&p`g;u?~Pz4J5B;`Oc_6 zW%Yy9e>~HmM1tUZ3F(EGD<0Af2Qb!pIM=ZX1I#*ZzhjeeC~QX715%FfU-e;C3J?sL zO$49|!h=#2?j9AtWMV=zjUL zTDcL~gT~pOu1-Qn6Y^zLIiTVEV{LD*CdbyMq2kSXMk08mtcXw~T^QTHD~^8rDRV_-i3}MK6Wp9(yGQi;JPZ^asdf9wW&776)Gxj!6k6H2{u#*MGQ+a+{zr zEVD+@{N)>DW~)L0(_$r|w+P-~ac4;2A{=-^H`I9(Yeu=cf)lPx!spl&t6%ozk)Cp@ z$v|n;d$~S%9ppg`zEVFI4O3l z%2>~KJ}eA0$MeyvvCeU;Gx&I>jP-1+wWuZ?LR&IROZ9nw4<@KGN79^N!FZfJ@hVS> zD$~!KqVR`>!4uOhZ$HR`uN7NR(q;fa1=ZFrWgFB~RLo%h2K69PC3}7cQwXbNUu@!& ze3kyTK$s6uy4M^h>+S?;Pb?Rb+SSgiMl<}|(Ih)BC349p!=Icq5j)%EF!~1y-nrWr zI&4AgPpgs>t*f%)8;c-nP1A?0p<1rZNpyW2Mcxl%X#LL0u-(=&sm&_AJBF#4O5ew{ zU96&dn*bnXQ~5hTUggO6G+zi1K!XP-+xsmOVh4G~f5vOX0Gi2-%Pc1uDYFxX7e3Wf zhDvzBNbG{;a&hoV*@84HUwg!SeULGjKLVaQL*|-;$LfUm_^~D_w=+Eh>o4U&1NcXP zktdA)3>)Li#yDLc9QW zvmOhz&LXgq>oI;xc90)02V2MDsEk&JDU*|t-v|0!r>DKvD1fK`!j{WZhPo_1`lrq& zxByb&2?9^Q9p3x)g|tX-x{_-BSm7^fNiLs5)RRlR|qKMAK(_uGWV-=K8fhES}JJA zhd43qR0qxM4kx!pVx`ZOj@2Mc=(0*XT49x7qlDK7C@U~!=9uVads5hW$=v>z`gakO0IUXeEZt{*FcD?XlvP>O>aU{qdc!0LIk@D9 zO7*BflyI6@{U-BC^+>a!TfDGj?|=Nw$qep5QR__Lhu`5uJ>Ts1W4S`1Bw!vcO2<@S zloKNExwIA;E9G0a(2ukyr^=lAyU(DTk~fm?JR*^X5v{8naj)W?jRjru#z6QfWdt0d zuBlaPu-XXw>r9a~Z#0434{Bhy@}2Tq!>08nx6$?d^ZC=7r%{p?{jy;BW55e+QmuG| zHuanNIn>Mbcw!pxSSR~=O1a&khSEghyCOTb9*a%0kAKzN&%TBqfB3V>i}%ur^6W*( zyJPhyQNy7pE0G{{i`|sW^1@nLhauMfG%MmSUvc;#b2jKtktX;RM48M~dW!nz&M@yH zg-7Wc?TUj`sGe}W6A340SI}|LR=mCYC6RtWVD#*#t8A!ISpRiJv!z(AOsbMNE+BSY zL(9hDxoz|H6GA_S8}I5z!v@~WaMY@+#Q}F#NsDYvE*5t962}&r9fzZ z`@O3FwJ{~`BNkL9xa29l)znp5v3i^Xka8X9Y+nufZ|z_O+5F%3w1!mb6dbK0)s!Hk z<`CS?dhm`>Cr~*afFjXT^CFGpCPg1jGyZA+B3q;ODsO2uo&r|G3<_p_^&m`j9D3A; zkyyoL0l;}aQ|-T6KfhSJ55uYfb`s+2SC#$P9)#vV6E$ib7>-3$PI**dT27D?ofzSO z#&_u269O`Hq&^x$N^eVJ;zU#nB?wo;88%i>V^$B$J>*qmlpUrvP-ERJxhVmmWawGo zxlvB}d?k89U?_bDGj8qh`bIH zJ_!U_o*FwpyWxAFpw^H-OXP2tPu$BJjFl@y)@nA!F<7oB;O88kjuMK!Y(2Z-0tyiM zI0IjHx(&pE|JJ5$eCW}ts(cVm$9cy6F9%`8O?7IZ3k{0WN=+tSnZ?Ihklj`$zbu%v zOdXM5on|e{PDujCzC9Ix`f)l&;&@R%3t2br%;W5=l>SrD00h3xR=3)`ymO{#aonhR zs(uY@(`IUaxBB;BMRb~@^~(gqni(0iOoDQQf`3cXASy(#M4cY-SfNCz=;st3=g+ov zZP4lfO`)2op*(+qx_$YF&>^NpGkKUwy7VyP7DnbywVhB+0J^Mn4I=%*PW_KVuw_fx z%SORA@`rg;-P@-+I2>9;KmUA~V80|)UvsH?`1`NF%2f}-%7=LL)R+q~4K!SU;YiUo zfL%JmM}&(=1Kb-zNg+}(7y~nQ&-i41&cJr@($YoQKK*_1%xC*9Y z07(yNd6d#;EDG`jWK54d+07xNnB8b~|R7I{_RjLhV=DJAJ`KN`)Ph}D_Z?8G^ zuI27wZf9~6Z)a}>?j&O-y(4It!GDOZg-aEtio zmegNeDqD?sTwBKNUaDAIs<9U-OZH4pIi|-N+~i)SQ(JCQTUE+sk+ z0Nlc`)=Mz%8vsMh4tE0R|vP94acc8vqC| zq7>$Eg$3*vPshKwg{Ign_vR#4T+_W!9y`J%v3l7LqYe5-nSSzFw$;5(w!(u-0Toz zEiCp7LAIM`n+cb>8xk|BABj9cX8zGE6k=|C%t;i52ZL^^?0X9EXMR(O^l~yO3fqZ#K+v|Z6u5C%BINlHt-zQONQ}Kt*<^}VRO<0sN zKl35xxT^>1>cQ>iQ{qH1BP?KJJC0G>nNy80lj50|D)4#kVF4JX5Ka1_+0`Q0-?Ta^ ztV_@1gF(MMEO_kx-Xc`B^n7P6(Q(X?xzgyqnc*xapg*sZQZ_NNZD7715VrDoJ#H$<38pT7H>4O7 z80r?NbI@S{mZlK~<^*)-M9AdEcIT$ZY#zw-akM#lvN@&EhB4R^rK-mt_2-QIndD(K!o^nIk3d^1fhn{jC zWfo3gWk63=#BBu+l3Sdj+OmfNJjH4TEHdqS8julmbrZLp0oc-2p9HboF`BUTyyOg4 z7w9n+53V8TZL;a9^u29j``c`(;tj`XQI(~0q@*<(tc~p~YHfc&8YWi+&`_%@j#oA0 zWEB@jH45Q1N%eL|1UDD=_BcHBo976)3jfk@&d~`Y+qQ%1{*VXppq(GzyzN#O^12?% zyy)Zz?kam6_MdupV=u<-wo<5X=o_N;yQ+{lvYP|>I2uVY^|!6;jpsvV|C5N`SdZc} z__I&Ll6Sc7B=TK}eR>%p&pGdg9)nB zqc=vjRJZBo4wjVEPx=xxnhtky;C-IG>;BgFouiksTKMh$U6TVaDE3)27mLGDCs*?vZBHq(>*U+pPgCQJcr!;_J=0iRMvyACOM=n5?G$0(EeWtcB?m_ zXA5WM19=vL>_fZG`9R49ws!ST&(DD2IXb+xvxjH;w?le3^)^Wmiq$BjjEwTeLda4; zs9mdAhj0E4C|H+QLdG^cK<(ZxJ8(NzvAUrDk7Y0na8-sIQRN2Auv0E)QXI29-yb`% ziw&*%(v#8vqF~NvSpTs53g z3SSnp34S50Me<9^9eZih`RNfp+`St2nT9fofP&ksE7eIgN_&sfTRP2oBvL2vJ1*@A zR4tyCn6X(*i-a;tuUZ_?l>SUNN5~1s$VgLJuRzNCcbiOWr9rV0aP?)(e}RXXEtApm2vgaiMd?W zbN`x&KIHqqSg=w+B`4lo==6qr{}e1N2vF9z*i#Osr)bQQM|JVK6lPuS|Na^~ugJ)9 zWU~AGsl$SS<%F=aNntR!_g!evS!%0qk$%|U!?izGl(8u`-QgE<2ud2HkJzFcMl~*XZt3>cOfqC$G%gyeN`=EW}eY15Z#HU*FNV(@S0;N*T?y4 zI2*?&)WjRrX#Uep(~V6UC@*rZG#b~9X`pvW6`-Fysby0}iG5`WDsQd8tDD=Ml&?CE z%vB;Ltc`9`*_fSDm08JX5csrm`f2rRs9A~5UP)EzwPOBwyc|BT3?}tHJwwb`vz@Ak z;wgs8IG5VaUsdbh)?{6A%Z(c=j_nuog?ekdL}N;V^tMi|XbCNHm%Y3wm@_$LjRub* zjgh7qvG@i21=X;{cRS!tmd$ByTvo15_$^1hSiipIkK#W4{e{a&L0T!-=&(|C`(!JN z(U^WXR6*17_)|LUnK)3=1zy9fP$ zT|Oq-Vd&`2-Z4Hnylq=c2j9uc3obYq_RTdtv6en66N-3Ch$e=6m{g9$(BV>;13} zxu7vp>0fg)?pA8t^5BN4>|*`{w-g!_l0xBElE#IG_*qJSr8}O%ln#5r!RON?Fe=5C zjfS`kq;36!oF|KUo!QA)nPFompF@@_zWxb2)w@Ne>glJ#W_|yW)VsyjIT<2w&e*?T z2X@+3*-em=Tl366>8X`QbRIefYf5tvZT(36bd8#y9!Fq|{O?iXaT8iC6Bm%M{39Xj zBt3SDPOYXq%_J$#pWL(TfV2DO^derWR*FbnCxgli^&1y=l_wvKZ`BFQhAhXA0_aum z9wkQmF$jFej69w(u}OAW6pVdNOMiS|m=7iv#N-*YQ)lpwf%HZ5IzRX8m9mZNHYDro(rPYj;mvC)!I@0g!zi@IukoSFO)wkB?z8Vr3_xu z|9)xIV_|Lj0{6lm?l$&CgK;h!9PMtAu9oBj;h+bG?CKY=8>5Xf#b`e;X(-QNKL;N; zr&ec9^W!e$gyX0e;HvRm>jlq5ijoydM-#EFpQPkj%+%U(>EJG;CQ4o+xo~(#WPVSR zuu`|xSf23BB0MMt=*x)0_&z(CZRb?jbJvQ7);?SI7_UkAR%hviRBXGgavVT6y}eJ> zMN!6@o^PsqQa#Ic$AIMXEG z9_nJw@|TKo^(Wgk#FE>GX*Gwrx#bbXfDF8ul42DXQvA!x;nV4S+K4~93YUimM`V=3 z^%!RZ7vBcD_sepOW#4zF-B+-OOie13)oFK7<*7N|MQu)3_Lo7W@c~MAZ1regb992A zvW8vkXY=4UZ^3Vmy~I;BQ!NFK$yHLs^6#FPyc!k)2p=a}T{r{J zNMDCpmc~SMA-FoKM|9Z%I1JczHmP+ui!>U*@+Wsp;qoK}$?O8VvI601W75(JUATnu zCiLH&W@N2K$%+Ff&BITh!<>Hc=rS}unG($`F~TDy$@{F>@16Xq&{d-G=JSg;X9cKL zSLts-Uwz0?&QTsBs}S(r27~}?bLkEy_fo2 z-!p&q-Q{_eGK+_CO8#7hQroNzzRl^COkXpqy(Oq5*ub67eI_6+R^sjQc zBT4_SQNsHrRW_qdxdnrAx_$0A=*jI8yaIB!DeKEcsuM zmt1vfO;c)ZM^h7cfEJ^|oF94Rto~}!DB~-HJH}Hq=~y>8<(DjxR5FyrictNwG5^%- z;?hX&Hnp)MrAhB4i0F_l9|+9Hxu0^kpcP4G6cNK1=q@&q$~jX#a;CE_uRd3aru<3! zUnk1ax^Q?Ao+@X^w^(lS-hzA~mlrLl*jQsxcx7eVwZ zWJI0S^q-7LC)lZ-_Q|!4yOJLZtPSuBC~NZ@F>b^$j&PGcKY83TO&au+Fv{uX4s$Ng z71fcJDmzV2Fva}sgnn9>A(~j{-yn;{IzN#kew-6M{U_E>V73=yjL2xVzsAhI9Aw1^ zvUiQWTBiyIUOe2dNtT&&&)P1CeBpNJ(rBJNbM z>66eg5m?zV6$Ll9thPQ(0Oo%tWltdVmWw*=lM4~IHkRs4`;gwb|#tbL?ya% z_l!&wQP={bqhyIS=5{b5#xm`b1n#qS00lt@9M0R+9P~Kg3%I*i=<4MuoCJ~7f zq-k8Rpyly?)ME}3{<<`N23~>acpNZA?i|K&MoX9=L+qic_8*RjIjB0_2zr4blEx#M zdjKv{!1!7v=b8uYDY-St*u8Z~Z(#zXCG6iL0hun-TC-tbDv1RZ2}4lz&IJ8$Bca+# zPLtQ7LK)-%v*d!aHAgM{?`x?ANGYHk)8R;9dTUs=uRxY7?+T=>d_d8*K`2x7Hz$>% zwJ5jG*#w3wcsPoOk0 zjkkTOta)Y7cep>djLv#I??wZF<5`t3{dQuua(V<@C&_=X znL07VIdUz->o+$T$x68XA()O}Ofj!tG0wl70W|*uvar9Bql6Dr`#TB#wqp~wxAb8z zid8wxG_Ci2df~78@w>xEckYEvk^vx-mIe4VlFV^*3vz-kf1PMhLksu$=a$)tik2B^OEFm0|hy+3aAwt2RZCU* zE!_td&Y*3#Aaz1Iw>gzTir#uU$F@s{?s-RmK$aH$(M)HrFTWuI?~PnZ=kbf}Zo^%s926My#M=rXHL47g@-fyRN1)F6O9`L(+KcCy$}E`X(VGpn z3#(u8^Cq%E8Io_D;^g6s`5XI^K$h^|z|E3wi%8P-4aXuHb5!};Yzm~l`Cz#>7GH20uBRE7g+YHO13A7%Zc{ybyEJ~knRd>c& zv_hrwH_a;9(NDl%!-Ci3UItDk6Oz~+-`$xunEy6lgyc6&;On3{Xg%USxaG;Rx@T!@ z5XwsJ4}JLnyBTjI^~!sK+h!V>mJr6GAz4HIbulcAnli`mWmhXHUXz=7Q>%yx?{^6n zoW{7tSh^4qK>qL5%x-<_#{oSd&k9;BD@YMLY~x70H@`rAPdS4A;y>@Mzzr$lh&D;u z;N(+DE$MvUDk=Aqv8BwWB_yPyYKvMxkYZ+JiGHIuKDkH2t^TmOUWmvq8y(g39oB$o zKR~Nk_I|jTYmdMAa3%t0iP`)595fewWu5i$fG9m!94hb}nN|Wjc}4HG+FPg16UwLo=DO zP&fhH6(xMy5$WCDH?~`l3}DU#-Bqc%5~bqtF<}Th>MDz=zF?nxc~|holz+5r)m(3I z##Q;s$F-3`;oB3`C*s9VFU(yk-+Um(Ar$rwmNS}W_>1g)lV%xa=Jv!AUc787%Z3f+dz-8ZveD1xeN!WtYDEPamI z3}8I*l>n#)9TZ5(S~48`Lq7anJ<87cY9vVA4*SM`=?PO0mprCG-p_Nj^x^C_vTtaWwnx+9m$}AHCy??vTC^e6LXo;L%$qA&8l!+BOV`07lFb7jbEA zFotige_=l%6(F=eYhsFsBUn8o#W|`fJ7u~*eV({{($abX*yq_=VT0jnU?ut$S-);D zxeuzvLavnWzHRWce-4qQz?^)^za++7+HD?t7Juhj{2uaOquaylxzKZNtl;%uTcX}= zu9L?>$;y?P<<~R2->>77{Wtt}?fm0vc@hyx-vl7?6I$6eo&NtQdr6oiYi7$!hGUFs z-Hi|;WutGI<@nc)Vo_shoLJp_Wm09K_dm@*%f(gyPjx zC2Fw`lhV@anF_rE*)SrBTC)lU=#zVOfedpY(+6cQk!1a1vr8hYzBTOtIG`Xj{g#04 zs8ZH%fB8eARO8x*(7(6$#L`Xn`WI0*gDV7|2ecxYn5wW|=Sy}tP=fYVb^LF1go^LHUjujJj$`L=Fz0vk5| z_5p5;6=HkBQhye2B!pcrhqDmfU1i{pd;vH`Q5tADMbp~HZA59Gn~)1>=(!Km;(Dh! z#dBxpsr!UDQZXOLva4$W-moXRI-g;^vC`x%b#anEZf z4Xm^k#*APvN+&Fdvli_qkKnzQy01Y3Z(C2VUWNTP&tGpeoSpdEQskT{o?^G3xY1ba zi`zjGoIB)wiz&USA$RrH^d-#`6A;a4SSEA*cuYpI+`BFAWW*bZDVLMTTlzsnkGjaTRxZp!~aH9{}+PJC2v zt22&HL}2R84@8T;#q3r7=ZpNpdDKLWrDIquO;~{4*@BdBuNcbZ(`DdGMQpCf+M6mH z3`ew@cO)PO8?jdY%X#;$z<;q3GTI8GT4~O-fe!`8jVjcxe~n`Z&CQGM{p2?h8N`CJ zJA;#ap(kqiBbvqk0T06tU!ZZ>z}e?P zT;VyQ@38zJLeX8A8OQAuo*@XXPw2&uPpwa=A2$%2mcp~0m;-`=hv;knM4OhZNBq80 z1|Qb3W`gP4ua6sv>hj?`;o*N}4klv$)nDVfJxxo}$iXnYpy$m1*(MY@C+EFV*l3yp#Q09B4{>M*g{+L?%IJ>Flc{L=%iv zB5gAmN=h|aI8D-CMit(yTgk}Gd#7jCudo!SYyLY(3pZJ(oh2>jNUi#O4(-ICr`&vom1ldm`Lma(k+Lc2};3^hiL03f9cR%-+I4Xj4gV%gZsqst{^I8nA z&#@UVG>@bA+B9IO1mki66?aqWTD=%qIZ&!g zezh59{O@Yq&xmvg#%HFPX=)z7eWv!D=zI0#Xr=mK%}YNI;YSBf9y#Y?8e+Wv>tD~LC9>`$)SA4nv)g6-Qel8sx4^h6ve!)97*11bdGc8`sE=qXI;@pn}%&Z z{Onh=GRJm+52651lKq24{m?n@+!FLOiu{|gfvN1uXIzDXfeJcp&(V%yN71D=nfu&r zJueF1Z?Q7uM5N;If{Zl8e^1(+@ptv@{K#9nWFfuyNG%7r-@I$UiH3r zQqvc_qIBaG8ZFIV88!2C-T&!uBk^reeMu7&U)o}^i4=^?yVN6HgAD*r?&ho{cH zvQ7FjEK+d^27JC>(P6C5N>}qgAGdOPNP*pyYL+IH8KsKo};8cNyNJUK`awKa?NcchsjhlwHQSE z3cXxsQ#L4k0*z#o-Qx+mzc(}p9v{3vDO5`RDVj4m2BY>;^(u)F6UNEG?l#*Fm#h>D zSZ1{@ESh$ zVMijXvQgSJUXc*H1JeSv%BgVCwz_+sml0hnC0{Q_TbB0xJnz1GujSdNRL(jO)I^zB zl7Gb7{aU8Fo4qOs+-GGyZ&p10(s*<|=kWDN^hh$h8GrACD){Vlgm#-SEJQWpUwN6O z-;O%=??01}qFSNw6RU5B66T5r5YgK?56_TRIjO7twGV%)!aLS;xQ;F~KAe1XcoqDr z*RMf}V!-KR^nrHuR+u5pI_d8qGDG?0Wj3E(mayRCeWmB)JlLFiM=SyRSSX|gWTQro z{2e~m=|!~YHGlQ`V$9uZA!NZVIH@y&jz0WYEc}z$QyLtv#tZ^gO_=$*@i~C-(`on( zWdy~z*douP#2h3&FG?6MNUs%nI*X(_edTBg3wC@titw3Ck6dVpY~n^j#v=veB50*i z`f>UaRg)&L%cHj+*QmJU!DKzON*BWz8hX5U0zX+{i5=^IqX_~1te`J!md z!l``lgnSiR#9)T0qAZkn$8<49VlgLgVjl14nbVF91n*SH zGttrfi?L#7u`Cubk=F)MTA{Jv1peP)eU~v()YjWl5JxmNoT?O*0Zj*N+*AIYyse~n z@|A`-ImS}9fHICPFVMuFx)6tP9^e{}PAgX}t(Y_36pXs3xOBpmds<^!ij^7j+v_+( zBSM-=(dNKZ`T3_rPuQp9IKJmP@OP(^-K0|Hy*0E-qtnhP@is1kkX^w^-Mn08>8Tl~ z2pj+*wbGH9!l@W2VOF55YFuPaT)G4%{nd6lf*zZ;m>VGxpLMd4sD46lg9gLbi4G84 z!n+x8Bo59Hijop9eSr9@G5LTIq3*hp9$%EfE`mZT>zFoHBacOD{<#Jc?^9dZp8z zQxIXBhyZAu`YF;gVX}HCj-2=Zi%3&zqEds9Uct%Yx~U=_q@t;$K2RaC=lO>>)Jt19 z*i?MEG@`jFs-8in{z29~7&H3}mhS^0`YVPw(+F(jh$cut6V{@MC()!m=#dRH1%C;Z zPKgnqgoeMw%#mWRx%h6Eg=Mb<11yEfQgI|u92qmZ0mv4Q3st;`{m{6cQ=}beDqI|5 z1qi6ai;NftXB$qe3;>@_5z3a}-$96!9Eolr_S@}QN4w>ElSO(I#b-5C7fV#06pp@W z40#lUC@-aRFOpFR$p4#I$Z09;{5ERH`EhjF0x{a$S&QC%~CU8_!AqYiVObzOIDU9W6i=VV>qWHGmF ztpKcksE2aIqn;a9&nwH=f`0e{Rf>azyJ)Ka59GF9)jCiESjWf0aR9<(=q9QP1Zj7( z9RX!U&R&C|NsWp!X}wWy>`i`2eByYw)%9}f?Xt##bbbjCyaWeM^;F3<<7|2n$^BoP zn-rSrvv7?p5QII(1)#~1O;kk)ve(Kl4sRPc3JfE>$m5Q2ohERuh?>k6T9&pO+b&v6 zxfvx9WNXixa&<^2g*pB|l$+6W>Ru|kf@Y?bX10*xea1$P{URwoEZGg5)J!M4>3QH? zaG}Uw2kXQ@F}XN*E84IJfv980{{*650KhtMW{L!_j;a7b)&K;ML&y;Tz*-O0hHS&H z;D%kI3Zq9|Yu9adu;_&Cc85>xuwB5C)MHU1SeaQ#r+ZDEy%Y zj+-%$^I{+OYKlk+0&1Nidkg@udy%z5KoJmfRU&{#6FGVvw;Wxb$=}kpU*542pH`RH zPu$wo>slnuIK7PD_M1r-NH9G`wm(H;L0oj@*!XJ+OL~JQ-6QPZd^C`2-6dg`AT-`P zU)?X*J|IEY-52PMCqF=^-M?*<)%&7Fs5aMNZGoj1rBI>>B`;eMG_elr-! zgyH<0^LS+-P7d>zzvD+I1}ZRU;WyCP`v6xT5@i|^wMAY84*glih%*njTnyRu4(rJe zv)T@G77PWp4gD$@9#|Oe4#6ni4L_$JF$x*R29IE*MlUT#UH>1-?lT^)cW)Q?!k8Il z7`-!k7ov+YqIVJmA$li9i7rO(T||%GLexYFLi9dL5G^`M5E2s6=J@aZoOAYho>ymm z*6VpQYt7v2{$1<(uJk^+8c>xT$Tl3HzWT_M*ef^Q_gI@h<8_jI=b$U?AX0nC_-cqP zc+lCnkFtHpjj_A**I+o~aH87~N_HrexHlkwIA$d&9lT6s(M){ed&AFVqWttTF96c}sP9((IH)|xohUOV=Fe5@;Y4B}OAY>kISfh8LV zB#&`NYRAXM$0rWPr-&z}$HxZ~$7kGb3neBn+7qA0Csy4imJcR21SUs_C%4=t7tJU4 zYA2`jC%+#|&IXUq1cSr)#2~mI{v=NQt)03YpSnJn!V+U}1TlCz82noRDG5VRhasB4 zzz#9z=9L8^Q=~f6RPNI>Nz-(7(+m^SOo!8W6B!64;0^+}J8@LrW`_5Ath9DUkZFwP za7JWxR9J9UJY+_|eYQma_YShPISg>L!s|N0`=LEIE-}qv;y#?Znh>p{5_?UT zW$`c@MwL|eS-1CdCewV8oCX<^kkeSC%zf!Ne2KPssnTNU!Q2v(d|Br1vgCthF|TE8 z+H%MBl2X%h7V%22;7Xs)%7FXIP}0gs-OAX+%EaNyRERsoif~<+^ouZI=@@P!isWYl zv1bLvE%o{fcqEUZ;IksZ3gh0J{#RY5mFqF<>YV%PV%_S>;p*)jyjg%H+U}x=OTGQ8 zAc?G|__-vdukdZvt#spM+S#*7X_6;f_#c7GyM|A9TwP10 zYD#6ll_L4d>~*)%g}afHyRtZh2%$|#Dr^D?_Dm%qTHdi_#_rk*eRX8skLccwz6E!g zTWfp3(kST9bpn}<9V?+-yXVr9$AmvE2;;x8NL6RBP9WURj6IDwCIT9WH*s4UNPeZl z98m0Zh3nUi;C2*=gzi>3isToDSX7>2q41FH4N#p5I}z@}JXRY$CcNiK)B*r<$E1q- z*&Yu5}OZ$<5TNO?SM7mT_eWC>Z(q-BH zWl7~U&HS`0Q&J)j$j$*LX+VLc0LbN&gN)?e8!|{G@|^|?;h{c6IhE)O(0WYv$Ge__ z4MQA?!E?TC?GV-|fs=Ttfc8-xk)yx2;Y4!NI5o$x9um-=72c1rooQ6VZNaI1;W^dh zIVbj52Iuds<{R(Q6x#sXwIbrEZ%Bb|aE~7Pui9{IZj=X3kF6Q>fwtc0g#aU(r+;5U-7wfi> z(pWx!jwN`RdODXujonu-gm#V?PUOsxpl+_i3Nv7}OURlUst})Smw+Lw zN`FFLN-h*PRr~Yl*V)RN;)*M@rQ_{LsIfv0HKf4$)^zLv{`zOW)r!{YrWcd+mFpEM zQQvXUP?`LZA!cyu77HCV5@VwAL)~J7Ar#S;!i|N)rIAV`bxLBG@wcH@S-cOU^+74( z?X?C#QO!KEz(3HfWoGp8e&^}DD=GTVW?p@F*wL7W0-*etTMRJX9}?*V<7x@ukt*xS z{a%UClfO9V(^I(ND^kr8ooP_XE0zJR_ra;|r}pDBC^yQ>bbdvP_EXx9iwvX5`Gz8W z4Kd1)hs0j$KqrHGtdFW9kH$=v-A}C~Ulc@In8s`4l^9$zD)+AFKZ5I0KQz_t{8C3Z z=BRxy^R7&eqoOQLlYoA#%)>1f8hF!=!u>kNSX@^pR-Xqc!zZ9(gEkHINGhPH;zbm5 zEH@l@^EHMA`}`uVo)Rd*d5Tb3ah`pkE&jHCR_~v|y2?!e4y#XUp8dP9mGhWL(>qK& zvpSymMyv)Js~{#^F!@=LHQ8NiQ($nXd4U8?Ww~g}iuV zI(AA8ICz{<8hTBrJhC92mgZ!AL>B+z!IA!7N9$;s-#Dx^-MnryqO*)nI+0W^ocWfb z%)?-xSlWHvl(RH2t8v8%Ex@fcp538D!Q?cp!DNI~I5D0#Eq*4WsGj+hdb5~?m?9oo zs0?5fp%pQp>t zJnV`EVx;RzFaK*={{ExqFK_9fKz8nkmcJ_E1oOK2G3Vu z!}Nmj=nxlkj|%WU>OBXJd*#edA`s&xOmXq+Abx*EVS8aTqu475k$5Veoh_D5IaWyq z3`Sq>c!XXj6#o(9>7l1avCj3*2$&uB591qzUM({RI6O+&WKE=B#sP4~$p}*jil}zi z!@kL;O0gQ+Qn!!L3T}$Qjq=BBbJ-cotJu-rP!NC+hMvK_MBT^hiqX!?d_BpbZ9Ps9TQtXV6c)?U7S1Ga zY{I|P8y%pl`ix_2k?uEZJQE`u^YlnIv7}TrNop7|7Qm+yApcjIuKgSwx=lG9XFLa% zWQUOLN>BJ!7?$(fJ8M~7%)H>*%*P_Lx%<;dU3g{#_U!g1p}8V5c3aHLh>W4`>M@P4 zW!8witpbfv$h&HOV<#aWj2sCb~FsgI4cYVBi zVca%o^v1i~)#5PlQRl8vebA1p<@Lp*91Fx;2#wr6`YY@IEMHtBU6rN8k0|GL4bC#fa7+FF!r%XXo;a`%WL`&-05a z{eINkoUw(Ou#(P_Ni2$td_#vA1h-~T=W#oOJrLAN=Hl{7OA5Ao1Kwacwz?~O+FN1X zgWK`xEtnVn01{$H#wx)@Zak%58>*~J_8mY%ZZ26qsXKV*tzPYFly9)OEh-lH zS*7vlhIq-=Li3dM7{bKiHbel_;YKb{$CY!|5io4`SAmL^y$}+qaU}& zEsXm0>-FB=`QG03&d%xnCU&pu)dD4G$Coc(u2)vB78W*ES8rAtvGd8R ztE($3E6dBvOG`_iKY#w8HtK(gs?$;bAgQ-PD&|&59s8G%I)3wSA$4LLJ3RdN_8b~I zA09p(8u~l-;j*vqs=ND7clT*`_uu#L|Gs;7IZ|-h8;2cnzUeW%e4BCgP8a*`?oFe> zt&MszFz|nP)ZyXbfq{XKA3y$27`3^%xv{bFUoa{PTT6+pBEVMQ-s-2* zGAimO!01~<2^5D;*S zq5AszdV71{IGNp;>D}lm-Q1TtadG}`@#L$HZoT>ATO`%Z&CS`_`9G0VH$%gJBdNy5 z#t$Dp{I`&*qobptp>d0zs;a8qqNj?AivLDWZzP5PF;fM(b_MTXSsA}_aNe@1w`S@M zJv$Zl0sQW%VwnD{?c)LRSnze%WA9GqJxmHYq4Lsg1r z)MzRj$>4cdV?NSUK9)eRxLBmvTrrU+<^64Cq`7kH74rY_P+O{JD^=VZG>)78!$VDU zyNP4cdRP0o*=e@MV(eYraw}?Uv_Px%&FXvqU*A^8T7OtbSmF^eYqvFQ^u_8eo$qnY zz^ZgSq@p_wf7*^}3ffM}2K+LZC{*wx(V-OEZIB>;EPzys{GT4`k1stDL@c_UZ6{m9 z8AO!^>zqlUlE(ta9mv3iZ?pA}7Yal8eZMVt#b6&FTz+}_%W-nUCrit!Bu%SA}NiXHlk=9s#v|I;?@~`wwP!)(d_9w zMR7pI@E3JLAs&MW<_?~%M6r1%TP5M=RhDSJH;bjAoKK<<@oaDXOYciFSO4Rowi~4j z?npA@QW-k$yfAU7-pMj|AqZze`0(y#+d0JbAeG2Xtx}E3c{%d#w6~|F>5_o#3;cJh z_X??3+tV{Y!-V_bk<>2x#j#v9`z7(@jbO4wRlcufag)LT;PsBcF+cBJCT}IT*%_~@ z&*oR|S5*}?-wG=$Kvl?yZmgAJPRo35IYijs>ie6wX2&1lqE<`Qm3>WOHH`yrd}^CU z9vHe5)V<-m^-zUq4>ju9g!_risI2aLn_kEFG>u2|xis^ny-x4=TEaiwto!8g;q9|R z-iuDoF0)=Zwa;apF*UIP&iljM*VVm3WWnhlIYqAEojRMYKl&*j38eQ6giEb?N~k!_F-Scm@M|32%b4Dc8&qpF%vZnS-KX%9u>}LAczmiN zbjMkALR)g;bcVo%7#K3@JxL+J4Y>4FEp=mu3w_Y;|1~|FZgG@?%q<`vBjBv#nA05+ zl}deCQYy}dDL|M#_-;|c@q&lFZX9ByZJ&d z(Lht@*;)_-<+*BvXymzKyy#lnw>{0H=I`+Kkg}beg{PMXd5>B&Bv1OiVNAGmO2&f3 zt6k(mc5+_gKuTwXy430EW*GZUo9I{$pq{EJ^UDeka{pB=MT%ghKdk3#w9iAmd;P(} zgr;98GB0u)@GKOj6E6KlcXGX-Ut)oAio*ka2m;hgdCr3iBpMLWNnt{vBFq3T3QcHs z98No41m>r`?G#?8hh>H_X8nN%Q`*8joQ8z`6+!n_w&1vp1LAAzczTO?P_T5Q92;5W zgZ{qY*gQpftc+&_yW1un%esm%BQz|0TrX5#`|*vk&xh#YBh?n7BI;J!Yyt9qrZf|) zeMYukywiTQj2Og# zB+jG1Nuv+XpG4@DZBmvG%jnx5$OrypqmdjLsc|C5iEV?BQ4c5k`t(sUBV$2NL?c51 z98zWz02;dEErNckRHPWyj}~evG}TvB;;z92JP<3AT({)%UKmLZ^bt0d z4VOJVNtS^sQ}{^TXTxj|MRukLr1eB-A2xt#vwJ|?R$;n+qqF~bs4{ZBIx(7t6qG+J zrdz@YByduS3riT3R#k+xf!kq+BFw}{39g-LgvefJ%A@5IEONoEUONT(AO|ED!=jsX z-&RRR_0k_8W;>S7-uO?ve)4B@q5I;j9u2Ftg4_<<>3=sw*sF>^30oYL@oh-MQ~}Z# z)1zk8{HBpTr1MsUzKQ7w_S0TPWSp zX1N;1^IFCoJh!`OKK>bc4(gr3W+%JcwA@l}q;9tjaaDIKHp+#axb#0~k zUC2~=wByf!Fqj}1N1xc7vLA-M#R)j7(h=qn%vgP9G**0lRuE0O-J>QG>=_vm8P0Ul zgU?4!fM$h8F#U!?xIwrP*8P30x|FobvUhirGXvNiRlWU*g_E8O*kA`#(rc^D8MkDX z+x2{+V|mx~l^-71lE}jc=%1ouJQ+*<&j%QcRUvmpl!Ux83^Q(qF)1#Qz~rUYkNkz8 zJ>8%{)|O@!>7!l}n{gaKOiK0M0V|0isskb0O;}pbW}~5%-p}WvqF~n8A>~SM7I4#Y z+Yi@fRmw4Mob%SmW!2SOEiIk3NL67Nu4-+oU9zdSeHm`CH>C*AY5#?|qJul%S_DEL{s&e z)Rw73%^W}N^Mc0)yq~%VBYxR`3Ep#5Xr1~Yb;6~%W)e9ryQioZIM>YlyJbl32VFnq zA_6L@>`6BFs;)o%0}1OD47C`#a-gYn@37V5&hi(@(|FYpEJW$tayJJa#b;McWDN!A zW-!rG9O`5@tY*MC7BaCXb6TqRloeJ&e_e!sEy<1W^Nkn^fvO9xEl9}G0JO(wIBgiY zR2bzsnkf^W0P%a~qZZJj7ILbF$Epr)gpEUh;TW>XR-tEV4*bJpLEL0S`UKYij7Hse zfjfvGJA$GaO*ZFEiy=kQM&6f-R5po3#^RtTW$692CmOZ!iivLPP38=BIsxD_2q-*; z0m8s`gZ*DMKQf5(<)2`4#aqh6N2oI3x-`PgljY8WtnzMrrMDHqJ1dw2JS~;v00V8W3eDa3w2YzR zz&NDqCr&;mDOOqQh=N!+dJnuT-*}^cb9Y zPTmyLR#AHA2*&n6lU}@;XaY9u*KiIE_@OboKy^Bjj$A<+&a+2e(MsN7B3#4mBVA2) zmj@Pw$)s$}PQ+U=>FB4CCE(9<}-r=K&#yk0(Q&nEMH`DBFLDu>+W zugvqDKxW>EQFIoOflsV7dwd+6e+;nZtV)DHTkN9Fr&vJb00uDsP zI4Ue$6K+bFVvZF7M&PjQmzD7LO1q^rX_sn;Tyh&!bQYTHIbR%#ugpucj7NlE8X!uS zsrJ@H+tQc6Uo6ulEaUM6!q9PrgjJ!VHi@HD{BYQG18()VXYhV@u z&q-E|*1Va{5fg17I@Bj!Z2-?|*6?l+PNNA3mZOP+>ZL~OVE5`d$Z*3D?i%0f;bYzo zez-eW6p=d$5B<9_;v}!vv`NOl$w@OqAg_s7i(Ip)9#ix*-mDSUSOxJUjHxJy=mpgH z(8xUWeb;&=trj(+a(+c1up#S-X5-h3mhbWKF9@Qp9+IUZf>KRd9GN211oY$YZ!O+8 zsW80eZNv)!(CX-N-7$EFG^m~x2j80Xw-upF5y9CyRQ4XNF&s9rUi$2Ph~Mj09@iGj zu~r@f@ZEF2@St~*M3r_Tg!o~k3&QZ`h7Me z$@jhRTL3}y<~tkSGW=O!<&5k5hVR97HBFyfyFL?jlNAGj=vUCRs=EyS&|dK0+fYj? z^j9i$@*eGc;G4tOzH>oc{s~=Ym-Vb0t-Bo`ZqZZyAh<6E_WKxy3hD{pcvIEU6S>es zCfj`G{6Qw?4UQG~VyTo`yQ43t(Ub6FSQzfq?QNz0(b@51JzsCf*xUO8ra5rJ-R1fa&=;)8xXb#02kW#z%e)ir6 z_FK%4=nz5L4aY0;>(#g#5D6YoNc>3EixXy51p)?DLQ%tOljAl1O|X zBmoF$L6LYhfEQ5R#IzqyFB<|A6~e~JG~Q+Qsi2P(c9IYJP4lHih6P&LkmWg znKz6>XdbW|JpfXne~|FcXhO)z16#6(DbFy_0t{gnhIkc2a*cs^J&Ih1grK4msitYK zF=;B}-D0?3p9n(?%$Se)FplTcj(n{B#4ZB< zdgW2>I`o8b@Y@U8WWs9QE_YF5+j?^-E?Gj$Rmh`|p@PIQQ=ObH251Pz;R$@+$UL1f zg!wB2Sp|KUvyNL!vt!6_$5b~GPvl6}O2oU)_Kwam`1mK*w3fS2Sg34Y=tPFN+i1=7 z>#6mwm}}=^372wTmxoG3N5Z7t$XH{+d0UHx0NK$mF63QTpNbDYzmt;=(;<6xOd7O> z+YBc;yN%2ANW1A1|5zvKLxb@YA&YR*gLNWFVK}M?_D7f`1q--Db&}7=*HtDhZFD7P zgnVv@8_KR*qugi>1<=s%3m-zfirvZFkR&S&lB(-OzUz2i2$C)YoCS01a)MMaMBjv& zBpce~i@-xgFkDZ(U#WyjJp>n4mQayJGS-hf?rY3~!-nQxc(pe_;ajn|+7a=B5k+jl6} zPb#pZ*hz*w^dK}Jdd2jTyO=2G;TA3#!2#m72b-i6z@bJEeL+%5qDa%w09y}H9|Ark zteOgt@?X<4H6e7hn{+4LHQ%7TEtZ9z`bFGyabZcwo~#C5FKzNX{UUq=kHx^4@OJN5 zkwkF7RfS0|8%WnN>Hq-wUPOvT!J^qoiiF|Mj!CPf;UGb3)=6^t<gA`wvcH- z25EqVq(Vg1zb8Lm5PM9HumTBtfIef3h*Yg|7p#b@#o+lxB%v9=Pph8l)Zm7Xv;cA& zuaQXoNRcsx`~k9^r0C>Z_vxd(lZQ_~vylEgf|2b9gKIIQT}khLthIAmp_55a~VHgZIpJrLB_252-)H0B;m*%7WMv2E-P@e)f>`AV5nKt81_|nkn*3 zI4s)zJS*y)ivIWY<^DnPCCNr>U@F0N>Z=XS1AmR*(Y+fKVR+NW#Du(;FH|m*rp~8G zuRCwZgla*K**p9!KZ!N2qOjIi6lp!AYdSeiHdx@!-iEkMdu&TwYFc{h|<=2-O*f2agGVgeHctc6Q z;I#N2Z)E10DBI&pj~CH<%Gt`q^5=Eh%nn336`#BP7mS7ea+)>aX3K?wnao-yI^F*G za>y>e*>0(w?s!9ZxrGf=2=NvEUb)}+t)ofj0kh79*KsT?SLOYE^S@rZ6I)rjK}*dZ z6?3nD9VLald6p=9k^gtb!z^O8>XGXQf|US`{qGQmc<}Uf@Wt7orQ0228HXd}<)zwG z1HjIJ;lR7vkBBk4@KmYBwG3+DJUhzZ`Eb?}>p%zQ`Nu<5Yu2y1=DVD#B-csQucZhu zn=WFyz}QB;Nkw5g58TF`Kavs=Hn!uY$L%IC#c(tY*96+R^v|JIga#J#Giy`|${2Y7 z(F^@>ks+6D($RDu4swlM;kaEY_9>wvE zTY{-v5GQn;6+2)q6yuanr>LXG5+%l_9QNR+(0z*z%7=IAGctN~wfG{6kIO!%YLQD` z4`Z0PjYzVbd=kWrO=s;sRccOMQhqdlRzP9|_-h4wouwUSTGCv@l0r~ zpoJ>Yq9om-^-*YO7w>C%byPWvu^7`ix1UN0)$+wkF32+B4%lF`<~%9mahQVqTk8mN ze!K|h3o`Q0sGz{}TG2Bq!6iFzPn$#DVYsxKVFreNaLw3Po11XgJ~03)J5U&+V&I@aF8U z{V}*)+3vb&($gCHo9_4nJ|wRk@3bK){&|&ii*vDi6zxQp$QGLt-p@fL1d0 z^%SQV$g2mZdB&%cq`1_E_WHBGf|<&OE$6f4@v`Cui6;E^R@o;x56s-OZ2byOr->xv z08l_`BMVo&+7ri@NmpHW?lK(QdZ@6P8;&Wtq;AU%&+@M-awNlLB8y211?OR#6%9e} z(@k1V4u9-f+}w#E{qo~vB$QDL7X=o`A-4bi{guwTAItT$J%9|Sy5Wdz2Uo<0;xIB_ zE>$XGK{gnUJ4<-@9K~W4ic=BxIZS6Rk6vl0yN2KCe~d5pvunOh&z@0igJ6KWhd=H% z2&cacrWkIeq}GV`GF22SX~dS=dSm^o2%*oKFPkVO{*bzF0^-sFai@f47v59^X_@{NrJG;P^WB z9j96xG{Iy~bD>~`R;*9}BOj$b2F)i+;vk;MX!>ZUytpqYH4l$*%d-nGX-bvhar=kt);H^)3cn_K>u z=|Bo?B8WB>T!f*U)O_>H?Cby@d@Q9GeYc^YxpR;0&xl_5w^?=$ydLOF;|`A+axV-e z`+aFpl!|jvF?ZdL66+r>72n$IwP0RFDXSK0T0qiu%Sk)bR^PwcM~*a@N;9gX@Cozw zOFd@>!v|ldpW-%i#EB>Y>0Gd%+bz}i@OkAD=I)EaKD{30tx-%Knhc*+6z;*ns=2xJE>fyCsd0Pf25m?xZUHl##g@mewU1I?BtFI z%!kyyqZWHQSM;8_b$h0L@6(b$0dBloe+1J9D6V4S3F*a6DRp$_8*9li)9b+B4PVFr za?F7F;FCw}f(f)<(q(j$MGL*!pL2zo4M1X`K1LSWSP>UiJQ99d!1k^CGXgG~A2yK^ z%N7_u#`#4&g{;cWv*Qq2^gTh@#lfsNPgSeq6iGW1YSFpcP(c~Ho7<{6`-fNylJjX& z`WI~<%!%q(=DstY5AO{=nk3kJeoLO)WiuV_NAt>};RLZg<4Wfc`0;uee#_?xk7)1w z9a%@2h4u+%ljef6PDlA6x+%9K?;?D;Jq6MwOpMTJG1bJL@^TJt>{c%>b$`5ysLa%h zL9yaH1z)AVtPebxYz(P|Cpj2Wja9C#WD-39tjr@2xkY_sxBJ>Ml$^tl@`av#xMver zHVH`W6H?V`ZHh-P7gN`#SQLbXC;gFSf6UM$FoP2r+qS`?B^>ZPPGGxSG~@%m0Z@ih zbo{94YQ(DSeB#q~4fJB=JLEIH;2I8uWUL1lI1b~PM@8IA+@d|V_e_AvX0^?R9Qm@8 zj9IUd=1c|ejNjd_`%aXcx!EaScOAIdUg=^!`-hB0{@;7f{*#r%1)zL!Sgb?^~f^N1n>FDLlb9n0UI{oN0p z3oj$vu3A4Kgm>$8`&qM1LFB?vCgMhrjCmg;BDOZ!l>|~n|MQp3uZJ@1-W`>Xd-nKa z`~J$tI59Ps$i?~7nlnVj3gh_4Mgn58msJe>qR1qro{nb1+bAccb}ylM@3G=tJPhtS zxzJy4`HNbw95En}7V#Ri*^#R)!A8Uw?U_jy7SV3rq@2j;J z3Z34^ImrL@u>CKClER#9IOYvgL-lhMzc{GhF&_FvJthbVd4g`0F{HTgj28OX_we!~ zFXJ2WPWe8*KC*PMma?+QN?+}J4mmfHqHi5qEsfg5-8$OJ**_6)m%@mlJo)kRx}bVc z0_7VU6#;J*3pe=(#L5Zx1#qm0?b{elDOGz!RgQx)IRc}_t_C1PgC>kBHg>AvB?DCY z6`7w^-N(BfGnLhfYh7AY4ebbaA2+fp$8u!e6VC4nN7n%QZN^fSHik%^tpRmKSs$MU zS4uVBIc1Z~DtHm^z}Fa_^S+S&j^~k-JMjwWNI`6v&v107dg7@-)qMt@{GmtM(BWLt z#k_={CBwg()WKKkskck4-0D(|T<0Ry5W|tpaCLR-hDoWBc*CIst)AQiCAaZGCbk^1 za|(0f(L{lPykJVO6bb*LM&T8*;O_|7e8j;`Erk`Q&MEBFAo{`duy7`GMQ|ox!svpg z#%p4&Mv&$c-j|H~gedc|_I%>Jdjr+msRoz5%`2~4?8ZKT#$Wfpuw@J5u9fLE)KtmL zFZ4!XIqR96h9n|=iV0M>EB5hpueO4Mwe~c_3m`B`4ol9 z^ec1^cP6;-m;Ue9Q4Wo6qTWJh%uppk>08 zVT4vt)50PAx}1a-=Z*SuvFcVaVL+HKEk3jXFg*u9Jc~pfgS>bkk5OS^QeXpoKph?9 z-~1u9$A~mX#Q&R-#f6cz&IF;+bfJ1;OPWSN{-Y@lLgoEvLI7|SjHMBdVPb@`)5e4> zLQv=OKox#aPqd`T4AzDgdTZ{5S4D(My$^?XUYI>1HK_7C`=m<6DG$PAsF((-B)mL` zdENu^3m#Gzhk{BopCLQYoC`%g(N+ymq8_k?RfNQT)KjVVX6FzSqli*`AYs5HNgNtL zf%B}3Cfx-Lfqzzvf3&VNZ@0RXYZ9B`iJwzo+Q!N~3}iP@;2)0@I^#;f2RtG(~~qucL}<%N2lcs6n5|3TXi+ITV=H>#siF=Q|NBVQpua;Tg^2YDO`6HlH}-K%0GqSA5;fQTUBOtK zA(i#jCBSS z4{M*Uhln;5cw-~DX1-gcGfq2wXRT0}`XSF#bM8q3!XB7I51RFzjd+&f1Z>)L8m;4k zEAwXS;;j7g(}PWS8@a(aEkGz5WGC@-OH;f?@QE(_Z@7xlHmAe34#@@}zVlG`bHRH2 z^R`IE!EOHeZJOt{Qm|yHL1GKRV*NFyd%H`56SnFO1mOKG^GTZ!m7QnXc9E$ukM|of z4LhSw3;r`Z7R);|LOX`fZ7i9el;}&j&Em#KyEkb+|QL}Xk5l2Krc20y|`{NxB&kOfsv-b0$X#AXL znVEeNUq<`#INIY#kL(zW*a+4A=wC^KdN-*U?XR72ds&&=meDJ@>h#a6K!niEkcxfU zXL0udaPT5nR~RS!7$>-mDB~z$SsPRKoXyDg&Y$o*;Z=Z{6C~g`iWdF;5%u=&+i$OT z;~4e1?2Ec<)|?EzwsO%iW>ygq4S)gd_ZK82B&y$E$2AbVZXjZSnn^*VO(I-T;%aYQ zaY(kOg%+{I;G zCukd|PV2HLG)wX{*#VQg2$A84rCEfGBffX5mvDw3w%n`>e!uH?`7KO1MtA+7b8@$0 z&7ojXcVJkpN8TOv%_-O9C_FnX5PdYyoa9~mG%<(Kc=;jo|>rReOXXyqQGz<-(pn~&vQqg3*wUao_57i09#QM&t)mYC>s ziEm8KbtkVqf(;~n8KBp@9$1OkC!T(L(t9%RU7EHH&qTs{`n^A;aE z7F9TwfJhA@j^x$>Sd6!%2THcp8vDVZyN&{6JGgAydL0yCf7D2E|>y zIqI4Gx~2NGpl$E=s}_h;(@=9S5VEPAPP9ijC{7NVXYz4|Jq?D)-*#%gltZ~rT+f2Sl7Bxv+Dneb zdp^_Z8xwGhPgmu7EM)C@^E*Qr&20!q@;ud~`u&m3H-jg-UMSix=8vDFZ!N)RNA9wX zRA03eh-TRS@$+w}KkhHpUpYgmMBxBu|CzPk(E#HqQ?VKL_1izDBSetU#{==!+*LE`=-|2WHp$8Av|>-hN} zqRfD(xrnN@=&vt-{|TLfLLF22=^~c30?wZJzl28X@WkpsqXUNM*XjcF=}8QFgvq}8 zq3>K+GX-YA4+nwbMESpygLZ841b(#P;qY+ZhKtu>mVYM#)xt=Kq%0WrK?*y5#iW;C zd|eu+pg{)^=N_DX1Kbu(|5O&O-0T>3o>=yxnD!6!L)}5*Vae91ffObXpDIW-X<%mk z9>e?`SxvMc@-DvBRf^-qGsifa?5OafsMgoSIe!wdbd$lcZZT}Pqq+5HT;WKM^Pm~h zzv_jK;pe#6kP(mP*ISi)l^z6=RWY`3d;_WIK$Ek9=)X)OKUZVa1JC83=)2KZT}?l_ z9Q3=|hM;e+XCo*&Dz@fK^5W#kF&7zOaUSi~hOhGBn*TpM)JQ_A?)YeD*8W)Xe|e~E zgNgK#Ubh}nfPEZ4lFAP%va&Xr4D{z@TYDAwOcvpq)0mN9<()A>g6-5@qAy1 zS4@x(R=2t$@F|_G)QQ54(oo_vPGHk;IQ({|)nbR=nJ(!1TVSchp_N1|(&LM8SW&oj z6mLf5Ql!Bz`jxTPqAwrt@UXUGJvA(%l%VlbvW&C_tKneIpq6iBipBcHgskx3)Ve(k z5uHFng^Jj>xtd4K%uur;VsTrX7P1GDTt;)5pN@759{YI2y}2;3#YL;VQlMnUk}zEz z{7TG{zJW^W<-H4753YK?O8>0F=}mXW9gmw%wI7a$5`P%G4uZ}P*{AAxsx3d<0eJSm z_9@v0+u<*MLR0Fr8VL8cAuvP)zLMmDg*)&GQGR8A)@Ztt))#j;{{Cc*Wm)rGaKX2+ z-;6ucsVGslJf2PAz>S+8q5}iNB_94bFDzwZOE#7e|JUOwPP< zD;nq#G%_>YiIpvh+QdFI_pRpiv0|gd7r(9|2LKMxj2e-C9Pg{-$u8%#6uS1(8RXNp zhuawrVQ-1?LI`DeiW#dNse?R6t9e2aCCoPSK^q7ih1x}0Bwa{iZ`w=bv)tKAf=_X2 zLaQwzJ%GDU1ktM~8++v4X`W5Ky0=T3m|}ZQ!s=4~-{1J_>Bv5j-lc=KD6s^gdYsEZ z5_y~TOi6)h1U(1dQ*xJAHf2ujYu~0hrhD%8wC?1NZ5uCEzZdc~Rn04PDW2!3*TR2- zA+({!MIl2qL1$0RPM>q26lZNfkxafI20zKf2?;nq(x81$BCf^+ePLP|1f2qY|Wq>|3AL@2m#G1c_Gi;+CN_W7M z*KEYl%pYWb5qAC7kZTs385Z~z+;ov#Upan$M6?QFS0p^2j`@K1NAAa8iEpaHGmY_n_#g+I!ArSD*Wp7j&*J8V_J|>HufEm>vHx8BF-QFBVYi}{%Y;8 z>sn;UyvId+pTn!8%KVD_XSmIQEsI>y1HPXSWOyVIHGgpNzHb(C1$FF96ub`Wieb^> z(M2#0FU`+A>ML|QR#l?>q!5h==hW;$#O|x&1MvHi`}b+ZVuuL69>b_U!fmFVaEbfQ zCFpEY{G?>rzq66|G85Vn$J%afVw?tRu1b@iF{<>=H-f^nPY~abct8Ub%?#%ix0`## z-_Jg%f_s>%XHdkr+T2a#JB4r+7(Vpk?$^92j}n?X;Z}UpH49OD6B!+&MD>bVyqB3^Kw_#@i(~*P;(X$11>JY|1Pevsxrfw#-Ppu zvx$5L+G6fHkCth(Ro_~jA#&4Fl%l8+4JQE^J>hkf`Tn=clCTUXrdsuo@TXE8nP;JA zA`eq2BrTX;8B}~5&ear&_>|}!fT#X|i<0l5V!#mDYD0`%$8;>+(Swqa)3162cX5La z`a(g{=9@Bs%BOy z>t{NfOdy7rBDiwm$2^CONEf-U)8o6@=Jy?=V!n!l(fA;XFneex-*IT%cW``YYR=OFX#;tYO}wx}EE z6LI@4*VAkyuR|F%tLV=NT%n+4^e1ZIPrf=_oi#a_xU>Ophgyo^XY;2AFUvuPsytBg z_^0C%RY})ErjVv6XZY(Z2rCZDVrK6q{Yfp0^i!3kqNEVi!$fI+Rk3va)$5X7@hD7; z@LjINV9JvBZ372tGz`;sGOMWu@5chP&DCdYQoS1?eCkUGqG#g~G-p({Y?j#GFJwf6 z_gok8eSM3;g-tJ|sovEEg>lBw)Ro{6Dke8ER+%n!FSg}>Qulhfyh3V1)3M%<^PF3C zle1K%ChzcTau?B)3t1~)2R8J5o?{5st~~Y-zozARep-lCDTT=5>$F}vW}3V06LtX; zMabCm($I@jsDq!|w4|0*wT=lEYNlAM+^dRjZrLywy+H`NzU&+%+efH;RQDv& ziTud)nUni}(RPCid+@B2RI+~=(4IqR%vt!G}(t68&WU9=z;Zr-~wUeq(aLL=%?=F_3-&ca^?PHJ`H zlyxG=$kuxWnosmrkdZ}$DaRF9 z7D=4@UdINBcia;-bmFs6bJm~m$8}!_54|F`>XO31G2m4>{!6{qvHOk*YaApI$wFUn z33d4BR*wq7#yHIN5dm{Dc=!^IF{#;0&uSEASc9Q92yC2=&n&Cjj%n?3 zw9G=E%G6@$baDE3vtY!* zbXCS?7#XFy0#PESV30744myb|+)KgUPYXzk+(M89Q0}=2Nm!qh%>sVA38jbZ@$=}o z`GO*ujQ7(y{l84E(Tkl|OV0)STM>mHy0F<^OVjrE(XxO=oqMIm(d^{ld-|q4LjW?b zn*uxgXvUbS9ZFXFohrEyy*gKKQZR>HS$~tOJv5&)Lk%mZc@03LAh^xWtNohC;YHyOGTWoZ3aKR#-&N%f~-IIgRENXslyhuUna#$W3p=8@w-glz(o4__{_yM`vsVK>FGeo*V00zq-X_H4q=ZZ0Ald!1`8BROR&hu z70alx$ZA_i`*cg`7t1-a$jh*h<1JYLOWD)x<$pld{!OiT{86bV(|y9D!AZ4f-p&wF0tkYnpSZtI6pjf+ z21={V^hk;Qz-QH@6SB+}x6~qqirNIDsWwTG#Zti*Psi>*9kWvX_TFKb#c|6@x(Mhy z{w6oM>7)TT#cw)NlqfJfaCI$q-P(Lw&nz3dH1uYPCT9r+{dxohl3WJUUk1`e_6dQy zaT@!$plFiQV3E~NU<+v;`}e5UAPKKtcp_Lr<(X9E7G7200BiQkcq&_Mx+tFwI=| zo#siq6i8Lq>oZv;UC)M{Umavo z1x`#G`P2i_UJu41fQYV23s3iElCUxPyxm|iNv}^|g%46xGN@{qa7Mq(&<;0g?y~3w|{|FKw)vvZ{(%)v=QnbP96MArLr16(wa|c7h*i;5Hk>)uH#WD%u zu0_+HN<3$M4y5hI z_@Ms?@Ax@#X=^+eP(Z(3?~~k=Dz^I7B!a1)4y$VQ;Ntc<*w)r%&QkpBQ-!qn z5>Q9K7obDu;aTl8G$=Y!2HSacC$u!b@I??Zk#3oR~x`W2@OSNS(X`sTK zg$UubeeL*nW|moFJ%Z|1yp2ITdlfTnr5prB2Tq6h8ZKT4e{TH*xr zZhP3P65t4`*vqvhG0Jo^$?**LmWOGE@=KY2{Y-6#~Cx4JUkmH5e9jt5oJdZ!7 zx9%T2mu}VU|3%PyFU1^z?@A@=Og%+T4@qNEH`4a%mE@_uV^YYS9PcIUA|kjI)X|v= z>T*7dN^&?CssafLV%9KTx~k(NbdJpkt^}oQO36;;s^bB&dU#THe^#* zppn0!+O9Os2gnOWf*2B_{SvK96n#%U`F7a3D+hyegRB4wOL}-DE5DYVs);ndXakEhKi4ZvE!ERkGEiV<$61c9`|`T??RWa3B4O@=Bt8*oHvRA;@cb^6iuMU-D2i{Z+XJ?JJ$Wa;1u2 zn*3)rtN46kOmYUN(%Wt_(v32ePT>f5s=IqBG9mX`q4+PX^r3&CE$azK=ii0CTG7Yj6_&NS*~nk9A}MIn}dUF|&3z<7htLKR(y!*Gk~C zoE0?uE@;IVWpwv(aD0|;?U9@g0Y`Xf#|g>HH0ZzZz|oN*N~F{sbRX>}Q_c5y<#|#- z(jf0khsVz5#tvK%~hD)Q&Q3(xK3FZ3IJX~%e&>ZCu6 z!GB~P>WB&PAQKYx^>mr7=XwgAL4|mm%GjMW1blq;4Clfg2NG- z>3+`Xi4_Ww5M!@!JFoQgODQpTNuGy67x-%5ud)}L(yiOGh?no3x*K1(NKKP;CyQh_ ziM-6ePJ4E}uwJ{`b0#}vz?c!_y?7P$)u)`XsEW3|cEmIJ^o$Q?C==@@zR6x|uHf*L zJ>0mR5Z&*m9^!6|fx527OJsLw_K1=`_bq#oN511D(C8vFJy8dp^!M-v1J-G)56^zC}wrb%|u9nb>eq2ow(l*uqH za5?GAziAA4*oAZRt17O#gIJ)i(w#%E0n-4evuM zR~N-c8rIlr!~+Tg2hN%z+vMo6%8#93zxNt{_cb3hTsZSUgg9ClTC>ZgKJ2wf+#E?< z*+~ZcX{-)OLQRuAjFm(I@F$5T|M5`afsp}BRC1}2|K1i=nQpyPvSaDc!KWF#7N4V- z2{qSd4`URAM6XX@B7eVC&W35MOzZJ%kL8N{kya`&+e{P@A!(ksr~aHI7%7qs!!p5i z*9DwqSTe-Prv&aAGTkhO4#zqou ztkj?81E`hB#AkG)jeJsD7@=iP!U9Q-!VKgG z-2UwTMC-E2*;7q%s?z_?ADYaic%6iel}`TTZ36GzN#7ESvpIhrE5K%L zR9YcA<7$wV=Y<6`e&Y$tB_|G@`a!l&vc;Rq*#3Td{}Fv;p|%i z`OlIpI)kEaZeGXrnfoq-P0bvxAcRJtnKP0?-KC2w_flvuUzlEf z#iEk3tuQo!+FaK`h33c95e7j`QnQM|h4xB@!7APx;mj)Y)^${&)5ab(dy>iS_K0C9&Go=EA|nB9btRIFL0T2) zJha;qEUCLcWf{5x+|LbwQQH8T(`6A<2#R3p$Aw|VnMz#R3%#tQ;Lk@7n%{sIgjz^` zywE6$T^8AEMtoMu24N{l=_z458H{?Oi{7S6bu;XwcpmA3sazkbEBp%f>lZzgx}P(` zf_JM+`Yqy*+#B>n4AV7Z_lxi)m(L8JIkUlduJ8D)<2wz#ZlO<0UCXDBF)|2}eRTgx zzza`5wK?;Eclj@aiP-~ruaB6=JKhF7dVMU-81P{}lgt0IvVZ{x6yoglo=@dlO}_9M zvB-yrfN`oFD!n|NwAoB2lYEUHfomjg?imu^2sXaLhV`TuK5}ku_^x+;LG0Lhh{(KL z#^b(wnA3x^4BmANta#u?N4*Hrp=4P25iw%52ZCR_M(C0uO@ELWA%0p&D30o5Bua{u zoi>Hr*~qYRCqb_J> z0g}Iam0n7FHFnrSD$e~B|1W`=6nS}K7#8)XB0e%)F@og8Fo8`Zh9px#mOD8q&TW$! zNv)`;_B%0F7nhk$aY(9oj5u^?^8uP#Nh3Zv^_{>E_G5Sye=uHx2Z18UDv4Ty2TJzF z8=J@=Q@N%w8F9Ulj{$VylveEF{3=Y;No}$g;ToAEn`Y4asj=pA6Hk3s1NkY(RqV|) zvKK4O9(T3LI5SPfHkz~Ix>Kj(*)a1vN5b&3G^lloQ}R^TexTwX2X1oJc!P@b3Sm@r z0lO?Orcg2{5I~l>=};gpy)(+vnp)KKGw)0#5`Q6y`iEjD>9A6;EP9vB$R8lI--puJ z1A$LlH;Cjfv9@oo#`6VJ-E)L>dl3Ucl1uL#NCe-g_=;fAul&o4kgN*u^Q25^8w=>y zr~!^xn&&A;q(p(Y@*M;3iG1PAu$Li5&=Q>KqB#|68h8e1lqY+EN2}7)w&I1KZE93~ zS*gZ51FN)dl3}d@Jk7H`xn2F_uVInzfB00WxuWtO2@E|ASnVFidr{E`7O0lZw95qJ zYYJOnGw=dYkh~KDi9c@|@jr7aV85uVRkFGpd&dGc->T!(H`Uu^??b|}B;3-pkvT&u zPedq5Wrv&|b_yP#)qEvD-_mMZ1V2+We&V`NA$i2_?x>nsp&wP9T-qVdjW%$O8zl$3 zAWZ}BZAOe7RzGf|Rpfe8ZKpc~H<3CCt!g4FDCWb!fuf2p+^@L?mX(`k<7E|g8Jwg9 zud6OPpm{^Si$#y)6*7=_gAQKJ7bS3*z=ve4y{8bdX^`(lN0zRZk^Ap38TAI<#wuo-es2c& ziDFr=dt!5bw7O6KzzY)uZ}G@e47F96B+dGUcsKHbWRDB{3RU!}5+aBHV$~UI7nDq_ z%sQ36NCrNrY!&=z9rawPj$9VlUi)IA5vLx#p5xN=+nb7-K)i;| zYLjyJP34h}UEJq&VO7x6Qu*oU&Gm(Ef_LfWMeHJmLmS?ciE`{R{0~Xg zukG)1uq86L3>n%*I9*KUuzS!H!(EdSayD5XUwzidb7eOH5$md7jhI&dwtv2X&uZN^ zqH%zQIxQr)6lv{Mb#O?rp_SjF$aGqyGN@vEvOy!ypD@mqX=aYZecp0CQcgCGV$RS9CBLj1Hf@?|e> z{!3yL`_CMAI4vc%(?st@`G%&G@TSXGufgrSi@SLO{>}QcW$WdqK|l!klYpvmCz;U) zBm!k$Vh1KynD{SrL-cKNx99d;&ml?2dZgcd?-HiJHzLH+N(!-lH_-2yl)j)!4!j+s ztUV~Gz^EM@6df3s1MhXUkP9kYt_T_?hnvZln8_bU2IQDXfOQh zZoNs#Z~^Z6qbq;zwZO5zL~%oyVq4g^ea4}}&IPG&1c^6lPHVQr$BvJ{Uk<@9Yxi`e zY0A67$lBedYTulK-OZ<0atW}*rw@J~y5w=EQv^~{gpscdJrcny*B^faKf37;200~O z*gNAljNug{P1_H^yfwss5%`skFv-M&c%I%NPTXwl;w6BQZ-Y(~kB_{By15c>=I$18 zEpOvEKC%WMYhqUyLQ`Nu;9Gmyy}CQCejud|MLVy-znrGk#;b7hOQEqK=71UW{IZtV zc)b2E4-dEwPMHA5pTL6;kY^j6y$96!k66^|s6QW2w9Of_O%goPbGVY@gODIM$Q%wTvOH5Tt(o%h=WwO+8QR13&`K?3x z(L}MxjNso43-*L;JFvfNI0Q^oj%b7zhzc7_8_tSMbd?N8udfG+XcqAEqW$>_`I`U% zX@0)r8uCBE0?H@5YEz(&dWOLRTx{h1{(?P|hL4k^-4?HQ>|Z@_0|k0aA((>bp_|DILVoKwQ9U^U zjHtBOV8iZk1L#@9{!+rW*0a5psrIo+#+N6eIDBmILRygrlDO+wqdnxN9B#x+y&vQc{yyaq`|0D>mk-tgELDlhr{PnXIk0E@W;t}!*F*U@rNy-AW?L9aaCN|&YVf#T8;RP_aHF`}24OLSc%Wf<`~Q;Vax?fZ3V5nc&}TT zBrAr?8}9*It2FlYR0}ACb5D7!DS`k=cTmWt%Hi;N6HZ}?eqjOqAdqKp_x(S%Kf$uJ zRJUAC6I)Beu2Z2YHrY3;BVPUL=x}c2?%{NjCgJU|$Z{cf6v)7LH}GE1j!GjnDWv{z zCM`}$_ZCa+B3MS*&F~d5Uf?4#t#tA4X-1zXVb(f6)sI;mXHa=$d^XJjZ=&65*ZUY)#u!Wq_-0Ui(tYznuS1)<>GC;- z%3By=Vs07r5G{*8>Ph+m!0UBO=iSR%#`msxk}>6;(RJ5}17+TztY+L2^YsD%)Hio=3Xo6Ya_Q+`c>*O|C?XJ`NzUp zRmE9vc(mB2$lR#4umLPNn!;yQ=^tMee(X)*`d!!(U#ZI=(U!Ls9ZRg|(eUN% z#*t>|YKsx@E{djYRFAo~_8qN=s;S6cIS|Bx+_UkaC`-!I%PbMRwu+kbl4K#yUl8%Cm0WZ5%w^X2L<;LWVca#6s`TFViPYeR27R3lVr(s|Q4217 zTx-b;FI{;5h^EARFn+MoleOrINy=mY`t4bJJ=ry9@&bne4FhO#*WSy&s=8`~J7i-a z);&wj(<7hDw~3OvMl|c4;7z6VlPcuX80n5$Vo~vz9gut3^=h36 z@k8i18nWveQUVj4vV&Y-w0svKm07S9j?2@eGd@7M~rld4cB!W<`+EQpeFdRG~CiT(m;22s0>Ma9Wn6pO9b24 zkENLRWn(dsV?CugZaIU0#CS|bp{r{Ww?pMn+&6IXiF@KHuC;Ii(~`d?a0{b;5BnJwt@!!4GcxP;^ViN9L;8`a+nE|MZUYd32VSD3 z->|vgmqoFeAlMyu5OFFt=VCJ#C7z85^vk^L{D|(FUjz?Gbkj2lA^8@&=S35iefR6b zXogI-B{XjpI%3}me+-)IxLKN?5a&qdxVO5By%b0_w^l)1w4iajASt}qRsCGQ&~X%z z`0CM;C(U4oZ#8CXY3k2v-A0x-lKuch@705omfcIu^a+dP{k={`vm%1d)(gP@?ZwRo zPTt3N#A}L19GBMye|+3b7p#g4iTh2SW5j!XMRhpE>g`sxSXa1K)cXcIHvRJ0)$$yk z{q;M}eNIwJTAsaO`Jr(zclFA%f*4F*k7Srzqio0P43OB94eR^4-`^6v-j$f!Q$Tth zwD_`iqpjm7+UVCSI%Mb?Ni;x+3GShTwN5qtJ!n~(QvABt1m16P&gcW+aH~{i_%A21 z%~=WKLL;QfD&q>UcP#N66thPiyz+5n#khS(I@|ZUfbnuI&T#@ z@YiwvuJQgd`fVEU`^?C9geD`xC__*Z*FfyPe$Vs2MyC*lW30SWcalV!9|$~vsye9N z{Noih)6U|>`K;cFgLqyaP#$1B;JtXNTt7|v@vVmO8BQ?8aL|YEdN2C&K~Z6U6gh`}XXL*< zRG(WIU-8hLhbk@+tLw`2uR5s0ybFYZQ_*&zGm5|D9}o4uckp)9(`>!5)1S`<6iF@r z7!dlkla;FHYqmZK%ybS?uB2)Du$eW%p&M&vT3uY|++FF08i*JFDOA1G_HPf>Nv_pX zr}?)0qCh1}9iR4q-QDKy-tskocUO@8Xlp=3tEMuuyHp>9?|Pte#BVdf{Pkh+8Bu)f z3XLv6HM{6GkJ7=CPkwCw#-_VzIk}Q9+$K0Fd5Yjwwb#!4mcVp+Ws$Eo ziE&8FwOjnrv}#D`F}>_V)%4(B9;#`$FFJJAxAF61lgKCcbf3A%UxBdI(oP|&0Zh9x zOlmlq>8mz^3oyobUD;BkH2FEqB2kJ+Z!y8qduLJQ5%<+Ibz!b=x(IW&Ffu+>-ppsQ zkH1jOhPZoQ{fL|Up}QbyLlTvkWK;dwD%;V&_`a^fFg8=#={!!jhF?ySnVPZ6R#@)i zmoLfE9fP6}nYl=%w?)X~IjbBeHKmvD-YB&*E1O|!mlX66S{Ip{wq~R}{L{EzrW*Rq zVn;XDqpi%ShJj{JKCwQk>|Oi8@LpKkdjad$O7C|K%+z8hs5C$Sf?@?G!xuNT#4$~H z-zuxWMW;8-nBf;@rv6>9Yh910rEO)w+S4x?r@)>jzofU6%NJ9eOb}2K$-$mf|QQm)fadI1fmmj6S7{YJvC=c%Nz+rEX>RFBfDW@JpK+uO{% zE345*PgUJ#G<{E;drElzz{#>mip*&{{y zvAo_Z5zbjLVWeEWB^6VZ+4!mX=Xu$u*+P>IJ@llTjEY8yOVV3@o?BT@qub3AB-~Dv`ev=(kk>?6ZKPZor;&_7Ohe=|HZXU=Q!qji0_#a7|Eg1;ZHBXh4^ChIRCk-Rh#B=u(>_F)UFO^dfP_AJxy4C;6gr!c z$DFn-cqRn=#s2u%@(EPUYKHVRC)e^deKJ$ zTXpI09g&!QFp5)n&CoBBGIn8>EKWEqNIJ++iEWmIYCzrpZ;{DS?e=@3yIP~zYkbTS ze*0zvuCcV!*-i~)HKdi zDoe&Ja)qZMBI!p|!@P6MxY^}YpBStg_-fXg2{o7}mvV__FYa7BwqPJXxpc9W#@=S6 zR42H<-PMg)s*!MQYjEJ!bK+P&T~BBSYPod=GO%(5zgY)IPyB9=Mhy>86m8zyD~eWn z)@`I#yUWF+g_~3M5vGwNdQ3B?Y4?Cs5rhKw))+lo_)dViDE+p?DMU!H{-tiVOBcEF zQXY5h`hAiSeq*iwn-`0O{1+PFF{WVYSo6;1xp+LHO|@ztnYDF}IGPPA|E}TIKTJ)X zTW2+WwxiSZ+g`&fDZks~Mjm6&vQ)n!w1u=CO))di`zbYZrdVRFw!G6TXBd0nRz_fL z6h}2uVD60mxj2ArRm5m;?WM=p~4+qT#ZeEeT zs9;!=GY$dx_5LM+)Q5mOqhin=%eJy+K47cnea)9O9}!B<{L2VVU^Q4T^ew}71{U_b zdaP%wIh74!h&0}m*v+d55f0p4f7ZZZ)SF+V(@7wz+V3nTHW>t`2;RTg4Z>L=mm;d_rL)#^YZ=3t?UAgUT`m@rL9e zlGE{i)KUTQQ-ZswCr__b>+*4JdT|JR90v(2!Z*pF+eT^xk|tY*KhiZlaI5K9K8(NU z-19rsWrI@eei+)AT$~iFInQ*eK1qFzqI2aL_(*6L>B|BDc0V!Z0b^$j_haWDQ^0CE=*KTH?N>d7{-=0?FUoy=7 zx&BU!xoFA1IIj8lCrA==v-k1u)pyLbQvt?-u@E1#<%M$>(c<~9h!&4``w>2r1P9{` z2Aqj<`&Y<_dd+6K1>QE)i}Noq%Srv-s&-ZQXmd5TL`~Gh@ef#3q7VtdU32Mel0!qg!T5m6}$QEzOb((gvGOQRkhMJ6dk(E`zhY|(EO zqTks>m*_^b24Zkn1EUM)K+#?Se{f;bI1KWy zikI9xdy&@W|eVO3FemimdJw5~=SEdLe)^vC*g`Itg)oyG2Nq>BU zhbtZ0&XgoU`3Fhp5%G0F0;ZPuI`D4j_n(lL;S+dLEfE$E{NF7vQiULj$RL_0a5^s^ z-^(~kMaoqx;&>kD4+@CgcKo++C#1Jmq)zfOIFb!ht$5q~1>ZUMfmGwj5~9azP_TE&&(!86oJ zQo_yfA4+XaaSUmGqgVFkzIQTNs+X=tpz~_*cO)F(!I>>^{-kaXId&$oj)$1S)|`o{ zN?a(YGu{c4zS7PR!r^%~f3H$8!AS8if*p(w|utb=efW2{r85;prJu zknD4t?2xGJ&%($dZ}BqroQBUCOo}-@nJ=5&(Zf->5;9o=TRAg7bH96M#8Bt)>%J|oy+_oI#yBwqJZ|5=#xs)8}ql*+ol4*9) zC|e|jNO6I7ad=y?O1qBIa1lG6gql9`?p|}0&^vvfce*0E+R>(Fwj=|e(N^_w|M5^C zmb_9baknk;j4tsmFYz5N@!Ks4z$*=USQ?^K8fIG>xDe;ZYpbX9o?tltxot76l6g}Z zl7l2OJ-RHjyexaTEO)moAFsUdVfkC7@^`l7CDEAjvhwn~eZPNss0^w4q(VnNNzM>~ zz<+tD!xde-6(8{`TYVtSG?jN4>fmripHIcmaOIcXis9YLiHB9=536Q;DyMC$=J6`$ z%Bz;kE0%VvI)q^0fPizUn-9g$;p%|)>R)&@KG)U9N;U2xHD}Q^&OS9)?Ii+% ziJrXGwGV3{%C%T_wKy^V8t5IVEgr^hXDx1Cd-s#Nj@3r{c?w{!4t1ugrjMy;eGFxw ztwwOvGmq4^L`)X$gKbJ$gJ?bT1Kc<8uG<>8bu8#@{sZD$&DNgCyEFpWVZO-dcP?V61`G57RF8lJrI2483bmQ-+6Msh}L6Sapj#bUd8H z5JG$Kdz~qhRX(T1e$FBQu)06z5ex&);M2P^lREEQ93a1CI7JNp=Jn^y&d<5_@O--A zH=g&?)4e)=iIA+7t%3KbT&?C zw@UNJuFLBfyE~ESPz)$8AUZ=4EGSdn^P4#80M^Bbe-_|7m#G%26Jf_;@1Y{nDTg6J zM6D)pMg;z5_lQgZkr0r{^_l>e5ckNWkAo1n+c|6EoDwjE3&l+V&M?|54B<{UzV&({ zL?eh&VL--V8UUuCymy}JRBlNi!A>B2E|JV;2A(;?`D@Z3ZW=h6xwC=42jT#Tq2gLX zC@9bt03=o6Xz^)#ziD2=StapV_djD;b@+0#vna0VE-9QA9vpFJoV`RmZxY81ZO83z z)V)VA*+A@`qrvK)R}$Ma57dcT#<3ss;DpjsS?2V4qjBD;!wzq84+C+O0fJ3bq8smG z6X8cD6hQJUgcU#p7cjCYfG_ke&0sROpU@gD%7KSBiVY{VFVh?fhrG!DCbF$^Gx zzKZ`7>#WkC9R9L2Mz}nwy8JC}d4YZ^KahA8h2wxCSRKcBPwj*|+feQ{%*(o@~7%_f(zUOK8^ zF<@8y1Ct3cK@??_Dttq~x-As869|(Zhy7ZGLF%v<6BByj1U)D?69BzeMQE6T*V)~@ zCcXjita~K=c(L-sSk2q4n%Kf|YanB*yLJnJ<6+<%cgyrfy${a4=B}}AaPY&Vdi%Bi zRsh4!$Xx7KsyLuv=kJ#t{evAZhAnfWEx;Lrvu^TXl-3}#nosd*Ks=`Z@b8G z>z)5Dw**|S`|jWY?jo_hsfjn_M`^je{_-)c`!kzhNV%;B zFDy7<>OMFyf*(l?%{35d>&yVoGafyMkhMcB&=D|xfP+55zN*3doQV7J=qCPvIA9Az z4Ak=+UUw%90DxE3ET((*yTs778YN-=0i5_ZQ%wTPN8AxDDdzudPzP@3nyyz>QwHy2V*)3oer~P$!|xRkrd6u`s>OwZ z@YbE-s9NGMBRDCFczq4Rg^OF`>A0=}?@<5hW_oT@bB^6}?kE}QB01Vd;OtQ2eQ=br zD?#Ze34i(VJo2e;Xh2GFM~ZmaB?Oe}xpoNvSAhwaeB;S-N5nY@_|oWn7C>wra{(#5 z$O$-4z+7OFTmpz|F1_m%J?LH_9`?jFaCGh9ikG?D1@J&NfKgB0(}%jJ)oA=5hzeJx z*#4b;?;v7DNq9rxpWKNZ&%9qp9cPAL@r?s0wLSoWMhA-__&cbcux_F*Vj$dP$V;8* z0}osrz~I@LKpX*rU)}Sq_;8F0063d7JVa)nP9W#T*Q6s!Sk+h}@pE%&!{!Q^Y+!1{ zVn1G!?1OCM2p@MZ^dK%PvT2#SKX3sEsoZL&h^?1Jb5q+-W2gjOp{peS@le_O8LE)7 zZe7_LCst#*l1+~8R010V@r=^(p_d78G;}$glU6|D z(QZLtrFUe~8|HEEkrgLNID9AxDUEm{ol^~t6MP(6aL9=^>=sJ!e}cbEI9UdQUzdD6 z`{;KKFa2gerroFd)5b||u*{Urxr6!!YkY$-D}2xbw?;W4#CL}~H!jm&?D%}$U+f4Vmi+MA@^sp~21#P?QbKQR zV`CF#zK`BcxnUbl5IuzLCWxJY4Qj-Lw_3O8J)>Wm_h2)|Iv3$yG^mRaFuRV0o9viA zcmw@MP$gqks*^g>y{)PIDtBc)gdC|$lDKizO6C~x%5?Y~S(_PF09FarECN|6;zV*B z^RFv2*H3(k^3`r z2#jBrkO|lWt7M)BPu3}2AMTK9>%D9;1(}SanI{jao_pw7WxJp2*}U~TCt->rPbGVG z&|}pvRYA|EC?hLA9q+h*75+flQ>A(2qWlw9AV@)DkiqOpXT2elOIy!kz-r>TaUg`k z%On_I=+Y#VOxw#eoYv#gG?F>Z%Pg9s`O++w|C^V2yy*F*d7?Chw?(qD(3M5%Gi`6n zv=<&%mKo-0-d0(5%~w`AufBO(=lPyrSr>#*_}CQ12wmG0r)c}Ue4p)c{j&6J^}KLd zMf0_7WkbAossmjz8eG*!;cH(%5}sk#Fs1G5(7brR3Q!*^i=f3w)3i&|`9`}yB>=pu ztvuJG*OB^6zfSDFOUIWz$VSW!$>o`V<2Gr1yS=9zM)_x7pA<@8g~u~6)D3>8JyK+a z$&3d%#retLu9Nt5vknDowNn#J_hGJHN7~i14-g9W7lswcOtQ1Q^`KjO?Y))lDPf7b zPYht>w{tVOV}GHgj7f25;GE(6tIcdNx8f8V*NZ=O7Fz`daniZHzMXz zp5gD09voWWcAdf_Btb}K0xq_?p-4#0h;|*s4(?xL3=0Ysy(2rZp6^!lZ-Z^|v(B zJ2qJXp`LICfpz+KJC?k0-YQJPO!VjQ2sYbL6&txJn>*O<|AHPp07ZZSdI^fa+`az( z{hvdR7yoO}<9{iSKmSo44-PPgQ^!aDAdmkjkGs47xAORN4YU2>f2chE{(mZu-&a=t zw?vR+JQ{eKaU zx1phbz19EMh{rPr$17{YQ)81$eYq3OXP2syCvx%^D8W!i$2;ZG>E+8i=<)8S{J)_` zBO@aN0|R}1eH|SgEiElgP0fE>kIKr*3JMB$)}ySf?49+9LZSX&*5ft@=iQZyVqQme0T>v-YJhPEG+*GJ<`$9(bCdVQBnO{c_bqvyMrF#aQL0`Nc8_3 zdSt&_4*&qe03aBhLTy1$2#n<0R52~+pm<#_6J?htX6Oba49~ut-13jw0RmxRr`Y-6Q z#-uNrUfF{qiW)1j{EzTPew--&x8d9l;9#jkdT-#<$VJJ@hd`3QgetnLtG%Jb%m)=- zyn)U9bjn0a=lMTIGWhLQM%x;;zZOWxFsQaS{+ud(R$=s|z3Ct5u_j(@-g>dc*Y3MR zWj5R4iuW&Y`i*a^@!EhN^HYY#C#FNAZ)sVMo#f{C<{Iq2k9Boi9Ip1IU>uaCuFYFU zzC3WNUU9xY$DZ#?ugUZOb8&>TFo-W6@cV8Qdi8rCl)`2;2zI}eHV~}jN$U?epv(;= zliFbn`)ry~7Kd(L;UY6KZV^k-P4z1+&Qd4H$R zNSE^VXE_hBKgi-E0D#o?HNEV-9vN(x(!o(bgR!KvZOh{5 zJI8z8<>=c6;Y$rUKPU)F)?bUk!fVec5393<7sk?HHf<^!zuE3pZGFL`D~7?=f`hP9 z6Sad1m{x7g-t&2KnvC#e+b4f5$J(oEU$_0$G-p+z-PDfO4}wzw9F;*7Fb#A=tgI+q zyI0*}b$eHxXjRpct=(bQr6z5G_evJWK`qqZm%Hnc*C*GTL*)p2|U2vuS_NJ zWrD|GxN+(e>c%#16|Zo%PN$e>RTHOUH8F8#cYj+QOTSILv}c&Z$yL=|K(+b7m+)4& zQa4c=Mr|uU2UPXk7p}Q3w+nC%yzeh}Lx_c5!Q2R}8Uaf$w^oyH3S)r4?|9_e_>?kE zZ0g1srwka;!@e_`@`V=WUZf`0oC+2I;>p%k#eb1+pxH8zPvM*1b}NM!7eS2v7t5}B zRojInHU9qxQ}^Lc^&kHM|18e2kG(ne-g_S$TUL@;_9kSn&M^-nWG8!N?+A5lNjfBi zj4~rxm88ynzQ5n^zOVa#cz>?zbG=^A*YokFY)N~P2AQ2eLkr-zX+n9a<*uyI*lT!)rHN@3FSCja-^djF7mLo{#o?@b*;Qaz z4%#Z|wsg)>71 zH6c4ydMD@69R}y39$~Z^+win)P<3Aa$qpzT_~?%F2nqh8R?Orhh9|ZHT<(Zgo-~>b zDLF6QH?3D4Co{8XJ%4)guwG?Vga|#-KfM^N*ZfgTco*!-L-L1GSaVbaAF+aqT@K;r zW1hx~Rlb9r;V0Gh5pdI)VOT11QVO1+F{A#O8qt!-cE=)tuE?20_{KBi+tc#}RSOV- z%x9)1h{;?~7pcG$MBUY%{N7k7^RO_6@1i3`o<)HQDLicXz#<{Sowu(0#D@%RZ$(cG z&u-XGvevOJ6c=2O_%?tICyf_7OMWza-)OR5nqKUE@uMXuv&oUz_Woj`hjq~~*@*}} z_GyADm#n;XiO?gwk_Mz{0Tx;0F-lNwheGGvt&|UpEYfrHR%e<$iGATVOm0ja*OTI$ zr&$iWXT=}Ik??<~DYMf#`OC-vd8d9rC?Ti{&HgR6CGR<@WU~RE{ENIz2-k_(ge)4GH+atff8D4&v9D85uE$^S<>CQSj^)h(fPi=(ticrtmSqP$|P4wZuNn1zjG|!nn6zm~f?X`ZRV-w;>)E#T62o@lR%e|g`0FeFSa`I?X zt@XERAdr|~)|@}3;N#e)Kg2>MOOL8L&{N$6444S|?Kb4TaH~3kRki-y(<`MbHlgfqGp;BxgRnFd0WxLmm zOs7~b80OfWl6m3onqm_;fv539Bi`ylntSw1D@+W((1lVfEUJ5Dgsi!7j%Sa$WzSK^ zU`H9Q*z+n?Y!GDiU+1zVYq)dH)8hwuby%ons+2PkqK1jA)bO6pyZT2xgIUNluI!d4 zDTg(;VtlgJDPWCrk7NL9^C;Tz$`UGZ55rN4H)avzQ=G?ke9?|QcjWt?$bV1x5M#bH zp$MRxqw!_gT=hLJeM%uf=F_0_2{y?*P`w}MJ?bzA9#DEIP}Ux6KKq$@=7r5u4U?1cc2pPd#CEV?4sTYm#%D-YoTv*)UBeh*A)lCDfip^8BSk6vHNU}V< z@~rBRVt+Ka|ABKEcd=V^D$A?Vx8_WR#zB3%ns@tK;5<~fS^gg0WRI$wbNEuI<+yS- z+q+V!`J;MR5BPo`D%xIlkp0DXi$oPDUlR;&{}Z?Ds^mWUHtTa;{nOphjj+{&UV!mA zm?Z68QQdd0NQq}UY`K>MyIo1YDukU>o!35obc>JdZF4&PcpN4x$Z_)NN?1?lb z^BBgkmw0!r(9l8U-cA`#O|y583Mpi-c_p~)_%_24whyj{`pfR*zq0~wnkKI}Y@nW( z2OrZw$EzN$pU`S)5We0hSBk%#2%LGR`XuM2uzBLu)rq;q&v$->7lK0Jg&%{z1r`o` z`f(gFET=wxU!7E&{38Esk6@+A<623jd6TiYhvL?&Bdkz`wXl|uUN?)u&}`u_6pd+zYH z3N*kO9XE_NpbN7~jl9w2GFOpIqb#Qfi(_sOE^rPqT~6(%i<6^IAaasPw%C+NEVc-n zgatZ5^qdIZCO(xW;2a8e64OzX=^y|wx}aJLp#IO3M0%*O#0M$g*YHL#z^Ote6LTX{ zX~9^#1n~R`CGTcxuQ!KTB)m-yo4%a!vJaan40mF=3)pniy$QPlKs4JQYQn()+(W4o zmOt5~0TncJ%IV`?vDC}=$v~v4OA+qxQ!m)w-^gz7d8;k5GU(&_E8FnLK&FCzK1D3D0 z@Ny-N!w+`^ywx;*s$U4ef92mLGLxjIu>E%G3`Dl7a?+M}I;kwkla!3|H_y9Y=~09R zVd3_OP1_vJkIc*mu{_>x%5`o(FLS`BZrY0Odf{*ZXBy|e6bZZ3waeUp!}k`^AHV?^0Zx=A8AfWBR)A-mVYm8Q^L`OZPhi*Z< z3WH}9m#$GHr(FImpL|lE!pIKrnkQNMZ^=g=^X=)1=C=Uv5LD(Tg(WJ=Dk71I{h=Gs z*c7tIl1BNzWytBZG5fSv! zqh&AKWvMv5lZ4Ii$&3-aS0%E-F0#rf-NC0MEehdUao<$B^e$7e((ml4VqpjY;N^rb z-Thr!Ud-L^!!-~kx@uVRI~dT=Px(<5QKJ@-DK9;5o5ZXMyt{xyG%^fBr5rS3)!t=TqC4ekqaw zTVydsS6=n2ID!GWIwDW4s%G~cM%YGRsXrD@aG8mJfa|oU|bMVQo;AN z{zT>3ZU=a{nEY6~Zn3To+bH2US(vF>@QA!F;Mub$qE)c3+#Z0Wo7vBh)7q@dmx}bf zip=aQj*b^KQ;ot-LH>k^=KcNV6ys+(sx2?s%F!p8%PUP0JjJDxH4d(Tpk9*Cs;y_! z%-Ls6%$|+Dz^d^QZngH{SBtF!E7^X&Qe}(fzkD;ceOsxf+Wv}mWYGdVojrH=8$YJE zKlPO|m(F0rw^Ki9YiFxwr)Xgi^AX8l5ywIQT2L`Ib{wlRpQH=q5sJCN*-5;IsWdUI zaP|%%_L^NDQg&!9X+~@N*KFDUK_k~INWbWJ-k45Rdy}Lg*0OWeC9Kw!r42;m0*oWO z?V4Izy+J!c6#m)ZIHsOYFN6gmLT(Kt-KOYz>PjNU~FHiT2tzwJF(=Crz|4 zR5!4)KR;1=?hx}lQmr@q4F@C}I{dml{;Y9>3@y) zw4b!@YLhnfM|Z3awx_dJTEH*SRA3p3mBaiAzo>aad-IrIT;1W|L%)}Mhh@7&sSQ^# z)<4L4TeJHKL+}4`kvU}hCj$&!g`BD{^>4o%eBI;5)ROUr!)3E`5fJs>1UDb@ctE-j z0H^q*R=n{<;GQ6r4FK0Ig!_7kI~;jRRr(TJ35aSBu2vf{{6oCACH;Lurb$dp1i`LN zWR53?pX?3On+$;|M}B&8wPbVzzaE`D%nsY6`U#*ea~P$6jG1Z2C{u>3I^s}+qqmwn z=V$>Qo1F{DhVM@X%bvGjAuk>#B<(Sc$19E79*t^IPB21WNyI!mJNOYw_ zQz!1$Pw-H_daFGdCO(zl^kRsIG!_@2L%1BjeT|C{cV%uCAZA=*IdE4-s&$E~AWL93 zp89N)LK+>DB;LjEKkly{JU0wPBbp)7lj!S|*8X_O(W?CBkZWijg zq)e!GY-m~?tsR`0sC+&g)zW%2A@_5t{7{z8?oF?0=M5C-5(xu!*!x$+jdHYSUQf=N zGLU9NV{xr-Ic6!LZ%s{Q)I_N68NdCyYX}1v=~^TZk;o@-yC(}q@AaHO`Hlbyrx67_ zPykOFU{16iPrLEpA#g0-udUsT`YoQ}@4GnTM`@rmkx6l0G`02xU>p5p9GuIYJ2@05049G!a@y=5` z+oul3n@#gLh|!S$<}Hd#O2F08+cwHK^$(}Nn1;Q^Ots)?Vy+9~GM6Weqx5cwO%wn3 zCtUl`Z&ykm5%6y>3YXJcW&>tEqNz93{ zSK^>&7(>9rw1T^y3R2~;zx`$RRmP7pU~8cicv3i2db=o<9c{oH}?@4^rt&Mw~1=YZ7;5%7(Dt z(&Az5G{Kl#;9-ib4p6+HlLBE@o<%xoeN=@U;d<$|eoCTQvUr*!ypSA#f&Z7#M?tKEu=KtL?QgN53+i{@G`T0}UL7+AUKkKQ#RUVRanMLS&3L8~v(`TD6sQ;UL$8ABg#`ov z2Q3Ft7Rkd)vZ+0YNF;K!J_wyN0tYyguS>%R@Vh-K7Y=lT^A%g#uM9s0o+d~xH^&z~ z2F`g}EbnqowYH9=mT+L{K_Br{8fYyUB)>LMh(th8L?IF(8r)7(aRT;{rrd!`ss@s4 zXOn5IpD%HV5knSHZNEa_eR@#tvZ4Mb)jT#41yG|Ro&E4Qh5OH*_I?CLS@|(5h#C-r zruuH7QA7nuX{S1Cr^dk{;5(bpvdy+Ofq$!4>D|AE2%mnv;ymU)Vrh8-ZNSrraJ;(t zV1@m!?ECuR6@t@})J)I4Kj(L+QkpM}xLF)ZA&szo&PT+dDRT2a=n+(OdT&BIg^E)% ziN(@&7*5bJ9V@c@qMrqjG#Xg2+%_aak7cN0s~zJ4VX-^@2hx?qk*8~xqs6)BWT|3A z$kA{52D3`m#7_5N1DdM%_be;|_MxBW3dop^$D>a?Y+5;64BdWqAKG?$ye-pH3l>`{ zwtP=rbH#*oB>o<*=w&R`uxPqC{?M(pZ2LGY*fRa8pGjr~G+h&A$6ohwZ$uo{iwc9f=Nc#Yx~@~>7Rk?Lve+J;tE~v^Ntzp zsc}D*7k5}jPk3~nZ8T-R&9Hwb{6}eWbJgv0_D|EKh_juytH+X|k?u!Ys{`g{%KyCH z3e#L}Rae_-p+4+AiZkc^Hk%==0WuHKEBQz5-mVROARAQwL-9{r6X4zp={icg6?_Hf zrSxb95edY-x;k#Or~z`z3+pf`rK8wv?$mVXvkQdC)REC1TGVpInbP*t8&HJsg0D8+ zpf&(@->Ie2hc_zO$)ds@oo}E`?mmUf zA5CsnGX_B3n=en+*z<_CIQDOzh=EG?3U7tum|R?+aPdwK)q~a*_IM{3wB5 z+pbuJBkr5@wKtcV?<6xWJzeClmZE+7;)9(+Eu)38WX=bAMjvsRUdQ_xpu!rRw1uCl zfikhTMJ(5v|36 zmwrw_O5r}%>|e-kkruhQXMK6NutyeQF;3R2DT3>~W^W3IE{R95UwxGx>aqGNQVuf* zH!OLw1G>I7+j()BC?0%n?_f#;XwnzEd;U@v?&>+gAUgifMgB~{6WCi9P z&DtC{n;0iNl7$)8aT^L2st0ktE}K7P6L_5&{DE0y-ltF}rY$ zEPgQcyHi-n^6KCLcN%~{0^L6^*&{Ioh;zHmW15gxR=tq7y$_aqLV$6UgIwD@a@6h`+CB)=vRAk`^~r&rcA zJyWmPiK1jf0`Kb)Vf|k`7W|LCng9y6RAiYt_;0FPFtTr>o%LKYBKWg8sLu3wIPnkT z9l4*o>tQ4x3WEdGKX1w|H%Y!Ub>ta#;~%Ovc+85=)ZzF-|HgYP(^`xYaB1>hKI(N2 zPUcZ2QSQU>G8y%TDCP0PxXTq#q`7nt(XmrQXFD?4dNPk0Aa|(rE_EAdaWYOp9FVCR8$$CrvhsWy>_E~wm!>pchQM_Qx6Bd~UqJXmovnzs>ZfFL z-dy=)&A6#W01hS8%h2#T;Ta8UJ?KloL7h3Hv6)1aHN90&qu^5*^ydT!e6)9;u6lno zciOPHHPbvk!Pnl6_d|9FeN$kZpAp|#sVoF7@?MzM)~SRuL$IaU;!n9f$pBrij$DaL z*xsFcinK#JLIA?k!$J^MMovcYnL3F;HY{PhWH_8jnOk7Ndh6FiB9qUg{!kyjML8^;3WbC`v>(GwitE>>#0=o6 z?khL{nj?JA^<`UM3`F5}cuu0&&Wl)X_d82nrm}}~WTfrqxpI<9hc(4~N^zf!RwfPw zxA~={&GpjTc6hVPQ=a^@Q5hyVAJ$55{}R^zg}r7Ur%lY+>riZQYxU_uncBVel~(2+ zrG(Z9XdLK8Am;KWLhBU%dYgzvzb_{Zt5M_hwJMBWsMYVOGr!?Oz8MImu+YO>wR|;s zx3XB(`lE#}0IYm7cz6%=P7dVj^|P)CFpQf(O3Og`I6$1QlnsT&9k&eDhF6v*!h3uE zgC18`H%KG;#x(-}D`nr)k9hH6C@?(Lfyj`KA{Z*!^txBqe@*-v;+{KH{w78JSKotDI(M7+_#{{@3?aXpJI2!x}aQaKLpvO#SMI&_B(~Lh3)9 zM@rsgR1bh6T8}~>x-l#45B*kr7dITe@$;Sazq4~fc8Aa_9=-39e$p}@_~icnhVme~ z;o0bfqC_2w1Qi_V{Y&(lGo@q~QEw#h>ZaJA>X$NNI2wN0RilAdMJk|+mX6|H3vVnP zI@O>8HckF1y5=fsSW&`Cs0l7 z=O6w+@#4?utLuKw$*-kH&qglXuzyd{;rJv0N(93cU48UOR=N({U4tNs(#oBe1i^EB zrFFZ$j3lxY-HZgYdndZurZU4v0jf=M&BNr)4Wl=8IoF2iA2wajV_H8mbL5S@_WOU) zM~gl!`Enc`N|=8vRR*Q^aLj@CWu+Ka$-T;lrB`uA+vvK$T)mJwHwAHo@-Wu5R7as4 zN1ywOb55c2uNv)EUZpgM$7g5($;a%)>m5wToH%q`7&sQ_00*`yNtiLmP(Aj9;hrs& zN4K7BXp4ovz7zkX$XMeYYhbh$hj;U+hOGV#d2YK>-Ftcbp2Rv%{_$`Q0Zc^`0MUOt zyCK$JuR~NSNS&FrX41WLGGtIc*58oNSDXp|G#(8iq_`WzB@8HksbmouP8zIEmY=kY zoeHK@eet<89zT*DYPd9Qcz1Q8C+)?pizx|^5hiv*V!_}V2x$4tURRM4H8_PC94a_^ zUg-E_toXHI~|l3 zVrn{m-5JS-xh>qE?`R6P4Kb6LuH+P*1*n?QU%YL1G`kh0qyf*FqSTbZjG1r1o6|~d@+`T=gqrcdFC5A88oNhisF>@9J9Z%d>@iz zff`epApCZ)`OWSdFufa<%5<8z#Gy3{s&9f9N0owu7L>IXOJr()#q{Wg-jrM56+%YV zFJ}IVr<+|uCH*jVu+(VfR67I)WBb48V~QLL7Py%d)IMg;f>l~hiD5~_XOu8X6jGqd z7(7ZTJ-V3xT1nqZ6I(0vS)OOvu^{xWr70j%12;Q)Pm)#lG0L#iJ8-PjAPEAIaK{i@ zP81*86FDrvDsU`EQR+=N=mtKu%nw`NmGkY(eDA5%61#rNz7~Q0ecn{55qu8(ww{iW zoCcPvtV}8?hSm9xdju$)F!5bNxd8y4DJYp3?B-<(W;5BPZyx9V8OEAE`J(b`e1Qt;s#lWEEEHKr})R%nN>8|#0Cw9Z++x28Ng69k7<4gIQujBWj zCJojm0hX!46P{1m!uC}Y6mCC%P3m$&MlqG*XbUD`H4YE`@01Of;>u!+ ziG+kjN&?X6DB^h=JUN!-KkHFPVhMv>a>}gPxQ}lN;D}OC@03_I)%)0*iH-UAh{!!o zX<$vlEYDWbXoM5+5}*KlvIYgvUpWQI4!dEPDsBvjQicGs6O-t%a?bWQPf{?;Bu)X= zgh>hJTo1>^(@&tUrZG2eKDf1*he$M9ek!oJHv4IXvdb#>%V1+w)CMmviI$Hd6>j?9m5-)l-Emu+bX$z{Gs*0hW=e_k%_l}?U%103KWn_b zo#L_0n7*)|Y7B6*2z0lI-_F6yTsV8U&I!M?-T_|i*ph!{m-uWl;hyCTK#_8&F1io6 zFXj^6N4)GCVNc7-E*EM>h4sn&fURvtvfL)ptrt7qT&^69Y1%|W5teGkvSImp*W!1* zR}dgjvph;sSij6ohsi^1mt4ZI%c$LDI+=J0<&hW(G$YcFFj5_hTZH@bdq^_RSW{23Zkg+_XGf_Xo9Kk_FN|fod3YlFm>LEr`5@4cMxEEv?X5Aq@5APk8@`nVLkm=< znA7=Wl{s2Skg;t3kNAjA)Voai5l3P0EmzpKw&-VWu|D48pHKM&tZp;ar~(b1*omk1 zc*jYm10#*yB)uVw!R!NLvnlF!b47Fo8&bB@y#KrQ!u%ilNWv1i)*9{}PwFo{3XHZ- zIs4)p`f@3ki!8DsSwR{`0Z8r%KR^zf_ATmXR>-iAcHF5;zK;bf;8NVrRbMUc;Pm}- zywS61q=#D@?={yq_{j<;Ja2lkGk58~$r8!I$r2>^fUyV&2A1%k&-t@LK%%Di(k`sx z8R=i&Zx8-?>KX52mZ4f4Fy`gdDQ7=PJ64}5(Aq!2oVQ&Xx_w(x&7>FvEI^thEI=7`E}yTfP~aA1 zeE$Sm-VG}ZawJ-huYhfKq~*i%`U$`UO&Gx9%2&)(t%PZU@2I3ZEr078IRBz?|;x^$bEK*=YFa;I*UK`Ot>&4WcB&} z|GJNT|KmQg1f~_7_GnA_ShNw?Cr>l``b+7tr(Cde{S&yfJPC8K1>dPk+kG{fQMN14hboNCEF^*?^H==dFF)o6!@cmri*O7e zA(Vvcc7cbxndc8lGD1aVimwP5Xz|0vOQ<5y1moK(&UX2M5)%hYxeJdXx{vFeoXK9s zKYz~t*u|bwLNqtoJ59no>+j_vfHX{4rpVC8Q-M-*=(k@lnb)9q`jV^KNX$2flBAAf z%I}2>VJV@MhO~)adL#4WerCZ_Oc7X9I4PRBfkUUMB0@C-kbH+J%PsKIv^Ba(DsAC7 z)!ncvyCABr{A<%5HXII0fF*>VT!rXZc5wfJw*x-3U~V9+$+Tng&An1?Ut>=u>-vCe zMj#roaLdWdtRg5M0!Bn1UkcSnkX(O@By+`I(OIP4Z-BPkj&>=JDv7wNJd>1=mLsXS zUW)knfRlLWT0}xrA4eP>mMzh9QO6m0L5b+2!F~!zIO&Z;T-fbDi}kv@fF+?9I3MMbw(=T>hk`-#1#eDo5rM)+K~{ zrO~5UMrI-fi*Aa4YX%n{6`Hv@f+bOHU9}Ui%ZI_@u28UH&jg>FU3YwqR%#bJz23JD z$pk!1y5#_JhH`5$$i6Xqxu`mY7miDM@;qQwJxIg8 ztv7(noylhgR(kLIKaEdkUL@Qb5C0y;UH@SI{tNc(u2!&RHk4Zp@nOU1H>MV0u=14u zp|k{SJ3)Fl+lw}q)z}>%H;=01!SbX>=9<1LimXa|MPd;D1}gQ)IzEH2NBC0L{H*-WI*?5O+H&RPo^w}ExIA*tXS`E zwvHk>U&bRH@_DNF7hjAY0kelwSx`AqpX#rSO03Gb56-CA!IVT$yAP1=9mA^5_m--C zC0fiiJz?CtrsWga`!=aGky~1?-4WT;vHQcA`f9d4|KiGM>qY|sK-W8sUq@g{vbN9m z>|*n%Gl~A45`p&-2X(6g-E+N7Htmw*t8_)ogS^G$AWoz+oygla^RGln*4}G*JiE~4 z47-#jZhm=Fu=35y>N4ZvuTkXc%cUXYiYM74fo&s3ev7z&S(E^R`(KOuV@RWuxk;el zD~j*0-DcGThIbSlWt>C}!I?013XN`k*^j*B+Er_y&Nc<9TOnOM_fTlj84npeEc&D} z5of0L?T3X07}=uF{v___#5$c*p;%B05qi9B4>8vT{{_&z=iL}YEW7*)sP6`fd);sZ z`AkDu{inry9>ypYoui&!(`RT;*v6~uPBd`-vTv&#QQ6mdlV`>UQK&LopZY6t^tD-S z{Z@P)01MN84XV1e)V8|TeaxD31JAY{s@soMOMPk0@byQe`uXA42NgFhji9tQ26P(b?xC6aTz(Mp2<5A>LF zLWCX>BdPnYEOJ;V`Q8Z?(==WnF+`7fl!ce=j2{!N#`|klnU?Z<7-DjfUx&4Wy0CxbH_9&^vocUL7Q`=&p_&BPS)vK zr_opSG(*EPeA;xadgDsI8o{VAGO!jK9BK%*oulzP=|pI+v9+teQ1-T>3!!Ii&^A0t zy90A$kiD$c6y`_Nahl?ceQs zeWM*K#~Ww$r2P>8K~bBssU-Sy>0|=uk#l;KKPYD6;Vy^NvxH|BUwo;J3b=xPnVN{+ zDsdort*m3Iv=SQD4EhMFJn~u|uR{rLJ43Wtw5gv<{%F*n`PxMulIVHC$2J>0^>SiQ z>CK&jwrcrhBgM+hIBz$48D|zXR(4v_8FI4Dp#W2H*GI`8-*V+;Hu)r~%?Q{wvi3w{ zv#u)8b1&~()jN^FQM6gHaBwHp_&1a_kK|E^5})kv2_e`S*}ZF~GE)t1&sPi_5*F3A z!ssd3Pe46s?$7FxFe9YeNJ_wwTj?hfz!>gw1E|I?b;Uv|jFfp83$GfSO>T-h9I%qA zdB!*yjRlCm7r9c5sNQ?qroT*pXM_^b$A8~i-&F*IKwY+h%$B2)FS|125n*}72C zqV)}zv5Zt$SZKkI9*#E$gJ-dl##L&cT%hcbgy-$zw7U*n%{#T4$Z%g* z8kF#6D(Ktsggl=tR-p5dzdwkyr{m03fG6{vWfV?U#6yJ0$3bI?rVL)*b0h62jTgSj zt11dEQt|h+oI7pfW<7f1w)$D9Ar%yR60@4 z#p@{Rs(2+c>qpDxpe><&1isXlZzMyloUOwE24nyxg>|X+Ev4AR%{{WL`E-U43)TW^vF;@ z%_7ZrK`4gZmG0)1>-*e9t0F9eV#Dc-!dXz((bMly4`9K6Iv&Qxc_OPkLO(iWj#b8t zHGAI@b1+xmWPeE5CSLiAO{L{6guP<>=t~wWn@~{1e1J9ZTE9B*o4U+WSL}Q|B#GOg z`~K#SyhPwKiDKXjn9_+#*X41SQw4q_3jYh04!AYYiCT#O|CKb1&Igm{&EKTZU>E zWcw_?{`Hqr|KjO7*(M6^tnH5ZU3vFPV{Fjp)1?U8H3q`NVVfXfoA_a)HW(|fj`{bY zOb^Rnr6m7W*d=jX8?~BC2+cA%QP{RMQj-#qX*0B%C z%~pXzYyx!LQ1DHvNY2xK*SHhMe_JeHdAL}k$69~bb6(rGQ>}WQRJjz>tN!IxDc+J{ zBP4LL3?qo7AZ-#PFBg72O0%X76$cLs9cj%>?j^cmNqqgL>mJShm ztkE{E(etc9uCK|~Aaz{bkt@^`-uy;P{DuYm#=P4`b^Ipe+s3`y$QATtFshFh(qGK} zqUHVEmOUyzN$n?{x@x8N2~G>{qMf9}@NblF4R}+r_NJzQwSKL&nZPZZ+FN%7Y&>gi z0{;hkw5jEZd@9ERx=lAylrwz$|DeZOhnE7kG)GJW$8Z|u!#s}KhSWRVIPoN1jnYx^ z&9oOvhz@<>f>rJOq~+R9~6>Nwp}%GUkA zrX!N}Qit;b$&r+(3`GBDIs%B5Svsol36OW9w0s@18>1PN0LOwfz3EXFySA8H{_dXq z0d?9lIL&2kRFP|EZ3Q{C9=Kaa%XBoD6Jb5Z+!VGhGW*%6#ttR_>Al{kgrj6$lDY4`@MQA zy-|@k*3w}u{}I*&G_(}NzKrDX*Htbh%N=1m35Sk)737*9@wY1A znm3WgSZg^`pw|#*Wx*4pQrz_EC7iYs0KVQXI2a&y%$b@&)Jk{pH zJLKAnC@+4tQnzFn&Z8(AorIxiA10Dvbg4|IR8GoD$sw8?BS?49R}K%WGm%!GrM`+J z@*pO({3svi*Ox%Q?=HUio}$K6)LN!?dDG4lnWEj%)nA{DecLJPKV3&2S#o2Z`MM`c z3n!Df>q<5Q+4&j%UK2pmKwJw5*?R2T_PM%DP&BXqsj={g)}^kNDW-E#xQo>JZIq~J z!B-OmsBw4=Y^#4uru!zH|A{;PPK&DAAT&&F*p-I$Ro{$Ts{EcDfQUXGVft4yY!Z2qXyi6j^pMVoTQioLImS_IF^vaYzwZGapd)E z>dh6Mb$_PsuS=-J6KEj{cJzuqH(}1BGNAx%Zyi-(8_-l@D>+6X4y4Wi0Gf99?eOs{cv`F z!#*uKJZWyXeoH^ln88o0JE1me42(5rg`pR6DHSx6mJz}zN|zlj9uyW|CFoH&4OAS| zRbv3Nvy2Uzc`L7tDj9kn&2!btjGkFkaCYn;vl)NaoZTe?R@EbQB_Ndw0hzXR?`L;c1=tP^nwge3MK z+K|%rTRbu-!+R(gpA4JR5ABEYn;Qm$XwGk})O$g*FV=>coS6*{lw2XBKfygAN#9^2 z%wTV}rVcvpXX9tB)bvH~OoO5E5TR>b3HMWy$00?p~t$;8~kP2Vc{J;XpB_fHmKz_G#mpi}5JpD6o8s>T^*|Jef`CeB|{ z`tD$o)sPBQ=l5;de;`?@dnkZ)=7W+kAeP3HvP*`!OR=PjSLi;uuB==HfjMAKX5APC zUC!aKxG(rcmWDn^(NE6cI#nUG(TM-{O!m1-Q|HIx#%3Sce4izT_ksG(37iL28fs|@ zZb_tShl+>i`rg3zb!>(l++G}V+VD_qrL!;1=dxlKFXv_C3@=bK;0-f*wWjX7J91in zp)}@6CxBX;IG0z4q_<+0L=5oWB9t)Z z{y}5jGK*7)7!Db8M}d}UuU`DX8vc+=QIJ(ry!&W_W%6AA`oirOp(jp5()qdUjps#j z1WI`|6#KQV2CmID5$1Ng@rK)lX4g;DCNhRG1o>)4lSIL@ZNawC)$Uc8S65N_h@AeI zziV0eDJ(pEO2KI${1!Wk)KpKb`@6x>55osN0UO~tWKPb%6fmf3E<#!Ma`QL zVS7KbqmnfAMq_@b;o1n?WQb0rRB!NuF+GPcKl(_N zbhE-5n_*~=tzYlCPIwf%Le#iaFt5Kbl z`!P?RLsTz~ynYGPDWDjTn%AS)aAjYp@@!Hh^vy3(F9_IzuqKu*YhbH*k*j3Ht&*gK z5PM+aOJK0Q(NW1Z#!1j6+q`5s=;J$A-jNt6@G#+hxKURm;!4@>{qx9r7iPSS zJU|X$h@3GKD)5_nJRnmjc62KvQaciew)m-EqkJaPA9gpQQZBgQ!Q}%LT(fDg`nv?q zw1B6p{RQu(qU8FEzgXxWg=#5Z7;wnSFsnv;MAtT|pvA5pB)?&J?xnqKIcOH0vevIl zd0FTc8Uh9YQ4_NMJqAY{+H-Cn5uIRYc`tMeGn046G;1sV%rP|eMt6!jRs+Bvam9qoJ`x8F1x?P!E_Gh>ZRIJ2)mbOD;B| z=Qo2^A}Ih(GA1rk7CUf$U2s>mqpk1H4dDBNV1ucOFN?8#N6!tW>1V!`#~nNT2$2Vu7RolHH!`2Ajj;~QO2vAnT)$FybXFO4%M5I? zW3S-4IfA!dTvRnb_*Y|eIFd*3z14KP!&AW5`Vd*F$Pxb3_Ga@$y9duA>Vs4XtPnJH zBI35mZ`V!oZM`0s=NK? z_B*l=AEjdo3mg#IDAjbJ>hMmKgn64HH@;3~Sb$_^Q}-cY%H+EYY18Ly5gMKmBP`r7 z4~O8}p4;P8g^6c3F}YY1$P&VZAG-iNvUT|*ZU10}zgj9CS z1n`ED#E)9jXD{w|>wmYmuFHfUOtKN#Ms$tz9gh#a269BU*U8D3hSx1<_(JbyOlV?f z1t}enZMzp~v*N>}lP_{BhPVd5`@jjAfw+C=!~1ZDu%6F0%krPvhhbJf zb4G0^8v=6Zr$0**u#DT%Z*DtdTAauo)|T~XK7}&d`W2HphEOT$GryE|NlqRt8Y-ph ztSyaM6q#6$fpP_HJV;j&rrXXF`RL(Jp*fZ5JpbD(8$${gcp9Dl+odv*b+*qnqieIC zTf&hI2tW1zY@?Xj7V<)}K`8q9LebsX8QSSyyIBPPHCXzvV{Yt4g^E7U*e*sjYL8j~ zP0afxqt~;28*5rK;K!TRX$hL*3>S`-^n-tNM|HPt?YmwtHqlOZivTJ?MXx(f-?+K2 zRrCN^5S(TZ-eE4?{eRHr${(mT!v&Lp8g5^HYY}3V%|3X#?v}ae_w4Y=DW`E4O{Vj= zW<<3y*&>Q?|8fVsFo>9qy4-t+$xf@icu(OKw=`>2K@6|*?t-&*f6ojVe|tVjANL8Z z^dV}uDg9r0VAgHeLPMDg;NRckm!o7?kb&?Bi&%vXdB1^|T6PFm(EGbpbmbQr$}()_Ca@xo#dxrAS@Q z1nE?@nhL6w2!*ZF?~+~>rqcY+;a=Jq*c)pP2@ntxNQXz0kc}4zpJUbhb26MRJ~I!q z=*wi~JoJ$N!a7%^uh4p$kuF`ryF8_*18Aj5#D3vCEi%wJ&UqAf@rC>Q2^Nt{o^BRv z1SEKBvs##L-?i*W;^FBp($O)GUg)}`4L9T^k+n$Dyl|(|=-0JKnNOkJ%#u~@9}(Qa zfNLCa!cHQ(wi9Q`!~!0&fCD20xnSgF`t~i+cB<*YEncw<<2Uie!~(=K&!>M%kvh^Z z4vW9XCcQUpZg9c=;7qbev45)Y0cvJQWpy*zdKYDntbTw#<~2QeL_W)Eu1aOe%cY!1 zEUHXl160r-wUOoc^T~SFQF&sIVxG2S=xHmND z{>EU`*am_ya+Gu{N{^5b5KvSkB*dV*yStI@?(Q623Ih~r329V7q+!?m{=UES{GZo# z9OtzgpJTUn9J}-RZ14B${e0NAlq*IRQIhUz3hRzXDc)nX%YjH5<-}jgvKm=7^4QMk zekc>)t#C1ZD5LKeAK~-k8l@Z#a#^-4W-_+L5A_sb zmWn6yW&LkUYE>rvam!L!x6}G-3aKnkE=W>_26yV|t$?DO@S5wy5;@=CP=a{nTW+tS)e;sX;rv1VxLnRdt_ie-%dA%= zf#9g>M18R_)Q)B2CB5zCQy&ZPk2I}!Zt2N?CTyDe@g>4?7 zb~EoZzfUU0Ma)^N8)p#kc@loKPS3lUSlY58#%(pN>-Y?NW6}-L)7HsMYp3e;r60?9 z)IU+yE;#7%=jJ%i6q$`%y$2+Sc0#sKU3XSmoGbBXb-l!bzl|oC37$j3a<-`V=0J?% zV!cVFGYU@YGBEQ#w0B6B@qa;&`L;n4`oIl77qQXTZ^#59^*4C$yHVeu356p`Rz|C8 zCrU@ZiM+|MOpr2plT1M%{q!Ym(#r1$0e+1<4#Z++?H{Vx*#AI}rx#y)7@gT3tU@2d zFXtv1o$uI&P`$!(w9j=f|oy*Gb zW2yQt;kG5q{=%o4@-Ldu@9zIdojCY-E#@K+8)dO^I^ZI+wR+<{wwFTtQqy~@{U)f; z4@ivRka}5MJzVzd=LzX$lG^2iGQelH=7I_yYxFcKYNBH03N!KRi48_L|N6TPDA@)y z{gW6?K!vUXVe6r!^x=?{9BkgNV3Y=gDbT?L2 zU=G9dk|vE$pYehM50a-~fJit`Y%Fnr4e?IRUYQYXFZ;gu!S6FPtOm7L6H7p>NeZk1 z6mO7i6p$VG36C3RU*Hjc)+D=MPR6`Lwtm39c>v{`fQo7D&9KmB`N9g}#A&}so2=o@ znkAamIdD6>P+K2Bq_DIs;bbqc!iu8#6GbM`Ee{P5(ZgG;6Srh)NjgF(I5kLmax~8b zsIV_=sSIoZtr#Qi7$wSDC2jyCX8`>ZUg5Vk6s$ePu5qEBemq<{=d0 zC|7@y+CPT0J*HBvrZOOBdguS^xxj594t%wJrXyqDy8$G3CZ}_(=~s*C!+2RSLJSE) zH%JQNNIMuS1#yip+bEKtb(|5V#q_%zUOGt%a?Ix;%!U}|7uGBi zwUo?t4ByBZ({to5knp`j#IIU{-&&lfwX{}v(-p-8Z<*7RUwNA0m}fI zDPzW#RX9=JUlp>$?_uB=)6gctu(9fJok*7!+0aM!WWqa@)_2UFoLN4h!Pc+Pe5u`E zTZ4HXabRO=A&0DCPwt#e-kI^GZ|iXnM^o?S5UwHrnvjw>5)w!hnnOLc$}BBQIiEu) zYRt5YLe8U@9>@|Y;MSsYczbN!z$>OV%rxRg586;#sW1m$|0hgp8u+l%rsyY zy7zwfe8OmGpwP5+AZrh)Eqcw_!RPzY;r5dUr%zZ8r#z6%KQd5o5_U*$mDoK?!OVI= zuW3$07U~KP39>cv8Cj&XFM}Kqj~98nD;G$NNB0;9U5*>y0?Sdht@^SNaOnQF4+o9X zSBXJT1RoEi4eRa)Y*35X%AEgZ;h1_b{TR#p{Xr*G_Sc@6lqIdqJ~yO?Zc|Z?xR>Cg zA0;^NUj`CsCqacXAbWTSSZ;mpK~@n(Ja@G8U7_dfqce$7ocmmFndtSAT-e`1sXqF_ z{Tdb!=mL9Kc#(AW#$>ZO)Ll6J5f8fQ zM-I+YCBy}T5*4%)Lvi|J6C2t5u{H;bjF*Pe&hgDv0)tD1MmLmnn`o~;TG?<+nedq` zb%myeiSRMA&OhR#t2BTvJhzTfmH``&BOm=7@z=<{18)(TD5xGQ?5wM+J|v?(WSV6r z)V!x({!lM~|1s0+$2*@Ne-j`%h9f4dIk2(tS5$)anlF6DUj;<7y;}o?=NLwy=p2pj z$ph%3jYSFNZcX)A;FQM>ZQXmh$Z-c`jj>dHqZ)xCp0Ba0c+c&D#@7b@CIU6gLU;x) z+6GG#P6~(nR|l}J75<$M@VL90ubqE+{$Xdki(i*Z=Z*xsp1As>8Q;qig`%jJjeP|_ zP`ZkOb$##t_Pgbeq|{E3N*;R2^_re&>UC`sQk#nAW#hAu={E^*e7-09k0&47{b|c{ z;8l1o?&dUTK7;$%LhVs7z8n-=v&t}^OEZgO9c2rnjgcfc)^U|?W=dq3N}a@5Rr#(3 z;zcKvy219CzJ11`dE7KiW2lIkWZW8Y?u-3+qCu_w_MIqgyC6A}i_%YD+`Z%WRFhqR zg@wcC=Umh`frrGg8u$az4rGq|=othEr$bV`eJP}3Om3?3aJ31a+rY&Q2yn)2a=c64 zK}*9V{9UmQoM)lGBg@ol`mHhWF{@p^aPo8y=4uE73D1EfN8@A!qQ z3biM&ab@{As_Ib4*GLuXX{=7xVn^;Oq?{y!&^c;hr9!5#T^RXuwYU(FJNkX~;dA8- z!%er}q2}yk?6L`jojHc_*e_AL=id+BdUj)C{rfGI?a_)r+}Zy4NwFmjt({K5z*pL! zSuywuWm5rMk}@>8Iq-5VFi0e5`lrS`|4(jwxY_A*vlfqsF0M+=ME6_Vno`6fQBJr> z;DhIph~&sWy^(tqQ4`~&k%Odb(ZyFrV%?%)UM@acXZ{>7o9bMZ#9Mff$k$Y6ia@u> z-?LVqz64UG*pt27zuBd_oeI+tC1G|8ZoU7a`~fFVE2n^%gIub}8meP>)m%m_6f`Rs z_P{UdEY$7vLx2q_w*TYa^O?ABXQ*|ZBnvUNz1esm%}b+%TQ_IPAhBcuD=QBFShJ(V zo^fN-FR;uQrChP3$tJ79)-m+luL^f!X<1i^CIy64DCd!e0kS)VhP8eWVLUwT`)j>^Fi{x2n*Pn5Syz{)$2}}Pt>V)KPSMJd)h&BSo6AsMK+Kk~b5SeO zTh+~M_T&8X=26M&i(tNA)%wOH1nqa?UJ}@(^}Q9#yuY7DH(OqLK3}eP zue2F;56--o=36{^am0-~)&GdLbUqs4fui?ljA}QrVxin*W*9W4uG3x*Zz~t_@VlpX zL|=r@Q}Ds9y=^+JLHKAlD>y8S{h=#6QsNX#h{4~ zB)b22bf33(Ute|u7l{j2pan=YnPhi$jzOmH^OxtO(8X@T4m9YBq{RrdneK1D(<{c= zcaJ^<`=qo_Dzwk(ee#p`4t07y$_o4y<9VXBs(PYWBgw%xSJC?KXo+&+^rJ9*<3YEM zA+M_;KgnS~{n+620F8_OI8SC%HM#=I1d8{5-|70LO1ges_TZpLpk#0DRksu#RTnxp z%XREjZ;Yd(w@@-5@9Lv~a{m`e|JjaDhFqWI!}^CLMt@LnYMPaN_jz&?8d^W1aU{)0S+DxGRjnH~#;j|Wn@A4t zJ@g6;{f25=a9uumUEVH5;TjH!sHd42Lbs#tFUp;^4i` zAXQsxr|^i4*>i>I`S0&RU3(wsmrEZnaLsQIop03U$era-0XCpkUBTTFE8mtivCqm> zp?Ls*Af4^YubnsJVXvSgS=k&nV=oa9K-*^SO|Vb;(u7xch4&LUj#}(lV$N?lWsJRi zbql+k7nMnzR^VKN%pbbGo_`f>$9P!mzIDsw_Bc@gch`}@H@iQK`I24>ve)GgulGMJ zk+f&rQo?2yXYH=v_>h|b-U1m!EB_c`{|GQW5cyVEo=$AyeNfN8+2nf)`_`;sxK;S7 z<(B{LCcgg1^+opeX};Ixz$H?9mx&g*J<`4R zDVrN$(wE7jO!8mok&eaAen>@L(EAKP($|lqGQWn4U2Vhj6hgGHO%DLR!iA$Bc=g&$ zTUW;YlkZy0cMu~t)iNYKWxvYs-~9A|gOy)3MFi03rJBxvc8a_u=))Us7BBcxM!R^S=&jCC z!OCE&+bOhj&gIKcUb8!Yv}Ehi#>e!0DSn#c$CCvXdRSMw5o!^~PmAi?h1re#Uu%`F zQrc^5$M)txUl(6-+ig9`o$ij2>Aty6`w{aYTHk4dEL79n9y|Gmkj9g};E_xtcD2`mY60ymL`7lM$NvF#R>F-h*{x@ros!vHz9l#nQ2MC zH*!)e$Ll&ucrOd$tlC0yU#mPEnM!nA4ttm7eq>tw{F(iXNou1Qvoe$8pWGFt>f?m) z9D*#u6l=>tH)eZ_vhz)CmF2mutSoPm-Gt0hv)hHK1iSAI4HIRPnT*gUf9GJ=AC`eL z-89n-4caVEEi=GO@H97ys44rXBIg!+eO5r@^2+EZ!5&b6vA0GzE5eDDqrOm7#u2TP~7gT+-%~ z(}1o3!QHoi<~@*1K7qhJd7k?XT1x8GQpRHmU-IbL?@Y&~(yj$h6rG4wp&e5Wq0JMyAQGO(PMp)=K%C$O^V>qN}klNI}F#$WT_ zesmiHf4$w2$Ogi6^48Byy%Nm~-A2JgLOMKhXHV5d@I>!6s`FdN_b#0{56QHjoB4Y1 zAn`OpdoMX_I3SUcAd3J2FLgmSs=J{hWpP0elj;EMm?i*rB0pw8CQL43OcE2SFj=AL zOZPesQ`3+Ze$XRfEvp-#A16yTA02XenM3VG(~F&sv-LDl$wN$}q_XFghdtLNP3l_d zkYpc>iG4#Fsk4C<%J@5L@&)9Guu<(-`-v}Jv*u)-q5EG3+7&aW@?7MG^O_4i z$$}Je%FOjuB-W`!YZnSpy;OSwg{BzBnaUrq4+ww6+{GW0`(r*ZB6T9f<9GMb{Z6sb za(w%gM~^mzCfpPpHmy?W9bQ|Z?$iOvc?HHW8~mMxGDzX4*~sIKXTxqRPI(SFU`kF^ zWEjo6I|c7OZJ%9%pUKZ*6q7S4R|PJK(O!Ajh|p~wR#_R6sSh-t9jZKU^DfD$G_(@E zSgjqrz5jBu^$lgd5&c@0BJEU$Gg*8BWb4fH)K}kH7M%?tK6CQPu5my447)l3z-nsSb@+A{zw9BTZbo8uCT1NdpAGyp_(q{rFSivq~*?Q$4Z~EsWc7nd8GZ z&ww@0dXy=m9pl#J>jPyHa(PRI2;Qh?n^!e59>?~7G&f+1=xyI@wB?8*E&o_FrJbo_ zrp8+FGBtdr`H6Z%{=@ygHQJ6=Ip@Y5#|lBOc}24kVgG4L?U+0?d5r7rgmX|OJd-GK$cInQitM*FA;|mtQn@+dbdoN*>Z+UaK zqI;<-U|n_IX)QVOs#5Uqiq5zkpSv)r;~Tj4nFc=32YZNfx!J1YTBQ1H;zeUkgiG+M zGcB8(qxQksB1rc|IYyCjI|=QdwzpnwQ+M)>)Bb&PSv;UoOLgraQMs&&0h;? zTa{I@Fu9HSP9Le?)q;AM29S-i*VG z);`1R#TpareCU4GUR-s@MvwIQm_^r7>bI*kE8nfs?`zY7??zZ>{NiCXtd#H?6mOTT zgMlDDyX{#BF~Bxjy+DC-$w=i(Wi+LXfY;domA6I))G1Nfi#_)&sCltF#HdIf(GNy3!0fnTWYLF88_Kx9PsbL62u+J~ziW=y4qzin%`kU&bAZ zeN>I5;5UL6#8NyIgkILbRy0AJvXI7D3i$(=8~|`;OT-mNyo;vzbn2<1p1V{`AaKQsa-UrYj1Lc(iAN~h= zbPZ&)C1lG9lrI7Dy1Hd@1U=h!(taQGJT&O#u)p4L5GlZY;SSSo4n8N)my;Y1m%ozu zANi}>007yUFZlyMs!$5*ZI3%No{U7Hyw9n6L@ftqY@M4Zzp+t+*`xET$RKrS^O+z0 zEJctJEE0(y2nL04hCS^GmDY+J+zyqui>CJO#v?wy@XF-%b!kUCiG4^q%Hw zHU@AW)2CyI&!r4@dzYj`RhS&SgaHWw;<9P*am=C|>Mye>3;?jjLfcUIL4vSTFu*Dn zmI24lU9nMq7jZNk|EM6sD8SO8$evR%jN^Vn%IkOXid2QCV7hHjQD2I`5iAUJ0QHs= zXmMf`%BA%eTl|(|!95rMG!+}cbFLxeW_CX;fhaW;FO}xi`3L>dNHMM`wbOX*u%uUU zrgI-Y=$1-Y&Ls(->yoIj0F#qkxISe2ec*cW#)~W2hd9Nv)at%dlB-#YkyeVyciS-b zq^Q}HXqBhlh~$Jh-Zx?~VQwj@t&|o!NvYsuf0fi6uCzYmR3?+;G`ExtuGC0GYPm{6 z_Ia9vO3L%Fw8qv)4Jv67h;%=(v~j!KFVV^&*KQs<0{MJ8O`I{%@ZKW7vjzrd6a+8JpVpz zzOtRUdujTKO73o0uG2}%<%0s?c_wWelk#eU>S%%bZh;0#p%!=H(?^BR%nM(HB4h5N*B71;ajJUc2gdQ!;LFT&uK#wHFE^S4gf1$@>Z|=X) zW1x9SSX*&uSxMBR;>g{SxZR>y?oyjJFt*0m{Ruz>h4!b`=J-75bAE191Qg z6h665>6g(W9S-~%-BKL%xbUcQiMDi+q$-NLYQ3yv!@MdeylP1oWPx(1{FBX{SkWz7 z&5x*lHX<^?{p61>)752Af%E+w8s4WOLrV%`ux0zni(1@WMQT2R3km`FS_D0wL1 z5w*8Tb7|Xa!Rb^K3->7CBowwBEUI;mCUxu*b=)3x;t92k3pMnlEW!)7pqF*WB=xYe z`l}Ch1C#X`hxMrTI%$apxrI7K)dr>ZdeyN8^}PlS(nc*FY~xea#%C6dFUCZOkR*Qz zMgYkg5kT-Cg0b%a#PtusxCem9)==={2u4jjuK%_VKjb#*?=>3nG?`j7y)SRF+-u^R z{7W$I9Yh0S6YGnb^%fcpBPe|In%+fFn6)=qMVOZjnpXuU)^4^W);7oOHNVzt7?L0QYbNV-2+UpbDVb?2_J`N80Ko(ON{;!X4L!OUb@NlWu9kR&qQXEt*{;8plXO zv(Zo|BTyh5mWHFNIlAnal<558(K*-NxkL*1M%T4| z8Mf18{o}+M0Jr)5+=iu<=Jy!-=@eX$4!{ag?EzS_hUgg8DYDr0i>~|QSpOqxNK-6DR}Jak#xn}PuL&B1rg(G! zlQQxff)m=8dwz?h=n#Y?9`2{`pnx7 zY0Uo+j4Nd3HHiH3_7AJzo>*vwBp@#q`bQIz)J`)g`H7_kP_#n!8xu$Crk1S@N5s-m>q61|276h=b#gk9A`YfT`>+ok8>T4A4*P07rR$%xz~IRuO|f5C{F_TFf{6zmUkG212Pw! zy2wki7)v2`05bysE;A^uuO@CwVSap^;#{2){4~m4OS+XbeYHQ4BTU$gB$PD567JfP zBmv+1E4~j-LiAyX6l}pg=)Uwxt8Yz+J2-+74HiQZqM{Hi`rS!Fg!w3BnW_S8A~>A`MnOVLO~}fMgL5baoYSwsYc}k9 zjubN+!!UPyb{=KrOH}e#plpo_>9CsbW>_ra8*Ri4$>@{TEdsId?yO9TT&ej`t@*B~ z`QFa?WWA+|bP6^uLe8G09KQL{UgC8lMBw(I>Ig#M0A`KGBKS`22O<%LzK{{wQJ+YJ zj3i(OWkF{KtI$C_j51GgR|~d<1{>i=V4#t{6y|8M)CZ7WB!o*APX_*JVa2ByP0ATJ zv41@WSXqi=UZu2NrFrE*R|R9ZS>+^OWBuuqeE{1d0|?Z>4kH!-ISc&Kt5n{rh{x-q z&@~oD2pbe&b@q=I-Lj~#ycl}8rp&)iJHE;Y1vn$26qZY~l}nkOYkXZadW`FjZZ??s zH%+6L0h;)G2gF>H%e*(sBf=zs>Imi%TeePw^Z^XpgvdYjx$#2$n^6YzrfN+By(S6x z{Ur}zS?QmXR#!O52`^*o^Btf{5G)`YGfZdpUU7(`Ovi5#6Nby}rE-#_M^i{LAo8;) zimE8sVs|6bDJr1-@OZ$f4 zmY8dmcoj_{Qv;K(qQD`HZVRB9Z6b|#?^iM?+L2?SvPXAfj(Bp9c(W<^vzwn;4&^i* zNqmKFyY2?n{^qp99&z~`Yo8tg0MSOO(VHp9oN>{KlgEIAV`-mbA)}~=2e7nQ5FmC$ zCyMw0RVNxl@nGT)`>$iEY6=+`z{Do%jn4@Hg}-Y=!n1k;0Gw(*A;GN)0Fa<{%uwRt zuTkoQbezR#RHXYb_-)B{k{^s9hN3>_Jhf+2#d_x~_>imiFhhEa^x%80w0Mgz^tc`B zQ;m`LB-~gbx&uIHi(b{T}cY_Pd(slM!p`GP(m zv(m)xIUp11iDM*=zvibIV(P4pp%|S2)f-*{Y%g28FLA!(t(S4ssd033aZHH##MSFS zz)h_T_U7XRh0Mp^N^qYr1TMCjN)oT~jUGTu#c%o#^a!xcEq@(=5r0Zd+PP|1oFNc` z1+(+kJ$?a66rdnsdk;5OND+E7Ua)iU5S}4sC#THGic=Wx1x*F!*qHX}ql5XW#P{@} zMOts5IE8WdufnLjF^|dM3rfW}v9}*&+zHA?e_-bkW{&ZBN68W~AX=suMC$A0VEpx$ zA=+7{U-*U1B4-xhZf4)R$J!={-p{KN&7{hG_py&SJ?nogw~bT|;Gn4WQpcMMQHG4e18l4k z@H1S|W~mfELnAc5eV_)*-rCt6P0JyvR?mC!^40~4fNy2D zLV!vqI+6T8oB5MS6$NaeRn=E=6#nNo+0LgN7W3FdEgwCAlmUP5Cp#l#UJFJ38+Vk>3>i zJ{ZQ`#+gqe^)g0kYKB>gD|*rq?y9*b{9B5y6&X-Hol|JFc(s2nk= zw0^KI#66*{EX$1gL(J*!nARiuy@NqUTfv?~NvWqF_ciqaG^j+!eXh+GEKDW{Moovj z-XfEG{lV$Eu0`XY=lTv`oL;>0`19w5Q2>>*j!DG56CKlp{|!BUaMm?1Z#>bptpDPy zXWjniM9;R5%0=IP?B1!qLi8vpm7|z1q4pb z;`gd$ok{Gqk-p`bFg^Eoc$OKVu%@EI-6E~1^2>g)nKQ))gXGbvIw08X!)UExtr(B* zuWwAW%4~gEB)!;7na`=<|Jz@5!1;^J|6hOc8hd?teSM9+y1-r@UtL{YUS47^PX0qM zo}ZteotCbUCnwlHf3U~L*x$dekB`rej&6?E|A)W0`>((F zbMo-u=l|PZ+}u3g{{A0-ad&rjdwY9p3pcL5vA(|k`@i_&)#Bpy%*^-2MeMgy>_R&B zOU%;J(&FOc!otG*{QTV9-0bY^*RNk^W@f&8`SSVm=jrL`si`UK}CRuEgAh!0-)WpR2`1r?N--l`$K$2Mn-CCYEn{Ce0+RNOiW~CWN2t;aB%R6kMD)sn=@NGteJYdle3?npO25v zje*w96UAM9gWV_EH%gK>k|H}QsvFWMFE1~5cXt;T7iVW@CnqO6J3E}i_&*g!VMDp1O($p1YmBj(((ZDEbt3&*rh^@0j4;Y*YXV1NUd&$p3$T(SjHO4lSeNUNbn2CzxYf(>EleL!MrEk`m1sem*s^nHxR6< z>AqdgU<`*E^sM%1i%9hN*0Lg)85m`1m!lt<6cZ?{bOvu`{u zcMiWf@nhXWeVC6qR{r%D<8cp=U#ZmJd@tgtnH_I&zsL=Ok+?G3(Lo0c{p0wE@^tYR z1^@bsC2QddVY4|_+rU^9!QGknfBnUh^=L6~-yuRtFxU6k2X_PwgRh;o)8kcHUS=ok z3lV<~;a%G>!MQw`M|Zi6b~ciYf>jnj?1;5|1qeZMH`6Seb~e*(2Z=ezE#b^tnXa4X zZy_KeHg;>DN4HCIG! zXx^iU&8S++;#zM%w=()_LRVfv{FVn(HHhcSo5X?=i3(dSD*xH`8jtf^5f#MPuO37D zz6VYPSmArUU_V>kU4Oep;MJwS#eR!Up71A*ebN1cK2K(P`i`?HIzGR{O$osstSCaz zkM0{)oj!raR!u*zztAUP0u;_)6r>A0vZmb9TdAjprPOvYcr02?v`484V;Vk4(zT0} z&!R-8ZOMO6Yu?YeYjy9GV@PHl=<8ryXvrGOj~;HU$MkwtFi$?rS1*}UDT|8j8F-wz z#xWg8@n^{u#^Yl8ECK5R;lmRH$Y<+*Rn_^5_aXL=tP$(oriF;OYq|xir#A%~!6wnv zi~T>nOem-C=F2V@Btwg~LjRC0eIvB;YWa$~=Z#rU+ahdjY+ipQk=HKs?s(+qb8!^U zG^NSK;V=_jhkmLp2qrl)%Zw39o)cz|1nfgH`IE)`?*XDa>XjcHpH0cKes6gi5eJYI zBo+T{%1S7gS#k@;UxVgvXIc6@{aA>RbKuRU5`5lI* z?E%5Z+rIuZ2k$!9Z_~oIQQn1Gd>PZ}_#AHn%oIQbh>!V<*CIph4eJza_!%KJ#ZvfJ ztFfVK1uWDf!}2UB<_Zw{%iwzFy@G+;zYly-!NyXw+xgG%xCVJ3@sYX^HiQm7fX@91 zd=BwFlIV$%rm5JNXq#P>w#ZBTr#f8E70hGMkRnr2KTWmPCcTwY`uKI(WM+H=xJ^Nq3GpY? ztVS+HS>3!pSUiz+Sf1%uO8`pHID}OY7m-GV0t6h0rCh0CmbQLtYBm1<^%uv?@djG| zRI;Oj`6yj9XcLjQ4s3aN+g4{@5#{42W0Y_K0Uc5NT>PMGS>ok5;^uk(YW9OYogeTB zn~K-Oao0ThR9kqWD?Q~oWR>rgROhGCP8v$oE6rbw&Cj%*G}c5_TI!XDT41&NDC$2| zS{rzTh1lD?2p;@mv8^fS7i zrV+Iz^Vu!TrR7!@Sn9nTZp-R{>wQEM4F~rZy~p63fLmbnL%Bx1$%y&S#Q^Y*4@k`@ z@}vPx#3<+ww48o)EKdv75mcv&G|FN8(X2+5&`a}n5$fTJM6)XkS!=;zSMu)MY^DRl z4iT20(F76&1#Z*+E!9C}fDRfZ7IO?(W2FZfQ4+%HyAsYbPXmy$29Z(P!FJs8=w)qt zDvaEax)%dUtv$j+n7&BwP&~P&NY-k(4CDvC007ft2fGno`0MRFEYjv|h{8LsZ41DR zI6ezGHPx@C1)-cFwgV3i;-U@dSCLsdN|KJ`5!%rI!jAC2up<_^f+|tt;hP?q&h}on z11AJ|AA^XEZvR0FRPc*3y*Hbl^-p^jrESuS2Q>&JklDq6p48-m-Qa}6RW4ckl_{vI zKAnLI&o|F5A<4BJQJfb&kl3KP=F0J!6kPF0*TW;Gzn?(tXKl2}XCOcrr6{q_41IZU zWX0Wts3R-3jPi4TKMtMm92*>Lq0gbcE(vV>?IrcRcvOH z=J&(H{(Ah3@xqu44xztq(nZ-%de`@j8Y={f)o9&O>`D?R<(w1OI~fpSwDJd;Z<0oi zapSPYhy}?3FpPSPSRst0>}uPUPFzcWnJI;|WR0oXZE$iJXmQ-XfM4K0MhI+f2b6h3ioN9Ap}v;bA|!2{eA=T-KtN2W@)9ERFoHqO_neoPj zsjL|OanO%$*l!f=@MOr7D20FV?R{8^KkpMCu3)dDBKpPG2oJFIn!NO8fb?#k^iPn? z(Q9~hEE#?eSpk|Fks=02aU~YUdmiF6#^Lwrs~Gti`wO@@S&skn5=mlL`mScW`-$>G zU}j)K~E1x*DwZmnpN0ARHZQW$oA`p#F06Y2OO$ay=EorWLZ$ez8W>Ly4@`HcfU2u&61b1LrTEMYM+kW7(7wW*?i8 zYk+D=Uj`AL6=~qC1gs%8`$}5H(CrypA*gy znl^$}aclo7xHxD$m6|0lo7qmx&`HeDZI;#(X45yv^vKA`0G@Rqlx6kOtJRF_6)I>~ zEC0WP^d}b0^s!o&fF;g7N2bQ;y;i>~i)GvnI&1 z%^NZo&l!0&y&>|s)gwt>!~BjS5sbR|c*Z%i_XTo_ov-Z#3U+e1=5z4u!9~Fy{NWi2 zW~tBw{AmE$_WOLs@O4)l6U1VlRC5bZNxk{-XzZ-??3SXw%^i0JYx)^b56L=fh`3>L#$FwXehK zTeQF%9K@U!^#ot5pz`;xY3m>D)H3tbiSuNi)6#FcC%Fa|s4m!3?Ij7U|>qQWQ^fSUZ!UYE!{%17xo)-Vbc>yupI5_0@uBji6p(d@D}d875*_nA)KOTHru?F&=7^5? za(YvE?nm4BCp_&dmoWJpN|+}6#0XYh15VL|MWNb+SoOE3I{lS9w$dBUxVr!ejFcEc zUhXVRx=FGY34tFhmlNJ7*mHc^`HI2|AQ_6Mj|S7z=kGTAM9@jVbFWd!sSD^}qV6L- z_=Ybj2xmH?yM=yxziaAwG21g_(Zy)lQBBH#7Yk-CA^DNpTAW+}o+Rxc1=Jh$7|Uhi z)%i|id>>T!i(mCIdDcs3)Q|Sy`K%N}G6rNL;JA5=tQAnCAk45egJz$dLucUm;-Ko+ zHa$p2O~k-YRhl>O+%K`fhZVgCCxLDlvXcX{S=Bxvk)Ti5oDf?{pBEnooIW;~cshI^ z1$tx3eI!Rv91Z-xLpZ(;L(hhtA;X35`ad}jh34Y>0&FK~2i+h_&-SvlSR-=whwUYm z2NXw3-;EYmj93@b6QK#ocOiTUBh`{aUq-!~_1W)Z3N&=bT9wp3{g#|$g;Qyg{y@UI z5AgaGyI9m(@gs-g7OBM#2pbp1hCWsm(TdO!e`-@wV>p&&zAM*c1a(A%M^^d|lE%6g zT|4&uu=}GslGH$7urJ0P%Y%_rs~y4ZOz80{g_ZoI{}gtq#O@0VN5c32fKP@dK$QdQ zp6Ir#Td%GPx9O*L7n?K!@a)5SZ(X~XzEvAO4#LA~LDP{2Qwr*YcZ?xT(~_M}DNm*a zsXohfK2b3E%Ug~R+6Oj)*cP59(vGc3Lk{(&qux3J~9@%t6n*P`q zePi4(zZHC%3h&Ft^wS?to-xeff#(u4pCowA(SMjrGkB78J^ko_P{M^I<$5mDV2082kV!=PFT?yJP^-rOD-tLRK%&YyHuFKR^J0=rac9=Q>6Dsm}8HR+*V&E+d7!t3=So-lbHM$Kfr0g?#7|^+pow`Wfu{aQ4J62OWo@w6{ zY@w86vGta8Ly+*SV&aGL(7e=WXQf2RM`~a!*e8eN+Ngana;njIS)=3QtF^jm9Mkn< zIgs1>`&;Xo$WJ)n5zlQ2`{^5#`UrzJ^(#rD=Ntsw5ldW>MMIOsSil25P103O*rq0F z#58yi=R2Yx4tLN!?;*a}XgPwgfc{|`S zZ-nYz*!ap)lJ)JC>{+1GZVgeK7$+IJB+?Y-O_ z_Eo3?1SXG9E=t3r4}Rb{J;L5jjbDe`F7klr z3jrKfW!ByYK=`Nb*cb>hgMq`7&Keo4AyhoL0~)<+iqQ;G-uQ?o--lz2i}+YkfBi*1 zgRVft(@nLsdsfTZVOp$@KM3D^!SwlZsDoug#(BAq-+wGnH5PTcpx~Ym_8ES#cN)6! zxrC>6?U*ZnZ#GVRB&!gSJJ-PVeyJ;n?#0i=+P51Q_+^RwL)9J(Cx1u*2g^NyQAgib zwls3Rzwld1(Vy9vW*M`)GJ9>0%HU0o~mY!zJk;-EL=MJC~dRTuUd zP1)T-)V=yrZ>4+3YTD7ZL9ghZ1xo+ie)H2is7pke%degI*L|HoMcbXf33DBvC-mvc zaPu{1OLbGUI3#1{VC*%Pv?-^5etdiJ^QPh$vomtRM2arKr>|*GaXtf)sa$B?0sMwI zlF6mc^l7kNb7$-%m}&OZ$irmV_Ihj2KvAe-HGPtSTy1@=-XxNhbr?g+4k1OdPCv0y zG$+0tE4hdMPOw=HIZ&B3Mxm}Ea+Bpygu%vrs)#epUaM)>baWLajegJj|4?-oPEq}D z-0*i{fu*}^=|;L^>F(}sq&pW_y1Tmt>5>vy1XL7IN=iBu1SA9n_Tl@x=b5?hf8flV zIcLs%=3LkN{feV*iSSTQ3{m_&&8*<=R3iV`vHKI#r{^BEPm_vRvwUZYsoKRAIDmB7 zyfLkQjCP?k-4f(Xguj}oS*&A;Az8eT{=aQYb?qO25rT7?$n`t}1uOfVOc_s#Ow4A9 zGj$!s^g2U*fMJp|6{%%?uknI8?Fapzx?1@wD6;t)It>vAO`HN`mIoa6nff>Mookau zUkn?HCyhPYH@VC^qRb1vd0Bu&R=xdc3O9U=sCF`CmB-Xu4CY3NtqYCO^et4eiyQKR z9S8m22}sj5R>t5)#@4@Zl-n)YKfZpA!`qx(wM|6Ym$XH9W+jB`+MqUJlPNoexmN75Y>p@5`H1m>ycE%M7xzJc%j9 zd;ERFa9D%n3S8Ez`u4C}hZ=D>=#kZyq2{{m+CX$-)2O^Id0~22M{jh?OzqXJ&~>lS zkt=1(^J4gL$UE*=l-eoyNSoj5&DV;n_4)-@Xi3y^-kKWX=PiK`voOh`_ovXlVV3cC zEF0_d<4OyuT+^&Xa!QNs0=j>zeC zmt38r!r6I$U{v<-bX!RByBEbsZL(bMOCWH7U+Eh_tm~B=wyjL}c$PLy7E4(@I^c@- zP7^~Ki5E1_68Se5OT8Y7@5L3RHdvKt%8yHJG#~#peB0uV`~_}?cZ@=uTGL->Odm@s zd`B|nlrL`rPuiZUHN=kSBMIWz@gl*&|NB3XSQAy-q-px|!eH&{=&@OPvXtcblxLNq zz}9K%KVN&ymv@TuM%m0Kzfm#h7VzCX&l0IyHBs#bh})~}sq)wzAc-N$U9%UqUXu(2 zOHD)$Xt2=FLwi*I^(yy-za3c3rba<;-v1$3U`kkABzrS6b)Nl&>BQWGbWv1}r$oRf zPqCUsnl+}kCqB2|F@w#aP+94gC^P4}UY!aZ0OHlmn-Z)hzdsf(-}zEJxp0sXa<5^l zj}(MWE3&GYi=a?T;bKk&91PpOnRE(D$DVfE6kNJ5cJ%_~VImHZWW_VK8FeBq04V!k zU##s%>+2jOPJ}Jirt-T2 zSiaw*VnepYP6=Ps8{#lR%~(EWn(1gszx!bp<(?J%in}b4n^VuIYXC62Kp6ybF|}iy z#Co|Tlj~z>d_YCo9~9`U6aUKG?al}Qfdqo8vYAyIO?-ods!9#Ug=+X)-iU}eA`R0G zbWhB_zOM;rB9qgl0uvc#{&dOIAlm29$zQhR*3m3jkxJ<6uRSXPi;(s1 z1O>CabK<1jK0|C|r(1qlFw&9T?Z|Or7XxPdqS&layf_nY;ps3r9A{{;1 z7(B|-A?@tI`@EIf<}?U5m*b5$ToT1PX+mV&+Ne!W!Eft|u$%r=$tMAUZX+mCZbh zp8^T{E$ay+8hZLO5q#60FFUbwy_--eU2&-jJB1Sae-fMF5J*)L!BHWx!<=AG#K7@; zo-&Mmc53_mt*iBjddQeroRu{6u5}$Vd)4dyhFtC__mDL16B-hRD05qo-g6(Ad(YBi zDm`)VoS6NH*UM4di=nSfO}RjGIWC*VcNExxpzb&ZsL&ChnBzYSj`Io_6dfMcf7Vvs zq6c-vOP^W=Lsll0gSzr@Jsp0AeVa=N>L{gs>246dwlsCy)h>MsFo4Y4&h+(V(t7!6 zgl`<62jSvay)pQsp{mGv6WQ(zvxOiSiaHR46fqe#K6NB|3BOs8*L*&)^Zy$uiol_ZPDqF`pG_STJ)1_5sYBNzTdYg@lmxhKUrGM-k$lt z^|2%K4+d>FuJ0xM>ZpA58hM+pko(qyE1>W?x8-KNyO(Q>V7-Z(5`?wd88tt8`|+*( z)o7?{qVF~u6@@I8d!7p67!YT4(@%QpsvC8d$0KFv?|Nf@>KGw4iaB-+Mh93@7tYcV z=g6LjKQn~CUpSe9etQCKWrS`DLKzgH9)qLTZxX!2hDj}3_PEe8*?}PgaGLA4$kGJB z!+189{GV{y+m>P5T|O2tY#oIk+|%0R{v5`WLuSsPn^sL=t&MS?HuI3kX|^C(Jez3t zh>p7uf@RFF1;O~P7+N6;Sn@HZ$-LrH>=KR>gv=8}tqrJP_!R@dX^e;T8u8i4$(FgvirUb?lgz@5J#&LYW07k%Zd>NM_mO#z6 z#JfOsC38z9L1ty!n%A_hfK~!-74E4&D2hQX&n+r3rs5s85e;^&+(w>?nzM=^!Va|T zglV5Cuj{gW>N>a661QZKry<)*%QhAGq{Fqs+nj9T0e0@|sh2pt(qRnSe$$?dMXuNcX&a*d$9xPmjxkeB7*b_#%)sgz7`COeS1; zwx!B#K_!iwDcw>k_jD$yb+leB4i$n3*`FCIow0^1{Ih$n<@Y`ZuJ%J?X0HaexWnx+ zpj@q}Ixnw=wJT}%@VJ_HFA26LXDu9IcfN z6~sVe-9GQClxic1Fv~>QVg$p7G%e&T$?S?_x&j1VH-W|2qOnb)m8oCjFORv^3i&>) zbVNxsFkddS`fgPrem81Q$Rr^{~dk{=2KOcJujw_>?cotV! z+#7xmS6)rNt)>xrvP=PtX$#m^yttZU9L5}`ez$Z@kvmWRut@iq_I{h>^LSb6t!Jsb z>g2BnEllQ*SYL|VOw}=#XuvEVt~YdWrLhTK!7okKh2>LjIs25(<<0S?aSm%vLs4d^Hp{5X=OCo|ypx!C#PL&LJfO?(l@Qw9)J>Pw4!UkWV4(2 zDSy^i^_`5n5$8Qfc;(9lj7>ltpea*Y$cK=X!-SlnSi_`o7}iL9vRi4Pnj?>aKcdnY$}azC9}*<5{GMG)Jbh zU<&}?C|^gX)89_sB=P&F;Pb^E2*-9?^%AHiI3x)t&cg%dnbEQ^lmRe_G4VLl*nTva z=`p%{@3P@*(@Z;~jm`3_`kvIAP0aG8bm>$=0Q}O2ZkJ_aW|O6@9y2uF+Upp&uxH88 zfnh-r%eWdJoCE~$0iNwfVcR%INP=!Th8aPurkK&%0rOiUo6LpHo-gJEcq_&1sMBU> zk`p!vTFWe`byt>&xY%eVUy=kAJq7|!Op5u>Yn+LX6$XoyC$-yskLsM^IJ5P*w{85g zWR?HD(-!FeT;1)wL;93NM)%3WewyjFklBmnanq`K1QQ5`XTAn=wAmv$Wwvq-zJp#{ zwTtWXOp)`8a@;~v5Y;2E$Kh$-&vg<&uLOo zI~3ir)Z_RZWN+<*OE&)ME(sRvDQwXxPC=Bs995#ea|WiUv-9PYrOBc@8ux*@oVB&X z9CR8;#p&t^jO{Irlc_22^;{2FtiPas+Sf*LidtxsZ#XdLJzV~|C+T%)GrG?km5NeD z=mrD0E+1Gl=oDoMx|%zCUe>y+Ih%AI9KCmb+2By%O6@^_>JoHd66G8s!wNb8ht9;S zGNo(Db&DV|7vz5~F>W5V{>N?h5iQ+J>*4cyR2tWGsB0ch7!C0hT?Ap_=G#q`S1; z{I?DZRpGW{i7)5je8Nd|V~HQD+?myEhBBNApaLuo0*Os9b61RKk&nEpYk12ei|*`o zLo&K8of`oNRJ2=X?7ot4PykD`aE(jv0O-R`-;9zW@fuDMewZTuf?_|NE%-1blC~Ye zXB8r6qcVC;PMDEh=+Jo}Y0yiVgtPh#%;wK7n|%dIXJ;Rxl2uZBh{iCK_`nQziLqIh z2hP91XnRexSiG1XLLsVoGA=Od&jqU(dO}HLs~Gc1p6{*K&dFXEtM(cViBF-!{8mBE zZNJomj=IQJN_Bzm#~9A4uO4VUAD*;}wlSX2VH8amfFm!DotG%*vc*-R%MS4HrX!?@z&vjM!Z{5m4Jq!t6KG&8G34I+A-R}V=nSJbq|JjY+zx+Ol`>Gth z&j$~Ww}5|ZgW|xk*Fip*l^6QFXN6+GR^516Q|Qd5PbjD7#T1KVzNyuUBP<5BLaBejkmA!7CkfHIy^{uy?s9|9dns{k^zv(a74<;Pip$G?JcR2&(+N?a&n2h#sKw|JWjkj*8H z6|eEe>z;|X+)lK1{bxCVrUSTCO9?d#3@)DjR{%YWGL6^0jLSXzOL!Y*ot|tr15cR& z*@@jhv*f*O&N7VgUdpvY-d;x{KmXh&0p{7Usz!(xHUjPHe62nv@iZa8%(}!(rk;TWcjoI+pQ@&k%*R2<=#e50oO-bgqBPG@W zp5L@iDx+lV6Q4Cljcs&PUAQ;k|M-ip7Z7<$r2DZQ?0^0uzJROPC8Kg0DXsJAap(3_ zCZl8mjoUnWZ&U+H)_raRY$k`*MLtjMidC*u43jg@_ex9Ju}+nt1;d3+AHeVwulnPf zW3kwzL0FRDhI6^qyx;FE%-78z=Gql-p@ap)2{R)V*gw9h`P?te^P!xgzioVoQIPLv zKh^|THrf=KwwNl)wuu1aem_n2*J}6v=J%+JL)dySTYxWA8l)t6JYSBG1Zz$vz!zZif4y_;q7-Lu88Aqr~kg zdL`FHe`XO>2VvVE-!}X+wC$v~O_btQr7$PJ@8J?rJ>a=;*7>V&rpy^787E&AWnQ|G zHkLAmUyBQs`3?dn^b3UGcu+uespYc@ZCoF%4(tpeGHCY9kJkoZ07l(qB9UOS7-M3| zNXUFN>pj6|sWn$Yd@*UE;3~KrUL8>A>js25M~yR?Fw47>v^GuGS;Rr#@Yg;A#mcn- zEfOI4Fph!3tL|2uFP1N^o6dwOsELiz%a_I{E6~fF)1)bgSswbMnc4KM&<%D~49Z}& zMR&T{dUZcb$$AX|zh1gJ5HKc3AAJn{S}f|s>0GT{&+$b{g`fv6<(JTV6c?|FzS#K88^|llTvDyYb{O5?fMp_g=^42nJWwY;kq^rjM8~AP0!@|mpA<3_fdN^ z@=oz9?^X~07{EKAHnnfhdisM9yTr48GGbbXLZKo$d{ zn*F$RkK|$=(Y!9X|-pi^kM5Ehzmg;+p2}Zxu>A%b`32ju;^( zp%M@LU^EWN$Lr;kAnC6k=^wLH=wuXwedj~I@!<+l)jj)*L@~l7935l1v)tXxsQBEf zxyzl?HhX9TDo1FxSP@n@&y}6gr#>uSwF$NL_tE3iIoEuHg`YP^Vb$Wt)v}4HT%b2O zsoxW@J|F)W?)!E66J;b=ivq-gox4ok618+dbnqy75qd-uW>u+4jCJ|G@sUO{2~F3X`Z^2?sX;t;g_LE%|@96-uEOyRUgAWbYayVK&X zf1Y3XpNPq4F)cET;OXf^43=*F>|4QCBdBv^YtaY#|LF%~fg)d0V2G|J*3F)sbKo9p z5=pR6m`FDg-!!2yQRt$pEj)#pj!09Ml6!GA=-dC=zgX7gQu89HJ7DiYZtPgz3b?T?Jru zM}m*JYADtMie5NniX>uc=P~VW82e5H$m-eXyc&pr?lcj|PX%7bRPqW0z*k3`G5AKr zL6B=Iia1gCf7ei`A=ts`EtFXLC zkR1pPt_`?siUCIKr25J%G8t5T=yZQ&@J2D9?m&uFVCkeS$f`l$>ED@16U!GA1C@)4aK}b|Xi9mLi#Z5?6g_7keGDT1eOy>+wU#$Tv z-$SQd)ev7FMdwbQqCF`lW`=V)Lo<;mPP)|}w4UU(ilEzYog|MoHyP4i_CVK*8E&c` zh>P&%D{4L6woMw9x*_QV=o)cpwyc#)B@$mHp?!1Y&(s>2Z?3}SkziPDrWSh^h@h%K zO%WZNL*xE_+V`$3j2Zf3a}xDRt>7B|^z7GtgG`~H#UPSd%4xNI3NK&1R8Wu4<3ph1 zUlP%Ws9Ij=FE{!Ly=Uzj|DSB=LfjfipOcbw(EpY)G(&p!Rw_KCf5hFXMRgp|Y&1{A zkk@5s+*(M8iBRg1pTs1v{Ev847^)5BwP!;v2qJS#y&P{6*ue5BUL+KH@6L8oac5>! zOlwUkVM#upJ6fr_R^A0GeW32?#4jlj!}RokCg(Ez5s9qiOAI6teN)m?)*o?U$fR9B9~-#BQrSLGZHo7JU{nlWhJ;5HSWcoO)eD&QpTRT}!W$uWI|0 zh5Ea>anSkE?*o02bYTqjp z5x|An|8czikAv@0ct;k6@92$|u|tS2Bqhs+X^i3AxAb2;_V<;KO7?ME>Ifnm1J2Xf zPlM@+EqnG>7VGjA-;WlV)?{@xa2M?_ijW=OK7Ym`PC7`VW_EAW@qW`-sder)_wCcy zyV&{H|H^!>UqU*-7=SfcM!t*Xo_2r8IztzlDhDcB&znLQ|ED0n>ET&o{-2R->27;g z5~mH3+H}9haV@v)sc&ac0RorPja5j}anrd$dy><_Fn-nn{A;5PVWP0KKapF4W}Xi8 zTyE9TJ5ky~4|e#5sHOlcGU3&$W3~3HatqdHY3m&tXoA9^@z00wqt0Oq9-@^A5&W+D zGvg~BpaPa{(o7T)|j%p7py6vOd;)WcDc$e8|(ds~n;iIY|e` z8&*ZPrS>IJa<2S$DHClhHSy=!&XjvU*h_s5v_;XcI7wH85l-S0m|h>OGifSt&f1)2 z8!^tK@~$e-yUCYb(0??e!yMeO18++bQrY)>oHU|2=HH}tvvClrQmraV>0AZbQ_pWw zpeHQ(yP`Tim(33+fDbDaEs-09RCbD%mdy3G)|24R!1c=!YSdSiDnj3Kv*q)&%<$|j zjv}=2{g(Xa5ocD!_^P(N96Od{wsuWB3d|dnZ>Rwq@k_;(I5jr$`-!5{0W8n+(#fvB(@!MMY=7OB;)e8#UP%NZlW4F%UDwL03?&7%Sq%6eSKI?2)Up zQxr#m{SSMLrQV9w z3Af5oC5uL`j0R9gqiIdw@Qz4mQ9~=?tCoDtf7~O5y_$Fi*HqO)L#KyMJbVx!mw_i`DDU*~J>g##wPe z4)TR#6WWCTuLsKW>^&AK@NDBGP#`1+Q27;!%K>A$hTVU zgGJoxp3nP^V;175fys2Jt%Nnc9*tXj+Q&Pp@GtDe$XD2T2re8rVG?S845}Fb`V2qn zZM=eRqcY(rvVwITwVgW-*GV?vSl0!~NnG8(PsS^jY8zSx^-ooWpfkFNY)hT4eZ&4R z&cV;yxz6y%9UI$UHfVCWLize&M+Bb_9IeifdN}4q2rBWT{I`290HAe@=v3$FRrlxO zSM$tTG!wEN3bKad2>Dj~i>Cer?wMT>5TY$Sqq1`hj0`bT<86M&XyR=@i5|3#kx&Ia zHIO|)$fA(|BA@~!2=?+<67W*gSp?&=^;mW$bMci00ByqqwGX;YZkcl{#Z_d$vF;GE z8w#>wr(XtB(s-vQWzMFJPc?@Vg<*C(%*a>>-`?`5EvxnZj5UaW&Ym8ZK`w7mt$tBG z9x6bifI$Ffty6enhe?4>3Ci-=#^MMc>`U6*N~c`sKYt7U0_WI9$X>*DiL~vZzgX|A zE=p%y`K(C1Yq8T|LB$QY4)eN|_d3=FQReW9R9DMw5dQR2z`th1AxR=wjpM3&)@F_ z!M`e>?Rzn6L4b9wld2FXBm%j0+g5UA{qiKRU2%Ys`vW7-6GJ_23whd46$nDs)d$xh z11PxN_p1Y>)6sEV!0B16T2umQGCBHTMYVUaVy!3|fAe^v)8-N#>1_!beJ2-ce zVetN<f2Z}YuBi;b1oW8b*DuIC z^vQ!?qWtVoq0yGrMf4`aQ_9k)d6l^gCb_~HnXl&9a*MJPMf3;NZD0QXAlWR(`Eg+P|ugr`fJ@01wciA4vzlb8Fm;|E;KUJw(iG&EL3jD6G z3CL!x(6&7KAwp#hPUJKC{>yO36+rIMY_A}Du3IW>e<$yG-#>+~LNo+*uN8*JWfxI#W&7cZqI`e-1HT7FGELrE z#tGDR+vd^xL7!xu%|->4Y!WhxBh_$GMB!hsYozNLglB#Q5s zgnCuJi9`huTi$6A&{N5FmmxN4Ytaf??jUQ)(z2izNW=@2zvU}^&i(_nToCl@cO2{- z%60xO7NPlH#sBmPRd9U^-CLBC0?0lf68yrd-VSPi?XNZnZpQ}gsw%`4PnI%ms~L#@ zZXV1S8Wfo#;*HCfTZ|PL;cYt_Z1lhFR0;bk2eP$6IKK?Ote0p}@z0q1lVLF=vUVv% zfh>??&*e4@Z)_K9Czlv`d#47)GD-z)-3Rv-{tLU8loA{gp~~zhA(FF|5C6zHtN<=% zn;c#bS6K-L4li+D_o;C2`6NqHaNW0;!pm#_acZOS;txUD4f=Sc5ZDsb#1fN3AtmIK zw}x@NnTi^VwI*CctjfbH72$B9VQt)&e%M!lD?;`GcL)p?bz z*TP*#!ymi(=NgCG5cIr>w~Ws(E!|_>U4(nL)K{BFd2A49Mx*&F{7sI>5>oPWT-%t3 zL#rsNrYZDwOY^G7WAC)I)y=nXu%s3Z2bJx)I%_hF{=e&gO@qx4$bAE+bL zJHAiNXAI)gb`m`5i}_YiYcShe8nP?EwU3ZZQaE*yv1X6_SSx;nKN&8DnwJR&bgWa3 z@hw$GQQL=`$KCyAjL!L%*$??8Yr22+{mZFM=-FP>kB`yhMKk@S@IqZnNF4I&Gcw;r z`v3M92l$==#sB<8v21&#RC0c8Pryram9SEQ1QPKaN3~owy#|tR7u6q<|F>E?#-fHU z=#eq3Cg?I#4tkz%kf-b?$wUWOK7140({E7smFYb;M6zg7>UYXJ7Uz4Iw4><-mM#DA zFza?%XxMZoYtXE4!_|+M)cs`%FjTnlFRj|NHNbZeN*9_|q}&92jH-8F@;o(|r& zfUh?0f%~MRj0@P>({C%8Yob3$roi6ycN0nh?1YA_3Z8!$Ad5#e&Qwv4hJfFTg zOF)aGG#S(qWgjTym}!hA1X-kYcDo@(31GQ-3>*o0y2!0JwPOO)H1jb*PpNXK84_5v z3mW_*NedOv<=R?nGQBTZ)&5o=!n4!;+I(v1C5fZCh`}{oF7_MK z5{&$nkK7_)Z_OCRHvZ;x)spkN$oUiR+F65^4*s(ld6b=vch`agG!+(5^W8}i-Y5f* z3W4N_ISMGi+x; zdtJ7mUh@>FGPMW)L>)n@8tUR0~NS>46cOf|Fr z-0Mqw^ymWiy;$3r+5{%soyLp|gP^utlN3`2Vy=XSasl!_$-hv`3Oo^J-AeDB*PG&)97+Yk4#Q zr7OVXOLJopz09@wc)#TSaKmts85b(;=+Md>X#ISn1O>S&*i5!#EdZQ27@ zrZJ*_{o!M=zAJM_vQeYrs89THoy3aI;aHxt5xBurr-K2%jAO>+jnSoMRUAf;$y9Oh zv7wnN$(oNt0cm6SstlDN$;5H${LGhBn&4BzL+;1w1MgkcF*zYVOm*GYOs!Rl49XM= z0~g+qr@e96Wj+GO`CXV-^A1!`hX#- zos=c7%SdYPhR(uD2;|II;4%QgkXsj-6gZRQBYZQci^9(wBov?4cI^N07gu8>P;#>3 zg_!A)Xl~OAygAunnlay)`Dc{37JzbCAT(CY8Aa!u+|&(6Ho0aswS=6!um?wuKc=XI z^*V6J$qz(N#5i{>`&fB*itlCQFiYR$6iV|mQ7z3Vi;~rm^!}Y=xz5sb;>|7o6mTe5 zO{wLkom;Zhb12+dtmWKQLq7+Fixh??$r9`mYzrNUFBEGBw&j+e1-J;j==`8j+*wG# z59N7Mz)Gqb3;sla&B?w~8-|ys`Fb`9*SAT5jtrC$o5Ms)nyj8&p{Fb5qGLjY z{F-`)4?_V#!C0#bctIV>ZVY3ndv$am$fd=r@ZE|6EPhrL&5HCIHeHM_D5{UO#Kb^U zmJH!^*E>89+dvPcyQ3K4)*bp%Q&e2QJZA9z4tNY!q2C@h-cX~Iv@}){Hgi$3Y8u$V zyUzJ>kV>+8bcs=Jdpep#j*xn_%kg#(#YwIu|Gl~*-qZueG;1MVI0-7a_-e|bka)nLdoeIWHYA4YS~n5QsOlZ|R=s5fSwP%X^4>)fj&}w22BlnHvF|d>Ut~Y^6nBW!lLSV!% zyBRFdO^*C$K^e?5kQ3jLi2Vh{@qvwSU?>SJLbFf4E7k+)OG?6A zHf=YoreA@g$oUDf$?l7ctJCqPy~qAWm3T3whz=mUC2Y=?lAjqZodga)7&DoG-n&ou z6@2`?SWU7oLSmSIw`FP1HS}$`*!+ruUyo})1CH%}E^r<#zO(yu(zXFpv4GClnXxioQ7#Dqt z!^fB}`!U&hzd@DmTkencu2FTyo=7t3oOE-)^tM;6;Hjn|+;gH6+3K^jlabX+&Aj%9 zH(a~pXuqAyOb8dLpzPtuhw?;nof(FAT=;3g`gJ zFuMio?d3bYiw4D6rHVd6p|V+nE)`cCK-5nJFGJ&WAq0iakIVjTfmFnFJ#X&jq*r~y zc50t~Sbhro75IV_WthWEc3Kw*ulPBpV!bwiycsvxa*Cz0HI zYXM4qBc2rAY8k!H#fi=dc~acP|4NYZnCUx7{m|Gid!L!HjfHmt+66e{GB)k@J^XrX z^8TBJ&vNYTk>U-f7$bLoN9x>+obW~&I=q9txG$1VY65B^NhUb>=1!?DZlM={b$M6C zd?L31^iK$y3w6|g=SaHq4?^C|R8V$i2F3!EeL(FV%>_{Q0&JG`2c2{N2|;`}hyHku z#=wWMr}L!GNc8u4aP^WQYT|{D)(V9WTHrjE5+e$^5*A@2%Jz=zRP|z&E~@W5>U0*4 z777Yn9t!heH9ZxkbH+31c$oCLc)-E!W(6to&@Uh3zU0Hh^Z}q{G43WnRNqndVFO(z zgd1kTk9-6OA1sTG4KTkG*$xWnB`)P9AsZvn%_#>jl&Xh?^act9;$e#F5$o}>%w{oH zBqW+wkxf+7%~q4C+d|gHD7MCFlkDdA$9xa%sF90W5E3BGX*D&862qyttfeiDdp(tg zFQJ0(Q_}_6OF|abP9nk!0`zM6Cq6(h0T<3MVuKpo=Z1rj8E_N>ei#gIVw@Z_fx5;( z9$N*DV4!uKAhz7W4YMV_Wx#)C?XF{p6UIm{#=)(Z)WuE!v1;SkYSh665}qy`L?^Ku zAq(G_XN3l%7?j{?du-YF%6yJRQj1dxLUX)LL6!m`*`dpLjeC6fKZ{VF!cPto_Mb&a z=~>O#s}qvM@Z+$GiS&|0)CHBfiu3hv&Q1ZYUO%okU0f}GsMj#g5kKztU2C_o+$}_) zC;7kTIj6^2w6vO>L3U(-F;?7NBIN&33Dw7e+%U4yoqu2y%3~tHERY#AK{~LLzKF(J zAmFRNFAKB#QT2t1{;Q_^7w)m&*kav+(pQ3Vfog!1cl#1aJpEYDLlb= z?Ne(a*7Yy6)42ci?Fk1N!cKD_mQ^&?c91kE&8;2%ST(xuZ@OR4OyLftpd2kuO;Os3 zKsP%0^N#Fb^))9kR=vK!*ca>uh}1iOsrTJd|0QPyr4hu~*8uFrE9o6#`96RQ;w#S7 z34w^M$Yz&_3NNp?5-s{`Q8Y$SmmNjO1WK13`Pw#a#5grK4032oM`Z^o@rP98@}s@u zzfuAEJU<3+NsUfPBoiukCj?XTT2W6($tXa{tVhXeQLz&GoF`Ut%Tul$^OUJp)(XIx zbikR=mqo=>{U^v8J|TO(ql%27zutk%Kqymo&Uoc$o!bi;p!F?J*&#rAy+^A>i>d~y@(xDuG={S(DEpm=_g{dlFQKT; zE^1npZaPGcLjaVsLm}n|5n`bAQ33ADZSF(qgsLGazu9w%G-Q6O(*Y>l>xnDoHFr7; z1W^D(@>+WVMkY5}W=1NtW2Dc5c`tx|Jyk1AxqSNt$j-^^R^?n+wKm8E zm6UEt+u=_w+HkdTg0D+8krpPQQOn0rtrz8)3rkIKWUyAu zABXB!A@2}4riP)VE1|`rk>d;QviRYmOhCtKV-h*O*MB@VMHzMTxd!^fJ+8wSguk>g z;8miv(-!gS~F)C+rM=idr&==?0VY+!jXLEJh>eZb*ox zlzO+>Kaauii*(FHrTK%VCxKAmN`Z^mcG0*-pSZc2IOzc;xgw)+z!+V%l1CuR zNw3nU;225@0*3yWZ~afd`uUC_v)AVqFN^$ZS9^Oz8AApVO|BD7NZ;kfBz^U@wh>BR zB9B}$MY9Vg@D-B~_$@0o9@|b4H^&&=U6VQ@=BPyO*blK_j8W=^$y}mEvddz@yyCb|_hqtT)haPZYx3+8ux`i#fwe~ist4^uR?3O zCuZudWXI%E0}E3BeXES5s4@|bz^2M0l&Fq0Dmh_=r~uPhtZJdG&@oTey3b3d${)I~&zC3`?jz}A2p6Sd^r6ZPEK%0;Bvt-f zWoA@O`?txcB->^+y)dlRrK$Po89Iz1&mv9{yX9&K%WPRwLJrU)Av=v<`J2}BT1*C; z>d8tKW@FY(YTk!+#Hn}SPT)OfolYT?A9hgrgg|sD^@gvqRjZ^cx4ZZyyM@EM#fQ43 z|8>8h#<~VzL5F%O0rGqnIKL#YHP^ep<$_pCbM-mO!+w7qix-mS?zDbEXkQ*2R6H14U)P>cuEL1iE;`8U`pIn*0I^d@|053}Z;b>N-F z0Imf?7m$ojvdiD1AGf)yv#NJTa#X{jN6lhX_@C?d^^m!$(KE?zo6->z_YojXKSo49 z%g`9%$(Y{z{&!)+w8N~XpXgr%mi3#yl3c5OOHsE%@~UJz0O@_>a6{EfDN%p)Ejjw% zxSkYqnkU(A75dgQa2V4-n^`7#JHcO;xszuEq`-+~){&&NQrKu337d&2HXi$DGAaJ9 zaBU`xf%X@WHmn*$C`@2$Ep;zUNl%mXDV88B*fDOn{n30T^`SkpOtww$eRgPN@amMe zRIYHD@{u{qKS5*33 z^xKf($j3F7z7=H2)Mm*ijmO2tZ5&Hq(u@$F;>UO9cT33;%wL>zi6$_fVi-ed*H5I^ z&rRnIme$ud=6fLofEX35>hQUdz~0bO?26avC&qXa&%Pn0)W{Y?#a&ON!<)$Yo5!j4 z2%ImMT2rRmXA!gSX!a}1TTtF@;!lvxRL?T)%`$Cy#Eh)RN3QDiyehAnUI3`v2XC8E ztSxK?)ZQ5~|&hAich%|ve1z7@p|lOmvy#w;5nWdUBxS}*^hTE2M*wFtYB8@ciR zd-F&c@(#*!)w7Wcz;2QILHzwF-1=|u)+OO{WF`9ir0v`a`8#pM6U|17%u0!4E>)p2 zQ2qP$>!?e_T6SmU@80Ms7ApquW}MP8=Il1RSmnLeH8$S&2cZ1ibL18K|MwSxeDjE^ z>d9mhVwp5k{#xaDa?!Bs)yq9aN+i-TNh+Dh>AB`pe=q`5uwl0NKYuY&dm&Gqb z)h_hON@~&L@f_ynFZG(G5|LQK?qAr#Duf7`j_2rw%qtRpG-|$D?NsjsGneo)o2R(1 zsC)hlVz4Y`)|yIRziQhWiTL;T5nGJ!-EdeO9;xO$yM9+1wMP9bv~*(`hZ3omyRF~Z zrppRTXp=&I*(^k-RFrMboXsaXa3 zzDf(eo8EuY=Eyd^5CER4Z45e+t|<$qnBH$5dL?~4Nn!R#sA^*GYo{d}FQsZ6`FHb= zT~y4C3Q026W8$_vR>O>aD(~pPN{Zz3CsU8+Gn+ER98&h8@w$>s)CFkJN$1MMRIBx4s-F(V`U;xCz;uVtLv8rnirh&x0uKhBr) z)wsKNec%lz?-FeOOWrbsa4(Nx77e-5fM$B?uQxw9X*LIg35RrtqPm2<-;vpH z8;k@!F_9pG4>V4^&2jA$h;`8(NFshyo_;gCd;D>M;2%Qc*R3*d=AV){=l1^G>?_r6 z0SPaTr%WRHvgObx->Z~B-DO$ukzwNWGC;1@$X}kQ|5$L&I(pM(g?)2L-17 zM!cUv<@Mg|TV1x8iwVQ;k6l_8-RvT(QOGmickw{0-g%L}uqAj*(zxlm=Iflp4ZS## zKz|d5$a@_#rk>#ckF)#!YN~zLML$VG5(p_20Rbg|2#RPBDN=*(%&&3%1 z{O@*c;gLoH_4BRl?p9u52$4=ST<>X z`*WIJ2+Mye8gP_fcZd~ zlH%(cW@)i&g<8>mQk@~_+HVloeTB=0TbJ8}`!-RK&I{I#kylr9J>X)UBOn$Hkf2YSdj0ej{@GH)4EQnbqLn&VXXPyGyy5fQ6}Y z;A|B>wY5O-SXX_Bs#+=Y(m?y8-X7uWc2|sP5Lc(eS{^>uO6~Bn&@iPT=riyqHUXEvR^KNLd)gJus>*l>Fg|v7OOQ5B&M-euP`?-?~z} zkT50|tyH!1N(rID1p}AANB zoQjAgAd9OU3z52&2d}-xf~nLB z0(Mj%{b=rb^CBTxql3?zm3Qpv;|?o}MSkkk^U9G~Ht2mO%gw1~D z!2iez7|2^26UvIow?kl2kn&4r#JD4|U2oK?kpvib;$X0N~B{|qxSx>fVvvYNh)cbPe z)-v9@s?1C=3Ndrcza8Ydb-bGu2&&p1Z&vDO<=ZBY&P8a4Sl=y)cy;$Ah#9by6YSJR zJCEi;sI7v8X68_)*K)Dy_)zJg5t<-=5Xax;o(pU@AOE&Kko+;ABnUSJTom*YV|{5r zNpbacgY}POLGq!m_>7^msH&w7uQ1yr#bGb^TMmqY$$M(yx_gym zrHyl$_w<62Sj8lA(_{bJ^!D3^<`uh5$8mgv@Z|ezz?NmOf$0UvAt0$X2Ox%jvM0?@ z<7jUZ{Zjzo*Mx$cK?gE;^xN2_xs6iU_VP#XB*tn)Rj!-`I3*e1L0_|P8Zbufqzw4{ zx}~gug$fN>t@$iTEgjy($nE4He3un&G>?#DV|EJ!d{;E=o4;hETnmi@e+cO-h+PF7 zR9L#H7d;f^qOdW(>tK#sSolA!wA?3VaDW8kp-rH1#V$~a9z^;!hwjGan}4*p+?Q%) zw}zR0Jia;9Fc%;lcPQ&0H4QrqGsE{e!cuS8C((AUm{zpA0oM9_l;e?aR|FCV7VaFblmOBmSKFf_g zAO~?CsQ`dXT$HIvCN^1%NCp2%26igpz^ns?&ynf5BP77FxX^uUi6Ayg;H!fF9fr%} zjcyG4hKew*Hux7K@=+yn;0;l1zM>@Xp5pBKmmISIEaP3uC!1J3wF1BNMFn-|58I++)U(| zS=h4>_WZzG^bSs1?)=zx;~ z#8Bq2rIhF#>KMICF$?^$9`vzXA`wBw(W`yYeT^|kdJ>x{%6sCm;3mdjjnTdy(Hq5a zD`626FWn(D@n8AletX0&r$nvy#UVZ8&z3m>RdvSm@m&3k*wiQIQe)XBWBFGUP8ws^ zf`u<#Nf7d6fcD2kwPu9HpPn^>WZzz-8f8?TS=Or zO62PxidvDAlv5MMt>Oh%63P#f4Ex!%52G%ZBuaX|q^txy_KfSDkB8`hcy=sF9uvm2~tf7u}UF^rv$1pKt#n&!(a00zp_kyrK3Qo;l!| zIoY4t)s#6+lht;ZIX9X9>XF+cQ{bi+C|p0;wIgfue9CW{?4ADPZPo03&*Z=1*~eFs zkNU~kKKh`WTmD{8t!k`tU=cYKa1rq#2T3Vaqs=YSH;ATwRUs5*JeidDF!!xvZbdFY zk&bMXvv``*8$}_PB=Rmt5R6ka`9cwy6oPTYD*uui*bZ;Sl$Og;pIbJP zDUCt z4~r^@3j(%4&2gw*9G$EdrU8rEt3-8RA+Qn9@)kOZ25`zj?qg9gl`KVRrDfkrE7;0v z9+x$wm9;#^#E_7GD^Z-H;V9_S-iXrD52cWf@@lm*$kVdM(lTl{6PkK&03ZInl%;R= z%>ZrLPcIA@M@JrZ2k_udJbDd_kY+3IdR#u0R{mqPbZ503`n2LeBD~E3wYP<&QNeVo zmG?X@Wf4foBB4CAz!Coe2jl4ahM{r}h{ahdNC1t47T6X;_shhenu@M-s|=zI-oYW{ zb7+oCU|zXZ9BWlrf$B>()%<1E*Vd|W>KKYQ7&Q!5kArD%lg+h7Eo54%E*w{JNmlcE zS6@K@0^h4|*!U}jnydAg-<7D-`4#H;r$$ep_Q{i4BXvwVzQ#8hnAW1RF@dekx&jXW z#z5XIcI>r})oTrHFfId?fCEh}1|~&Jda&4omv?rfl}+d;|d1YA#A|224P^co@9HDhmqaJZi~M z$7CUz^VFLQy)ngQ&99!Zq!e1cKem!%WvOpzZCq<@`Q8Glf-VE#NE_HOAs`)!&Vsg7 ztGBp!v;m~nrsGy>q4ve}3aB=s2T#Uq2v~1QUKJrA`d4Xt23R^o3>a5gvf_}GCPoql zQju%?c%MaxgxJtRPv?+)sVY8vV{yRHtyDI0tSOsj0|1(opmcH(Sf$t0dnAA;zKa=>9XK>FGUAf z(*YEA&u-5KKsjF^r2v-u= zGY3WPVVUJMTCgA+`3cd*XhGDmbV`w|55_3D6JN9NkSiz&{=p4offLy1cb^l?grfdVFyWFXcE$% z*bSjaebc~D>KXf4SibrUPPPtCpA61P4K04``o|nJf!Y6K4q6Q;W2}4Kc5DYH)`zCn z2WL;vKk0lIY=?|l+|1mwphy7j%d-1%c>iShhz@ATX^r$oFiiK7hif(rFk9C?y_g&M zyN)@a8)4A=43X=9_zLYx8v0EKTyMLUfkXM``nK4F2h4%U04%J-GDfMxmx_$&n`Qem z(CS~+2#!N#;4!==XmBITZB5KCPt`~VRHOqWdKeXr$JkaPx5Vf=0TS;P7+a3i6GOD& zs@@KK-sJe?E;sfpddwOL*lvtD7-F0>$Mu$I$fPg8Ea-T+hHY@f@z414%rTqkv7@aq zN9pknt#JVB)BW71ugJ&JeRxoL(!y>sP;(;9Zo(6bGP3#1KTUNN33#7=@y+~3@SP0G zoJ>aom4e?75r9%9sz3|Vh#dW}P5Z@%#pn660%leUJ7{p3^{mI6@CR8li&)D++O&|O zPkj8U8Y$)=Q3Dfx^0iwN<3d6QUzJ$GH34|qZ;_$D9*#ok$prfb}vuyBN6N1R@4=JlJ>!BY^mOq5M5B0_Jw@ ze$b+TZ_0>WKL29}Isn%f;xhxji_tKc-FY+jWN=RKqW{qr8kgm^I^3|5**`!r2Z0&K zIqL*CP<@#dilNgHWTo`IQ^8pOr*JrMgGFfL%fhs~{T5o74rnKguSH|dgVGNB4XKUx&}xn;6|#Z};L_a(S@?3s~|p!uY%>&y{RFeYuoAhLW}X zVdJ+z_%CTz1Z zM(>Q}AdZe&8!>mr^76t2p{ns&%rEO9mfM3s7V<}4K4O_v6<&#|!eb&R2xty$VG9AF zXoDo^t*w8w!6F09nnu$qpyal_5AElCf z8sT=uEcC|UzcHJ727k^_TcCSeP>z8QyUJ zyuniEfar}em{`ukMD)h1*uykq3>N|Mdl>aD zPA z?j7a4Jubet=d0{~MHxkNqmuc_Rf``8A@$J-HdCH47O)m#Ij%FHBk(#rh%kb9fC6gp zABMRJ{2F{OA9bGc`6fo@mE*V+V=n1` zUQkWC^6;(s`Z`vl!@xLDWjT}RzzWeyFLQnD%O5j~VT zG`ST!azCnhc&;Sg((qb2opibWj{O%lHbA0jz!@^pNc$8PBk27K8f3Ec3hRm;r}&Ej z)ac6w6I)Na9lsawV@%*4Z!3 zOdq>%&ApH1GoCr|++F!v@%+cksrSL3#ZN`XKhAtl4)->fe*7T&17IcxJP2`X3lCv@ z;2;NOciEDI^CUUkp%tjzx|7M>=^&4i+})B#s83$zV!a6bQDD0Nz)|r~!Tis^{$fuD z-IjTVSEDv0SE{?JH$~~}%F`T$_9h}n0Mq03o4~D6O?vayerT9zb^P;`NNDo{yEmyn zSP9p~Ooe9aB6`YJ#IBA8+Q%eI4Ac3V1u$8G=ISmlgs_r>%@3b(vCy;aCIm1a z5@P}+sGegT-?D`zncw`^Uv#Yq^Is5pbkV1p3P>^VD7eqAgZT{3hA>&X=Ez+Eo5c86 zyA)giqz;H#W*geddjI%~)2rVO_)wfb_vAt?(l7AGKF_~k`OTWKxn4Eg<%wC&*H8#4 z-W~9m<5XJM%Z0k}yz(%OU_8z#3Ne|3a_MR)x?=TP_4^XF4Uq@g0aW}R*kITl^mMa>A)^jxICGqVg{x2S%?l@rQ6 zZQi#0eVj`rN(IYy4Gow#;*9QJ$ZiDq8M2*f?=Dlx7*8F-go|hjg{^~GM}B3w#i=gX zbRxv2Z0-%+_HpcCcW=$t_%@px?{4II;`C8i)`xkrlS`3mP@W~Tivawuq@Xf|6g;9L zk}2oxjC^)_MmZEr@V`mHGYTg7e^&*`2M1^W!2}NvD7@ei#TPs{INIMQA8h<@u;9tR zupoJNjsgqr?QHGr>}*q2z~GM`KTfB6PQH$kzh{s~!)In@{{Py7{YM}Bj{j8!kNWzK{v`#EJG)NX z+bM?Nep~zDK>g{*sN;@TK2&Dgg>gNIAO$q}|@$v7w=z*4F=c zf_;5`6i={&a{l!M+uGV%T3Q+#8!3`tRaMo$l3)h8oS9sLAQwT&g`oe&1o_WOSf&ZH%n3tEAlaoWi1P@Zv_T%Hp(b0dRWB!o@V;;XtO8Os3FflPPK0ZD= zI{H77U`R;FUw{8255rvt$3ts_c#0$F@9*d5cV?`4c3*?6Dt#t}TQ@LVSJU{Zpy=b{ z!h;Rr#<7&Z*g z|B!;#Q+-wckb?3N9I6yjFp>X$sloZ`IZz1B>_diXP2pg=xbx~%e@)S+e@Q{L+TxLX zm8W9|y|pD@inQ|8GS%uzzn1CMSWkbbD;uvc>590ZUSB?0V>)@saG?Ip_Xdag51Hx> zZ>L)jlP6}0K{}{cSB}r9qjYd{iJ|CpjdG7m^F7?0lq-Er1x6em-`R@g@@keo<;X`~ z)NHO@`BHqp%xJK=Zf(5MY#>XsrGDdkquDr4%iSs(>ds~^3O6{|3Va{SsPWbZyYuT) zF3kQq&gW? zE#U4%2KEzHo)nJj;h&GXb(X{(a%t#gehkOwr8%PX&$@gA`Ob&t8kfh4zeEqp<$M%= zz<*^i>A|B(jzs6fzZoDFmw!pYE5B0AW3Jq}z@1b=Aq4|V07tn{)}jnq+S^5j%FQo} z?x;S#&G_nr@AgMNKW6LY+^{2vrNQI7VgOP};p)miq~OZy6jQHmHf8hGm7<(SYF)s< zwCZ@4U2gNM(z3J5HcD5Rn-@97(mB) zX>GlVwc7-OeBBvQR95k<*IMWM#jk>LzDHLvl^*njkHSyGD5T)Jj`E8qomWj1=suh$ zfb3IMkDs|t^z6OSCNrF?B%QM9;}WXt5u_G(*KNA1w9421bgK%rzN%zl4UlWwM-c<) zS;XBdvv?A1H^O*}(wxfpl2aU7n8)k7ga?!Ge+I>uqV9iGc}jP)_u%JC$G(&Lj5qZH z&gr$El^B~`B17 z#0&&(?L;9xh}R`5(h=_)47y3&aS-9StHZPS^D-}H;k+@J`8e>)mfuN?wug%cr&+__ z+g_b92gF6aJ=uQ5h8|sUd>w;Xm+ilpxB;7+Io4_+kNV#G5%kV?p_4~JYK2_9%o*9& zICOHnmA%}``<(=i6>@f=8VdLQ$c%P16K9EnvU zql1IC5AFk>M>?7)<6InrC8ogipxh9l86a3=LLLsi9W2c+7yOVkA5@<&Cv!6%%&W%@ z;TopKrSS&@R#w`@)qX-)^|dgwEriy5c=`nLl?Lmzo#;5Sfd3{(!&@42c~~9K`KbTH zqvq|Gl?E0dCT?lqM9=}k)Y8^Uu%31W$Q1Kpo>q2Zd*a^X-%_c(e>2CK!Ug|J zx7|0Z`8i=G&zzTMg;C?OT9VBO=q(5E!71$vf8GOt`?n*6_ifOHX_NOb%pIyvtaF^V z4@eheu;f4<9}*?HvA70P)6xg+=DH)lz90*w#{Y5_+#+r4M@b;#MwjN}^X7CSvth3^e`NS?Nl+OnZ%rvc(k0p78bk4J|y4Z{<^Du_2gVEAFvjdly4OCbgwD_Hh@v zlYn}&)g$o{|9wPftn#Lw`~{Hu)K9kk#y-urPRRpPza;jXhNIuQ6sb?IK4xjoTJF91 zmO={ZBr{k%9M@0$i3@AmYh6CQf8@p;fGrO=w`R#F$3Yt$G+HCP|8Ys?`0!rF(f&IC zwIvtA6&WgXD{nKW7^Kvplg^d{Cli7Q(L#|yZ22A6H7&uz@igG!P8RalEBAb@A6BI` z7C)7)icp>Udag|T{dLhlLPt*{Sl=~v^If*_ViGkfzy&-LRj-I6YQ)vh1~F69bjWV^ z7V(P$gcrHgqD~kv@#pr1pqh*Db1;HIR2N3Zvg`8dV~oOR5WPI>drtbIMo|Y-GE!W; zTY9@U+zG=4Wh*Vb)HIp9K0)b2-vVWO{v0%ZBc=o{PQ!+MwB*WmWo_UOV?UdNycR$I z!R~yZ(DENN$msR}=aiGHk`T(LAc#dx9L_gJAN#~3ZVObO0S+m_X+M37xc(4$BAF|gs6{Kc~l+bccB6?Ge!g?5_| zrMu@M_|i5%FAPOBZf>v1Aim$-zDUb*q#dnlp5gsnU^mw*g9&uI^9Mf}#@%lZYMaxT zx_%D!xmQkRhb=9guW-3n=*1AD7vB@-{ZNXgIM<%UZs;lCK1t?|NlqT;{Ut+NFY?li z%4*jPBb7bZtN5b0fZYO|W!5>;D;2TdTa80!FE5(DDH| zOG^}t<*1jr&Kz?=oQ0F0z-8&^@swf+!ua6sSM)sh#e#%P!MB14LKDFce-hC9-i};& z%{eP*FrKy>kAlcCD9AC7+JHM~$MKl&SX!y7Abw#2BrMR4i{=!ITu34)cwD#|CZod2 zQ(_`=w~?p=3V~?{odYXr-co8bSF$WnvRzPefB;Sk%5LOfWk>*otYr*f!{r=8fxb`~ z{y=waU{i^fJ3lm<&-a@<5qDF}wToEF&*SHz%E}6`VIr%=BWv{{>sccWlQ4DN{!O*& zZM*6nw1~eC$fyJ0kFj{(C9nfX0D#Cmc$4CK|_c0Mv#V%i-NAT%@vTDF(2hnFE z5n4e3Y{TeZ9x=-)F{_O+zly19UDR5|(Lutr6t$<3q?<~u!}Xey!Rwsn)9i@@^A0vC zdR~JmUU}jXG)-PGPfS6M;a8_ek6k2Mdr z*w3@54}u@zA#z&@aySZ2n0ONaL`Y~G@+|a7E0NkNI*s3%p^5n-26;NHDs!6{{D^q2 zIGT?ED!9$fe*UG~NIaNIy3!+3FZE?(F{UF&quwPUM-)>p3?Xkpg@ouTa0t>YMG9(}Hia+~#Mo z3m26ROLd(KbqM1?o@cDljd(~ly}k^}{H4$Ixj!vfOth^jyr(47SqQWVrFE!|>mk}s zTJpwk1ujiyfIp+);+|Kb5mUbWoG?32PNy;pr}JyUv{1dPOcw!96YD&9c=pc~zP_MBf;C3_ z8?b%n#tR9KBb|)jO~u+|F&0f+hUeoV&Cm>i#sa>ZE{ZJ0mJ-DP{#wuWwVdY51D~(u zJ}!OAAo%5H>f>+4?^2myv#?VP(y=e^&1znfH8BL__6eX)D=o=5;?HF$?<~ENakIQf zqC7vZH0ncXSu?ZL){8>bvcYeDH?9VSes*u8EzY=#F)%Hip}qV(;qs58H^+J9Tesi1 zTxBtv&7pBDFlu)FD&b_UcHv2m=VWuqPK536t8bP+M0rvA0Uk45#s~Imv=256I+)?P_VGMND-Y~FPY&9!4*{MRjwbR_F8wGb{J*XTd4BdyfopMolB zku_{3)@$B}p8RSPbhsz=OR9BCAL<#`>g{tqjDa_I(yQm;_1oWSaS6m*9~yqGG<-~} z!>4B^rZX|m!q&ZNF4a zs`8fJW|}&nn^9^0bfxLhTJzQXW<&KR8EwEnu8KI&3@^jnibJexp{FXLo6nmE1LE6{ zTgJ+2Ys-oWYc(Iqk=1s8K-XIu-XFIymIUJPsQO{33?7!G7oY20axb;5h^Ey}pw)Jy zZN|GvnF^|is61j1p&6llKU-DPnfz%s`R{S^!9Y-$w=KPteFCh(prsXjLL{3&vgD|! z=a3bZh_yK6%VF2=?EFEWNhqJroYeaB<<&Q$m`((Us(+{}ua<#qTjBFe&s6>q49iWR zFSXE-T5UVt+#gc~u5!FYb2Lg!H49zqP>lz?Od4-TwLkCe$eind1fY9xn5wP!$iB`l zxh$Ky?%9d%S@!o#8m&TWJ;H0{et6{RR*vpTLw#A`q80-DlxEqayR|yoJhG>(xJU1} zyUV7jgKWb@g@;z9N7h8vmK--x=OSR&FcsLI?EwK6HuK=}h|s7^#&yYvjCV?ZK)yMx z?(6RaHA-wL8y*-)I1U{S^tIm1&o<~Y*LZX8=7$1~_MZbiI4bC(caB3wt*1|!D`nz5 zi{!N(X!%^w^pTir(A2IW^O~+hd5+2lL+V){XprP>vSBhmy8We<__eiO&vuY>txJC# z;^)v&*4n4$-O##Sv@{jGb6fL+V2+Xv@jf3D z4XPt-I+ZziQqn#N@hd2pE2uyyA|uMF655l~54RakkQ(Vc84&QrNDadtoeXYdH2x*G z3P{$Lu_1$=E2>>0pov%vW(?X+{LJv?GotO?mFai*kv``sv^ptH@y)2a{+E`(H@EHl zS8DGn6H-9hs8kc2i#>}H1KJy*B|8mS)@F7JNGzl>i4gFB%{m>pcuIf5| z|FzizX@R{`x^(xidoW!mMO`2czK_RD4Aa8qbTz5;X3k9}NKYmiPQLP;Ov#)~%QWyG zhAk6m(=U9>MH-z$4z?yd`ji6=l%9D0-DvZiaoC%QC_Bu)BIxk-xQF3G!B^jH1jk!9 z9yFeQmp?bvIcWOa4&)1zeIbF|Hom`)e$YMrz-PLsouRrc+E+;lVSogTq(@cB(!qk! zK9lR+a(}3O@qtQ`p4!Nn-pTQrZ8KJ{>E?aQhT$)vSd79J`i|l7kLY0<>BiHIALUbw z%sDVWeA08DY~hXg*U~*Kf;<@3x^2qbMafRh#11NkSj2ti-LO0L9afN@vEg8n9)=Ny z(Lyfq3wn0*J<}e44vI7(bkf%^PB*e{?={3Pw@Y}(;HcfeLfZ#B5ig`oZ z{&_BnF>MQ73I1{dmV=FB&}$^bZ5+li?w`enD1dQ3gXyr| z{^ptc3f-(MYN7DthZY^v4J6!Us%3TXC$gQ<7Ki$tBcVz{xRC*f69(0S#c+{O^>~O% zC1M53Ap>;dE1}(SNYEU3XNy+Jf#!&04j=iY8c*b7SrTp^sAu~*er=}W?!p}*sP9%> zW=R}jhM5b4a&`y;b3MQDM?(yYQQJZ%d%zC~H{3|*&Jo&a944XwQy9Z^{>`eg*pg?= zQaH!j2VLjlR#^WqI`()8Vf0dPh_P{tw$L1tREYv{f!49K3%m5@IIb~77uF1 z(1En+ip=p_`0rUrq4H&h#TLHeqWPbn3iEO8HPu zMF$N~JmhC3`gjXD0s$OyP?P~@4_z_T2^aABI5vEPXN_80bx4~Z5c+g3xnroX`gLDyRmcy z3_HSPw8#xio!!=Yf@fdOPieHBEayiIr>`7&ZvG3z7YF?^jQ-lV`)#IGRU1yuL5Gpi zCpl<)Zcq=F&R3phm2iUrhjyr?oiO=*2e}3AfP=FOZ_Dz~tyMbT+b@6Xa>svvp?AZB zlj*?}Y|@o3E^1Bw$AT~yNHy+Qm4IxDgCNZ4x^efwjx;N?5(q51?u6EiA9HI9{Q>~8 zsW)tBj%dxMUz2TJ(OsoKoT&cO|)`FF7E;0}#zyV0#_NUmQY- z0BPDnjdH_Iu(Wq7p(H$teSQU)D-GlIbpbdOQsTO08E7uZ1hZ=YRERhy$Q`_0ex4Zl zU!3elYLh19s z?K5f)y)Bc@5Xl){+n1$t!I9^ATu#KR7m8y!??U_Y?_Jb6#qX8dHaRXQK2lUy^f}@y zcwYSAUFd};f62CqCDa0!ec5W}rh~nYhXjur-UDVwVX0&Gw9ACRY=lpz7{Ym!I?G#d18x~ml*WUX|oNp5!U;6iD?BuL$)GQ0m8 zPkkzUgN-abk&nKf@Z_xuH2TuY;MI9^p{VC^a@c#CVqcSVvW`aIXvr(Sj2or=4WWA& zo3?C5cX*fU!B?~eQd?C@T4aREBC8|tzOla{gKi35I$^96>bk3Kp{jZVRGxfmvsoyvwtUu`~EV_b$H@J+4N_Fj;rgr=$nC2Jyh1uZ=K7tDPkJOU(M2n zf*i=yjm^(5jpNqXUU`F&St;!wrvT2>#-kKRx@tXv+JpukkY53g3Ckd%4s~By~fg z!zP>O<#X@vDNpl^$UFHwDv~6!ZAYA%AGJwKi5F%o|0*=NRH1K>*}|8v(dIGFNqd$* z7W>k7@E2nti`$HR^H$`wH133*8GYD=yFIrvg%jp`#bgdIS$Ul;j5oMTAI14BbOq^L zjxqGwp!x0hc~eZ0K6S7kX7cmnc>H2!q%YLP7$ob&h3hNl)Je;Fzvce&$;Q3==!viA zK#g+b8YD)-MiL9MYLKCJ>jwKQ2ho&=)*Xe!5e~avQB!V?L^uwIVs~;BX(wLqmQ)1u zoa8EggoHAvVa1q%+m#d?Wz>HXxxZqSfd0QQIq>6uC&X8G|xk3|hQ+T1?AXm>`PZNE=yRXbtB zW>G;;F%-zi<8(a=|6a%~b|+0GsalBRYRGx{hclrsv!g678DF^*aS4mYq~DP(j?Xl( zCOanoU0V$EJJ0?(^+n1L$PAmAi-zv?L}F6;!ou~>Z)KTG{IW~fSzO`rKH-e_t`c+x zNlo{_cES$J^3SV3PQI7qcIJk8u%g|xqG3IPIl}@-Y2im2CLyueEEnQr8FiHL`a5ac z>&x=Kdh~<9Pr%CbsTAy}<5uCe@hLl?WbxrbGRDt9Y5(!PY7 z@8CrqA|Y;yA*rGdB~++MnyzZ2h1zv?DuL(0<wSoo`U&|{3N+0~m z8;E^78Z)qKg^p-!D82l}onbLm?@s}>pX+wHzpuvQ{*t>5KWi)RXTm=+U^xfBe$65C z3R%nUdGSFS=_`{(qD-i)zrJ;HE3UXk8ugk5o~zirxrhu;-#V)6pDAI)ciGy4^Y!Zs znd|EJuBuu`KKW~VY2KFTj{P?@B=|6#02F?YjGw)#n&);P~t+gq0! z0RbwFH#G3!;oo=Dzt;y=2li8s8A<&$_?!2pPF%apjPuFcOa^9d_Zr~h5q)$~)OZb< zPQWW*G3;~QI7!!Qvl6QQgY4zh{=rAZ@n|?06g*yuZeMc@KdfSwnm;cn?hvNUV7Seu z*z(=3GH7EBb7GzFj^$U$$Ss3=RJyz8IT##cl<)jxf>k$G`cwv|;|WtQzrG_1l2@&} z^yiIpRn7^0bxeAgZ1SqRp+>r$Ghs0@ZXaR_NlQ|4Zun@jBO2e|&UTTpp!HcKoh{=; znDUb_0>;#5k+UXeK9DQwDRw8-GcI9^1*EmmaHi*}cKy=J4TVRdVri-oGH@Jg07UpC zkAq7bP8l+Q?`BVa=oZ<%y{7&vcwz`FmjIo-6S3GAiun9cr|b32Ma#!L5Zjvvz3eyJ z&b>0-=WajS3lB0hWn^q=?x1lIT+y|Z<@D-dM4kt^y$*S-%Wf-opv-Wy4dvz%bdHk% zr&hte;5p%eaW;0r*eYMRHGH4m40Uf^l-_jBe=@z>Q z2w*rr{;Q`XDL&d~YD6)e`u44BM1Nq8>*wW$Cc(Ro^%a>LOzy|ud9q$Kjki%bHb|0q zha66oI<|s2=06RsrTV|G+Vk=qlumqq+XoYmIqAa2OqIXtZCzshuG=@; z#w)B#r(e$baP5JqCijIKivdVH^D-t-VQLG_cj@*{E_201!ywA`2wcPpndw{SVub#I$1)j1YGLBlzdn#rM5_ zpT&3I7Rki}$gmEScUafCtg)R-%7cd^iRa&S3=(9`M8d6`Dh{Au?n{|)T{!pj9mjmt z?ER7*Gf~~uw=@HU&z)7j=ikY3lU{hVv*Jm)=P$yoNnme0je!Wf{IXg4+Yh9QyURoi z*6UlxGP{v*?cq>ff%Mx#)ePnpjO86P>$02a8ML;6=WuyeD>YoL0z9l@3^@Q16Y>vP z*hkF)@5rrU()c3>26qmbb@I~5Q|$^OCQ8Zl_;a;a$jOY<#GD{`2ap6V)Coh?uZA}n zIcK!e`S++(NJE|}xXP5~4b68dYw&1ITQ^a^jJVp@2hz|)Rd4Pap4}+;(b(Nm{8X^s;3-m3O9Sq zTDy5c^%1PfPE4Ya{K^q3%HfuPyhqB#;Tu-?cEizbt0=gk3eg)6GsH>0U`m@m?iskF ztPf@B~)Yq>jK7d7~ti z8huj4Nm(REKbB4*nu+ewVbBGY7%?YRE`z*;Yw7d~sx>Xhm%>sx?-!%v zcl&ob`Y#kDX1bJS-Fl}t)oSU}FLMxt%?&m1d7s_dzoV8Rm?2Ws&0qXcCC9e^4HF&O zf%(obCRSKoKT4%SAw#M_w2EWEVS%LKquw|*z$1wiJ`a8{aY;yipg2lh_fLh^ody~YxCi=@G)ix2^swgTNvRD&>bf4} z_drZg|S78p6EYekd<7&;gROX93O^52inp>KmgEdM_az5Xo zX10}ES%-gJRlM+k!-qR-o~dwQVW8huv*2Uo{%p`KRj7Q<(5jTOb9dqAo!*)`x!>z| zTR&F1M!}C;KkYqGKArls8w{sOgoJ(oon^pJTIr0O?&$^%`iF~Hq{tl>aBuFaPaAZc zBBHK;!D!)z!F%`qo@A_P)KXI?fAE5)1#5{X43}IRJZCY|%Bm3V7|JlAMNHA|!)sx_ ziqliG*h`IwtBnkr_itX)C>f@cHQ{eB(PrNmK06tHt-wK8AA!HVH?O7x6zd4^4xbq4 zTo$3D+_RPqWAiY$osU>GfgXjbEye^YyyDw$f*ppH?-CGAIf#}N9jQ5h|LIlP(=QKQMQ_?YP@dLtEB`t&@%i!=m?u!_TH8Yd zZ2J;8!5O@z2igzFtZCAR`ZQi6iE0z5sa zc^ZQQQ^J0-W7LAbB0;0H$RQV}`-xiweAp{Pxfa83RKB*-13j76 zefv?pl@y{200FLWH9cYwhRO{?O+x}GX z=TeG2)rQ=Y|en8qf05+`uU`j6PiW`t8*zB7ir*W&(=!XkQTod8bhG-~$ajU~H64=su_^ zE=Z&?)C4o`iGc?;wuWhqgQzenn5Uy$Pd(2WaT(ry*#}sr#DXx7SgxzH4j}?IXp<2L zGQdiiW+8%esEjB=VP#03bXa3bWV4>}_DVJ^^Ji{}=|^g_a!sR`%TZRtYA+X!!<;me z**F;ld!%L3Wqunoh3ZbN!!=i7svM|1vAxs53bICflybSRclW z%e%kz6C|>Dzi?r0fM2JbPxss+s(MktOXJm`>7wn(ODqr`4!yWFEPwF|nfET>^uqwf zrlPcPM7_Y$LvxrDDqCzIsAysG_GOjtr=R-QG0wl9&sc2aKdhWKemJv`odS~I1vBD% z^`MWcM85o_!u&bE6c_Nz{MADI>0&&8fTe!u4c2mdLS_ zOBJ8Z1oEhol=-9tREy1VH27XGmW zDr*VaQ+O^f`t-3|*qvo+A2>`C_&MS6lU|>s^~lOT)p9yv$ywAgPA_mloKj8zWcXR1 z+xV3f7oaf_>a#^HkJJ0gzY0Eo5vgYFpuf7U^IZ09895whu?04(UyXgX`q404y%Of9 zM|`MdGQhe9o@D+iX>;4u%6nxIA7d52x0DDc+zN-vVuN)5E=N3Do4ZDHewZQ>5)I|keTpsED07* zZzqt-$SkwrRUal6Sz{EZ2Q&iuCNPS0Xjdy;RA^K8$|@{u)ejf)sQ;H);krsscOn7y z*d&NZB8bx2p;4*6R-vBPUd+FRtLEQQzrU=HgWc8xo8h3&F&2`8Rs*Lm8h#V+Z-He9 z&nMr$_zD$BT(o_~Yk8+CZ6l zGIVP#rW6tq<{S5-ZW=b>u?4o$8qU~43e(tr5v`uz2;wJdr2Ia6Va=`UsBc8`F*j6h z87y51%&0l=H`vC{5?NsYTQQ6c{X&2XXjl2dp=+Lixt#zekQEwaR%?XR7&yN|p}A}jQ^n}cZs!{@n9v++N1 z4$>3%;Xb(FAZ#FtbDL*>lRtSokGP#F@Bhly(@ln zUaQ{2QWDO3FN`(CG2BB|^2Kkr6qr#;K%&?IQ>+)H0o8UG48oz98h($-ESFyle>%JI z6mwj~a-2oXpBwp+gVqi%-VSCBe0`2KIcuQ~Y9BvMn7U03M|4a8>wk{}z)6$aac^+FB=O4y1?*uHBCk$ZCae)Z< z=2}rr^Pbc-P(PW48Cv>2$qCT}IvQndtx?a&Q`tU5m4n5U*WlR`fkGdl%QPmH!NHZm z#<*i~+V!uWw1Y9!A&=s|qvs=gtc}~@r#A%^!Z&6c{KkHNNU((QsDyEw5EqI0i#P3- z_+)xI0P3Cq4NKF$qBE#KzkNRU_x$erzwMlzopWv1xpww`zpm#aTv`@4n#ywv z=YL7TFv1gI)dPO(q)-t?eR6RfJUO;YZm;9dD({EOFKuysr^`F1lrg8)w z=IWg;suWU~v9MbqfT(WotB`F7ta)rGT1ki9BEF?|K25hgtw4PayX|!)E+AkwCK)fs zxYmzeBdg3bL&cIPT}jutxs}0pvcaVTp6T$}Z2i~KpU0a6qCe62wit=G@+CGArgJ0w z(rP@F249qu=FBdJE$vG3J#ZjQ_Ep}<)bZC#iv@!;`-0UsXNmj(VTTaG992k^^FZ_CDmd$L6*a_2<<`@B-ev# zYb28KU>1j1P^ohvMm$P&Cg@+TVsYF(ValXXYQ+t6qJVPL8sg@dED@OxNQdha8;fph zA(vQpQ)Kin)npfJ1z^;#5=l@o%J|B=nu=MmX`pD2p*S=Ge@dkw@h<8-QIIV%kUh`o zjp7D@{eJ{Qr88B#40Ru!H?(_Sn>}rO?3+K=vFVnNCGvm* zRU)M#9e|B%UPmXU#{UlIlpwhX;uc9II%?3k)cp7dAk;Nq`+Y0`#fQgJ(Dc4Xd;e^> zKkCl#oq=k(5fE(JWF7NMzPEbhOlHJU?H9Rt3YzZMt|Y(J6!Q+?lfWm1G<;z&!A;`jZRExasyJU9`pWyCTK zj~Lia)sT6rnriksu!3->{_^{&-^pJEQQmnSL3<+B0qXbID`K(r2?r8!7av$78T=r? z_2u+wNSNSsK!fDjAhg23wX6x0Eby-P1%Xt(qnqfDe2rvXXgSBuH{{{r*5F~W0DDeH92(Bj`;F-gz(FgxSwXuj!u4w>&a9MXMqd>-!;3GrWqNnMuWyaQX_ zz{cO_q$D#>2E!ql*&=^tDNq>U*GMVUNN@{}VZZ-1UB^&^@ck+rf;u|8{xk)a=hh)}1iO0iIYVa%lEQTaan;qXM=7+gf8yuxf# zJcNV+3O0d}oejDvA+}TpOeh~jU;tO@kD@-DEEjCEEZmM`LQOMcPlE8p@@iCg$xCrf zrxeKagfl@@0sTnzaTUpcXM%02u!SoiK?BP!%ij)8I!0E=Rt{KTAtwbs0|W!aU%-9_ zq-jfmDaxemat^$4ZQ9Bi#?a!C29u)WG+*@73~*Pkh|2m%6!p_k8ERn9b9{iUAVPo| zTlV@K3|M%P({0Vd&F}&&E{Momx+E6%Wd1~=Eui<|eh=B=(QJ^Tje-bUJ#OGsQl(^N zR)zzmxU67`9y_3sg$g+@U?S~^O|FmQln{l#R&q#L23Werqa`r?Wn+5Qx@|Q9R(OmP z?k^!6fmQ01>ruDE!+egoaas9W;yu_d_Mt~OGCnTFCkF_4fD90yQRt2!+L$FV(|_cq z^M%;TrJ~lH;)^s3rq}~IW{5mFY~K!f`LweB`+EVwP~(uMzzLHv@p~Wh~Q0=ak-KrIxJ9T;$&NQmnL*gV)P!{PzZgD&i2SK&z*gOsl48 z83L6zysD%Nz{KF=A-bP63!0CQV3b$N9UuB8Dr=NQu{;;pUeND2)KV9!c_`CTYsN;4 zXCPxl+oH*8W7SFILD~oM&B8aNTA@5Cd?~dB+tTke4q9>l!y2yXD)PqVo4Yqsz8v*c zqX^$mXVwee)|a!UF5nHq-N`!7?Cp5lYBbGLKYgr;~V3g&u`9~ zN_>uQvW@n&^!(gWzVs?iTybk~lRlt&Neq!vnE0Oji5CmTEO>l4l z(x&WU3q-6fHa;~aThE!jA+RRj8du?WD|p5ycH;T$pSQfnJfSu$l58E;>aaDnGvHVv z-yDxBl4`>F`5||zMDkp7H6`hl;&m_a0d0wb1#F#Ko@rp2l>fIiu43!t)EGnaw7GN| z1!mcQ9yh}lG{eeY0-cCwY%PE$ril(PGhEClRZkz`UN!41lvYjCdXdzcw`D9|XNrtA zy-Y*zFxujkCq&Z&;WWNj;lbG_=ViI~X%ZVxrV)VCV!j&!5%FgWeArbXe6QRVLCOUc z2CTN&CIdiBA*M;R)BMLh?6oZ5*+A4cKHnO*Z_q$WLzm` zzb&|~R=NEps=$7yEtKR9qQwGkl%8*l7ThTIYakr!a*ic`YBt$~?^dp~(!2lFlJzmh zn#NCkeN!hrFzD7r%JRi(GVT75VC*x$)sqwjfF8+)iQ`PRxy7hK<*XWLS#D}>f4&jj zdm_cc|DCYj|FSXG;B~fu+u^wv!gU1avy;pAU%t!aPfA$rMPuG9XgHZ>w~emltG!d1 zrrPX9J9YHEyC>NjV^{^n7C%e^X6g6IlJOTKNjaf7*e%9{4N$uyazrER(~f(`I@I7b zWtX_O0krJxY#x?=ua{uvILzn^K(Q6X-R|wk{CQhFiRd!$KFp3;-+zyO;A6D%Wm2nu z8r(OfMND9bju1gDf%~9yy;xFq>+$wbB(38ld zt(-SqRy7plqn|hJW)d&m_@#` z&@L$og%1hI+d#}W*7j@!Ka{<*VyQVRvhC88jb@SG8eCCw5$h0FNs6u3V%i zJBQo9Dlbt7SHWs;cI6|+hL;rE0FrMJ#4^~}rLFysY_b>!Ro(U!& zF2fnATob9y8D)GBqCey-6M4{O{j;zLxtT&Vh~oV(ZpeE8r6U-Y>{Q_QD94QZO7%wg zy^fIf7{1$6wEIHc%3l&-Mi!XIAy==!Mh$TsLZ>^XRXM3wr@dwOedOdLTAR+zk-_ai zVXn#Lf%F!gU_v1?xPNB&ae2Jv$~mdZxvuhcwo@UnJZIRTW!*p)=+Od^q-Ws_fH3+< zuq_aY+Z4eE1Ck!gODwB_t%e_u*C0E?WE{gu>OnGaej*-R$TIwijM5MEl&)aIzN;z_N`I6$>=Hk1-;(Jq4_C87g{g5;- zD(rrk5I2(aemEP5jc{gipKxT^*k@y+%fE6Scz`8PvxPn;`Hz$nd zUV%LaNEC_UX_F(Gk`s*t8zDyQt0+3}NX)TussgYF!o_a50po+>DaaNKbJzw4Bo2wfY7LbX+y1Rk2y18> zjtg219%Kx?cm6&uqe$QOgU<@dUk{c^0rN@GS6}mZNi%%wip2L&7IfrMqyEg~0ho?I z><76%r?fSkNtd>xYR-tbz*QuTjrj6v*b{&x$WeG{TaVmSU?zxUL(T@h|MAJ028dei zeeH)HvI(MV8+_!0j^H>4odW^OAk=bN!^&&>alg96N*(enR#}vSY~-_b#)_X` zEH}-@zBM}kB5l-gRFOpv|0^9~j$iwQIX(%ag;EIPA%f|)6lp?X{4>JXlL8Qn62Og+ z#)Gic3{R^KNWnpXUWJR3VIw^d!1Wjzz}p65vYp$~SVoE5E6CW+9u2vzGVUBxDn6{b zpV2;I)r*Zf%hqUPKBH{>hJOYiKE1K6QSc~x0vg~TjkF@kvPMwiQG*3S0CMK?5~w-Q z`0z3<(ApCu#X8t@0BXgL6p%V9|MD)YVI;guk!xmH_Ht-)>~Y6i{*`Z!*Z1E2>*h}5 zoY3$fsoXl7`-|p%epsY|y91)KktZj^GanWO$fjqdr9)HLZggJ zC1nRxzC(JXJN4dS@Qa)PMm;1@prao7ae}#JQbBCp5kI?FYqCURMov|vgf0f3emasK zYTvucpcV*F`}ScL8ob}A)VhdkWIv;^h&tMp7wxG8pAf!zCnctj zG`r9jYFBmk5&bx>SGTx&>l2U$A&NBA%lENlZO0VuO*s@R?nQ;cW&>r(Bjpl}oN zBQWB#xQ3x(CVIFKeXZvIL^=2`iVDJbsUWghp^<|$T0IGPdQn8zyzsKiP3}o<%?mkd zly16Vg-cgijDKwUpNQf2$m4-g&TEZhPZmD$(y!eO$?xYeyJ_Xw_&1kAu7e7^@~RYf zbsJIn29c(rT}>Z5z-J9y1%K6gMZQ-BN>E6Ms&vMnUm(STUJc9N z?F8=E@uUUWcvOmG?c#m;7iAg?XvGNU@X*WJ-ot8mj3aaRdO!SC^^t0C`f zET@C+l%s;Qvx9mPp5AVgQ@|r3s8c;gsUdf%?1cB~tv8k{$j0fB-9E3;A3c*oy*_{L z9=qXd|CEsHl~-+Go3Jq$n!g$X-*s6?uH%OE`Oo&DyVDHrO6S`@J8Y{+67fS7RVOy4 zH8f_>Vq?i-Ms&tv`RKteG#ymUg28 za?mN34ST;%@^fCOd|D#v_RnKI-D;gu0g?;BjkzizSs6mF$F|jJ79ah1In&;jFa6u=LFD_pZx~vCtSneP zckUh=lu%uIm!U%zbbHwpN6&k8I70U>HAKR(l7E=j;s$X%^$}@9Z{*oYr{Pn&!^@jT z>K~R#Be@kzsy1EI{<=Ds5lc&TI*pV(k3@S847`9?4H8lu!ag#PIai3fBJp}WdFKg8}9D0w!_Eh6qDyVJ_B5(?dcIPJhyM4|z(%e|b(_U_deWaEUULcuZ zS&W52We&hd8$3ZZZ6o#%^wwnL2p{EA9(Ina z8)_0&iL}O1O53LDAyop*SW`qhZXt!w-$;s=Qtfo2T6jMwJH-!sF#>v1ZHvK-P186y8(uf^#>M}hVK%c*cU#u1)FO3awd5vaRx+6s zVV=+qj84sE`&mKvPc9qw3ING4}kx&FzmxIiomFaMZkPEtGgrS7is8&1ktx@|S<}P%j2Di*Qi>t$@ zeP&rsnxOipA`lFdE-ZxmJv^r#L4pJ zD(vO{ISGc5wpEGx@~U&)E`J;|Y$34&3g4c`#^_U)k(?3Ji0iJTh#I#&-g9*_3Nl;p zGHmA_<$8Q-W;l?x3;u4RPG_ILR#e}bUQECSP&QSM9MSXHr-yRhrV>16ggoJ%Q`oFX zQ%q6y?`}7rSUm2o_9ZgHJ~NqQ^PziwihGSf@JG=6OT`n~1OW0pVi+=J#>Dcxc$SQq zpM1j0B1K=ZK)q7Q)jAX@4x_R9pK~{%d~&rJUuIXUjps3p&~0VK3J_^M;G9_H5C!Af z;EL9thV?m^*TazR`@c^Q#OG=n3B;Ls-I`yi$xA*JFe!=~&m&fU0V?R#R59=?JfEnCrSdG}zMZCGTYu5!@WGcs%8QQ!(_P4;M!qlRhJx)@#L(=FkE>FlH{dmM|@7A#k`o8}A!*1|mv72Em0)$YY@s0C_t zo`f8-wXw~maND$hqI-k=IZcWU*BP9Bg96veq3J5d1HoZNQz|2t{1kM0A$pWu`0#G&wS~O4Yc-@~B$4Rm?=zjhGs(XT zk|z(7Ur{0{Ta=0D-Tp}>KYl$OM(~&|NR>AJxSMwKi3Abg9nm!?1+e&djwmGny|l@g z#Y{)vbkXz}v{--ZM#KrTdU6>X%!?u@vi~jK1omuV<0g*S{|O35xCjF0^;7=IOzX^O z|BwY5+DWJ_|%<>-i7uI7^TVB|Lwe zuMVfZ1ri&ACW1y`=4ZbmJ*fwqS%YTSjtM9M0BlNttr+4xct^kpgF=zIkH46 ziZcWr{f*Tti=FGynhH>f^8~iIk?Xt74|l*J%STmc|e=>g3*VVi$b6Cw1Ki+ zklLn9_sv!sGTgUfm|F+LqU6R8eN0gcqIwPl49&qgtr;NlkYzb?Rsh&)kZ!649$zX5 z9H4)V$(>r$-Q$(mgZM+EmmVFT-V1VBd!OZ`@zd$Cm9#K**Rm?7x>F0q^8V&V7+fBE zaKpmrz8?tUF=J1LQD8IUjaV~XZ_%Z^fsg+-005Y-NdUYUZ7{sHWnYv`8E<(jRk>9Z zO$ze%W)UG}zT2WE*I_Yy$EVLBlRD4kn~u}f!sdo#C_uss3^E#l)XE@mBamvjgwU^) zjvoczwPK{ShWC2IhgwB2OR*~|AU}l5+azhU!5K|LtH6~3LVYvvH5seb&l~cC7xWhb z{z8Ar_2|(CZ1`JDm)0sS%1p6pkVHA^eJFraj$vC3v@h4WiDcvsgX?<3jmaLz{UEH^ zWBMXjtmvbdIj4-(s@yuq_B%pGgBidn_&ItW^+K5NFPTib5Vs;6Z&Mhr2|Kp1Adh40IR30*OYr@P^^GE{J|>)o}0u7%(eoB(eUB zj@7(Guz6^)2t5pJ3#x6>z6avk!;RuwQhXK-Wa3;Z0T*WPp z%1cj~67`P3C1xXy&t!q$g$(-)WzgwB0TvKRlDFv!x#1rJ!yb$ZKQ-iqgzuM7e=lW- z26g~8DR~pAZv^O1O6fp?dL4!e8RtyYr6zYNit|3SI+yUb0tO=6Sl659W$pUI=NiB) z4U!X+D@78(K9h;H^xmQg$Cak_<#WRDnSv{XFbrAN{QOs@S)H#{e?1G~j8&>4_Lw!- zAwr(c@A;Z957!m>9T}_W0Bth~s}umX91eV>|KdrijqIYCuexoZEnwW6Dq7esA?3Mr zyMtCZEM1P7Vz2f2rKN?jsr0p7T(gzUKF*Rgm)EqT9f?z*v6I>mkl)3gO`fj7&1Tro zA(`xE_0oYtS=1%Wy6@T%{d8$M?Mgxd0J?ea{&4LM6!XCH_rU9Lm)s<}evf(JQ&0*a z|LXq95S^CwvNF^8fy}l8<|t$f2q`^{FLBE!aYaOcPmqLdn?8DCzDEAOrX9W(e|+_x z5~@@AS^7iI4#*tEe7}Ypu=&3%uTzw4e<@Ai(p(9=nVh4A`HbrNFztA>qwq__f-3!k zYCD1&{sc9P1xv$M^T12?;JLd`R#M7hA! zv_OU(k69GnO-Ja%pHQGU3M&AG*BSb0lW4L8g+q;>wL?aZdD=ldf`ra=_^)JpEq?W~ zA@*J&e2oBu(UAxjexUv@|3K-0ufN~(T>c3&?ToUxL6I#--Tm3F0zyrep)HC8HK_1; ze`iV2h|n9axTl6EaFOwxKb?C5J68)5LrJU0jz~{FX_yHFbP&EbY){Sl7V$7yv)VDj_&WIZQm3 z&nR{yJE>;}S9>O9k^1Xdhd_b&8$=iC$4#78*po9%_!^FX^EH{T(+evwMeeUNG}nk% z4x`?S(&Y*;K1nmBL2;}^4Woo0a+r6vMz!q?wjL1r z>`5;A;ZNo>@ny%Atm%PJU(=U;Id6Qf6T+Unj}FWqWXS~EWM+0{=Kc+9M>^4#qFnyo zl$quQcBX?(U0-!(zcSA6>M9Bx&If`EhM%N;G!08VqMli?2Zlib0eQpA*(}(JLVjLs zZxZ>Yix8^5-7r;QkvB~gWK$ltRj}% zO0Z2?&!BN!dueiDd3sklj<{?=STa^XMQ~J!R(GNQ-@-NjN-~Lj8?999?pli%W$i%s zXU3Tu)YYb@)nLrmUdlv&Q>|uJ6O)%vo148wld=;Spt4fC*!}puA^ARr7er9C%vYfW z%;3VSZ;PqxfH&I}gVEp|=!ezvxS;wZ+KB1f8aAPZuR+b#Ws?V+{|(WX(reN*1Du=9 zT-qNULOMGLr0!bfB-@mN+thm6wCLJMZrbFYx$B0t%?Fm~&=D?_fVsI_Md+$jkKUW| zbod6ByY_Ub@U++;wnyhQCrLKt&?0mJjB`0~&ehs|?(WLq?mlPIfu#DHLm1>1R@2kd zch@s0**hBC+wiuLeibKKvafC^qFGLY?^!eUVMkbgsW=^>;oXOG$$kaN_EX7a<-7K- z%@20@?^)D8{0J^3xF0}h48F?mppoiiO6a6`*2fjnn|246FJZ_@{oqFX4vjEqzP)VBC}5M&M?nbZ?YgLFm(o z>btMdk{#luzhOpF0d={RB&#VIK@X2Y#*%s_eg2CK`T%hsnUz98;}Q2^G4%LnHDv$3 zLg|wUvI-_}?n;WKYE#W7p9R%6+<(yk6{F>+KANXhccL^nXln*Sd*B*^rqTHY;)ClG z(6uIoK(6UKIdY2W%%{_T!>8{;P%*tD_hR9L$aIp2&w3J*o?KskN;MO|AZx;CgQZmR zR?mZ@1p$0`R52ja!J%&R*sjB*+7mmLqACA%elwOT8Sy<6MEdO|du-$}L_pR1Fto~$P zYk!s7#eix?EqwV)fC*!C!{5Y7%l_zHn4oR`%76&pWI~ZHZ83b`lYVs2_xI{>Mn36A|%p8 z7+;8eU(o5>)T*t0zYn($qi1FaHF>`G>(ACl=502{y1!-wEs>v1pZs_g^5fO_Sxc#F z#iCt2dCD(?I1-(csYUsjjJ!D?zBhNL>Bw2g^kvq5-@_{UfyVpS^pgjHjij6@jUIY^ zyz_AIv2z&X6rT2l+H^79BiGaa{z_t)+>*GSIQs3wI*s%<8uZ~J z10;d&y21RqHvHQ2Rl&3s<~;Se@4gH~@94<(>oZ*uKZlGK-7GHORD=Es73TI0*muy9 zd#qm872ncr+(v~CwOfvLS#tOGPjk>Lw?bgHUH9ev%hekLl$KxgzEuK2sDZHmB?aju zLU0AjFr*-lS#PXB`B)OYq%!Mya^%NY5%j-BM~~`3)g*?K5^K=^l7jZRl6E;Bf9I=- zsdXQ;_oU*}<0)|o^xm51&T<(h>Q_Incg|#9N@R1feZVKFP;IjPlqa1a+OXR0Dj9FL z=IgQ+&S%Nomq2y;MexP-_1kAXnljeTpne4dAipaX%1Of942$|4Vu)+Jg$xr8@NDYASK(Z8&-tmUu%cEC{Z zH>xk<*u&YGO+i7?7Liy*KxN$^*qni8G5OvLEi(26go(8M6-x@8x~Q!ZQxT_ys_LT& z+jMQSOlA|F=PFijR+MHfbgc>o4K#HzQ;i(PU)osY<;;B94V~Vavf8~gv!6=`DRDUz z`hEY)T4<^@VVYpGKgs}?OWndE3m#oim7Oy=chIzBY};2)4HD+6bjNpKc%TZMH z8vpI9LhaEX_OC_r$jEWAu~e=28So9b9x}qYHIr!#om9Hq+IZe&H;VjB)qF$i+&sp3 zN8QYm8NX87zBDpQEr^aMQF5^mw2l&f5dMAKfOYkjq|@*LpSQ~itH-HGo%xen&&m7B zW7R2{{o_^vPZArZU{^J=`ohbd#DMmowVbXWw62IDJcq-gAt+vtZSSeJrst@2!?QfK z?dOK4t@^fH3$7xALF%%_%Nl1$I?FwNQ=Vs+EyjGoIgRP0&l0`AJlU9=kh56mty)Z{Ut9@JY3a}kDpzI%5 zuE#0X@O>e1REp%A?=!xNb&sG?t}zQVVZf-ROAzUIQjQYWHTLjjaKYuMq zKMkKJin%UsH--o3-wh`wVaeLvUtb$kd;ZWxJcoaf3*(4-F2%;JMUnoLDEH9yFp0}C zU-B}rFd|z!);9XqhB5dH9Zw8&nAOUi?B924#tvoKEw@M zR!BXYdKbMngCEb^r!jvS@o_i9a(d@_{pq(?T@Ot6vN2Y_6o2p(1Bu16L9|@HK&el+ zfJLm<2gJ+zm5KhWQqd|l>|jE3YII1o>>Jc$A6(v2yuxy1e1$t7ac{!5$ztdF@h&xc z>&AmynjAq&-i%s1&$~mx1%W5P><}Az-iyO@CVXLq%BH(5Tv0)OB zA0e$JNs8oUmB)6X$0izo)a7L9y7}~@qw1sNo3$6zuSP~|Z1vN#r=CqaFR?1pdSyhB zR{|&|%D5Y_@kt0KAq|R>>$>_0DXY7k5^?O$S_ra>)}F)FY}NJg$>IiWap~r_m2>J3 zT^n0S1K)~iREMQx_vG(0&Eia2XL{zWAKS~v|K&H-k4p`RW8Qfy!p^H(&J^BM+Q4n9 z;cR>n+#P8uZO5(?cJHOQd08bJ_f<#WL;%4z@|6BZ0Jh<`SQ?RdcBXe~BC%gSXRjnK zi=yLZt+COU&fCZ7+}`1Ar@iltbybyRb!T<&ex4WIWE?17boD14lPS`DuF>-Mn|()5 z##av|pFL)aeXY3zubX$+bQ)z68U~TTTy@eCJ(=k ziHwUH?$n?5O1?FuveFXFW3nDy*A)HBmH8vJ`a+&xC(65C#%PV#2%k?>$(w^LrAl~} z_No+Zcf}VH0F{adJNpR~b6}&KbFcDW_D6j?KFmrl-kZXm zSpIf;*wMKaHO@9}o$S(P9lP_8tAV*ALu!P-PZO57yIMC`ZtOoq{{Ed`)Ypv%=NyX& z#Sv+0Pl#Ek0yZe=v4VsLuG1?Of-F0JO=oX9gM7fP)f26{y%o zg2^V-GqEVaPM%S}*Lm#ZbMu>*Av?mSzth(W@#)5z3E>=JRDOVP`k`iMSR{(!Jsb@p z^-CqnOo20WAwkRsdU#=-a!h&rL)>Snk+U8vpDI42)3TK$%M(DT`Z$}5IJ{7d2ZO|~ zb4n=Ol8(%eg1+{iw7>IZz}BsAEfjp@Tv!WTmD~x8p~BX{9TLEK0qBCqbbbT@nxaG3 zk#O}J6&S!O&QBEyZ@7s@`fMeHncGm7eQ~edcq!rkED{^-F^n|#ObXXULGDF|WWCP9 zBtuGokjI^a#Ba_bc|x}E#ell3E6K4MA=~8dI!7O4YVd!C$sG^GY0bCKQxZaUSs!;z zw3kE^@fU0YnQkWkLke>A?g_r@`b?#Lk&ht-pKNqZ+kC$$rjo*u+Q)r_#;oc%(M6IT z!D4Zj5%_pk0Lt&3evi!fVE-uq1Nc?gu?6E_Qrm9aKZ@(!O7hdGP5pjNiTeS{93MJv zagxy)@$K}@pWdTary-|38>hOsNC2}J?c?4pVp&gn%`#Z1d+!d@{~-mF|4zBQz9{gQ zVvBDi`OkE?TJbgVg)WgX0W042@<*8uVc;-G1SR;%kZd9V5W@Nbo~0Wjw=MHWulm)^ z0QqZq-3I5dCbNxu_OO27Bac!I*)4YJFhW-=T&gCkyYMSst}UK zD2D%bog{Dm({;iJ0GO=^hLAxZIlMzF00;rRK;Z&Be8Hu@=0AL`IQ%wjL)c=YW@oLh zn{bukFIfHT)hToY#}SWBY$mE)9b>h`#z`=(ZTB3=atgFm88n6@U_!#OQ;5KD7^d#j zL*=G3h`)~wI1q)64Y(Nx_?eE!3j0RkdE)JP5QCJh9F-$P0^%OsI8z{^ZA`3DkRXOq zAHq&TBtN(sH&V$8P26e)QB8rKBEbNDr_5;FixekJL-%hAo)R3tWXUZFH&LfOHdx=v zttGC&F*-{zn&c|Z&N0HF)W;JR;*|{s3E+%k2t$4XFgr}wp4iUVZp#CMZ`t)zC;k}M zN$!j;#I^jmtdB7Vb7R#`R86L-We#GKAFRy*GvODViI1<6$EZ`(7F}60l5qm1h8-y$ zZYYkI-~3)qnK+0$!%cA-jSjDPgIk+w-<(YFQw^4@acPo_Nt?2&!D1_uX}VH*aw!;0 z6Cqq_BwH!mEU9F<(az(EkrCGT6KT@5l#iU^$W2qlbJK-5Gx#SQB!8xBOwb^oq-PnV zci5#}D55hI0@F(ZQb#|gYffbH)uwS@rhWI$cww5U`XrOZ({ivq(_$ivWh+C^lwV-w znT=YOvT2rYSG4*{R`5is<%FV#TDsR?m`<)_IG3eETowv1^V%^b?@|4Rz06^uF+eEcsd_-Ufx^Uwc~g0ozO^J;~QPK7g1!dZC&77BYr z@+wU8p&6Mh`lR!*ML%ncjwXtJ{VY1gD?aBczECT^aw`54SNylO_->;3;U~HnjaTCR zv`E();Ce>vngY&90gDX$KT?o{yOd15lpwDJYF0|~wv>*xlxnh+3BQc&uoR(Q#wJn5 z7GFjeRK_(~M&4bzOIz+AU(NrvIykTF)nPR!eoYu{Swvo$OVCSppDJC!Dy@~8 z{N@@1lG<^BS~b$#SAn&*dbL@%H2IULl-io)1Re5M+4gTY|c_#JTBxT$Q zjkhE%5_P%URquo93f1dI6o6$&pw?Vn|0L@me*FhCOx;wd48Lx&yN-CUzSFtt^D3=?yJ38lW_6NgleTgFwqe(~;YWPq&$o?7la0R)8&C1yopZmt=uX9N z!r##)-X6dU!379Iqze;35us5aFbU3z2j*qCt{7zS?YsNK zcL1Iyh)WZ0T@xk?w`N6rgbD|2CK=c_|H*rI#|@*SYXbAYu!5WLBw=drZMCj#^{QH2 zJe&FIn$fhaSOS0n4Csaf5I=)nHW4+Z)Bs@3WY5seGM`##?poy6njv~^Dm*az66gMWs;3796e*7F6_D(rVoi1zd z-Jt+XywW$gBe19A)m;am$ua5LF_k@`EZC_dhw@EucWO^}h6XH`zjLA*uns4%N8%in z1Oco%W9vE->nMAnU9~)2_0PIMh+cCjAOi;VI0MHciL-S(WAZx_5-_8(X&*4{&p~Jx z0HAP2tjceHgv7(%f?&Fby($D|f6z^Ung6s2y8#3)r5}!uKAiFNbE)=UC-loH6MI|1 zwnW|jX~a6|4S;4poYM7QJnP5u?Ejnpat#~s?fNCDrW-{fB^3dHCUJmX3TBTY5-REQ zX(G0A#5?16L(>g_>nXXXhUn@C7%&w49upb^!EE3Q=ej>6E$WIh_Zn=NdDku>^oWwI8={inWFrJ_Z zOS&Hic;K2Jpa~C3pv?D?m{sf9o(X&1ahBr=K*>0UaoxH8?}GM^ND~}@-oa!9!KcE+ z@iu}cVwhvGnByp%LpRMaEzdpXgXN)!H;_0l;RGA}Xg69; z*!!4ZX~H??qALdQ_78NWO+L}ImDhO%QU0Ay( zP7Iz0m(EKiQOYDO%6(o`lx}tZ^*Jw#cqaJklfL=!GQ6DuYHLyZ&1D+FGh+7{nrX_H zR#Vgsx&)vpa3pud98flFHJ zV}+Dw4eMK48{m+Qzb{7sDUhQ9Jn;EO+$-L?nc0_NA$9wo@<||Qm~(-rPvu9N?`QZu zO++gtJvk)fL-e1D3qxdKpTTkj%`=oWgaGdW;+b2qAMg*LK|D@P5bORjR&!)eHQ`-T z#9c{5Is8ku`DdrF9dPr`+|~|Uy*%in$;t0^x4NK-1X|h zO@Ie*Wpl-TgeZ$2mJcJsMnIOO{VsKzk$@QE6KvM^A0>M!Tc00wJco4=^+Du-y^Vt~ zdfRTsSdc*MsP+-a`lz$<=yv}&X#Cx4+}L06Sk4g2u{XcQwPBM)03kq(+8J@qCK!Mm zwlcvxJF6T1GP3mgc=b!?F;UDZ<0$|IIo!m@3OkKj9?_V?Kcs2Fu(R7|OE1q4+^Bx$ z3qW`IOYA&Rcn4eg|IS^MIQot4_yS73E|&F|A}>=h+JK8k7n>ep17W8 zV1Fc0FC619;<=!}Zky0!Ks4;xeDo2%k`>;59hy>5=R!33LSp(th8Tc+e5vSu37Um| z+r(DegnoxRb-EWIUb0rj*B`_;1@yF;TA!gC z4qJWJtCiLJsqRwq^wP=m+DY~*)cp#pv=3SYtriDc1>9)$A8Rm!l?MJ6PX8s-1aGB4 zb=9|O?Y9aL&>yg~{L~0Z>H`_v&O|*T5_i0V0h*A1dzBxy`5ICDUk;OIp=&U3BrB*% zm*{UdK3U>_vBH#lkQ})GzgS_{%qSLOeUPu&zK3!&^nUy79?*3End#rG?89Q{LyHOY zWB~I)3~|!gr8H1}Prjd=zW+juzMa!~SdxW(%}H9rg#jQET=v9;>|y^y3T_QYGFxTV zakynd!g9WB@%T4y^~>XV-j{WpEQUvVwtOS|h`Ws;1%av+jwCFABzkE<2$$}HYzcCr z(tJgKU#~(fle>~cJ3G8m&*phL+suGmttk^xN|bi2aTBo;DZ!k?Tz`Awr#U`nUdMMYtxF%C={D|E$Pu`B zoK8az5bkO%ulU-DhUR69g}wowKM`tn$NoR0;6FrpiClywxBsbG{_pd!ZcX>Q5C*s7 z^QyE9$G46gOWQN2lpl=MJ~CQIFKZ6oxJ}6Qhi-eg{|_k$Qy}+LB-If9f21JgGoSw< z1(j)C+Rl~fy%#)H7=tg*Rp1fiUaHIq!oO8n(+$1U*zAh+op%+6Hqy?!e2rAM=dhZ|tBGQ|JAc&wyPM-IjGqcW|wPxI`%$Vxt=^7B6>=u z2c|uDtH(NYEjwgMTr9Ug74I=gfwgKfaJ%FhKq<^;-R4LZi(1OjNc2UzHqxY>L7!_G zvMMMQE;k$MoECy!h?5QF}z3dB3b}mfotk?$)b3zeK&`~pM4YW0wvnXK`iQS0NBW380;4YWjn}7 z<#4ZtPr(s#4ByQ0CDm39XG+V_6#nI$amt5ED+H-;9N1b4MmuDna#+Maq+n#t%|!~Q zRHG%GhHO5%t6RK`MXA9FI?wNlGK7sJ0L@;$3s(I0%Do(x$(Mz3nd!gZ_&2y8*0IhR zISbsReI~=*m+|m5c=<+}n{`5r!{XW2Ob3a*&3Bf`(4{;$K?V}C-}fj)NY)Ggkj{VoH^cBR87@3K zyEy#^EhOuOWVev?FVc|o^C#)}`0vl3CnqNtM@Oe*uJCy6AH48C=)%o^=)(Pd(*ESZ z!NH%st?%TuzyEi4=VEK?bZhJH#>V%r>wmXLNE?lNdwaXPyW88_{|Oi#k?q2N>4g_x zhR)|ck^@IbA0Peydf~^9A7^K0KYaM`cY6Aad`wP~rV@TnjQtrMy%-oc>+kw-)`Y)b=E}<|3wx3-*Sqn=MTtY;Tf^yJU90uEsd1J`y(Th>=Pa) zB~KDkE~27Hq522d=*{4u-}gN)oQ%HSbFHbVdH(!)Wo2b~dHH|xhDAk1|A`r9WMn*g z^e8bgF)l8SEE&ec#9*;lGGG`L6-9;$LqbA=f`a_~{Cs?TJUu<#-QDlqyXWHK;^^pj z=gu9nQh0pp*10A6#6T!Kw8*BkEJ;-0Umzj(9vLL$MUu!MAtyK4 zB)ni{x?rLwn}oOR>}+goEG;dqO--*~zi#~h3WwTSS|}7sLqkJdU7d^^Dl04h4{qVV z(L#QHek2mf%gf8d!^6$Z&BevV$;rva#>T?J!pzLf#Kc6V3;%z&kdl&;L;)cIfg}K6 z9}I@W;V|+d_n<+c6ciK?2m}lUgFql45D55hfFYF&VN*9X{(lAxAz=cv;QtXYbgnr2 z-vC3$>HiKGf_%>HaFqRqS<1gJ)Y<30V=`jt9~)QOkO4zJUhNanv+q-!{{V*OTKNAN zFbwFHGVexx<{^I$bWWj@mN;e_RHgfEPcgoEzFHU(hsm(B(d2SW| z0EP|C!tem>@@7Hc?6XY}=WN5+G5icG)sf)0T}sdu-$5k~ zZ4?E8Cr~{V1;PIShH>H^RXRlTo~o*f=i*iJG|OBiQB)+As_MW)%EvX{E8&?XnLL*6 zkCOpM`n5eQ_a#H#cLj+BJn14v7f$HDsDR0YBKO`-dH}!-@@e&VpvbA!Vnb*~epV-}H2*~x^+O5PF4<=h zlI<3B7;5S0xfh3hTx)0{#ZZ3SaU07Mfiny!K_ka!ia$o%i3LK;0`d^ZLW4t(q;Q zo(SVkUir2UE3))ThrKVZH~xXCYdkxV9J3KPIo-O$`WN69W1_m38^;9!(NZmHQ{Fydk8Q_+;?*_XK?xYSJb$9tn?T{=EzW5Id9D zZ6@`UaNG+31b`y+Fd0Kr%GST#3lJ=WOjWJYEG?sqw%6F*+_Y749aH#6_;@oAaEY?X zINrcj9!+U|!Tsn&kp_X-&eG0n%F#Gkw^cB&bf0WBJUV8s?wT^XSXgGB8#!x~Fp&r- z?IQG8Jh2cZawVup%k+L96^sU$VR`Nu4BIaJ$Z0Al2Qka4MvJET(W>EmtbmW`;V$g3 zHlRj}5aAx73pr)hi>ip$A1eIEGSok#@gKZcH;ey*Hl&Yg>MlMfs22-9DPsfD=ob7a zJQy($XGJDPGCL-1>&GkVuaJOv<7GKCxw5jm41{5ca2{za&?Rp;PQ~&uRcaNQR$4Xo zH3Jmd1W_}s1AtSUI2ocSWND=1AGWQPeV>b$p}|hwWW#XhB#4T?EHO*x=m3to#mmS> zn}g>9pHlrqF`$+K^oSXtzR7co$NvC^KcAUh-Zd{Z{P5g1`eSx9< zYMs3cVZ#5cHszMEElmPnpOVNPodih-^3{ee{Cr8t;KaVvNgqsu0OTcTvkRNk4RNF6 zOgqusEUGa1o@Iy#N|RdHXnx4{O&FsEkQ?<%lH*-VD3s|%}+@eXKdV6$&>#A41cxE zjlK+SBm;)wzgo#IeF%>4kzT^Dw(UJB;YCBmAl)IS4kY;YmeHNyW>ygd0K}mmofg4} zPt{N!&`@WZh-Nt^Qc^sRVI5h9>eaJ9tJ~I)4yO$Eohg;C+0lmS$!sMha`i8Zu*`|@Y6O`&*-YqcfoG+Uoy`(d)fH%R!1089mXKP_m{DzN=$J3$3K zzB{}g+I0yqs*KdUcJN5K1CrzGsH5PE04su~yV}`{sc4O8d{Iwf9tS;KH2jni_F5!( zsdCx6Xl2}Wc|pcAwq=nXK0Mo8Wj^mhnUdU9gxnBd;7L`U0jWBQZi?{q- zXDB`Lv^snKZ6 zRpGnleG7(T1QdwB&3tC?e5aRhb@s98Nm}%0;p>e?GhbzcL}WMvc{Oe?ZkQGTzQypQ zDJ#BB^!7^9GtBBZ(3*!8`@erLv=?+s)nVcGi{|fw>vGYN>*;Iwu!(MXxLz0{^+Ghb zCG&uIrDf%4W4|n~S~&&wmjL%27gDE zmel&U&_85vnS${QUUTo$zQ5u9TMGA;IorMXO;Cw2iPT_S9@aUvu!|yX)&_i!RDCFV zo0seR`?7UMN7CQhQ`bzIzU16d+&?y+ZaN$^IRBYQniF*O-)dBUU8(eSONcN_{Tup_ zMpWp>FT?UJ^|t}4zbX}#DJAus@90*Zu)W1EXs`51S22+L`N zsQrrcX_AV{3=BL?3~`L71R4Rcz>3hMs@$aKO-U7Qx|Dpl6ISDHOXL15<6(Kkmv!yL20Nak$Up1MxADV;tEC6N}qS+RG0KjDmKw%v%KpL>Te4pTk>&}h*yZy+e z$rH#38WHgt(Z^1>Vkh8YEFGeDm{i0W%N(1=f@m5`So&xEv|6_`^H2{l`Fj8)1cnF-$uU#MpXy+rdPQzioP*CQFf6c{Nw6XpoJ233SzjTwWh3!e%Vv8L-b zvoN_M$_A2*=d&ueli-~+&z6n2+3)ePt7%O*${f;E5~+rlnL6jBZ;If97yv-gL~+Kf zBe|^GjL?8fKt1-yI_X)VOwm3ickTP)5$ow-^J{m5@3}YJgGN(sVCk{|Iq6LS8U{fV zE1-#-nB=@1%CnSXe?SxBj(=XBrsiXa=0iOOk5VfSddNKh)+4Umqk7Y$&I%#oOJ5I9 zNo3FSj?W2<4*Jmntehl&=kvv#gNc*0(AqbsKt7q6&?V;y)TZxG^q^+7KmFvOL5 z_$)M_G5^j~zHd5~TC`x%ooQ~~H<&VLfFu_5${=xbrywsKq7e_DZdRLiFFe#M5J`~v ze5+Xgu&{`db%~YLasC>)2-r-?N{(nbUZ%z#6mwOD?bH)8EZ|1>iV;HsKMb&aVSa0a z!5aoSZ=U6bu7ElbUW(5UTlI;@U7+`56dF+??twUEFY*W}Nq$_i{jB7!9D6?6_auw@l}Q^sXjYGTW!+7THoT^?ppE@*g#lZZ6zC>P%?@9Dg9!Cx_`DJ{2C z<_xd8uSxt-2lVFP_H7BX5f?ilIae|yRe~lZ$73#Msff%tUCw^;?Ecfsi>sGo#B*E? zSp|KmkC)}*cb`#(yCidnIbnt9m#a=FpZ%&5dtvdSfl9pGU%av9MdN~am3V$?JW)xe z{Ki3m*+FFqRhCst&I>9rxNlw>=*4HT7a()tC*d`2AQAtVn#C5)_u)lyLqS0$00;+- zZs7BQ-MFM7nfGEf)4xl#-IR-Wi;p0$JVCr#ttrIMNDowoJ=V_6sXrTsHdcU+qqD1i<(sp_5Afgg-S%+_xaLYy;tcmc&qzaHuvlG zsGrNXmIN{YYz}grB5Dz$uU!AgNpAVyzn|(g{K~+nHZWkdF{W(A5y3>Ihg0iLE$;Q%onXEwHKW^`8d(aP!Vr7K#oSuLmJyxINYaTi)T# z#3^qlZOwvd4@hXQS8bJ1Z8{-Kn?zX7R%5Esd*MIy=mT~pGsGufsy-~;EP=90wVj|9 zmAmua0Nw$X?9eyrSVps2`sVbNl)?|SP5G!O{OEt7s9Xt@CuWpwx7xn_BJxznAl16~ zB~vD;3FG&fxQVclMlUh09u=Dg`fuzE#)#iYT5vkmd;K;J8nK1uZnczd+Ja^pt}ff* zHo&@8*Tx6m3g_RAxHc;y^ zyoK$>z6bbHS&%$?9ZMU6&mV-+Gk0Y-rY5zIuY-2=KlBzSMLcl6uHn(^4&eP(U~3=&Q~+d2juZMFC# zw;?f(Z$z6Mqs<|J=hAdOSm<=!KuFaX&F6_R&avf176a+gW9*xc##5hM8`4!3y`NFn zicjK5zg%8ef_@_?L7k5GC-BI^K7QJF*)*+WEiwetcZ8_l@f)L%$e_$Hwiwn zyspy`58|UMKwXsaD#Gv-US<@4dU}Rycd}?JOpBP*925d}G#=_GaKa zE1i=Gjp>&+Og=nrwT@CiWfJHi=Cl>QHrGpRcHYjVe4b1DJ4fLDH(=<1?SSbT)2Eot z7nsa{4QlC=RMbP%MZF8u%DVIC!yTN%T)Yi!ZtO+X@U%}?`w{`~Iz^Xl<5wdWF*-$b4<{iNaW z3GK|2?M26PbJ6zMQEq{~7(VSsyK8^3GXg`O{?; zslv_}?YC6de4+8aRQ{&%V&xEqkp{l2EGB z1gg&%`ZWR-J3qpGndVy^-3VDMWPnXC(`{pDl%)~g7}~RC+8h9r*e9;Eg4N8EQ6aU} znP)4UFWaw158??OS}7}!zOuLj=;lzW4j7t%1F+8o?I9e%OQfqoLhLa#n*(62R5p7qg$C6z$$chEB1|I`SpH&DB!Ve}Kr1fy^}R6NxFEt| znJh8WFA_`u6VR;=a&eRP{WNWnG{XOY-cbdS@PYaFHL?Cr-+z)me9KbXrF^p2`?2W4 z%kAl>17)9;Piethfcwl>Kr?kTBPGC@11k4_3{YA@Iq+u;mFom_VuI$S(+|r*)LS85C518+IQcUEuUb}JtK0HtW!bu(U!6f>N4*F0KXljDyGmdf# zDUATohsjfYK>UgT0*G(Gc@5r~WH(;!OJ9%6Q;be3D1M>w5)3H317Jz>f*k z)Tw)g^hKI?n2-|`)n6z+plBRAq^1G1f8`PR7`mozz<1xF%8A(YC#Mwz+8*z3aGA{s z;GJ2$Gt+x#Zt-W{4^AQ%`(f{y)QB*fi8b-RC;9K)o{@@~-U))Hv9uZ(9XYIswlDp2 z6vQ4y^KIg?&oX@p0^(Xnvx1V%@TSrxQa;{4t)6}`S5w$9)WpB7^6Zs z@9cIM1BW=k`+{31sT5h@_HE{>owHfS+mLMnt;}|xZM#nnISP@@^4nap3ic<5rq!Np zgV*QwSk7O9HqDg0x{zBR`LDl|^gH>P&nm6mj$>fiKhqj7)ID|yLVGr0TnaUWhRY*v z1$5o&0C_>VZI9iiq~yTuf2`&24pzfjAJlNjlfGqI9iu6A>8V`i^WBT$K@L zULVb4!VhM%gPy+97kE@a z-O{PgWzzeqfQD*FG~k<&A@1n}E(y)WG&oeyrsk$62t4o`NtT_U$Q2rKd1InD9GE=# zp{hD#tfeE6@_KfgC6QkJ_JCI-Y;R^v=O^g`IAo&y*=3sn!{R7!VW4WCb@}QufqFA8 z+IPm|nQiNu^pZUSwZq0hwYLH?>D7T2xE_G+W0-yU+u04}8 zTSg3bEk7Bs0yh~vzxP^S3B#@CsQO($57F@-rac{up`}`;QqP$CArnkrf77j)B1C?U3=$P$^Foof!ut!qMyYik)tYQNGn zl?D%doF5kk_Qj4<8j0(&#T9utUXQYS{-yfe8pHY<^N_EvHlhT-*m3df?8{Kx2B}?e z;fw4*`mJHFq)0MMpj?$EN4!1U!o&Whr^wO(5>ksMXnXU zxyAIGkR9iO%Fm$w>kon!cu8#^-;;>FFM%P_EX><{DXHa;LYr-ubH#1S;ALVoOnArM zu9zovcYWQGN*AHm;nyDHljtc36zUx2ikxXR366$*FP?76=mKyIGWe%dkKvE0ZDH~I z3w-o%L>WOCO?tJ7PPJ`w^-ZtzI|h-n%vU#KZEhlyd_0Re)-1cfyPL;{EPmJ-3xZL| zk0fwa({Q*8_eU}STwSov{Oa{x$(AyA^#u8m^dbhyf}W0?h&b;Hw?6F^+Hkq`1-{*K zeT&Wbbf%{QLe2eybk8&RB{H$d?et{0Zbr5Sli(&i@5&oudDi>LaWRS2fzp*%c0pw*y$&QmU*y^g~vt%-EPZ7 ziyjMt-z8qDzM7K%OE6VhOlzbGedEbSq#%mvwY(Sr$ieeqKYY2oEh~yQN{7~&j`NF~C*^Tp{OV2%T>c>=(Gwdg|Brn?Z-?URbtq+GkaHa6H`<;aL zT@B3eef!ibSvccEGa!@nWQNE+*mbRLOzuuySL`&Xb)HBwOZH0(oLH0Ruo)+Yw?L>f zw=nCF3#M|NpNrtBdbP3HS^1ox+m1r5pIn|;mGUusDdwq5c71JC|5E5VO@Q8&i22!O z16lD)A3bdRexEe9_hwuIp`OFH$7@m-zs9R2lc!3=!Q(nU`hC=Zi8P7lSKsd2De(g} z-eCa{F7!babwgH#Op978yEG#2HptH9-JZ_p5GJlK6TuLyH3F+*a<4xOn;m8jo$LEOc)%W%-~Wpzr*r@F z0FD9)eKOP3tM-6Y;~(^Rlv63pSJs<4=0nWKwuWE<%cbP(7b&t7SYH?bGl8hA-jMXk zdL20`)9$^s&iQeK>4R_lO*{tShTPzNG3T0)e!fPLul!1rV@{^d>nKvDlJyq}eS_?va5)(MVIbf1 zzqj&%vBoIK7vV0A7&92Xa>wG9Zb-|AcmDzmH%|b~U(|iVKSq2$lxlqU^WFD|;ruV8 z3#Imd0K*9C$R)0W*WgGF>X?t8mTBWd-yd=N1+Ni5u-W>=%OZJ&&~^)>QVGBe23nj8 zKOK1t>MEfG@eg2_TlK#IhFfR6#}hCVQY$6l-+uU>F=|fa|R(O8JjTi0%8e3cB2nVrW)IW#)YHbJB1}BRwJoyoU zx!io)?nQYFm%7aW?1F*3hnx4Yq%U&Qh|ERv5a*7SgK_kQuHDwblWO<*q#No&Kh1gq zo{8!q*t+5#W|jPCU5b27Iw#%#t|$n+ts5j+rSf~|G0$k_)-9&B{@bM@6XaNV?z1fo7oQ;hEi3=_IFYaAZ+ro zvRxn=LH<)khFk!ifFtRP;*<$cKL9WVd^Iwi#p9WlM1l5QP87Xh_d!I*iV^(Ar)U6y zQzoE80FP2-qKH%eM;*MHrBPJE%HG!fxJB#WsQcPT&#*+o7!#kCgs=&OQ|`P$-X*~U zNughWRGf<4f8LYSf|laaK&zognb4pn3OR=66Tl-v(If-PV4^%@%DeOZ?oef8eiAgVQ(QDo=z|Bnb|fztQ&}dI}T3_BBzA zQuSsBCf*eoWE;x8eV~^mDU|KmM|2s?S=3>U0CEqAYXS|T(dFs*E=nqC=i@;%Xefqx z$fSNS83K@uuCpOW>j(~A!q>1p>3Jqt{+w&5I?y1_xN12(TAG-CY&TSg?s_3t?mNP2 zRc7!8&tKm&^uk`Kp}xF^h6uKi(Y80LK-a&*^Fj2Pt}GiV{}}F|8N7C5WO)aB7#8hT z(AQID1P?Tf!t-q;k0?Dct~)mlY#UiJLP)ShFAmhcHy$>1GG+@`6fLAHDy~EZAP2A*qN-o7H1^n^P^2V)@v8=B?_w7DGkRRJjd^zk7@B$xk=Wa z)tlN=jkj`**W~de4vnA9k3Tsdk7XVKKL_^?;JC1(@S5JAuZ+$IS_I|`pxMQ+?1>?+ zHy-tUj6ldI0%%p<^qb%W>znaEBODCxco;vM(cT>Wsm4&=4Q6->6JDNVD&!VQ=5IfX z9jiC*?40EOVE(0Syd8_p%>{w9MnFHuVxO3^IlUJ8Ss)y1A(?8AjLA@ zSemgANafd7Hn?)vVyD_@H_Jr!=D5h+WY7V>s=gr;h2lcs4bfd8h3x6^k{j^)Y011q3{afKjD_EhTYr?98kXv=MA1Y5kNC=jO)cE!X8VW4u-3BYZpEVHZW9~f`1P3fT$Kn{2;(kzS(l~<>1ZRpKlI-`#^+W z(n1J$@z350ECO>U(r-hR*^=-H_(%)@pbt(G!#xCm0LYlATsgcn1<6Y~!O14>mdQ-= z{NPczHQL0?-gZXj-3{Gx%O(N`#9K-xNFBsI*oJwBY5{CwBXZ*uCz4!66TA-~I0Eh=u^s2DQRcf~ zmNZ@UGxyos1<-u0I)wwb=1t3$C2$lI~fOC6}&ZvoL#fMuyFs8b#JkqdQOR>aLg0y<2fq4DHP zDYLc4NaJP|Vm+(ol5c)Y*~ks{`to^Yd3{k^t!5@&XugFQ)1M6!p1X5#)BZ%oDwE9y z+!x17Xy4|Ji7=z!Uj{j0{skD;#knbi<#VC;5Z0m6v3wJdK$9;PEuZPzbASC@c)sDl zcrW?;!1Hqt$Kfc)jgiD?1**q4r~nu$QYDrOM+7?i!UEhVo?eF6EK}Y3jQQzsCo#+E zGp(b;@E82{>gwKFA>2jtr9Hr=!uUxn{I@gt%WAN$fbHd@AZ{l5v9*X2CzAa1yZ$A%Wv#g1;{zT}4f(pseB zotrN&S<#6bGtV4S{y+%jl#r3$+fBf$#4kQoWm0HQiyLfn|-6&djpWV{jctm1QTyeVXDoIBLLB4dD8@5$+yEwOf92#$h!Fj)4 zdpSQBpTqp%L-KxNA0b`@<6{q%{Se` zZ`)%V;4%n-m?HO_+4VB2Ts;we9lq# zaD-^nIcO*{PKgNdLalmgZfS}4z2n&uN_TUH?j;p%6A_QXkPu3J&(7OBf;TAj^`TKs zaVE+@+$k^$p4xgXz2A`NBN-+FK5{e;f*!)-XXevuuf zW5#OtgQ--uTl`IZ9DV|8*0eV=HY~R2l`Tv84_DYN4={`M3k3`0#I4`k-+Z}WCj2!i z0eguWdKBQ;%Olx-wU1^dL_z-2tNQ37$JSwzR&Ud#$opj%Jj8%gMoNl74(M9!W+)UL~6CR`>mI^ z8at1Egn*BvLmEjk)~ehCWp)!_)?6hyk$}XAqo{y@7zwrPIlRes{Pm_IlVylYU7TQl zB{hCTSff4rv<00`E_wOm;ftl%tIu)A`j3wdDvu2t1BqaW12G;m0hVYwz7G3oM!Ndq z(_LQx>>(TM1}xqi162S7M)I3zJ=D+kRU42 zk&{Mn%%=>;39#BWAl&HW&Z85h;*+QsN7qfZX)7O za^im7`$dZA50PkhdaMt;LyWhvp`oY?K|T~ADJI_NsK0?YOJ_Z^?ysyl3V|pjAT;2N zJ_+ZUA6Bejp{O`^?Dyahi#KCu1(mf$`d_E%p>gvM;>xUlmnoe^w2Wq1 zpT!`5;1HnlDAu635bBS=Yj_jyHsS!{SjnC+hf7-}FRM}m*g!#;C~vK)dTi8*GA*tCGUqZr@LhQ8R_J7{ zkM_wk3E~jfIU~PLNHA-`J`cBMfbcxZ^O;8I9-wBrF2;_iL@6-V&*l z=i!h43m6iJ$nc{c!N~x<&dvld_lzI%kiRd5gTkV|=}=%GnOi%99KH=5#En}pSYEm; zG(zCNNK9})5*{m1q2vLbxQR>+fKSEIoIf`ka5X_QOH#BgL}nXgGWtF7LR_jvj0k&p?Rf8f-%)w=^*enAgLLw#5;B@1Dac;%_i=X$sz`F}Gr6Y$ z_7Q*Qrkf*Pj2lU<-d=^kUJBPQxf%D!A@@Tf??(JIh=2uA2~rF87e_15k$XrR=9&Z^ zsmJtup>btH5;(L`q4{oN{N-il#)`L`^b;rKMi>F#h%g>*LP8nI#guVlLq}o(f>t`P zai&#UJjZgSUZZQ$ywb6~EL<3LGAC?rr75;l6dx@%Q;a=%X0CM%0bxNQ+v#|dXz0ea zDS<`sp7D?*7>AOUETzeppTC8a>|p*O_N?5rl37-P?~VA27d(_p#N%F%FV*$_28_(E zLi}dT;h1z(>01j?$+$*xe2wuzmL`Gydtgh}vuO$tjpU?l#AO%5w;&LpCiG8DV=ceP zGt>1|m;L4*7MC9BS_%NxHoVQ3spa^2^6ESBqO44n1=^lCm2oG|LfVdF*{%*UV0fv> zX~(@f@k~nWFca}rScbZNLfZ%eGMD+(+G#toHL#f-$wYcB_U>sa2biW#SMephP1?T! zpbZ_p`nBLj_Z@YbuY<3lUJ?^BUcS`o%}AOK>hN_kl7skwb;g4|C|dPnrJZu> z2bL?vve&L!z_&puEKPrSPW-AZkd*zpD0+00Ho`9SL&ocMmNyTD3o9K9baYtmhDzbH#q)Eh+BXmL= zaF_ZDs{vTKF1myJ^UD}jN1*hBSMr=cCiMCb@#+?ul!j#>9`ak+!$w&~sP8hCgR)0$ z`_+qRF09W3qY|dA{+^V;@8Hi^u>3ty24s&W7{Jz%qV}P?bY%73{m9bPQzlCHDsAqm z1hmzI9G%PilQ?bao?9G;8h|EK5DK`M^E=@H1OmIBmhxWPo)t*Gp{?BK z;+e86DEjw}!G6>x?qq@gvvHoj4hMu#OS%fstgckEOiRmoEg-~zCJs}wp&93i0Kr~2 zg0*BRbic`ktLmwNLL8&0BLFHjF*o8~!C)IZx%SC3Y#8x61Njn9AxX*4xiDf88!5P< zF?B|7ZoJDiOjUs%afAZ6m;l#&XJu;)M)T1~Q@uG6l#txeQ%q+5{5Ro2*&n06bnAFC z2@x$5-PVWe{*NhuJsPJalMhdEyt1+hstGs7gJo@ zmmbqmRBWk<+H{8#G`DLRAkuIWJ(tsf7l(XBSs0PVA?jK_g;8R&%9Qn^2VPeuzcq38vOq--DDVrN;$^ZlsW>bH z>iAx$R6lZ-;bs>TxWPCZ{l>1B7g%@MR%ED=Z=?TzKvwV+ZQQ4EY`5E zgCAsn3HPr+)QmM@D!Cw@0+drvoSnvAOkES83J|~USA|oS&tBZyx4si@pC78typJ>W zr;v!_GI-N`@|Qub)0{HK62vw4ZZ7P4-lu1@E|7Wx&riB3fP|uX^^Ss+y>nNh$7v}? zL2l=&ZNwd%3(_>~lXSurl7B&j=zi3%Qy(o@WXo`dprknJiF5%|`t3s?|K_{PSP>4# ze7Ga?=Q)_%$?!)6r=aDUkZcB}KbKcz43aniP5RrjN;s|Wy^&_*7Fd@|$F9jQcz|n5 zv$!h(3(bZ&)S8l;0UnrL8jK}cWvodO)=)9L!=aP1C%{Be)!9zD&r6Ik>GkxS5Og@P z%VmDo>O1uA8(wp;_z3WkQ+?iminLAtdWy>hF`CVlzmMJH5BH_orjeAwLbin<>Pz

b?v@ps?dw$#1hv{@&0;%dq6-=+{1oy%OY{GnZVZ zV6c?$McdD=r}E<@?$M3G2Z*-iRkmKjjH;)zE9-)NbceuD(lo9~WaLOUr1(R!kA-_{ ztpK?gU;{Y#!&Aw)&PK7SE0bm%>BMbfb(-DJc$AvLK0FXzbitUu9fQDB3M8G3>@WtV z=trzItc4WZ1*Ql*ihSGe2jzh=Qn~`LjEl-gU96+Nw~U~`$s;e_sfGBrw-;B&i-NjT zmaMf2H9I5fY3j$^__1T6oOGp9p3DR9Ni>p$$`L)NG67RRAkKt;tP$hh(=HRaMVaK7 z^66$ofp-=u23fuh1x%UIRnr%47qSj+30NGZcw$(lsL{oJVOD#24kL-h4JI`Cj!{Er zfYwi1>q6tkD(hg*YD}-fz6=cD#-G_Y`Wu(|=+i(7k>v)XcIeRk(^(~(HI*ipdCyj|M6o2J{W56?al{@PLjz|v&^;K`+j z^*|YYu)8^kGnaGqbMdG-(WVX?e%ckk0i|4z?w$X#!jSuO1(L{sMik6JFKju>t>9Ld z3VTUliN$UqFHog1Gf1kKS_R!!&zfJkw_JMJJzTUGc;#jAmU&&R)#GsAF8&2W|p4oyC{bTS(KH`NC+eqP=-G zkA=1EuHC{F18zOF+&k)L07S+VlVSmKcFJ+taq1f%?~>u&8Vntje_;b%8D(2Vfyq$s z*hc~dU(WbNg1IK9g>J^k8lX7^apYJbBn@7oYFa~0KX-0c*q@)3C01k;BpT;b@^gF) zSjgS*MgCsT1#QX#ZO$2+mZUDfTv(T4m8NQ4ry#Lg7=z~`fCNwZrKP%Q+61UDB)qi{ zaaQb(RTVZ|+WEI%;tTZ|7I6&g0>!skj&gl`8PcDg`Z}mjm7+L4>(SVEGAwoq*}J%uVpa%rGV9kS z;SlC%j`amSdqF@GNR_CqR0XPF7SMZIrXIX*Eq^B-@kEml>uKNFvx70zTA^FQ50)%) zRdEeB7r0H7VM;Ns_NM=oAR1-s|21JuP6boJyy1iL`dtd0zN%@_N z4To@)14!7BrNZ$?Ic8zQQA*gEe-oo9?6O*Z1KQ01xaYKacY46c#hX;&EH3Q&VDrvx zVYjr++eyOiKZNLLT=Y@gn#K+v912nF#DdG#w-l#uT|Cu1?a*k8CfkG37hvI;XkR)J zKbA^A9ua@xN`EPl0L99HYa)TVm4T)rK~f@u+g(}6m_Sg>Qya~o2O^68cms&(p@3UhtFhbC$Zvq9{4Gwi3zU5hr|p9sfiRK!2nc8#k_*es{;9gvpSbbNBJ zc2N_a<>s6rnxa*aGPdnByX{^fY~&5uxW%*S&ZF5upaG&-*+|`7=N+7Z-Il-(Se3Q} z9LUOsyNZtkTjFF9Rj6v9Mj(hGCFYuBHag+%oo0UNb0)lh2A%^=dkW@8mUE@)D%h^& zKk0K?DNsuQDp2)2{!FxZE@&0bXL?Zd9awz8P<$B1z($#gLTg=WsPFweM_2xTFq`8BHwA5tZnb6(aJ-UI8+_1)*pXy0_qH)=+S# zU-#XCEoF#qGZp@taTm%B1iOUyp;~Lbcw+KY+&I)pJwdSjNmA}=yiEAI9!Ss>mCn3U z3{K&HL*+GbZ^MK@q_lFNqC?X*F}YG^!p*v6L-A0vZi%u^4mO-(E`zKk51>pEQ0+O~ z{>`r8MLR$HtxX8~a<|F^`0F>%XUCE&=hahEd$pU8*OZJGngHLQHO%`p({KK7WpeRm&9(b|@g-Mr8v^>yD$(x+@oud0OXqH;2#&AD${T+W6Y zgXKd3nw~LN^_jqJ;9wdi-+#mrloi?lY4zluBpxvxVyOAMm9d{1UY8FJr9<274q%Ym7oA z*k}UTUWyI*nljg+CrC~|R-b|d5brPU)pu#i*Wpx@aqr!H?+0sNbJLDVI`|d4Yf`PL z5`CZg(;#&``Y-4!AoG<87xoJ!*fORk`!rf(>BGao;h&4Pyk8BdIqpjBY!|fn-g|IY1 zeHxU?&21#p>%F2o{Iy^Brb`NhtxBZ1$s6XpE*&ydA1~|m2pRR5o~(b1D&7lQp6Vsv z;a>JV7EpJPH%cpXL#-E^npJ0PhI^)flqkQ!DvELJz6^G z#`XHNa&8mcTz(iv-u#xzE6?j!mSogF9 z>KIQ~db^+W(~&I@^)!Ghz6V;>FNsc5l~5>%dux+R-Xxbt&4*fB6|+5 zSP14)2tj;3pQ78KV`{n4tYw*mX|vQf zA?YEC*)JM(^#`Q`Z^hi_^Op$m?{7j`1|~de_P7i1l#7QA#qj0+MA3AppM&S)!U~O= z_+Y1g@2@^f)MP#j(?>7c4mV@V8`;K{?=fMJY%wO3n#Nix+(IQHZwmi-=EeW= z=4?i%V3WwxP!d0qB^t6S6%}(@+{2>z01499l_WWO06pCrZ9P@2D(U^rW%+r!5J0^2 znMvExxQgfLPT0x2@zBzMQQ1f?$HgS8%C#e zgAz)Lgrc;JZUm%3_TBruzn^o?=bX=e*dMUluGe-wugCScqf#SG{Ki{_KlS;uDsvUT z=p~a5iu97rze>sX4l)1ir8lfOfo&k*yK2f`td{d?ro;erycpX(!eh>qRRu+YecR@x zNRxflq}!V8Ldluhs^l&;x;uA!B~^@kLi3m7d|ib`@$Kj36;O&&E-~HM&Vq=hdeIw% z6#=L`LO^--vGTn>7U>4cn|n%aB)}V!ZTYlM_;-39*k2#X7bo+%$y5aT6(zPs<$Fbu zD4!6BKOF+mG)XrNN_BP0G*3%SP|k9%cKr}#<}7~EetCn8?976EsHDWjS_uq<2%f%D zWBEKd5_2;&=v(rsD?>{*(X!*m>J3@Ri{W=4c!qE8k;r6a`}S&tLWt+6W|fKV8`U?+ z-jniIQ1To7;vZ?Fu(;~?8-PXLzX679`A`4(`zTyywe_#L%g|l<*G~v~245+_#v4~w zk9QIz7GRh3@jYvw&I(MXZg$1}@mT2NeD_TkZ2{esKO3r-oGwH} z5Bp0g!1MZVd#z_Xum_Kc?yiodDiuIpf6`n900=W^2?R8Wk-0fs3OE~cNNXhp2t z^q-kOPJl}W?CGz*fhKZ4EA`{SB~w#{Ob1dVMemR(h2uw=Dgb)206`OXGj#WrT13^d?B_kU zUv+xguxQ`IUncO!_AOJ(WH_5>7)Yk_%S^VTo~eXo~VRwq2Y|E|>iKkH%M z`2w=iRt`JU<9QduU|-MQOG1WnzDDkD)f*)Z>pQ2GRI;8Ne#%R35C3k2?%L&$-4=P> zV$H9HsQ_RB;Ro1CcA@4Ql-WdilN(rqL%yMqLCkoCqsT>80 z++g*3YCoyctZt80?_H4p9HUg&#Ezu#u~H-B1RqS?iB5K8s#LvWN3bthp!`IY(tgh7 zErTQ^_DF^Hp0Ob>_(V)mD?*v81Q(VQRU)WL< zNUjkp5lnPtG$iNQ+o4BFLLPXfuRHd?iR3*TwAc7|EIXfOq)=RZQFE!25 zL+?7R82lrY2E~!ju5VeXi~kI>neW-Mp!>?uiIY$7CNIpRw;#XYF$=SfRF4E7gcnk`o?% zD}1!ozK)m5*EKO+{H3^Kr*O0BiY*C1qhDyH`|RTFj_@TosebaIh;>`|&yJ_njp0Uj z{G4Ey&KGay1*dTK zp|HG1I%Y3m0#q|huI?|M{+;~9#$Ezt8bS24N^qrj)jbO^`*gP0Z8ZO;kW-fVRD@nV zG|%Kh9UDdTR94K`ogr-cyxa!Qnls05!Y2G|&bvD%B_Fl@+Hc2?2pwlJdP#%|0nzm{ z`DTI5*kdlC0gHEd8mni_lR0m^SBla_zA}gU2=Xmmm^DP@E1Ls|-O#op+(ggi75#~} z38Z(lK^A@?_!I^CaUh9iz(ZnqFU3=JDrDH|g=#1^hU%nrP)ddQFoem(&wWnsl zCYXg2W|1exeU4_Bo=y&wA4LoZhbwWxg~{Q|tP15JL`-n?XYolXCHL2PpJk3{`(TnQ z-PZX{ZPayx@1-?2mGH)G#*i<(OX1iGL3ve-7=V&9>Y1!W5_v~;xso$WWUNFrqkuv_ z;MjOKRmOm02(w{wc9~?cI&zCr9ls}uj9leQKyZ{)b#m^$+otp~y_WY_a^7jvrtDFs zmjA(@+(>cbZ$UoC7jVt7e>Fzh8=ZsW{SfEPqvI%U0UHd@}7*ca%Z&&wxLHk2z2 zCgYwe^* zmLU1d_P%02R^bqKNz-sf0Ge_a9RiZfcvgRjDsgchzl%Pm#ts z)Pl;0F*7{vgK15!rrPBKax9Ri#($&jv1sT-zhoaA<+>a#^!%_IAJ;(vo-wmi;4#=N zIc-os6;QrE*}!^}*2dDi_xPdp{lxRVg+Af;Gz9YF`h@z6?_cZb9p5#HiU0EHH}3JyKB zlja!m4Ht1hMj5c%O~C!Tk;zXhz4!8zb#HABKm<|4r|%&nKEyBa%}mFc>F&8;aSq={QR@cb4V2v#dJa|B~V0% z2p*lkS41S$a;)H0&B{7RH{_~-+&pQ+s5z+Hs+Lxprso)ak&+zD`-^WK2Cz3Z5Cz&ldCFY8w; zCFUn|1d5N6`&Qv!Mx$%&LytzSqoo)sqi@uh_>8xu%-67E!J?-X`(|CQ5P+$75G2*5 zeE+h$_jfs~Z?U!a?FQOcxR+20)t3I-KPLI`VfL z)d65$M(}EkLse|OU#Dlq=Hl`3iF3u^3t6rksNWN)> zKgDr9tL3b1R@X5h-#5b2c}8w7(J(nbXOnvVT{BRUmTSVCMLS1AIpFR+mwB0OiSzU^ zsJP)Q>HrS{sf^z-2^QG*lHW3)oK~Id?wP(qiUkD6e+Xut z<5^;ub#nA5A~w)uoJ5h_Q`#aYdENK!jlp2!>vM+Zh$1-=rM}Am%Wi4qb&Qqd6Ef$R z1Qm|E)Q_L8F4tHMB!iAGeq0^=!n_aUx$}o>$xl%#UosGTEwFzqx}BX2nEU2;6d&ld zWBTq*^M{A;SkaHZ;D+*HODt^dLMI37#;HQSK6eYEd|0z0t{ND-FYXO=>~ab{RBwu9 z;6Z)d&%}0m*>McdrbF^Wf`Sf&xCQ)UrH}iC4o4FX;5M-V_)))Lx8I!RHeh!dg!$q7 zcpgF5XTK4JrGYxQ+CHb7*n^uiCp=DWkl`Z+>_Y@zMEn&o@nNOosTDp}5XnB;moDH) zi02F>tOJ6bBdpPk0ewvOdkA{T2%&vf;qO6~?D$-V-%aY+IOM~s(YSLWV2Lm!;VV#6 znHbLk@UXy=9gp~uj3f%a`Vhu>F-psaVdpbzdGvVZ)(KK^2z4dnmsw_AAqG7!VB9lh zdR{<4#tzL1V*VLKuRH=p^)g|W8MyG+*n=1k*cd6edgKq^`e8QD6pFhJ308j}m4AiK zPw=q!&h6TRa6j#c^-wex(>xkIx?&mw4QukfUZw(|nVIn^CwdX`2xetG{QCgv zmR<&Ob_NguU?51E)QqaGpcp@#gWbinZkzil-XF4tMT&QnogzFD!TcV}Hp2KvRwy>D zL?)o{on%FdhJp|o3N|x&Ce>v`M-Ssw0c)G-Zz>U10z$wE8#z>wa;!H;d6%oz68dYI zJ85~>hl26Pb8938S^F~{>_ZVMk-ihOHt&l`q48%JmUX6)9z^N4%5qbB0YzZ>GW9nT zXsiNbz#-xnfF-yOF>s6+P2y7N;d0mnW))Zt@CtSdGrnObHI5~GSxDM@#Lm$p5xmb{ zMkajsxo`|V{5FWy?GNis5UV;FL2&`S)DS{=nTZaJkHN$Hy2*SGkL~p_!s3`-vr%IU zZP|neQhjk1aEv#Jl1_*7!VzGRLcrV_89Uzf*0^*KOqLlX+xh*Yp%9lmnq;eyq%w#u z=NUmM9)k>k?LjY-TO{7EAb~{;^8+@v*dSJ@BEu~?JK9C;DTbje~`$bW7>Suf~K;|)+yAb;tef#Z?BEPfpDhYFP-yJ25 zCg&am2Ej0+z?>8G34olP05g!WQ*^MgHZ7AgyGa=lPzCg{?#QcAqSTt*G>B@)A7I#r z1PrR1WUs0EbiO-RJ1es^34<` z5LaO{M-0>PQ%>%e()>T1ca8-uskuJd(%q7>zsBenBP1cz`1LxoaKav!gzM z#|F3VvL4nbHR9s_3!p0xK0re1l+6MKxoXf8p)#~iOlu5xEi`>o`W1|8*cw9Q2LCvA)w$IgK z#P5NzQUS&mSbjrti>EzL)}b`|X?f=-+YYoJp@>JYLe{5c`G&^yZ8PucgqblRnZ-Db z>rWEs0}GL3&N|H%CU(5JV%W#8Z~usi%~HQG_xK@5@;e}yqV$ZRN|z`7j3YLJ1`#ZC zic!J_iP;aIne@{T<+f-GE~{QTI|$V~oKsu8F#`&!%rgZ8iiu$hV~4sl_NN|Bi)nAP zQZ+zmYQq6K!gL4epUQG+HcMxB+SqAT_iqNHMe*vJ5GJAENq|I>5%QN1rd z)6OK*cWh5}U!?oiPPy~8zEhcg_trCzSwd`z7Fi*Fhl+-cP7ijB_T4=94WkbF^HT@Q zcoC%179n+(V;Ihex%X$nQO)1 zfizX`RFU>n)1C6;bCk`c#uY8#DVkZAlkG{H28CAbY46*m9O(g-%Q#Xz8UIm|-AL*i$((+J%%RM54-RrwBw7`asnedL z2TohgOda>m%T>$U_fGkhnPDLrT6>uHKon5pSi+71=BolWsY1#u z;0~aG^QtiYDN7zEy$)gd>=Ej8FRGt5@Gm`DbFNM5C)Mk>&@4RWV2O3oj=MaDq}Cm! z4p*fvQf2NwW!`h8yXdl@tWwKLnzOGE7LQ5!t0I+-0870%t*eUELi3njrsD#pXw$aP znfp9aq%G*G4_8&aQq}!F)x#atomV6~7?M$+_x;Fw0-qs{V#V2QA=qSwitIW20;yUt z_Tc^C!fpTn5OYJtJc?(L6X*LBG(1glE1XFug`JyG7xGO{Rch0goA%yKn?G z$r=S-`Ut9KHz!KBQ)kzwGJ^Av@C8d!lza<+cDo>Bv>jt(5gl7vFGX7qX^H}qx^P>W zSKD-3o2AtIY~K%>M$M_dq=zQ>=6H1#jIGocw%lGiu14(2@OMM=U3g4v6Sz%u_6O)f z-C}lgDjFid(ThfYd^_LK$k;iq-~C;m9f@JhIqC+=^k9i@1Rys(Dl*NPjLo?{5+^8kuenRwFI0|+U(xTgicGJjFKI9VY@o*+6x4r5 z2IVy0|GU#C0h;@IgH4Bx>54iyv~zI!Y_JNqHDBn7lBrKMfe3`ca*+JNrr?aOj@+9L z%dQ$1%>nC$0djWgp@I>QoG)MJzm(vQe)9V;cvF`vkKiyOK>;Kf6zYs_zMAJ$EHiz} zoMr6qs9oF9ufv#hdnZx$ENjiQ^4YulN5yZ+A4 zcYZeN)I34L@=WS}fsN2sI~G3 zBKCJJ_5OO0|GL4$cFG0t4Kr+Xv2M1iPVRL@f$^Gmz?$rXFYdBiVGpIF@_0CIx5#tq zn@u41Rwa@a>rw$!(|Su$wi-t-ny6xACzod%eu?LWJsq@&+t>JQQzI zmSwZ#;aY*r!QC#K+>QgA%Y(3$-P3@&K@+E2;|^wNeUsk0qF*&-50BmlY&MhcUYbuc zci(5sTiuyy`x9_X**S5y7?$;`em;wZg=q)6^oN}F=TgAY=Eozg{5ZCJE{-?9v(b>V zudqr?t!B23<8qyJ;F#x|U%vTkLOH)ey3-;8xuWye(@h`&Hi#VL60s<7HR;M7l~iJ|W05&WMI&qQqBWAd?OpL?wC(gm``w>x3vDbhEBB+4 zYUcBOuCM-*NYr6^L!rk%q^BHBi`9Fj0t9|UrB->BTHDN>R+-=J+XD0X(rmoyDf*lC z;Jw%3cB&W2s?45L%ie60-8>mY+R-dJCRy?JuaO3|oL+^5ch=<*!l$=IT`Wd--S)%x zRo&J+!^2b5d#Bpbec7&yqqQ$2pl%OO`+=T$jh7T9<1hKO3b{OGVps&~CRE-|-?G}^ zL58wzf!KkmTyMsLGLsOphs36#P!YNmpPKs3*Wpj%dIw+n#ftp!e-Xt7lhre{O$9}q4B6Uhx>>xMRVHm%1tlufRD#3esZL@9OMs3`rumac?j*8N%9(|3 zufBzGY6U^A%8Wu@udSzBXAN5y#qYFj8DrrpoF?`ylBqN=Fd|DXsKrYvs*|BRp!~@a zxALbID@}Y=VKqPal%tO6wu@SRMejN^&lPW&q?=u(P^c}q{GdkQ6IH%2`+A&_5}>W3m!7c&Yfi)Wnw5o5NWax z24;jG;cxN?_VLw@-c#oNqU>k_gYh!CcX*B6P_e$JpQsv3KIT?^raInMV6CGTe`bb|o1d@$R>L00JZFbp-icJQEN*EqL;Qse@Y6*;J*-a+>b5Sg!;cnZ@N{~?X27Hl9E_swUMeNtV%I_317Y^AO zL$isLh(9AntU@FCmczV=(ju8{AO&`8NB4`W>zg+H#r&9e-(3g^#6Nk?#6(FRMm&HO zZdi-h7BNFHeGgsUTDH39R!BnMmcr?_Au4*40d2mhmbN;yuiGum_{cLL4>@K-3PjOQ zhkiD(dH=%k6$MjbU5<%$b-Yp63JYVzpp0Qd!b5@)gdBJzo9el4#K}wc>~F2qx9=03 zLfKy&H|Fy`nh3~z#cb*^^vSRIZq&XRK(}Gc!|I?Zz4vrnjcvqLeDsg`!)yy=s{2~)(uKLe}*4i+)KZw zPb4}jkGiM4%CfeltiawI=WC%vcFVM(E5|ny8K@i?hg}(cn=#mI801%9*m49SgV4Fz5VQP0`6YT#xX6a_fv-@Vh zHZc2;P}OhwBiX|DS58LL3s2o@4J@2Fg?1k2_@Nn{k&jHE6j6S{0Dw)TG5swb0l-?3 z8BV9l+a>}x=LkW3*YEd|wfjXEf(pEUF~~q{2C=2Hz-QkQA-^RLmGbJrQx> z!2P$B-Zqi$nUMI-oOp%SB*g7m@cYh=I<_?CL-(yUeCMWWTAGXEq7>%;iB9O~M=(Oc0~aNAl5!Fm`}EYce8|Ys>|u+nv=_dLX_yQT6()qZLs=)0+?? z@K&C`Ye-NShxGx#xbWqF0)}>etCSIKpLxfE{sjy#hiDIwaz#w*d~YPtMhC|aKgn!( ztGB0OMVVErGhzr5&__hKe>xlQ4wU2FoyY*MMOn4$P7@Pf%xWp9!fQSfeDEzTNxtK4#R!=xV(IB ztL26q)-N}Lg*#GL_CbJf$lka=@wql3d7C_`#{>YtDLlwuLjv2!H-TPneTFNO|Dq)c zyp<+=xYbYgck6r8Wewx?ZF(S9Tr!<9asza|VT&u&a)v|q&}3uI=0G-sb8WIT6?ozV z^b!rt;S4+(40@$v3kVCmIuE>ki~wZZzu|rcFV$im3jXvqkd`{wB0cbqYVe3&NKTmt z{b|tMp^(_5mw3s364t@t_-`aagN5BgM$de^{6Smzu7*ZH19KPxN=4~cpxfwCbC{XIB7;9#Vfj1g3(+RUS%Ej-a7PcWOxsc zT%W39(aimd$e3YkstyTw*HGAJuluo)5e-8TK@$GO)-faHame0S04BDVIF8{Y0!bIY zvK13x9XCK6Hrp1rpCP>G6}U=Fexe*-I~2V>^!QBT&UEA*PG<^TA`~7k3aEx6v_TO? zp}-X=l3^5d8wCR=lJh1~swGm}B+^DD(n}_CCF+y7Ml_ZuVCa%QMJ9~DcyXhDhszYn zKb&-TJ4pzfEW(>Cs+KHflPn&UELo8(J)A7Noh%1VQQ%Ecy0qQNpcFST&p_gMz7);v z6fJP-Gv3q}YS`2#Q9yNrRD+6CBl=Xm_LNuPG}GBsecm)ngS6K+X*R>D))i?E2C4Sj zX)c#3&b;Z`v!=VcTp(>ACpr-nMe7gFptwvAQpJSh9rs^r1qD{UKJ@w!A*UN)uiAWbH!Sf`myW!D8e8o^&q#&5?4s6icc9x z1n}h$wkrk~N0S~Q$x1Of0Ot~ejuM||&tPat5({iYbLPy9;}USbctbQ z(fgfB*b#VJm`DN+KBxoZs&~J`p*9GDDg+rTu7zd-B;gDi7AA9j3?D+1>PW$50kAT8 zg6tlc3!1iGs;U{M0CfDrzMDa zf7J2*#1NiSR|j+fmrsBm%7c%btEjH4C#Bxk?lcHxlfIXSAEGjyWVs1@cuedAM!>~qek)U#@DTlve#IcTnzrvA&5xCj1vUlE^WG(ZKfI1 zDD|ZgwA{$FVT#}~1K(pxiqOselP~0`b%K|{KQLrZ`3UNd^e{AZ z_vJ}1G1ckA!R=rZljg@gSR|M>as(?u-ZB!~7rDvb$O8pzZ*Gmo#Kr z9xi(bdkX-}Yrq$;KY;AJ<#xL!NC1%0o>(LJXY?!T(GS0T`CTR;E;xbD8TVzQeM7Bl z{!%xno;0n8&gYctiZJaIj(>Xi6K}YXK<1z^*YclTE;i2`LW%FZU2OYU1?!5Vp|MONoT0m{g2H z0E++*?`zl-T3Yj018-&EHeCY_Hv=v*gG_tis~)IJ9q4Nhlyk%FH;t1U+mKc4fbHmj zBk3TnANAdn!F3PE?Qm>*Dk(raV%Va3IBaw{@@BXSSDzZxT75XodIQVpA0%KS3hWvQ z=^BpM8}^p^0^KVo>F)VR6tRV+tCqSVhrqos)fzKe52*yy2 z#-N~9pa~h3KK?nt%b%?;`V{6xubw1NmZS|zL6fBl!>yg64y~jkh_*Faf(AS2FAqq+ zFnm@T{$+1)tc&LO$@p39H~>9`er8{?q6+446O^8sW@-4#?t`}gk>o+BI>Ur+EB%g+8*1y`HGAGFJ=P*gv zmk0CGAKAt;P1^lE0R8*vzpIdS;VP7H1&|!`95!*x*7 zX91hs;O#Qn%y=M@>{HIut?>A*=&`N%*SZUv{uu6nwYLFVo{NvzcAEsZT5q?Bf?A>1 z`Ywq2uMk*@<2LmH&EUuF-1uGMpw{P_q_g5cF`4bufbBOFKqchCcKm^%25|8ZlG6SI zPaOUlN>?FIrYT5gU$)@P?HR;I_NoT=lR@`sfBJ5~Qas9QDdRBa&Y?YBj)^dgwQbu z%fUFK-IVPappWt12q8G3F-SDm(w64W5hifJv zOu%W9)6G+BF#jcOwzl6OHywZbaj3`@Qsf`)cV2rhK;%?-iI%X4q@@FMaOALSPysS28c3hwPu{)iK1q5*#{oFHXviVVC z`Q`bPSgA~V<+V3|#L4+`_S8Ww|T9`f4nER;sR^M^HztU{*Z!Lby zQuIwHx@iH8D z5)LpVXBWKn-u&!&Qh;;b4PB}w?G)+D$^2<}tQCS7Zn&XAzb=R#00f^AAz`;sME$;F z^e+DbhCNdkWl%&VK_Q67m@1Nt&XOwf5hJ*-Ui#auh!R3P3)n;90YEM1t5p*e67l>C z7{)?EeR)L6sq8@vVe&x2zA>~GzQu&J=%h}vX3z+pik3Qm^U3okZ`nC>)dM8VDKFwR z1S#I#^5P-GMA4Lm6g#9@Ys{i%85)D4c&d#JV)F!mWUmM0g|QkE!*2R!F=A)>VIWK> zqyL0KsRV!}=1FoOPn|uZ|L56JG&t6P=>9#8s#Dz{gywjb-&7Qc!eZY2+}KO#Z)lF! zZu9wTzu!MNpsYNm5h;E^8ZVRJU77wI-wwR6pkPLii{%{LC4aU{0ss%LZAicspawVr zUf@Mwaj)B3?CsxM-1~o*`Tk+~a6aGJf5Z7suCA{B56*Xrz1aH~=exymd}n7khYyGI z-Ja}WPcSDZC;ys!*rQdP$%p;@`|9xU>i2K#;WSR>!>N3?`)j{<*KapBuzRD}?Y`TM z4(wXf!NI}a-roOU`LGzw+RDnmG9MPxj9n_hPETRyv#~SD*dNjV+vl5^nfXtm?_XdK zJCTax^d=`KCnhFvs2+BtZt?3N_T$IfruWz{4mhF@``HlN^Ay`Dhiw(ZHVI%GIB@FT zmoHyNMn;B)hWh*aaq3=APtU*bUT0_Lf7*LZO-&6A4cI!Vy1F`SRTZ{I5c{46TM5Tj zkYLL|*is<21P@yRxU8W2P@Rku_-blus;a6gDk}bU^|1MlCB?=6sq0~rld-V|Uy_or ze!f@_^=)tCf4#k|tgN)OwA9qp)0q+F_1o-*+`S|#Fd3oXZ zJr55LS6A161wQOsJ*?qVtdUz6|Et5-%wMtXXB zFJHcV@#4j^XU}lD-qWW~H8eET)YMc}RUbco{OHjm6%`dFC7iOSDE}YK9`*r0mX`y| z&WvTI$I{VY$;q%_A}ql_Fy1XKMVbH~&f$}mmj0LG6Bif%e`bdI8l|QQV8*LXynyaR3O+H0CNHy7OGhnSV zjH?duvWe_h$=pfwY8G3Ze($KLde$xl;fD550ezw6zPI1mUw6^&cMqcOXyiRqFqw6O0HT=EZ$`E0is&q^H zpUsIPjr^w{I^1`Mi5SKO>%`9wK6SHVPi}MlJpOEciV=#;J3Tw?RJZ}+b$|SOeeq{^ zsr$m;2XoQ!?2+BO$*Y&|O}}@P(bau`?C!T>AR5(;LoHdXRfN>n_SG#`M(AppzTGX)PTM($ zwu_A_p`_KCPR5QaJQ-BSM8|baz_b~^Q!mM??(f|51OB7WRJ+qo?F4a03E)`cdvWsB z6D!F*_~fI4eW2^KLu39gKaRCv^YkwL_owX}v*+q|Xfom00@AmtpBVa_@z!?fNyG+3 z1_>1qDh#(cMf3vwNK1ty)JDx1{$%uh1~3XEN3Ep(WPa7*5-m{s zYRmp2>*r|cgOI4Nwu;LH^G#ObpVXc{TtUa8rHUA)hsUmk6P(Jh@nXjA=KR5sRTj@b{-8E%-;#V`FQomGDs<#sePi1wM z^O-@polO`Bhsl5LgFxBxvI5h3AX3Z>YIB;uE1Qvoos(Qem8JYZsj)9tad zV9S{mdUW5U?29WL=hkXdXvYRzD0H9TSC!rJW7rw#d9sOtK=EFfC_w?mtDYc+j-!}Q z%n<_(&$9ee!q-D)FTR+7Mi5snq)>olsN%*ChlJ6M2em3#YE0W>DKA`y&IE>buZ~Du z%Jf4hsh*2|7c5<9%d%|UOUOJlt`j*4dp@%@p|mZO6uGydZj^O5uqG~TSJWD`dNGhs z)=0bU8*F}J4oLvHn{xPbsK2@TQTOpzun3KClVzgm{&V+AS7s{3lOj5T8L=!oy8*Gm ztC=A|jnYPYI|cF1F9kHG)oyp~^9khX{z?%1DBq{mWgPx7Ox9YGzKF4Mx||J-Zz*Ws zmwt`qAR5{lBx_-|Ff02$vohBDabL!6$)4e1?m%bhh8f*u`Th#Sdwdm+Ey*UN)k z;&!(m@{r;VQ$X%EEv5-`C61g$1~ZAzOk_t%37t!yu`hMe1%Ho%mDHC7ic(pJn1a(_ z()ySO?PJrtE(5682*BgkGKY@`v7ZKIVnN{@$*cS9>wcTs;-=%YcOKAy9IRLBB@X4s zvXrp{>qKlpB3F~)CERLj_wIO4O~=ny+$r7Jr0D30d3xS)=ks*GDsndJyBoV~?mlue zYn~*8Z$QDS50%WcE)XI4)n&{TO=+xf9}gO={fRW@jPAp31Egsr64o@tg}M) zu>A2VhVaG5KhL!MW$l-)SH!!o7GZ$P`8U|x$0&}Q)%PE16*txcT*evwUxR}byEZ>~ zvZm&Fm1%uANr?CWu)ti+jDI|99sj$VFpj_#k7FnNiIv$XCL>juhA5!-;?#+iDaYxe zH|!R?^-6e`vX-9j0qCImEt#FQ!Fiv)~v!pEAWe94n7+U z11bt++3deuVV|rCfw-TYj5OY zsS{nol|&qtF0q>eBK-mYxhTDvF8Eg$(DHb-#0C~Pr_SA=JsX=Fa%Df3oQPCa~ zumM1*P?YHPjI)G6nx7<__j5kK=R9HWc!CWw0u(c%8hF%BQcvj8g?Zt8!tt@&!s?PX zPiE6Ic=_}iIgGz$8Xa@y(PtIXbE4_F^dnLXqOuqa2+boBlB0N2XKm9nGn;th2q)RX zC3%FCvb!qSJ9+Pv6Q}p_CXmS!{Y8-y9j38g@|zoEkJ*TMds``8W>wPXoDBj$!9(I~ zvPUJe$1ii|C~~E+4S^=gc}JFco7+joYoIT!x$8W6rLE~0$$T%hTu+;Pw(UHIGW^FC zIVSYkOB=Z-l4v%fd}AV4k7ajo0h%Nl?b3_(6JdG@2zgzRkF`N>^5heA6jXuGQl)t{ z8CmDUg8gb%X4VC#-pNcIg|*~q;2ks!Qsi)_NHjW+)zD40$GXTQmll#Ja8<+{U9j#Q zoxodoxy^%DM_4^n#5<4y&&?>qN)!}TJm510tso0hit^!T?NTJ*L5r%L<09n-`p&Z5{fuW+D&n`Kd z-)~1D)wUuJa@Xq+#JZi4uZ}w?BDL`>t%xr3VJHf?D*N7E3R2_p)FwK5l$-&{evG2p zQ-RMMf*Vj|-|C1phO0hgm3H%q^)k3Fc9bnaYHG6(jy=}#R#hqV^y%90GZR?WAwi5b zEXcWX*0A=brBd9s*uJCs&ImJyHj!~f?ae9dYc$ok6#QZWck}}pldnCStC}|~LNZi+ z&PqH}AT+Th6^p2;Yfo54Lx8=+>zF!NOeMKp$ugvR)wVv}kQD+TiskabpJ%lJk#u1B z;Q8pfhN$G0wxC-07^fjJvA7MAqAixCa@Wk_b=_5=c1eYq^ke=v|e|xyoq)| z7&P5gZ#CmZzaz<$t16*1suy4^pEV_P*Dm+CZoSy?43=&~&4>q5N^rVD_7Jc}IMDX0 z^e$sZp+^1C5uR(0bsrp0>6$jIll7}w`}Z=L(N&oVSICMy=oN-^^swD4yEU4mqgaC} zE7~Cv-o&F3?g8n{$W-J+!h8_$$WuZHO}l|z*Wh*A@t07VMHF7^#s^D2G}^3x<-_;hpqN&co=QReelXwRcjO_iL_ zeJ3RY2BbW7pPxK=qT1CB$?3Ycm(o@85zzDTd({X1;o1*I)kD2)u{4m^8t~WC9al#k z201CCMT#|>%6%jO| zLH{2Bvp`J0K|luEAPWM~0qn2}MUVuta1L9k2~$0D%NiUJU>MU9c@o|L_mOrw94a zDr&$FaM20YFc7ei3vm*|7;Tao{mzFw%d~9CexU+&AP3miiYHyjy$lqs@Chqq5R0G= z0^tGca0wA`0ib{lG5rJgpa=|50gJO_oO;(n&qWWUSPz z!MJz_gi|fj_lg^QPz}%G(gN`U;lM-!p#B& zmCYp?c74}Pnb+e1(t3T)u*%eWu>o^X2cpmqbNa~~Ej(3yJ?M~NS-mOHfD3hT0npG2 zUhoC7U=7D21KZFE@AC`1FeaV-*`Zw!?_1ZVJ)o%lwS>LVX-l+X|NI&ly9TXE$lJZz zNtx0>fd~Jf5A6L9{Gbmr;sMRT3;v=A=+G(=Fb{kH0GSXCWF)5A&<6nE z36&=hGw=^!005m(4L~i_7ERO!u8!Hw9;%(%)uKn+1aJu)yOMqm%8a0E%<3h&S;WWW!WFa%tX3*c}p58Vky&Z|)OgqcM_U%>ZBq%HG!~zN2c~<2+8-JI);!jp+cG>f{~gtv%-r&K+2Q z=fpsEr_Sk^rs-{b>8uWkuFmIuZqA+_#=haya?l3-aJIQ#?0$~k7qaTVo_fLF&OZ+1 z&aTJbjTnqu1xMbu!oKY^3+)yn?b9B3)vn9duIsFN?afXcuw4hMg$&AC>h5mu7EZqB zo|)-x>hHeCa?aO&fw5RH>exQ)jlt`O?CblEgZ+N*_@3>=4)A~B0B}$TIdJQ(`0wJ* zzysfI z-W2cg3rzE;9rIxe@vkoNmyGai5$Zd@TJ_HHZYmqqP8>5&^d)EWO0OnJAMR5x7y+OK zb>IUA5A+?cwpfhy2mbL1zV&p@^jsetEKmn=@Bz23v372H($57 zQR`H|@@Sj)XAhl2-}e%!^>F|8dT;Ek;nZ`m0Y8t_fgcxD9~@Wj`1uC;ldtWIPx^md z2UhU(#}M@{zxliV_Yd;68x-}u*WjoJUZ zLf-zd?iZSx1qToeNG{HUFRAFC{EK;S@v1q~8Z@TQIqDgBCNI9Tuj zn+FjsUc{Ku;KYg=J$@ue;~x!>B~6|@3F03Jlr3Gpgc(!jOqw-q-o%+x=T4L&N%FkN z5hzNbLrWGl3KD5jjZ1U(sI#TOsD6f;Qe^tkX;zpT&!ya&YekMOPwAykoDVfwWD3UK-=2Q85Z$k#*H06hHUrn*TQb=626Ri@Y>2S zb<}~gz)-(Y9y@zIopW;Jmx@`xh8|LoYSv!=eCSuJj+yp8%U89+-N9~p}En_^lw z+~rJd)Ar~Z`gH2mtzUonJSp&@+EFkn zUw>rnzr~MV47{BL%!$B@0>GjUDh>#ypFyMuY0_QNnk4L9VeLZBwR3B;O2 z95F)6;+tuOI^_6Z3Wp$aFF+GJoR32QF0?U69e3ohAP>Vs5kSO9q=`tGj2!3+1py$X zDy3$m3`(7Tqz}g)uf#G-?5NZU$(X!+3Cu91%q>WmRH$Q)4R+|~m=vBg^Te{ayv|B3 z@5D1t$LPdKOqcv5ip(-)jMF70|E&N(lzu`vO3>{bwTaK_?9{VTOE2ZB#<2hmw9qI$ z{ghCgNT8z*5^6XGutq^0lq^Z9qZCtFXQef!S4(8IRm~XV)FdRUsN)I%MkB>nNV_|h zrdy$lwN_`Jg*KvPXX@41Tpzs_TTyM=V2(OeFb+9uw;gNR*_w?uU3F(Q_se8Ie0RWj z<;@n^dNZP;4lDprkG*k+oEN5cV?%dcgAdkn;4$xomtlH&4Y<#U3z|TVI#_^U7za

7wkLKHIl_h7n?6U=E z$e1??=WJ(??shD3#z!aJFt~g3++E6xOdY0@5gj^OzcJk6u2xzF2I=(m{OkR5+0Hi3bIPyhrkJiu9L_}f|d1yo>HqnVSWa1O0NW>^k@c|l82oD~hC{bAP z0af&37;OkfF)9%UyVDN{MYzV18Ne3I7|0^dz=S`LV-^Rw#PXD<2sZT5kADPYAO$%{ zLKf1HheTu|6}d=8Hqw!ggk&ToIY~tNp$>MyLm~cB2ugO+lb`gYBG71|@UhX9r8@;U zz9$ee{38ekaUl$4SjH!kk(OSx@Q)^V6P`edppeQbP?R7bi~bYEk=ogka1P{~Ymp~CC3>e*yh9A|lfeZ5 z5QIu_0S9X6#xI=r&xdu7pwu(zN1*Zs1gLX^?983&8fTF_E-xF_iReUi+9N$GPY?j0 z!7tch4{mfqe$pc8%VH|ifu1yfC^>*adVo;erF1C$xr8+^`U0Gma;IPY-9v-2P==Bf zY*v+1OIF%a4OX?OS4HC`rg5K~g4M3h601cT3Qn`)t%FYeh(Y-R0IDR^t$#HNR_9R; zZ@l6L|6M)mT_roWyhdcN7`d!o`|4M6o@A{JImSzwideWF;e{ZeKta%;hbEk%8R782 zq`W#=+HS3~2g$5vm%6ZknuR+FsRIuJ&?H8&Zny6Aib(W$35%Ej9*U4{WNSO!k==G9 zn_U%J(@NTlSnmLt+n#Z?yAzR^_JygnNHjJPUFx=%WY(1kcA>}J?V{8q`wK1s1ZS1X z(U-g=?La#o!Cvy2mXmmb0wlflT0UItW2BHa0mf`X(5&6-TI)91 z%2x3PEYt+_F|KB}u zuL1n9>DHFN0h$pKcxwfChQPuR9w~#LOW*{@IDaZW+KJ0s;U&e06@sNsNK4$pt47?# zGrn@WZ5*ca1~tr$Y!Nhlt4W46dA$?sa@e$+#E~pj|hV5P=!#e zC*mG|J6p^S8MLe2?;2tI){#wi)S1aVa&Xb36P|aO1luTm|9j*sO>3hYTJVEMIza@G z1qBJ?f8Zv3pZES4$V=Yz4jsLxLl64ZcL=yjKpbJc)je3X! z6eSpl7kcpycj&?i0~tUhwsDVgP+}lskj6c_@zaZx-uZqHyyS~M3F@{Jix0s%1cx{` z?W4Y(>%N)rf^VRP22z4qP=g>KgKdxnf#?8sScM`;0$DhRjsS&hP=g=f0y7YZAD9PE zI08q|hiUpn}kYduRXv=z|kZrF!?$cD!P093GtX9xrQ z>ji<>hDjI*H24RNB8Zw=o=BX;Vw|5)WVRsm#7{KC4QQHvP`qWdMD8;Tbm%8j1Pf@u zg^suYXlMm5_ySq528~LEe;@*Z;DUcRo?Yz4Uo41N0s%-g#(4xhWIVcQq_+m_J%Rw1 z;0JwR008iSX5fWV6bMB?2Llj@{|J}|J^%nr$cKTrfPYZI zL>vf4^g?2!$C9i>Wdz88ltxm~m|$44l(aVo1PTvOf|^u{KAqn#*FmwLY(p~ZPTX+-&l`r9q|W+miSGo8@Qlw)BTvZePyfV~1Vo0CyUL=QspT6` zdMr@lY)}UU7%51VLqJgR63duipR9tW-4<9^x^cfvA8}UbXSfGS4;&~ zofr*cSO`p9S7co~p4*2H8;BR!2Lh7U|9SN>5;CDyN>zaf2T1VN@`O@N{n(vIJbj4( zgncu1r9__N2Zt4i8K?(|bybRuGB@hhKDY;hh=xvZL|K|4XA+`j^4XtNrl4&ipe5QJ zGTNgR)_wqnI#_|EJz5-s+Ng!1p`}_If~J>vgh$v1O4!;*fCO5Q2AGvuY)hq|uvwhd z*@6(pJp!e-h1%3{RVB&g?04M@}?N|dn(2y0^q?povID{psGLua(=M^$I zoliV<+}stRFaXn`Tp)|6sEdLhU_6Cz(AH*XhF$g8frYybHHj41w^68rH*kRH1=aKw z)t2}K_W6YT)!+OjTkDmqh9wAyy$H+XzglgFd6)$mFkj+5U-m3foj8Cd35LJnfnQVC zlT}#VaaUhRRbTMn5B7yzL<~yxUxQg$f*^uMY|aLDU^GQvnJ8FG(t-l8;Q1XunS{_1 z{;FA+g?+FE9-f6-_=c#gwtsy<nJ%or%O71aD!1=e=MkM&gW6m=dsE0B`}^{j=)T zVc=PXRp19$_~KPSg-PJ5{}pE7G=AVUwuz-Rgai>5DV}1^so$5tg+?FV~J7TDTy`X}Gb>t%!(wCSACLjnVpodGwWO~{KMgRa4K!rgcaH09XWSFaSNkhEHbU;w9uA1PTmw zkPm2@{#j;Xre8>g2{5RKWv~QGScZDo-p18pYZf1Rc&u1}RvM_~U}j?%ZefDPiKPvN z005RO5P)NCm#YIp=1fQK37f^z_8H6G~W73Z7?fd&Bv z3#d62m`zbeG-nPOF4kzq(F1(g2T7d-To`F#E@+buXPP(wsu+e8sLi?aHkejDlzRyV z(1S{-ggjWtjIQZ5l7T0nNC5Z(Bk1Xp25O%^>6<9nz<|9ENa}}9Vwr9UA<%|-kOpa( zhiu?6e6H$@6XbRtW_B(K_2`Em#4jJ9PrW8*cYcXmz=hI$0bH;Js;+DCnFW>r;>f-u zfsWE~woc2=2y^By>p_6PR${ykWS)ybfY|LB!pw5DR7Ylj&f2ry`e(?)Fqo!*!BZ94vJk4OQHA%(kB5-hlF&z9{g z?NB(hhA$X^0r-MyU?cvvsWKJcIhYZX5U0;oG#2%KHN^{WF+!lWonby-zn!`|IX(f?;3c(Xn`046)s{H_v%4@ z@?n9-|LxpLeW`95XJ%K9@`(7pQxpggmh%u6Z!A}wb4X195Cn8E@F6$ypZ@B-hQ`Na zfi!t<2_N$}#ZrrizzMuIJNF$)s0UC01VAu_d60xY5A-kxZ9u<>Hu#Ge1AqgFa8X-x zh;H+OD8eIzbAu3qGtelZtaC`Gn>}ELc4!A?*aP?E^iBtJ^frk$NR@=S*LaPDsKw+bTK~(VPBL3AP8p+uBA@)%MNYxLM>4w zMQ1;VR>%b!hzDvvgKNO{Y^SbmSM~|#_L2biP!M;55IHPpXk_PibloHU_>xCI}NhaWJ2SlB?C zulXiTZihbgw9a{r;OkJx&0;_Hp;zz~*K~uR!-!AW#0KmK&F2My9ejMSzRMPXpdqvXFmNt{`~s)69nP^zXuV#MHOqDwfEG42xe!{AjtG1iUkZ& zQO6btptoRNt@VbXRPSXp1a$WCHzJ88n)nqz`>43$KH*?u08Acsl^|0z=49iI90p)W zKmCMq07EL!Q3nej;aJm=DUuwh#eX)L{ikX@+E{ksLNgV3h@l*e9TY3aVc(dla-sF8~0NO^keE zr{RW>YNzK|b|nx>kAq0mLmhBTP$#7Yx+ZB?V@mnwpsA|5DrWV7NYD`U0PusXVmiuQ zsK4ckE2$YCWPvFCAfstSAHY#Z4|nd$>t=XXWNMVCvN|ob)$+6rCk1h$4FFw~(`a0} z_F9&+yN$aTZyAu%&oOOGWJMiW5TNY2l`cEuy(B?v(EtN@Catvr3p_AJYTQGODymFl zj~W0l@(H;1)+=ge<(gYi2*C7Hj1&{KP{$l9s5!B?&F1Ug|E(GUQjIvW5R6btOElpY3qXA`nRM4^H%L}T^bO1d1@g_;T#-FE;e&?p zN;5Mk3dVqD7d>j)kgwg(Fm6Yr!W?z9U?$!?MXgik)ct&sJwg;Tggt>5zB=nt>Oqex z_5cBZBeygzv4Nq(^f~Ac)DV#pSY-~-jyUljS!>8Hl$etg~Ri?sYgXQj1P|68h4e?R`t(bF^b005DCa7Nd@ z^+m2?cL+)_$~Tb>#Gwv6*j@P4m%OmRZy}%&4QZAGw)}ChgNX4)8352fKwyI*VX#Fx z{(%RAu;L#s{6{VrQo*^oPeC>GTm(l_1HJ^KHWUfK73zS6H%V}Uk*b;iPqjf0GO>wW znZz}|01q(yAsvoj2pTkz2Nkjq7c%&w3uKtYyWJ3nWkgaALozvG_>dyEkpl_Pct$xE z@GCP!$bSGNAm}a8iGKVeNd`a(dGLcD^~eN8xHu42(1Id&q!$5=h?o$tEg1@&2zktt zqd7v5lSKr}BMp)w7OBWZFse-S0IAAVUL*oY|M-G(61l=fz9SvlIK>OZ=s5MH5t5QD zOU5Wyh~rhE4q5;b9qTwLPiiET1-Vj|w$!CBg$XgKWF+iGP3s04^|v|2FC&4p5YUAYSOjJKUiQCm2Ks@pwl;^pFjE zR09nRDJe<=E7*jnv>@tWL^;oy&W%!3ql|s5V;_sr$VxV#6&S_Fr0@XB#&be%&_HG5 z$=T2rbhM-esA*5@&W`R9BiPawx4cylFMNXR)cQG_JO;vB7c zKs0WF*MWdRACWjhCh(zzg#dQ2)*WnN2SNjWG)y7Rybv>Ks7$Z~08_^37yzzg6r|WN zlHLn1M!q``gCR^|409O7e!Gn_{GzM|(Zf9&&@BQn;UA_ONGDt&h~)wR7PcVBGf+X@ zK3=ygArQr1Y9I>nRG3;Fc)}C@{{e|7+@J%V_yP{fAdPKMU?K9AntP8}79JtPT>}A5 zoCZV0O~$w~ymK*EC4w`Z@eCoYfLMPIvIuny!~^TNLSY zn4m^t{nHY`b+{|R5{49lB8oCkYYZ{{2P-b1i*(=v9I2oWkXy^1UV;j~eJ;x&GF1@Z za0(8(Y43Q+#ph=Qxg&h2Mg;(ngm0>CyNGeqO;Nl2N}X3zG0vP_w46C|FTq#HX-5^2MERyga+tn z!aycH5D-8E7dW{9G+N<>|1ZeG8W#Y-EV3nP2ABHOsWyl?#Z2K@=VS`|Xh%QL%Wl@y zx_3QZ=2)cgolxvJy_5=!5CtIYd;3ax$5zPeVmG_m6$B6e&0`uSl0Nw#{eeC1mi2wkX3G(F$w|d?%sev*iE^C(;uHG5>aZ_#$NHljf0 zpee-z+{AI^$xLVqi%@P)Gp*gfPZfnnYf)72WrV zym)_2_a6Wel4KA(|AQJq_@WHRX#{(m;s{A_#XA&NkWm8w4EczJ5iTKJmfyW5DR5yK zG|b`Fi!JXL!TIfVZtKM_Bm)`?#_WBqqabFX0KDY=?vGwJkAU#;BveR}-TdaB0l*B* zct<;W@r8qs9sqjK#yzazSJu;>Bw%o1mCHXi+gk+p?bp4%y>bA|T2dj3xy>Akj`;T~ zpL-mEq7+e)71@vag#;}8!_yUD?H!zW_21ca1&SWnfkWT0hvB{b2~aXn}=bpp3a7C~;syxDqUN#@nHw zLU@1+wVV(N|BMR81Pk8W66PNA8HB#|L$5J}U3?53h|B}(ppP|SLL{LG9wA0-5ifvY z&3K_ixZessq26Uh4af$+MZ{bCN5 zN<{{+4KPFq9A*dH$W0w;Akt9~59Y@n0%A-210c?fAT9(NDxo13;!_Ynunw48tk9<6(G~0~A~}W+6t7 z<3@sHE&Kz6fh4PlWMU9v8k(d<1eye{p(+vyz5ykoQDR0q2|13S0k}{g=p?o9r0|hs zFves?L?N*_;Q|ojH}0c8isLfYWI-B%3z3sl?&LJ?99H%sNul{;Be)Qrjpv}$XF`@FWJZKg ziY7)(h#hD^e0EZTGD&kf$9>Y=1L(s)-~xX#Cvht1f;ON>$YVcjrA9R79X#hqg5@Oc z;DwUNgSy-%xR3`_XsY<?HsUW7xA!dzNJCQ(6*5~hfbXn>;3iH=B$&YKIJ|ALFY zXoDVNhK|ffV9GEAUq-;o7HGhZLg$kDl2Uf3P6C1p?a`423XJw>Pl~Bvdc+h63ov2? z{;9x!@+gUVBX^GFUT&fbb=sE-N|?T>HD*K#Bm+HigyEe>n_B6QCZ&mLDMvQLKkUMt z_GgmTpM+v}mJ(>7)MSl@gmq3}{CT z9UPe_nbzj4((0;OM16XNsCL)|lpKYgDyjylhDIu!QbY~Rqlab$2{cf$$m*@~-LpDU zs%p@jg5d#@C9s-Eo<=KMUIb!-2he52@C2N#7OJ71=1j_IL4JV?^-Z=`|H-zRs~Kqo zj}*ftWyJXyTA9l0yz;B)21pb5B8mw7C_PU~&5 zEN4Ye#&H=J;sHifnKeZJ-D& zN(}%r{KGsfEz<%lmR_w}QUn343n|=aMdT=_)~dh3ZQMSscL@+9Py;-`gENdDe{k(d zokEw2ZJ&Vbr|zkMZp^)&WDseA0=zBVDyiApiqfe88VmsuXaYVY|ACOkZ26hvKUjj` z4sO%RXyh8*L>y~}zAA2Dq16_y;byI55@$Oo!sZ?=?G=FwJx}OT3E{eIMM^{fsO`LL z#IhcqsBXmZ2>$O#q*oTvKk z?<#Mj9KnCIm_aasJm|wa@NK|KFU?T^Jh+hPVegb^FYNX&LWBTcOyNd&)(2c=>6$M3 z+Dc4a!a+oU5OBdJr~~xQukFGeD7X+8=FgIj1Y?~bkkdoW%`gcS5hn&N1AP-G6L|M0~s?8`DlFR()G9w8dI zP^j7P4RbKGKCY@R1O%{6bzW)^#f{VI@D6+NM~ulPgaHmP!6xv787wghW`YYb8x-#^ z4!bE8hvP!<2r)qEMR1B7u?(vRfWtkc123ep8Y`eCxKJa#F=w1m3e6G# z3;-sWLp|`qtJJL&?;`SoPrY#HZbs};G;0?paAf}Ro^0}T_^ls3f(tFf*EzCgWYHE$ zvLw6%8#F;Jctgf@VH}q)5o0Yu1TT27?L;g<$`S@0n=%3i^YZ>OU9fT!L4phULM+QN zXDHGDm_sBCLqjC|S=`kd(MHJH;bYm$y|MMM^v;S=^{dQO7ESU^w+a7N(Y3P9>W6Eq+nF`!6u2RVTY{Q^Gcb2iV?`Q>jc zPzJgwmO81HKBbmO=MzbnbVeyuJn_gdi~vOyuMZH^NuxA8%`{EFlTF_=JLNQKu@<7< zofx=KD_k>1Z-ydmG(mKFx64v!Be>b9!ND;cePi4HCSKO zRs}R=&a+@Oz$>^=BNVlB?6V&dgtQSvx`6;Xg|trNv`XJ~Mdh_#n>1gy6K0V@1W?q3 z7+Pulbzi5nKP9$bFE(Q<_G7P;PirjAdB8Wg|4=`(wLZ_%Hg|JFfODRW^ZB~0ITL6_ zP;EX!E;A2MCo?Enhlp99)C_>yCCHQ#QMG!3&YWZFh$By^s=9@;TT8FA#w)5jS`nt{vmC@CZg0+#u9~F^{!& zGeL7%NObEo!V3jKb#HKZH#Z8WfNX@aMHIIFrT1!oFmpfiYd;5kuMQu$P&t@DecShN zKe$X{3NQ>WMxeGp5BNJfH$?ZzffLRm|ARB6UxR0_dk5_t=j=f2fP?(-0v!t-CLenb zYeNI+PgmFsbVD1Dxabx*fCqTL0st|u|5-*LfcP5Ug=;v5J9H}7xOJUh5$gDk-?uPp zr#YkZM5yzj9r;5ic{4w^(RSDXSb_`X!w*1tltcKGBV7Wp4MJPQZO{RBYPpnW_?8bR zlcQ7zSc40ZLj{|;e(*1nhh?B819?jXOn2~%v$lG7M6Py4htmufl-xg@0#W;UlmL32 z<4y?pDa1~M1Eee#P&hUE_>YtNzuvhvQM3!4fu)b_oS*Fx@klU0?3;lyP>}RV-@vAF2Yt+DZOaZ=v%tGV3AMZMvM@+9{(*Q)m3nB8bpE-VKI%{Cc z+G4~CWDY4K`m=NUwu7oX_jw21|G+^0!#GrWwv#xItG1~_kc!6}MkM!~81r&Nd$b#S zJV$hFQ;z{$aFL>AylZ=!7kk}cmXKQnksDLv%6Pdmysq2%wEqzk-0wfYLlGoAo|gE^ zp7FX!u`WM$bM>Kj?Jo>6Q`9FBVMT5M9pZmXOMFe0mMhx8?#5t43 zc+oF<%!|BO(EOk+pjm$yEdxl4;e`4KRnplBWc@L@!pGs_pW3_ zM7$RKCWan9#dA50XFUFN{{S?+kZljXqZa-$!@Ni&Ku{pU)Tn%?{P))zy|YXH`zU=_ zF#VKpsS80v7->G?Tl~d`MW7Lb9!$;o4E@XJeewc-(sTY7;*Tf1kfG4Nh1&k_lLZ6> z#ULz83k=D)2fx_!{KAiYmAL+iz`zSJLo6wO?N_~`(?#x!z^)W;72G|!tN!hie@Mu@ zRB%6u%z!qy&^dgY_>(8=J1f{D1VBI-)^E@QHV*(KRJc&#ge`Tj6ks@!VnvG!4I;d_ zkz+@T89jy+$r0p8lP3X`M7eSyjej&)#*~Q?#6J)-apu&?aR8-%KlkhuI+SQpqeqb@ zRSLi*%%v1nKJ^$?|0=~n{f1efO0fWzI$I_@-CDKcSh7$Lo+X)9Ez_4$CH(^hz=bJo z^~8ZHq0mdOckXmKNjRpKxp~w6EYy?DUNtluYu;=-IVKQzKl44IyqR-n&!3Gpoose9 z>8ch64ob<^Vt^`j;*gMPx-IS6tUud6Dtf7xZ`9^0nWZKOnQgKXc3`)vND^7+5K_tn zCdi|GY7&Cc7wJeQd`d1x20eZv164oeHXy&AeS7zmd8^fZc7D>U!yv5IXt75fIxVWI zZ#LX=Bd{|8hl&rW4z?-dm$?|y;~w?8cnbg~{t;p#TUJR37F!g029@w^dhas>y7_6H zBTQ`3#TQ{j|4Biz5ERS6vn(KnpoC0oVU9X{pz+4ih9q*o0*@qXMx$E!1b_!8T11_M zJXq(F2rd8x8}%4s#*>7^fkYupsF{cY5YTi1=Vy0h9EsMxw3~ zCO`cwQX!5yst7>HJUQD_DMgWD6sJ3f;-i`ho`g`L7sAm*Atk!mXP<0tm}rlCl1K=j zJ``#Morx|%@255EL<$UfeyYWQSaHo&SG6Er%F&~K#YvzYc^q`m7z1!EOFPNIN$}n8RpGb z-+gnM|2C;;g#vh``~C!UA_ugnLkkDwD{?f4A4b&3$^69$kAL*Z_#b}sVE_ORn&E}g zgcL#NRsbTHhYy9skY|yF!W^?qi^Su1CN}q9dl*!lOJ;LTe?WaRodOocRTVg&Z*_P5>H^2UP&Zkf#xbK2)fg5own9 z=aEd92ECx}?%QvDgEmTFod!3ljedy903!ljgH461$15Bs$z`J4qri275`<@{2||X? zJvPFgQ;tZ&m3Qz(SCh|Wa3Q;VA~E8U??{C8?~7bO?-$!|@7?zoF(=CMn1<(wfMEJD z|AZl`e5hj%03iph_?4zVsd|fo#|g?YT>S}$gv?;(opyTpA|Y0~|3x7^w7JKc$7=uG zqDp?^hYk7h&)>c51D2XT|BG_CVuWCMxZyz^>d=FUMGk-gYM_m%mK6Tcsb=~c03^@@ ziIeG%gB|3|1PS**2(~2vz)0RiRN|vLP$5wwT$Br67{RGo%_%>tApUNEj-RN5OCI#$ z50!Ma|H*KMYMDYm28cqotUwNgGSmX42g83!QD{UAjSzcwL*E$y6zD;P6@eH=F~$Uh zIk}!m&d87wo=}MhQ2`w4a0O*S5lQPwV@U4EkTSAKi?>q(t^N@YBaD%dg%rvj|7ViN zsZcQ{Qs{>WiIn_!R#b2&$5GlAfpCl z$wL;t@_{J!GKO~iWeB-REobs;m^{0HEYRbHvoVvM?bPEqeHqRv$}=XR=!YmQq5(HF zO*Y$v=0E+}7FE8eocuC_K7KL_cP^BnZmHoAy-ClNq~I9+kU~We;1xJLj)4;0WJCda zmVvscp!ouUF@K`2hOU&EBcm z#$H&OR8+bYC5r6G9YauzeoTQP1h7I*@8Hpo_B5oq^yJ-!imL&f=O@@v>RC<6RO`Xi zjBMS=Rf0i)i3s2|a%h2D6Ny*i>2cxhup@EmTKpQ4 z1f*sn0ic5Obnw`XX!aw3eQ9KOqS?l>hp@5Q0|geF+A)q6kDhI+YZY=hViYVPmi3Pg z493-;?$)aU4XR1)rdr_+cRZ|JBxpkmTL7$4c?%K1W$C~JrTMguT|JO;DPr95l$N;N z_3jlPx-9D&#gWD!phD>CAL&kaymYKCZ>yqR&~W#=^|h}|{uxxHZ2=JOY z;8r1=?JRQJir@sdcPaVx41Mn#Vf(fUJ=xfZgAYvIqezpQ3b86?3#j19?f1AEzOINv zf?>`;Si&tP?j@|jx}9A_#ga5}QS3Pig%seb18(Du-P>FEN~Ok>VX=#myx2=jBgMaM z6p2fmln@xhq6t9&PJR4i21jqmK_;@3cXi|>k2$HAm`6Fh@rq<(56pst@>5+4S3^0# zD|VeFidTtemKgZXTb5v(b0uan4|<_!&_ff>(2Q_+z)WZY!4dv}g9l8S(v`OKr7@jp zO-~vFY{0;#K^RacU*P-5Z zuYqlAPY0XVH~=)R1WjmVyVC^lPz0;GrwBGoo7&a3_O-E{ZEbIx+uio|x4|85ZWjWH zdboof>Hvp3h@0K*cK5sC9dCKho8I-dx4ji{>{umx+5KK-G&a#_G(lR@#K!fn4Nh!? zC%n?6NS+FiwFMH8de{s%_`)rI@QP;~*cj*dtUdnmOB*}9!VIpzQLfkywBr#p)_4E( zyl22l^B7QoqZXc~-hTTwocLXIvF8sK<+ukqU=f51e|^C{|BuO(`+-0!ARx+JZ{f~gi+41> zIUz-!OxVXB_(J-9aeCjop084j6$+rWhIcIAFS2zlce%lA=i|@?pLv!NzQB-=yk0es zjD7%Py^YU0m*1QEAU-`IlZZw<(m{(NARF_Vx4k<#&tALZLL`GrF=|u5Ql-tQuuBcZ}Cy@b=ETk2LA{H^m#XZ^`El( zk`J*^2yodtAfq2USgYgt>-j!=-+}ml=lB;w2>t;)>ICrC?*RLz{q%4Da$*9!q7FoX zrt)t1iU|CO59p4-(NK#b48Rtcf%ei50Y&hK{}j;w>TV`j09oQd2Xv$jCXoN2?)ok; zh+O3oD&iEt0RTxV`bMw^^QQzU&?5-I2k1ayNIj3ws9$pRgh}-~p?^k{s^8y3YbDPzKX*^(y%j#e-sIINmp5D&jk4I#?6#_tr~K@3>OTnbPN>+lhI<_-zbA|?Q*>L3gH2>@nF z$9V1wyU7#h>8mKBd;UQX&<_$(@oywi^+citkYx^hV2&U_N2sb31+o8va1hxLtQ;{F zeKA*7QOHDM00^)evMG3q9O3V!4puZ|d}oEAK8r5Hd}ZFIy5C_3$Asai>N? zn#^m&K$Gjd(jw3DDb!IaH1afgGq9dgD|2ZD>hTS9fbmSip72RF=`s{O^RLqJH%(+W zdviLo3p(%5j_zO~eZZ1V0s^G!qLi~aVQx9m5jDw4EU7a+O~NKA!vUzEiRhpTv}q*{ zXBgTtJQ1@lYg0eVQX0`yJpr^M*i$VEpa*sm3wrXE*a$!OlR5L#K`*i~19U?B#X8S$ zGXkImrg97JAOd9KE$y%E{~okF#WT5{lQd6}LRFL{22?6Y-~r#D2PgoOt^ycLlsrFj zL~}GkdC@Uf^henYMaPpeCZGy_L=LDREP};^I8#I$ltguuD9v+Uq!UOVvqh0Y0eoOk zNYW&Kh33x7NkudK5b{YM#X{SoO085cv9u@zKnHd*3tY4FBxf$c)0;vF? zFa9Dh{}iGLmcbszArcgWF&qOj_LqNq5E@J&Aq=1#Btd;S_G_IdZ0mO-;L3BS_Hh?D zg4g%Y3iu>^12_OcIEceIkOKgegE^c7IsgC!&fyi3fDh>5WdJ}sxWhXLup(HOh5ao8 z^Z^ePq7`a^hRu>Px%3KDAOqa^jo~+in2tw44@RJl<#;pU7l=_eh?f^PRhJaPSg-i z1s;OR`eBt>xs_e{m0>xSWqFoqxfn*ElqoIbaM{;3ZkKhfmwoxvbUBzYZJ2SH)m|G(ZGK;G|JHrB!;RS-PcN8l_P{ z4^ZHxRayjy*_c7P(r`MbA7H0>+NVJps51_k+16UH<&d|fTN2`1!ev~_1ppRWAsiZ_ z*9HJ4x}&>!g)dtDTo{JQVTK79kONtQh4wJN*MJ2XpgrPZG6tbI#$!N6WE7%g|4t@l zR%V*3`I-SBn*m^(>&BwDS_JpN9s=PAP{AEy0F7Jrti{%k$C|7eTO{%;Yqq9qz9wuE zD1G^d>Asp@jeVtCM7n^?6-Q`!5Z`<(wV}^kldI;$l zI;2AyhAv4d5fKCt5fD)67QIr}|1VK=wW9aUXE(4H8N@||b-*ukXd0*>Z_qw0; zyn6nGc{6K2wtd^bpT{Rj_s%}I`3OiwKURc30gz90x}F$A0lg&_YYyTgJGOELGCOT= z=hY8J%o6og(X3|`_tUGms;g4(2I%Ys0EocOw}EQD5zW@(Gpj*n4CU#w^w|o2x6gv# zrZ*O(yFvY$Do-2M#To^sg6GrgN&=e4PHorIdAI6)?a!k3W&@ysd|*p~rjzCl5iET* z*5Ry?N3pr3ubDBBi&fEwBLmB!@DVq_HO4+0(9pc7s8!4&pWwnnjZuPU!Cgk%is!XsEE$!es%6mX_GN-EueYc ztu59Qebn>1q3uRP=PefVcPwrCHq3lh*b0^~w}wVf#eM~cuI9ku_vdYSx4J_!+E!Uw zCIUNt)DINw445bm3d~{qSnA>$?&~e_uxt%eDUDnS8ewc4VZ9jPP#Wb48Wm_96}}i1 zR~nNJ8k1`r!}rCRgY;@``Yu?8hgb&IZO}Byv^N_kZeL8;D^1=DntaeW>2@*csr2P( z&=us8gTKmM@--knPua-) z3M|)BHqg(iG*lK~!jifp7rIzS6S3d#vHiGbyYQgt$Ku5gPuuyY!K*`!t3kGNp~`ES z7eo!1=wZQc^VhyxzFM#DTmK%=8>GG7SHE6x$zPOJTN=EvF1GQM<)=#9MvB^I1>2^2 zgV#V7Pj@iqWH86f!q!+Y4{qV|J^vDQQSzOim)plYI{{HUew{l;54LI4@Zp=-uUWhl z?0X-Y_(|>zv1Tg)>{6VIlDygbTUm;N&5{x!lGkv1O1NLDDhHY&2fED%2Dk&sB#^{1 z^UoY+!DZLGs4KmpY+f7`G~g?BIc(!ObVLt0Y*8$iEfCtfWckZ%buF~BYKJ!$5AE+9 z;fYreaQrm;m|hKD)WSBpOxu(mVIce4vib0i3dh}$qlb4m@3Z%j{B2fIF6Mje`|vy+Hs#x^(Kl7{FU1$^OcGD{4fqnN!8shMI&vNb%jr6cgNnEytQb2 z^YkjJ>`q%EA@I&78)1N7e)8Nlr&d0o>qwBLFE#_rO7BkePF%IB0OZSWnRDYSE0h4j zqJL`dYjnznX;Z*WQB@r$1F)U3+ZP(CpHc<4XOFgACJlLJKWDt+*m?$`38f~0z?HO{ zr|Vb~mFkbS=IR4*6v}v+Pton2wd}?ffD`u&E|qL3-NuUx6LLI=>%SS6`Cd38Ro~}F z&Re#CZ5#;54kR79pG|u3Vj0f0rGbR=O~ZWIRM$(tEClSywIhJr=jsHi*Uz~i0JSL$ z70E!|y&Os`asZK&5Q73tXYEKh*RJu@VhG4f1`|c-jb4g|O!(%xk!OzLDIh8cso$(L zI8kXhP<(-Vr2RRCu%=aQGB*x&_dD5#@*76dx0AI~G#MUzyUkGbBAn}9TG|atQ4Y`h zd|6dW!@APHUX1mUIf~4%@+`qYD4Ml%5H{wBN{Zqtx#w<-j1Z^&Ai2XP6f5C;4QiB^ zq$U5L;86I*dSRw%O|%lqPTf$52Ruw7OuD`b_DNI|6exJvS}dTR;ZK5sZrD(_5Mpq4 zlExpJFKITt+djH%mZb5BJajte-W z`xMLu<16^cPm1eDH=fOp+EjOtGy_<9Jbl4;{;h3@8=?d^6cW*}D-<{VO)w$TGg zqX02MYrvIDO4a%NF~~;=$8s>N$)0&IYM^3}%zfhcxRbuYQGHpYNGPIRMca2va`+~V zo75^LvO12Oz+l0e-KAn`qd0o^j+ z4M?S_6jinR=0K!sCEEUbP*2sNH{iRD8ZQ|x!u}p~_QhUb$CBsAeyk?A+};=eV9Ssj zl4?iEzF1(GOpoIi2{_W;6Q^Lm4zwB~AfDm_DyQGPNJU6f#WWZ`>wMkkGdDH(xnUjN z#Cp6CE~*TCOHWchRQeFK^O%w6azq}$+Od1sv#9>`u0DUd6R^yD=l9^Nrb8-tFi`V% zPwmf|+U>^(0MX5QVNxD~Yr~w5V-qMagV)k-!HBMXk(*jJQV{%>O$bU;W#~<|G2}#3 zkDJ6qPKj#IDCj{Bmh&yf!>+5HL{q;Xk2L}izTa9p`5aRya1Z!lj{7dD`>q6#r@|3& z3ps2+FP0K6<(a6)sLe%Z8bez8$bMKhQk_#QNg1$XIvb8wKC)N7UVhbXcP5c_uc&Kv zZzPEvl#ifM&5gvgiBEFE%4>eqxL2)REAU|||j8U|Q za?we|xXC)g&U6s!{7A}3h$=B{2R8$q1wY4ATo(pr?yS!6b2t)d#<3X+2W*CouYAsv z0)``mKed^JaX-lsaO>6qEx{fSzXR>V^CPT&jwY~~6|&uf>3|Rfv8D&?Nhhj_M-}Cb z*l;k=&7T@onVAN*D`Yo#V4B)%_7;pFUR%>pe@}u6rXJ^;JKzmz)y=wrahPcZW0KmcJ)jceX+z+ zs?*B$LtJYUO9xGD6mpZ>xCx*vDslPJ!a%%T(hU|4;xgap+^Ab~UwM6G``or&rAgu6zb7s5=NM8@&3J1WyHpFJ}uAKui_oD z?ec7jX+z1lweNSZG>K&Iidepx@JhCX=Sh`a{m?o#*u;h;b!h-vgkHu#kyMFs&S9EK z3{d6P6k@u8CAu|im#nRLVN`w<0;-Glv1R${-k*k$Zt_ed{`i#*C)-_U5~(mHPFi=( zp796)-L4CFWE`97l${h$3L^U!nHI{p)lrO3P&l;Y@gf+#Qa0OQ60ZnRs9P5Kt z#Y(KrW#J7>x} zkT5g zX~tt5I22h51c#s`5s7#}(ebxepu5UDMNsTp(Pp%dq26r4Yl+$2=vNvMm4iUk*J2LQx(DMNO{ z)Bt+{bcAkEgu^PRY6YHwBqvQFUat-|U4g%_3*Nm?%_?(O{U{t_LZMq3;h+71tt>I`Z%!5BSzD zsoyTTf+M>AIUtqRy)*U;8dj9w}op}9Y;_rCM%$S(KBz|Bm{*Vs- z-<*Uuo|D)kIR2lU#5wNb>;jKUoS)&&PyTWehyO1*iH-j~CxIsYulUQG0Ut3#SU0wbD{rlIiU-$5s#Pagu;v#P8BX0H!ZY~4&CFTDB zN#MrDaHCnckzm|_*V$nH#Kgout^^*Hz;##QdLQ6AZE+0^mo-U$6p2O+T&*JRvncK( z-@nO;fq?^)<-&hOiDFzCH|{+xu9y;6 zMDm}a#PK`ky3(}&ohXrw%Ty}O&BS0Z+1c5+_c*p$zz)4tJTmN5j68~jM$X&&W^5ghXn$L$j zcuwM!Tvhi9rnR|XS~g&%#Y4`C;} zw5-_uN~C*UBL2T{65Sw-dHOux-Zs#5A4jjUAafG&E#)nJlWp1Fuh#$MBo>1da7WFc zv~(1~o44$tRUEMNF!jbR_PhVVNeuqDqxv75#7kH%^ntJ4A5OxGlVBM?Dhn?i=}t?K z=|!_As>r3~*ic>a|K%jOgPBRB0CLTLa}s81wHoyLW`8&d3te@H{6d$5y~Cw>;cNRD zA6_+OHb%2#_fCO7oWyJ6XMosWPGWsEnxP%lk{v>?15yHu{Tso3(+>FYuW7eOMN+??dbmfN0R8r z0$pK#LU3XpZdwU7?ziWNzQ?t53}b4wq>_aav#y5|R(HNoxG}ZeX+#*YL)c* zZN1rRpEJEzh0k|0i$k^GYR+MlG{DKTUb12RDVjl$kln@M)cp?^N0ZQGIPrj@iaKM$ z)vzHEn}~`;k#eD&PNhItK8d9LIXp&5m7zUaDUK|MSg}ZfiF_YK%p#jZ#kvLvd4L*W zwE5lxGq?S?eOap4wcMR^F_UXQN|va0!V&LpDA0{GWH$DDpb45nS14w;|K%j=X?ev{ditGsAEyn*7fPj0_wl76-%O43 zNPmjC&Vs54zblj{+x44^uUnmc2VemhJc;;DLRmf`bvC&_p|4FzlHW$F66+1)!e~x@ zWdr0zNa)WYy3Jo0m@r7vu);`x0Ru@ub*ajkB!oAu&?SyV)7M~4M96X=tmJCM3nS?8 ztlV6lnla5l}0$Mb6Lkv$i$dCHp8T#~&Wt|?pMUodA|0gHmZ*~vCMRgs| zNhH;wA073Ef9o%{sHXuTp4ij;H0DyJ?NJZ!rV@Bk$;Eca-&a+4Sn46nEqXnrTT_0U zHA#p^h#VOag61gG=gyZr@YhpUMzN%bp#)u*Ev#prr6(VLzs99MZDUyV@kOJM6IaQ! zf^rUfk65eI>*?u{g^_fY1{c}t-kHgnX!-~)81&MU=nKwc)nmEWP%t-?fPr5kdWQiv zZOSJBG^{ZDueH$grVw3Bs8gw7Apm~gL)18zRA#D83DA!5AOjJNf4o~)S);ix*x#_K zgyug5k?raX6gRXMKU~#cY&{6OLI`S8`DiyAn!hWn=0T)%*&@3{LjSa#kc_t}G|8*K zl^B{6A-~cRYp6&CXySk3W)8VF3_?_o?ox4DU3}~};?0+cQKhzv4`yj?v~i>fRN+}X zojK`Lo7P|;t04}4u?$UJ15->6li#7;uEHrLP4(VesqC0CF^Zz~zt5E}a6rJwf!ce) z`f}!^jIPU$;_*#0P+~xSIQ_lh#Q#dx;rxBn?AsN_P5GRUOf1GUpa4s{^Epi z+v``o{Df6M+ORU<+om+n7e*Byt(&o3^-`>_0mh58R!oqL!|kA(BN&RO^qN3TCO=$Qg%l@^;&7m#p z;{E*95SfDS^ImRvU;4s>ph6D6ZPO;VYV5N$c;7)i)Jk!U;Y(HLXAxH`W-gHa2kG`f z*29l+kAIe$*f^2|e(5$S^Lo{nfs|d98)np?8AiaQh3x5HKAc_>iLM5cg=2H#l;VwK z>R0;EN1Z66z;AuazelT^jv7USfwVgp+pko@#O$NNzZK!9A_wKrg#$qga7{EdO`M{&4R}8p8iQ%OEblmxxQS)hEb|}*uv6Ej6Fm9-XE|9~%j> z2v0@>8enF8>S}SxKL6EI(dwsAX9XGz8EJLU?<0RRnt)}QP-)5F4WCd3=isg5fE`Qa z79M!pQ>j1Ru7jx0W4mU@h77wr=ASG z^rf|mxMJl7!UpKoL{zT^z$!=!5%8AdPyimr$pyi|iBv{Nvph&@F!bXxs;I7~1JodK z?Wi)oh#y)JT2oOpW4;L$w;B&``8>5Fu)o%oYJl{O! zVP0^UA~kL;D)~fsg2)c6Wyj_mJzii(_QMYD1n04%RN+Pwt)Y-QvFqT6T>vOf=W&9w za}q;L`P5a9G-k{D?Dn$44py;ubDue{yF2Y{gz}r7D{i-q&r8x<+Q`9NR4G-Rhh0(~56emU$M&KA)yp z>zsI)113AUJHpQ}=FB}&lXz*xu?1t^@nzd%KrBv4$@4SN9nhE=2dktdb&SNG9mV3T zQdFpuOU09yOp?D#Czal3r|^h^rA4hdr|{N_dRYifMhW#eqYu`e9aazs7oxd(&{&4h zb)4@rdE(?KF2Ved&(3lL-%}^vwR(OCf?4u{HRN1m*3ojc&y8!@eRKKn7=(o`XQ%|f zWo;_27k`Xb@}uX;B*ZW2xnBmPfKgf`PQ>>f`oYhvxGxw|y?U5^KXTvpdgc3o$LiUu z!0A^8`#g@nX-L;u@g}<419}tGlPHh0U@dop^;jdhSI>yqd^zE)t*L1@LHxO#ucu$L zgSoGv>G7(*{GWd7K+;?6e&doMMpUp<#gA9a>3u|j{j{{nxqR6w~#i@nKR ze^bMmLaCin>6dZm$*tYVA_uQNSOUW=}0Ed0*wcV>6S z_1NahdLC<}#e-Ex>X)T=Gk)2)pS>P~w@V0=ehwL6<%GcClH8y?G{j1+43N4LP8vyYV*# z3t;PMN~#1OuoQ>J+%@&3W?SWAH^2dhC17dK@64{bq z*~**uWv9jIz3-4Sth$K&uH<{wr)4%T;eX7C5!mvx5`|cdT18|Py zE3L79=@AS6;86_TBR>9F&?#SmyIH{yP{Bm{X&=U>U3w#k$)07$SH zWoXeyA^nQ?r}@1<--Z-_@}dGP5&7+aw_IGA_6&`SG5HaSyj`$Dv*fJ^^QS)fPi6sy z(>eH{R{A*8$1vSunVHYF0hN0CRg9!no*VQgcF?p={~M$!+tUTl>pr?O#{`VYgtSS& z#Zv4eNF_WRucvdl=)Xx|mT@@)Jpr7t#);eVRlioM&vo8~ZbWs4EB3Z2zC}t2zw0%u_EyJ-0v?Eb zW#{@%(hnJ=ud+(&-F>wl>{jDbBHQ zmKN&s8-5;8Z!F3fkA<+bm`CP!)HU->o8#?sKnM$QwRntwCdO=VT;JL--YVjHbDg=Z z3(_Wa4qS`B=@j>-69N9E&?e*BjJ)3TJI)tDmRcU!NKnz(7S})*SBWF(i1e&RMHT$; zt1tQ4ViV9#=Xa;^tR4`<4+9%Y;yP|0G?4wOX#^F$cnB4a`ZT!Fe*ImujcbB@r-Sle zFXHVinZT`1=lAzrSTfj%>pfMArez*l;#j%|3Oh7zb#3T4IYl`|%~JdlBNdoxe|)tn zy`eH*k+%0C6cv>eC)CBv&4Sk=6#lJ6Ai;PoqT#O=Vf`;H;-kkc2L$=?FnRbA4G&4r z&y&v?b3GkrJy5?*@_68r^!757ZXge6Ae< z%^DM#%fM$Q0AQHV?i&Or<{ywu`7M{|9H7s%BPRfn)(+F0&kePm40-kSchwJHC1)0} zgFZ&NZsDwZh1}@41pgorJmb+n5pcG0idS$DJwP&r98vP1jKc!laMF6XEPl5q7NF$E z3lX3iezz3C`F@ds37O2!W>rFO)QisYP{{nm!;~@P2y_A=LWQTK;1s&taD!p;vvSI5 zEDe~0XbpqUE|5*vlRw8B@4J+O0yfV>CvILO-I^c0BitRiSr<|PdSVCNxYsdmGwkU- zAe%sOJ~2iB0{;&rqC?^j60!ajk3;|f9#D6iB3y2?Y@FJho~lq7z9#&skEP1nq};;e z(?im^2MQm{Q~nqc!+(tkvA;%y?I+k8QUq^A1mR&(JQDFit`j3XVb(Y_);HTjR{e~% zBZ_SD4gQ7(4)ykcUBJoGn7fi1KUFP*40aa{@J_@qTfkOIQm~bf^vChsg=aL%f*_?1u3i6w_iN_fitx zc`m>69`>YsH+(kVedm)Tqa@>;$zLG?OX^4l1R?$c5l9FDRezgJzsdIUjjYkl((eH4 zkHmoQ5b+WZyG1s^k9;_H0g2#D)27vOtM5jVrG1%e3A*cGdqVGINPF^=T9@^w>Aq9`8ag;GZ)SCuJMgxM$Y#wxbG~!ryH#?69tv`Bj@>SMtwS zvJ$f}Z0S|O8(L`_LxDf5IM<~~ws;p9UbsQCQ^~5BHc+;*U4v`6Wt)8qtHs-^w!(9w z!VHAB2&34FK2kK!+iomUY}0mcf*UuCggTzo)BkdV%9XF{RbT66-Lg5|R`D9$Z}L3| z?(9%57~FO#O)}fb2mmk}4LE8Z)pFA)GnA9y`akta3OL!+q)M$l0yO!(Gcg-ZY;X|lS`8I#Z z0WxQwzI9(E>9K0kcg3My(#3THerk}|A14gjlI*|<7bKLozv~cn}>*$lw zc48^Lu^rSL4(<;6tw?!D$9Y(u?T$(MnXhu1duPu_9OPvOy^4fwrY`n2ACZw8?kS&} ziJrL{T}a_@C!Edn5&nPJhzsMfXG0fdkJ_hphGuZ9cX#&EvVTW~z*+isOyLim22R(E zj?wIgna!8~;w0EK(u|kYqR3g5BN$BV5<+CTZ5vK70|fD`94_DR&beALmjS1cpJ@U1 z1)txP-wivnW_7k(Wm0}L_f=!1y)SM4ND~;%1UAh#X6vSf2ARrAIwPFpk@D}@D*aRK zEJ_J#y)Oh)u*?dIPq;VUw*BZVB{$ER_S9RHk%WV6@A>#iA<^ABj5Wy``nb1BU$BWV27kyOWrzTb4mLm3%fqP z``-t$`9c~L7T1uo^&tyYLBLh-XDqPEq~Y#kg)>nIrBZk&O*xW)QUfk{xO+gwV(D0sLuf)E-p-IiE&i4<+vNj^ z0tP_QzHvRE=tRVkz*T8)X-MeukOzuaGkXS_e&#P=p{^64)N7%Tzb2N;?r01=s}u|o z+{bdg(vUQeR(&|yEB?LS^c|B*;Ei%w(%jZWegIyOZEX1FajECS0p)Eeb8}0c$5P)kSg%-|h(tcK z5Y&uqr4R&s<7tWA?!}JBkeE}MTO?^-yBWsko=uwMitVe!EG2O>RavrMxW`xLk{7 zAQdv4o_`c$P~nj5^P?7-!c#i!6l8LAluNu)9!?0}pH2Fan=*5vn28H0toykfT$Z|) zlkK!?`0@kXuI;Xx$L@;Qa_e;ayHclmx54tl{>@KczFK$3u^{E6f#Ba2o0v?k`u2=y zuX>NRfbg@)y3BKCk21q;RWcpc2v&r&g_K}S9KZpbe(f)V#Wt=J@(vn?!VS7A1mEQ|or=caB^PJDin~S(h zDPW7a_a2gZ`2gi%lUo$}qek zfmAkDbPV!(#+>=GOYvO#8;`g+*cw^z@yKn}DeML_?y_1HhXdh-Q$)7>qiFf2XvzL%iV#^1POwR|CZ3ZBPt)MN^oUUz z$DVudqLgEDV`KtXu6%aZ;BeoIk{w=rC)KSgu`mc!*>xiSHG`Dx=858K(5!4p^l5is zJFL-GKKkEs5=5hL?;3SBa44O+)abKU?caFlsX9FpD&n&h=LE2!EuqQF>?&d~67y~~ z(W?E(n@tZdGGX(vaJe0Y9|FvI^6r`64W9I?Mq8NLL5Dwv1WZj0Z%7C^{_>r7 zMSQJ!rx=Am#val{7WDg3KY6B|xv8<1Yq&=tp7DqXU#6lI93f=SHD94}^7Emk)znHh6}Xpkh|1p*KF zx-ZQ>iZ^Pg=>bWaD7w--LU*iQKy!ESry4E?q3dv@Tpx$n`y#h3$EyL;5gHCOO;=n! zKHn-^HZ`tLQ!3M@Spfv70frB44}A?j*8X`cHZ|`a7#Uy`JTqByr0K54W`!bW40j#W z6w< zx`{$d{K0zt6h+c@eWISuHxdulyT0f)YFkmhi^EykV_#i()a|%O@n1=}zB#`q#ev-3 zT>Ey)RDcOR^n5`@=-5T|yVSyaPqj%4)dk@KS-N{2DhqXP>P`1w&GlLjWOAbWa1)_D z7)qhY6Uj+>6D$9NA!(@LK5r>QgO!s+y1i@i2V#s-$~#HSj^Yo)m#>GC=#1Z(&@ash z){Q<2wxZyFMV8_;JxcAjAH$*aQ~B6zIQ;Sn{(U(_!Dbl<%yY|~e=nz)Ju#Bsc{p(% z|I>_pa`4pxw#^EVbg(g;eA^_P=M%VLBcmYo%zN>@pYT=<*v{4h1`EnWHbubCA>pM&ze960xxL{LJGGOlb2WjOMod@PV=`}$2l`FVT-BsW0 zvy4T<`!#!wyY*|cVdw4}AIvigTz{{X5kC6#oXXueQgZIAwP%eL51VI5fF;5&7F>~_ zWbenGu~2pC+kZ^$wWeJC1I|~wFQNgx;vCS!fcw;Whr&IeZ*J{+&hJX=4eNBti;n)h zp+vP%R^O6%2cOPuWC$ayeiZ2TIcmEtxFR=*?gt6e6hPh z^N$SyRM<>4^`>LlzP%$OQ$V~|sP|w{NK2cIQyLg+Ecoj}&`AAH7vjo)xDa3_m?kRP ztXL>kM+wL7*k%f9ZogU!J3|)QNjLd5$dY|LpH@m*`=dheDYk^7{;Ckp|ELf|*ng=I z8~>p~pgGYmn6ji@)vvwBqOD4!7&?lr^_ADBNaNHx53XTo)qyRxnXb=kqs<{ z6cuH$8z!1e_z+cOb^_&q!$eM^7vHt(_qT@`^T3VUj3Tt6U>(oukS26TL5J)6HElhGw)hJ$TC%rSjPRsS6^O0-Z z_19^3<>HF(B|J1pD4oM_v95o32soaH*d?U-Zyo}wg6AP*c|wQ7?Emr*p}vHy@klln zov^^RJ$cpd`A zl>C>6U{DV&SKb_JdQGeIv9ck|v9wxBr<=PYJifo)mwW~hshHf~Gk5)lYh5i11+nAx zyvNrE`?Yxbbql*eO#(!$nEozWwFj>Cgn2z9+zq3SXw!rKsX)zQeiTjtNh&jJ@XU8$ zF1~DOub1~+MkHpUHmHwc5aYI;sPQqWx$ z43DDn9UB|(Icg*R7cikyZ*}7ukF-pqsoa1`rA92UM&q!QqG&!&IH8`J9IAtj^7AE> zfI}Wm_15#7sYgm_B#h|>$+Eb?(sZNb(@^{qW4p|~iNgf9u+a}ZBB&YA>{w_6%-keM zV1Ai(kr7QIi~r}om0CU47}Zo05ArW3Bp47UC~%4( z6oEG;^bb{y?dfpqUdw1>;br*qP$PnG(WV%%|3t*1ReI7!x|P+Ng+|$wb)+ zMi@d76G5t6Y3qDpm|=e2_5Imq!a3}fxfUK9_0jNiVtjn#ldc8e{7mN_IFmlpyF6#uvsv6;6oaFt&QBX|6Y65`7UPw1s~$ zPkzO1Qh#jf;`OcXTiIedV=3__5mrS}^6Un9V?yVPlQYr1Qd_4+TR@+LcDTyK4)0no zoNdX(w4;p}vW>)+2(H=H@+`KjSS1loN7U$VaZP%sMc+&Vod(@}bz!@E5ks(>VuyS) z`TLHR=0K*iN$47(%~s?Ur{yaaON543gN?;P@lE=EcAxnkbjL!aVoc1y^Q-(Q;ts0} zDf@4<6e*GRRnyV8(js}wA|EB|CbZeJEsRkY-c6BJP{Y2wB4&`TsX3i87lsIJrG?Qm zEaGyJE8JyF!Kg@c4+pcf2*$E30SkTVvb$HW#k?;dW}QwIDZ4{XXP5K`m_Xx!33>~M zS05o{nsrefiz*iKvYI0#y{KQDksWE_PAo^mQ17^iSP`V$Mb{0Z^fM08ejZ>vec&(l{f6z^+lX(}e~k&XCVSiM zdjQ2!D*pECn;>r9QKxAdxsA5{V@wcwZ_PDY1g^=MmQ7!M2dxx3 zVFJ6fYW!+cgFna?e(a{g#EPJI@XW++q`%JMBc4?+5f*>oz18j{6XFN%{^XC~tnb>k z#7Y#A_yf^ZILi5@6Zy9viBn;gf0+qiL8r(|ZWrGOCKOc6uH~`sedmRH!G+E#u+Z}p zLQ+f(?bD)%VH#%Q# z#Qs?FKYBs#@H(Jzouz3dMb<-e$+i{BT5O(iMdHPWqnrwGin<2u#}FNmLVz_5n0^#To5z;h0VS5Xcg^D z`0ykQ#DEelBC;so-cbIux!~Rr?6R|s*6U2fy`hlD-uSWL!qH@r#2;$C6dh0#9h64+ z_1EUN&pVmKnW{>88xE59X+zj`DHJN;sF}DByO~XgBdyV&@=cVAK={|=9epAnO#xnW3(?>EC*WA zlkrU2GxFO;jHS1%|H85wG$sf1LK zDlmjB0h+q!l;UaIGJ%tGw6`6Rvd2AHc6%M4!%zLXy`oZyYyfk6Hxqlu1AFjdNtH<$^6Rmu%9-@fH zCL)>8(O!6LLdWOnqKNk^N8FaXkIR;rA0?qbA39-sO>^LQNn}N?xAgflO$iP3W9O!D zD8P>0QoHXf@c86MmGfSnZ`_9`!h7rcfyehn?*>=D4})uajYA)6bm6fHUy0u${P$At z__06qyMJuTaz^0t$}f~3)zJ6UIplCv3l>|c6A!^l6Op`0(QJ5WqFW{3=#=)BKUel+ z|EvS!;l!|-qvHFA<8&_3aNls}zsv;s4>QrKwf3o*_2e3bcHvp=j;D6BmxW@)uQDHz z)n5rRa$;2hcjz7dF(!DV16o8`RR1w1;1N!iXP>K2Esap`@}7iaf5m5yjZ?ZPvt~#h z2bzaQ;L2>mrPm_-tfpCH+=80@GOAIpkx{X7XyAiiZOD`M)mKKmXgo6^y%RUobiw^Q zYLp$OdJ<*+D0o$6Ym^kkE=MGcXC@f-de|=uDIdq6{$VB}NWDF0n}angqUr8G4%ofa zX+Cv^!T>PzA5J2Saz;@W4Yq2&Yf8;oLC~ez8qWk0a;^EpNq`k%g&vr4v_0p0cwUmT zkAYvG-QS`<*#Dso$03(C*MIR1W7MLlgZqs)y=T@%JZITO4x5Zn@@_s+IHjYJ?uwhW#5aT&}9f60j)wwmf|+jDh3 zzqVOF{v{_oUo%O|Y&7*Oirf!oLeV;0pmMrv+VJFrR{E#!SrheoUz8jM$9amvw`ZHa ze0sEVsT3H|$_8+gUq zmm{hvw45WFO=F3{@iR{mMw?TF;ih>A_gE4?oiiko)e2#^6cdr4GoHXK?Rx{hX_Cf~ ztV$xsZF;`>nETmTM0gBHYvBIf7-LS$uXe12$iLzQ3a2G7Zr?=$Gu53=OVjMJ)7Nl0 z$a~{f_nS8ZLi}IkglxR=3dIdgr5Ni(bwZ|bOhgq`3&%}1Q)?}VjlDMQX=cpb*CAH~ z@4WG(ZZ9m%^gmtqZ`f6Zvo`<;ooj~5*S_apv#6UXDOsn|dl?bf9?t6NjCkk%>hxQQ zs)9?eKv4%%!23Ig2eQU^abh_9Q*fEyo%g-w8#X23F-Sd?p7XsFBG0LoHZ$yz&X z1-ENPJLj25!yeIRaz4mE;zXVc8f6dywrEa+V53d~F%k$X7uL%3d2Rq)z(F_Xs6mrP4tCX5a7202tB!vfW1 z?)W`ysx7o{7$qZr8wFbF6-pOLTe=|23wIG1wuh4199}p7%58ncPxlB=HO9v!2IY2J zC~Kig#ZzAifW$d9`H6THk$^2^fk^-TS66nO^M_SF1g$%dMvj>pC`B@lwx)+%x{prL zQtsPiw4JYCx_|hEv$H!?ztBltDK2UIHMZE`IetXlhR_m^|IKg40X-I*>-`sQ#Aw5No4*n|nOE19BK^eT8$MzaV%uLuyVjU5Iw!jZ-wbNd~ks1ul<6LSG4Mg*V z$%_Ttub7l)Px5)B1te|-a*I6vodOeDCS7acrj-7j_{8}ut!Q%Ic~Fe&+IVk7?*8W;C>eV)%~_+CSh?2}6oigsK~WMVKvS+j@`$TH}t z;SVP<6tw>-`!Wz9nn8tzP*-Az=I4O%1e&6FdHyh#YTfU?7uh( zB|+2Y#p4AMpWhh<37X~MISD~?O1O9wM{aSn!W0N@b|GlhCOBE~?DKow+wC|#gIu8n zIZ|uFly(&)2%t|>V?KmK`E|tLqPr`s+ryD`B;W|&hHykcca&0bXq0qMWnp5FkdC_^ z{HYi?Yd@b)Pm**v+J&xwZ_8C%h15F8!jASrEQ;z}U?vu;N{}aA#A1?kXgO$3 zoYl12iKq7_%|0rB?P8Kx(Uq_t^Deut2RL7mOz`axauy$xSZ6@aXSF*ZXc&90M@jr} z&m(I}eyDonkwoJ7t_u5HLDu_YO}9zaD36YZ0kMO0UOyQdG+z?rbpqQOY^YZlO| z^2iY6T~e7f6kii6TtdfznbvrRMcCQk+>6JgM~opTTOGJM6-sjB{f__@zxv8I`45cZ zW>l?1KN2uIQvHOZp_865FdKk&%1#XEULuE^`65=*(vf1S@QpSg5Qi2L}t^jUEM&TLJ1}1;K$O!b8*9-o6=*Mi z212wv+>U%RoWOPOD-qZ)R94H=NFz`U(cp zG#i0(7ohTVqC!MRady+*maBvOk1XM+wPU+#^}0_>!Zd$4+n7a;%RDsq3IwyMi}P<* z=E&MheybSvZJGVF=0xQrC&|Yj!`LufiKGinw8pO%1_4+Fk+P&9D;p|6_7`$|ZrOTg zmY;uDyYuPo#{<8uNBdo6P2&-)CLTRguWJ)o&TDqF&(2eoOcu#zkDEe$F~k;+)TC@c zws6@tdIkiVtKVK6kV3MRiL_1#fRcFIsoDr05Jl5)E@U=q(C(jfN&LL-({RW#f;~Dm z@h~8PIrH$a!|7|u26hWedPjL4*o|}Ww}czx7$HNLPRa$@a3AUxwzvFX8k@buVJgRY zyKZf6v`5U&VBk(D&Yn@n_3oFer91tX^(%4DLSGR&9BG9hfuiJcFp#w#?Bi>6m*F=P zZ$z)(q@-gnHr}T)oc@kjcO9r4>NeNL6z8V26$6f950g9B|D=RHd>EL)g01X8IW4m% zhrba}I{w+*Jmv}35`Q)l50eTp#J}qE3hT&{fXqnBILRrUK28{75H}ep=EV_YP@Yr^y*S%L< z`r${E+rq5IYe?~OotBsgB9GK5+8ipa9An3nH=9dzhLb9^+AO{L^rj;#tapqZ0gdyp zxCTf(w;|h44qA#xW@=)VNe=yUbylZ-R*}KxRJ%{a5KuRx_~skkB9vBS4`RWV@3ftR zLYK4iFB>71%gTme7+exufe^@Jbol|gCllOEdcrezxsNpXNqYEgmkG|3OLB7I#ksU} zoL}c7m>qTV8rzq#p=@(2Mi@JiHwfeY|A)1^{)+1F|AoINV1}Hb8;0)gl40lul~56e zZX}czhHeBzq?GQEQjl^80YwoI6%dpXDWy|n?)hBT_j{f1x$k?OpU(Ra*lX{#_FikR zS3Do%5~K!_q)VI^NI7z+aJ6MZ1P{$}+yp9n z-_BdrJ6$!CaPETt=tA>JzNk=S#Um^-j3dcSRHzMU%M4Majq^ibc0SmTWhF-Y%X@|j zK`5Gw303(Y#0;5urw(4y>54VYa%oYk z44>uWs~ZCO8A&XqS~Rn%Y)! zpg|%ut`4kD=C-_|9#z%wDi8fN=dvoaet(J>FN%lS*0s|2c*QRl>gAf` zHT9J1VnTY-)hD1zkWujZQ*C&&i_l@5fXtdlT`8aE4-xGWXT~h}a9v2Ro0R$Cmm}iR5a?<^8f}U%9H#+(KJ`4Kl z3Pd(lbF=a*?EhrEf+IQy643QP#+x@IT@!iYXxOzhuKzHZNDC^{jx}{ksjCU@gNE28 zh5ViuxX6ULyH``LqZ(_X1FF$bXN@!rOKzM<{+cF0aLL@L!SHyPFR!KE)KB|7k9ZQ3 z{;eh~$SpO2SAXKI)ag@00`0exFh1PN3f&T7Ldpt6={DBKjbv;d{Q4cfC5DOad-d$E+y<5m!aef?J} zJ!P{nTSU+BC)RU_>kuNtw{Eg)@i$ty*v_+o)XSQBtP#9O(rlZs@A)jCCNa`IQXr06 zAC}xV1dlLZPOh!Y7Ol#yGyLsV?OO`y)<5qfB$ipNw90Iqb5upqFBs7SS(ecQll7i2 zs$W#Suj2gCMY_Z!_M_X*t4(FAmJyoEtfgO|tuv%qakka)lz+I%wK1W(yNi=#aZm%N zH6S9^EF%`qsu^`!Wmti~5jRnsyX_+(#^@uK7PS5C`2eCHKiX%|)3x&Qa#NEXKL!Y! zqVVO+vqk$t6Lw<@0%j(`kx!SU(K>mPObgpOvPjNN+ zSIFN?!Rz85&NodiMdLPcNp;%>dG6bBjZ=L-gSzW@Q}=%GA|N%W@ecC!h4>3sF?^U1 z$d5u8TB}bfoSNd3@wTB&+3sKb1Tlg>f@|cm@$3n>kg=)IR$S|{;Tt*h%d++^|GUS( zh2}9r%jDje8W1Zq8cFmgq@o+cB!2n)!%wVdG<~gF+sdt*&u}-}ouuoM_~^U!ZE6$$ zVvuLsmxH<=k#4qIN4D{qe>T^LgalZTcxMu~)j7}q!?bC2InPc8%{3pZ6XeVO0w4cY ztI%~P(|gA}=vnKgWGw4YGbiMtHf}OQ_m!^iH`<*8Pj4E((R7A5y3yDxJ&>QD#ddzP zli&vtSx^7cl3n&`=Xv^E!~qq@+Om;oUrwo91xcaJS$<}1;^GdIcZ^DpB*`6ap$jC3 zuM`Y%hrE7QY06NlVbiFAfL00f`~3Ua22XRl*lvQH6lNDQ|H%(o_DMr7f!a$FLFab< z)+jg$q|Bx7wDTyc}KIAxq)83N6ZEe`wDM`gf?EZzP42ZWzJ2<-^L+1Yc!TRsbz~&@ z-0~Ff1yVNciKw0~Yh#v}(ST~ZCgXIBB96W4UCV*M?ypLb$-W`*JD#b4JJOOO{A_~n zRS323F^qf{=91_@xi7i`R5)er7<491y{JgSsI}pEf0>V02D)p2qGZSUZ1_quRm)Z# ziWgYzCf^%CSZIlVlJ#}IYUI$8J=65T*L6ENF|~5vLtCk7~S}f zFx>K%syUe3^4=!*e17D1B@{DXn2SyXnwIMd>>Z*{+Z#4m%<~`JdL?f=B5z58iQ*fu z{sFRH(BvGIw?BDqPmsqxWVop*$M*3yq-OvjkGZjvpi6-0IkCmiX!k_p)ySS(F%fbs z?T^)6UbwZ$ExqfAW?Jy<+8pu zG6IQleFDamRUK$ie|*Be_0BC`U=lGA%oi@Z9V2tA1b26$QJ>wEozF`vDmb9NBlX2W z$?!4nQ9t657McEO93l8}nH2fuj={U{_tP6w>130xu_bFXCM!;f5WoE#0$1vHNwk?; zMsXZX1N=+P5NQ%cSoyPn!tI!?<&3er4+3eZ?hYcN`!gvd3_W$} zT*?`Vp+6K(lheN=f?huUt|SRbU}CyEgom?V_bzBt&PnYYk_r~l`V80%Abw~eM$d}s zL!bQ70aK21hm72t1_>I5a(tAoQuKNBYQ*@CDa?lWJr9P9o+~oGth86L#u`Y+0m0}a zKEY0unewW4SNPqqZ+Agse+Pv#rWqSA%$7gD^IaP$+uXto3UO^^>KLet)4SxJeA&tP0&TzpEG}0 zg2(I)r|kEDz2??(_-O1!=d~W|^YCvK9sj_y`b7$Fe;Qb+X+DMnhb1KOFvw!bN% zj4W?OyBD<77Cv;19Vo4SrDCyN*ARQ~*l5~0w)xVoMnKztrcJH{QMI< z6&5}d)^Zn+1G4UpT-JeNr~^mzM^s#vh7MFf#q^=^ghoLGfE?v`vI48bHDqiJS5eSZj?_ zA`Fv=;MUDyZdvS4W|DTzv9Tal;F*;p>6NofG_!e#6;uCgm$6*bWwf6%5#Y_1zWm|* zx!={SSR0Sjz7AI!Xx$nQWLjPO)cyF5eWCtea`x_EDGT_(IgN;y#bTUdPy>DDt&o7Z zzMK`u%X*pSiH;|ls_batpBh(6|H)KS5n99-d>yznsQE5MkqTpMcKrE1uBUYnjPT8u z@-Oi!H9Uur<0!7pZ6-r>97~w&cIG#xc>IjT0}rasG&=1$-KzY zDWRUZ;Q|+MR{n`HlmV?I>K$8Xp`;Fz2^C4kyB>}_N87xqAWK6?Wi)#<<<-$1TQBo| zlHM{OW;m2S38uPCS*?lX(n6su?%$%fpEFn^@5-O@QHKbplNKjSsOZPh zt)6zodt`eWWFF!NGDO*DY#b`HhGuF^;@_@t-N#=ha@}VJ@UgBTAnOvH2^MA?d~L%C zCB5nZEwyoLwB%t=A9qimY6vae=_j+M+Nf+%kn=C3MH@?}31J7Rl@uoC_Q%L>7YQ`Q z?w2HgC`=k=VAJ#)W}-v}3>9HP?r6@ik<1aA#6|WR7L}71ZGOpyc~$KngAjHhz0@CA z4@xV_2;}8JS+iCKeN%>ASbgepkC3@$NJ0UZ>w2Fz&$eMBmK?(Gs9uKiq&$CX z5c%H~0VG^hY&|u4Ta)dinKW!|z(;sO58?6w)tB zX8EA6YgD_(Ye>&XM-~jZOB`5ks9WaPTh9_5PDt0%Ae`3yctrAIIS6IQ=qrw% zS?Dt-BhJulee$97o|y7UN+4ybWFRT@(3#;RB-bFDFB^o4XOheYH=36Mvg4q%?F|mhevOtVbGf{UGf`Z!5b{I z@7>#Ky0)0OgeGi{$ah{IZ%gQ^7O1&VLA&qGM7wFEcJ30^tQ)k&bN#=tVL>N~8f1;7 zCY}2DXm|{+S~oGs9c z$*wF^nca!y!_Z)4g(#%KX>LWUEI;ezW;^xMW675b z)^VlO4Ehf?cAZd(xns9Ue~s8)=<26b7&R2F1t&qFPlg1ER_NU?lDf4|n96@4e{HfkQLLzxWoZ{T?q~V0 zqWx=y&9($l%^RGb3>Fa?-~; zu)1*JlU;E4(!zG|Na44Ur@_6C(_?R(w0-V44mLC*4ht`i#iY6q_R~D|izJ#gG_oG9aPe(L41F{|zt@10Ly|H+@pCjq`9rf$vmBW>BcW>|v z3aQYt_v9e_r`k8wJ14@3teBA=2k6GJ@`u^`cPol-Z5Rm#e|+-$x4Rz4?0M5+>H$+= zV`>}ZSICfd38l5_&U7w?P6BOvO#IuupzR2Pk1Ezd-9yU$_PZP3&ll>~|9jrJK+DAa z>egccX?~K529(*0kte%h8M|MFX9HUM*moX%;Szi6j|jjo!@L+H8h%7(BiYNj)YHJ= z`SFkyl9ziqYi$eSTz?!A7P1t_;V;~;5hpb@0q4YvWe!4!bz5Ag*4yUotPdJ<6jn!^ zlW6JlJqq!*)ox+{Z|buhT18VH);)dV9wRp5tzhwmlx?K9&j*WAOg-1=%%Ar?Yi9ptCk=`x~g(`+BN$mPwae`yAB$;2vUg4E5s^f8du zx76AWP4Hc4i{u}>#<0s$c#uFZY5?$#W*I^pyY7&vcfv9Vqx^JTaBei z7AW8c#_eM3v^+$UBKr3#FKMYC6+xSP$qWv{0hw6tCM?u9iFwV7yg#$Drumc2vsY&ywFj?Erc(kYcm#gJt^KXG!51Qf8aQgi{1`tLb%q-U36NeVOI{SQkKgKMYtr!m+w zWtBck5CekHqOInr8ZnlF4VdiYu*BXmD^f8j^S9{|#}N9yBdPv$Gkv_jx@p$AFAbBV zBltJDj2}5bSQQx;+oR$3qO)uskR`UTJkh86U}CQSbD6@NY{klJl=mNsuJ8Z>i_%r3hzyU?jOfhV zYwU#|Wi6139dD$oWz~;Hg&PmVt}pT}5#O?nJV(zecN#g8Y_-@-=?~WwKOJbm-YXcy z2!`uZXQB(vA>b0T$=}z|M-!UgGd0G>G(hc`{tWeA88LPg8Fejn8MX{M7)|hXXQsxX zp3n&&$x`wkjtWgd8|z@aY9WnNB{YCUdL(1T0dwIk~(COodcufzQTn0sDJ09 zVYR=Gc%x27JEnV@=Me@{0$g3g%kNR}Mr!u6UN`aC)gw%sv`Cmz$tO$QRg1@fDq0h3 zN<^~uc-~Q~!5%5pPhUNe)z>>PSH6c@%i#+z<9_~;eE+SHJf>+|RzuoS$NH0=j;x}p zyp_g1vnUJ+a6lDQa^if*LyPA4m}8PoYtBV)bVJTc^_~^)b3p|x3xVo-!8tAOybMD0 zk)iCPn>QF#6hGNeG2Cc;CMbZ@YNH^RL-Wa&Nqud%d`52*WqHlP@>Ykuh2$rG_i5eq zk79z3hf0CB8$Vgb%VTDrYb+eyu9wxi0XBGaNN(f9&5sd@={KmpuC~J9Sa12+b?V2W z9G3gxt$U))S5d~nIAaC{9@7o~7|Yw1_v}9&*|*UyWje_(J4&vlH?ak)M1GM1ChSYlBdU=lk8yY|^F__N0mgL|8$dm^KqpaL)JRq;kZ z&xesaGtlDnlQUP4%-1$2k)VBvT+i3p?k^2fFIyA8p{0uHxO>_}2nAM-&lv6uTDhcJ z`qT$u85nqVu`H6ZvKEKj=JI#mYUBy6f}!uD@dN$H3q~IUeKI#AQ06ctvQ9p`lBMf7FX0UaL@0Zm1cPU-x75 zlSJ1xMUit5a~D(Smy?imYp^0M%}2%v#8l`Ak4Uu)IqF`x-i!O+6+>rFJpXKYD`!U* zGTj?w6n~!U6?M#T?>GX|83H>S6rO$uPOb=_ADtm%~HnE zPDwsIvMQVWDhi@@_E1wfM<+DL;AM`%4d^i%svU~cXN)(SN&kNO==rmx8v{moZCl+M zV_?yEhR5V{1fd2c1H*yK8een=Yd!VA<6S9y;M_>ji<%#-@ACX`UImNKvc%qqbdDlMW9 z5Zju_6o6q~lT;!!$U`xnpDnk;xOY#@D9=Nc&7q^X1(yvk#GQr7)p$I2LtqpEJZZgDVCF( zg>oJixtjRAK3weA33K-&xA3p6gW;{oojq6>t>;;*kt@+kf@9Iy3@xeImlc6o9XbRgQub%F}uO0po zM*3=c>^Fu%Qm?tEX%g8P{yZ8@J~D}(7l^+YO)q+FZHu?J&2Wl%)7|o>R88$w_{fOW zh+fazMqB0<+qZ#5_}=g_tqXj=+B*aPcmCb4CohISMvOPYJMYgA%@$qE&%YjHAJUlr z@PU2UNb$q#qG1Ai4`N}M?#Wm=`>n^1Cn%nDZ`h7A-JgOij0r!X3!lFd$v(B``(dSL zO7{NS_eIlh!r!ZNyr%j)Wz_qD=E*0}!gN&l$E{fCbw@Y9|DBVFzdw`QJCpu*hLH6? zIEm7QFK@upOCi%PPbS&ar{x#iu7cTm|907!e_MDW=8MnwLVZ8F|NX4@``^FcL01;N02m_(2EAOQxw7>4$s(2A6368dQ{N&t zk&}43Bz(Ed@NHQ-a)rc>C`zoHEv#sAF7_^Rq0_OHC8YYOxv2Z%HkUv07k)TIu06QD z=5e_ezp&;X`7`|X&-f=|c-*)6$o1sD_4Ld2tScLjA~*8;HjGl9tEkJBamrQo$<|$w zYPuA(UF6EcuJ-nk#x=tGzHJRgZfo{!zrS3Wyz)yr^4IL;^1|gW0{4~QvzMej_zY&z ztv{HZvzVQeft@4pt_NmUFJ_m5>qG3ot`25TJ%$(>uopeBXKl3K8?#?JuwMv1c!W7n zjX7Xr+2`dtygzWD!8I5abI1)o;=mk{rGOaHKkTc7{1WiaD?6I)@CNKZ^SE^3|VS!k>PP zi`P*XZ;ES~QFMK!oL!}~HhQEsrR?k6Oc)E4c`4f_kqiXoA(u%;m$(eED8MnTJ$!)_ zq?9C8I`9uCp*D*8*b%lMLZu`WYpEReG6tpnsqtyoO>F`#b(yQ=f^gi8yjeD;jZz{f z0n#qA+2g^bv8hH3wOvi1et&o98Urwa$*G@ z-8z|oP2`M(J0|gD=sPA0JUx9ZUWeiv69wRV2s#)`<~R?9%iaeBTz;8?rIBMgSsvb> zoth}py3Ug(14fsplP}dc5siu#bD~kHy!UoLBk_c5=e$$!h^B^nji1~pADAW*={ zkqnn>%R{!7ZNk$|qAaVOG<-#deHyN2L#phY#lgAZlIdvyp;ZFM{R36-Q2iUK$mz5)MI|^GDbsi+CMzH91~A0*oWK1J zd2(IWOu2Ca@7bP0umEQu0r%((E})@yMRTRO3<)a^f&8Rho0l4X0GxuiG*j>^+|NHd z){A$*@3Z~xwApuffSSpqGb#YuF%+09FD6QRz7W^s^S{LuW_GTE7yDHnYx{wOX3}(; z`w6JDl7T~od2!;Ea3BRA0Ld-z5j8!iVcYPvDQ;K5_Se9Xinq*=@Usgq%(Kw|WH(%R zd5NVyZ)uQqJ%pBr>qMwkTjckUl%qtfROxH+Z~5!56{n}g94QtX_H_`hIbzEZv-gt{ z1i~&v-l+OGTcj#7++{wQzsSN57`gVN-gck==!d0A);1s z*9as(N2uCj1-`09B3TKx6Q#>(s?;x6b8cn4Tw5@VF;j4h=r>ZZ`5i-!F}k>>y_u?L z8n*h-`trjMoNJ#l#^i3>hby!5e#o6Zh~&lQ>+X!6{hGTh4kB;MFA%I{52&(AQs;Uc`naiE?Alr82H4X(G3gLz-Pu=~3&vL??*^qmPV}n#Qn( z|AAHkfXd%ev-=#FQt}(?7}?i;3GzJ-)WMyKh8Mh10IvUvw^MKIg+vHkW|{of=>UO$ zY9ayFUrHSc$5Eim8SGAD#2TWz#K7289pfdYhj1;H3>v^|Q5Uv8!nMZ@h5S(EBA8l_ z@Wxmqhj}}45k_0}IV#9DYoM58>n<9P0Y9!3+!dZrDL0GYaDsbG^36T6f=6(+;v^lF z3J@1I1}O3rU>Xgcdgx&2kC?(~-AHu8dA-inLU+4G=SoY?3iNQV1UtC$95} zkt@zgWR_i9u5b|nOlCfkR;(?bBD(4YeY8MaNvsNo>S({p>U$@FwzQSIu9$aZ#BHEK z02aLl`$~oj4*Hk}0M#=2FKNwp%L~p=N3KMGfXDsDu5<1AiOV-8LIViRPXTiwEe>)E z@iHfLR|Crw1_})sYSofEg)t+i$lUWrfft$BkDC((I`K(ieE!84HcMI1cWECzjsabGXyYkZ&&eCAGPY9vyPu<05YT!O<7S0pBrS& zF-PVOAitTH$M;BG<+n6ACu0wPLA?5-VI)BF=h*g7tvBQwZ0Ru8fZvO@Vk&VU50_yo z#P=L1*>qIed$35Z*ogrFR9%ymi06lu=xmQ7#9=T;SN6fQ`jquDrYr(Hzdy+U336%bu@) zAU+ZOz`w`QlALT=^Ee=v+N5i0q4Q8vrgy`XD~|LZc!35Cwj?^bZJEAC+nUsnF!xWn z!|hedzdX!S3#R*=hgIkLDXwy?e(AqNw%qdBwh0&Eezi}oKF!V8N*O0PSar9>{=WAO zr+kga%)d48+`er>!EDWovPn>-a?ezEph`%uMSnGVT!EXlN$N+Eox?RC!m*pL%iERW zeKDmk63Tg9Zq?NxT~aS>g?*=UM1wluWD3XDQ=<9U4f#Bh0mSh8^kLG!QYj+t3(k2Y z^<*LpfqulK*ksPuRw=c&0|fy$#7L+SBnxinCu^U$l^ADwxBNT0cV%MWO$W#Re{&Lr zGVox6mUaewL|s>hr=@yMTLF>vFWv%R(f$&2lsF}C>-S&0MZ+iV9*V~dO2|LVeHo`i zqLF)PcY0R15ND%Ck^4E%dVWYgID6+6c~G>|^HT$HK9L%ESRvWF@o!GzsNqiUmObLn z%vj`c`?KC(cOLwi--6TM4b*v_U%1*aIq>Hb@uK~-$Aitqa7ydeEM16 z(X$76Mm?0=vP$B|uMn5JsZkfe#FeuT4=xYu35TS4L)tYhu(-oX&R%3(*RfxEIL;|n zfTc-u^(rAG0#A8_q{1wcOrj8-CH|>6s^d(m#^;eVLeX^k(E{3JGk&C3q~OOWQfva^ zsTA}+np$IuuP<6Xr5V!}QSAtO&wkBZXZp~}S}eQ=0ltH`e~eZV}#Zqbym>yk1-4d6ip zG~$jsV!b5c0X#WNDb9Wu;Rrw_Ujpg~T-Ebb<_nhpp@)_yE8b8-qc?MQV_dD8wxQQq2%ssh?JpXGXLxFpJO>fb5f9V$Igg?iG zKmU`qI5}NqoX6j(IMgR@ci)b@@SKA@cr=c@ZjKJ ze}DgSZ+UNTkFdLYzOzI44{))){$Iew_PfiC*Mzlh!b;ok-@pH@Tl`PjV*h{97LA0t z&xH9Wm;Yzlf=F0QJ|#><5Z?Q*e#HOBwYVH@AdFxydwU2ykp#TS|3EDS{=cZjn>TMp zMn+!0e*GWUqOY&7r>Cc@tE;1S{&5yb~YCM8?|U?XsD~J ztEs7}uCA`EtRxUEixU32vZw#$T0DG6NViyhh$BQr5rRxNg9HBWxE3Dn1ZNe(O$&mV z9zk2R$-&Os+uPIA)6LDz)z#I>$q9?a+S}XP+1c6J+TOZ#>p!%`)vH%6EG*2-%uG#9 zjf{*83=H)3_4V}hbai!gbab?|v@jUVe*qV&;siMff+!yW#ZF+RCm^Z+p)E+D1PFux z23;~SR7i-ctE;Q3s3@{D9FjlNlQyhN=iydNQjAviHeGfh=>Ra3kwPg z3J3`B^YioZ@$vBRaC38`P$(`gE>2EP4h{}>c6K&4HWn5ZW@ct4CMHHkMg|53dU|?V zT3Q+!8YB{lKp?28sVONbDJUq&$;rvc$l!1|3;KiB6AgH0X{b3BN8j z+iLfrjH5oNX7+{eN14}#kfz%)r0zNJ{*GtgU*RAWoW`BaOM^*tqIT~(TUJK?qg!Mc zO-T7M)qn0re~&p94!b)rRfQ-s_3@M6if*!pB;C$w@@};uYA4|by+S9qW zGWt-|e!S=9!Ow|uqhizE^MkG+_3yso!K&N8zq!Q{PE7yYJDdJ#QjPFbRr^FsaK}D1 zd)4>%&*{O|_YbcKE)D#5b039+8({^}!QAeTV<<8@IAVP?lgz`Rx(ovv+}CTC64-;* zmlDlx=Q#vH7~267p{kmHbc^-nRIy0xFih&R`%1dF1UfU$ZBIY4jma_*uJ)+U@37eB=@|bed5K| z@9uZ4;g-q3^{n>rqfo6Mn9``IMlVU&l%mia^>uJUeE4~#TB4|3Y-do z@RBv7C6`I+$(%Uw?uaDe;_wS13Lty5XnZb{=C8tYI-|qb*Gzr82Seu8naByvPH~Os zhdpQ}1~Qhx!uc@pyrjh40fpEIrDalMn>d)-F1c+D0!$M6G`vBNp7DjB&sG0Y^X8vQ z$M<#;l(cXBAfL+6E_&vPp?Lx(tf7a9o#Z5aV;&lY3A#SeqKmZFkcI#pckSKaKmNtK zcgX`IvN)zZsU%rrX{5Wil-ms=e*twvGI)|F^u;)_)98t*u#RPndfK)Hg6yCGi2ln_m+L^4Ao zJ2V-WAD(2|FIxZRLBY(sDus?W?|tn83qBoIDUBGI`oy#qts7S>eyAM}stbggV5?Ps z-Y^ZF`Up~-aO!D4A&f+x%X(bUlhdsdH?s0HQ7J+Yx>NIv8z|?{9)mbm0Z&qKJRU0G z2O?K^JDCx7SdLn#p^!41$}T8jsm8mD`Cwyo@UayI&7=nQ4it1K4A-sE7}GWslx~|I zE)X)pqwh(cUx2G(zNg8e5S@O{cBw{QURc+mghbZ(u+HXvomI!%PfcM*^;oKUn-Rm$ ztp!I7?k4p%RFepY8lrBYmyHGls3$(i;H=dXeuu!x5sI+4k-jM|7Jv^G+#w7>928b$U*4As6L zV%z}3jtS}Sn1@TKr5I%l$VlBtnRpN>2kJL1T?+6yohROq+9U~D(#irUc`-;H`tIw{ zHf@~S#0pmx#ZE}P^*8VhF#D<0h*+K<(x8EtvwmiX1%!^Xtr_I}ij6~Kn^QwB%0nUC zyCd}8QgFSQHwF${QqIiuWIGQBn8sUkHLtxijsV5wFTz+Nq{zhQ0jh7OI_s^f%U@34 z6CCNv1Kdl*qy!Xa$1RnKV;0hIWx~+gd$0F%VJ7bN*CiO1IulhwG)aMpMW*d$Jw*lX z^_Zmb_p@^u*@+21Gbdk;f4iZjk--htcu4AV=bB{##rsVwLFZ3;FXgVBSNOvDtq}2<%wD&+1|QVTDVu^IE~gBD>W5LK*=Q zTp~Cg;A~xVoyYh1m8{*CduovnmE^7udh+wmyjsF{PL{x1riWs$*o7_?sPNZ#{mlPH zWOPM_UF9RPBMtpOl^+~6FDV?Bg)h9+vk!cC4Wg4jskW%_;k>c(DRwq#j+p_k^7iq* z-?jL^TOnT@zWkIw?gj06-cVKj`0>h#V(SxIl$kydLy^M4e?@}lS$E0t)04L+d%tIX zsoEALG4&T#Z6u5KEZKjIaXwrj%h2d~8S}K)@z&*$;!p%8o0@Uzm%!_qYaCm)FxA<~ z@u1F+Pc)@ysA8_i(i(#Px+`TM*AxkRuq9>bUBTcxdXZaoRchNEJLgoB}u_pw8kt`sTij7r>F_T=C|}@ez(M)d45N_uWCD zMRQk_QF{*J8343HRfq;4(b-r;IiGg;D=N9wB}x!!!CD%i_t;CpCZQxZ0P{0UO({`u zB^Ji5q8Snw)|p6^8%LHEP2jZyYuY)K!_HAqjm#ts6a*+qk|Hd+Uu2Tll^`B4CoCw0 zl~o5;wSX;0e0)x0d}Hq;J8*YxQg$2@NtdoLbfz@GqnSdG-R9)r(&!jC5SK^vp%M1G zbbWZTDjbFJWK1wL#q=@jt`#K=jT_PzAsxLJ;GQzEE>Yv|!PIe^*!qv|bcAp#tykJ@ z|F9#;g0D4GMR?Kbq~)tK zHFu$()M zYATzX>0SvpsGpylqdND?!&o}T+#uypdlm-gSw>efR`*bBz!@f5IIpAyGM5l`bK{{Q zcPMTuC-^Lnk>{aV%VW>U$H9A#p|W|hhnfDNOv1B>AvEyh<)go(4@1cEYtHzb-nf2= zA<`7AUu7Pp%sy-jWfa?u0x1BRnevmj_!cu_LoKP3>dFX zV1o)z>rc>#8|9Z zmS4z{r!9uBs0VO$`G)m{b#?V! z45Cv1NF)ecYzS*5^+`DW*(`uy^*A}O+qc;k_1QB+-a*DP-j?rB&*4 z;&cIRYWwHm=eN5VEYJ;ur~(Pqri`xkh{<*+H+8KPG8IdGhoXa9v?JKH!*%_+%Vvi@ z2<(q53?zH0L7oWTBj*%FK52dt_PRMmwKVNd+ug5~8Gkyh{Gmg02m!qp*%WPLEhJ|s zG7UWJz&xWg{CPP=d1ZKc?O0|WTXppo9ejfH_siVZ;Sb9~NIzo{vwm&KU%S7bci-#o zxh{<>Uhfp?c6$o%79`xNuQ2TW;MrS~+N+eq9eiF)EVYB8Bl}Q_il|ay#6Kk`g)P6RmAHfZQGm1W;cw@^rc{A z*6@SF*SC92Z6nOy#1Ck1SF6gIliV|p@IyeksS5p&$meXd4Av3zBas&)IQG#Pwb3}+ z(VO>RchC)Q2)nR^`OyqDYt4p&vaiFLFRkw%SsO}?+>00?b+F;a*|^ybd$7Mem^T2=IRrv2?kJ0x(o)=uqhL)vgx$e*w(vob7_*6c?3nnIAm;i&$c2l z*FE*K`;jC0FDXPDK4~y*@Mry`hST84J9-i9xS2=~MI&S8F2ZsJT-i)@Bt>0`M1fmK zdWkd#p@hO(3h4q+?KM-kn)5qIQJpMOMf-{D&QBP6^l_+9aI=nU7`GZNK?CuDI|frT zV~xfwB#Y)$mTl11f6Bh3^GFKt5@@@G98&^q!BN}yL(I1zH+CsLqL6A*h$1vJtpxEU z9;xL${U~udUSwREawfW$UR7-P>v016`<~yn^qhDqCwwTR-<}cxZk9+8>$xY1u(M22 zH$1|=h3pFvipZo;Z}}3D9vu0km-F`hnBK``b)F=)Y&8h9}YkV^OopM~CFbNPB zUdwS4bza1HSo&}*)dF}H*aa^mb-^vrZ_S85B~)tMNNgtc`7UC7SAHHz29b_$R7Qq2 zuzkM2AeX;@uAYATW}5nPQ4cg0DK(YUyO5$Tz5zIPt0TFQRGm_cj7X}6W|G@TiZ6cR zGI**&DfBBmh4=n<&?N#QfqZJa0RKIqbGzX2-1M7^xjCODz#QU45nyxNtHE0-(! z7UMoh+YiQg{m8Gndmy9CpGGLE#%5^uIpwQneMmq2Ctd)+1N#K?j3V<0ur!1c1QcSa z%1q{-xvsg{rFdNSqkpgYboGF+6C?Ux?^3TCjMGQZfhWwVu9RGnDdE+^BC60(!wK>o zKVc_4f+z#s$fQ{E6A$bq(`tr?++Kr4ZXD)qyq;fpT)#cmM?XkToKgM;zCGpHuPFJE ztyq)v{Vw&d35o?uAY6)Szl8d^6cn=eQB!?-$alNKYeQ;e`+oP@N>5Md7Ss|}sb{(w zB=P3;`0uKuZD3)|lX@xIlb#O+3p9uS#jbwz{YLp~r-p2o_~Tw6v2&0?Z=T+m$gz7K z`OUy_4*B2?ZSfAH#tgK$PPYZ*Cj~1@7=QD7_apoM7lQIWgWdiYqdf+D`UX{!G61Li zeIxbd&d&Uf%&S;AvrkGN_7tKHbV1(&u~6C5F2kt(QsVG3cwc8H;P>wuRnsFOibJEF zIUUfLhApyg$T)0J&seB^wUiH-K9^bGLOVzH2zqfTnC~uBaIQ7~`*}9kLCu3_xjP>c%=ViQEv$bw0{x(qPbVrK z{6B2n^;48@_%HBfSzrNKmJW%fyStaAyBnmt8x(Nqr8`9lNd*Z}Lb^dZ1eKN&r9@I- z&wkGLoSE~(`2(JrooAkzo%?-V_xts)y7Av9;`}$nQ$eNI6EnARXTPQ3TWuR}6?-ok zFz4T?Ugw#O-@Ufy{Q`GN1}6jxON6>d!8iBQ8~C##Bcay z0dx49k{f@Pv{Drf(=NCFqg%w&nj9`>tJnDaR?oB7Zvc0M*!(2(8fbLH&o>!knx>-| zxWyMv{!+h+Qks(f@bo|3BJ%zLhgZngxE}d4Ms8KC`O9$XuzWq&u12o|^S1o)_rmhE zK7PDVTzbpDZu3=CQBjuHjV^WduR9Y6WW>=f39!vc3#K<4991nZZ^g&HimEOSrZK9$ zvhJAJ)-m~qGc9^M|Fhfu+&Rr@I+yuAd$%c_^fowkpg_bc>dF1n%OjN<+gn+Yn@>vu zDWw?-XeE5#y{79*MuXbdzVCp)ZWB4LpfSFRc#Ls^h*z|tn)1IP%8!(WMT4|^3FWj8 zP*Sy${e@AlV9=pkNw2XkFjuaiDvfJp7L59Ni=V*1Xa;gju1M6pB#k% zL($aXDbkX&5!#x{mWiFpR4%pdnB4L4FI^EtlY%Cq>Oc89WN$`5O+7Z^ zmvuwq2SQ|hTt9`*M$D}hY{V1PI;7LHi|m1(zn@w(!QW47vrlCCK*_E1Pg_FPm!wCs z-0!=-UGCc7slq3&RO#3DIeOJOTdC~FqC3PkQBq7mpnQdllOcfSM=(WHvs3PK+}p2} z@1`c66t>l0_xRon*+V2~!5HTQeJb~qIfUL=%B`Ud!t43=*P7mbQ`$RPWYNAPbE4BN zSByuqT<258#*XSwK23Y7O$W_a=|#WW@IAhzfh!nhy?a&C=UqQhxpsLD7dhN4v~V4V zeyt)QMG~|I!V`{s(EJ(ul8nAxK?^7BHg#i4IFU2sTxy)BU?A_RUym7O_u8V~es^f~ zX@c8@P0n6c7-Je$OTcHM3A!WlbSeMu%Z$n2I_iucN=_x%a3WD zXLIXPLXn`_H*)a2bY3$Cj=q%4jApEVfky`HpV81)JN{*eD<+u><(Yb?WLY42Na$P~1N$&&kgiYr@JNbR`FObTWc{J^Sg_%X*?x9W;c493HkM zI&Xf?rby=+^8?G{cvcW}^w2Q@eI{)2kTZj)ukFw+sNu{Hv*EKTO!PX`oqUJWX||xs z`#qf4=MhY4ugYGL?z+KOgj%wIN!#QC*UAr(4H@R&ZD3;Io#FSJj9ThHq`&y5XmGDJ{z{^ZAWkNLqeBttXfB1+A02{LiJd9li(`4lBC|)B9;V zi=P)v1_3~#iE+&J=p+2;A$HN`4jl`R_eBz8^z7(%jer2*9DE@pU$GEWB{v#Bf^(D? zVu;T|DMaGY=ZbM5^r9{oO3@%UIF7V_4CP`Oo{AfSqEkOXe6bwOIz+drkC%b-qnv8k zO;xOTMmf&NXP?(qy>0KEQQYec$LmDmM=_cvE!i&w(yAovJ9Ubt7mLI`)Cv0+FE|O4 z0o~zNp(`T`_Q$!kDobn<{o&&o=|+`$yR`M%iVy}^B{rHf7NPF;NwRY~iw_%q8zdsu zbUc@x6v%D7bSt8P(Kz-12t?N@F^`)`))TQ`)q5xvB+in|CYL80@qxjw=%9wg$bw4k zGl*c50WO*nfFx!wkAGa&|F~D3nXaIHnUuh^@o@@rH0)e`1~;P#UzFFuM2kmb={+hM z03eF$hdc{%By&$Yvbnf5(F_U3Y*Lvkq(+O(-%=`SSJjYwXr`lk_oYLpJI{rxXnEU5 z+^j74b4Q4l%>wfkZF(eDpwU0;KVRxPe0O-w8a}T*az~oWsOJjvzF(VXC+%1~*bMvp z$(H-28B1rwanP^t-wCsli8$2BtWTxw_}D8+&jm*%tnIPSw)1j%;FDKA3U5NtlrW_ebE*wej|jQ>@IoPslY`XSzFy1|3FL)t zIvlF#Kg)*}NpXb$hNPzEs6g4>0ZVE%0Hogked>0PSD%8k`3415{jTyG$vi$?l&CO? zGmp{Nso6ZujGW=2tMXI55D588M~7+-^PEXWc^)O%*>u&Wo2kU=x%5DuHKD+-a~k3) zpybNffUJwTv^__JBv!)XFng+B$mntsIgc9^i7|PXCWe2^%+i~c)I;5(kz0FnW`#c( zcEjQ|RdhU_n0;OB!VzvV>828xiH5q*AD6~e7=#s-Yi9 z(P1m?p5h+gA9)9as?G&GdDYg~@VmCw8KTqo`h$$jFTefJ)!mU$+i4wd_-E-aSPWWD z=pZ8*ubIcIZd0KHTJL>T|2>`ugi4wl!xE+H%Na-AUUV(Ja7V3KZ80tr4C=}4XVq8< z7&K`VBg*$>-pkJ5zYT4bg9H>SsqE06`1MPy=TS^DL9j?MO4KyBELnF#&4F9unK+GWV?N!j4{U@6h1y{IG6T^}?^8hND5>SakC^2g>L7a=@!B zK!v!BwPWLsj!q)^3y&97;R$7v_&boS{@A!ManQ4`Cq365Q?mB1C!eMRr+unLi6E-D z@Gbg^n}pf!AE|heMt}Ijjg6vCjHKXws}94Hf%hyW8xvbu{O7aF>zuD8?x&X-&=)nC z1mpv3{J(X!Z%@Y`e(mFbI#Nvk_xyF_)pTMq5arB_(-w7L)f=^J|0Hxb6djd3O26}O z>ff0Xnv0oPl>&b@=XdX`>mMTWSKSKeRKe1d-HeFi@Oef%FjW(fL_Qu2Z$b6Wyza#= z0sk|S`C}zMABcZ+P;!XfcO_GL$s^yGqX1fj{{{5UlJw#(_Rf3CSHrNRFf=sDd;C`T zwN*dCsyy~;AGI+UC!*)>vErRoGN&J*Gg9o5M=Dscqy`!H9L`F`8Sh=2=+7CC>CNXm zh!6F{vuTfsrbeo5COi|w)1XEP7A8D9#a$`xhvfDTzgEP(`}hyLzxJR59R(|kp@uh> z^(CElRj&a3YH^h#~Y5#Fbfohf-z2qE)1wT zn^^yiL5NQ26OYpQdqq)Mr5Z3&R4{9fAcZn_P%`xs(20O}GePJYN0}QX+m43|0PrEn z*{>5B0RZMPJSJ|GPJ2RhSiCh@Y4r2Zx9>x`)^OdS{))cnzhnsnNF^g}6^{}b6Kev~ z0}vogC00Ey7>Xh`Pt-&L2v6g@%7)ce64U^Re(E?>P_PS91p@?znb%Q#2Rq8D&T5Ug z+zrwG9WCTUZVXBSTU7^?hCPSi)hpPZWdNTNwdgP`|GqeMv^mgsB{6aqmjD}S)P(1D z4dnlg6TO+BP7M~h#v5Zs?FchRuBr(S4Rzi0qvvGStO!!HC}K;-DF_ft8i}1T>W`Cf zt>O5DC|uK(7=Bc|Cz99rIuQm%@nYBx?(rP$@ff>0=-6lhCV$XY(z9-RypzQIwt}2@ z_$BYFcw+(?jMm}z`9H10900fmxNgQLlB1N>@vxy_jMgCs0BDURMmHg!`zeRhp`P-p zzLQmLyi*f-q}61M4?O6dpzetkm7QFb_2Nw?HjkOH2D-c9=o3V{UgH?if>k9Gv7lhw zOgxPGA*{|7-5yf|Lh3Z(+Ov*m1!;_s%b-V7C!LK|k*WBsQn;KbxvAe>amwl+f|7k6 zVY$`fGWykb&;g$b;xOySn1&_N007v93ASTEK4gMT*iiUN9FuvRrnUA)uHvSw+;)Vv zOHh*hFFbw0&#_@j_fFH35&bm>BZ7W>UQCz@hs2PBcz$XW4F>Fh5r_ts$kJN8S1nv3f5m^&mv**)YHwX9DNSBx&~~ z*~{*sUsDt|@)So5QU5fzQVpnr@qgrEleQbQR$~5zix@5p;yvfa$+W2H4PQ0s>BE8O zAt{m_$?_yaP>G=c+dR+3Y%0779Rt#)I)cVnMKBPN8v2W>KG$cP~?*RdSx_Jf0rHe7Bl)V7zdt*9f*t? z%-EOMU2C2~!Nu^03HApw-vJoe;e}_$Q;*fh4$GG<^%T}31MqQ4?6Gm67HPYS@PFVi zcs!pVn6L~~Xkt<{+$>1@T3DJTS~A|B8k;XHA-Lr&5s~hV>~|4w6o4y%xlojn-13UW zB(;6n_{g+A^1UKAD}WO#q7OToI_A0lED5P0kJxH!Lepd6>usRk3a_jb%&{ zkKfeE>Gs6_&ALP9`soq-{&02GElSlbE;18z;SEwNi+4X*`*goX$HJ9E3f>lbvcm_? zZ>>qgRLxOtVzF-m#Wy25V*?Bl6i~HE(wle*n_%(UbkfCG0G{7wqJO)c-wLkHX3R~) zMsp7L8(Q!jJ!)QO9co^+%Vt{%+@QRyI*YeA%if}Sw`D~Db>xfz!}3|i*w0^X{lwXZ zeOzZUW&g{DZ;R6ZM6|WBD9{$e6LWyUK>$q9)rGv(DCciZdEgR#G63AND$i=k=G&{> z1vI;$iC;tZx{nc)^g#V!T?hS%dQY-g%C@Oo4|$( zpeozQ-?a8{fjx=BG1+uAM#Y^PzVsEJ_h&b16$7&>CQuVliAPGg`M8C#;iIk1K{4iW zRw$s#gR2PGkCct7V zmYUy?ow$`B`$1ZoNlX~gV{jVgJ**SxOlm zL2Ue+Dy+K8!+w|Dk9$87pjd7Cd(mz(kT9>MS4V9lVBRnsuS{ID35w^_rI(>nvWFW8 z<97(ussus3#uzNWx%^5P17vLVN5hes4c_TC9#22_ZQ%N(^kGM=BqpVStkr$?bUl8B z{E80)&`wE4gMTbRJeqVX2y{_6eX$yaaWaKk8()r<-V@M_0ee6Ie(IPr)5G(qlMH?^ z5Jl@a#-iAhh6p(^;6M1moy5435MG$zUWn&CE9SH2+coVxaPI*UaJjzx2>@q0y7>X% zQe5V{yZoo%=liMcIM%3Hsy-a6*%RU#;mWZ+MzlXr!j}fmosC|GNCcQR<)ShWCR3EZ~O6 z(;M(;aOF_@;jjHkUQAzw( zPYn8gkD)DMMP^m(iO!7Cu*xw|SXhE;2yU49`vucup{UD6Ik4u;3}-Sn`%IAF#$Vi6 zMTb)1O7(ax7+6a`-puTa{lianA^@vE+#T<^2-R*N)i0Mbl-kEob@^c5P?1Vx;yNW5 z)}-djagvyRcBtwvULO>5aBjYQX;I^cHh;H^>UAbwzVdAY2i58Wz;Qu>q43b_1c?qj zaAt`pN-NQiKR-BuDky<^0419K?A>*33s}82(Qp%6o-;li8JDgXo{JYAEQOV!k-+l) zLdx$fgKEEdFDRjQP{ta?$ca7Xpre{`WAl+h&MhItEzxBbd+hAMo7j^q^aUL}&%xZE z?Mlk)>ZX$TSsWZ@8l+Otw)3CdaexKT$I&gjeS`Kgo+%~4dlqE&6!t8Jj4t6q9Q;!x zkVWt61F@lqV{`26NSQL&bPNY0cYG4S_F8$?)4O7?01gVg>-T*YMG`kngA3bK(SkEScN{ATqQ3eMU4xlITkPNjLsUt!SFY<5l<=3SPg^t)PVjOpERO_o)O6ao@ zj(gUa2+_x2+Us#8O;i|)XKfi+ba}ra(5NPGBExuJM;#p?L}g8dJboG4FL1AB&;2n- zD-x;IA&attUWIL9VI$)e?xIfrAKfC3fJ)fw;FM_yMWS>^$aJ=?h*=V~`%OI;O^e5% zCJy4tX4Q;iH)>%mM3^f$Mp7RZo+l`2CGrG*Tpbswn#rPdXT59MIUsd!$cI^HLzcVE zzs}xVCuLWtytQl#I6A!GS!r?@&1ORdZz8em!~%G&ge$+das1$Zq}jGf=6s(lXU|za zRYLD{gkI-UZ$IrDq)L>&+tskg*J$#wFOI(6{Q9|ABJlY4jfh*4E0)E3*G5`cqn9F& z>T2hyXIo_I1>vQu4}v4GmYn+0RiIaAKfSQefn@98oniL-Lw2+$$il2qa-<=FvId z;7H`)nreN6*+%S(ucIb7Fr6-ns@#Pvfz3e`4OPiznLlOGVG%~|F-8kb zNV24fI5^J`gRtz0W4)vCww+m{*jV+rKnpWMB3P&2Ac3t+{fU1yz?GiHs&R}Oisl14 zX!%dDF`87dWGVI{XXb<@v23Vll9-${r!&fQUByXD<Om_P^y>KIGsyn z0J|bXs)gS_EDBwuZ#gTovg0TiZg+&oSvz(D6JMLQs-R*ZYtTgw>(Y#ltKBF@3ckIcr0qal-0Z!*D8RG{}o9FCt!UY zp!3g!9oCqH5L(qgT6&t5Z+!?v;gyPU^L{$&e7xED^5OcZWNVs=3ahl_Y8)Gv{tMu7 zAf16g_o}qkd^_nGnGTB(jOyeQiI!}$i+Q}C&+r z4OD<2#?|KTt0ENX^GQW*p=qgK)^;j)zt2Tx|Dha{uq=ZmPCi2^z4EezxWb|K++#v` zgq!?)zutpqcz;gGJi8ZLsW1V7r3y;?N7#OFGAGG+SO$wunvGJuH)obHj(ajeZm=Bt zIOM>4-e{s*f50h(UVJ-=2LdqdK2XeL=mr2#;;JGkL0|kcEzMgYS}rr~i@Jcj)z} z0l_(-_A(x?xNw+PcuNj+JRQTgGmg!>n1N_LiRisa=?l9;%)1{cvy`U?H@&8R;_Mu! zDqE3yyiD3&2?66yaQPo40Co$ew8c?!Kz74vaHOb2(G7<0}PlWBa6?R zs)FHsyeUaP-Aw>V4r>`fARNKSM>8>8HqGL0Y4m~se?YmVB`*}+KOt&JmZ9c?MV~`n z^*HcrHW^(V^|S9z>gj@b;-YrBvZ8x=nqRXtZMZQHz2DrUs~O%wsw);%(75_ zUKugAn8`By@P?p&0>Jt|;zvOkN*kwzz*4sI1yt@ATEc>P+CIXEl@+OUmi|)-FO1!ng#4FGAp2rR+n+D7oP52Y|R&f}^PkCX)kG`Kcp`E%(m$4138n$mi(64E_ z`MDv(;IESj;vbr)ybG}0?ToZk7YSJF0V~+Fg?5Qv>W)~rMSv01e_3@|ThBe8Uo6k+ z7HM01Pd6s3wp-m5ZtECSc^B}KXYD5`Rp%nxv1Op&+U6G!gnNZQtj=@oG&{882cN*x z_-9Z4toOYp^{3lmRqL2)GW~E#Zy#x+mC0}yTZ&T`haf8ki$UA_Fthm>vieONk@kK_ zlwceS?-ssM`vAqm;LF@IJVM5HNF*~TQ3=hvO_I|-#4hh2N4B+&>eE$geQ%=(JIfet zFC+h6J1VJZ5EJcHPIcm!$p211lX2(=J!m{u{I@-k2ybQ2RiyC4pBLt_^-3gdQ%61v zZ=E;ag?|2d)Kc)7aPOD6j_*%r3X0#*H9^ntNw4*HFE)7BcdFaEOS{!C-W7BokvI`< z){Z#l!%{@9?H;Y7;^DG=5EHN>elvX3nhus`MQs6lGCRtG^23i1#8mSq2-jM0?53V# z6A6Fjvix4Rkbv4$C)dG;v{c1Z#ju6*HjC-I*+AjKmCwLd@dPoObcji8itqoC!^oqiY;GRB`+%>;Mq0206MW;4->_*$LqHBm9@aMwv_)?^o#h`wL0b|kCGm3ld?e72l&PN4dKLJYJ?oVv@#pDkTN0T zQw`LzHw`khG&|>+7=_2r(X79C(#L2PB&Eb5akxL5V&HuYF>agNtduBRo{zKf=GKE4 z@gx2Muo(jAvpEhD0Q=aiANAVq;NSSEDNxQlv&DIpTg!f@l!eX&91zkBT!H)K>o_LN zUfoW}w43ohcTL)i&PtD~WW{qxe17oy4!xNu@AVI3$qxJiYA8!z6GVsq#sZvh_R3!> zV*368yVw>|ZCh)nQpyCpN{EX!fbPt3QW5?DOz&>-pR;s>HQ5w90D ze0D%#WzN1q1#NWf6cN)hc#Dr~1DkeT>2H5H7@^gQx5TQ7_jGfP%LF%MeOE3{EX_{b zJ4caD4GdQjyN2tGBfW{DbPgZ z7h*CKg@M>hvH6F{V1ti7fPi7yiFWo>+^cM=PuQch=iO}(zjLS`j1Y9A(`VLJnTjG^ zN-}>DRMbPivEU3|gL2l`IXC4@(nA!ix&PL-nF#F2#F+*8nU%<~yyFl=S#g5RikM0y zN<$kF%QX=P8;+=Qr9yJeI&v*VG68-N_nnfA7fU61sWK-s`McsCMPaw1ceahU{M4Wx2Acw~1L~o_Guk;((F$`t@s+qcFX#VEzv>(jojlWkHahCLJKr zm|5h@YdKX%DGOHBRYy%|zI`{CIp#GE>!KsRQxTL^Ig`be;)y2rP%o367I@*H&(Y0# zO~sHE&!vI`g3^fjHr-68k-wwXqVGz-qsgocFh?zXh?Cg{EZRA#N>?e*?ig*eip`Jd zB8nvLVyW*~^=}=RrE{emru0eU!s!Oj(?H78imGB&I_pk7NmcsBRcWAIz7aUW-`Ol5 zNAuMW%0E{9>h=oy_PTwnxlOy;h+Q>UHN6fC_&CGN=LgT-;L%o9p|!KpZ#HY;3PDOV zNJt*4$Lowx-!<-GGmM0t&FwPsBasHxj)!dK?5wuw&IAYXoXYxImAjU2;vD#0tfU=% zv*T2&As*c2G^~r=%`R!?)$Lu?Wa1oxE`3?xSfv(_{hujc;J%M3iMzP5qv@U>gh>kH zTEJ>T<*W7IIC-Vd8>AcQH-p?P_wAq5h)%fb6z`E1?=w!o5nP1fmb;<+B!Q&PPuVxF z3)%EGtBK}ZBQMzo44gyR_n$*-ohFo?BRHcTKrZ?0u^zAz+2~gAo}ILY{lI<*vtGzV zd?dksJo_eqH8;=X!1|q=uG4{anzPijivslz*9tNtcDIOp&UvW=_lbkkGxV}T99`-N zDgf~%Atc^SbvM?yFAJoEL+7UK!I2qYpD(ehhmFPNPO5V7lX}NRngb-fA$hZ= zmCTth&c*Iir?^vzbFV$SxCyIHCvm+%_)e*ox449%{pk2J@l-iwj|)7f)w;} zfUsy}6)-udkQ?*rxX!bf3sF($MA3hOtYtN1_I=L_ZknDwitDqla=J9v^QHTW~#7 z30Sc)NX6YiJ1Oer1o3;HH}9GAYH+Jf;5I`3Jayk{>z`7-iFv(N1n)g`>gZhPaB=Cp z9a;a$sb`n+WBgaw#E&j{ZseV(I$JKcHt#SuPkqAg9q+gFUlm(*JvBF>oH&OA6_}>U zSJn>Pl84d$Z+JUe>N`4l%zU#S>6(L1@gB8E( z`D?mwfAdu+B95q6efZ`qf3JGjyB=r>HF0Tyk+<54zSj-Y9_WLOCoVJWJOaANha|kLo`5h0UkOe5!j2u;T;O#PR&GVGp0Z1f29J z;6)a^6pSmX%eN#f&|8jy<@slt$AfaZdvbE; z^X`;V6*7xU5i?0}TKhxT5Aa%`4{|#3P>#=PJi#Uyba!0xihncUjXAWBE)4++*9L(m zKNb7_xb^)O!jI+XYr;m(fouZi#4mer-DeM7EA!*Zqt_-_>mQ+;7Snl&eEop5aFILg z_`{|XNs{ z(Bhxe<3At9ro&&itXThZ)MvecUT>z)_>ufFng*Z~DI#tvSrtaB7o%eOZ3I9HDUpeM_Zu z-U6SGACX~=&~YdVM#~-y$}Cn0{a6JJ4ZaaZ2ZD{xG^YRHU}HksmK}M9%iwIwy(0>| zfWs#(UqI$;)F99ulG15Fnmlmz!G;U7T-z(cX4Wjq=x-tGr=YzF4OM=3%nb__+4~ZZ zgghTcohzOKxod@|`49-5uSyb$A|fTS*g;%1AObzDbprg4)=b}YgA`_(x-SQ~%UV0? z4i&-_wUqt>XGC9j4&Q&=S9Sn_0V7k#e+5#S4L=KmT?VLD0c1`gRY=pD)K~3q%GNTDsAgERafw+iyMEg-I z=cm^2Vy@zVOl>s9;()|&=F=$g>FjuNhQav??K^Eh>u_#+Key1{NGYuJPh);Up-UMjk^a<2zndI9HUAV^%V5L8AVdtdJ^E!Yrq+pCIVkKd(J`kS3+=Iw(>ym8u|B zrr;%8m|dPCqC6&6q5WQ25)g*&k0Vx&U#6cSqE2S($QF>w;V7i<8{*^)r|+XciFM@J zO69wDGqAu{b%jlCybEv=y_^G&XG%a*)`KR>?CqO8LCVI-!6X$RTPDn5_YxtM%>dzyxv#Uik>J-ilP z%6bn&zu!=hH^q>WY0(IpivxxGafztt!RF=jp=(a;DO1^%x6U{Deus|TvyVgf-_HYf z5D1$=or|6m8QIf7>9xnoR<^AhxYxDI{7+u{+`N`PX3WB>m9ua}7oZ=0;ywQX{It?0 z3n;nX6;U{P{qN>k#BBx?4osbw#|Zo~^_D0-@e$=Q=4m>55s^cXwBdn%x=Nada%VGZTBV*q z3^{%t+G8p8kvYkot2@%9(Y8Nf7CJ5{J!UkOo+UtkRf?ll`a)vX*bzZiA(ne zUPb_#=}y|TYT_dfm`ldPs6|MBW}QAPZXC>FpvG)n%38YPNbX5Gv|y9m>BFfS zW6?q^I08{d1#?o?Sv*H>SA;f-GXBm5k29oXrsNJrn}T?2Lene>9Ka z>VIAW#E6vLpow^|)=rj5kvVe6WH~CLS(Dp{w7f9tmKq-@y;q9>5^uyUOvpQef>ikz zKz36I84qP18(H|`oElm>s9GF*S6@Gk;HO$4wkpCQUBdYKyoJ|>S*(ihld_SaI-g}c zEON}w6@j%zQhRZ4! zgMo`NEqs}f3cXu=m&SBsxDbI)^IuBw;C{_~&Jf0mIW4aSoXvy)@ODD<)0-o-1j|#o z`HxmXp=^Z}-d^Xs*A6G~W!7;PE?`7ZyHOd$%E~>W;5rH=|?#Yfk4EPe-__Kye=rcIiWdI=0IM zJ)~S2Jg(I_iM@X}k32$2zA{OA3NGdVXV2;W)5;P1uD{qOHGxGFFF{}@Eur32*jp03 zC-do5n&rnge0_B;2W(DKgNZ`zNxLxO6$2G8n}cEvn+E^cK%(lU)DM`z-|#q;)~UsI zc@tASoU(ya2!6D@plZXCOUVE6wf-&1@N4=#R4h&*KteEV>;7HXbrC2LJ%Q~ra_#IE z|EJy6mJf`BOnM$=K1OK*c{)rPS0=R^^l>Q!Ngp%RjCFaTksql)ez)`fHS_Jy8dQ2% zv14LS`f|&2bV}Px^h@qAg%|id(pZ3fK30-nl4E#Z4Di9`ePmx(3J}HpNwKMeB;aOc zF-qZRXlfIyk--bvr{|9^8!~N=S(3i*;7OznIrGyoML+%{%-@|iVvaRbbR_KnFZkV0 zyI^UD_%H5&Vd9RJQTf(#`S^n^22Dw@d`n2CN~I%H-YkKlwt9>3PAu$=J`>@bIUm)N zxR7@=Wi279y-t}fETpvqbk$9?4>wS5nVs@SYoeq~Ec@px-Y?bXk0 zI8OZ&!{4XGk&n(X)Zr))aEi$|94zrL8HY6<06ghP491F;CC`FFoxg%?A_;U}>g>{GgfZVI0x{ zRN!3#)}Jv4>YaXYd>Ap)G_+J=+)RKPsl?+fxUc3KKb=$?=zP!%N<4TCskFs)C`3-S|K z4YQi;75Fwcs-fNbS-*!St+e$~wN!S3`ng|Zj&+k>TX=86^0>5We^@Amn zR~5~0@w7hP=(M{X`JxrJGN+(z@2c^gdfIFL{3E0RT42AUEX69S{r0nq_UFZ^CcZ_& zkL46II>k#n{eg&&cS`y)J7`evK$40Nb=6wbx6W3Ii@sSaj|<^WRqU`hQ?KY*QvoZT zJY3ECe<&B0eO{yO7ImMqLIB%an)d4wu_lcvURME3`(IcdRpHCy&8}~*1-PM&^x4r; zOLfeT+gT_sTaUCG12=4STAOHOeXgvdVNFP6Cy6dy^v1+m!owvZmo?Q!PZ_w{Fo2sm zd1U1g@#FrLSNp<{PjfC-5xzu+voZwWb`r3`RAHn-j-&;Ut^8n2ysFh8JXI+z+0WL! znRqttU#taEml^WAOIu`&w=2;-OnL3NhPJ0+*Ehu%kIFZM z3}IP-FinVpMc^-`v}Yx6ZRR9BJ{?5+Zq->;k}j%q>_}vU#BD;PNs8{Ddp*Zgxyc_b zx>ij`>fLVo+NOOw*_NF=BQn#b9vu^?`(h+00h3_`aI=YI>wP(FCIL1L+9j=sur66(CF0^e)-yri%021#xc<){d7XkY z&b`vF{7w;3C#23XA9sa0SVscjLZP;z9|HHw_@{TVJk?(bhKYi%2(`4hh z%h82H1``4NH~-12^tqpZNDkr0=ZjhNSfroJ&LUfc4rqasv_PyO2t-h?onRhz65LP>+Uod1Pj)}^&XTXAC(2?27zE9F*qDn^M zk?-F=UR-j#9Qato*OLe05NYI`mzil>c!JR%6CD+PUQg5?x#CQ zMFh1-O}%G&l_T?>j7hlbwZ zE$TUv>yuH;srL~pW8*gk8kCD_vXLv-{4yvoGStXp;iS;RAB2Q#5-GDza_1R5rZ90f z(Ni%|(z-B3vl-HF^S1>GO9J%vHb>zXMu~ZhETWE=#xMzTGqnGOF-0CP5RT_}K=g>o zT6W1itf6;{%jk4M2M%7XiUU3-VPdH9z`uYU9sT74`o5|;F3c~^lYqlke zDPvx+9iAT;l8#B^-f3)$Nq;!+DkJ-{7i@eKY)=KWU8CSNMt(Zw^j$>WwB*?ln{qYg zSuNz+Q+=_QS+agv#<6OL7xEdawu#m8gSEw_y_KotCo%Z&lH)F^(-s9U?Iu{5M^o^f z07TK~;M}Gv$n-qV%~r(as}kJZl+ruIEvEty0uVSw>He$u)#>l}A=nPb$n!gq`?8XI z!57jOAGI2o0e+k5e?WLK`Is?|rI8q+yO^lNjKEah>F=L z2+!y2k3-u>8~cxrCzqz@lvd?2pq5jjbfg5$HXwJ4hsexv_tMYo^7=qrwlBm#xXJ(7 z0;f0t|0y%1q|B8bcp_S6H!2kPl-k3+x7HVz+th?qH#5TjxgAl{kK`q`3n7y#An7n zxCtPDnE;iYK78N;bDvj~PN5$QwZHEdm4={r4T{)jk}Oc9?UW{g{$FMWJKb0CM4Ib3 z1L~M(CNVF~P#hoPNiO4U@}=G^*Vk^I2m=)oq5);*aaDzbm~3RwKNrHWm|=3Mjy?M|cRZ4u73jq-PcoY3Y(=~Y<(^IzOr~Mm2z~$b#;?SQjsC;9erqv*vxHEMjhQpUJs$()I~FEo^fJD`j) zyWCr@^QGd`68Ed>ZmF8!Vt6?117=CL;!AzCT~ZFhPsF0q_G`5oZA^}Zed+D2|9Z}3dM}>!UdiysVPTWgHY!>6<=wV_7U*De2ru3bZ&iH?KtAoFq$24RXEMZrN*{|U*G>}4E~gchvRLwNUW(`7VI(|BTKCWLE(A}I?pkOkAo=EMiEzMSWyU%)EM(R>+a`F%kL@=`dr>hy;1ySKbzN~w#OF_RfF3%)fOS`Y zq!{*h20%2J;M2rxCKOWp0~#f@CICjY*1dmL5=c+>#OYNEJn69@pB0D5yp{J(Y# zoiFN22;Qud%Jsh7UEq7;8CBQ&ZO`|~e&EAx58@sF;=5DL#_L0v`gev&8&BM~P3E5# z>Z1PDudksy*4;l*Cmi)0hdznlVBq-?^`d#b-M{CTt?8-Ua?Vv0<-eZaZcmQWC{OS= z&i22a5~E4UdaKby6!vXZ;)9Q|P}Nw*T7DXJU-E zOV97QdhcyZ!<{YL^Pb;e0g-*tAVOMMl%PEV&x4LL0xZO=oB&~yuRP007*3;;dCF?e z?1;)@MQatyCJ9$fKK z5&xrG*!4J!GmCnx{8|`N>J|QYaNRsVoGqjJuKrZmC9YT^VeL_I85S*D)VoKX(ib|5 zZ>&B$9Z831t+aT)uJpFTG)UnhzW-Oydb%}~@>n5Vw&Twhrl8dvBG(zTGgYeBn=TiA z@q6{t!pgDSUC`}z&qH}+jfc0%@qBxGyGI`*+9WX&3d z5Q@fK=Sy2HNcsY&N| zKgYtKRGH-PL9`0yp~_Kv&)=lH)-lDzufC=<)xV*Ex6LQH$$x)6vBgnYvMD0YUXsxD z@a5GMts_hI`6#A8;EB!ckvm06G33J0uPZm?@fv&HW52T;|=vTAEPR~|l zibEXw(lwUV`-7e=B&h{CWk;I^X1?xZs|K{94uC%+oC1`>=KGoV@n$?IP|6I z{DS>$bnO1pMK4nc$mkLspnYGA1X>sJAhA>TWhnyB)3wh7#m)*8$*vK*-e1*0F($qX zhfC+RfKEK`71;1l~GTMsQW30r#ZI*(;P zY1N}U9v}wK3UWJBEQRhfqp3G3I!KYYK`r%)3a-w$GryaYIHZNzZZogacgQC1s{5qe zcpHC;Ck=h(`>Yxwpr8AfEJD&-wl|)Z71svH?2~;6fJCD8G!6gLkZBPum}sJ$%-B!T z@-DZ+67hx$oNGo#Ch~;*XF}TYUB;R%7jzb+H1Ai*Dcc`-`*Cwlx%u!9apfJ5wod#dJBYi z`YiE|65Rgq@{0%dAUqwt37S1><*U}d?KHvd(u36M2X>&~cg^eVS8^^b;b>}sJW}Yf z-7EiQ-t7!Pf582;B0|UjN~=<+(B)km;*7m+1@?>M5@8VlWPSP97#DfiAUM=!3xY~f z@TC5HBd)!N%hZqsVK#vTTpRA+WXcPi36LQ3)`MI6`=DfGfz}Mz?eTWs!?3Om7XWYf zY+30Mj`F~D4~%1>TAl^mn$f*yY_Zpcbz&Yro&OPg{@ItaKW|Mvb-m+=GN%fT{hk z5M1E$UobtZ$~+pnOWRO;>!GK$Kg^;!m}&t4ou^(Jhhq)6e-`kZK;Uz3m1oe%C^pKd<7{c16kEeLy1QrZ&p8xoQ3ps4`7 z#+_qk#Bh;0UaeAi8$Vm0KQ+R;N7mzDv&uT+@NFs6e~e>FFd~qbdV+Z60WsN(-DwBx zru`sJppP*gaOZ=Ij6hdgWcZ}qm+tKK>mUwv57>?tQ8FX_r!`5*Kd;6x+F%DR%x0## z3A`_V--*LK+{!(rw+y%qssKa4ExjFrgwKJuGZRo4b+jyBxIajxzCrQ=i%IlKJnC}^ z*Tukcinvp%+L}!G%F}1oOhm7%p0gs=L9nSglX^}VIG!tFAntIj<5cgNA58ZIcoM}i zjFav#LR~R#KX?ddvYk%9#`*kI4sS1_HE50LJ!qr)#yvYLrib(HXWS4t-hK*1DM6P5 zyrwPG<_3|W*(l~u>`pd2Quw6=Zfz5uEsM*L#(ZLb-J?dY8ZLx7IuFpBHp9;GSc5~G zbx@Io!yV_p{5@^fyVLqk{TpbJRv=Qk3vkA1m}x_W+m_A{8UB$iqQ`}9AG8cV`-K+h zS-9KCuwHm>{nEr=N;=Evbye*0tGA~Xo>L<~v5L#eLSepmSfP#rnX!@V zZvpp$@Oz!{pj)QgJmrB{()Xp7UrlAjE|J4%wSA{p{3E{JNPTzf>Wp_EJKydy&}PXf zBO46a29;u&7UEFiZ;{J*^inVi6+yp-M=vkZdD>vCy=3;~m3HLfl~x(gi(ync<2A%E z3S05o$_Wr=aQ!0FrYwCTNN&%P=}C2hqHnx%UA+2gJWeb@4+(fu7=BWidMGe4NRkI9 zpQ(M)g@`0;;%yU8$P*lTqglalU*QiS+1xkDDncL1uaRHQ@fk-no|UBAr{h`Wdt*uW zoi*u{JW%7t6cftN=N9@;6@8n2Nc#7|vmR^Nbz#M7rO}Aa7TwU7J zk+f)e$UK=|fpS|OXW6C)Mdj;qc+mX>-~%HL*w%1R>%R*K@nQVG>~5WW2HE3b)J3E{ zz(-nS@+CvtDAqe~G8Q;9&ygdRgJA=m#GZfY791?dtJ>IfEYlydK6fhz4w50kiS=>& zM-}<}jW2mM0R%SjyKW3|L#?`@pHYlHdmGsN)f0-gjU4l?)$fu*#x?L^1VSu0?K)5CSUn3*FPLYqM?`Ulq*b z_u5fgXki2@@++gyo^KPeuC|$-&(Fcu*$h zTX~RM33g{PG^qL~rrjV?*vy1qggB6qpI}AB7-%GpiHc=&z!zx)$VLZDG!|{Y1rC%i z7LKemF7n@{AhpR*;v&-0zcxIz_D~MUC}-R+XX*@dJoS_7mzYO{BkPSO9^ zLK7VB2c+JYSTEk6WO^QqxYbZ!9LfH_BPd&tKmQj5UG=+uXb)TUF^1`M^Hfm(;6*21YZ z5Nb7uS`8f3@%J`m{Z|2{zP|q70!q1CbyZb)d3hO)LdnUYrdtjc6i}n1sbMDHBLe?} zKPf6IDkvz(%gf8o&d$utOifKqPEJlrN=i&jjEjrI(_&Vf~dasR3~$)r9Ra_W8Br@+P~}*UteFEed6Wi_5a47=;`VG7yCqp zsz9?(1gU~NR6af`7dw>&LuI1-M?ir>sbDY_1UkW>i_iW`Kv7fs|4%?+Wo7+;Lr|{J z2$cT~L7CitBK%(w6eXtVe-M=6|3FYC|AnBas{a=RMMS?)`0-KIe}|x4@=L$1)F6Eg zUqhH_a(OPXvVKX*y48Ck$^0tY*^iZh8Lk=I9S^l3at6_}WB(n3vUB+<@X-4OgQB!g zS*eyN!`Z*swMp28D&D$CCH#!mx9)RMzstUV?7Xq@|B0Z4Uzt(=hz)rA&eZ2r&+(1$ z*9&sVR2i|S-80No4|~^%-k!rhTVKY?F5Er|ZTyPLeDsuh?RE#Xn!VfslFIIO>%jbX zpBA6c>S8>`Kzi(o zZ0FkD;#Kx&vjQCaZh0b@5g5Q2iPSIu2ZCZQLeOWiwDnubx9FDzuAUXK|6+65gx%Zb ziq1_z7aflFD@6evYhR0l>GXvFT7W`3HR9`N1?;SS`M0u2TXH`}HrSyc&E>1z*NbVY z)4msdh7P8Ra%}zAstdmw-UsV8%NB!#INd&#OZFDj-O7^Bm#|Ncyybs0+nef$scxO| z-)QQT)?bF|+HCpNeZ3?*2n9E(&OCU`Rh-xA-`*hBisSc{Z0fST`n`SThwA2|O50({ zmKxPGiM9uFQF&e0veWK$YZyC8w$Bbp{(KhbPyfTeJWTE5lNYUH_ny-(=t{{;%mH?d zPx?*&K~Of!d#Z13qfx*z{j|^&GA~uiVEeRm!fL;l>}|nAJ9)gQPmz}4zuwx|U1N_0-*UEl z6%HD^F{Fix!MqV?weKMK3>0>xU!B_DeTh=={XG|Yz67bXMgEe`3Erm0If=KpGva3g zs^dQLu|nLC>fXM(6OtVJpiH&OJPCrx$~YwB6jCM5LcP`v+%X$&L&HtF0%TEvC9HZK zoy{HBsy5vwrE9)>_GWm`sn2{r{Ml6?H-yI7$6a6nwme?akN+v9jDv)*$GdOsf{uSr zB1jbED=8|NGv##L1!=qB7AEN?A*&&cTgXs41?OD~QA3L}FIgiQ>W)&cy1}5UnO@h& z!qx|3YU}41kHTrYBIM`pjuO)2%BzHs;`1ve{^YT8xa4%EuF!;c2usN@3pSahXe&X? ztb)$85MN63=UA!=`A@90XyqupJeZNQfFUG?%>>)koS;oDl1nA1SKS6W`z`1M&c(}a zX`3G!vuW#UU%Hfi$%x=sBiq?09l32tlNvQh!}K>B2e|Jv13E(FJN%SpQ1B*>Mam6; z$hsv)j8~z!EQdA!z5$dT2=3du0lMS5pquvxmHyVzIdGOUP)W%`E7@o}PPd$DS-jc_ z#n8g6Dzl+55yVZRk9a1)ECp1HQSA-sg(@JyZ2-3vFzonYr=WAZS~`4m%;{xLK@UTX zY;yhBWtLxsBb(K7xufImFY&0}5-)|?yW?K+kKw_^1#`V4uL8gNqIM|5YC~9z9?=~Y zgEf@Gw5rbWfEl-hARLZ3FiRsDx<6j4`Dc_m5xaB)_M4#&XG~_We#@Gph$RRtGFzJ2 z2$naM!%z$rSyIlQEA5bAlSG<)Fq?&XZ;R}Z$hBLx4cWFv^>Qf`AH9&_?0v4f>0 z>oxhR7 zEUd*(r)qvRzWgwgDsl=hI08TEdlE)X33dvT(^vE-gSSR8yz}dKhm_%fZS)r=HA=tW zh}-i>PB1cWaUqzt5@O^=fJby97O>2j*k-cB1wFRSoSQGMWW1C1TTPZzFE87X9*dJI zZn*l*bfIlkfF1U}U#o60_wF# zIXyk|XGq!hrEn*f zY`P`Lph1Lk_`4+qZV3bzbMXXjue8T}4olS_?D$$oOH2G2gbb}3a=XsqxU^&%ta5`g zht0ezO29mSj0~mw0X)}M9QDlJqJc<20ESxW?PCGIlgHfZGiC4K>B?b>{j1FY4(3YT zT5-91>ecF_*)GM1F!Pi$_Eo~AZnrx%CIJ2oTF3s|gn?u7d;&0j%QP7@qi&L!}q`IpC>#m30Vs$6!4ORo|vnwA0h7Furi+56DkNPLZyqzAl z6UC)Z{(gAJbj~NqrN|@q{D(lupUuGxHU_pTK0H3`&ST`)v#DGkw}v`88whCO|7{3GJ@+}mFrraf9Wg4l8o!_X5hgK0Zyu@P|-oa(pOLVF!)BxHf}!Fw_fnmI8b8kffm@@F#oih`oqA`nAJ}n5BIzk3fqhtc zSlc2b?=jC;#q&$FW;SkUMUqgS{GZz^$310saz6G9sbUNByJlHI!}Jq>rFl=p=YEw2 zv7hhVxhE5|ag`7Fbn5xRbTHO5lR6LjJ%+9rpYQoQ<3tUo zJjL%lnK=FtMLqoR&Xua;TKJ1=W-CbrN@fC42Kc~OBK)p_5G}ClBUSwiL?4s?yG;6o zb#S#G8!LS(Mw>aJASdkI9lVW#!YK-xY5(5{3R46~8mhB$9z9=a1gW6g(1T|y8Xr*T z0K73kLC(_3)3zAXf^U!f2^T}e2lWB{6m%j!9LjmtCmbJNi`P_EVlX1m5EQg8;Y%{% zGsGFp?~ELhyH$?XUW8b$LSz8o;w<=XAKI=N_7|TxTM4Jlm zw+^ptUysdmF;Kgh!p^kWN}8BU`#46FbtWJR+~{fQKo~~I4Xr$w>b82j0-nJwnxTcr zh&NzBxP`yv46U#AeYT%*J;Lcvh>x9NK$CBp|9)x^GpJ++rHe>YmLP0;N$v7rr0>s1v?X&2(ME@AEAK0HdjF5F#rfJgbV6w-=UM9N( zK95K$=p zy;XX6P=4`E*+*1idtEeLQGsIxq{O=j#a(`VwEV$ZIYzazRz#U&y&}}Gf)ZY#&kx+d zkRb0XQdLs0sU-p?mC8kIEE45nABr`KZeOkdXU*Q;6Th>6w?w7r{$_!vsA|>vewBm+ zyCo*9O{`R^sK{Vlh(b3?q@-}@FXOYIu2I^F?=;C!{ktISQRQ)c|+Ri3+W}6Mn6}_6jw!%rW&op1U5(Tr2*! z)W53I!?(^n8^W1V=ucM@&=8rU+Q2VVm)uaVp4t#1!4AU0lvZ=}KGdlpA&q3F- zx5X?Q2(T>rdg*?r+&@goD_KnCA_LdcmeU_wSW@cQsD90sT}|+8NC;3R`mq`9g!vpy z2gydRU>?gCKU7SsfT}eMoNhJa2QK0wU6LO!-^Db!Jp{L)&W?#ZEo#Gbw;?{Z@zS@l zarCS2v_KOVTyNshmYh)p?*}8mEq0EWJ2lkEjz{#@TO_Yvu!4qcHJBzp{S?uY#bt0s zF$&Dgl#a2zwrg;o)?1hVe5&pF(U{rE;qwtTGT6)v8g0hf4EJ$l5VdqbIFtK!$=wN# zVxy!^5JYTX67u>gD=_~Oq|Wl<_3rJ1}&u=FU&buV-dgV zpI=gc!TjvSfL>qM(}6IQ(+)kbOW*tDYOmiBuHZqCnN_0{2g4i5NZXA%RjDD@TbDnK z^#B+sb*ra?y|-Sq=Rs;$^i#GA&0VWh_>E09{|K{OwV5kgaNs_M=`tSniqcMaHk3X- z%KCOFxrS}Wzi}k;X=~Ad>1QO>O+gY%_rVgqgryUd#WP(CF8E*T_aaV zayLfjOW0mXB1S3b-GkALMs}WNMz^gnNVW?-0N8J#6|fl7E%Z=0;(&72i;Q;7M$O1# znu6&y8bkhG!Mx36ysWLUtK&c6M^)QVMSx%N3s?c;9b|_+tv}7ENdjpWc zpRs!23g|pd5+VH~iMZhZkwjhriXXR-5IHy%TL94>w5w=wK0CFs{_s5GBX6}4eF7vz z7SSgT@o$`|3t&^gGaV_trQI)3+~~cmK$LPihjQ2>H^$x_@JAAAWq`h`SvcNhHrWNk zA8^dfItP@yvVJRW@r$#4C={;tWbyG}}#@B!Zd$M-pikI74CR3YJO6GtKV+ zzo_L1z!LRF7Gt;FW2b>hQy7eHneAU$H39P`S9@u}N< zmmV`LqR23pH-0`)MiWMn>msLF|I*7Z)WD zOHevn6QCFj@5$#~&ZR47=Pqk3El07vphNUFkJ!Cl2%-#WJ*OY#D055E&S$UvC=oc zq!h(gwTU`j%#8oBN_6TYJ}gOn{cU@GZR>bVEBlpIaA1eiTFi;py|Y5erE7OO*8-e- zAGt1RnX)muAdi8bi-Bv)E~^c_(~X(mexB`(;@ueNUC<@;T4NZT1J_GWy4;U8n%35b z9&RL$uL?-Bp~}g}1q_L%n+c`s+O6x9AMul=Gc%#Y*romlD#>)tCkelg(2 z=J!(*8=oI;OHq@gCz@Xb{@4ke(s2&q-}XT-Zvuyl)k|A1hRWa{!lnYAK6+Qu>Q=;^4y1ky><4eOaTI*7par^j|h8 z81uL6QZ?c7Z(YK6PvEz%=V4FLzRf=lJF@l={Oji@rW&b-FBg7|Qx}db{~Xz>?(Tp3 zYknESxd^X#zMJ~!SUqS<^XKvFtb^i52Ns8iffq2S)37xqhWQ_VNBD995N;6{2V>;b zE42KqlSHR=bV#vW(o1DO>pECy^~E6bj7BV!%X--;2Y%(~fmQ1jh$5rS!+?VvLDM_( zN|SB36ukS9*Oq5jr-Ljl;*?Wd6(hGj)2qyxHPcsZ)@>RtHMzbhYF``8b7U0x?HKA~ z-=Z|i1dTd(ON$-eD&6&c_%gyte1*dw*jb&zxxqOL~?jdUWh^6tS~1z-w1pq7pu| zdFJUbkH#Jw*U(?N(TBXwj@Igg<1w7taCpfA+sE_>o{&Sm?BhalxbnoqE$Z{H038Ba%>Bkzo9 zXDV4>zYZx)KeMjqW!#iE)A+NjP%C%lzQS{P#0&W@2vuU--Q;p(BWqWBhoa1c=06CE zp_N1)WvVq)n(~pZzwZ@G(wb<7qEb6@a!07W?ULPP;nj&f_3v!cyOtVmbSk01{j$qU z%1Rg0ZG^Kf*=Om8U2vFayVU1>k*DsJk}Rgi#yhe7*K=@&d52Swx%0VMbH9AjRLH2; z^+w(B?@F9*FK&j;sy#_ub&C4QEje!#Nt}A} z#;GME+?i1B`GhYVT@!IWQMd7rd$yspw1>7@7>Ac{^_gkM%(De{9}{&&y1a{Z6%H=u zAHp~dZbQOQU-V*P{x}vs{+<1`_>On?qmrxhcgO3fAQ)~)$?;tNdcD?Bp=ot7Tx~O* zH$|j0)Dz`_bv!WVQG0Z0y<4MzYq@R^t{$8ccp#V};fwNt5F+GO zV8hfIhN+&5r92<5H%aqz-D!XL?0Iibl5_AIL#?{R+nx3$xhbWZr`%tEbG;BR#x6`- zM(;XNpL}HeEhd!j#LDCP&6$?3Ec8q{i;$J%{cp+e(qzrZwc6U=$c;zIpTLSzR9VMs+AO5CYIH@H%#HkB!i63+*9N9rrn_AVJa>g4)s@5$ii@2nKF@dei3 zr}V`?WTjpTEradL3JT07qwJj**!v1K{P4u)AD5pf zaBuckg31=jtnVs{c{T1RDz&~L?QxUEUT()H1bpVRsjFIs);}@s{UP;>FeVqE+hwwp zNlJ!#4H#@^N-O_>u>&}?03ngPu;TPH{KuIcP9w)8m^??SyO+OTm(BNPdkqFJ*~`M( z9mgO*VG*Xb*_UC)7J?0fa`S#}H*IR8dNKJC(->4$Oj9ve)frg5l?~zMWxpAWwIpj5 zYvVxYM+i*MF(%){MxP|;HD7y=VN!n4bs;+YSIJi!7FBA!MLkd7*^1R+SseC)Y1q`A z+~y>42hs(%ovBLnFCQG}r4YeCuiSi;d^)yLC0=gVt4B`|5RuFHx%#V8Ch?MiO1G8h z&CnV?ja1fU0LHNL>i(SbyjD{AGqh1THn-4FWrvWfn!o{krb3ho=*wu@hy z5CAKWRG{|yvZZR*EKwGfSPwFUeUOqK9Ew$z&Y*RzDPC%{%@?xkxoW!+Ss=O@D&O0@ zVYDSNTXxU0?xli+juDWh`>ef^8j=`Ly;}5+oa)(JFfHjd8V6Px0TmBn^t^OK-oN3P zxdTfX66QI4JJMn6kaPd5x(b(515TUi0^WyT-qik0+ueoCtHw9IvW6JO0^z&Ci)JedtVI*& zdrSi2bQrExR==dhd$r#>^PmtPCOx@!4Qd+K3{N}0=3h(U39zv?JXJJRGc%gMJ^0o1 zNw?xxbD79%fBZH1)2-i11z4 zKgj9X(r5TiC%@*-4YX57i-Af@asOw3VP$?~S?BPT*m}~%qG_Sw14E%e=E7ekOA0>c z4e*m$o{HT38jp~Z;yLq0thJLW$=$cn>c3mK> zl477S$e+s0AVl9Ck*pSMl}KPHXa3k}sDhQl$QXU$otLfA4dlJq|0iUsrSzN|?DF6&i zo=56gA_%Man}rF8I>3UQv~d-B%{L(kNWN$fBG@ObK>%Gm;`i0(jL+B>EbxEjwEqXR22NGe*i4U{Mip=~Xos4Dnh- z0)aFBHcmJWSBX|m`Td0~#zwq1pw;|9C;g&yC5fP1pTj<=18lV4DFlV$?{f+f(RjF1 zT?&;B55Gi1Eh1o7al#k(5j4C*azD9EPDjY5ze+$vEKi5&zRvMu9i5|o`Y{w@D=`+E z#Aei|6Rk&joT5teJDLY?)BFxg09eI)kH9$Dh`KnM-$6taB4}l-CN#gJ4u2cpL&t+; zP#36-?8mj~|M^IBru%XuQ^dvLtm%X0UzB{KQkX2`uGqx++9xg^{NsRp;UenG()6hvAImn>Xa*sB{(0){h^CnSbH93|DLCfm751#W7q63cb zKIKWgveo8n;3&>SextZc5eQD&1eyeQ?F36jBsmj%ZjC_sn>FU5=&17w!}Gd^GWQK% zeHcj~fnFWJ1UvgPp}JAyC}0=tky9e;mK5%baG}Hz@F06)@(o-fijCNN_>?R-oVGja zBj1H#&~$ZH&%)#N*^-pp@Yy!QG783&gVC~aqr-T;jDVM6lBf+axXK8jS5+BV~==OG2MZR+wl<#>IlnHc5qEury9#qlKF@j(WY%DEQ}r%f`NGu=t?$~Z#S zm$BizvC9&}uM(7BM5_#qk39}B>m3yFEQF{8$EBIRlBOS^-t{woH-3J0Q}siM`S9*5 z5*9rCSnihItFh&g>HEkR%;~kPuR{c1$CJliC|dkD(!r2hF4U0(0Ohbe&Sd}YL=wUV zcZS^jdLyr6b5nUaLGf1}5?q+>=9{L3!|y!njyZUhUPoJWO1>5hjo(cBlW@T;cOpL5 z{O9JYznjR*o^fHVpx`vi3%RdTeL)80NzvtrYMq*`mK4~vcKE&Xhi|!71LB$>(0i$I zFL}(^o6bklrRdYJ4evnG^Hrt4RU|EMH|aD6O+ zunLMs(o280P7^r&Si6`|h_|AVA9&a)@(Zf^#Kc?uG$j5_9)bHRd=VKdCWBF}d_M!7VNWf2FRh?1 z4l!Gn_1%8c>U};VU#4)G!Uv+heL@T#TI2#XAi?}(XBYKm>*y+}ZuZHE_F8#Zy8ep$ zmp)W`eWiZ z5kDU%NU(oL2!2OA2EN|4zmv#U_`<1R`eRSb`|WL~pMLK*?y_9juS8g06vbEeGCH4t z=7u!*hQ9OOT_L)VN8Nrqbgb0sISR!o&v?S{SU1~q=c!(L5Xxz9joe(bC?zuaWC z`<7^KSz=E9wE5ywX_HGD*e;IKF42;9qI*jtKkOqwUsk5|=WQ!?NBj>G!u`_3Nl%v3 zT^if0(q|LZ<`YkTFSua)AIrY`;ZlSbMq)?EcOquK3r$6=yh;H;5j%-u5a1!*xMkdkGMkG5NE?Gw;q*yP$4!t-La9Ko?Xy~QK%u3{rif1TyU%U61@gdU55*lZe z;JE0D36}FbtVD*{cg7E|T$%DnorTd-5?1y}7JHuO9Fv6rK(8DQAwvR` zmuszc1frg=|RiYt<9LJ}|B16de& zDV4tQH*kr^#wl+nII|ML@epQ;TX@0z)gh#$Z{k%V+{R7lGOrI`Ws-g&C}I}8sg~^N z{q0GkJJnHycpA%Y84SdYu&XG8kD9zzR(zPGSCzVH*azZl4Ad!jb+Yx)Mql&=KYy(MS&iH5}=NA-2^e&sc4_>A^-Iiq?rg&f`oW}aD8xz{@!(ylYpym(0xT^!pLey?B+nAm(TB+MBn5@UgB9_#Q5s~4z-PBZ<8)@5Oq?M zIBO3nvbYx5<2U*Vd8rwGmd1Qg;{1(ZA0B>3J-wE1J67eeA)31sNAjWvT^son`1BK! zr4Sa|nH)8XaPU(Woy4C@e9tMQtc#9P4$atpyiG{RRIV5ms{D@^44 zRPXn2M<*-j#G5!a_AGG=B!?6Bp9@hJy{qmqGe8){&>8X}C5FBo zpSxlI{7Yg)@9KjaThp-ESp+Wt*iaJ8zlC;5{6;=;Zz|mCL?*)frd0}lYuklfuqK`; z=q6YuIuQvGi#O#u;cn=?I_|K8*xd%-IAs)EU@`L`fBADw$bd!RfP_SRur?k5Kf)RcI2cRn2q2c z2hGNTmHW4h&_8N?w?zlC_?3_hM20g!ME-?aXSZ!rw1~`js9hb*6lYobGqQL)-oF_U zRi31Yy?HzQuo}I82MOSs(U+UIy75<^r2pyQZMv|QuV|o^1lUtH{P7{p)qCWsg@toXoEZQ*VcE%-_}{zT2J3HTxc@N4qSN*x#>R8z;!jX$EYJ<@Uaz| zVg21tRwPjgrk4#71{@Roe=Ti}*ac2xX@yh$KYIqcK6uWQEpcgcUv7CMNA%)Qze$mz ztzBhYwOMeGCxxW10NWn@UJmhtd?8JV=&q7Wjn!(7gSX7Ec^xYQE6MRbKzcl@OyH67 z&hlk0mM6#WR4%Wc4?0@6lgfBs$~imohTlQeam(w)sll_kd~N#D>1ewjCmKilJA$!w zLC*)`SKNKZYRr1qZ)26R&9wS31ZL9u(N{q`#LSOkw4ZofP}cKchE0bAHUCP|n3mQapy z?DDX3ex8+q@DdiBqDCqiaZXhqf-h4uow@aKPRF5Of&mY|Y$A{0e(j2HfabZ+S~&3( z%j_E;Zi$xitmhbN-&zIZ_})8rEfl#1I+UbgtQJxJ5%~_;%pr|^xC&yo!^i3;FYbzJ z-wgRHURPmao0SMX#-RbV@|SF>T8{p{#mygVbYzY>Z4W<|0a(Vkx*UPW1)dTBgVJ+q70Ya^)b_b8so8&jB4QA$kwmR$1=#jo81h`hRr90&HvZ2!6 ztgbm*LLA5>`(Bf{1rv z_NaP##NPIZv1CuEWs_}@!dta!W0hjFNWH&(KkY^%^vie zt8;FiWMIIDR9t>{IZA^SJF@!)byvQ9FA1soQ6s`YKVUK3NCbodz?AVdgP5f$l|0ls zh_>~17V6{+2S%mrZ&J9}U7qrok%%&L&Stm@C+N1e+-D2RI@V)$dOReWpW(p{@v1L~ z*LhV}l>@{qXW!3+PA@;}iXCKk#+Y)a=P#;<00#3WqK2daHkR`KVzW0Qmr79dULIwK z%fn&P>HM4nop~Uf4)4*Tp@sw@n~zC|y_JlFpC3`#B|yQoeoN-G{|c2lH^E&9g|9wD z|E_1Y5FZOO(a5uMWX>WzGuqRDmjpcv_+(%LzNk%BFj_a46D7vnzAdjZt2x%9R8?|$ zN@PjeISKinsdV=f+#EDAWJirHb6D~{5qAxATJQ8eL!AbdBNU`6m}ZGdU?u_3A;V`r zEnh&9hM@RaKQ5YiCUUOI52R?1E&g;QqWq}qRbbNNlCOhbl_yZI=t^oh%`Lwv3AV!- za0>Ufp4F;+Pnn2`yjXU0gA_Z2)+=63yLzPC^z>~o(MgD=V0GB_?72eG)(Fm-RItyc3` z+%jI`Z3Rnvoq>jgb*_nx+S`|$ah44i*2t2oxb_Cy9tqpW4bx4$zcDZvs-7)b;u5>i zKjR{*ZvKDHi(dS%c~SCZZcK(_LMYaWVknqoNn@}HMwdOsJy<_Zn)2$MNwE}BxQC*Q zT3js8gVlM-j7^Mt-vFnFhGpe zZf2C->aT$J4QOy+nr@G~VNLf9m*6=mmyRkP0lu)a$ena+&YA0}J_CxxHd6AXKP+W&5eM?|cy*2p42mr`$>7n`=BxK(1^3~S?(vt*qaG{5WM5&;d z69e!(?W6q_1#eI!m>trQ3%~lIUZ5g|ib52c2S&VFFe)hRn_eV+Hn6}7#c0~J; zMM2sL@#CV%leo8^`Tj=iY3)~Jd4`p9b&2iZmRg%N5XyZ( zQ*7)=Okx#FCd45Lx_>DjV3Oq9z9G(37+2tx`okFO)Ov$g>5i%cj1kv-Zx9y&f>1W9{HFkx3cn_n8xC$x$wA;mC z_u-tapGwiusOO>S_=&YIl6*QRV_(lDQ-vAEBMj9-D-z?=xq%4EkVfNm>-MpG;-%za zEnCpWq-e$us9Izb>tq7w&3YQlDE7TtB z^WW&{i=6nfaOI7;o^pz)!IRtyLjurUtI6NDV6y$(dV6?ggyCw$01x-VftuW)R_fA8 zwzk&I<>Bq)n+y+5i*2$p*}q(XzW!s(SFuu7!G*2N7+i9Ja@}R-uD3dTRc2l?pfwl= zO*K2#MsL!70rPM-_xoW|iHKlBW&jT2_=x)9M7LLbpfqP>#3IaWXySs^V<1BvK#Xx_ zaFYo-UT3sO$sJ2v6BP0a`hp@yC87ec6HSGa_b%s*yD^FA(VLM*^xdCrx*cP&KZUbz zF+v77Uo5N|vB>iyBr0k;7fWyz?A&^iNAW_970=wyAguLd`U&~wcKU(ZR z_&g8t_|%TAtK;VZ)4uc+e%A`-jQ>I0eMU9)ziWfv2?-q%dhZ>iN$@l{6tD-+J}=e4+D2o>6v6X~WTk}W`uCxXLFALPCne-$f`reWHnwD7F`fOBe zc^$T(FB_n!7n#_70+H_zpwL6#A=5v_0=mEJT3C{7f8PrB%WWq;UdAyk%s1Cm!S;&g zKmTS3%uf%qTFf&%(PWz){+);{In!B_+bGduF8R)uYh!CGhp*Hrhzj$AKGV2-Axpoh zV8Iq4zIl?V1l6$1+b_Wl-ZVlM>+pre5G~qAv5U`_77E&NJS-M@*$ZJycbdm>Zpe2Q zg^~=Ya{|nuNhm34u9e9P_I36*5^ENxoBWdcGMHu03`<{37ux0^`h37=!YV}4F{@MT zUd*NDNt@vrrHk)-A*oT`<0Ec=EZwOGLD#?dLlJ#*+OZnH0!~Z3?pa@pmcFK62L}4( zIFWC0Io^E9W7$+OhxZd?=!0TR%$k2Ax?cFj*##ZiiQE@5Ya{W5%R|B`Lb-oG7Y4G z&|D?cPGDwqF8x#f#+vKVVvk14dW|N-VbDecc&DWjwarVo$1jVJxmA*Q#MDCgzF~c* z=`a-IT2T%Wd_}eNXHw-#!KvG$ygjd=BdQSc!lsM8s^!wQDOlMYUx`SyN;{>jmTAAw z@b}P{7yb0>xZ3(G%GCpAJMAW=j|3E=3G=n{d$exLhLW7U*sEjhu;c7zA&%g$r7nX> zj!zKi+md@M4#F*?5Ps@BTxnly_=}lZUidb|^RBu}_rdV|zG0)Dz_!!#gaML|y}3Ue z`uMoUPb-=mD*qPrL3lH!o_+jk=rWh2Onu%jxUn`93@N%yY!c-a%;V)_2aEJzNQ;M1 z79TM6t;pr;@geemtH zR$D;R(oXH1706l~%vN;cI;^;w#=0gSz_Z2 zAPOx@n)`lEguAUk0*2r;pdTzTsl+$DRo8Kh(Or)?$9TAUKteI*!G|rmS$A*!3SY=Y zF$XNZs3f@orr)ano7xAd2xd^jgx$bxB>JTCL1bgWVwUF2(SjR_gHY0s;i}5MiZ2wO zJ)C>yK0ZD)eo4%wjpWLC_@ZtC$iVm&hmd)jZ7f;$^G}0Pqsq+YsS+hu?7^?I>4z|- zgA)RPR~t#gbY@#eq`k&id^7#P2<5p&4J8^-cR4IpQU)^kT<@C&$?QFZ?W;J`pD}17 zVcDLxb&0RS>3|kRYs!I#Q))so$9x^rkCszTirPY?A|GHxQaZ64LlS&#F9SC z-TB1EKj?@6%c?afy>-lYMDeq{5;)!*5$I1K*GFzriQ2lDMg*9qNCZp4lOGIt*w{Ds zVXBbK;;LDDDnJmykq69Yo-aS`Z*_SYf6rmi)|XYzbWr-TVSpruol49q@c}^`6CV4R zP>5GFiCmdNWB6^4z^hu9H%_M-g~$8^@?axZIE9!;$C1jen>lvKOrgEP7<;>Q^GiJ; zfxn{gg#~u)1U}YM-`W`G_7k1q9t~|~R}26gljiy3>fO4*7*6_p z=dF#;n=2tp8ww=@lvQ+l3p3AkoE8MCFZOeMlX~={&DJO9Y@fIJJ{#HqpSHf3_D%vz zy_8XvuBoSgKR;k9N{a6ixpy5&BSAa&SwP7LKldwSs*l;#m-5XG;X)`vtFU6eIrmch zeRRu*SIpTTTC%(KS@hw;KPA%TZtlk+Me5BJ_fNgCB;zsKO0GnWSFT>a?}LnBDDwE_ z3Q4lZLrBCQ5{zY&qMj=u4!B-Uy^iaDp##PdC z9wd4Sc}dkO2A^rhB0^CZ(sleb{C+V?H|mqTg0>HieT7L4H0!S#%26H(_8Z3ky_^Ph1T4M?Zt%_)v;^4UFAv&1);B7k`eSzwHt=2lwjx`t(1sMZF6~JAFT|YTwC!Lj-*fHdn z2SAg9qyh*9=0N1GkbADHaBJMU32ELGh%O(#9ru26VX7%4@%hMFolz zM-Imi+y%4B3(Nlm&meL87ebUZ(1rz&mWF1b~pwQu8-K&&QnG(+y@A>rZ^gvvgY0W{rn0QW>odK z-fpTb)%kI)iQ4qF)5DF~xEDNxyIavc#`w+~@KR9=BLRBn@6o^D4%f? zt+###fV6i)xO_KTEKIzQpym?~ud5&J7XLWm@Dd~x&A3H@@b%^Aeg4AQrwJdZ^F9aH zaRVG1mP(;Jg+g_Gx5T$RN?oFhv8?Tn<{*e8VnyZLU`bQ^BrNV#2+b+n8l{>XJYY4z zs99eBsu|=dq*wWvd(~i=>HP!ZBCucwyc_aDptPkbDglF#jCdEx$Mdbv;{k7XgJFC9 zdAVIMQLj*BnA-zE_4h9?=QwDniNF5JW5w;WhlP+Ta4_M>ZhIEf#omsRR;?)>2qnA_e9U-aIt@QnBX8{eS)7ac^f%=i!&Tt&Dqj?s&xzcy0h72(w0Bj0F=a3?YK)Gf--NoACTj^E zFPyVV3^oT7<}73VzdcmX9*8>-d9q?!f_&316zNsqQQ!0Jc5T!}qO+ak$z~tSQS4UL zkIys4h+#e!+mDnlWnj+X25^68NX_k~7+}^MELeQO-RxGsU8QpJ^HF%^8&+qZ!jxqC zn~oAdP7!xLFULjjo;oT=YUutn*o$jKs&RX*=2)D4%l-Xl?{gJKXTIK_lYt5#E}@8k z6d=iMZmA7k;-1UR%H}8Tq%`5K2e3mj-^@>_L)-BeFj{)(xFMwcWMe^y#4_(g+aOV?ovnlqE zR#3MML!H2rA)8X?C<4AzuJhOYUicllx2Hd3OK0N(@&2x0d4aMSZ{tJg26TWm%wC?L zL;qnogOMTnl!><296xc@@R>R}k)30>Ik8nmgNYpKH%PSjcoofnP{2jq5cxcoMh^iB zPEt!|!P`g@8Svnz$vQ2uoacnRKAq$aO5C>&&)~h3Uq0fW1QEVnTIdoJEftW*^+*6? zoGT8xkJMXuNvG32wj0c_syEH1k!P_~iq3nVm=NZIi!Q-;P`!A46saYcO*_3B6s2y! zk}?*_b`(66wqxKa`F0ubU?K~k{F+cAT%rnZ9cF%cglWx^twCQbIjv)u%wJWq_>!vK zVmvN6`D|ko0c0CXucizNmns>KbUmG}aZLoz85Tk!&R!TMeywJ|tr;nJ(Z-)mKhH89 zSkc5-ti(ORxG6Z1se5xWZdBzmOb}O~n!GAcm{GYQ$`PqYxoZ@@L|Y)|jy?Xs&J|RI zAfTGeM0&B4WFOi_3Z)mKmq2^5jm|j;_?`M=Ox%k+A=_lod9~=L1@wl#SW;wJhDHw` zWz&5unyF^fi_f<-*UK1{dFnTmv*})zy|eEYRB-MIC?b&83^z{hLIH+q2^3N%1bDC2e4^ULxKXiMQs9pv%lb4H!dei zwU!gux9^WMjWHyLjG&Y1(jJIUADJ-zHoC|@-!mHvJgn`)f8gMry|5T*Qj`K!mJ6I9 zk0o8jX$U=VX^OA_d6N}CC#!f_K(o|woK_SSh7kAzij2bs6kp~4a0i8In0@hXSUY$D z{lN3|qDG8o@}k`O9S=UX1LU<~7Q0WA)3a05ym2eRMD?Kf=ra&Z+_e8I=EJGVm1g2q zin)VGqTTlxU6<*RxXpFyS?zNR#2NkIyigJN5ExS1)ZnV4B$wn4idEJiltA)?jbi^& z4&3M_!*fITIWK8whdja=KZ*yz5zo$T;M5}uGSP^~R8^;a7K3&AB00;ndQ^@7w%;2y zCOFW^zr;=Q#~_BpHZ+eEx|{Uz{bu+>im$-3Kso-i5uC;@zxMW?KY=9*;>RJH< zKywPPEM%DIc>xif173bF_`Uae5mUgnikKv_cu%<)6dUrMehrineqJm?=VSn*o-7h= zD$@#ZGM18@s`7qaV1BSeZ99wlW*B$&@w+D2hnAVCk9wL333suAWzPo2iiSxZ{6U)atU z%VbeEQy1i3)dzRGkEBR`ie_w+Nanth|7E^f$?nsu6W|saZMKG|CQ_s$vnN`$Fn!Q0 zE-8VGQ@NfQ(%p2zi6ohMe{D{v2d~kaTKthB*VMe-c|A&2`JQjm60a3qdm^s8UL)b9 z5cdLmMCb4~nu7iP{)Lbw520rXRz2D87Ay&~i4Y=K?#CG!UKK>3M;>`V<0Jl)3D@lN zlK8ufr_&WudJpiiVs2N=P%CXSZwTMa{}5jyZ5Nz7d3G5`^0XUt3{B)H+({Bb56<*z z*3$plhD$S3pQuMX5Ot_--^x8L5&pX%0o}Atk!RlcmA3Fb?izk57NyS{FiPSPEyr4b z+lW1c$=ZGR_4|FDzkO98FE0@}P489#*29%|@B9a~iqUOxiu;4Q{=YqsPdUY2@%(k~ z3xfcCqz9cxGK9DLcnqnp#Uf$%LDVWbfj7TV&(FTQEGxdPW&*3{${6$g!No%DQPTJ2 zvDLvbkik@A%-uI2q#sgmq;HQUCvOJJ%3H*da2F{!C?&DvOoQ+gMFxE1{_D3lULi&L?TS`L#Q80pyQRZO=%4^esy@6wjy%zT z(3Kzlf#m>o$jBV2Pq-`(jh-MAoS+t&pp+1#YCX|+N$ftwAdMW8Fa-Ff8KD{VWK)84 zbAq2b;;n4!X?~xCq@7T|{)O42hKXDSc~}ycAYcdebf1W5s!r6GPoAv1(~~ubbe)`^ zD)Gt|fcAUP-L!Gjf{cP5jQk$VPGg7VZcGXdqSVAy#r>eVDja1?!s24=8h*+O+$kNilo(y}iL;PT% zffMD-0$>*~gn~E+dEzEdxx$EWJ|>MOc;Id|@R9vw%{fid)?%>e-p2Dwx z(rI}U@@ zf`P%vs^}pPfb)ABqosb6$nX5zrf%H(B2@gxQ_;U#?4*H*G9SA+%>0MynLMNH0m&H( zmxNvHl+%$|j3imH=u8eI#E;8}wb~bpoM2=Q6DJc^&OK82R;Tbvi0jHo*GB5`Ld}m5GBb==HM@*~dla;z;uPB& zI0BmKLW;R~T1%u%jpy3!VCcB&>!==PlJz5EQsqn|>9TWPEz;gfQo)r*{W}twPp8}u zS8@2DgmLl>)1R%1DhdV4<&>CW}mgyoiw)d*7gel@;6B@*_Wbcej$q?A`@$W{I=%8@#b^v$ob)f#UbRoWdg|$a-;_6-kB!;PMaYP4 z;QW%rTZiJY*U+Uq2Ac<)7!}tHzj6h9Kl3J$$VV;=glNvow{)mqhpcP-@p!Eeo9esQ z?A>`mR$$`SZa~!2OP_D$gP&}_1p|5IKmL@)ga1Z7RSZvQ#@q9=#D^JHeML6YJ~m55 zcHCfg7cd8YFm75e{g(owU~A5(bxvurfNy%b=n0~BFP+;<9zE|bCE=tRW8{U3 zjLUp0QrtfDz=&vhrh`6TYtNCu4RPF}=$$AU_GH%1IK#a^_17~~mX?00uMpoaMbhIe zGSe6UaRJ>p4hbPXkW$LH-S3;0LCzr0u-n7<$cnslR(_jNe4z(ha}`YLn@H7~NOzOS zKn2NKJ!+ed9uha;Z*|m3X3-I2Q4H1A+)&QnV=%yThHA`Z( z%Ak$|JOok0?Y?h*TQhN$|GSnRB#{y3oAJICeNjfP{zNgxr4zi&%#>KmxyhvB%PP59 zRA-UZ)1$x?lFSE5QYi+_U*6;sNfwa#6;QPm(ETY0BUt*{!mP_?ET3s?0X4A= zGjU;4AD?5K%*lt8@O-j-i=VBegRz~Dp}1P=E?M^4ugtft z?6u@7vrhI4>gjUd@+Tk5W2q-XB`e4XDl)UmYb7RIo;;l$e7dUgY+>2FOM#^UNsO?~ph%i6cjh6-AAjmkbcy=b=;y_@E6hrA_dMUpcm!k3e>#I+rxLhRj+{@Zl1PeLP-A*>s{{3_3?~~4*cHjOCFEN@oGyXJa6Ge`)^PPFi8Fezu zqF3UkU8JrVtK;^(z57P2Q|Yq%v3SpjP#=y(4N8Wlf6%9QOR|OP)^RSo|J~=FDf0oj z#XfV&fjjelHqt?(#eRafEkrp3YSKf#i&jV3Uu4|-tUCIh+I}~s`5cHNjY;myH zXE=anNGqoW`gTOBekA(sUb`Kau|aUl9~&01~GYNpOcG>Kvys9OPddk&qgtq5JXN;)`zrocHdBpv+H^ zfS(ebKV|NID#%Q#1WamlPU_rE8puo;2TbV%Ot@N%#=reGCH>96W0a0!ENlR%3*(uC2AZt)ID=4S*{C z-o`789ap6t=a3!8{v8?cuAt&>8GT=S@GcK{k4tfnBY2OkZ*Nc?%x;BQpt?V@Y&}Nr z{NvtfT2{U%uesvyF6v_*&ocetQsCj|!oy_BqoIzYgZtGRS)TJ}Oqg;^xC~5$C`RHB z#^9ABx)sKGdO7Cjr$e&x?9V0nP!bQj#YCTrNuo{^!8jJcXa*(XRXQ)e2*2_tiTT!g-zDBls`Pb&zYw z%^>RL8^aZzH4qn70zzOq1knS`xusA5*Duk#cHu)XK8++AK`B%Y$K?*Fn&JI{2<9_P zEqb#T(GO}y-A{3umQ1zy&60~qXSfyqpAnQ>9N}_gfpRppOq6hiVNt?#Vud?L-Y951 z?FEh@_hNW(WXojBL#>?P@CK(l76Z2-X&oif9gR63Mc5kR^mqa31|=Cjm-sTRtvhk)_Sv9P)6^6hynp0-r`T# zui%~|PV|`%r1jzKbJ#x56m~w&Ec>6x3@`$ww?aw^TDQN@&n!c1L>MLU@LCYgLtCf> zzW^43@^6d2KJ&5u?8-Zkhgg0%)H`xD0y^bWb8`9HA$j`_z(@e1+AUiRg>j8F+-pLzyhv~iABdP&D@rzG>` z*MzeCC`~K+%j+NliJBB_1b2hL`Jfz+8&*|GhLhRzj~_%ycgq2kSKT-(>`@PnC1o>Xj&Sl4j;@*WO#brwf!k zC8T~dw*C#WT)*Go%CeE91~-!@(J5A(u?5&~H~PP`Kt1Swh;j^85hrghS6`s|W zBDjzvp{cshSe7HPzHuI<{!%aIz3qn<)4E__@-sw7j677L!08F!SQAG` z#F7dJ%lL(I_$xfQCAmSas}&E4`#qSzk_sdZ9TY}wdus7E3kdhYEXJ5)zhyUC>sPj5 zxJe$S9KGE!{}8!|C3iFNJ@EPy73;l~6wqkN;Ff8jaJ~8Y03RN(Yr_EkB__8oDDVy_ z2ZSFbLU}v-sBJ$n0s@@!XYNSEfj4sg4Xu*0nk2fG)J2fh5)0;_1l@Ft z*zqt_NXd^=7ua~WUaySoIRgU3HOM|iroiqCASm?;YZ5^JSyo;B`^Uvf)VS1o4Yp+L zv?r?!CYF&@y+6_E%OC~@$`1^5599U#Mq-M>l>xu21T3`b3}k$fJuiq4=!hpivBvIf zBT)~BH!!h?7a!3Us;g43GYDE@OVaj#3?|((T^O-d5Oq{Xzd=egq=yMAtNKu_EJMU7@NZgOxao8XI`b{lrj%x@ixl5hJHf?|iT zjvZLuSRTjo3b2wO5h);tUVQbP0&3BA7TKwZy3; z*#^Iq#|C(ipdG~R0ghx z^dRA`4-as>3Z>5n(bjQd!{~#c)Gk)!``g?~EtlEa*uA`NYq}0<=JUb%CQa3^d0k#; zE!2GNqc+zE^VS$-5#=b6p)`j3rN<<4R;Ce+rF4f*=6HyiFW${fPy~EmFp7!QitNZI z#jC>k>3)rB`y$y(r*1qV+BHlHW4MxJPX+nXX|vQh!J*@k`C`PXI?j&iARhhV6maCt z#S0G(<41p(UQ3$F;TJv)ErWcej-mGZ>O+Y7lt#VIK|L8vze_pnTHlc%Npds(eEd@enM=0D>;=PWiFjsV`-Hz!FXBS8 z;h^O|KUveeojUWf|8(WX4#GthnnO zd;9-=J6Caoc8yTzfdaY6nQqtB(kp5=Z(8H+%c5F>lSr+%>!h_ly7vOR?_$)5)>?+r zf25pf*P0KlaVd%H2NB!^+D|+qgjMeUsQ~G((_Rj%lysb(wv`rQQe6cPz9T%(#|zk2 z=5L!o#mAi&^91Z@ziRvWf$*YSD`59gZQE3B+(or>z@EiX+e|m%WnFZ@zAb zUZ1BFeYAO7R#X>}nD7QTf$wZzb7W7rOas&K1kbyhu~+wvOhE*K=qb_VHW=_mz;qxA zu#H(5`6Uq!<85ydVFiM{`oyx~_dUY|L$FX`eKfB{5KS?sI>T4@2)f0!$nm3Y6bgny zEHZ)4jvoVVxVIrVQ$6ssI)>^5yge@h*qSeXePDz>+z;KO_8U74eQf`J4FPaq7VI8@yhf4{xT6H^`IlOuqsS|WLOF4@qCi6i9#BOBME^z5K11#_->~Z#1 zv1Ht!(RH%3={WKUSig>8ECBEr2$WyN+Sr2oGr~-Iz?MycL6qS(EjASAb=dNCknkSt zXwK+Q>d}5;Ky(7ZbpqjMeQEIlg6i~tD(?WmUrW`WkO@?~N{B-Ezq<~r7>4^J;0HZ; z-ulrqk+E|=ZxRFu=eJ{5u;Vhyu%E!`jsV@Y$he)z*Z;FSaq{1~6Mz0YcjEHDxD%(S ztG)lLJMriI{2onDoUi_eJApb`LAw)w(bmM#^uM7K_Xm6bpc9*$sQoe2PCx2*>wk+* z9Q~&_QH@%d{YRXbP5j?*6BDT@q(5rZb!oEyKe!20Z!hW}Zo&rDZHMYoN41Efn)p!- z?Eg=>iT}fz5c|iPsH#BKu%kYbqpFDiu_pcE{%@3tCrw2k3JVMW6Pk$D z+>DJv`TL{Z=q&sB=H=z(h${5IIDqjPEil%2pmR+@AFY|I3{qHKCmHf^rG; zhSPd)uSGD1b6Q8zAtrhwIZMk6BXC)58SVJz$!wkqH5eDgVrSV~84}30{Nqk=Z6xGa zaUubJpy1!#34K+n5+Y+trr)Wib~_t*7_?qCX3w+8N==!^$s#o?UC02z zAcY3m)M}&A;F8L~Z*eNlHJ?wN4w`0PqE|=y(st)-hf2Av8nqIurax_EW|O)&t(&2n>?jT6xLoKZhM?cjDOTBCUB)js-uo)+j-l zMW3sNvZ=O(s4_Zb*p05be1wA~MW75%?jLu;h^+o;t1a4{;Pc`_4(hykkbq6bG9akP za1`;dNKMM@*q)VQs`2N~wmr)+v^&vcC^Ta%q$n-)`%F)X;nBIb7DGm3_pdbGqIu`+ zj?+@!=e$>ot>nzHQilR(Ve+kuDDtm*Pd*ucb@kK7N6;Tc7JQSgGEImO+qVs_grvu? z#0!}-HbzPu#TdT-0))~H37?nSjAAA%rb#H+;GGK_)S_KLdzWqzDF*`{X_2Llt8qt4 z%VT6e>lGzPp0BVazaw7e8?8JTsmA}0I{^y-aNgHxpYnNGwa{NpCJmDBAd{kqtY(EG zF3!}#g~5G?To+$WqzAgCi9@Dhs@Gp^LTIfOBT zRb1h7lh&KDvs_Fu@v_(0>pr4;#(|L2dPv>czubw(!+j*|`5fjLJp7 z2v@TQ?N0nT`v4Gd${8no52p5ld<9fwIk-ZIDEsK39|weSvv5sg7~wZ{U@}onC_@aQ zNYq7*2^Tl&eO!Lw&7)q52L=RQ>TAX1G7hp&^q~UCv;WqexF}cGsni3Z355ZL3jJ8_ zN6-nKme&S3rr(?#>FYwc^}%#sSR${y+!90&f5*D#*w8&6nQm^o_=u<;mM6pHh|XkLqV#b=;kjTX>F72q8xbIBZij^?TruY#CWt{ zcr>TyZmV%rN{oFEH2LJQ!Cq2)sq?YzvguX*;0ks_&^y%rM_(2Q0{o3R%6`lex?E%> zb$ro;e2ov3Z>!R}xuG5FPmG@VYK(qxoIBTQo5v2yWVVc0{`((^R*rjd(W7i0>xm8r z$?TrVQBq>GknjRQ?N3nJQ0c_|vhG`LV1Y-pAt?k86&b7t9!jGZu%SnB=D5Abll;}j zN4(TBByJWI8X^p)JK_vuOTq>i$JS{tdcH70`hv~SKiI2i)P1)`h0jgcqNl9f4eyaK zOSpWOS4N17Hg^g_}qUbJ=;cR9+=^UQXl7@T)skIMmD6LwJ z-^r>|q4!{@eI$?uRx@#(j+?4dX50`}ojjFKTgFU&CIK(AO%)g3Cp~E$k8bA9Wk9V6?t}nZ>SkYghnC&0;ZjPpVVX`+mRr9H-G0#=SBl-Qb+2-l+z|$JuD6@s* zY0=Meo-X68G-ms*qY7IHTf3{cZezN)e)5aDiyXBgmb;%_A?SSjyXJR`shxx1D?O@3JW}7D z)Q@LRAG6Ji(YJmb?f1}brQKAAm5r4VE9LCq1N60c!?mAW5^!?3A+sLoM!E+f9S8G8 zx^1()tzH!a$9$qQLgQ608w(ciNK*TEs`J^oCSAZ$e!BU}heDY{=#|?V&GVb_ z^sWm~e!x-m$}P5a=(_|mplKy&V`kZt_A&iRI>j)K$I{^{$NZ8dtn*Z2y8}-gb%TuW zIxjnVyU)fNE?m1t;MvkofA7YqD6EbWre#Xd5Vqk;R?Awbh;zuNcz5^wmG5%89;))& zKKO39`~K=X>i(}BiULq#N(nec@W%?nOOJIe=0LNx-_@p1-y^ zFy*taelK7q_VRef*Yni(;!W_G$2-*L;0NXJKt2H&*E0Po+=C**o(VA7It;gcF&M1$vb#m1!_eKuyS&+M+Tcj@_thbFlz~$nj!IEgU^YD zVCsj^{lq{eK;?q)(gECt9@3pM;V%)68j+-#SYh<0@DqElvo~RHvH6RxNINgg%Ob?_ zMd4P-7Nb)Z-;LoR0)*Qr1lG%8e|K@`WK-wV?FR-y;G+^q24xtIwd*N`cYt_Q$7zJF zl_fU0PpEnb0l6pvU`4EIg(V2S=n2^7c<&i0nkQ}}Lhj}5;5!xmrcga7Kk7Cqh=Q%ygWHw{s+1mdQC98F^G$EnGB3 zH{SJB$*B^_+JcxmPqOtg<0Nk~TQhTv>$CSCr&(NOJOC&DN za63o7Q4cX@6dbsQV z=1sPkU$JUpQQiAO+4-U@Z&Icn%)4VeEO^oGdw2D$5`}`|35|U2tO9LGxN=?oj$`&- zMTtX{dHI(@Y3kB?(c(*NXClUuLCd%oW;qTw>`s}b>|aYZMoN!y$|WU9asL#;-ju+< zmPNIBIHPt;q^Qf|xXW=20DE|`iBl=o3Aj9;@LYhvxQ^YwtsJylM)9YF>rZ(IHK{0L z$s@n=3^O?QDnYRuRNT@wU$d~#tgyJPFmb+$EUFTl2+)%+Rg5Z!7~qW5sB>tR&(H6GlBb2PqXfoCaHl_1rbH!XAln59X2We&+Ng! z$E|zIT?fUh-kmQk)r3@=m7Gu~p0!b2Xu?+na4`(9f9cngN0(Ci*ZtUa(Z&6wKm>9` z$ycXGl}%;fj&Q>>;PuLiHN4T;{8AqU%@u^48x;g0(@tf0RiALIpw~!jDSfO{eXIvk zjWUj6K1E`z5ZqljtQrZ{oi5+ot)i`}e>YEp?S^^8{i)UrZY4l)VM(x_)nrzc)WhSBbZ~UFs=vGx&RasYq+oYQH*?C8S*$w8-2oHP>#ZWD99IYv-Y|dRE z>HAavzP;#6MRkHysZ)^Q6SMquIZst=LS&uZ>JYcQaJ?wIvL4f}iFFKe44bV>Mn}=v@BWxr(CcT9@kD zFz-4S#`N;T+HCLI&o+9*R_GU1H9i_)@!Qx^q;tx@6Vu9s0bw$n-O>5CyMw1^0@4B5 z*Z%6?^ToD@zzy8L0LyXf!LRQ5LetYY&=D`y&CO+Ag$I1hZnbM~b-=5zH}Au&hq&~# zFzvP2SN3wvJx?}oMenho5Uoy5Ej;_J9Zr3a0+2J@tP5x;8Z9l^`+(Z*JEyQ!GO+~! z+?5`vaUH(Ae?MkbqvUNh^by-a1Ib=GJ-Lzpr4V1`|@~( z0`TW(vlu~Gjc_st2rlag{8mX6qX+yW?3}*XJ#QyGMdHd}_lctxTOP;Musnc^@|5(; zgP+DUtL&4SAPIh03aRzrTIFLrO(3XZgwy5|7O!Hc*5UqMB@;)~O3Fi90RnIk#;F^Q zyc_lnIze_agm6hzks65aC^p6)gZ4I>m*QY(wLPyUrA;7s>gJ6x@s9;zoX@U)3~Qsn zx?bhALPHQ%IFkbK3IRNs-qB9{gzlKe=-bBFoH5K^z`h4_0EtGI#?v~+G^}tl07Xne z>}|9LkwBP$)*uqlg2Xp*OIUC|z?_fU#0VdOE21gf!@BOb?qq6j$GJ1dBihF$7RFPx z;Z@XTZL7oVZ%4EguztEdK;i>D#{^2OaJ4#uzoilOfVNuVJq1rH-occ4;kVHf8m={3cau6xGun4E!fuLpaC}nB9|5sHG)^#4 z39y(u*lhxg_XlXy67P~3dvlc+#t8EQfTUx5<%m`y893?F@zd-Xu8|3eu~w=5nYVQ4 z23O1uB%GkjL*V!qQ(?`I5Dk64DvtEP&iT@)X>)v92P`sZ5R`dagJf30j98n-w){vze#NxKG__|+;q5Ke?$mS=VQ9m z;WczNKbBeZ(b{_5HRFz=AERksbw8|k(Z$!TT79m&t)sgdJ|5v+^TF@s?%%J*_-cjuROD5wwYR`D#xXEx&ww(sM2?-RS0569y~Q@&zqQ{nS(AAA`7uoZYT zn{lMRbLggfeBM-P4{U#WdN{M(hyCGj^!|X5VePK#nE}D^odAB~@^Rt#M#kEk&i>Eo0(AJMpz=@AOU)-*1XhR0X4u$r|U>SF?Exn{f<(_$hAO z{Wd$7PwkjGoDer12_H&puWH|&)${+QQu{ma^tXcd>ebpj(ETTwf5U#{x(@bdUSF=m_5N+vj)Xfp_!I|D1Q-m-OCNK0o-{y|wY`Wb^sEFGu;q z-;aV& z8-3vqwb1TFvXyR#@{GC!(00#`u)u_0cWMBQc@-@em8e1 z5^~45U+?ov5(e8Ce*3L=KgAiyMud3w_3M0LO^@1lF4cTKQ6V%ZeUjYq&VH!K_Qqms z@@?e9qN~p96D!Ypo$ac(BE;K=9nb7pk3(YT_cn&!+T(_fc7R$LgxCs*j}DqAL4J@I z6mFfV`uj)U#OFKi@_N+mU#6O#LdoW2wU>&DdtDdv3IO#NdWxs2V`n*&C^~x#g(UIz z4ViMkj~Ve$HB2@$$>A@b8iGZLDO>xGMOx;2`h1thkmxFu=1~*@~5%2@Zb&QynRMuI9;X z+#=>&|HBWn6tA zK8J)mX^$s4#%?azbk6KHxYI}%Ds3rgDAlNG``zb~$3`UkB2EAA7N*ukrtrnG%H@r@ zrElwHT9*5|+z<^L-spF>ARK`!yOY9`8OzX5s7+$4n>`+wXU66EeRe2uu81EFTF_*5 zA&Mfj{JexLwo!jv;`nSR?VW7Yxo_*YT0e(vVuQa+m^v?&TlyVuD{4uH9K(O9@y{BK zWOGvI*Pb|;ySm-Gc51ZA!0^M}!~#aemZhHJ_$%s_Y-3INy$>PRKVk7xI*E)AaDuYh zv1E04-`H3gH#@vP{)eaF(=fz+<4rVNU+nW~!L9S4X~s{%uYE2$(y#OQs>84A_dmvM ziLkvPvii#(odK;=(u$8832+g3;;Ks4o+CWCk^AI0hNMi9%xbkl3)0vfn;wK^(f455)MQ9eybGb#S+r&gE)4G6S?XXsgUH@z4?G9 zWj2myNOELqH+o3qSilT3nc`cznmre=> zP2vM6)-z3$IHxan8_m2-$4duZX*xd62X z>MCuLS#BZag+Bz#RpAsQnx4LU2ZyHLxyYv#efFVWHfx4hUgk*c5JiM&yc3>&*xzts_= z7e#tSQe{7LIlXeuF%tCL)i7kxE92+sI>DLR!?0BZEYG5;LQ7*w*T2P>Wl-{gZgL(; zPO@>OX5)JcmK?2*w9^>HI7$t3UXy{pA{G3pRZfZmh>!9kpV-w+Xy%}mAlJ5@pWUvGRTJ zB#X5^tTk&Ha;5ZT^H`}8m*J8u&;JmmyAVnHqV1mqf8eJT&hKZL9diS|LB38pinhTW z-#mG3&)Z+s%AytBE@F6iKZBmb#CYelf;a7SN%G~b1t>aWoMPBrF2jj?zU zd_6DEh2{fZK3qK@TCMY^00UE1EUq%*{7 zp};ra^82@ZXFeOHv1~Uk4s}01<&a66N7R@PBKUAfrc&=6%GA*GyY0vE&lFwZ{_{=33`zX!>`A0(GVyl>OyXMdM30?wWIg%(lw^f!!gtzbij(13PAZk+_y= z+`ZI#7B~&OyoeFFM^gLSb(y7uV^!Ba8ZR(@wUBOb=!tU8Q}m{n1bnQExBbGBV>Q~M zDIFScxMTZMevF$B+q8su#TB7npvWmaB2w z=gNN#k=_NS>m@nBE!s2`7FCJ(h+P0F!wE{b!KtJeA0Xq^Vge&qqlceNq39Qj(59D4 zK3SPqy1QK{g`TZ%s=D>drj}%y4g^U)OAL+Uq$*uw17S=6lBN74hQh)){gul%MklN) zP1pTDrQvN#q^!C!bpd&T!s@QTX-GZak&j*e4uFYDlM!BjYW{kzL3|4--H}O@PoqwH zWeEVhuV?4Hb;bt(K+1#W2cQkSCy{7%GSYtPA>CRAAA9$kG{osgn z-%?9*n(2-EU#*tg|$Vv|5zfOEyqI_?$#V!_+iFO~yAwR-YetWAd2>gcu#H8x} z$GywGveNk-)m#`B_iQ+k@)kdO7$187fVISXbfOeP4ha$k#DoFDi@|^-NECe%;dSDh zo30pgrS|>LFwWlm0whsxThgPBR5<$ipZk|_9Jx^w5pnD9FUh2`v4V=R?y}ITKY)7~ z;ypu>8vOr6honUL`w&49ENe_=ED!?FEl6lhRVaPk$==_`D_+56*6V)Wmu{5d=mD0t z1R-va$DsB?qb@QJJkLoWhe;1xHNFu5#336W5(d1l{(1~U`Kx2ys-ZFg9o#VeYWE14fPqF!F_ zL9D~hJYpC$@B-3$-oy(ePeIL&Jdzv2eLh>!`U_uQo>RdPtk(x!w*+=$!%J*!oUyP5`8Q& zdSj_QoMQgD%C(37}aU z9&8j2eP&LkHG+8GqZ6AT#o`2`gOt7UaqFh>j6Q?sdZ_waXdwuYrW*IoMgQr+kkkY1 zlq9faTcU?7hJqf((uQA;p1AH8^as*CW=J9cK%XSxTX+DKYA5&#^|}?40M)sU*JUsy zxRH2*EKlz{F+nH{DsYcFghBA3IxydlF?&5-yR2)xqxfZkGkKSKjPa8((3If?MNDK8IOaO$8GLY4bg0D4_^rk-prghf}I#)JVQhD`<5W)2$*;UB<}@Fe$o$nL)wF$R-mn%5=I*|EH~hgvjDvHfEpP)A~(dO%z>FzNwNk43Xr2WD5V zSgT=k#zJ$CP#n`bMShp_{?LU0nuj~>aiu5FZ+tAWvc?MZ3n5PyLZynnmzZI86Z|&u z1F9GNuz1!m)770>&paWJI6UThCWhS1^bTFCI_DTaXYOj*@%WzWEW{<{SvuL8lTXGk zR0BVjAb7Fn4m9&ATx=;cRwpq`^Y_>K>DV#9!@-8*AVu~K85polbjWXSD&-+M4wIBiMkSIa}9|F#Jhw!(kD~} zi-G|35KmEnTs@hNflTETA@h!xDW_tV7U zT{7o2g)Kbh*wTiQ*51VJ`@ih(f*EVuAE%fr11R(O+dnjpcZZ|7af7 z7T^Df3PD!{R2ox7>7KDg3&j!8==-ewMf`{Ltz&l&8($QL(E9X5d)9pR(o83$T8uB^ zTYtnyqU2>#Q0Gyk>6W}1BMOUa+8_H5@1VQ{66%o9W{Vek&5xY_Ni*k`4T~*>;Wc&B z0W9mKD?GNI?9`Hy{5tgUWq{&z;7Qu>_}&-$?ZWOwykMqp@o$0U$DIAMn!Z<`4r2;d zb}JwKSM+mLnIW{^C1w*idAU~Uru5?<48NK>eaQp)?LI&5V5@R}_|xjupiOwokve~( zI|QI4iodCRkU4&wQynuv%8VF9kX^GdO}erl){cJm9Zx?-TR|d*A&S^I!^}ht>~W06 zF_C?;_;r?pwvCQ67Y{iabiA~BJ{$u69Jd%Ff@GIq-iKxs$r&X)vBY;Rh?Dwbcd74B ztVMv2_OhLvhz2{^Om`usq4-8P;B0zdop*5j&T{t}@CP+6?9tq)Ek50I`0&U714usx>bf(g!|go7C| z3QC_Y@VAR(d}-xCXF+HfSwzu2sUS+!QbK7utr1)wL~#WsTFDw2#1 zPky}!Gtt2qQ-j6oA>s69GqhnM^A|DNv7R5V(kJK0i$g1<|0w>vXm$yYTg1~IKKhJ3 z%-72C8@`Sij`OPyU=i86D}sTrp^uk;rzZiz!`Dhw_TPxu1k)y~hv7ws;i;3aehmq) zmdTBn^f|0ctT_(*kT{#NLZ8ZioPj=A=C~1<2oL5k%-W679>$BRj(?Zv-~No%3*HtJ zfRXDD&sDk6X-(qfO>w*q&q(r>c@om}d(u|zB)JXbft^W8jH*bEiz%W%On(taNPOgvsFB`+TiP6siz#@;RN1FGBs*IE#JpDta zsm*Gtrdil_DX>`YG?XpmEzSAgQ?G@i8`=@9UV-?8a_xislC@64b8F(wAxjloZgt$c zLyo2z>T?7czuoF$!+5-CgRtN7C-EO+uVjLbR_}L1bR2uNL0Z)motlrGBcf{;E^QZy zM0|cN80LVp7^mwS8e{_9m)zpX@cr@{e`e+9NcbP!%3b8N{(u(-5dn(4YkmfD+s!Lj zodCQ}erfqk34WybY%5@BVzy5uGe5@j;WX;mwrwG_ID%K7B#Jv$k z?1pDY*>e#@Y|OEQO<+U_s@q#KM}OZ+Bn1U*Jfqut$ezOYzO7Ve$t>20YY|{HAiE+2 zvkzsr_+iV?f6?^CfkOk0$0V~^!Qmn+UA>b{oW(m000)P#r8dUig84U(%4X7VnaoUG8#OPP6BeHCu5ojmNEOz&jL zZpi+MrGvMw{a43+QmuJJS%pt_accN(9(50c5Al}KdkLw?>88oLltQhwd%c}?ZIPei z<66Xxuc=jW;~3GR>lAf`+)>{aIFUPusiTf=JrD{SYl*aI=DOTJZbr;Cfl-RH zO&=a^@^^{$F${=J@Lui!u!x4@{hE%Ry4U4us?0MPB2tC9ASRz;qXpdO0bk}vqZ?3S zN~!lOJHwJNnJ9^Ix%+U?l4CtR4LLg9WzKpHkz947E{K&0$f#ZwqJjI-+}J6U`1?%j z@s30)NBUSS8ME}hqV&?*I7iL|U?Z7(%Un^%MaZKf0WAbj z;S!@jLYn)g*?}>TRdy?Bolx$$`+P`S>S0@s2Fp+8vq`!fY)|{o#oy0=gmLm+ai)lZJgrmiCP9HotXdq6t0a~ z#H-Z`avX15zjr1I3&7* z$uR~|>_GN)fjQ7JO;+F8|eo-9EGi`&? zgAM5+!Q0F|NioaR&SasrWso9tE`GmQ#xq4uc9P^_4chGIX;GZaG;)Is#m5{o@5Y}r z=45Kza@_A0_VCoJk_EV+AovZvLd!j**4hY!0`5L^o}4|=d)ArJAxxX9r231k@DB`Z zq(_B2pIjS58XOA;i|4!>a}{rTIUdFR|92;vlE-ApYv|FFZc>L11q$eUcS4az{(qNz zVM?BNp^YZACh}kq>@W#Va@f^sk=pFY(| z5#U#f#y{h9A{5`ma@C2(2_rd}D8u$I^zs|#`?o53ix>2$lM?ViFX|o!9c>gdt({YR z;&>imR!)t&FHQjfSsMRWoQk_IPIO}qP?jn5bQ!?fm)<^eMm(x0_a zUDB#9yuEq0Y`a*0z!KQgiUk9{%YwYQKb2R0BCg~`*jb0`OlTU_dCq%0C;Jj01r+Y8O zljV9PM(+eYh?5WSUm-|X6eplox2j4=AcUi^l;t~WIK2T)rg00Pq-K$9`r;JpjP{!X zX1r~(8a&h&Ddfa2ZlRQYlX<^2`thY-SXDQR+6X3+!=0mbd9fvPn6v;JbQ&wZ+>rjr zMirrehi0yKB=cIO+{CB*!hL&67RLGK$FZ*LRf`P+<0~zK00Ck~@+RMsXPtZAhi#gi z_<>)Nzy7pG#3=uxAi#kZe|3T7|Ks$_{!hMNfAF3yEPvsY=(}Ed8J#KO4+-n# zC^~(A^rX5O5WKe*d5l%Y3U3UMwWvleuNgcR%rHD64~hEtzBB939PT*!&y2$6WA@}{ zs~qPsWJiMp&t51kW{UZVj5#7vSF9aMegPQ@LtGOS6xo>)16N&I!>43so2-Gcp-cN! z7B9sY2g!6PZk9b4A{M-FPaB5j4kQ1gm~1!t>w0q+gixX7qK-4QGEf|(^FJMwVVf?^ zP`pU=xyuU9V&4BxdH2n;=mv-*ee3D$saTy&MNRadIHG?zRn|3Ior`XJjp9BP`WRq3 z$<^2AI6gLjojOSrF;9S@Q-C$;A^CaUMiT*i)=CE`?4YI&+?{;|Th{{{(BbMFsR`@tj5LF`&5Q(3*gDSESsXwUUxG1(gVEmAe zaa#>-pb^gT5$@dVSf1Ms3j|hx_e(d7~ZW!M8bFJKC9cVz(s>A()8z9;zK8l#|PqzN1dvu#WI15!&Eq zy-S_tjzL1X_OO%6Wa)t!S#{C_m1uU6gmu(73(cz?_J}gF^*92?ic)xm?)A3mkrRnF zOwx-%%L9-l_{Gd?TQk#@dz?emk4xYTu-iss`7On=ciX(9ADXKrA4snS!$!!ezUku9 zyW(Vb<1$+Q&S%}H($#0jTA}-D!~T^zU=}whCb*>%2>IoyEyvI0?B>Sq^<7QVi4JWb zV1CbZR|pHcX=SpCP43uuskbobh>unhO8+o?uWeMf@xv$1`|P{xI@~i*oig~XsS_q_ z7`}bTZ72`7q5N?^=jydwLV+Idrg1ODx*^ek68>^4MU+va$CJf&L*=U#y*xB{d$wZOHJi5;OiGhGcoUtfWcksGw{g-* z)lZcdbwA%XrMar;OElEKkNEInzTw={SUsZf9J$fs{@-?=p{p2a`LtvK4aAix7LZ5L zE-`1j5gqP1rLb7gddR;%N;$q4$UVG9cMa`ocRvmddTs-5?yPjq{18615D!ja4Kn+sdlw@{%bKI%mA6UhK8iY4vMo+Qw2v;= z>!URr&s`t9&AWxPrfJk$Yj#qE*d>>}Utbvr-u0^M;O|#{!;}D|KS7e|^(yfeKP!0O z@D#X{U?n9O~xn{_&g&P%4!Gf4)>{ZAHJ3MX_xi|bj=D|7TYso z;OoCWOMiHC#jXd4d2nlif~zX-s42{@jwb6@wSf5*L0v80TLe|AGLd1_2Ky?dJ*!z?DvW_}m`9=;NsgWb|8hvNKX}{>GI0!jNKk`yrMe)Ie zj{mNLkl@`k^a*X<>iD4s^ZqyCV^wl&;V|EUh0q+zpVS0JI|iUM0;z<>T)OdW@}XV+ zfuDwabaNU1LCpmqMsj9?l@@zLKgKRJSj~jTq z>nd;*1<%kwzzj9Bddg!P(0M)SLv^qWSMC}ob?`S(-vNt?$ltsAi|?_tFB%x=T=_$) z_{&jVPmy#_rwmo64TR2Eq#7BN01W{kgk0c*28!`gG#48sr~et#lSZC03f{y(9q1fq zw|h#Iu%_p+N&pa!->7y6MlhX;QY?x!Pzm4XLB>(R3-IL*8ztIR^_PI6bWLJx65>2f z;yE!2;intR{#avGCBU&jU*qzv8e`d_DMCFH(Wsqu#_?KQR)&(LC+n9q7vCcQv#dUq z8SYH>S)=TK608GFiur+Z3+IX(P4pyr%||S(XahyKuax^B1y4hYR6|^k=(cpf8(zX0 zY5<(p15)y16*ysP65)^AyTmJa`VRb?^un!w-e=AtLI|W_lqJv{fO>Z9VFEd&P$S0- z#Mky@8r0K1lq7rm!x?p+Erjj(2bQcS)ArUJi8r_;43L|R6S}|>@df)>KnSA7Dx)=E zCkf}v7kzfYWRX59Y=wm7;N9j}B-xV`WW(zO7n0N7S_2Ib%!COhW%2fqHc0H@`RP{% zfD%U3O2&t2=F&nyopMq0YZ0cqu!qI0%DVBQ-Js5(kH_%87ch(g&4HA?!jmv@Tt6^3 zksA}gZ^AV*C{-sOqRDjNTs8*~+*45myEb{*2OZc~rFR(#nwfoS9RBXhf3+3z_@T%W z9Wd7fzl#BOYe!75%(tbZfP_qfb zn;RC?Az-0UA?e@Yexbwy>dsYXn#a=s&RT0%nbd+OHp()=0+1A1HN9s8dSraz3!D)u zpDvt6f)&yUgTcGCV4~sB0Q@$z0HhmrXfbJ)1#oIe`Q^R+*p|c7^O#Z(ozB}V5J%?k zy>S6zS{LcsG_w&iX-ibSZIyiW+g<+J^+q&Ngn>7PRN1m8DZ?Y#{gcH44xIsCH=8`& z?v*7bl=+a-B5~}Os9?;38K=E!%MkdJ&DO6wck*!apjxyf@6j)t&Z`LTi=0SuBD0#8 zLb7=e<(`wt0E&6V(vA&^(WKw&^^qhd1nJLyA$m>b>3Dk$b;xtf=0K znl-r94N(zx^)LLc^}a<@IYjR3(Qe+~_BbMBlm_L;5`X4W-7wPtIaR;g51o+~RGm3$ z#vGXOf2CcI(<4tQN%ktP%~ng_a^9 zGzHB~eb3i)Y0Qli%pGY^SP&mQq@Dp|xm0-EhLlDdD7Q5pWN;iZb#=_*@#twdPBsUH zb`2>gPYZPK`1d=9=btk5yO__ry3V^jp+)ibanVDHU($L}Jla1dL=qcaWWZ|)0OZ_e zZJCa0iDU@Pdw0S~Bb83fZMH4z-ko6M=)IN!yNo1|3`>f(n;=Fx@6w=-OQHje(lWxO zW^zFl21QDy{{;6;d9_Q4HF|kpWsWz;wTlbcociKSdO7aH%sRQ_wwNO|$=7RgCNt#{ zD3!};{y2I*Y9+{_7}NUhYug!m`eW|(L(Y+Is*Hcn7dM~RMZa23(C%~7K^Lk*b%~jm zwp>PugzWtY81_^ubR7#)W69t5l8w6@)^3jF<_XkPn;Q*luohvQMqb&%k{$e8Ud4!* zkynLQLVL1!9)2zixBmeU$M*+RZ-`RqB9M;T5a8f0_CIe@!*Ip$aiW}-r{^N}H_vX* z_yCiRFF(Y=pf4rRCozih1fP-;$>Xs)oF&@jasnU7<|ER@`Bo9bd3VgUlf6V@x5IKj zMpN}-?f;%S^MPJDY^TA*e;J9=;GB#_=IvG?tXs+|)_R*FRf{_ahu~*LSefUqpIt1N*)^jMbz?$08ixAr`f_ zAi`B;?t~zr&5qF+s zlB&FfP^m@w*s|bfrTILOR=qMC_COe}#b&1VHlKs&1fl(!24Y~j70)J5C-+ph1E7u! z`KA*mvFL$9hyQ_obUsy<{^%tB=TgSem!Yy6tQT=3@;%>Cc)@WGMeAd0|BXJJ3$M^& zI~gJ$yU1CR_&!{tEMwlvaKcVg&MgtN=Zmd+S0_LAQpv(vf;@K5ovd7pvRGYG@+8Tl z47`Iv4xULfQv;b2>$qFA>tI-I^C@LibtG zjbRkATjZunW*642PG{BL^MnA0wWIdQUU-7H%7QyeN6 z04;BgPyR@(f&KD|{oG-n>bKC0?x_V?S0uMvA zs(y?`y?c9i_ON}`SJc&_7+;2;xq@d|$?VoHW$B_tEB- zDWC34mE6A`n-(w0xr&=?d#@PclB{ROp=PlluQYv<)%?hXnD3?9D&JVfN-4_UCrH~k z`!q>nmY8XUUX@XDB0aC%j$1BRN6*eMvGCyAf64?z6lvM{>VjM}t}nARFyxC@UCx`Y z?c8!A5_(Qv>{Oe8IXx{s&*Rej*Z5%$y$)SG?lg$=se%pYQUw{x2kBB+H{i|yo z#O_n#J@?o?Zo5Wa_w$ltKE25C&)ZV$)%9@1v#f^7!B02=X2rH*BmU~ zYO!;;=CCPs73rP{Z1S>uh4f`9&6{0^(80NF@rK$gTXpLusW~z+px9pomC=7+!Ss3@`;igM|fSbt3V@EU72WN_84*5*_74H_Oi`wDMtQ^Lpn(PCze%mMRCrqyl_ z%mh6kBW=VVRQ7sv%Tz}1JTNBVz0m^k6gq_0`g8j?qm@28!3Lh**k>-PoAtuiLy4g$ zDbk&Y{cljD;iT<~#|W(9bpfp5+0P$)Dvclo(Mjmow z&P5l#0xXs|KyNJPCOH_3V)%Y_J>Fo@TJ+^Y*j*kEiYX$uV_N&BSH&>m+u@N#O+-nG z1IEjw_?8s9zc~_Fi4Z@eMBCoVeFxCrbY+cy&*!LLF-VM1Q>GwgF7!Hj5*pQeMEbCq zXNRi~7Bm|E^ss`+?nj}F0vrBG^5YYL`SWMDdqXsTbe3JI5*wTz7&!Q1x0x2Nj=Fw6 zx+6DgRwK&%#XSBoJz}dWdcwW+OHSO`kq}gRct&B_xBj+De_l)Y%$glAXJZ9C7XJII_|1u2W{3LYy!PRKsfvf z%&Z@1VBkVH02;>uHa-;MKR#ne0jBxw)*a3&y&&L^02MN5s|M6c6h`*`8Xmx9O(w=2 z3w*G{edW0vZ1gQaRD=8I^2|4J))3Yp8k`h>!}LN@5Pvw?K@plHUKIpDUqXRi;sIik zo4S*4NB9DwMBg*RS~4N2y*KRakY+Fmt=7|0BSKteUC|_j>x4vCg!HE<#eOf;{E&wk z`EQqu-3a@%7@qRu9fW{_N`Hjp@BxL=sW^Ss3?eO9y?PmJnvf)qGP z&OkJ-Y)tZAj-xvZ4)4di2tS+RYFb04)DWr zo17BIXAy2sO;R^9y*8lzV8Fn3#>wZzHeO1P zHpOXt#&bEwKsU`P|D3*33}N8F;tQ|vIOCWSI-r6tS}j4wWV`hMaOQ@dFP6Atflxkc!PTi2mU>=0q&_c(KK5 zp!C~D>Aqi(C-+QWlg#<4jB60rZ3EkKvGDOUw?7rn^C>|!Q%Q~{o{}KN3R4C5Z+Zzm z>K;fj^B|Ewfvg&Vl3LRuLsX()sAP260r#O5e@p0Iz!hSe6gJKko=_@=2hzT6Qhs@= z+}^~2Dpvn{4{K~fvu32<1j-R*DbttyR~c4O++88u@`4UHh4*Hn68O&UrKYHtEK$T#ss2i;9Jxnh9_yk>G@ z)DK=hmyAWEJ*&IV| z2A3b|tV!q+%qmPABXz~~ZG-iRauFanG$MgyaubgpiO@?|`g4jZyD$i!MLxUGjh!`Y z%G8!?WH%}{nsIielpIP&!MrIh=qRE6^R#b`v%0|@5Ou%kxajA?_=TxlIC zxj!Q2H^Js}lAKDL$+KPr>FJ2^$Crb_Yk_kpoCLN0(>a-jU?%f)m=C+N;1q&&szmeB z;z`~kwo5(Tb1UOUbCN&=GFS68T#&7IUvS!D>)Z@%ZfKtSaK^-jE!$?x7~ztu`KFkR z%ZZL_!uacj?e{sYLnn%V2!69os`?mKEP^V808zV1yBu?`B@t4x6K0pN_Nr1)qe$yY zSSx{#s&`lqFHebkn11yzpm`DjQv4Z`I&a}n`cDWwEdAfDnan3vFQu%s(jRQ}5_YIE zmVSd-B8Y>Fi5eYg$Ya5?G1O65m_-S***EYgkR}aH`oqzy9?nJ$gmEHFA4sbjzBuY) zCr?9CFCr#9_FPY^06y^bu3%?=CtF-F@Hpzq{Y$Q1MWc``oT;N&k`_gJuqFE*?w7gA z7IMFR?#QA}4&X;r12%OiOBpI%O!ZoPn#LKFfe2y;W?F=(^B&M+Q-Aw{ofO`2^1}VU zJO{^FhqYd6(R-HUAp#G`LS71<22!#XgT#9n)BC7x5Qw%-HqHtpDW|GvzK_(ypR91U zbvQzAi$*vaEEXO;k}sYbt*tinnSArw(#ZH{!b=)TbjK*TSb{l3Xb;Rhpvnb6_hFwxKE@X=iVZb3p?j&Ws zE#(9ToXH@r>0q}qIsiC26l`6Pk0u&NQ_v%*+mce_|3e9;3?WHw1>-)*#ywZ1V-`$l zZ%ggIPVJFR8wg7qx$f2UF%fc7TIR^yR8!vVQ>J8B;VoDBrxupH5C#NyUvcQ?T`$|NVMme7UZag zcPcNn7S{^-K(vA}T2T;f3`RQ*qI2Kk4soL7%nzhMJs7;o5XuZvddQ4gaQ*$l-zwB$ zj?VDsTs%&t)bJmt5#D`D`*$NsS7QJYGTK9(=0Lg=<1O&rq(3A)+zRlsnDq<*L&dOI z7e`Dj6qr*Z7G&(c=h@}U@h3s8)48l(RJcmDu%iDs*L=5b9LVTnSR>tHI*4)o0L1@PtnU2c%<+9|C zN8#4iWgVqDf2)icwV@sF8c3_!b*kth-lzU8$YQ8&_?z@8;%D1m%B;UN1J>{J7|lPv zGHLo-i&GW;a5q_#v0Qx_^5OiIxm5N)t2l3 zM116ltPGW^>n=B8xoLRY;V!V!cqw10!qo6Hr%WdD8s1qiF;~H-(5$2Ia*AG89VrquNn~qyXY13O))B8o`#*!%ZBs2BUboD%a-NT~T`-G|YnSzMRCfX6+Cl%Ev z*VTtpy6sa{?3ategE-=;-}W0T4rmni>)Q<2-VPWR4md^)dPeoRb`3th9q_+*C!z*) zyM|&E`$G%+K5Vjyd%uxfQO&-Udl4n~YIWpihftf==XYJBA8tn*6u*3m`qJL@rTg{^ zK`-I*-bh~DSWe$q9Qf;u;%Gh!`mYBTt2izf)rv-rA1e0k-QFK3E)~cBbWOzEP5_mL z?&*ogU6WEac(t3di#lIp`lh77(|l^vJa4|H#!f4NW+c|8pP^YUHM?2dQ{Wo0NN*sPH9D#T2A#3arZ`h+*7QOG9feMRUy^FYv zr;86kOW=-%{Me4^C`YDUAd8(U`rAY1e~u7Jr+XBSwWZ|m z75nq z;v^!yBRB7?qx{W~6=3rD8=VutWs42M0B`}&{@7v`j+x4H*<$)90$<iil#} zr9csyAeeW17#jt*^47OD?)G!aD5inLZgA3d#1}j?Lv{~g6r37Bihv=AaBgTqJ0LR# zhOj}dqnWtUqCpyxGGT~fb7Q>`StoSP=yWq`6dob ztBF8Z0%-un`0J}d6OQEc?1cY-GxzD+fh9y&tN_6nMoM-XH%Aey{q4xcZ4U@=AF)$jmi8kEmfWpCA>fH?-to4Cu%kd4s43_~074Cx^h{53}IEP$ATwkf*uu&g-x zA2zWZ7D0%3cMKL48XQ&E4Zki63S53h8w^3|ICdN3c3!6mzdbpsdmLP>m^gZ6*VyeZ&a7| zf|IA5G7+b@LHds=wd3#sQ~LNw=`>o%;QzzdeTBo-zWW1T##C)aiQaolj08c5-iaD5 z%IJcqAzEbgL81jg5Iwq)XwjktK^PLEglN$vT13tKz3=bZd;hO}u%Cl<&Cyy1Gi%Mv zbKm#(qi|&*$h9y*>eRLPxoPnIQpi=`QAt}XyCF&137U8%^>fnR>~dk*ilSugQ)CIm zB7P%E!{hDf?XScE15|AXC_%We_f7D2B@nfr5>p#jSQSkSrM_e-(t<1SGc{!QDhGtg zJ(bYRQIOjo**8}V4X%uxKOYsX8?aA?%Q^0mNj$Po z)mD17UwN%Ha8UQ{Cu!3B8>6>Lt@jCP-=_x@&On{rx7RK25o){Q5&oZUuC@7%D!{56 z#sHIrr$VMyb!3vSQz^02`lD4xU+%V2)-%p{1HMWt%#K~}Hcs6)zZ=%-`Olh>Vx*Ur zY#xGT6N!vp#L7|n*9Ci#D+iV#wVmge&<1N)a7ZR#Aigz;c{3Ls20IbjjUz)i<1EK4M&^ZIb3&sv=*WzEljaz{S8)S1nb)s&m%0w0ac^mJQQhbw zVY_VJVr@(&y&f2O1@e)Er-GAIv`v|)@;FTr94U@f~*`j^7_TTUXyx*~Zn zA?n(f^qPDqeIk(H#%TopfsUqLU}*@eTY&xJPCVF;@W?F0GTgG>)UA`9e9X<-6*bKgxZ3{2#DGNXtWSbmoN97M z>~X?V7o}J;xr8g5Hk97c5~i5ZDSuAd@3pPIu8^pCs@6LNr5A+3S3} zqzCmW21QqQr0(2H{>MIm1a-MP+`1PTilN&!&=6^4igx^>!b&9TG4|3+u$*`^*?>>K z`ha8s;#BXz*0i9bRCsG{)AB|A6lG07T*%~?kDT-eiv4`3Vu^2?jRs#Y9t6bdyoh}Y zrTKIody}=|``nUHZ8>JUpCW)}v)coB#Te_R8ZyWuw@il*u@Js)iqcJ{buM82(XY;P zJ(XmERN$>gk@gIMFc{b;QB(KK>*;b&n<7hNAjv)JeDQ-75_kbd!`KEIAK<#!zvE^j zE$Ivim9U5T!#Rh0$?oEOFl5HZ8r-Fd)oOSZ3Qh0mTzKP;Yfmhol!0o}#kblTnOLdSr zl=I~ozK_8-KQ`Evr0`F36mp$2G0x16BXK>Poj4VkLS_}g>>;1tPqg#nL@zTncY?0e zFLua2<)M;N?$@w_L|FGg3DzdlF_Ba9K6#B1AZsR^KY$@6X2O=Y z?5KJx!+uwJwX4_cBCl>^j&21aR`?Xy2Jf*SFifAX%IV4J>#+jCt}wuIH%XQd28;G@ zKX`?Fob_lyjt@uqsai_R>fM47>f-U5JuPi4A~TRqwKE|N_kER!!Ze;f-Kz?vJV-T^SC zfk^rF$fZg6;%=mhW|W$_cMJw1gN5yM-c?_Z(iimj-yQ=y_?RS?c)9-mCH}qmdwIOL zAYPpP>oJ@X&yR^`XT-B3;@RQ(`T5!9>(k%=pUQCX-zo#~_wS>lqu;-O6AurGzc+~o z3nvE~|E)6o-CMa-87_V;{fA^A{ujyccW0Ei`GL6hp1AV%KPto4*4F0c=KA{j+S=Oc z>gvkM%JTB^-r_&&`}gm}?~TOiN#g8F;@AJvW*`uV<4OP83?2)g|390dx0l$|MC@}W zwz(5Kw1}+=#3o5%{Z--{zW>ED3=Itp4h{|s41D76%3G4ZP@C*qF39+%UF)=aG(a{kR5m+qt$&)8x zVPT=6p~1nyj~+b=2ng`=^YiiX@$&K_y1EkWZWGNEhIEhzziM$*{b_OB~9g&`nNQ)#QDTw32EP4h{}> zc6NR+n2n8%m6er+g@u`!nURr^fq{XZp8m>}D|B>pw6wG|G&I!I)F>1Ri9}LSQBhD( z{2wI4e|rozz&{I41W4eln)v*#NI3P(@mlo%cnoTBH>u|S@fb7`|MeK&{Od8OUwRBq z|9A}9mmb6Fhh(e2)0zWsUyr_0j3i^zt}h!a(tIv#Jy>7<`L#ijcCL1V@Utg3E3QAr zuZB-nTfe_{=`ncxx5sd=$gy@jP^YP8t~Kyrb8e`q*0#j#?O)0D0Pn8u7#Q~*3XG3^ ze+(Bg@yzR*LmAZdDZK05+qKbrl>~OZmimp)WyX~@pIREWzTzE*^7L9SJ%$<$0@~o_ zu2Xm_5&Gv=o0m^V{~!LZI@9~VO3jE`ukN(B{N9>+>;8SDz4gzpg`NZ=hki%f$-(;P zO54l0u%I=M$3&aF7q@NB9_`Ie*uGGhTOE~=RCa2<;<^wH=Pz4`ppaT$h-|W!RQ57w z>Q#g=I+rc}$7A3K^X`LjX1FfJF<&PL|mV*C!4AaFFq`a!jX0~ouobNgq-CZ@2f@*z9c5D3CW4KTE zQq5G_AoZ#hb}2737}rJ4cqk+o&rq)zMPXAT`Ks_mu26cBp%U5MY~OuVm;ZPSPpz3> zg|aN<60@=6%li%tEX729QKv_HEl3mCXLPBm zvtuxp+h(yX7>K+%6T<>Humk+C!%3hEuQ7i_Q7b7zuZK> z|K50g_GjG@LdvsX^iwWEl}mB}>r#jY zIoT{dI+p!(H&&6N5Je1W2J)II0dAh@)liJE@o*0*s7~#NM?O*&!OM_|#@)~qPj=Bw zcCsL7DXlxBsHN1S$GRu$3FcR&Y!aeJ{kTpXHTz{x6Jkj1u5Xu=GP+WS2AKbH zC7BNLaMYl&B6@bfBVZ{tH?xoDE*Cke94EuBw;H!4e#pjoKZVht8%Fn0*V!IJ$>>@t z@mlMXo8>|Fl*!7CqO4Dz!3QtDeB+ny*Sg~o|2AjtAqYlby5suhAos_&Rmy$IMwywt zyyG+n!%R*h@^M=a1xQPkDH9L#?F4bXFB;*R>?GW9U4-y*l91~vj>TIZ7BYSkRI@;h zB?hN~M+DVW&F+)Zh=SPJKB-E|&cs_JccM-gl%Rrx6$8hnF5hg~@B}i3-c#73QBROq&KLYJz`PVkkxK{xYC&pi{1L z)vL5bDvfrvqhEPHtIXMD4Cip=qTSqOSK3~SjHFAw5v#kx%@Q=+&3uH%ec-*O+4b>B z;5h0R>M~WLV91^sbNN_Tv2P0060@X#j^ym;q418kV3f)l@({SW_;JQF?`;FVVb$G1 zXV#fGlF=Bx-Y-5mJu^F*(YWs+ayT#ib&2__Mj)@|HC@AGs&gLSAEfC_4fbTN-#Q^j z#!I&VjPM{;lxNj$A6pzy>91!7h94rl&UcC)!z z+>1E(lKJIQLRctwG-=}3>Zr=mW!dAdQLUef4^!eJ0v9<<*FXN4qKR@LEOWg4eC?5d zd+Tgnm3YQ3^!6YLIX|l^%_dGmSYl5NKy}e?;5DQexsn+cxY>#DdBtNE43R(3Mx(|o zHN^<*bXbId$1F#P^obx;jt9*%$S7~@K`5LfI2?Docbj4$-nRYd{VCg&1{>GM4EIQHeUXU_m@Ljs#xOQVefgRFYU}>CXGn-3 z{&xJEgKm#j=~>fe^(NyS0@8_&WVXy1k2ky637)<6O`Ykc&7k!QzsstCEotBs_zuco zWjY847S_WG^5At@lN$ruslBNULDpFv%%8Gu9+ln574lfuxPC|RD1|t^={seFw!ckq9tiLDJa2W}$E&RqG~I zy+hT@GWA^vl({47Ga3O3M~vpvwKKS+zkaBla&N!@^!rh$*NZ2-n(}9{D39kP7x)O# zsfcUG5$NU!CXA{~8ukEfpMjwyEg*yWL#tM_PY7hdf_C}={3`&EE>Oy4gxz~|Q_Ym_ z0ursSNhe{1$?xh>#z)~W_8Ds1RB5q`&;DHLW6V`m{l0o@MMJ-8JxNpaGK$ycc4yOg8q3gLi78hpO%T+5H;^x3ZO_7v1#UU zL>DZq&K#72y{~Ei{lj&oU8L;-Z7Uv8Y(TD)67JU+9`=GR5K6)PBHH9DuHIZeVO=~$ zlVQT&dSXpRx;aMRvZQv`X3YtOGoadBfR&ep@f^mA@Zww^(a|cp9mYm;2L?7|K4Ut- zLB;|N#_Tv6gFDJ%Ucp&~8ttzJpm;Gz3S9Vbp!!IrdX;97W}SNxQP(IS z-N_&&6G%9aN)e2E_6qb^Pukr!_WsrBr?B#Hf+k(WYZpFZd6H#js@zGCLTrMl1v<1Y z<+0TBN>@5=Zwk(@H#ra(@}}qVOzD|MDNi#J!ctN!mC|yY)1de1T1_b+ooW0V&y6fH z{QMJC9MT_$r{66|&+AKPy-!EB`!Emf?NE+WxStWsWas)$$}L9J!xk=d7t>^h76^w0X5P!nR47P}Wbl53NO>%jRjQRzg1Dj% z0s;#KBKNZe_65R0FYDiNMf(cIji-V7vb?nDq<4MpaAqe3rM|Yvd7+e*9}%Th$TvKl zW2nq$x|B2iF~=(PWgEinD*}ijAbSOJsAMAgnDU+w!*hC5H5!8Q*tofQBl6bX2~Tch zRUd~b){*R+JqwV@aTLlsjmr+&c=6+Y(5_a}J|bVa&Yh#|K~cGo$-7q++0x}Fbd_59 zW6}j!hJ1J(VA?F%a^KNdBZu;|z)LBQUi&%eU^w3(t$K1$%z7?yvfuj4lV>~ z7tmN1C~^U_C*+?q^0VILiwo!7a4X{1F5bIe46g%yz^5^978#%9D>0Y2gGvY~IX8n# z)Z&XYgHaKk?oPP;rTAU6l&Js?4#9RTFDb&y^0{Z~7S`;XBd0B8qY)eJvOhx`_ zW#MK;VmwNA_u&y!+0{$qb+B^SP3UC{T`pNwt#DT6uQs8gZgM6au?Oy($=Y#4iSAOC5g>9X z=PPH`472%6TXlzIZ=tvF0Gh;)NI(wYtDBi$XAvm$PiwD|7m2aFzze@+ajysafH&ha zdG4XUb|Pw$sm7DxK+hYc%2z5w_2N49Uk2+y;ec0up=E-PnG!fxi3DPYJi;O@E=v!) zFcI>4v#mF#BA#(>HJS-cRtd$j2AKEQxLXOhFNO$6IC2Dy%JmNSw6F6U!b$W>Cz8s5 z3`vSRsrGlt&<4S3txY$!8kU&>6MQk(%|>yvMwff21#dFa0{9P9)3eqJi75G*9{G7= zvL!Usa+e~u((aKCUgE4ZF9Z*&1Ko6|ux+VztgNbDcnj)6w9fKBJ!|2EyGu!cjVlkbA{6kj13auoq&-^LF1S}?LIAa}01tE0 z#2w!IyLIpH?7g3Koehvq@cA8RXy-b(QwR;aV+tla*F&&&Ez?Y)O0GJ5Tq)C`Zr4>ciKEAIz=vI-)^-1{L>2?~$_h zU7^rBIP6gn>E-Zf81jD)B)|XG`fjzd$xpOGAD=sfO$w@XTyL#%(=ElT+f6341Ds$Y zzI{}npPSg);BSRzM!~pP+I%MajYtqgZwXOFvS|b45&=P*+R?I0_0yZ&42^QyrP#}- zs#O%V<;k8`5r(8!mH;HUXW zLNw~F?hww*H8#UF!Bn)EKy?6+`!V)g4-I#U5Y}1%FMK`er<9RxI`(`@huuI@C0j}W zxTmPEyNg_pg`Hr9T`#={Lle?5vc`ofU!74E)?ONcVZ_{ki1jc{3#ngz?bV(8*hGvo$qm z0=!cPTY!e?06oL~gQu72F_a^qu}i>qAz2Mn2cE?v&#;uYxKJ1@)#)yBgi~?`g&?(q z5`j$8u3j_4abxQYi>>kbp>fMk4YFw1{>_#flx~ugjO)pEGV&-cfU?1Wo&lh&=!94= zkWFGm#q%k%lOeX9|t@5*q^IBE57T zvJEJ?qsz~H8|UyO)$`_a=|JKwr{wL`S78Kluro^HH5vLKnS|J~*!iXFt+f&K8gJ>Hc!Y9Ex<@Sl$C zoAvK@Q5-B@+nb{L8BzdvqG6rrC)06zGgOE28+(*-`!$KX&Lp2_?^AHXcmA;dHhPt6 z;`Qv-ub%a}?|Po9oG;2gzsaV2Z~JM?T0u%3OcM zwEx(P9SRPt<8QBPa%`ET98LU0L~zg<9v@}M{<+MR3m6S@`t>WY_DX1NfDHOX(eNbv z$w~C96PkA?eP2&d#FM1=hY@RtQibDUB5jmdX+=_Ml~;hd{=s|wE6=XNpIDxyJvqCb zau(KhR+)5cTXy_x^cZ+@Wa|UmMZ=&?HGQ_H1H|{-T^Xmtub#CdLu-h8c(E(b^k5t? zr`e>lxl!7|U$u+h&#!q+5EL$gy$;32u0XsmpaSIp$wF5)44`0F%`{k4j-h0`#%jL1 zs2YETL%nz}DMl^v(qm9%T(X5H|BuID-4VrPysDePtu=0yxd*+IMjdp-dwfu=U%(ef z|G3OygvIe9n^7*l-od1tUfiuJd&1eY#=1QW!eY8T6@RZ}lb2lF)iT;-n#}6#D1WvF zQZY<2QTz2_|VCsRUbQ&166Ssk~^#OQpW$7>Xdd8M<7n!khw15upBTOs&Qh%j;XkX=`uTK`g#U)6IV` z)Tn}OHGesia&|_%O;mvuRS8NGy{;?XpMx0ANG%o{l%U?Cel4YMw9t2P`q@zLY@2RN z<8YYwt-bR) zyXSM_OtN&JA?_y8HyfsfDcfmIym0i_8a)92mN2u9?Um$HKCnvTx4g%kQDQITW|ACs zD#SgB(RqCI<(eKT%@^z14*|nAhNtO9Dk3E)EAkJ~S`jx_y|0+Me0-cT$0+vOSJnM( zNz*({lYIF-o%cT;eQ}kS?H&tD{a8@oa938E@7|}LuQst9o>hyfhm=jW$KP_Pm(%&N z4pf&zhP?$*;p3V8_nC4S?9VZ2ad<7;UWW11oob22f=q9O~=sq=1Acj5}i&F zj)kw4X3mSE`)|y8jcFhsdc}H>sK$vnle{L43>4>sPWOyxeM#W6{cPK+5WKV#h7DId zs4?68Ry6vOJon*`7XqUX<86-D629K58`yj5BWCibTq@at%Hh;5vT*4&Gy7s~Wl3(( z@2_Hr?;L+Emi+xE>-cFY=nFZ)7jefh9PIC<#{iL51kn?)Fjh|JB$fm$MF>ZFtQvu{ixGd%6;7HDS}Sc(Y!6`i5q;Yc&N_ zewmTiPYq+QWsE&_QRSgS?kTrVc*l4}@c@l?HX{ZGq?~FpSOQAyyoao;es0)im=+%o6fW?>*uY#{(j_?Y&8WV+@UDvl4T2S3)13--AzWY?tIl1PaPS z`njIJeqZQnTY>J&Z{V^iuw-v92?&r_fZW=yqtrV;$p86p{Q4ih(JT~}%nxsLyel;3 zZAa#D=?LGHdB=@YPb{RCzptCNU&s1DqC|UNkU~Y)I6RS#zg%Mawy~Pt>peO*Stre~ z)yu6eiG)zabY>&>XuX)}v{L=KyZaSpMtnXJ&SL%_({Lo$M^DoHYAL@^YES~tTpL<-YW}UeWisHy!xv5;MA}ERQ|f)S%B{{Szk+ny_90b5SuaIQe>s{( z!3}+gQ?6OY2eKC8JO12{t68i$UYn=80#w}u^4xE-<_9Sm>GqU`lD!)d1F~svYAK&P z&7QD3`DSG8r6Fj1V<;^7>6>miY%2+iQ~nsBZ|r~Y;4V7k<|mucMuBPUpW>6xs}(dh zssvlOU~;nda1rYqCYmxe!D`=4=Z#CD+t0AGk>4%6WE`Y1kYG1Uv(0NfDpjh=gIJhI zS{Kv8vEt>xybb8qTAQdv&C8kKFPp0-{6g^M^wrsgY$tH*>FhNXO(01He%uLx?)gH8 zlfkynJ0^b&+|V)It#caK`Jfm> zEPr}sDLg=;yH6%&-+cD7LmIb5yMm_{37AX$89UREE?JF|6iEzAAPK`}VAu1aw$;*k zMy-ucdFjjNKhn1`m75i{IpNWk(e;I_e>gQn4$GXS7+RV+Ots>EXDtnPH}jAmn~Mhq zSgL=&Iy|6KUm$sr!6u?Qc3xE9sThAE0JRX-Fsjq9WzT(KC zI;~ZGRLEvcEhS1`S4MSHq4w&Mhu7?!!bYP~N4tqtlGI#-vlb$L3~5L>n;%*|uqJ+& z_kPoRR$xNqi?7{Yeh%)u`#~}MeZRGtsl)69xL^7X#ci+7zbxNqA8B&p24jjgQQO>2zV&Do`LS~%$_|X} zXT=NZCw7H*_!cnCwcKG4)dr#B!x$r}V6H6_eq{d3nvXXbYfs0fExn)#7o6N?eXOQf zucou~ZISR^g|dE-kz*12(t0nPsvBb6*2C7++^q!Ng+KUK#F{Ft$yn@@^nmdTm$SlI z=jR%~%&+ZZd_u~`psbtOn^cFHpJ}cp+*PBawailxB>*q}z(osI&!Qyq{(< z?UW`dvR)Ayxrgy!m za40)Pew zP8Dqr;)q-CnLIi!USVO{`unUSSI7hvCz8<5tjpd?wkU~$FZDfoaiyEheSo3wmWJo1)cZCxki*8N6C0cLONBX>l?r5AZ{JQ9%DZ|S%5vp0KhTeG63O| zz^N$0NYOZWCQSaaS#KaVvKjk?^Y#@v9R1;Yy@%?F>#7E6>VwP1dW3x$6lW2`T$R4bA&n=&?}2M8+y;I+T*hQ z-nCeryRG8qTL63>J)Z?4x!fDAzviVHM<%D?wo5|vsrbN!hZ%8#_{^gpC6fSXtm{Iw zC?Ue7GkWPIOph@_&Ah`IJn-UBJRncNn#03Axu%KS3ek5MVf(t3HW^|Ml|*$;F{3J4yz zWgp&tGBemHkz6D9vR3yco}#tL52T3z2ggTJYU+UKq#7R%RnrYbldE;-s7DWk(;H)3 zn|nG$hjVWzCy?uQMGYk`G*=Z3{Kv$~U^ zx{;hf4ND9y5bj|jG9KEJA4>T}S8v7g6LG{(6ZW=RiIDZ$U|?M5!$K8$jruHw)OvTU50o6x!h8`86 z83Uu-GhwDEQU!d>bGig6|Ib+wpXt*-pZ31t$J6NN(-tU$sO86h^b+EmBP}{(?_$$;+TFFt$5 z02XGv0E%t~w9yk!R44Rk>Ao1UO$rf=P_g2IA6b=43vTF&m)vn~x!v9@5IF_R(wW|t zf5&?lC%Ho~er$^BVOUSeqwa*sp>bTtuu>1)P}^M&w(bU*f$v#TfPrR=+*dEXuX-i8 z$C_^=UBe$^$kiU35j}l5j!6JHn!AwzOk>K_szf4*FKbG-a~^~>A2ilvn`{s<4RbY* zOb!pmnLo-kpBQdr8K0DIhDBkadVyWH_h0E4ap{08>4XakA+_21 z=<5bFC6S#|kyBH7lq7#ormOg75HxdRSFNi*%zSR=?D)V;LUZ}ax2Dpbo08`&F0lq? zX40mj%RRml2OF$d&q^@NrIGn&ArOFT;A`SJ5D`XZEhm=%JcLqie*kJ@8*uocZ|3M()UaQN$f@ zwmZAuiNC+U{bZBz77?R{i}lA9*0-5Ghz-IWuHuZ-sfff#J?~LTjO1;_n4qCDRGch|p zoTDq9Moq<9V5506AYSVlSqopS(id8E6KHmaZKcCIcB^Cv>Qt*s@*FrB|gr zZHyuvpQFcW&Yr$U4d!N>E?SJy7D6^s%y!$i;|WwZBX2aNlQeV+rur<(vU$VBv>~Ap9>QPYw?&0$ zPSAPm6cj_V#XbUarmX;rFnK?*b z7HuKD)oVJNqPg_>_D=JN$E!5=SUgbEx)p;1WTkb`bN89&ou02d5u=(xL5vT^JHDl0 zmKWJQC&ISJJRZadl7Qu)gQoD2g`t&zZSgA`0ht?-yAc7$4;G;F={B}GrOUf{#s$(O zqoOfx&NxJKN?)3%>#Fm6XZR%zaE%d5vL4~48NIXW8Ti|iCc&lS@A}b?IPT^}3|ctW zn?)9GTHev%C1gsI3<+zF4Vj8HN6DqzY+q0bzGU2{`sKY$?VWzKJt#21nt+CV*==Yzb$Fc6}I(mD?Ou4Xi@<~4NRZH?cR)^EX9MVkw zl2y3&QW{nT1{4)zufY!Xj(n3bk&juRhXFVM;1WV%Rb39$Y=5gOxM{EbLSdtV*TD+A zq(+%A&4oj12Cr|&FAgQl!zgDdO;7q)ncT9jQ%w>Qy z$JOHxzwcyB9Ic{a)y718vcWAdrKv^$6j^EifW-RJpjamX6r=U9N3Nrl>X2RiKbz^U z5$>Wf%8zjKv#p(raz#bM+(0JXfA#$p^9ud zE#e18@d=WPYGDsff*um9rY(5&vzEW? zT)Xjh4tp#kiIz9SvNMXs|Lmi_!OCtV(e08w$%iTs0*3z_y@MSl!Lf?Rd3IClNmx%& zr9bb)FHUGeDRkgwQEHEq)huJS>5A0;$N^)g|Jl)j7aPlvCCizB1$*5H)V zFW8dP){ti%o^bC=9qj3==&2a(fdl66Va+hy6Rx%s5)7)7!wdG0$FRGo#7y*5{MTcM zK~BmI{Nph^V^c~M-7qNr7^#Q-twWDf)CTldb%nfB9fotbd^Wd(s7prkk!sq-DJfXZhG(s_ai29w86mNwNJ`0S& zo3PI86)SNKs`vuAHDYj;&hgqp4~~OQKD*u?r8Bd?C|owRI5qT-$FO~J!?oI>TFX+p zJbNatfPtB6j``62setnDEe2tgI|$EJ&Tz)rgI^8`LwT~0= zvU{X@JZQNl2V$ai@CjcgCovQDPI1WucKi;r9+D zTNChMl`N%2jr%b1UwRBJWhM@LZ;{0*KS>k$pqL4VKy2dc`$0L%3tA7_b5L|-zL!9s z{g~dn%TBkuAJ+?>4$6vDH(Zm*;8?bbfHJ?pJ;(9>ObfVD`r9YiqS7Mnk#fofMXI6! z#6Vnwj*%~6qQT6`eWEg<&rPIxG2VUIyk(`%fV~A+fJwcmSY59B^Wh~&zFx7$Q(8kN z@qQLs^INsifP)}DE`s^yR@3r79>aAq6a4}hi4qc!Gtk{`%^EDJs|banaMv#$GF~C` z87@#Es?Tbd_?n24PgEBoZpz*GB>6-#Ln=!&O-l;!FidP+U~1hXu+cs?fY$%^b2I_# zDm@4xvhS>ZdG(H!ZdisAjrF@edoDR;wnNNmrq3mu~{pw{BxcI*Hm@p?BQix<_mHKxjkb_M$+n?lPgigbROT)_6Hp-TDoZ?NI1E?Me&1LZD;C$~=}U5+3kBg6Qg4EJL^ zC5RVLK45cP)3T(8)d!sS_+pizN$E$isEby@O5%$S$aRA0WI?~s_82LEj-cOPHvhJ1 z7Qrp#;AJ+}$+C(8H+@Oe=5w4tSo`0~P41H@)55@+1$&r+bvVZbHRbp-qy4P#u1v!i zDs!W!q1MsC5_MWuAY2!L8qNRp<48b@!)<1xy7-&SvQYxJ zShQsYsVM)VeEJOH$Ftb^x;Ya)poH=@r>HLLm#23Xons^g8rNgp%~#0Z3ic~(dncQm z7o`yK(Q2Kp4Rpc@sZ*AuEQw>t4LeAbpLB#)%_^*N=kqH(le}peUnXz7yYeZ$+S|kF zI&C&)YVd)t@eKziEbmGeGVIGT4f|q=k`Xm|lBTbxJy?%qcMaj1Tld6GG)~Abbu@GP z245NP$0A;ckhX;zSMsrjk-1{L$K^~|E@PKcbAH03=4E;_%m8v}FEM(7gypC#hDo$= z&@;8ZSo!`Pa2g?+G1oX{BUD57jbS`J{J_ude9=ubUjpg;;d%byn#4W&FE1#sxKBLQ zstK5=w1v2vLl+}%mZhZewSg#aGe$~T*`bhl(ksda5h5d8FJP*X^emD%BE#VxoZAY- zp;I=XsVDsPT`F%4m68B(m<;8gT4W|*6jcNj`MJ+Y;Yevwd)msW57!&(5+85di(l$y zij8kF+C7~3bS#E_8{a0)VH6S#ai4~#xhsPTW`ZYy$cq%WYcF}ljx z3)PX6Np8Jq|5ZsY|Cu;v30GjV25Bh$ZT|BfQRrB&FyLbf)Z5d;g4Bf;Dim9Mn_Btm z+*Nj4lG)EmlPSuhcvymPlK7_fpO3{tmqosxj5l>0wTp!vRDQoqvU~p+6X$w1^j-G6 zgbH*U9YI^Q0J+iJMHTjoD}aR-mm6(Qe+wr(Z)z38smumF>68^FQiqd2Tw?wR>11r7 z25qpbvUc9U@s$CiaEcB3~F~^l5d!hVg)c)EGRQr**zl%^8KLGH-OXg zHN{sq+hx=x-n^@H1p)zb^W#_^JcbnMQAmE1QAMI&DV(T@G!9BL)ukRkNH8Q(baHKT zdA;Z=?az}q_vU$#zC^#wsCX|GkpSx;b|D`FN2DVI(b<%~@P~8~paTLaFdy#qczbz1 z2EZmDX&jVdv4oHF+6ZOwis`h4rOjJMYTcM^6RQRKjn4j?x&?fmvky~$md*{8jDux< z7cN7mGxQbM{Aho&M$4OVwKeUB^PwIi#>_w5Q`x1k!C<(aqG4YF0uXeZ1y_3kmdij5 zZ?g9?O-B#Bk^f0OvmMP>fI1uQuA$XR`Z?=&KSEq8?q#H-`)AolXT>nV#Z3I@@E{oTNcPETHks6`!f~1!0aOnS!|rw~`XQ%QDCSQT#`Gyhkno&@>;qJn$Rt^f0nyWv{>;_tOcfnVz4|GiDithtPD(H- zAPu)d2E7C|LXM}Q)bs`VoSfug1q|0yXfwdlakMg7v{&5h)X|DOxe2V}WXOmpWEc`< z3HcVcn0Ls^e33+U#Klo+Yf$_}yIP%Hn`77MGuxmx&l}^WIXc>i4;(SdB+x?r`VrP` z><*JXOTz+l%tv15Jl;#rK#jZGyTEjNQLxa?j4nI}XIrrjCeaN4jTt4zEwQ8&o@Nz_ zyjd!|h@_$6amnFU?_3faTr#C2**pYo`4rySCSM@riS<#V8|@3YmQ|7!d4hPVD0tRI zImLt2sNj*`5Fzixop&J&OmhZz_sW9|9<+fl16 zmgQK-Ade3&TWofXkB$3_d6<@kvZ@{xpLJhv3@<75;^&1jMO=QoDRh;q!VZ0%PknHa zL&6BQ&1a$RY;w+LcAe;~g;#n2R&Gh}1&L}spBfR5nYo{6>9$E*e)(pYUa}V|SaatW zhd)$YOYeJ@s7Wi?P=MT9#&mo8oo(!yr4}9bf4GlhAW=LICY^mx!JgOneaIkJXP~-K z{F=wnIAHZ*imK#sIt^0nU^M+VD68L|%uD@!pC?ttJZ=ysnzzJjS-chg zLr4k&A`Mc~ARr*^P|{K&h#(*!-JSEzd*1KFI_vxkd+lehXW#3(uO9_lM1g~<$A)>V zHL*l8XY>Yj(#B~@wRm zcO6%Bod#}ILHQ?(2+9Z&`$#sm;Wchs{>EEOUX4n*^dN$rx9c-kMP(-Lr*fxeV>Pn8 z1a7xYRf+ZRE~hUHmF@;SqGW*Vb+>}aW;?T1lhkaJ%4(}z1m5CE08yoC_IiWZW;~a3 z62&sRgh7OwK-1p}0%PYIW@pt>+qWBz6iT>6O=O8J{QbEO!KrLE)sE{MKa|sP2A`D= zp2COzIJ+mS!H>hmw6;{laB=i>srK0>q{^pS<_b>*_{C82G6FqhE-chl%*=vaf49|3 z9h8fXlA$Py-l7dEo zMXAEZaz~DD2zK?b-@Afl=R3n;_CO-WytKLsS>xo|<1!H`G-V^`ak$efIl-kTwA%P; zm4+=^XeVKoyYrTJF1e!L$AQ`hU_*v)Rtp^_?)1f0t4km)N~^qZPzyy#--z}O6NE-n zt7#a}k`e~rPpU)p1c3V8da*s#6x2`Z-PxAqk+9t-pOz3SAD zsy5XY&b!a}P~XEo{`s-{OOEd{_c?X&hBEr`l}_bMFz$8gdZ&<}*#5d**9WuAkGPZ7 z7^Px1eXs($TRa6>nYkOkgk&GF13ldXJ$yEFSL8xTjhrO!z{9q|!GaZ2D)_J=FAfsYSFZ$VYE zBz0G@2VyvTAAeNm3B|wq9$J<+{6~n7WOSc#+Fex*4Yfydm3A{bxN|PKo(hEyWcCKcQLh&IkwjjOpwk}+Oound2uKn%`1M%6LnvRoC%9Q=< z`IA7psuB(wG6U|)IAT@yyx>A4!Gx@uteFBu^$+UBFY2vuP8e)=cmul?i&TXo>a_y0 zNpHalxRcsWo;rDyepa1Gv}u%>SN7lSNLcuAFkYEPC=;aN$uo)A!KyC*Y$Xg>9^zq$ zIWlZbp}kgBZViL5L|DcXTG1P)&C{fvG(5NcNu`nqjTn zn3j}klV<$l2D29#dq_fxHp8g$A^toml*lNUG{c&ccX0hbO#3U+Iel()T9{_4Q4^l& zbXuSd9S9AbYJ9OL<$BiWit!0hpP9pPt5ZjaOHeRJoC^2h8ezhXzRX$+s98jzEgqdZ z-ZXeCr@nLP7t2QYup5sAPk=4Ye8p+}(mp@Sk@o*&Z1d6AE{NVv*rBc#Ehj<2#&hP; z*MO|_(tWG0Cw#2eUCRMRkgxQnbm83^5T71T-hU#oR&dhK%s{@cYVgN5I9%XY3CScABUi6CuHau$EABmZDZE0Fkk=dO!;gU#JNUx8NlM?ypjM{T`r)f%|h~)n9 zyqWhROvU4;if6>MNeZT0YTxwTo&9%rTv9a;Q)lb(zp01mf=XV=J_aWyO4YyZlkp`* zQ~$9(X_Pg?yvR;#<`i-frSp3Pmx74k#yzop@7j=|ENdPg%HE91-#UDhSnK%XK3R{s zS_mG-xuhu0@4mR~m#*_hk2FxC3j0Vn%(umm-TwoW^X60~KT`c=xZl=}tbE<&!tF)H zC^bouDtl=7lV6urN72Ub8$SE}72UUa5+ONN7g;X-vies^t^BSTXBhiqm3;ZDeAR#g z0^z9?48p(0;R)RXvs8HP)9S>JcNCwWW>G=~Bq)@!E1MV2OEgO8r>@pDu6)8o%jC+SXfULm;T z>9qktU`tw^Q;!s1cQ3Ahwn}VUP25Ub>x<=rKz>r-MABfTsjcLB;PBffr!ftYnU9Yk zh?6F9$sesB`VLMJ*SUWKX8Hl_+oAluX?$6{`r*x^6*R#7(qudC@Lv04Xxo%8^oOqq zKPd{pfcdrqXU=-A9Ip=|@ox%Vnv|mXbnlM3?)?h6KNr`|Op210Fi>zt{(c^`de}Y? zj?w7j?v@Ma#a==vMLsny-v}nR|9X!dz{|5ZgtF&!O=~E9^~Ea{ZuT@m{k)LCQ6Qz} z0Y=lV!@r0faoi4#j!{RevP-JIuIpI&B(%EM@!T0AvKV@QwC4_*_t)Fz7HHE^YH-ga z3~xJtT{i821vB%x-8j8HrTnst`^9=($ih(vqqXw+P$HfFxpE-bFfin_uyt3rcR>@C z-ntAqkVOD6nM6xuH~~4Ap~*frbxMr&7$CJv-7&PH8kOl-k0FxG;ks}s$z~v#_4buW zbF!^&GIQq5+ZcP4ZkDwB-|x+DpO5D97+p%x9Y&5N--);Lnt(ngD^lTZ%Ai!o0AEYA zWi5IgrbUcDmw^$|N2fo?S*-keLF=%98AC*g1#ih8Iyhv z;`J=o>eqTHY~7l$rBWcEYk0;CXt=yub4By z1nR~!rLN)k1buzY25sY2F0so<#0Eb%W40uo!D-F+=H^@2L|zMc9u@DfMiXSUJKE8t zGPl#}D`liBy?*p1Hz*+NPkio=oYvi#XE!sDZF7&_Y+3$}g8QFtCfLRVz}=UEyh3gH zkxiTy$nGf7dUtg=bOxyo;WU$7W7QTq=!()fMXJJukNqN|b@v~uu%6EmWB4OoZNf^z z=-h`NXf|6OYj=#ojtAZb`?DgHLGCJ`1lfdrp8l%b9=^e%VhJ5&zQULtiA6L&P?ESpIp>LXwF`9cr3koA+GDPxJ#*J40S_qiGE4o8raxQ89DCr8|OSnNKAnIFqha zCz`AD85u8;Tk_afuAs_^exV!^4zVDESCl}L1cclh_tG*)hpj2^ty7mkf5u&0ioT>! zfqac`dDkmt1U@z`nsH{Kq{b%Ez^eAxFiit5%HopnRh|tcAGRZp3r=X7TRqSFB&Ts? zV=(u)^zT=FLJtt59=_?btf14*ulV7IO`3$E`{VcW)W<}l!(iv67{X~Q^R7a{ho*Ql zi{Uo{J|)(ITa6r2m!f|oo{I|-#{6{r)cEYT)M=G<17pX=uUF%>DsT@xB2cEOKnuWN z)U@73?IZ-(dhMrBIBfy!ORj%w{Hr!o1aeH;$YG7RXX?O6jh#~K2p$rPbn+xHa5G(l z_eGdo+7a-_4h;=? zL06>y4zJl3iv$(6mF5oml%3>CN(38BtEa+h7uko*u|-r|kBEM9jhnNzb51^HlP`g$ z+6Tqh8@r1}Jb&4Vf@=(y5u)%{YNbj1Xn0FULbGGUSqE4NFnMtSHWQo|Yx(bqFS2<0 zQjY3%;KlC|BpxQ*XP&;ax3u?s(OE|5IRRj(z9kNhwlxu48`^m6abnrEsK~^^*PO%69ACE>L zUBs-t{v#EtYFGYzBJh}v0TqzgNxx?wCDZ~>G(;!Tf;&~EcCASFIj}ugqFH+72VrbN zNijnCdAb5JX;d03xc%!kN8hf;)xx#Yn`vCrjY|=}=Oqe<#2HD=yvL z@kin#^eF3GIN^OUK)E7%+x1xyNk0?IorZA`Pzubfm((R<%Y5 zjE=R9f()sx?~!YKKk>>JEV9qm?=)4b(&;IsZs5~4p3MAE{88C+48%X`s1+9`T0N8L zv{_R=n#1;*c;4QEq>I6%cGrlQ zaH{Qz$#L(@LJ}m|BI6xRMM|0*RJ_59;uL25ah0v*iJ5+@>vrLikwN`7jBeyRuKAj# z(djzH92~)=is#=U3$2wAXRNYcAaMm3J`pz4RQAy$}{@i&rUU<qs0 zs`m%~3Eq+3km#e#se8NYqc&lrheWfOaT8vNM{*bXXI*DCC8=z2Rd*b6a9XB%BM-~D z4G5ipvCr`02HUp=VOK9NCu2C!_4b7m8ma-m>PEI};+b~EzW6gx4oEo18$46BzAzAt z?}j(HteN@-bS(T3s_o6$8|(0AUR}rM|1G)rJm4441esVhZSo&?C5DeAB~@*LS&mL@ zPZp@5j+#UNKlQ6Mx_C~F^B)s;k&A%`xgPI6X0HnRHV^(Yac|51E2-=k!)|$$(iiww zP&zEcE6+0@nzN=VeL4Qv!mCJ_X+!7v<)rtnSLyxvRfUDUWTSZ3IM<*&Yfg{?*^)RN z^D|Og>8qdPxjqdab9P)XzE{7Nc2AXnW|;fu)}LF8EJ|}ZdqHPc3m}%4ozUF`7V*qVRb#&0Dt`8>%RI(!g}W!H5bUjQ9gBbQ82hNyTgHMJ?_y!A;^|ZD zA17iNzP!R+(>8cpaX#ppQG@{L#ov&PU2Klrc&J~l?14OcKzM)Vc;dL>c65fi00G;0 z@nSQD+ZY;(`~J--rr^yjd>>bF821VGI~&K1W0_wXc@4nFOA!T1uyeJV-w`{%^=k+S zhE7YLFM7FgrxwtemG=SwF5?IMD1A_tFhM^4B^xWlA6BMkNXWVxPLLb1q$=@a{T8m* zkDrOmNT45-W22X&girNIs|YTgLDV*k@%oSs7)X8exEBdk0k+=19QO1 z+-g^W5s)9i*b{IG|KQy&5&Nu=9l23VJ%e6-By?w^daWHO1CJniKt2g0nud+uhC);l za47x|+;*yO>*MhrP-lFle)NaffsflGk0phbKxK`L$h}xalstr-iWU~h_fL&FO*SjB zEjdlb14WDgIY|4NR<#ja zp>FIB6GC#ycXU;*zsGS%|B&=+6A#HW$ea_o<(RdHK&mBB)_+~wBM0Xw+C1Fk(}(IbX+;ywT7dz zk{xj1qp5QA5&x|wF2PhK{cc>Y_LHLQGnv*&b_&bd=sh+ZgjD)QgMyaa2qkxnCmrYE z&CH}Cp&{Gi!z7bGIII9W5h^a-X1@Qe@*5o$ZPH;JDq(_pgyivPSD2)5EGKZphM}=E zU0JM39FVQ3QsAbND>+iB@Km*ukQe{Xp+GfZ+$APT$%cSO{6X|iXsh$5s9%Y*aSCe0 zA1gLY&NWdY@2W5etBA}Gbs7_E1;ndVNU)SmioQM83OzzlPjblYFmXP^ON}6Ux%1)0 zL!q*i@rdKx?+v~zfMd=-)YBDJYJ=Ku<_1Z9Oqe>6*npN5p0l#8Qpz4 zWmF}pzu^5O=+hIZk1*vAb5S-m;y-|p9a-_B9=WHbx}>G3l(Aopwd{#C-YHu)wdvWE za^fPuoM3BpB7hMmTJpBGlCpDohpGIoO~?j#S!#3q&=78Xelzj>mx%qer#*S2eb5^f zK}5izH%{^D1N~Eu_dlNbr8T`#wwG*l)HVqN$&3gki4h|R81Y2C;09_^9wCj<&u5}{>LMSh z$V7L`B&y1$tHQIvaz)ng$~^jQE5@dQsFr24 z`6!Zh+BPT*$%xH+s;Thwr~rVfM1-mWE}*i=Xo4g>MloOG1Nv&}CK1$%Q$F1n5x&pOE&UJ@H+W)dxUx)2QhMlWI(MCoZi|gPT1~INM{i7xd=_~hfK%F# z0+E{V#fWI;izgxC79>bQy-ubUVU+L8Ya9gLIW-w30ev3?2TL`@FQuoaK4lQ&Z^HyU15;W?wn8Kxnfub@=yJ=5y+Bw@xa26+#_yVAB@vUktar%Qe%S z6I4^khG5yYgc~Ahw&}Gt;YQ1gglcfG+2sdwIfC@n2S~pZYm<~WFCE`CvD@d_+~dkJ zinPV;vbEH(v&RRpEh7Av1$&%N5ifESFD2x4@NYYb@l`1Emdex;Dy?|ss4t-pI! z|3JRMD4^kS>mHSBiENm+8TOYw%E$RR+)dN>rKY^)Pd1VKR9AW+Rx^zyO8{wFq&-_i z80OYEd$>8fE|W*5kcV5^+ESI(BEHxx{-(O2^{?f})+f8IodK-@FWOx0wT;|awSzY5 zb_L~vf`RDZZGw>Fs1S`sMnfdwp(QifPhvRD33vDMRzn65}4iI zCEo>UW^={FlB1WH`DC3c&LW;Le)XK~e9jo=H21YL9iD#X7IGc$ZrYy}$f+)a^QNu8 z+vPQXP2Ye?9<|Q^z4)N@gPyYM)5@?GT-Okp4|ZOU2?~uXdyOwE z1TiU&ZShWg$({gDOyo3<)8CB$JniMoc17k;sJHux&X3;Bi4JERBrE)5BHmq7{vk1POaxd!%5wo$4sA0>`qOXCzwxF|-=F{X(A-`F z!J)GIt5b2VH)w9)e|rq`ONzf&gMM$c|K7RzePI4ul`Zx&&d=V|@8UO8)J%)D#G}91 zITFN{sDqd2JC>Mkmspkla0dV3?f4^j`$tr1Su%K8wqsfGb{T20^hz_PjGX0Rd&3SR@hFq$J^)A4sX=dX*>+BDOecgNcE-@k&C)(3LdUggefqVPNT-o{?6 z*qZ&yQd+&M6w|FcsvSP_Hf-}^V)LWLmTEVCc_uzuX}dRgd!S=`JciVLl_5!{$ zf4j5vdj~V!v9sKJU!Mn|iEI4FMHO$=1 zPvPA2T+J3dY#~Bz@D<6BBiS!UikKs$^09izvG&3rFj1S(LJS{<+xYzn_fzN-WpR^5 zmK5N?<^8s10^~)=S+~-e-}|#5%$ck5`74%#m@nsqnDZo-ea{8_raa5wI2=9@W0d-3 znX*acf@K|xWg~__o&98i{Zutj0{v91_k9!l+VzK^8>f?#Ck59JHE!-?T(4r_i!6y- z3-I0dH@r-@dl(D|yLu1c5;G`7i{y8`BB6|g&4?8A#E`R)6=6LFwKxWOe}(>o!u})< zjBchvjM#_4cLGmZ0tv;7hcmc%4GR!Qg?F=M6?eBcj=07Wl%wnf98=gPiYU^=f`}x` zzn2+Sn6}4CR{W?kYxTb&lB%4kwHeA(jFYOGZE*h867=g`C#UO4(_IDxOrzWb+k3!k zANxenyDpN^8M(_66J}L3{|i65%&f)d0B3AyTG+BPf|M3lZNx&(0Iy2oll1O`i2?7u zzw^J&ggepU#I!2~TRE*y9_hTlC+PRWX(-*Ag;9U&eNLE^-MH@OGLUs&V)#R!Ao@nT z@cws{Z4-`W?N0F|Qo)S$)t4vRzgk1y7*Di_OYisaD=$747gEs+-9qTIJ)KK@CGZC$ zVyQ1s&!Yi@9yzPvvR|eor34=TjCvn@eL(;Ra478IVStRmH)bW1Bzz=mc6Tg=|Jd8; z2Q)u?S%8b3>4gvwnaN@(@DfeNr^2%|C<_H@p2Z1&tTu}fEXkySIvhI!#M{`Lic!0bBmjm993qBXooOP(B- zLMWx-rvuB6WGm+>Oi&?0(_qFBFiOldfT;M019K_~`$5E4UAUDIZsi)@&53eu50^gHRpgd5^%$l3jpBGMY!>A z2a!x}6C<@c>DH=rsZx{L$Vl|V{Eq8OVv&zvTIaD&LNInQFW5{qfgg>Nrz3zDa{wh) zU2S#!g26X~b>g#MZxU=7Qgq_wn6aA=@_!a6>=k=1AOc8%QJs=b0J@lSlB%a$`7r?0 z_E6C>iGP)F)zhE6|H%)=Ukyup!{YtPUJAKvF)ZdQF^zS?eBxCi4nw|uBU z+iZEnCsa&T)T69M;;pdR`Ds^f8`FOew$sSn-XnFj9Uf1L>oD4W_BBhW<8W0PisBur zb09hv-C?1^u|P&XQrKS-_57B;>q(UC1+%uDU}T_;yg^CU`g#> zeHgsG+j1X3Aqw5b<1DGzfqr`piSi`4vllxf2p$t+1_Oj=2wtsgChi77c>=DV(e;^p z6)$#=cL^+{6b49*-13R5Ycvkvgn;&DZCvUxJ6y8ttAukm7#EZWh$7Gn^P+E5%WPOg z>HF^vCa3CW!GYAg1Z^sg@RxJ&_srw*<%n>JLOueHro*t1Kr4Rcv9EM5-Bl}W3g|8J z-!&0=Q%jMe8OyN}*>*lbdEyA%>^$naK0VQ0paA|haf;!Q%-skzOJ+>wSEb|pH$my+ z6eg`pv#$&82VcHT1U?ia@h^o{uQBED_2{HANS9a|h_e89qXem;{~(lt3W!2PfgoaI zFN3K7)>rFFx^fSEi|Z+`5v5ot18M;v91TC2sy3ujCF7urFt`YW-{!+SBFW_SeFNmg zkK(EWLdwV4I=ILALPq^z{L1Hj6paN$_W&UKaWg)*SrVCp2qC{n>&%x4hY#3bCo!JY zmf_#WiK6?_R8+B_LV@lv{IwJrt6y@KW`MaJ`*}I(?`Qm zmn8eW96;mr(Nr*L;s9J8nQy;QsMWqU+Cgd&0~+bwVx)U094`&?l z+zOgZ{m`djUVrEx zAFOgxlA!RU=>TYIi6{%4*a3Fhg?EAAMn9m{W2_)wMia;gxeL&b;V_-k5%6F8B+5;U zi_U4ic@RkI`~s2%?~#(KBP?*XlfN^oCHG2x21Kl%^_6+0>2E^_)3z1u)y#l}&!_k1 zFfo~Brk%0gc}U%^k2v11gTJS3Uj*&Ff1+rP^)NJ&8Gp~Fe*U~{2a_^lo4}mo z_i*l}(vn!MaIpB*HRQ*p8LU=VF*zA)iIN@I^^)1Ctte}MZ+N*ynqZoTYc+K}ud4^EhJE(x~KcUpeA18=B zC?Y7!I%0jA`Mvn7KIO2YN~(wpyqua$HUsxs7cff6I&07HqY^-bI|l@8MX)E2SbOEs z`scVFz2A+NRFpUl!WAp2_=9|o3>8p#0@vN-CW$N@b4mDIJq0ljK<(?=u3)n_%S5mG zWENfDT+LlE!5A@7Ms%QrfEhvl_RpurJWr`547-`9^~H@K76;`r0uy*|=VZ5&;)2v| zFB9+elKQjY&&P#auLys+7=3el{Ex@r`sHc?ia8$&xjp{)oL%mhTiE9Wjd!qt%kDlgt2Rd zwLBtx_z)(FrsV7o6I>4yHWB8Ago|s1OWKD&v;vY4wBJz#c&xgoHN+v7ye}1S=7x5m~kbXeG0`$pz(O}%-FaWAfL93hiOZ=$PWB*8%F9sbX(%ACL{MyrGRrqSp>i zuOSOr#J1!?p4CTY!f^dW$S@)}Kq8(e9d3wQ6hSS)Aqr0jMHx)@hC=%dfPx&4L6B(N z$VCVPZ;GmR%DDs(k0L!!Bx|g>3+#ut=0PxvYAklTq+cT=5?6_K_n~^{iP9VLlo`

0*a(*sQ(ZPvT^)ks(0J~LWX5=DzA{` zW@qVoZQ);8V`pb)ckA!Q#s-$pSY2Jk+8KL){`_lato{CdJ<~ToKR-7&_v;rnH$VIH z=g*m$nd#~2A3uIfO-+6O{(W+Ca$;iQVto8^yaOv@T#SufjE!E5jvkMWUW|=gj1F9U z8@?DGz8n}h9~e0PHncx7ay&G2(bsp}-+$cKx8L7?G17JNwfDTU>!PFMtfS*%sQF@` z`tobhWl#E5Pvq4X|I@a%^Tx*WPt{j#p4ZLR*NuiZ4O%y~@?&FT-@bht9v=Q*?ndXA zFYWE^SahSQsj0CMJM8=i-N14iw-o}nWt6ui#J9!xw;#Y*Xyd%1;;O>tri%Z%jDDgb z@n3P{GA9RCnd8Hor)rx|Ez8Tx z|Ft>(OXc{N;mFL)OifLF_wHSCa&kgKLUeTWzxqaac=-RRZ+Lrqdw6)bxw*Z>3LLJk z&d$yb4i5iQ+%PvcfAZwX(W6I~4^@x#?w;#N9jd5aDDz!Q3$01Z-UzY(6&5|>X1`^j zIbdgBVTRu@(5)~q-qOHsDWJEcL;?Ex|56A(sd|MDD2BvM&f8Eb9G z%F6z0ZAeH+{7-9xkB<)vZD5rR4h{~ivH|~3V&lJj4SIU|e{l`0tnn|a@jp$CTS9_c zJltC_&MgRp0f0APFcA?EAt50I0wEwEz{khO!^6YH#RY@G|0)~Ulkh)%4N4*fga%%0 z6pURbTdTI9H;zu+aSrQi^u2+r#xiQx6%D-Qd038H7B(Cjv3NU>(yWs|k|pE0IXCcs z`5Fdd;{V}mluuQdd~%#0Y^a$2XxSahq}y2e^OOB#xuPzY6(ObD^tI}8{eSx!3tv#+ ziu31oAC{u{d8%ZbWw32=d`zkdl`lPX22$@o`$j@hPLy5NMhMaSFJHr7GB$+YlvWSm z4s{NzcUhoG50KuQ#kQTCD$boKQ%SQFEmO5MAFYiQ>b|$Q^mhJ(uHE`=e(mG?bKyx8 zM){^iBkBkSlltQu)^c^WzdZDQVa|X5pyHt7$NNlWM@$LmeA?+jP?)~>V2>t1#G1Xf z7!K3mS&E=CwqJVn-@XPslIKq}$3MOXPZ%8z5iVf&-sjA=FX#2|aY%0bpCzr|%762H z6Nzrn!$eeFF8pKm=cg2r(@Kf2)D6e46Gn+R}! zhi??67&~tK<7<=^Nxin}F3yW&*d#3cDN*vY=13!H z{Ij{$yk1=K!T>EL=M0j3jb;F`)zi(?JMbMlT3r2^+B3(@Qr8&NR{z>#9jYDI3WAj>*Liq1^MWnm(b# zt$UKcX;-AonGOF+`vt?+3CeEY?kkZmygg80b*0>DpAfn_8e`eHMy6VJlgUrkv%(}E z)Ox(#323Ky$Kecy56HQ?SwqFR^>7m8%2$X(c~`%ylA04Zc-)h(dd(&cbU3L=?Iw{u zw_l`u(7Av>J%_Ds^n^MVFl2G8a}jlH%RsU$j-~oLNiw&%UF}s#Y~Vyea{w@AiD#w< z6L^IZ2JoZvNuFzUGt7!ag0!?CMfoa}rTKx$W18Za9=Av@g=IRam#RvPtck{2%Ot}6 zxJu6~6E(0=Y;hQ#{OwvZ|am1S|yQfqL2CpOsc9aH%n+AgorraFoC^ONr5XMQpSK{i+NI)+R7|c2=W<77{^y0-+IaE5SJ> z>7g$WiI#9=OLTCnePMmx_Z;#^KD?4#+EvX+z(`WpcxuAva|AU$=_yj_@-Qu8i&LLy zF*=k@s_MG))m2*Haw|IAE~sH9{Tys|MXKHX_dXE?(9V7X?^M49XoGw zsCwyXLruJk5pU;YKITHAv}we}EmAI#0BuQ9i0Bg~JXF6HOUpQoOHJeV#;moR=p3y@wQD*@SRSF34DHl!{>i72d{OPo1Z4zkTjF zH!9OO8hUz@N>w7C*r!lB_B7%5XSD3RLsN&(lX@~u7BU@_K@yxY_XPiX4numNHPzg4}kT~x#NZbEn5*%-xnLi=Q{ z@8sd}q+P4jeMxMK_B$>R@)qc4^5wLGJh{Ls7h=fVgV?b2B^HIT{hH`GDtf(cW(<5G zS~okMa{4YtCht5_X)yFPBVz>Rx_uwNmb(t{9Yw#6CXg0kO{9=0Wb%AqJ-c6QgOW70 zd=u#*#J`{5w}_n3$ejoa|EVGna5-t~3(C2Irp31R?rW1%Vmu;D`+YSa%NtULKZ0Bn=Q7`rr$Ys~!19@b_*dDRG7`lbrSQk+~?xKXoS()5FbTr691lOu$kmuI7?_MVP#GUD&(3Ay7=5_+w5-YGndLjfEN7gPOKSa zmUf7F!Q9UI%_HWanOmI?G0OsOv82dF-e?_T?KTojP=#(YnE5?l1$u9mYYF6WmlUkyAPW{2q- z2Rv-Fs4fh-+07%9zyH-DvuUI7JGC0O>SE z=*>jjJCD$53WShrzqL^ke5swm0n5S#ats9lKnLHQGzShV5Fu4{M=8EVL7FIoMWA~C zPLo==F4FhlL4@kdC^Lc}J&+QW2sHRS3Pl$kCKDa31xl3AGU6dT(SP>KQn&^K7`@QH ze^w9u3INx*KxPdo00$Nj_M$wV;F3s(Xdl^p;v;=x__SXeRm97gSPkna!p^7&nYjA% zsK|7fAw-RX3&!PR4J<;gMZh8=uSG1eeLt@`EnRL!@a@phf%6y{)!1s^aOnrQgpcsb zW&(59V(08-YSvvoq($h>s4#^cnsG!c`PmV&WSy z8Q5B%hDWr+wF!(7I}iHnj_dFQKPFMg!E4teA}^ZOF4FFVHmMCWW7h$B?xFGA#}3AZ zf}Z4om}TFxJxX9i%li?rOkq|h^ z&R2JS!nZ~lslRvx#AN+$zrO1NrIxU#m8qs7YPozDBZ+C>!J1MXFVY(OQgM)WA^AZ* z`EPy~q&%`t>t;t5za%!0Ni=wzh}@UpgNP^j?u%dE|eTwGDWraAn_MeZi|d&uUUV_p~x4D@;k zj8WwGcL{uB%cqIuoKO+;qRN5x80BprcEBC>i zjmt*m15Ktdk|C42r%-lHTy8PScXMoWr5`&SaxmRHMFR$i8VAp)%Apw^e~@`yaOGNZo6R?eEj1}`f+ zW-F>LD?J7)Q*<(Z`By89S1oQ z8Gd3}6UUFAV?SQbRt+?FfH)v4;?3&oeOg@o2DWPYU0s%dk?I|86?bTwt7HM>hi zR9UGsLm%nl>KL+Wx(2IDS?j(d>o|4aac|Y}W3p;x?o(@KfzkB8jz^oT0=x!JHq#oQQsjv78@qW>Sbu)ly5L@t+XDhIb?9| z$piH6NLcXKTFTcxds1%0|JiP+5{!Nk>-K4CyixnI(d|i%Ms2aCQ@#IC!>&Ib;aRPA z>*r}x-(aU2clk2!Cyho=%Gsl0Ukx?JKZ!zJHR&=mfAViIlyB;80VAaGiYgp}H=2L( zSxtE={uEEINF>`uk&LdZv}QIJRq^wVH4EL^{zVpNagoTj2B%D;=BH@~U#4r1jUF=(Y$=hDAk>U0&kS;kCOAc(P^_S*Ba;lB|)M2=obT-h(`-7<1p@vUt1rToUBR&ma0#tio{<)ktT(M`}gsM^YG`~ zNO1B&8;eBZZs0ykvc_7R;ADG39*FTn+w=G)&=?LZ6jWb{{G-1G%yk zc3p%vcA9{#GzKs_9XM5)qckp)#xCTah&J`1{g$s^4-ZdO3@6SpfZQNmjR0-@msm~w zD>R|VKGu$bsDOw|;9B%CWH_~;jeSBW98{J^DqM?mft|y`aQenbaL7r+ae=pJGK)aw zkH}tW!R)+%?;51zYNT|6=oc~jV}7Exu8E}QHKYcNR0)Zs4B``jKF$(M2PYK#dklJ0 zLt4S1y@rNj;H25zq*)>`mwo6TS(uanrBBebjLW17Ytv-g@GSAK$^(KUI5hUxbih)5 zg(sO+@f3I*^c_vo!V3Bh5ZmbE_vMjNS>w#<6RF{neiLEH6PztFhmn{~m%EhtjZD{8 zO@GAf(84WaTlK37t&6@kHzPX^LtAeO;SphZZ>#`M6U zgn#w<2o}kVU5IeB1R_8{Q6edrocJ6vR_U^66tfsuwn+GUJ}?wCHcUWik%naUTQ{d_ zI$E09$Kg-ml0ZQ#^uf{q@zxl#<03Q{2DV0%EFwfN%!nl12ygWkr4mYHa^uN!mK8c^ z%@%!7mcQF*YIQ>8o!F_TYw^d?gQIT4U+hVDQDlP%FgO%{I&r8~;IDN;u`Na@%5v*wWkO>0Evk-r%OQcbKnYq0OKTCzX{!D;Mn3js z*F%!bbKrWO_{ENVFay2_0pbzvpwP_ox0??ccfbleN+vr_t*sl(Up`pju}2ZF6K?T* zZdqY|-)RxvUA?hrK?}(vc;`cKkh@pZw#i_21v|K@9um(719xV$+!RvY zdsluqH*gr&yv?+E#NvO1&B6HrGxfZC;QM=WUuHWj+?%%!)aUnKTQJCr95n_X<0$+7 zx!13&oUIV@0)Z*C`tpJCDJ=-V-%i~&Q9gM6>7@PliN*WFfV1N`r>0Gdv%qm2AGoEO zTZ*mn%!{Y{ccEw7XD6(D$6en}bq?@~?TMQc&I9Pqd6ds1Fhd?Je(MQmzOHB6ziIuU zUJv%qLtGDao?dVTT(qWLWG@UGU=BkL@b-j87L+cjgfH<^5J^Tr$iS-Pp{QMSNH6`1VeAC{jSH|4+e$(2Qc@S%I`PnkM1um zQ2CGkO}TgF^5$kV;p*2Lui=HVZ(k062va>3IqDJtttn#!%Wr8$Z+AX=0S6z!Ko}nB zzrIEo&ux_@-Ge`Bv3QhdZT$z!Ut?*-J#gs{^E8tFuS_5&xDI18Opq!wsP{K|W?UsH>Vvo6`%U2) z&L)= z>ALkxb8lqIl`UV!e0eg|zL5>T{meFW+R;P3j4ivEa%rZJGlSgxTK4~J+O=($jJ>pT zW5#(|YyEvS_)f$w6Ga>jHThB3xAg*b9$or$>XmaV-R;{k-sMZXEB&7G^t^Wm zerWUR2Cuh=A7B3bo9~fk=MLur1OEN}{|7KY0S6>dzzg&%FhKn*B`{*OFL=#U0U__(vyUPMNvXCN18E2%iMjLO$F~=LTcu_|m ze+2SJ9$^f!NF#w9@<=6d1Y<0C%;Ru1^xg^)J{3{KGD|IGyOJmt?K%(&BgQ1NOf%0! zGfg$uOp^&Xm|!zbIp>tqO*rYqGtW8g)U(ettFR+OS=5@cF7^L}s_w#WYh*H|4ZbPe1Jx2snTMwNz72HC0qnQDwE&Q&n{})=rz8CmtOL{m`yM zgG#izNFN0@SYe0ywWlxZs#I2GmxXm%XIpLdS!qj+c3M;c&CnJGaFsGwwtA(m*kQ*d zw_J_H-RW4mlC`#7POEh{UU=hecV2oqr8OQuw%w}G!Tbda-09FYw_t+{CYUC5=VJF> zckOl9S%@Q6cH)S!ore}F_>IytfV&b{x`YoVx#UJiR%v0m8m3rUi(7_vRG6oI`CeM# z*Ce zfNrDM73@F^4PlCUy3-EVK-Reu?Js{9#Nb3MD3SmEUFClORA1CW=(G`@$_IJ4#XN?g z1P8+JED{8b*Z4xg&uK4%H^iY(HW-l(Qssl>E8)z72(uxAN`dcqNv0kczX)Ehf;P-y z6s2gAgl(c4?LbE|W>64l{KJd?UoW5m+PsUYYfg}@+!5?!c}T@|H{ zJfR;<^c#z zE%Alc;~fpN$H+dG(v;63rASKfk24%H6%}zLQy{52OUg@<1FYqxgdm3$>f#5ToMS@n zIFw=HM3nQ{<0+LnHlxAdA2>K9I?|zyQDpxhArR<5Hf!*Y7$m@(-vnnk#W_xLmeZW% z3;`UP00efn)1B{xXFTOOPkPD|32;C{J@vUye(v+0`Rr#v1Tk%wW)oWLxy(YRH|0hs#jGi zB}6JBD4Nu(ISkq=z=1u3sNo+kKnOOq$<2?p)ve!5=Q<5KSGuyZpmoKoK<}DYzUp(Y zeT8Qi#v+e9#M7Y=jp#<-x>%1Yma+ejC1*&xbrGW7o)9=?+*Oo!!MotWC9I}iltf#ikq&%x zqZGM4h-j6P+{NYBS{|m^ep~g0Hx?nl!5lDlfumyVAlO$5W^jy&M$&|6I4K-HpNN%v zU*}Si3YpyGrvy9_7E{H*DarriY-lWFCU+OZNwG0faGX9Jceu(q=CQNDkRe?3K*%U2 zG7Lpi8T4yL9co@vX4h>gHJIpIU*)BGX>xwn8QZ8yLzoKF1i7_J zqHQ`e53JC=#M9riSPQSW~y)nrmXh7edo7Zo_vaKY7rV z4D@uZd}S@q_seCa^jHn?3(RI!$3rfXsl(F6pU{SROYrlQ3*GDWBf2r=`(~sQo9S@7 zxEjGtg>(NBRZ_3Dcj8`@UVY*k@9z57^`4oBkKNQ|$8XvlcJ{VS>kzftLaX4;>Fmzk zOINQ)IlK`I6>xp;mq+>6jGi>W_gL_i{5-u%XayuH!c~iB_hbH1gKTyH0tabBBY40D zX@p|~V9z_|b&vm-zEi66lMKBr|4qwO_aKGBh@;}w4Qbmhmfoe~Ve4&DSra8l$*=_Vw@U?azeU zMe(+9Grt`JzwjGCO;G{{ss&j=J%npFh3hPJz=ZtUzY4sI-bot<$6av%nc778yjc%~Kl63AtU>=Y33 zt07F(#8-q3P82jx6dzC|zEPAkQCuHeAPX;e7FA3SN;H;{y9rJBhgTW_Rp5qu5C>HV zfr21|XIKYyXofH-2m#0hZpepn=!Akm18c|!Z-_94_%&GEKS3lrLYz26d>mXZ72w1U0rjG)#ghfp8Fog1`Z9=!bsThROo~R=|g8I0H1ehG!rMZrFr^XoLTM zKre$(s}698#ca&uOp&Ujw(h&Pl1#eETsr7%y5(9#JIDh^tjEm^v(%dlGlZpcC@#}< z4{BhBkB|UrfCVxrgJaMJ^kRj7kO6`igMZi}-tC;$N10BLZB(j*8;*gcf_7ohf9cG63(b_+ z032Xa9H<6ZfTj+Z257LRg1`iG5CDQW0C#u<09b>wB8V`6PXHi=Y$%9Wc*_5eRL&Yr z!y9F}91Xm!)XD(ulpdf36|w_5m;xd-%OjOLKczbeoe8*fz=u_+fg6B@ zbvOY4AOLHK1~C|eX=sLvtcOydflKH}#bnb^RR}jdIym(_Ic*tsWSmKh$9VVyJLm#; zDblV1)W=KGn}AC+cre6SgJ_t>XDEY$I00m62XkuzCsbE9jn*8T)(w*ySLeSWgT2qm8*Ea>(IL+Bs z^#j@&Qk11w2Q)%IG#4!hhFutdnLQYe{X~zo!XDkxL!2BxP^d&upgGu6pbgh`6WZ>) z*rCf<`A~pe2nHokT7zNQT6EetOjzNAS1n*5T5tk6u!EPpmy{i|m90dgH5Wt(21Gbp zgsEBZp+*0(#nNiq@k`wD(-bJ+1&1vH!P0{va2UMZG!z^qgMoshRe-=Pm$Wt9wGBn6 zUEB_I8zN{}V2A=LpaVOwf{3wPu;|xD`dUH@Tlp9Ovdsd|B^UqD^`OHgK+=uOktK#Z z(19ia1MJjV6AVVZ9mbXg+k^4j4dGox8(gcq*;38fQ;p0-s1;7CnmRy5*bUku^jhfc zEdIM)`Otx2_yr57Uh7?7t1R5#72R9hUTVFRcub-opq*HynAmMR=cP&XJqUMjg;vT7 zkc=-}NEjwX)LvKwb0$O}ZQ%Kqxt&#{e#0J{;PV;Dcn)2X4@WNVN+F zjtoKw21bxzV4>hgvS2LBUxPK!d9a0FasqtC0+-Ae(KlNI6-Ud29~i4xERZK#J>PyuKqASXxqy&HnScPk8T7;VxP3C-dxqArM|e(Mg{rnrXe#;)tbzU#gw@4Pba^A4ydNZl*| zf`2M#E>Lg7dML%FsPKmD$Hs5BlI)at24r<;u%?eh_}l76rtR}B;4%n}=4b$zfsan= z3>@j;l}rqFl^@{6;ys|1ew(WP(}l*Zp^<{4MF0a2ae_F5Ce~5~R*3N`FGUK@RS1WC zmWF+fa4MYe3tsBFq2~1y6{(gR4+oE{o<%h_1w%50BvCu!Qu3N`pb8>}rb5)5D0Pva?@R^`=zZifA z)&fkowt;X3SMUd87r!&%=6H%EwY1^{Nb z1cR`IWx(^HDTEjXcDySHPpD@oD|H(_^(-Fq1-Dj8g$cch3)&=*`6jTNS3x}iF(KZ zgUA7UD0q``U{umk`QfpZv#dx&{K5A%7~dB=eQK_)>=`QSeA`04_AS`~SY zcm`E4h*f~E=gxH!fngbLc?wL28vuYxzy<oFBN;cUV77319yzAUw4<3T|(+%U9pB!Q??1eO)`7M$m_TpyW*$bxDzU`%V0J zl$#!~%y>BSO%Vb;fK>yG9NxF1%BQx=FMvkqgih##4E=nQiQ-=_{xdWP6A%Lt1%NW3 z0oV8XR5!`kzZB|Ezw6%=$pr`@I)K0dqT?XKgbEijZ0PWy5h)A+P^@UNVgfh`E^_SX z@gvBP9W!neY4Rk>iYWe}Ncj;4w|dsB)!X*MCC;1_JN)aQ^C!@tLPN?5CTJ+qq)L}E zZR+$X)TjV>`jiTCcpaBU9EYD44Cvnm2Rq?D_LYs>pmID{Z>8 zRIH#)a`nphHCnx}XM>eZJM7ze^X4|}5yuV~vITFq^=p#wYLLj2t7JK}UJi?4+%c~> zxjOcc9)1M_k^MXP@Zt+ob+rM2tMuyAr~a39Jb>23=P$HPf4=?u3V*=e{qTw%bW9{o~I@w*f;CGA!LkNZ)diWuT7iy*&eDWEH-*6`qm*0s* z&=MDK4LKo)9b6>DqKbVL)8vVz_ll>)m2 zqs0HnDXWa@y8y5ggGDj0^RK0@6+D);HxG31e1N<&k1kn&RhJ!CFqHFs7LVkrcp7iU zaZ1lfJvG(Oh`e%Bi3EcP)?Ite*@fmvVv!{0&@3LbI)8<9!EBG!Ln89bV~Y}C`H%;2 zJsiz5rb=_<^k;x)>D;}!ehm~9!R&&-;f*`~)PjVQE5&$6O)sF*(fXP|-K0NV1iP(rV>Zl`4 zBUWjNcEFvl&A0S!x=x!Gx|nH*-e65JM~$9S4<_su(Z1RFg4yoU2+#P_j|=FT(tH2$ zI3W^DBK7OPe`qa_=-#uUSG{VDZ-Ak5NW$hZ3~q_#3u|f<0k5~I@?nH&;YpuX)|V1k zFarhch#woYK|lVP#0bIo#a~FM!ulDmFwfhZ00%fR8H!JWd+C88;sG=*jKvCer~?%q za=_V8kRlkQ%n{pzn4p*=3;_5b09-&F?6h!&91%b+f}sT~a?y8H%pd>(W-}V5s({rS zVnRlz8(I`$EJFBJ7p7-JI2DmW76eZcqoP5Sv;$^PBttqz*u{<%A{dMqBqF``MdyXF zW@K#LBWF09I{;%I@km7X#G)oW2th+xP9ofc)3h$4{N2VH9!NQREp>zL2yD3T(qcGx=<$S zL5fA zqy`h-^e)tv=;QCaU3&YGlF$EF08CFGGvFvbIAP!pE&D5(9kvH9LW&;b3!w zG#nB`Tik0)>Q;xde(EQ(q@<~X{-Ipue&Ql1I0p|X!d8&T02JKVM>F;cPSjddsNHET zc;nhKZE(UOoybOQv2)vC68B~~i$a;|$-}mM&kk5POK#a>+?pa6NdK@bW-r2rfAFKg z|L_Mt3Lug)T%#YbJZDjk65a`Kw<3+;2Qxa+31;l059zJWdJX^B-nR7<5DJ4wB39a# z9)Mv@KEUsY=d<4nPIg^5<;Vtbpko|V0~R<4Nf}aMj(Qm5!Qy;UW+<%W)re>ev6x9L z!~oI&j&!Oq2Hhu>&>vnjj4uG9Ll9vsR#2v}RsF3~jXNVv&wix3*Uhd5AR10|a^O%) zzVnsl?80`6G@g06GPOG8hf0>NjeM!Ejba06+RPY_Y2Mh4K{DNr_=6gmD1msndr=K> z2+y9T%!Mv1>JDt+0Uu^gh|jp_O^JyJiO^v&XX8LN4Q$NJ4CS024H~mDWz8Xh>v-gf z$R|bV)5g}yh2GbXWivY*pddgr`5e_4l62LW`cn4RnArc<00@ZEvi55ljpj4oDbno{ z_8<)vj2|4k-B7tuB*qbnT7^O!mFR>z$~#bL1D4uWwzb+=G)!%c3N|ycLma;i@Z#dy z%w^T}|CU%UbPrN%TyrcOB8UtG*r)@vFTCwUW%^?rE@Np>|{VcyYX7ajb>G36x;v+8OkAYD*O4Db(akh`qPUp)5ZyK z}1TLUYv%XtMHupx>64R5sh-xqjJ`CQ4_bg$Maq!B3i*HN;3+k_nP0f^|#3v z?%v@5qPN5-_|;8?7r?7tzpTHQ>(Q5ecH&$oNnPq2n)=iVw{`%*>pl8CGWOUTU%kkG zy7Eb!g#PHF<+phwxH47!nO}ctG6gkJHLUy)yH-B13c9|Ky4|C~WANW()x z!Wo=ea-^E{fF6AS!6Rr->6{LIY|=|nU;N2f|NTt>B2fw|(NMrv%+MABvKA4XP?e1765A>=hJ=fjL;cT~r|*5*VW2h1f$@K#>c;AXK~%$=zKY&W94jmn|%Tft(&~u;Et> z9&=D3QdnU}I2n{l*&tffEd4?)9U|{th&Qak6U9#?h!9AefijfCKkz|Cyuxz*12cpK zBsQHS79pH$LAJnyAxz>D-UcT=gePXq9`0Ko{>u6d5;>U@D?Z+ZYyy$6!x=mRI$%Ob zw1Ft}K`!nhGnjxnGR9Q|A*v0bh!Ou|mo(qP_`%lsUH&oSB#y;1t_CO$g(zOcs9jd6 zc?30C(+H>nH{63bs6wDn1Q|TTI;cZ4IFUubKs&61MKr=T;6paFK}b|%7fn<}WuxO= zhyZkgJNSb?+{3<{#5q#LD+{`Aj2EHfEsYaD*=E8q=PHWzzrOOIgC;QRKqf8Bt@73KWIV? zgn~Z&SpVRjT?y4Me1J)!9hN+R4U|Egp+rmqz$>f+I&i}(u;WMAr2FAyJkpSh=!WV1 znLIYcG7e>A!iG@>4pJ81G^YPVyv^Gi)Z4w~TSe#;Pkk0eG(tWc0NfEy4*WxG0RSn$ zf+V0N02qTZRKzr}0!WBt7txi3-Q~~mCPnRfOJkL zbylZ!UMF^Dr*>jz2*5!T00DT0r+AJhd6uVno+o;mClbH`5~Qblz9)Q&XBL1;JQ#v_ zu4jA3=X>I#7w9K^;-`NGsCzO&7F@t~N@oVZK?WQsgEpvxW@myf=z~rug<9tdC?!sC z+(v#}$WcUEvDrmb0y zmhM3%5yK#OX_q>X9`pg3rm32)DVw&bo4zTWN+~5^s7nl8%p6_PQN(6-)}&EH350_v zR0Ixq!?JCI3N(f|RA7u!gg!h%MO=c}Ttt%gB99u?2XKdX{3yl+>5y6kI#>dZIwy2i zD5;j}bav-=3aF~CDtH1YtG+6E(jzcz0eQMAtb*qf-fFF~r>?Flfg0$6MyRO{D}@Rx zu^uaSUg&0`#M)Ve+rgdOJy&#r=uS`rGn9k`Py;NGK^bt9?jQr(Eh+#s>Z3-gMdWA) z?C6peMW<d?0Kkk^ zgpKZ|p4}CaxvRU0qy~gR82m#fgnUiCe{BCZD1X$=tna;MAgntW`Z4^J_TEeEjGM>I+}oj(EvWILJiyiEUd#rkqvE{ z!9HXH4Sd2|!fd756{ms5i|B$9XwPa5F5&(z8iIxz2Hezsg%Z$bj6~3E99+VA?(;h1 z9ahl7LSy$rTEm_M1WF(PP~b7xI{7{($1nBghfmDco%XMn)Prm!vyFbnI73+n_7za!;lVD>J=9ViSi*dGqR#uU)V z_44o*`|$P}5e7TO)doe@R)iuNaU&+NQSqG5afU4@*A^J>6jP%CFYjkGug>%^Lij;% z>4Hy&6<@H}%jwn`$4MI7Q4nM1B;VXnyrL1$A{`f1*{v{Vpu#`g0{{T7;P&yNRB=vR zF}`N;8a}cP_`%QMLg^{;UZf6~MI8n2#Sd#n8w14~Qv^4bfj5GqIBp?@S)6Cw!#}W{ zDf_YV0-@w$u?&L=AY_#-7}{_VBch>PF0bCf`rpG039UvNtAnFc2cJ+F`ga)xrz z=tW~xMn9rGGcP{3vOYV6N0*Lci5XjXm3>{CE9=NfN8w8I@*0PtLMzHktB?u(!UAZ< z11MKbJF}YQbRh4v^Y%1DB!XiGwNRtQ5a3N?88ui7UO_iCQy_FIKebEWv{4N}7Hv^w zl)^u7URK-mGvjnLuktkOhgf4SS(o)$JWRx}+EFLOE>{Lz*KD1fHXSY;{_Rt=5b{DiwhF>FBTe>E{kBDQAvOv|1Sl7%_Vy`LH~R&5 zR}c5{wf0XZ!X^@znk@EmH#R~zcVtAiOZ>8Hc{e&ulpzX6CMXw+a`#-@cIP4R=S^aH z>m$HT=6bhwQNDIKgNJ-$NK~&7T@sa65WvN%0)Kb6e}DEyzth$kg51c$VW*z09o)bk zxJmN}bicQ3yD@D~cZM4kIsK+oM1pcX$VC zldF(-N%2!;_CFY=m8&^@JGG8?29Jw5ari-2(SnzMx%Yriq7^xNLxh5xIfJ)2oxiwI z`KDED!#{k~oZ~p8-8pCEIictB9rTthIIWOB1VG0D1ZDb(i&Bzj$CAUxnyZkHMg>p& z!=zt%rDu7yQScTh3@&*3r#r;MkhGo`jC)VviubmH#yVad`)phK zW?(v&?Q0fP67iZbFr_wF5%-u=?V%r6qNlmBGrCa)?^ERWKj{CCvoAW912{)p8x&{{ zFeEbe&QWsnbgAdsnd@P{^Wn&>x(XrLW-CPoD3^t|ySvXiymR=f6#=LS0~izR9EqU5 z1ADmh*SH5fw4YPn?k!Wqf^rqD!sAQF6T7r)2DJy;q7gxv5W@}MyJSjVKJUB3A-a+m zyUCmTxd#IiFGZ35LnV~_!V7WASH{Yl_=>>=JUFn-FT@xlT;*bXQsd#jTLpZlM5+hd z$&1te7TZ$bVmcH&(R+x%M=q`Z+g^yZJS3sEyG4uT0nF7r)t9-r=RCRZe8!D%Fc85~ zyn%ArK-ri3yE{^V7a<_Xjd_=}LfCSc(Y?R~yT5NdF7f}oQ6aNZC|8va{Q}EHnN=C^qY?e&lC7 zja_|G=6&pE99=~}l>bBqTTNE z_}2kvPoF=525osKSkYiQen$KEFN9F1PoYMYI+g!w)s8xOT16>yg;u8*;4rZ`mTXyw z636zCHILXGvu_nfoT$Tz96Mg%<|QjvZ(oBLHKttYRp?;CH)Ya1yx1gG#*ZQURItk^ zBA<{ojgKf=Qg-nH(9_f4UZ4~XFuKbhv=d*ZCh?aSV(L&oQ z>ab&vu)n66Z7whN=xER8rZDMgm%iGoPK%PoBmtmV$_>2;N$JK!A^JR`&fdpXyiK9H1EQxBFZSFNK$60N=R?L&e5HMdAY@BR`HJW($lqv zFYM66iJ;rAIK;R+s+%+87YqO05^UIEXPP#Mgx&S06tK4_%SM7^DO0BJKKjFv=Gwxr zFt3trD1e#AmLIfjuZ}8&pE!Q{h}W<4c0VukZj#<;BL*2np^qC3NqXK3ipYur9gmn{ zDSa^D18G!1pvVq6w3DBodJrgJKtWq1vI7?~S3b9CE-)^-pV9IsoX~kh9h4v-_#n6# z0vY8%8xg=NmU4y|?odDy{0Rk%W5I*Xr#0|!i>`!#B{29Pgd!Zz<(5>xjUX>FR3wZ{ zYR~~KHi#qza6~?A@WQO{a4~!f29E$h0HypxGh}olc6{g)APPr_=i<%nz;!M}De8$% zJjndwBSipM@iBzd%5?vh@{do9BnR%`$2y=V#y1|ubVX4@0;aJPQcRMQ%aPt0lu?d< z@PQ)&0EId3;fx@iWR9e%qqbI~g!I{BOSQU!9qN#)COQ$2>Jg+N7X!?yU{Q-5;9^G} z0E01%0v%x#QXD&Zk^xvR7>p3dQZx}wZGJ|2Z4gBtM#&LPtOE`_P=+@mz{@K*Lo?QU#5^b!W`KCP~r?$NOGH0L4;A#u@n~;l%bIEVK@OG0CS8A z03pDKBh)FrB(>9zd~qD)YL&z+1!08l%x8G^dBQRA^D`^#$TMC+(1t?A14S9fKlp)$ zneOy34<#i4T=4&oFmNOqsmQ3}ILb?j+~FPQ(PN^fkdTwMYO1#AZVZ7};;IE1#uE!OO5U7Xt0w$`<{&G3zPYhxVmIIzA|jI^LR z(++H7DX}0#fl$X_B})jpHi4)_DcXUH9+jP^@go#E)G%#z0jdnCYN5Uyo2&XKt1k<1 zyqdgZkGKFIO9=%47(h+zshQ3tk)8&^0H;iZL1mgy#~X5x40KX?d{%a1Je8m=fe-{} zP{ijwEw(umVwI)CIpTxW3RkR!5qPIT%V>Z@crC1}X*KVoW1bKt`nGT6#G3++xo z%;W!Y;-craAYHp$V`$8tQ>p%b9IYU4^9@VU2X!~%G#ZMU*#H=}O9>;BT1G~+$3*0Kb%>x-l(D5)|z*0 zVb}EOtS%c(@Gz&Q*ZBLj3NI}>Qae`wp-7|#OfpTQFhb)SpSiU>uBW7aZ3|5`#LE5R z!Fp1xr+lpyx}@dP?lw8GKVo-~9jX z0n+s%QZSH|B5+@k-SyIP6u!JtF~8K=y{EmUxPkyFnPE}zRdxmgp3omJUu%eAHoTi< zcZpgQx=i|XeMWs(+_@Od*kU3MVeED3YxH$cp_uqWU7^`sm~K^2nb4EjRyspf-G` zOAL@v$geCAu%8t0Nc`?~?oXR=U>%l%9ST4)oDeRo zAZ<>hPnb|wR?s&%4`W_%Gte(~s1WO{@QrYw9+n~bt`6nq4yywkuhvhH)bs!jz|(iqz3{nFN9Gy#*re3k=#TvRY-CDO!0v+TyEZhg>;85iP(l5?Y;iOP&7!cExv6CJlk(j|MDsb%Vaht4B zA7_UjxnwPXA<+=#ASnWEKBzCsF+)T$?>w=1(vdNYF({DnxH@SBsv(gu$|~yRUM^Cb zGI9|059Ao-4&q@RK+1gRqb?{16ALo)G|{S7(tapyAsG&99@32>A(5m3=e)uTgCVVU zl9PH8seqDChyY4xVc^u`VS2|GnWQPfEG6?IAxYyUCukjoLKFY~!Kg++6}aIZ#6cCB zVk5}l8P-7^njyl_KpD)T9V{z-LSnE`N_TgYPM)s3n6*Hu0|^r-BT=0UL}82aw?nUO)}F;TSeT1Jc12 zX5a>n!5l<_6GFiZULX_t;SDyz4ERA4Y9JK!0S8V(7KKCr7-%V4q4@}d_2}<2-zYR= ztyUf}1XE5tI_nBj<0RwLHOmh+2Z=TbgD!u_E`LG;xM2;T!Kgf<5%S>x0DuhcCI|ij z21a5TTwx=OK^Zt=8V0H|tMY+fzy|*z9k}o@D(NW9(~bYo)A4F$Y;uw5+>#=c4kc5R zOXRa5*yXCtv|u0(2xQ0Ub7C1JdCW9zX(8K^qLzBcg$O06-il3IIR>8z@YR zWa2`*rvO?Zk>q4ECc_mwG(=-)M1^iFm&6ZTqZ`{(Hv(|(Skxd}6g6U$Zf4ZXY!fOR zAsf;uM?0bf!a)=`0tdXIANpY%RAxZ)VSoTY9~^TdF5w)m>(r#wb;3YFHk1ZDBMYFw zUb28odB{tDvQ^6RAM1`j)$#<>lqpGwXrxj`Pc`&v6fw?$2R6b^H=+Zmff-mr0;mBN z$e;|4K^xqSBh;WCB7q|el_L`MNjo4)d58d9A(8(~VHG{YIc&l8F!g~nH3-2JMOtGR zIOtQ?bRiHWHOY}a)#F7OqD?zPKjmmuZGsPQiXZmHANU~$H$WPkA)PjY63(IU0N?@Y z;U)n94cvisI6_G|qDi;YGXLcOzM<=ojb13j52h7@s?`jy6+_lD61i13+Jn);wOj8_ zTXqWD$;JkH=)K z4rO~HM`IQnUcdy{HV0_{A6B6TZU7e6A+G;^RTS9P1V&&w_aPH#;1ja*U>ntH+#r!w z0Xq<&QxflKp_XXt(kHF8P{dRo$P`6mqY^2HiF$);+p<(SCn~WcCW9hJP3_dUW(}gD zFrOj*Ug6ZBfg>7$8}dOLD065BcV$E%8xqOYvO^2RZdn-Db)t47r&c_E07|sXRZ_AS z#e;Lj5oE{0T*p>ylgDf!ggdcg5)$bdHXuI)fc54qcnfEED~Kc2gESk(V=GS%1TGk% zcXQvjBBU1&$u=M3R0eO?Uq(Q8|G^*NKtP`F7cNkIuZDbs$b7>?2|6TqG7&X+CYR#F zdEr8W4`O~pk$UmOdLIOPm*WJs*IxexL`QgzfCyp-&I2}Nh$AEONt$rF@zNVY)i$WEI5g_>#4n)5;lgu$sMI0ZWkhJ87lyB3Q_ zmYl6aba4co590+A>K~**9_vH^JZ*&K8E<5{C$4cZve6<`n1v}>6TR;)sN|PhIGD#- zi$Pf(jky$&c}PN_CUMH4HAM%Ec%mtKrOTFkF5-}G|mqer+n54m0>Q34v ziFrR$njLNWMy_%xB=lI!SXybi0jChBi8n;n;zXY}4z(?lKem%wQ>y`(kWx!7qA=%aZUd$=aJon*~eS*FsmZy@Rc#!q_Ho zUIxIdKBcl{uBr79vrkyF^WqN1)U%szW8qV@uh_6Z*Q8T>sgp5U#9$O20A!vo7=D1Z z|BkUo8Ml{Mx8I@%_U$Zv``;D~{DhlSi93r?yPT0*CP`RiXaS9-`gj#t^J7f>rxXqg?<@p2bWs%!krQcgLjTd=2`5~ylE`VAE3A?KWI&2Xe zbW}S#SevJqmIMC|oT(E$J;P(xh#{Nndm-qUEhW6a-Iv9O@w8p;xCLCE6E_&b_ruqk zx}i-Y^;$fLAbl9PyBk8J^q_q=(Z#KJyayV<3p&H$NXIddO#~Rnp9#wAjmI-vJhBxe z!5NBzfOmRX4kx^)E8M6r9N1=jqIEdN93eIqyhmNU zOZ~sgyUG7q{h+NJ11*3u7FX6wS<>sF9K0bG0@WmPoiKJCR_0-all&mAAZ@gE*b8vb z>jTF3PR47xvWdbXp*`AZeI(kT5qN+Nq#+!-*CXsoi||UXc8}~yT0rt>*8xHwyNIaJHG8P z4CMdUowm)Gy`BC#I8Fo9;Yu&v&L0`iA0k$I!D<_P3MMBHz}nkLy-f8D0S#8b44eTSEPW)h-7B_Tf#-pzJJt!Xq{z!>zX_1>(S7*T9mpm> z3_Be2GhfGzp&aso9E{-w>KwjPW22kbO0a}|MacCtR>>`#$h=CY9q`sNBQNr*o*tvpC9QX2>W?Z$_Lo`J%gUD&z>2A_{HN0!e0rK zf6P0&%+K2S0Rn))fdmU0Jcux1LKOc{D0~PpqQr?3JN)ZFF{8$f96Nga2r?q0V2u9+ zggl8drOK5oTduT-(Pc!2D`cv?0EdZ=ojiN`{Moa}uz7}n8a;Y6$QL_wtRQ^~HLBE| zK;QtGiZ$!hs#mpoJ!(V>gNO;>B(RyX>{+xO89HPOHzLfqbnDt>3F23_qh-@?ELBF0=q7}3u@drYpgrz`X6Jv~#uZvA@H&}7XP zA9%XAYJ|)r-3YTRoQCfZg|mMTAAp5j!34#>j~}>uyTrdAzs#6p+I3-v9asNYr5$z% zCOBPo41y(AcWZqY-fiPORKh=Jf^ZtCV@Avv%-|PBbzu*7xn$O4maler`=RAm&v8-Q8!<1}uVh~hk z%$YSJ$68tVcL7MEe#OA+$%gOuAG^nATP(D-R4IyRGKvppIO8uKl8&!QW-%%cDW+ zu1^NHk_2$hQdK?IWB2yP)$vbmyWM22bvAi=G<{paYlrvIkc?lnig0bpvD<6`QA_-2 zJr!({^{Dq_mzA_DW!*QeZ|Qpr8k?8f6C}o$^h^Afnf!B>uS@Q{3>Es3yv$o-%sj6( zb~{$U`J3_mMKAt}vkfWyL+Q*#VzM9f+s4$IWvfxjsp$gXa=7I4(htOqcJb^552cR2 zw;Lc6OucBghRCaK9cF~XvoN%LZ#Z^74zrzyvW&VbA5VQEmR70Dd)uT_GZ?7$Q*BbE zW+9zhY)7_ZR5}4qex4?OP`>vZllY;fr?+0=aZ*eKFBSz9^t-Ph5(TM=gYi1 zM!I01W4SIY0>I^|k$7{1LH4KIV!+r{=+LJS`c}mPfqBfUg})ijQ!p zC3+K#k3}<;r02VyszF>4#raD5H9GM$IcqO(g^PG765W2963BWiOj1r9FY(n*oBixs z4vLC8>Sg&5-{!QcL0WNK6Ea%#p^94g%(&2dQ6>SD8HvOU2SU?Cmq%J(eIx&fw}|EO zou5G}0v1PUZj5qF@+w;JVVdjndjl+WsMrNw2!$IK%n*bvH;b{$%rNB%Dt}b!o~D{x z9AWkTBvq>cidVP~?cKT(F2(r%u!vct_@KX`hY})g=ZANxtGVQBCvdxH(iZ4xR9NWT z@}J1NZ2+QGLb`e}IsNlLSh-aTb~VJ!P?c-`V!7TBy{sNahnu|-0T zzPqbW+S4f{e#onROI7clO{n;@YF+osi6@>J`Ec_OAOMW%dudwrg%K@ znHU>m(GhX&T}h}`hij$iV0pUWe8SLem#X6J9R%Lc@MJ6MdAq>84OzV5XIDhR`!rPq zRASiq^F%!!o-asT!QWn{TK17|RdC=hxyBORC$aE`NsljYzx#9D7hL!{Bl(v1S|QyQ z#RF@exAq>3q{}DDbH9__D^6aP`%jmxNLRgab>soB-f96E2tEI7RqOGHBsOumL-+p2 z#h~$fk!O<;4t4$W5%AMb zh|~FcbhG(aXtwHW^&_jXLAsmsiq7CCJGvRdtwN~8louNx->25EBF=9l#SYkXEbVQ4 zvGXU?2jWHj8`JboRAMUV@2OrBGa#jKKO3RgcX{vq-5MV1yU}zT)Y12 ze>{1FW;3IeqK8tB@82zwuQxLVG4lpwS(k8R+GPqd6CxUW4KqF)AWprC$qh1>ScO$` zeXno%#HtPQWVU2Ezh>?o+Q+TKel{i2cah18c4*z-kC^nn$-qpf9fWH#e)(tqG3)&p zafeB5{OR{%4pCJ~wx1!)-P%ph(EWK6Ybqc4MPxmbgM1W7_~zOvynl>+IfFVkL0GH4 zvaz<~S6?~LF*0rJ`g*GEF-Gl(OY3RSn{|fXbNbZvfI@~*fu5W%lzG*C>;3Oj*S^Zx z+?%m$3l`_@ix;?(ymjCFr1Q{MzQ5}Xz=zi9k{YQI0$dl}Mus@yDT2j~uB4mXH%S-( zJQ{$4aKZ?kHUK3orXKI7J24Hjg$Y>0L6adUIcmFAD z0|@L89DzdSVPPOs%6?(ww>ENeCqLa}W;kcigWka4x1PXPDHhBV565>eaYR5HpgDsc zroa7E>}`4I({O$NsXtU$M{)oeLMR8_LLr$k@DDhE8bdy35`x9xDZx3Af1nB!JXIK( zjfQzKg!vUyp)e*5Tg-~R20@(+E!rqgESLy|j6MxgAPvtW4)1sy+*u!NMi*@Xp(pgW zQMHA?5<_w$;km*{u_f5$C}KVv1RA6C;C{nQ&v&2haECn3(u9I*yH z6DGUYMrgJJQRrZrNC4Cl$tPh%=O_t-2@+0*52hk}O4ImIuaSo48S}&+Dmp0jI~?Ld z?md19aiI+W*ndjkW_XZ^j&NcWlF$Pe0|2GH5tY!$8Xjb=SnThx1er4=Wj4JkDy29_ zWg?p#BoD0Pd=--t4Z9LaZX-y7kWWgYkl{%`l)~rlMt7g2_IA?|D&h*l|EY-694Gn) zz!>F_DJF1p7vKOF~aFpP;E zBS$h$fs03`7)TlRnWfF9=30ig620dg3oi?Y38C)Xz`Xxoy>X5p014UvD1@FNZbJb} zEFx77`~eeK?}3l)Or=s3zCHrYuAxaGbpqi{AYdJG0(f#9#&s8m5WxV~Y;))%au`c< znEP{BOLJ7MNs|mxI{*-i7m)!#qMrTF;;z6>t`K>iNI$U#K&pYtyC0D!UYf_Rns@JW zo-BF3#9W@dYW{6<5(7sfHp3i7fRr&iUyHmzr$0x1C;zc+fqq&JKRTRaEZo{LA+8=W zX5u>{i~&{qp31>vd6Cg=u(NE~@68V+rPLsdk{owYv`aQ5E}Mc62{TN%|A@>HRUD{V z9Bf-08c`fxS{(YBbd@U?hlWP-l_aQ^B-xfEN0g+NmZbNWWbTxFATQ0~E6r0aPQ(_V zK==&j=}`BGBD^?NPih9JIs;M4N3ELkETXJ24SnNYB>rT}7zF4M=F*k{ z;!Q2eOnr}nTI`%kVwXxv@)0VX{ko*v=Ti!I6f{WgId7yie-oAS4H}sND(xmb)#Ea% zC+SprYE;kEF#G)iKTB(gO=})wl%nLIK`6JE=hW&H%5mb>#II=#Uo$zJ*E;V~JMufS z57fN~tY;!3v5=&0)UFSb%l2-fYMrSDA{&^}8$#!$Jk{J@G<`y8*PEJgTcpj0*7Oim zn@HN|olfGbrsyx(P;Er@u}q^*(kE+xI(y#h(|kQB(shv8yQR##mp>(54H}$HAEsR| zZPHwG-gL95nKq>O9L z@eaGgwyeG{14bRM%s-Qzx4)$L5~R&-{<@x3N`dSGnQ`6-%b=5rqP{tpN!9$tV^@G< z6j>V3`KY{8ZLm{guTzV%OXpUXu6ox~yDt5xE}e3cU~Om^8v1;&ix<;nrrvE~*KHNm zZByP&$>BTxzGI`QwVuDz`4-z11-r+u0?+au@4+6Qy&gZxUjJLYf$F`%cD}L=DiZ*Sx zIqz6J9OM%jx-{xD6dMeBHt5nclsP{nc`>B=Y4ES^&`q7;jqihgPQ$6pLy?3zTLkFv z*2t0i$ZxxmKT#uR??(9L$oR8I@RXxOu+fXX5s>{TDeEY4^eDy9=@r7#G=zoSKLfn^~{&CnbyOZ7OL4`joBpo+2nmy5+wPeBjU#> znYk{gioi3qQ9?P93yL0vrvLy*7&aycxkGr1av+l&A^gISeiYnB9NCAZtQPoR^|W?N^pponNWo=V zhh>J!Wq^PZ!&k0nk*(vPLT%tTDCDiJ0AcG7K18bswq=?Z%k){xyZ)>Hz`JmO%Q}Fk zIKX@%K!_nw=*N<(%&LaNs?)-}7;@_+5XJ;S4d47n@2y-4_nqz^B?tRcRs+CoxrwN7xN@a09tQ%Ol8uf=)WCrJ zY#7*-a&QSxA9b*W5!}8nxBcFsFs0S!BpU)*4snD6&ZqQ+g2-65?S!nVBnPC_(vI~h zoo#Q(N4C&LPx=Np@HuOzOa^Hx2fu;&0UCo`I#$1LgF8ZZay54ferz?y>@;fvt%Ar= z!TlW#WEqYURK4#yvmXKf$vQ~3gaQLd$R;kvHf0+m0dh}e?hwEb%>kr<@IC;LPYWXr`5*uW2d>8X=^P5&9S;9KPy_Oo5a&yX^ii2*M@mi{Ff&bw+k)eL_h}S42K`QXB;^!YFZ-SB6IxyoIFcv$^<;zT1BKDc0=r2y7Y7G1j z1}1vRyu!Lr?*!@BhCdYovQ6NBmMG5!++&2{F&Hog1CK)?%^dMCvp&iJ+yMs?ypBLl zT?d3MC;>neugJ1izl}oQ!*faHKO0+l7{!Q?VA|v%&3BE1$26YAvVXJ~WD5y%Qc9Hr zGOjAbpXIVM14GZGYY(eJl(OXmosXf9xq$c^I;B#*vL{q zJ+U0h@1;_y+tMAF;8&|In5Q2@8L#SyMscQ{;V*uJxS39@$7}e;N=e%4uftt4+2*9f z+<%(&#s$_p)pd8JyA*Q0ncCu6!FlJ={f=7{$}`8ik>;(YY9#X~U#XU! zCmB?4blJ~mj5ivL6|>%0%9sz^F+0sJbaV9JIl3o&=7!&!t&43s#(ujO!J(pSWN|3p zq6}32UhS#+@JJiTos=)xyFs0YgbecWc~u! zs?JDF^=e)U;~*U+CPd9Liw;lP&m4CD#CU#<=G4bLwok;v(9WWbzpAOP#8=f?M3*dK z)?Qq9igj`gT!btPJ)x=3eh~MI6Akv|^S+a*J<^i9uhtVEdT+Tqm*Hj}x+^z$@+qJ;08{?I{gc(lNWb9=e!)94HQAg#rzt-!#OzYp1k$$*-X; zGlTUE0SB?7#E5!nm2Yx=v;}D%l50g3fhIbIKcY-dNlAT$0@i7Pamt44_L}05%-2Y% zQx46xI3l$0@S~rmo6k>gMuld*J6%P;N}jRr&v{{iZbC03PPAo3^s}J0Cp3hyvy@#!Ed@B%cS zZLs)shg(1*ox9J{-ZgtB4sPas$U5KsxOj#7*-roAB2dEmVWumF7l&d~1hcQ<#?$6* zO79pTyysS5Tz1@V4K3$j+STs4(~rXda4hetXX!uFJCYZrh0c zJUdkGRKU^K|LgS4E2po_0cQB%o!39il>8r{t^y$lasT^komJzR2dEOG1-`b!FR?jG zEK*|7eVIapjg;cGZ-BweCozK-=v+x zS9<9MVr+Wzi3r@)KMHZfW<>VI6Lf6wYFIfRX>Sl$8QQ|mj8!**S-|s=y5-}9^fmKv z%{G`B>X(VZ95s>b4d7`aCuDFQ{n1ey_6*oFtM*_8G~>ErIn)eDzb0h;nl93W=%#$- zvJ{E-?51)3%6PLagAB9*eW#cU$!#=f`=?`5^p4Qr$CazmgjF5&g&NeUPsrD13zN!Zh*bNAJjv(ewt1xC^*FKcNddowjhgY_$0^-U3hxxy zXxMw{W^6nul3cgZ^7*Tq4S8DpfZJ9l+UrR^;iy>6!d5r)?~`Jsr=_|Dwofa(o|aoa zEi+oT)o=Ox6dUri+>HCR!H|URX2#Qs*Z(9yOEa~;Z*kn{oif_@(r?~)S_OpdzPS9W z-v*f~BA)5If8ZajBtY>C%8*tlx4b0+Q+AHgH%JX%tm};y+`L4NKh;2h4|lks0eKf(l0=8#m%-{pNufOqQcM0@sc+hq*8oCp|Ox`6k#gyd%WjW^P4{dN4udgeEq_C!zujID8w(D2*MvC?+?#d3cl6Qj;IU^qIj_U==xeU zfa#O~kcG-v28h3?Q(W{r^DhnnI|kd!gFVD(XY02BJS5)y9b`wE9#-P_*kgSt(at=O zKC>GxsSC+`5twEZ$`oWD`LR4Xqv$IZJe26M7k{7%aq{(8M`Z?8jKG?+dXL2Jp*)`{ zLcJG7nvh+d%6e(7V)PV9oe7Z{ZI2SkEMShR>y$132DLY@8q1Rik+||VV4?Ut5G>Qn zIa(BBeatcbvCyreY%bhs#&Ei6qs~}J9zrkoiZy)KtvcGrt}-i^<#b8u=94fxYh|NC zqW@x*{sI5*R_O)7D!n@Yi$6cUxVZQ~xzc}wO7VYo|J^DjK&8j{U%xJojtExi)zQX( zSfvE0^zXsJ<^IaQDWwMo2YY*a7aN;b8~wZ6+gn>(|Ai}ET3T9MTs;5&{l||V=aUoo z*_8jzE&b1EDSj;dzd=iTkB5f|Zt2;-+|sk|Zh}>M+|_kD(0}2Y{o7OY zw=?Og$N9X?_pGUj0F|D7EIn_2bJ6(XqE6$gUg8pamtdX}tkPfY?IR;2|HhT}_4W1i z^mKJ~wYL+r(to(p#>Pg1Rr>Mc$Li{8f>nwy;U)N_S7oeMCA3#X@T)@7s{+t@nd@aa z_kM}*X-@7*M#gzU{8c*YS3)AeC+$cMz6cDw^wItm96}&UFYN8FETwgwv`eVX~6O)%OU;Z*QI(s62q^WhLCVr&&@UNW6m6-6Bn8cOHtt(!RP2t;HeEfJ0#-Ci= zYwR3X%nWPHtpE6=*Ql@H6z2c3O$k1!uCA_+qT+uLrK+l`Dk>`fp_IzW$^E~TQht7Z zUS8h+0+q6{vHfSIl!2a}j*jlywQK(;RC+~5c122ZMGU?I{iBp#0e}F3DgAe-l#Gbz z|DRQ=sBQW1|I;dM%%ubc3!C+4Jo;Gpf3r$S1}=>HYfHWrY5#XtsR7mkQ))a=Uorp5 zakW2F?bE^VHGF?<_Qb1##TK8-O5$73xR*P45S%h49wL3+G0Gsl&mEQP11Wc2{}^oi zxS7LyRiF(hw{QCAYkZ(f@w$tiDl_d7+&4Vgp2*Q{_%YP<>E~iw;HM$`c^9YETC1|w z%;%o_8-v%@=rmhC|K6SXXm$h6diHB;;j^QfTcb?hTl7b*N7t5oX?p+4&L zXm@es3xUf9AUsQGVmd;X1N25Q%Gb^5<_oJ$dpc7~npb)`!3**!IU(cW^)J+OGP(cV zDlIHtiQv4)lV(S%h+2&jow8ny7TYM!i(+o5ZjX_JG_DfeF}6;Pd&`l!7D9b{);#pH zPw^;eu7LIWf3iwVIyP6VYst_GaO=X7jWoOZ?TvKD!V)l}M5oPW=G$D9oVx1xB{kFRm4I7^m0!i0U9ah9>Ika&eb;)Sy8;;%gH3O}N^dIe)H>qf}I zGq6SSw|^>rlw)s;8XbaeXJC3B_zNV?m{Ist&RWsHO2$+_?Vrq(iNKP-?fJiU8xnEy z!AwKr@UX;1St2&EITf;lgjyZJ=ltKJ?jO{Dcc>Uov|6f&Hn zc~(a`qnV&KkKvLfK>?qBL_aq}NDNvpJ<=_v>HH%fax`(S`30=y(Jm!h;@C$iS$Xk` z=MF2HXjEC~@_0fY;RBHQ05HCr8Ca$D_^pqF3^o}b)kP#5;$k^L1t1NkJLUmeFv#5i z1owS(&G4>R9#-pyz>@zzOsFYWo;RGQ_kfbRIYShA6A`q8i=u8%N5S>&%(5W&tpy4h z<=`mF9H_EN2X(+GK%T=4Jcr!rACf~AXDgG36i^bzStJ)cNpdMf6ht zU1(=ivZMtckx8ImJ`o`*bzP9u8E`TO0mWiU(;>6>Z6MsKjFDU+$Eo-P`A#rB<|1{D zEvem(={P%M*3w8@B$_U4$y-3QK+gJ}CP4g^Im*MI@!m2dP^^P30qcMBL|+BS@TY;< zD9X$MfabeZ$aUlhHCe!jqTsJWdB!%O6_GG>h*kXSGA@Ns)hA6niG-ChCFv{q#;^#N zXI{GKo6R|~PPBofq|2S+Gu7nNNus3vgwNl4Co=y;6UMz$%KR z2 z@q@!6AxPWY2R$0k$n*;5Wd4M?x%GOdzJ2T6vw8IIsZR=IfS`xh$nMTs#FTlZN6%~I z<`l_i$GA#&?q>^uWKVdWgpo=;A6+EB&6JL6J+uU+R(=0C8Uj7it*TzZ?BLR7TQ;!UH>`Y|UocbP|_krH>g~>cf6IkjJ$+=(g@WHvF zv${>`x^R*BuqWI#mosyFN&=~^5{R1GBGzJ%&Z28-xGD0shxnF{<*oRXZ*2}4Mc%p6 z2cC#`E1VzBMvG)lh}wK`3GA29+(5r(BrsXnUjA`VQJKDPzQ5UZ&i8SoM{Phv3;Yds zdPrY*Zd`QJpEz1Ex7-s01;9fIWs8fC1XEEwYL?3)W6myW?DF zWvP6$!zx6g_>1MI?$~Zo@~E>_6oSy=eC0$Q_A7k}|6o;d8v68phf|DeEhigMcDUWz zICF}&*e4ru2VL73!5BHy`B7QWCGfz3iOI~hs%Zl@6O6WXMc$!rHj{BCy zwkm<{V>g!r%UU4X4o%WAA?U@zN1R zn9q$A8m>`OZ=9p^P3zlYLDTYq4^0Cf`Ue)r`{xJy-donX0|{y>0wEM0k^&d9$6vQagCF0>YwrICJp|d@}9!!7x@~p0KQj z+fwh`?l9|Z0 zUK)o{$Xyd~b~Zu+0Ez(kYdOdm07FqnycG+tvi9AyqCsMf%aJy^V(#l=7|A$zB97?q zD3k!Z;T<8uV^L?tv6T1ysZx>pC?^#FV{Pq8JR2wG1jJwv5;#xLA?&9)5`knVJM5WY3Ro(=Z#zakn zL=Cb;c(zp?E>Zg|UN1FC`7B-l7g|*p!p8WXxE;LLhS+I)9E(8^i@oTC$!|TAJyMgs8k676Ci|WxqZv~I#8ZL{QbIga!ctTG8KII%(1^1X%vnm}Qj#X* z{VU%0a5=C!K)#s`wrPBCA0E%w7q3&2R4ATM;F(sMnpRqpR6d)gcb0}dORVuE^ylhx z3a8&UNdKIgC^eg8bDESao*~>$Su7V1n8YJ&Vy`s@4mAeN_Zk(f6V1ChsNaY|t7OdC zAcwHz&^{>02@JzGW|&iFE+&PWoMfC9XMs&gN=QhE=`acnnP17sZIE)=O9;EAm_=ml zs9fyYnZ+o5BsE#&tTo_OPtoa?`O5&wgQVOtK}=)lrm7>4XG2PsU}q-qLF|Vv5Atm} zL>E$xC?X4-7Tx9+oA8iEWQpQX+vcz_4oU_3kxg!i1KBy+Pnzb?&*g!L;?9e6dHb{Y zC1`w2{F%*iM?+uc;3&T*TgosMkP_w7GUn?U7CehUa%nr%C+BZ?X0gVD4-Wy7I9R?g z<%S$AsV!WaufXAN-k@iJfnm0*VG&6?32TUt$WExnG8u_K;uIh^(B8HqW_*u=443j98HY|O+li_SzIwB7EqMU?Hj7$1ooN`lY@*(p_OD5X$ zKJ&eA-YJf?EuXZl5T*jha8ndVWP)`5@ef6D&|@65fv#k#9;hU+v@T1z!k@8H197rt#ZHE`iUY-MOf@2o*q@I6_g+ig zigXn`CnU3LjnrzM>{e2FBVTAcRH8m=q;@Dp>@XH#KOhhkdG+{9E_N zD8@^-VR>YP1$huqm9Vq%fs}F!(hV z_LUH-Lc>cP!4krhYbH!W$l^P4kP$f;=n!-)OfK$7cCnNL#V>!Znh&Wqs=mYDWMP!8 zha#o!2~{wvdYD5rkA;NYL-PHmR;A*W!Xf6Spyya2hb2TI75R)XvLl-^eC5;XdH8x$ z(Z{AH%hydLa-=aN2FSs>7Jk|?IdVYz3rL4-lMs$_gl8=Q)Y{~;IBFpbBGD0GM^O%- zkR!sXfH2uErfutUTgyxvrC005d0V}Ao#gL8`f|T_ku))mu(g%;>o}M+7gBQcpA6KT zqar8{vQA(u0hr;(|H)Vyh#`5&*mL5(N({E?q_>(IeR6nSM}#9GJ*Q~W>x@coSJQ>d zqL9A_h{iFLr5r@#SaJ(T$X7J%hcjp%k0M`Nr5wcGd_md$>N)aFAFXvpH@1neFVOx| zvLT4D#G}^4G~Xao4J82!lkmk#V$sWeMzJiJ_hUDmPfqh9Zr5NFg!bXTMA5`f+GV7`)&D zQVal}I+BZLgWI#=1vQYXQL?*okp3mukKC4AH26KPMNDdBytFTaa=T0`EbCi_$-r&42Eo9Dnd^WcBSx_w(@wc$7I~1B-ltB86^DqU}3PF9Xb^=N7GI z_d_S0Bj-kKuyR6Sqq`sFUC9E?r$?u)-rn4)ir!K!w zY!bPnNY@L;J@GACaWIwyfdyBq`53G3snOrnYFaZZu#2$F&&kVFGs`S7goBwn7p$>j`Hwl30_5H{DFJZ-v)iH*N6GY?K{tIKnNQV~h(I zR`h<*mEng--b9mV3~wk8SNp%1n($ee(b(>*U~CqEiqCKPTy6Pyuf)YHCA`>vuQ@IY zrym$1SuozRS=}rm+RAzHDiB`i>bng(pgX@s>W#*JFka(|>A~HfuWq&Zcpzt{xl!&r zl~vtpyhMJuL~e0qKPI?edBup8*}HhUSDLmL;R79nFJEji-QeKw|Bnklw3R#*8>Gjw~IcH?b<)q!XGr+)8A$X*Wz*^Bm14Y`&oyFhE)$mafsRP?VFD9 z8G!r;K4yi z*;5k8_FfGgWokVsT7ub}N=vAA=binL_B>M(KO5Cb7?-^iF}R$Hz4S+{D&pnJr{A1S zeMuT&zY6QJ89T8fft=AI;%=CtkS;3jE~n;;<+_!X-#aO!$PdDF0FZlgF#~C zn(_HIM;pBvk`GUg$*8SIBSh9lot6cEPzOE;cXs{jYNna`xZ+--%HfV)rE!Zd3A0{# zpYG0hh8#apTa>1`Ve|IMV9sE%8O>B(B=XIV0PnNE3rwik4E~UnE(z#Nx3h@ zY^p_4=JYJ-Yb+N>PYmhH!;`Iw*qZZvrYh;M;XD6WrRLa%KWpbPtxyt5#~LE}8hDe; zN_znS+^ofRAg_6p%LgGvMIK($H+L!`O{bx%p$JSHD`JxDemalb}qN;4Wh zvmFH69#c{FNP1Rgel0>zMC03CLz|+ZuxZ6dzbEfnkbR%Zdun76W)R!SIz6kAQ*h7N zZTiv<<(#u~QsQ0|k=*Tdx0E{4>}!jDukYp1#K<*!3xZWjR(CRBS7+St$uH;KOzs=w z^-rd{0<8_5{^HUNX0c!m4;>}t5NsJ=PFN4CIsXkth3KbTr)C6zS$OTGh|=Aa_>IXh zD_|ptlR7UFRHIFGkKn{Y znV$sneo3-M(`=o1+9^k#Kw7#(zUfAaUCW>0J)4kf`^LVqD0{2dm8S2~=h3f+(%{&%1jQOxx?jDmbWxuhAwc&|^q;jk>90Cm54-;?5fas9d*AnKA zh)G+D1|eX{&$<^|?li{*TBy7uVuiWUFg!b!h-q;K?bSM+O-0#;zUhjYy#cMhRwL|a zYrCuf5oX}Gv!e z3s9ynS$dBxkPcP{(>`QDMUszEC=z~BljN7M9>qm>hfAX!y!$EFk>LHMS47Ve*;{^W z-4nd72;OcZX6VZgdhtD%$V$U5Hf7x8 z@kb?bp$(1|D8dyjo{g*ARX-7omG-t!GJlE|9~={|*@CkfmGlVM@^N%9D9dzmL@`3K z>gX*J{>P1jmF4mFO>5ko2$DzQgLr=^;Z%^CpRtSTx05`lIflY3hhjnGTZW=j;R@}k z3gky8;F^-hzp_mJOhNa3b@NT!u*HpM#{q~<;;kLJSxse4-862IewO3kaE6J5^p;-) z9IX!}a~zOG)U{O!G1LyEuFbpYxyf>eUL%%`FZait+&HD|$QKQ$JR!FcrCEdV7t*3! zdYA`nmB$ocx5o>~B}@Eo^rQ5SK}g|;w#wsY65bm}Mfc~)h<8w=?9W63;L_IjeZoHp zGd-ecNeKqxCG?_h{eE})-BPd0jV8mlUAV4+^O1PzQ-7!5>M#>t>fX=O;Qr%07h`@6 z`2Zrx-W+n(_MwX`uaDXFR>gQq1w|q9cK!aW?yAR6$~x$ps4~3dv#`Ad&#m}!x@$J8 zDIyd&XtWKc*gDHkY;6rm$_x@bmf+4a$Ol4=1|dmPDOP-F0WbgHDY`#(zl}CuCNakg z_U2Gbe9L%shhm~4K%hW{$&4{_U~Uz3t1*S-R?M0s>DN7wZ&RjV`aAyqJ4B`#bTbYX zO=|MBe??og%ZA-P3-{qWD_g1eEQ~AWCpqKB6Auga-Wm7KPl+^K7x#K7B}dV7u3+D? zEiMp`LzA%Hkq+bSydu5GUXNX2@uLFV}iLY z{D5`)nGyr#b+o!2C;RFWK1hB-F8ZD8*E`P|1>-yWBD3C}7O?+dWDy(%1l?x`UP4?_ zx}+>`hn|591zpl6n>TKM@EouUamo0$XDOcSc~9?Ydf*+sh0Mfu=BboJc*t@HW4S5w zSDrA)Xifz4mI=e!XgF`}VF*3OA4cLyB&`$|sD@h|r|c6Be7>y3AA4j9_4jP3%S%bmAMB(COSL$SzcULbb-`s(r>(`=YRa^ zc5nUd^X5jIKiN6NqYY2e`qLNhy+o=k)<%)#=<`M%?n^i{&2CeYPJT1XY(T;b0Q*5t zR#-@8+r*`o0kXvF%#%}{_iiu4-sE2=Ch=6NB@zyI<60vk1gzwSee&VhiGsb>UltrL zmN$;uwv?5<#*kO%_#U;>?w>csf8t&pxrSa#p6ePggr_uIqF69Ww_UFj z*_7u}S}{QGO$6X0{ARLI=BGWMNMD|QUYrxp8?4n>bMB;1azn=}%w7@7TVG6xB5LwRlF&CL{R5`vh(D|9dqQuZT- z5ItuEY{sAFyT1*A<^ceB7{sa<9oRXYNzj1z%_7?fDBt~Bw!idWH z^OXqyPAr&(Anj?B(h?%c*&$X8;M-v#7Hy(lND>w-v6f_;re}acL>c$RK!vY94O~+YC`I) z9h}S`#{IhH=ADkr2k}J6%Ff%JPZT<1wL4YzJ}VJ-@1%E{=6AfRmEyyI=g}mnwoarg z=Y%fjkz|ba9V&&bV8xlP2k+XNPam4qN|+KW=hO5!4N95sNuW+aJBK7ZTmDwWUo~p6 zniqwf>eLJjMMrbp)w4l1CZsOHA#eD@pkgGhCZVRn{*7BoO{YpOl+v!Qy@mYBE*UEL zf-;bJ7%7{GgvUfDm12{KIr6n=obOJR4=u9=hL{x!Ha~^Hc*1mn(7SC9thH78A_XF? zd&7bx!X_RSl&Lsg^yP7aWVOll#3W*9+s6VpY(?R5b{JVKPr_O{^=YUmfJP7qJRT^^ zY3P&MTj_&Q8GDbM*ZQiZK4-Hi)$aKV%)}YW1>_BO=06ww{EEd$J)UYS_(k#UlIKiJ zr=)bx1N{J^z|#=*u<&3OifYjTHthiwJ9TA6wVOQm+mQfi}T^M~eYhvqwnzE2D-G!G%rf%qE?0ZX*Q z%Ur`NqQk3-!)v0N!f3Ft_V8xV@YWN}4Oh+W+Tq=Inme7E%PhodT$(q+0w|V-4x2S* z5;cA)jvPN3nH3%R?K<*jP~*tXe@KzHNj=`x=+mfOnl29VOKfQ3`Ou|~lqxz9baxc| zaFqDzD2c@=#BG!`codp6N>(sRUN=h7HA*=-3WgESV}l>gj3Td%QE`t^+iR<4Yvt?= za&0%hcqVe0!Ke!jr56rsV;KzKQJ?B$pSJTq2^wMd(OM)P-sc*>&I;NW9p_5YN-A%QhIC!7Bs2T9jRy%_j%Qha2d2>Rdr)|BR{G{CSO2O zgCJ=c-)<>DC0W&^GZi#~J0d1P1!Ba76i@Jtv~BLtg?7oZ)p+sP#EGf1JS^I?N6D4JQ6U%Azwdb zv)hN-N2|Q)l5uR&MQeP9g_FuU1~_Zz$v;(1csw0KP%W_`K5`JeQt`ds6n)4eU^xQx zZb-kAmcrLf#jijnZb8OhTH@ALtYHJF=#IWV-{gp=L5f9xP#f_(9I4A`5W`?(qy=Vg zWoB(mKL#*}5S_IbnDZ4djVEMHAA` zV_}g~8fx7dMjOW8dyOSf(6pBruwb#oU{~qqYY#A6p+TZh0#w<3_{WW(MtK}CXwO{tQF0Kdv z=#f@)yqx%o2^7Fe?75W=s!I>wC6J;2sFQGlIw=gX1(qHN&@|`QfNrFNyC3^$M6lI!c6i{D&<9e~ld4bUn3%x}j==&p5$N$09U4}LJ$B!N#Y>d&P8%B4BbazM# z(j@{CLupWn(MW@oNH<6~(nvRmGtK}%5^4T_w=vbN!VhNL;g2)Kw?tqiMbwEc0h<&9+@?F=?cTSBot zO^F@T<8Y$kjD&Da8S&)V^IGfRE)e>k0VQuSVQ2OXQppscwADjRnhpdsf#b-elixdV$=9n{xjg%ZHFIWV@~^JFNA9 zj6efdr$l?s$af0hVE#ylvqBS!qGRH zNYH^s#I6G72zKfE*0_JIk7aU(Z3l5NQHanL%yZu`35Pk`iaCE&b1wd{##=}54B0C) zvlV5%ziwsL@eu7;hX}6&Ifm@HXfEvib-q3TnKa{?`$lI_EPYHk%Ji`Kri*!0fW?ip zuVdMx>$e%o`r$ni8s3ZH&FSi**^8xfbe#nF^a4ZYRx~}YtE}ax1-o{ohh^v2Uq$ow zyb?m=KV750+B!_x#(F>kk)h$p&_Ib-E)`47)`>45u29Y>cwJO}#;?qhUxo9(u!n!` zJs$6ibx5Cv$29@D>bh#hO=31S5}m#iJaBN7@j(=tNt~Ww}r2A>Pa8QcKd<}E+NGkHg4pe`RH1jy&?pSbjyr1 zwv8Fip!h8N`=So4qY>((00h8*ucqleox7%|Fqsj%{b@{15_^DbW{u22*6~&u|9kTG`<))CT<|Lw5VWPZhEN zH6-Y%8REw1%(-vKnsbd(Ac2$$_y7cm^oG)!zK)zZPpYyFQ z(1z)~*CnBMVWRgL0K^%Tix#wv;!30dN|zXX!#9Bxq&WGS==^0&Y+df|t#zms(4|cT(hdP`^1&>6%6O5$)bLlUadg1OrHuER*V}R`YYbkf1&b(`f+*{l=pspOI zghW^$%yeew#u_`Ij^QS(9ODT*+&$Ga;|XbbSNX>%{L@pAzFCyB;0tH7sCGPOI_!|> zsP%x4w-#zY{FAU)qoty9HV=6MwYGfPZmwPmQFSe7SAK~%zD3MvMr8lq%jx-n;r}rGm8S52D<;d7mV`n{b<*~`1ezp z922sC%yEJ=ErcsE3J%Q5d#42%yP{-NWcS>u1|fq&~OV z@k%dCR-!|E-@i5Lt>pV)sn080x8CGJyX*USx^>t_As`JwtiT!2)--(kz2(jqsY~?^ zxksa-H{Nz%zYe3IKfZiED#H-hkE0oU47Yo6vLB}gfH)t{DZTG;U2o~Ve8B0Xhl6tvHdA{9BE#kQ7FW-3`uCUth&NmPy-yZZa2 za(`OCOl{C?IH$Rqz?4h7@02IUtuQ@XRr>F>HC{*HRqx5)Cuhk1D4rATD&CnZ_!20uqg{@H6UNEV>ev*uQi@B0}#!B z{!C|&)g1Dd1znK#n$qXkdOdAq79}H8`Fd6Z}CZ7_bw0`-G+}Zkl zvB`^B?qa}Mp7Qa6!lvnq{Q1pyV2VstffjsQmPFb6+Z{s)OnGw#6FPxtbv;ENa?^;Eml@-a~ zeMLewDt3!>AYcu;lFH8?;HIeQ6(Ao+k~9tOXj3p_Y+?ERptnSCgIGzg4N<)hU{dsHUm`AsX$xmkW2{lQRPa82-L*H~Afjvp@A*UF zkOs|)km}5)*fTG4YHW_H1=?4}+{)|z7xtm-J=La6-LMO>A1`)(>ayafZtG4F8$8lZ zE0FRut+73J(aoy;7D^%Y9;wID@asYIXP$qZZnvJjL|iFl>Fi94X66d!e|P#`qSA$L z_EmDLd{!@oWm`H}7bWq}81l=1l;@hJLVmXTK)~nObZPy>j zQSraLsp9X`{k~=Z8ZT3ZE@riVL&bAh2S>$)vbA*H#1UJyCkaLo|2IJjToqE z)Z&S`N8=E-b)%fw=X}6ok6luamWay~2ntg|R_#og`qKeI__`i)lI8KT9Pjgb@4oB} zacS_m#HL1c61JrGR?yA>$wSjZFUf}_1g<`j#e_cY>ltOLzohx*wljEE#(+riH9G1r zMFLll1OC6)7C3+AWg)SN(UW&bZ{AzHA0LW2q|5`|Ych>N6^9+P>nxgivS}3?gWlo4=m(>PV!%EWu zoY$z(%*nmrdbTz$R)6>H%c$^2d@ogjTjZqI3Ma|dErNFK3DeNkCKRPs@ zBF+jZYnM4S{tn=W!-|O~007pe*(C9hLW^rqFL#PpSXN}nXN9J6c`TNhkkh7U{B7k3 z8XuCCAEyNdY0e9r+_`Q?SaH;1jvAE0nAVr}AcO8B_%Vhy0Nv{a_=lSE8R{Xb`>E6p z_fY|{l6@{qd|9lA;nLeoahzGKZ-0rzSST9mmI{&!pu79xHl?#kVSk9sWRE>th+`25 zds+bJfCRtrQc&dp-Ksv5J;gZ5d)T#coI$M^hNuw%F32@ zwKvks)EYrKps!tR4{aUsnu90=fLqNxA6K)PgJ7y_?LK`g5WK^)c{lgut8EC7>Zoe-@uKzX z&7|l1zptWm+qNNBK82(Qe>VYtKH?a(^#-u;Zk+g<_EUTnjO^Cl!hh2?uv-GhvqWW4 z1RuuPv_76FO4ZR)=C=*`1t@aH8sO_U^>U_~MC1RfkBsnV{*1~8(S`BuGLg2AsL2VZ zq*m{;iL{SCeJ7k&#QT#=I)JzucE+4m9X$pL8?*i=oH@X|CzKj6ng%^Lvlnm7UO$fD zbW#-nY;8-D?hoTiMzK-YTM5~jcCK9s=F8@8TnV?$M79XLBdR%27Vw|_EgQ!3+8zR& zzk%2w2}|}@oz;83_dy9S5h(m418x6-V!7r3#rVDQd|h`pZ3g4FzbM*f+Lv53l?C(b z`8A3aS$x$ra39XWarx;ouIsE8Klh%o_A)b^Eo*Am!my<^3fKyLY78BY!C7>MZo72S zK7|oah52p?71~sAeQtA(%xKBn7*#7wcHGFjyVH)W1cG+*{#0WYpC-RT(704hQ;m2L zi{1K@lbA(HUTzT>LsOQY(5Ji<3OGZ*97v!%9?)(f#b#D{D9JB;3a)~X@vYRO0)O)CK8c-ps`?UtWDml_x}DpFxvS5HJ(5z#0CZ_}-L_Bx(d za?OrN?|57K=i$*i8;vKvmY+37*ad7DpDw3QUWa)#XyUzc(!PIIqRfZ-_g4M8!(0r@ z&8=OUTX^?Twd>W*EYOzphs1!?+!^GJZCHxL_rs@t8~J15DtOqsoH{K=3(eZO*&h4! zYwsHaiv8rclgLt8X#!ws&M^>aq0~nj--P#4p)_^M^f)dE@iVUv;+DIA z3?e>uX`uWt;9>Ot&Z1;jcJCE_u0=Q4Jf*#X8mkvr5&D$`|2CNTt!uDnvM}e8Yj|uZ za6Tu1MS4}B_UyP`(64uGQ) zh`WddKso++`R1l%2w|oo<>QP~x3%86@$oDJqZu}z42F(Qj4J_32QUX3av40+HO6>m ze6AQFS&%AKpDNvF1a86Jp;KYm1!Br%@SOL`hfFCVlms=Da4-QKFcs1KFx4(wjflzR z85sT4=P$i^3hOpbZFv|QV z0TP!hoD66t5>v@cN%G(aiz2AKAd^Z_kGF-zV!|H2fU=)HuycSU@b_az_Nuu0B=`m?k z;RL2$^ro+4R9l1b5>C>i06r_4qTvyLu5S#)$1Uo0m-WoOcXI2b*!dO&tpxeCpDGvjA7 zmHhEXqVY%J3ZfFqU{(-&(m*W?ARX;M7=ps*s2(6(NE4(3Dk+51b|BFiqd!Ro7PX~n zU2JO$jKs4=$)J3z4ovH>AmYJLI)6o9P=x%Hl>+XbE#V8RI*6nB0RF@RP7)p=a)4_$ zgb)-iRjsY$&q{Nw%#IADVU7v_0qeyNa`r80#6m}OVo@C=!YQcBd&-bA$ zB1}trV=G|H$({_4aWGwX31KazT{rkrW1>uTp^Rx`zfuvavz@kUboE;atwhXx#KwWL zR!zf7e9&}=N44KyT-0_32M%&uxVMBr`Stra9&qcT~g)xZg7~ZYhr?< zUcA^(0vk_%$3+#v~am*x^fl15=1&HGRgeflEmzTD}O)dpwZt-PFRyUY+|oko(E zH}%{O=Nn|9UuGg)W+BXk*tOuO9C%*-XmI3BrbR(VmIlH~eytAGIm+n(#Y!Pct+`V% z*~(}l4h!;*>aEK=mOZXA(D(SVk?_1a*Q$)N$m{&V{(Wr4(9{J?VsJzg-=rH2Jv;$Y z>QtF(5Bl5A_%ON|Uy90!y~2#c_y(C6KvR)L)!fbfNd+6=!fpF6DHStx+6`x)bw%-z z@jMJeTxSG4XA;K)6jg@HFhavAmnrJpQEE8)cr-pN|FnwW>X+L?Re>W<3W*L0C;k9F z7)o|n%YFR%!BrXb3;inZvABxGsyc2m+kFd63y%fED?WztqM~_kdf915x%*Y|NCv}Z z74mcuuSEN*n*^)hX7dadR@up=`*mctUk!UI49G_VXP@y*a$}8-70+F)B?AgVhbKQqtoJ@Mu>>pOgJw}aeMS|hDv}q><)F&^CPf{|gJsCzr`hYX_ZpkF{ z>tJ53W%qz()UgfHeM76dvzN)<0F8sYwOv+kQPfnKlT;7ytxRp`AQ4Z=A{RRN+qt=x z<|=-MoZ1Ni@;F01GY90877lTt+y5fA=SqHJx)GgWxM+gy;+^}qZPv|QCy!3{Tu-kq z_@3O=#6>W8KmcXDzF-4=;dIxf?f2t7p7~6x;k@>F#1~`lM2*Y4HkAj!$IXhES zL$Fpof%~tJ^iz3szmk zG+YSwUsx@iiCDnt9qQ0UG~W1R>yY2_#!3R%=Tx*gceUgq^6F#4TBK`*%sFSY+Ne6l z_6r`PH{&xGCXb=&hgj?n0}{9APb{VcHdO^Xy(9&&p`x?{`ufCfPD5!vz#HE2 zKch2mj6Wy{Tyj~%$1blL1)@ayK8Q3Bcst=QOP^r`E~&sUv83Zf_X@F9)I~%Gnp9Tt zRMi*DH&jI)287{Fmk*6rpi5F(;y=Tungc52<%t5dqL20rAcKMnN)$5dd{;cVkw2q((VH+)los zPW(z*z;`s?H}0Gsdt8<1M!C29dT;RBa^m`-VTw~dQk2cEmhjU>;gz%erTGmXMb#={ zqbj;dgb?<7<0-c7)4UvWY0Dd$IvDnskW6R7!*`(0(^LSC2bp*O?N>&-w-&ZnJtX;{ zyp?qmu+w~W@`39M^=lZCs+& zQo--%lCMnH0L{3cc5z0s)~%tm-8&ny$oZzoA~Rrb7IO&}0bC0&1=S{B^n|anb-UhA z*ICh0@;7li=wzV}_}y>OunouO$@_U*bt_TN_#yD^fP8s$5@VYvM^y4EbIQOV39l9} zor_PaiojHnvxu0B^wo#&+PXIBSjbV;vRxyHg1EDHW?Xy3xNp|LT~;SzRs7bq070xD z^PIyqcm6gP+war-_^0oU88?`g@jd8?vH0I*oZm47Y9m2$-w+_ImaJ(Bg{OfL z(@mfDC1QWJXH0JyW@41JiI+#+XIg+_zwel)s-XW$Qg_I2HE5&g+N;L7s#pC#S;OB~ zSuk6P3QSZPAVNNt0R?WPeq>5mfTR~`aBap-f?1>$N8K-JP=Sq4+&=vI_D(y9-ZvyK zZqjgOUVb61HHV<>OGMir*FOAZ0p7Ug8bV^7)4$Xn;oRpa(~Dt z^?m(&pD*uMFkVveagad)JU~vb$@!-0Rco$Du#5DAi?U4D>9Fd~z3M}V($>g7Cnb~=5oL-Kka9P2D zXF@7HRYN_Uhjl6|{4?aEQ7T1@1*Urb=HEKf$EA6Pf2qdhDL)*`m-jE+K(yP*l$^t) zdi#jzl%MFoP!4`;j(9A@#H(y=tCS{y)&*+t1k=&Vmaw2?6L{WsL`9Tu>E|c!L*^YdT;|IR%AR#+`@CATMTU6E=J+1+o@`TBexPYNp0nItNN&jSKVRtn zFzrP06VrJ=hs)xf+^4{+@!6V}-!~)!c-oC&X%8iq@j%uAAY>18{?96n*YC&Ss@CskLQ?hj6G$E_LY{9I zs74bq4eAdtR3<4WaBH~D4&jLeqr8;a3Y~jPFo{&4OmsdvkZ%}o{Nuy13AaP(-z~Tl zsmD)Q%#HTij#N=9K~`QCL-QsK$N7NsdVtr$)X~6TI^rY+V5>1&g#Y2zh)ufAYLMi= zG8(2UQBtl<$iID@swD9koTNr;v2CEOOe6;H&HH!03&VDX0n^@$>=+iX^G%ADJYV^x z5S4r}YrJ5fX`&G>GqL7~AEV;oIwti=bJcWXC+;Bk>2R;+rB`WO}hSyLjEE?xev_ZH~hG86cDu-Q(vC$*f~r*pk!?X~;p zue|rm#9P~mic`MUQ6Ia$+rD@!)&`Y2p`%FPK26$*P5rB~tQYZ|xn2E}U!++LLP4_# zi$UQ$>Vp>_q2wxWAk*;Y_j|JnhZPl5uN@;liDvC(8x2$9t$||RKvWNsisEX9PNlYJ zK7F{hYu(H4&w%d7eDBmB#>vMz%MfYCvFK!as@itMBVdGLu6he)D@)``+qta#-wb zz9COG$@kO!)$06r-pZlYy_bD*omlNJNOJEEE52#?@-_ckA6k73?x(cdDQ4cwYJQ&_ z^d!pk@b>T0OZkAgk6*02v(@HoiMT92+MphZIyS6V##?2-VU3ZWmt&D^?;<2ew(!&; z`GD|NaiyR5ue4o1zkNq0G%%F-9#Mg?0SP8q><&?o9wTwe_IoTb&O+&>KIhy*iTsb5 zo+_M$(e33&Lt5&T1RRa-4PPtXL%gDYuOc_}%@{C24y?Pqa|)*)Ddkv`W4{>LEt!od z^n$-m$}1u z=c_tYGa7HfTa<$`BTls9WeVO=E}~%k!7P?H_~B9?cU)`=v=s`mMug>0vjR` z5ZlD=I#tYgYF&>KL-i`h7cqofEU+17hPr5@`lhgUD=<7)5-N=dePclYc>{8Iin<;rbIXttpW_6&oxYQ zrJ%1+guqa-dHy=gHxt@i@3R;Frd`T$JaXtVrHuePTyO)ojdV=zjk8M6a|f$n2W@G6 zpWBTp$O14Vv;9+JpbC_Xdu%eTW-ayadxTAsv6^vRI9-eF z`Vq?T#&o#`;%A461Oz>CL`HB>PYIDY${4UPoIrRZJFRibin|X31Xw>x7hpb3*L}*F zLm8I8`DlOD@rA(NZISvJX81(!us48IJuEz3g%~X&*Q;^I=i&WF^xY@pwt+Noy(^e8Gs+uhIg~=$IkShOJ6962==HtemKn6aWS;KR|Sw zy5)7EuNuQ2w23iVb%${M8`z7gjR{~y99c+VZRa&SUjM8a0*pqx!3TxxYddbfRAO(t zm8!)s-#OvfKPr32?NXarnE~iR;Jr|a2Xv7QIAW%5dA_gor2`hluTwax>4Y7SjQYyo z@H-Fxxy$X?iqgjnjndh67XqcbPxADtdNe{G734z~C)uN`aDcxqgchLZXILyRiWMaN znd)SBuYPZ=!EBy@maW}|!KM%O6h;PlECqw$1H%xb8|K9+5Ah~!7WWgZ%U9=+oOr}B zf*>Nu2E_P8d923KE-`&sUQAJ3%|6k-hiyi??n%`-AJyCNobOm<2HDt=GnTYjgO6h8 zGzRgX5j=G@ z#Ct9|Hf{BJrT_QOGRHm%1(V2rkU5SNhv@Xl_MeFl^AqQAtQ?QGCWOQ?Hrl9<`t#%$ z-dd%WKMy@(*#8md|KDk0h5tJ(3@(gxND60I^jA@&DIf^8RMv!7NO5e?uh>6wd2?%o%^@Y+(UYh-&@+w#&bD!`qLlJ>h2SZe;LC512h;beS&L(;bLwM zRKQt)l(83(9zUE8dwY;$Mi8iTIY1z~6~+Gg4Cn1}?*-|8F#z^2F>r)RwrB#6MB%-| z?0m#!-S?~TBz-)=u@T7gcFVZsJl^o>jgQ{yHz%_WN5@LQ7CVAmCIx)7*vOPP2DA4^ zG6s*sl9oXqutE$A{+}1+8W^_6j5GONGvOF0Ie|xZx5vFgv@q~-Zm1xqGPVVy+Ytf}{!P)q zj4a@g!jPx2O?0w@kLY(#%<#>eIlit~@x=(W1kH^^fnS}05An?@ruYr>>E7AGKn6O+ zOw_McFpKTT$B_7u7__YUu%!?*-3UW5C&M_sIA&By^`Z%sP8hrTK;Di-fPxy~Dzdm= zWOmHt1nepK05@yalaMlS;>7N0()Gm*>fbcBg+1}VP{y-!#)nYGuW(>~D77mgfU|&Z zY#hBArvqjtSS}zz&n@F@GY*Xw%t*(c#rLlf+Pj^r}8f zTwU^_*oRKt{w~<9kM@RRpAfQ%+hV)D#x7-|YD)wb_E8Jx!vsU=+VC-!6-gFD==u9# zh%G7zCXJ{d)6yhdKcAzJ=`7C?Ln1;;qJd?amA!~BPVG3^*5!+3@xOk}H_OQsVv`g* z$wburf{{raHFn^q`TRXlY}DBn*=q&tFhzO~duqi3em!K&j4h)u2DXgd-v+@L6(n_F zp-BrXZlEHitu2q(IExh~>+0#FZ9$GD0^;Eeo;76qm8624Qnxmgy_{iNZxD<;vz#fx z0*4Xg6`W;m;e+kTXNIUDXz-MYv991kJc*`E9k6o3$f{^0QMkd|SS{GdCTfIg;XXjx z`DuV43%rExFWJVErGt>7eyn2dzbPsbBKQ;2aj7riV{J^|_ zY`#m7=pp)RUb^oO>=|kOAnDD0-TcHKZ%7DfU_TXIi1Fzt1vfx0^+@tLv()>DxUf@t zx(~{>;2xSXQSwQ7l*L6Um@Ks`MG#cCb-Ayt5P{u*#S>&F!0KJh>CMKQW*Y3AGf}HL zSIgQCR&gNEm^`GvspA_(zX0R-qozdmHOV3`pVGfT_~m7xt1+7g*$eiQOT$Fv3&+)t z6ZLsRm6$ZK4^4cB^}P~x@F~Ere|A(FH5M5n{iS4im7;95qWabl$gV)Vl*;NUkzV&3 zk>qNMMpgx^Cb981fec7s^Qrw>Bjs1GrzI6n4Yr@kHz`ro(4!T&co-r2u-On#d%##D z$X$h~S*N5#!Rl0@jGdr*m$APfkAF{*#n`YY#!#={u+Liwq3~}dNm)TeLWNLYGkqtv zxl~82Q_GkgrRQA;CD+tb2WAv-@Y=bOgcvz4Jk!H56;m>uXRk6p!{Px!o{keXk*Wht zq!QB)Q?7b4Ofs`g1P#fi&8{4@@;RD9`_lF_i;OK=P2}pad2ix^l8|xle3V0!J3#2J zj}IT-mDSdj&U0Q}MKF1wJv#)O_&|5@p*glqjHSy*+N5$NmV4D8s zo`y*pT+W%5UC|YH-+-mrL6*W66(#rK*mr4WQvyBAtNlW~*)IG8pV1W`K@*(!nlX38 zhryf0M?6N3f<-Aqp0RiZ-bc<;tlZwKPT3-FDz5Zz9)`bYwc}HkC+1YOM|_PzPP5=+ zYs`bHT5=8WjR+R!rC0xoSW@z+!84zBre31ATGE_*=FawPoioD{WD71;7v}ooah_ql z2Oo4WPhntuAui7@Z4C)N}%Zl{q>7UW0RmtFX;>xvrq>v(|5Jk%njmf^dP)7 z#SGr!N-7O+^;S328Sm6VObVF=SIYcM+qb2~^E`%9~Yi>B^8-K4iYjyqDN}1gn{jG$6W(#{6K=T!2 z17GRw+kRfE_GJ3!T*cdzWPO}uOgu-nDU6b-Vgad=?WwYNsmYjpnZ70%KVXmoN~cf^ ztvh=KTl$s47$#-mgXIJlNs&sk4_;YfNkurzaIxM@!a<3TuUI}rNPdjDi~rGUUgq9z6&t(GF5 zl^QXwir7zckz>yJrV5-Zz$NX^;lRv27f^11`Mu;)8k1DfkA}{&^Y0>d?non%e;eFgbCC?Kp+Fe5dS|w?P zBC1rwOpJqyRIralvTggqlqG_Q*^NFa#^QGancp-ht%%Im7O3X~SNNswzk}NB8M0rC ziSIiHy59aMdVgO*wH0^UR89%W6mqM;@eA*64PXDkx7X~_*pZmUSEcM!g`(XqveMwL zB~U8OcjNc}J`w0PpY>kP#D!Wav8Sq%s}&lE(Z5TRZf2I=ai5KO?@7P=rWrFl`TonI zSOIxL-Og~`>}ARC7NFWeB5jW4K{nHIwz5oFge|D1gw{fv1`zl5S z0wDS=cwf`zoICY4a$wuir+Yaq)t$z5tIxhPQ`SB2QQfPr;_3?E{DN}iQjSJ8T_cLW zOZV+K_F)(H8IZQVk?z-g(eIv~r-(VA8PP-B-^0TCuLDOp9vOKGqX?C%P&J7nUuo>Q z@n64h!U~aXNFTn@9QYeEz*xTW4g+_1*yzMoK0LQOJ-hJ@ygP)enb#9`Wg6 zl+RC2o!6{C5_hbWaEkn0d+^9?U{oTVQ?hAKgaq-N<)q2OaEWD*94mubV7u2yu9)da z%;Na@%*bNL*NW_kR7$Xa0p-l^>Gr{4B24tsYkmW=t68b#ea5Un`iOLn|5X=E+>U0s z4~=4i>9XfiZz{#!&KIl|gS&mhhM*w>ZXmjjyQOaTpw{OyH7FL@#B@axZy0{k7Oh)L zD=}>-qYu94y6fxi3g1s&Ng+9oeP(CBAUbbNN0(-|i04$Xo3OX7f4rIdWa+?hzw#L| zPtZSKu|@=rRK57ptxNYdmVS$&>r(`u21AiKREf21dfi1v>*)E$N5lpm=C>PI#@Sm! zsOx5@m0a^)8CV-@DCmu>PWkD(zOut zX=jmQLh&CXu|&;=~KQ`Kju?=>z=bN5rbOJ=boPySA;YqlxbTsD5H)j*k+!iaVg z^OxhVnthiiyESItb|mMfq1gznpc|sH8`)nsem`+fwGaN)-2TcvVnj_f=SA^tMtMG_ zWf|QQI9zU0y6f1ezJ5~OzImlhx7ZVW_d|1?`s0$`twAT@cxX+Ui$xU ztCWn#uvl0&aN1J3_2_cv{f3Q z&!LyE630!Jjb8XK(#esMMeq4Xl^Iu=cgKponpf&Jb9uxSuU@WqtYOz>YT`ACBz)0v zLhLwBFX?SR^d|yqZ=^NYX80KIc6YNEias&TepWL-7@NavvLYeeUv9)^@im^h3eURR z((xa@RFiZ5OX@_qkqkjCE*sH6A+q1=41GZ+s~Hlv*C%TTf|p`%J78x>5TgJae}?eI z&xuj?qlohM%fp4Zj15iM=F?b{qmlYIB}85R5&9P!47W1(UyuIYtHr;)Kl?dcWn-X;W-#BW`H4&~Cip{xckFkmn`o_#7)UA$l&CT!wdpiR|rwPEsy_=YK3 z`jZ&U=r%pt-lz8RLOquMtH!g?A7W`tYBXL3Ad0VpEaU2Xiy2Ho3gEk?NMRpmljt(8 z_TA{DzUBEC{ioC`4BfrVfOK;Y&9wM=rZy{L%L!F=a#>#V%x5$2Y)Z09#_nDY#n2Cu z6cZsXn!Et10J@K0&BK@Zjwboq0_dSZ&O&Pj4VFOT-2wy3rUksc|gl$3RW-p$<4{@t&8+umOhpkgUSkZBt$ZA+f>WC zsCzokH7EEZJ>T404|`TFFvJT35Z>vp#|zow*ZMtVkFv?2x^#LnVPu+Ly2yMid1u(( z9-EC!d~ka{8k2W?(Zhd>Z98wM4Hoed?qn?;fNtv4PX*(2b1lD)wIZI?VWOvAanXL& z&|_5AWgq7`O#ANXAiqu2+Csk+{`x_*rUP&D%v5blCRgk!rpL7_N+_~gh zfKnEcCg%%pXRGitP1av}~gKvkd znrw6MPu1QQv9!+B=JmnoF4sXR*#HkP{{&_;eE?blg zT`pm}a|bH$QBYG6f9l`YLeUk?+8E2gmG{eL{TyL?ehO{n~N4N@)>8#FAEY;u?Vg;$$Vq z5=gsBzxnA)P&ZO_q1dIlt4O^ujuhWTZkfB&DPLoSD5fizFW5OhDnxrM=%q-tD z-j<>chyOqH5j25Cbj}lhtkU zg;KhXYdL&W=emJt2S0=9;g-ET<7pa<$x-H~gGroIGjH~-Iu}}#GjbbXKnf0FgAKt> z0 z^g+4Yv3Vv&^(&^PEBF>qw4Gx~bF|2+-g0YGciDaDIklzo$n2wO5yB632GFA_+d>H= z6$$g;A#{B+p)5xRIHCEWjM*c79GCUL2zX0VktP7Ysh8Xus?;QC`{grTa-!w|fc#KU zQE7}O3lG#U9Sr19$pApi+E`xp*kX~zj;_ABUy376U@%cn|1N9dEn0&g2X3hczkFzh zeHg*U1n5U{oFf_0i?M8TTYyl65-oZ@M;J^(U|fEaex06xrGgi2amh?vxTuua%1U4a zK>&90d6fXwR3!OCsrkzN3?Sk-to>?=un-;u2i*uR57`74#;GpCVv*pLM4A16JL@p} zaP-bP=KtGS=dg|t0yjjyM*slG-a!R)P&ZsA1Q`DmHTE=dB3CxrSG5s(!bk#e;gk$v zjH4RiPB`CO62``SHZwwh){Cu36-M4P^Lh&27c0wpIqv-_H8VTrz7T<1#2z#Gz2P;fcQ>2(YpnE97q7G38lL5{`@Pd&b0W?jJ01rvE^_P6r zHn4M!_ngX}NY^%ONFd=n{#Eb}-S4*H96(fTQ1C9RK>Mg7|LfGM;GY~slH=O^k(`#W zEm02t9+cIe++V@_fF8-|_k`Zzn_XBzSlYO#v2$SP;B%8XjbVLO*awreE&PGrNc3pm zNvNgt>gwrr>+eZtLW%qJxe7p1gpQ*ES^P0)>`fPz;qNd+(As}v!KVo~UBBM`4*uP_ ziK_KeU9cm3Zv36!LkQ25l^Gfb=-Oc!(2C-NdVRe{z3!?aS-M6uy5! zj6y~oqPB?M(E$LoAz+bMKB!h&H~`ZNAWMe~;8OgYd45@Y%U=IVv{?;+F)@1R`)u^|nBX5TddqpcEAUCwA7WUTP?W`esAf^4ivXMdVtK^Ied7cz~QMK7GqB%-TJzcvAM)>K|YxHJhI~a14QBO=$3VX{ZEH#Sd%5f2fao`6hmV3Nh0ZzpzY| zLG_^!OLI4qx!a6l{oupuLEK98hu4tAuT%*Z%yCDV5f3TjDNMy@0#%|!IAhHW%OHx!Em2O__iy111h;*u&9ldAqEO#ods z{Sj3!k)T{b&JRGPX~EJL4ALH0Qq|hiotx6kB@@55C4o2-`u)<)gaBMI2?m0gqkb6> zhYwGwGhSCD`EX@0Yi8V1rF*)NKLC%v z41^{*JuEFvl0LG6JU&L=CMy%&L@m%%k-}kP%qO#p%C4x$t{Tm*In4folT*)?)2Nx# z?2^+Olha<2(>a>ceVEgOlUsjBoqd;?AD|K2o|)I4HP)W1H_ENa6g|uJXKcFvIUg@TxS@4 zhuJR+K0p3Iv;i1r5$@Vy&z2y?4DV;l7i=q=*0|X+6*Qa z@;|Fok-Jz~t60^wSgE5(Hn3QGtXMa&So5gZfV)Hox5Nl-mEISb#Fkiamza;0*xVP( z;Fdbjl=3Cn^8mEP$LL&R>D*RIMUR+0xGA_I^L$*((70$oWm(Wz+1sPC_qgTT&%kw; zfV?w6jA3~cH)l+2dE`oYY&IiAAIy{QDXCEUk-IoOwj$@gD0{3T6U~)sm7=*)2d&DI zF;q!eY^8;H1&=#w1-I<8SJkuns;=y+tl26P;_61NYIX7Ir(V?~ z_f?t6)$9$`6Zh2_v(-~lSwpThM3ObC$u%o9H7WHq3g$wvUOkC6G{u(S)|RlWE;@xg z{3AvK(4r30s}83V?aI{=OV?v2o5d}f2}wU^q^%Q|ZjgG_0AvD;o)JxA19;H$&sVmD zg@7tRem&i<`p*W9%yEsZosFQ`COsag9SncVmgomE2s62v{?`{zyw<0EIQvL2-wfo~ z))^B@Fs%=M5`w##kAW_Iy3AlY!ts%HfoKD81YZCDDx3dWXSIH1 zWfo2SC8xciv%UFOJ7zLY{Aw^ZoM2oK><%X!2Llpm+fyytYqeYJs@j`Y+d;Ekj(C7n zeOwn9FiD^2BeE@tr#+3f^_-_iA{4(u5IO+G2iO8p`6!^a6XD=rGZZ?gxrZMbSr35z zPu=vhLC;N2&)?M^baMsu3Mvol4KX2lWeXLcaDYsNemw8R4DGoe@A-#^{?G@^wf|Oc z&$rhnOwrHm*27BI$Dz|l!3%YO5ppPeb)O;fbjJAwb-?NBCCH^_!3VJM_HoKUWsV2* zwV`D*_`;>VVv&P?s)j7^0l7#5aR9(hpKz_k9>@#bs>8)9z$l&}V5|o2)?tSF_fEsz zQtJpa{tns63BThN**xU38$Y)`qM7 zUIw(he0%*eb|Ppf=UdXmw-kK9dwdjtI*9-d0POz7Srmi{oDn$y0NyfC-}rBdUEkiy zjADk4RqA}jBF3K;8}|wRX6ZI@t_>*oKa3#^ihD-T55**$F&&?AKSn2FZHI|$36esZ zKi~mYkrQaZ5e4_jOr98Do0z7XoVT3(o;&GOjdPz*;08xGZV7}ke3l~J52`07WTs|# zCl?-wmUy8VA(JZ;Zc||Qxkw-8HlM8IDZu0u@No(df-9!;wcK{5?13noZ3<{GwI57P z+C2q;&74}!a8%72@>>6`>t@oOLcwYHl5m;gUXFN~S2UZC*W=8i3#+#HPxR^E`nZjU zV)lg)Uc(8(JLs%}P>p^6i?RERhU;(p1-{KN>WtAlBatZ4dk;bM-UUGjqGXgHK@6je zUZS_?EeIkaBBFPK=p-4P1kp>BIrG2o=iKLc&Wp3oUbEKBi+Qov+GXwiyRPf|Nrvya?*4Lrhkg=7g!A`g&m!bw5OkST)~gD8A_6P&{U zY^)3IktFMEZ^H6_1B55ClBeCiPd|kMUJ5hMf@huwQv`nR!PR}fHAb2C=_>#q&oG>I z-tX_zA!RYG!&M&y3WcnVpVV&3w(QpNra=i}jd!+78YCG|rYsz`-`U!auvN zGy7y@4pTE*Ff!Zdu^{*vywOeyrkY&~V)iH?b4P%m8o-K_SkFoydN#BESA3=2rwK3X zfhkr_EVRlFBGe9f9LL(r@~LASQlRw0;0@_70G|g!@g2YgzNY$ls4zb?Mk0lTObA0? z(ZIIvz;lJWI1KQBIaK%oys6J)YK*dMhO%^nw99&^Cyt3&5l*HD|A!^jgHzkK9htzE z()xkAezpXxO)D09jfL1RH>d{!c7e?wmIZc~IoMZj!hq7G7v(dQqX1BIIapu41hOB> zT3RB#UJ(;qE$gGi8LV2F!=~@R8;4g}^;omVpxsMhw2O}43_-Xg$i%)qryo9`hwQ5X zo0fIwka8PH36HDKpP>Sa_lF3*%6!qVbYXZ-9TZ{+POEV_#@36WP_GbAuWwDOUowR% z;v;q7QEi_I_kkGCPF4yFOnxY+J~T@iw*^w(j7-=(?cJi*2&Kn_ZWV-zxigi*fby4H zn3o`uW-ty#DukF-=5PLutVmAic_p}6=D9@}x&~*}*20Iy;v7UkrQr{s$G}=Nh&L(%*w5?%_>Q z7%s9G1$C(d_a#B)MIuZ$Nz5_(S3f{F_B}v&k0@jhl)Oj&bB~e|(CQD@BZ)B5h%js3 zO-|ky`LZwmb6@Hye3cycIlc$7Zugny;XXqmle*9$>(j$dYxwFX@H(7AJpcrK`T0m` zpZ@h$hcfuL!BN(d-_hfzBg#NOurVUy-qYke^q*L9)NH@~L~A_jYApV;pJv;f3EG{& zr{PZ~eer!qP`U>Nlaq18kuDWb{@f$why(Q-!2ZHv9ZHi#oPA86>OC)*UOhbjjywk? zpXdBM2koC1-u;VT$*W9)Z5mJngDlU+Fj*ac(-Y6Lznn~3%18#7-N9Fiw>d7 zRQ=1kr62pPqG?2j=ey5g6 zWo6n0Gb$zK34*(?h|JmE{F*RnX0Wjl{M+|+`)g$AM$MwiZX0O46UYfxrAK?A$7btw@C&JeA_Q=ICp#rLN1K#Tv~q_?)je~;m_2xQY-({V zD`95k_Wsz+fONK-C9vAHyFjYBqdZIFnxGJIzhR({1q(lbchfy`Xh?S6&gzX6Ewks& zS|zLEVhL*OfSP*`Nt`Z<%M3(9nYcQ*p@8j}dMXPmRi6dWzgbSh!d2H`TjKCbd92Ri3J9;)g#BpG$kw9>Q{fn) z2>V!o9^!F{4{6EcVgtm_%GpczdCOgz7W^(e@-6Yw%G)-9bCvqSWaRZZ;%Bf2X7y({yS+07mD#OU#1zeG6T6N( z);{I2>&(l*T}wKE#^XptohjgyzKKcu+7OO%JU+jDfo5mCoflH1a3!?4pJwaub7kKeM1VCaz_b)4c0>X$cZ}k|91EL-Ai*(yf{?~>V5Ao*V<^M4caeq(${{4H6w+_$Gug{Lp&d%`K;q}SM z)yc{A@!rYF2_8B8hdn$zy!FYc1>pko5|J&Vj)ZhOPf!N!7 z*4J^-)^^&~c8>QC2j3nKw*2iaz3f9@bfPZ4`281w*zoq^lh-Tb3by6#% zqx=8UKkV)8{qOkU`}gnvgCAbMxqtnJ`MLsrT~2mg2EogRcnk65P4!tN=Bk$es*0)S z4GJ$Bo)s0J$hii?Yjh=>RY2?+`c z^7Hfa@$vneK)iYLCIW%r;NbWVfyl(f#PGlULuzVjDk>^UN=hgcN={CWBLe+n9zr13 zAkbSd_&@C7|DSniy)Oif)!{eN$knJX>WO6(ds2NSyxg0JPGeMi#1;H+5AuQP|5gGyU;EHRIT&rCD9ub z{<#L*ueT-MobW6(sr~F^_RUqR6FDfy32UE9h}%ceicKK=bM?L%0;?x&`mg=U`%It9r?x8^Sk5OcXp zyzAB1(cAkbkSCOuO7FKSw`*I{ky~ip6p0x3!)hZhm|7@N1jGIgFQNZ%tvZ z9sPgILrQme9|WLxu?r=>Ol37Ax1B05r8J}CG#!#KpS{cYxMC@i)o*ht3K7Zk-_1k* zrp@J8;a;AVI6={JhG0+uvMWLUWOF4^3BtRYB)5!$z*KKnmZb2IB#ng|EAytM8XA(O zrRkfx*c-69ul>ldi{xF;bWC?$&vGf7%Qs^i{*Y!V8!6lo>N|bTL3G=|ZX=&a58eso zk(bGSigt)BHI9-@bFqk+zqOFA^pAd+WcFmMG}H4oZ)xDZUpti3?mmk6;P}`%j98#0 zwaVrAu}d+g16P$<4Yo|LRL=QP^}Dw9gwM1#uWf4zETx0st9+@8>;jY2x6s!lD3fP3 zrWk5xH8!1)Rli;I`@Qo4?2*Ipv|BWAuA=n7)brhR_O#%WKUMTXZig+AJH_*QWV>yb zC*+mQKFOc9>$i5_dsZEHrVAs<$!CPUC|Ug9#XWELtAs<44!BDu8-dPJ*amHi0%ihC-hjcv&9r-nQ>jPI~B4?gEGf< z-yrw$OIAkjloe34FQ)kVe3hMW5sry0rZG8HdQP4eXz&R<^(idGoGGB^FT3aEekAwH zsd)lM?B(IV%)?RQBm?50f09oE9gN$UTO-`L{Rg8%tMk?r4mCjv_&x;_~ZR+oLOXK zKCPoCL>U1fFv4V_w*$<>9MVfL6-zr+XqMq3dXWgVs-V4aJBnfwFyM98C%1l<5X=Pzd>c9C_(b5Q6jT6lQlwl;VYESwr;{&>1&vgfY6kv3m?+*) z$Bg=*Q9BsZ@@tu1YG7c&#fWdXIG;!TT>f|3xC{T0t=!~nypgU4^<_l|#bX&X4S-6& z4YadgoT&pOcF+=Rq^vbkql$MTSuf5^wEX?>6A5EJYE+*{b-@Sc7Pl<=R)>Arfe}xu z%~yt&)(?t0$U<`sy{moK2A}LvN?xu;DQ`Ok508@q%|%STmzh)ib2z^H2Zxr^;aWGA zz2b;WzP+C9o+0`?Fcvut$u*!Vx3W%#(x(;#3R;&cX^ao1a(dG*<6Y>iX`oXN>!{_(qq&qZCK$DcD#EX@4Qr`SteuSd>)Q&H!R=LZdL3 z<`s_jEE@VaQn9u{ok|L@yHO;*+1=o6)DfKK`B~DYV2_i1uOC24y-8XUY-;X@z72>iS}YZ2 zXzKq(?)!1b_MYh}_eW{I=}Xy%6EV=%m65kEDUEDPb3X`;<_*30&hnkuDupm&b|h1sFO&S6)7vFf`|w_Xe(?udIy3extuCfZd#TtWK#0*Z zHWIpR-#%p#ASKuj#86SHU8Z%tH>xl;*KxdRn&lCi){dJJT_FWoX4##C{M7eWsO73E zyMv!3e~6pE$#84nx#fXn_Tmz^7!CgijJn|8>=oX5a~#q-!RN_m9a`ZBYjN7zZ(9W2 zr2cwlw43D*5@V?-73=1Px!Y*-)`neP3s~{^B@B`!mx+gAviKceI^?`*cGd8EQP7FF z8BHKy&FTDcydv^fF`C-7qFR_U1EO74$hs-|;1@$1hMnW^?4%T@0t=4Y%* zy_lAttll>NIOOE%lXqdgc_5o)WQRs9!h4J!2d`VX{pB;sJgEK5mTh}ix~D_$bU*Uy zm6;q-;QUJdX*;*#K^A53uSc&hu;y^qOK>ExcS_MT;=Fh+Q~B6$-SkP}V`H5njnsrB%p*(t$!Jfu3=&%=%dd~fD&T1wIxF|*c;Hf< zhW}C%H(XTogSs-7Gw*a9&u!?54en%w2aZ*W8a&dl+hx(~A4^WyExyQe)=WH`uvze} zV!7Tk{n8?1x;5p{X_VgBcuSBV352hILNEK*=5J>1xeWv_nw&=j?dz??J(`;d(f>RL z3UR7uja#{y_<38i7Va(B_J(E0MPzPk^tH}Sx|)Fd#@@T0?cn~ludf$r z%|9Pq^!$amCpG)IeXAOWqC; zeDT3B(ml+TdQ8R&!zEUd7u z9Gl^~jFIK^{Ag!)hG}#IU8v%eU$1k7F@ZyC5@4Gdj^K&(!=OElBB?O8M6V+6@`Rd8 zKe3d?=yg13k&N1P4%Whi=m$h4;Lez)%#{tL8I1$zOc_l)FwuroB!p^C7!6E}MO316 zOuh-)lvB936CIq%FnAE<=7J18b1vwo-G3JT`s}3^cT7ohYynlYvSh$(2Mr@kO6atAfU`-XA9=#0l=I9`HypsCR+P6^5c z4uvOiz9f;~&JwZ><5Op>+DdL}dncZ0aNQ5%I-gC{F>>t>Ptd-VL?#0CA~Cs;cygjd z3K`Qf7kExPbQcSou`>qtfSNkkp8|?(=NC`yIhGhxt~e2dH&U<|zBNpoXGO|APNzL= zH0fNz_-vB+IfDruF%qW)J}Lg^wq0WY^F%>r?4aF#@%+yd)Ln(@F-U!?hi>$0+H)_% z%3~!g)1Hq%+)g58E1*n4z$N!6-NrnRGE>2t>7i;#B%Gi_IOQlw8kvlv8B>N&p*68E z={X9#$PHgL(1$Dm-@L%Mb`Y&FF>L|xZ}Sje!Hb*AOvuVaTV^K8WTjeW#WQ84XJuu} zWMzKL%0JJFoXaYZ$xi3ZE~x~5@eq`gW`%#uu6>?WGndIPj1HQ?ct6h>I8K5Tg8#Hr z?${Zp;@!n$XgL!8u9!1Rm>6Fh9G=S^J zDSrV+N*1J{#O>67$F{e_~xXs;xo^>t~<2>3Q_I{Wj`_TnOXk`hLqlDjeKL?SNx zfUhK^xI(H}uZ7mciOd~)w+u`96#Hrwo;t0R%Jnx!$)%*2sO zp*1-sTS=n)g@BsBNUmvz9oJDbO_nOQC^pOcIJILw+p7@X;PlhM?0llk(osL0W3s??jtEA4VY{@VVFCGkKKhQSxe{59| z`oe)z7*Ni^DVm%w6w}}6@WIOrpzpV8_Q+~mn3Lj} z%Z_EsH0_B7%?T&p*8=$E`y`5Ab9H@faaWgX@3>RWR4@yxmrkqzHkIExM7f7?reb~3397Gm6;hAQ=j zLaR4xRnc-eaPTt<@7cGa7WETe^@Pf>xAO=itnSs#Brp;dM>crDkQl3DmitL4d)7Vel9_rQ+{PiP73Ox~m3#s<>o z?@`{T0aXLAQv+D_*loNKI57s>2A~SU@TW-VZUJnt9RwbS%qLMUAxSYfbW`I+LX&n? zUErq{x3{WZL=kJ?cJh|(b6QsfY|&0!rhvi=0rmu7gLp!*4pwIXmM);!+@ljLs24>+ zCJUgTCD3sanN&OJrEock*SnP*&$S_+t&6q|w>IU_=7OG%^gt))LINxn@>UWq9svOD zG{c2poG>z_j$XovJ}C7C8i;B}jgee`&a&Z73iE zk~%?!q`&ZjVjZlw9iYK?i?nwNCQ)V~0k$NHaRht{r3Ii!cd=c?(67SuG$?38 z62z^5;)fkSHvp?ZC{7}vdJY4b)dNIcxlEwJ!q(Vgo!V0Vk@D>hvScDR8NzDTRx^Ts z97XKE97WOwf@uVl;}z+a0Uw0{<(3NB9Nf|Vc`vxI_i}3hc{%LQIASh0a%DZ@dr5_~y~F(_DsTp<@uU;Wj) z_p9gcue{JPzc~0!WRh0vhzfI@*Ox2-nJ}K0=odv z6+3=d9GPStDa~;2ZGrda?zY~;6JOhlfu{!0u{%(C zGT>DK^iKh7#16dh3HpP)%}8O&`S-Btvni{qnTpmaTpXOq&ZH5UPV_nag+K<6M>F5f zY}n@sk`AKqGD3{N^qZDhiMiRzz=rIL*}N+nBB1jYcPGjt-lTF4IxzQY!@c#fsI`O8%ci89Fxis`nUzWobb)6WYRGYj@?i~Qu@UkAf) z+RYX!e9IYJq}W;%-I?#hK^JD?;r2={`tTpXRo~#q%=}f&P#$eu%%`6o3j!V^gvkUY z9zUAme?S&~{LXu^_`MHnvk)rqQ$EQ}L;!mfKR@^VXVLIa!Sxw1`w}VpSd$IV4W;CO zFHpZ+s2stToc%2OymY9$!~z3P*DTT0{!ID31g-tyMe*jx)uPCc?^CQmu#$@jVvePD zS@JiQ-_{F%*@?lh2YFK<5zuM;GFL5D?0kh|cjX~uiAHhR#B-HY5Ykw)!kfQ%v9qkV z>#r=hs5Uxv!*i9ZfcQo3l2zL(Ya8}q+gAfyXQR<|Q@wR#&s94+lX$xg_tBL_=8dO6 zTudQ^M@neVg?l&pvth!xpusA`$pof~+$>cUPbQ1@F)ahuZgS4cZR)`M?o!K}!5`lp>`a=JHYO4lw(@wvdnD}$&{n?4?5-4aC~~oF2QCGAq2yv~ z_a{hix6yFhK$*PTfCQHyLh!n3UvD+@<$HUe^N?W&dUvNWpEp#Aq8Uh{qZDKis+st{ z6H(jDgd(=Y3GSX<#j>^CVt`Y0*MWKOhE3Vpm%|P^^0)5&c_**5*k`vWo`{bHTg^Bi z>8>MD_$qWKq>Sn5CdHQ&h#m3Arj4q$b=X}NI3=Bp62)f&!1(RK@7i)OW$e7*-qY7r z@~HJg`0m5IyEpW=-M%uAWAVF4(jOC!_0b;?md#w zKLRGlq;ts6!vQduvP& z#Mx7b<2dEV9XQmwR^Wa`z1`QzFZ0prHT469+kvCuO3_~|eKiZ`>~ zvXEpR2NWt{mBRjQ9u_K*`S9?EGa43kMpAOyb~o2K;LSr~Gu9Oz+j??#-Fu4xMz^%0 z$Sg0l36$1#vL!rzbY~fF=;h1FT&|26ZyFS-`8OdXb;1qHbn_G=m`#6~RGHS;_WV6^ zHmD%XHO;Bqiic^fr+;TX)~}h@@mXw(U@_mdZh5xzqbJAwk8NA<)in{T#hzVfFm98I zp3=y^H=a#wlu+#VYQ+QIhmucXGZDji3Ly|St0R{Q2>}%k3BfX5DV*c1Z@cmdEJ7+~wVnYZ+n0J>IQ#ov&U zU-Be{e-VrhR++*oP^ne8JZUsFD$U2G-!(qu1xmjS2XQp`LcbGO-^w^(jDoE#cZ~JW zF)Y?A56DiE@gVYEglDQns)}mf%Aoz#RcPfJ6;D%^3jj>_l+i>oorRCNiJe&~b@sa{ z5_R^5F9p%^0nvT*?1zD3J;Yh71Ddi=55h8SA&mw#L@O@Ikl$B3m&1k*>5d7iWq0H5}I%;6WFvfIOOxZH#L8_vpqSA$TKk_ z8J~pB{Pw-23zGAW-bgoad!K5Ntr3xS+Y;v(&Uim1Lek1L*6Kvm>M7l`VfUfMlVQ*I zE1};4S{dmdJaWD#IsfFsH;mB^ktu2We8a}S!ELCA!6bM`tR0r@x8(Ei0mqf04QDA^ z0fR$Z<_G(zhc!}f0*M5ttz$39Pcs9ghcYI7)CCylFgJ9i4(2v1wPl}xq{PK&zzLgn=v@8{S|*GtKnGIg{vjp_f4^B`BmT9^U7>L%f|9*)NhnsfUNr$1_xvkjgK7Ck;dd2% z0>3`Rz$fLzJN_POPg~E{dqVPqszHqCq=1C;_VdxjK8nAtG902HJB-Y|z^l`~=L+dWX)MLZlVx&HD_t z&E1PVV?1IM-ywIodnPc-!3T&A%7_3u1Wd#)IVX>*{5^?-d|0&eQ4UQksAoL%t*>X$ zB7Mz7Px+BBJITZiR{L`GWhZFd1Wj?HpHiHiH4q;~n8O_1*}Jzt9^hR~#8GiZsb%zOLp_8M$eymQE|WSN9;D09eE>(f#ZCHA};n? zwz3py3WiRsY%*>3>2EXt3~?EDBdAZ#H!{hC)=9252h6T;)c0;^3>v-oI70kmLabwP zh2ND?moNRh{vxykSkN>4W&R=QLK0i2Iz)AN2=_8Up!5o#EhLJ)zzr zS%zL42I(Ia3uTOR4XbbI-Cv65%_|^0J}Pf)USWIb*Jv_*M6JXz-QXK%1v(bJs2}jTP%7UE0qK# zW;J+aIJv^QoY_MroZWDPO|$%=DYd>AXjC!XH;s)ponTCDN+J=H-L6cn z5P+8GuP3-2{r>Lrc^V5Ma;`7);nj)!n_M(Q13gVXl{hIIXZUs;SmAC3QIG4vll}nd#wj>r< zb!<_2UT09H{mL=-Cdax)uUq4rhLk*tc8==>ml`!Jm?NW=fD20M+094%C8I?!5*ZXL zEnXl&+bwk+hq83jS-8>EXGp5za5C+%cHP*ol7}l32xNI{xI8;hPc7o)7dL#9fv%Uj z&0D`n4s_gcQ(g61B+*N5rEtxoU;qB0sjtp50dw=nt=>4sGJ0*{9EP4pS1a7b6arKh zyF;!J{E^NLBXN@%lIImKqWnzLoS^hfvi30AHQM>fOS}u#YEvL#lcoL0X>g1}EKOyE zR@OJBCZ@K**!aqf>GYk;R9DZjq=H*9h3t5oZKIxN&2MY zM7s=xR#FS{d7ex;RNL#WUC%`wG3xRas5R419~Sm>y`?hv-`2`5EGmXJnJRj?%jsv& zr!px!JfT{7`lb2Dkz!MGN7+64{Dq&A_0Qho<^rF3GJMJ{AVu9+UUCZh5SV+e$T_R^ zAR@%v`ZfV~bD@}?dz8wgnE4oEo{ZpDRN_am{Ifnj{D6)bYK48xPL23+3dFS$%{Hc# ztV1|Pid}?f0W&y1vkIfGpK!dAB;tUB}{B-G*`g{fJRrM?_MGkfQ4LCgzD-o z#b3^TT3P7!U6p=pbcLe`t zBm&>ABYPV3g9f`9F5SBy1Me?k&LIYFFB0Tb^m3mZh=vcihg`JlJAEg9cxmawk*3Pe zTAq@KbJJDK()3*+7$Clz#Y5oD6Oq*)irkEPc?PKg0p{&dZgyzN*+|zUQsh~97786w zL7kmc{$Bb^fHGOB#h1rjpTElq(X@&Uo&oWOgk}rU)`7~lcNBTGqjHVgvao=AK;&g6 z;GPsAZUJ`Mi{$f)2+>dgl)yI$0rGAoXm#{#67+C|Wu%~nYO;~Kv59v0o_|i96^8gx zKfu7M*i+S74TOhaqr@+XariGVfP&URT+i-i^@sZ+fGj)Ii%dcQ5fPjjO^T!h&f2oz zcV|~}T9?T&%=hw2T7;`a$ZyaH>6JShOO zv4p-!5`+Q7_!o02Bs6Q2;Ff%ZXJ)izz~@~2t6P2LU1L@8u6vr*lJ-HW)pe-u0U~g7 z_a%AxRTstDO*PM?&=_wOmi8z!{Hc)?;ip6ZAOMeoNHHa}8wQfqFK1F0s=FtrvdXd` z6aJ8*(T=tEIsbi!l9>Az90GL>j7Jh~ukxHtK1w2J-`f#n1)!hQ$+%jevy=#&ki@>I zh}~DDq+GJN;%{pAgVKb?UZFz!xL@_XC{h3MsJE~n%>8D#Jxy2gk%;r;JIYjs3(iQc zO%1zljf#M~6)SzAU8;Rn)nsQ1wkQIwg@K`o?)0OapV^w+7aGaAcYECii`x4hZK5Fy zeTBo-X5=@&EPbHY8f1AeNVC|P5;#~`&>esXrxF%@6I99M`@W4Ah%hXwB@}5m4|hir zKeLOxNr)nLiFg)3>?9nTbfdBIL1k{LY*$H3{Wd9;2CFS2xT;z!&0Qe9x-2`0uJqN= zM+$kDWl$^IJWTPWyAanxtTk^l-eMy#1c%5oMJvCZ4*%dXrQlHU z`Nxsq->lFOc+d16Dhm;%mqar)sk!MW)iW8*kQ5bw44-S%dta@)I4L!(d6yFW6}!y( z79a--!h;H;-KB{Ra^mMR6E?9J$TNdD)EG$~2G1U1>I~wVQ8pN2+cC5-0=C&aMvP|< z)5fR;Fu(eBzmO_xTzu_V&YiS~2PupZmR5zj$M%hlv#pJ@ACGeo8Fdsy9FL>rlfn^d z6L|3O6DCdzoN6-+e_PqfK*!&%nRuK;dZ?;@9MoA+1YJ-vq)Ee2&>4Rx`6fDr!HKDT z3r847?}fR)(HHEGm$WhdS%;DBF_16?=)UU@i-_^52{e!?TKNGF}VE{RRUJkQG9pJ*V`X|T)!upvpuA-BM(T!Wsa ztxs>oP;U}?&JsIg!oPxr!gSNUwJj2@Eb7Bm)1caU6?Y#ohRIc!FUL+fZJSnM|B(-$ zAtH=f6TS1`?aTeI*2+?+KBt?uS_)|PlY1gPQOy&!8?g+`8zQhF8>&gdeZt?Nd&$I42V@JX?4hk;ZMoS<7l|%V&Kq zXFZ{7ot>ojoDl@>L<@&6PE36na3Xt+-`fZ{SIp3uMCo|E4Q|%se$P?pIcqo`UQ@t= zp2S;;PR{0UMz!Zg!#9bq>TF0lbiRML8MV2o9yI%H$7VMIfW40(z%a|Tn>>xTHh5s0 zzel{0MoQaEywzjd;gdm9_rqxU`_JR=3(VRaS5oCJU@RtA)cs*Rt z4wA*3bM`E4_vr0kh2o2;hXnb<<^0;W$TDO#P{6wFW!^&YcTz7naR?7F4LvbFu~h=~ zP=8JMxY$m-0ZRZ|BG6oiG;OmT}`X|wt0+zb)7?iGKT^H z*1Wd=`2A7kChCT*4C6`M)=1LbTaU@9sVz`MAsP_>NFwvIaI+=`$;Y!hSC6|tlgf-H z?+ZNCO>i6_S}zZX)GdhCMMfHpvK!D%J)6$QZNnoTUX{D({Rm`p32lomeeVda00SrM z@(_pp{ByqwgRN%XWIVu7H-mG!d6Zxi|MxDOA&Jh9=l$fyWaurJav=>G3_ z>|1laYgx1FeLD`x5a)T=sHtmu1 z?Uo}Wos;_E0g(|e?P$%jCLBa)7;!qi_ptz$Bcrp%n%MbWI9Nfw9 zrpN?y_Z=03!Ue!**m2b@VWJRHB-o4o$6Z?O2s6qiM_2N2_W**k6> zsDj8Wuy>wAd@T(2+NTfrgpX9zk5tW%)SQp*`yZ*jMyqEWX_otHCLU?^9qGJ2(w6cS zI{R$12~z!#tmpz1HSJ1&_)}p=yp|d*VMi?gGw=4uP zQ`>_`zySgav?qqhVuo$8^qC^@!KmT>@38}(+0ekg)1aBt;EmIlr>7w^{+yZkS+}z= zsWUXrKa@Kl-1#h$H~<&%#s9uVvr@l5qS;iW0`xTGaL(`14nG;C3nZjJDrl4VaneT) z|H5Cvr-gGd9-Dg^QO`XXk2-4oqduJH^!a1@&hwlD@;1(2hn$7}Bv1}$RUJDOs59a3 zKSOSum2n97Pm?lZ(9%4gL*xC^=5+0NTGRBiY6{#9g^B!|AxcdU|5<_C97);4f8YP{ zf9-tn;fw!=sK6%kGeHg32WO!{LLfQpI+w-Yr%^s-A%E%CUhiJ&)rMql2M`$*kQ%{# z8;RlXUtfI4xER2l4}Q4JV+i2E8rWKZf}hUIB0yhe0+@;Y+e5a?;j2>|j;a2IFqO;N z4QBsYkF0`F^EOx9J*ku7^1#B4;DWx(pZ)=yK=`aYL}={v4swBimSBS6Qqu25;-6^4 zvX@4FS7chtv!}Oem5E~sQQ8_&SyAu-hL^dN*9Yonhw33{29O3O>N%V+7#F(Ch7R<9 zIr(%yi2YKr1|c&2@&y4VgcX1v`6il{YE}Pweq(cwvl~Or4bs>biU^Y-9SvdurC#vVD%kYUa{w=iPLbk=JR!7*6MxvT&B!~>bk>+IH z$qJf0t(qrkd}^`0iZA|ts9K4Wq5(+ip3rj(esPs}$-u_Pc5t+_$bQ7hbBZBI&x*Np9&#(P-My1YsY4msyin3G zM{kQ`L#=QwB!gCkJ%*z<^%l+# z;azEbV}JN&e>!(`p*lx?y)!dXOmU;kN8(y+Bez&pTvLkjX!fD%?ihmWscW@QiItJ! zS%+|Uqa9Ciyeyeb;h-fGXZpi?>!qc#_Svr5=*!f8f6L8eb$Xu9(yX~7rGvS-QtKoS zWR-U{lf_C%wm<{}JSv+H6Fb$(MIz2*`RjW|)tua3J(i{}&q$x+*Uz~ZJHdW{=NTy% z2*#t>9ZGzko;^eI8|%_<(_A%Oe9GHMhMw-?Au2idz6f?doqdnMikJ&*r?3OhI4+plBMCet z<9JgWM*9q|B|4fK)`{+?9-blUfFE{_DwFTHMWp$nDHRt@QiSi{yfcgJ7Sv^Z@Bh^( zn3`tg>Oj@esj9z73)^JY(9eCxMNmUgvFdOvK;hmnr^k@OX*h|W(N|vY{!lH2yzSC$ zw82Ax`YH5Vafx#EO`{?P(+%Ip97^GA-p!A>HT>3COBa*psUyS&UsE^eo?1VIePysp zo_hrG!Ky`Q@oE@}kNQ0q-Fi9udz?#kbw%{Yl#v9f_R!a7W!#>g0#7W6WPc^cvBB#3 z$oGgus>XU{M(gjnWJX9fio}WukDz0siGba$Zx z-+(ixjVX=ZP*bl^N}|fSbR=S_U}#r}x7@qAc%iq|{00hQ&&3%UUtSAW8NKfgi3we` zMOHFsn)PtZZibVpmTMZk3@7d0>j7aZb+$Q4)JIp_A&gj6;d|q$RjjsrZ#6Xr8&kxT z?V_nJ+wW$~il#WkeUmX&>y53u<@=0fU6fZ8Wee{j-*4SmgqP&J+cW-dP z@-TZ>j7PFqlEiK9#v^|FLUOmQ9$e`wQ#yee*{@TQhCh6$x&sImRrtgSO*>gjFetn`pW{peZX=EQ7%` zLGZA1D9=kgUk-6!SP(H$Lq?%IAxvRcLV(f=dUONHqlV*hdGgIUx1fe|)^(@ioK*>? zS7F)kMi29%zPQ$r!bKFMo82;0p1qySG{P~lDiX`_;zYw!o?PkeiCbZd90CN~)5{4hi z5`jQwE_0Rv#J~hHA;Fg(sCS8yZ6A;M@Iw?E>kbgva43kZSvXRxdI^d*581ElB9(E%#JnVh-M1A*VvMVo>E1Q>@JM#D#$lJ4 zzBTs>MApZ7RIktl`ZI9(c`;7VL@<7nCNpgZF!;zTYW z<7x1t;^3tl3}Ww?r_4eRRVM4BG4hP+RQbq=n(E(tvG}g+Yl%AjxD`7Zmf0@Brue{Z zH+q)P2M+MgdK-5~u0K{Y7PXR1%0W9gcb|*FkE0D0BL^)}{i9PI5-@M88qYHm4D?+c zWR$N1lGHx0c%9VsqBw?O;-I#*T(w5)#V}zuavNqgmia|jV*Ejwl+R|5M{|v6+d-a? z@?Jc59c$xmyjVHrB!EaUpo`SmR~76m-E~*iE0WFypmVbeWoaaUu{rg$q;}Tw5sVgw zJF8>G&zTuugOd?C-Q)|;OqVPXD=5C{(d@&2 z8-PCBe8gHy^0I9MSuVTS8(M~D zcQ0Mxj+9cAyb!vtu`WwpC;0h?&)V`|;uf8kt*mb3ejITWW6{Dh(I;)gD2JPf$8r``z=*m)+Inwoy+6ju>9dD|5j2q*-a+F7srZ0pR2NTJ%A*zQ@1k26X>f23PPW?7eS;A zAhNyt|!-sj2L7g zBu%RHCfW3>iNv)7r1`pJk@@E}J&MOPcdv|j3KwzDAz5p-` zgkr&fi3tl;Qqe!*guF;_jm#^x@T{!Q@q`M6x2%X#gz=q11hm7G7}m8Dsjs#Tw=&18{3JgAZi$fSm;tSU+GeUqvNl*5%| zhFNY+ww!uEGbZwh|soeohZbPZpo-bhgi_cCh6# zLDKJNO>xuPc)Z6gSq4r0iKeqORjr11vv~uO@?FL{fMowY=IT&=+`1sxF3*rjuVZgB(wJVh$vH>e#P9iOGB-CrY+ zT{|k(hr|@C8%5egtZH4N9;(4Kvk~V54)V2#2k;Cp&J6GGjzi59cnX);8Z2SZu7U)~ z0u-QDwAc@&q3|%d)%FLsRK%piC0LhCj2>m3!|^rqM~Z|}O%YO~bn1}?yiGPvO@!vP z-3GKcq8s(gFp_k+CnaPlrIxj7FL%sCuFO%;S(P&lYi~3~;}mIoEEKD9XAyw)-;=`* ztMIJiJwxur%J!|sk2z_TJCAm=r>@A%chk;>vZF%% zf;e54Big?A1kCrCXsTt`Smt3=M`*moX|4XH)mYt+f$Jd%}AcUYZ%#kd9HZ%tKz)|B_}&7`eTpyRA` zSHXm)lFG`wa7MSnYdv<$EKM%cEtjPb$;V#4Tl>lCiAh<7sS3pbl$X=?jw~|?PwR-+ z7HQ-j|1e=2#c-VW+fU41mKO!OrgrBROMfx3U!ECX=2iIlLAzt&ng^o=X$12H;5%sW_<<;gid&B@G<}sB}99wYx0M_j%Fb3E8^o3A909Wy zvD;5xr@vnOIh~m5ich^`U7+bhcB$=^sx5h-Jpp=ewWlW^d2MekobKqz&8ISABP_5(gE?6ubfjT4# zXf5!=T_St*6{WL~6Ra45iSm}r=oad zv&sk9*n};(Zpox?i+iOUdnsn?F0IY3&At#tpp_UWtvei?(&{4-|TX2nI zk4$R2b4j-7>GT<1S@|v?6FImse%AMWc}k=45zgp9lTdORU6WZ+hc{TC#lg;l)NPXA zE2aFKZFHQa29aP<;MlsLTCo%K?Y3SA!Tq?i_c>`|TyPWWxmz6ZifVbZXnA~InDoKV zrOpQUJ!GH|I^%2H08 zuF+$zVf&Z+kDZ3;?^@7xS#g5UhKq}6pHh9u)dh>pIpN zRj@#ROi-jT&y`V|Xo#=0Pv70idS<=px)Be4QyEMl)})?teW)tn@w(A!lYcv1{@G;I zDj-fdkX|LinH%0Dg3l)^Wfru6j4`HSRd;Q`7eRQWAmAMNWIvLA<}Q8=dMg4)fd-su zg}RXj3Ye06m{JRXM;5uKLN@Ytr1lHUTLdh61wuvyI%fn>FuNl?u9UP;{78(wmj0kc z;OgL1=ty1THv=dX5{+~ffr9nR5psQy)MKvzyO4v>U;fE{i%=y?n`+L*6H6$th5ygWwWm&?mw|(WzYq-l z7RwiN-%!0b*Ad`PUTZX~V6mqVaGLA*d!F7v-NqON^PRI-M7@oBOQ3&?X{dMTN`_LB z5Pn{`nAlcGX`{bZ)f@TS4_ZEvB*9$!c3!fI73q$#?zdi{%?V)V$Wyo)|LioXBaZKE z$O}GXWD*AX8sQkVXon(Z$3dr?tSO#=ZYyav%S$1bz*gs&YqA8NiYy-r!*Is2C{*FQ z6eHzSzJt^wmz%r3ZF9v$-?4NDAsK%W+9G~;DH^0HeBZ5*MOg)Otm^EVI~VcW@0}vl zZ>b3lusGK}Dyk2i+(o*){$_xMLv1X6WZqiHgrkqC$Wi!xZfJ9V>*g`)o(2^MOS07v2BFURe8lWrOCHC0smgHB?hQ9*LJ9xNal_HK=6(oenzv$?WloOLMG2kkj)NOMm@P~C#UB|izJ$%5wY4$!LrM5q!1D}@K7qz$O z1rlUTMVMY>h#0d4^~S#)Irf!b1ELH)5qcK8rD@6aN~xpcp{eTagAAs(LbG%sfv^&q zv|l@T{OQpYU;N7CcfeP9;>v|<-cAkUza;ICaW^-4)UM5_cg;tlmNJP^LL2h2a_y;r zr3hb#&!QciVv@Z$UyW{9{~&!h3jVNoJ*xFMHyYrg*2m}q4;5?e6}a8|xzuS+bD5-t z#5NW+374otdaA;dM3(bD;g+2-_uV{_|K!lRg37x3O1wGHiJ}XLJtxhw4~9Uo_t^BK zQd%e^`hWqwxl;@WH~}yF=F|yE3==`3tD*e#%~S2d92o(cEm}>c(|?!4%Jzff#hzCZ z_~w;9kcA?N!FG0I+P*0SB|VJhQ+Kt(L$TSV){XiNzYt#e%ZiNwrLSxmPk;b~d029r zA&XeEM59ss5A%>@SAMxJ$wDcCTIM5x$V^e9h^#WgJiI`w@oD{#D&FR1fh*feQZSP$2>G_K*hw> zRdY<}2G2h~&3dFey=nJ8-2E<*o5#_Qwlf(EsC{tFM(%cp%dGY$Fb`-i3Qq{M90m|zCpSq z^%uiYKHC`Fp$oUD;i1VYjDbm0s%Se35Z%yp+ z$E41tws1tw$8;wp?v7_CrQl=RpMN@iRVI6t&R#JrPuipwWU^3LI;6-_H8;~i6n>}z zD9oM7XYIyM5Wk!1X@du^B?)&`nqt;&KWaa;>GU;DI8iOyUQX0fOg>My?pt6=60$0qXN?*A;*(A3PMZ8^ZF{PB-M3VLTsHzk{iy3=Dc zYK^A4YkQBQZZW zee~TpALSVwb&dHsbn)2^8HP+5P+Zf>(r%&pL6CZXdM|4B zd6m~9mK90UnR-~3>Z&#zC1gAJ#3AkxqqLKrP|Nq0FW;pSH^YIV3x*3AcBM>-0Ak@zP~0t;4KUnedk)Qxh_3Xi}cGt`SIWlvoVK1pO-k~p4Yf;N`*boIdqPfv1&uSgL8CT)B)nzV)ec|Y>EtO+%RdiE6g8SbJs zdG-1UqVuJG+{|S;x)Thv^W5D>ZQoi4Dvq3x)e^3GUt;_+I?fSTkU}!FSb;vZFv^_C zaCNy_b)X^hvT_Bs$&(;mmgMDe75d}RPCed7TcE=6K>CYZ&(@p9LPB3~te_6TYsX3p zf$Q>kTUK~_>^)i@#jkGgUO19jUlA_gD~!3pbS_ZRRfY3ita?@C)aU3g_^t;^WXUt2 z{c;8eBY`9Lke_J3%h)Znf(hrsK3-RnWN*{I#Z<#%R$N$@pG_hw3Q(PXMn2}(9TeB(qWt`Jv ziP-ER{39^{ZT+pW{B#;7g%StP_GxeduSr=du~UXdwOg=Q4Fh{q`N?<>A2pU)8oxJ} z{-3k=z-->b`kOABS|#H-9)oHmTIILWXEAAo>!sYnqI(S1eoXj_Z5J*WN)%vMg?6*= z-wB$Q*m-4QD#r(heKJadbeNH((?Qaz9G$lGv3193Pl6u@rt0dLT`980M<)D(NaQH_ zD$V9nn`=rvFZHm#ZF97w1CJsxMKxWBjH?wg3~w%hDy!L?QhTH6SPhzCm`bB)8#sF@ z&L0mPUO!NYl-w~K2Mg36pJw0djx=mne~X(=d){^|lPk7{LdSaYO4eAbacQj8&XN*$kF4(ZKZcYJ-k zM-J1IwaeGr{B^=q4B{N(I`g<+hF;z}>rdpqr-^HHGS*Nod@?a*+MfL{*NLCh4!WW# zzNtWj7OC>2ocU|8tL!RYf1D2a*ekpv7bWb-_`N$iCXDC?E5s`Qn=yA_?zlYBEgDDX z&y`Jp;s~>{gXEcPld|(JTJ_yQkcykEn9q0F-@{Zy^pUTm-1ll8TBgB>GGT&nJv-ds zPHKWDbi>1&L#6CKxaLIAc`NrQlcQZJECzE_eSZ0f`&jGU35%Bo|M?icJ zq&J`dJem02(Q9b+TFLWw=p%2Un;UPl+~vkm`Yn#XWS@NoTFp5kZyvyeR0$ZA80n6N zP|#z~*rJN%PlH1n3rP3N1_haep(+7j>R)GZ>EKV=6peI<11TAgo7%{q5bn$MUyogF zaT&Qn&}*?sL0ygpuB-8HTSAO}M>s9sK{am#?4YPZ-&6iQNsZvek_9gSiR=NWsX$69 z5P`B8wq-v4Jq;v3j9PpHMOlX04RGJA3N!&K>TML1&;?aiK2#n(z)iT0h|sQ9M~?Jm zQ=);+^m4L3)~P?85z8GbXS9zeAk;syO&7A@u5RoZWLkO}YA66OW9sU$PQ4AG%>@!k z_LD+3$)Mr1%2O8nFlz1C^}?cyFnJ``uNdV+NbYF7j~d9jo9MB?E&8pV6V`@mjcb>< zYY*%Lbxq7uSt30kAOuRoFGGoC4qh-LATb5$cauj$X)9<5u?i`|;s{!SU<7zFI19V&8`TRxs`H4B+w*uJB6ihXU zLUjY?2BWwyp#I+N7{<+pB}<(=2@|BDl}(bkmmte7y;y# zG}sH$2vGop=n)+j;6Xx2a5hP5`rI>hVnx@u)fYt9f-Ey#~5q(6zAfDP(fGe&qf^=)vtU>8~O#sL6^Khq5+&8Nca zg)Oa9?ry?J&S4Zhq#~xI^XN-@kxUuIb)2WP zth2m?mz>-UJpAt7Bb-p#k$I0zjFYaPq8OALwJX~0&->bargU#a2i*<2U~BngAGF98 zx?twr?qwS=dLZJ#7kOR+Mp1)bcK6rKl-DTI79)ouEQh>87oW7xTGn<@y<`H^&m-L; zyt^9shxs_()O=Wa;ZVz~f|gHUYKaFQ&=sY%C;8ANjngRQ%q$~NLDyc*u3&!k&6H`V z4w4un`+G`u`hZi zn(P*2#>T5qZzx*xocD_Gx6ThTH$MVE^Cm40mm-o0T5M)&My?*}QK9I#6Tb+kIKCU% z&iw5_vYNXG;g3eb-Z{$g%Nc7lY|Ufp1t19zBZnW2_HTliO}%GccNqyyRS8X+0#_u%79M^AP7{f z0CFYlA?NR*y-xoKOQ(A;$dH~-!kSLMkA_24Wpnh>;N=VTVZxi{61hM+icNEBkcS^x z43U9={iTgP;he(L2|fIe28pW9TgGA=(b2cvnX0}F1-zu@QFYb3L{^NVKTSEBuJ3?I9!XQ z_#JqZ$8R2(LC;V4Bp(u|W$#qHBw8+PYbW3mm1f$InZU4#MkI*OL2B{1MDEvsgk-3B zKpV1yQht{DN}>?W$;ReQ$zuScI8Byu(wH%&a|(-jX~TKgyiW2R;2ZsERw(IGg30c!@nYxkp3AU`b;F{j>>vFJM;jDNol3VEWLmOXK;iV=Nbx~)~%A^oz@I*y$U{vgWOuuJ(n zcICUYmm`=&mN=3j6;Jmy8%s&Z53*7Q*&5fixJJRhQtRY)t7vEmsjRV!WhkW$>t$N1 zhcjiA3imwB8k{2>?1*Xu#Tva+8+9>>ei$_2(sE#7wULGoCvPDBl2athpvbm08{Rf^ zdD7>>vie+6mxQyxIqt7meJp%^Y}$O-Nb7PIF*DoS40AeymOG9`^^|D&e1cmmrC%NA zH{_7E*1T$!Ypy-WbeScuGbAR4ws!i{e@Gx{cYaAh(zG)j+P?wxNeCtG1ci)`%6cAlu+RwZ~3k_V46l z-S50rH^QR4VVL)f7Vzta-u6&b|3>7FMofx2(hQOi>A{4)zEIMkH^TIqzI2WGn)h9C zG7tR{Eu4%i>=PaAK2RD-8uC>c%1jy0?*4-In!1YV5#roIo3TL$$L}h$MO2MF&4AFM z{Er#Ap}|7E_~h+I1eX& z-%H-v+u#<2YmV}~0opU3EFf0)GgI-V6!q(zRCu4sgWj-319f7;k#(OldNX}MJ3cJ? zYf#n|EgbA3M~l`)TCriyEpZ837jETRnU4OMVIF>3SpPtt;^#yhkA`!*uo~BCktFep z^l2VhSj|$N_O%&>3t8FIlP7q8;_j1h^RLlI@nMNg^q@%SRTs{!(Khk3O}}^7CvmLb z5^FRegk#;vZe+1dcgRG7IbzR3k{^z~JyrYL=({M5bv~^cJx33E1^wNls6O5GewxK7 z*o)ZOlj7Px$e}BNWl_jr=}QdZN*JenZ%w1z^d+HvT|l{%FNEy&)72!$5UU$rzP88r zoPnBUAGnA?L6g@Vv=mNt05mwD{6s6hN6ophaQ+A~8A9Ks60FQymR;+QS%u7S8&L=B zNEMDzem_omf51g`e%?`c(|UfrdA`MQu|QU+=8Sab`sxe7){F_JEo>8Elt%s?L3_?ku5(_Nc zjJ6rA-7e8*GAhCHv|Fh12BPZk-|_WKp-e`9Sozy{I3N5O3LeO6I$mxRDw%j_aeM~| z<$9Pv*V`vy*ZwgU^LMAkEhjBQtY&$2&$^@7>Xps=_xT6EXr0~RkPn+dCVe+yQVDrY zf7{!BESx+A@IpDGPaW^f=Jmym&jXcCPgerPH5Rj+n&4KYWFY{@j6B670W>qek5I5m z7?DZlLa1xgAY}kRGfhF;FVPIy!`%m{B_14Ln-#=Pwp*x)H1Z|iR^USkER;mFcq3l2 zVgba{9dKrmq^LNzWkhkZyAdNvh^t8Dx7yv0Gd3=xCjL#B#W2>`+$+uFwT=z!oe)a; zmZ}nG>UOr%_i#*};0_h0Pwy(4w*C3uFY6L{qA@5&384o^il3wPFugQkJe(~Q8YfxI z@>i*Nm2Eq3IQ1#h3F8G#-&BuX8Hv59eqN)%@IFL8k|ve<^*(){MSC%8T2bS!rGrLd zkAj^^XY#?CjHr`pMcIHN!8W%%)hN49znj&eV;TGc{foJ8m`Rg~FH zh7($Xy<7m+nNw#)Q_PFTdW|D`sL>J)0jc3t>Q3c`e%f+(93#86 zV^VrKXWxQ~`c!S^rh{{5-pou0akz1!>yWP*d-C_n^HK9i+4+L-G;vQe+ZK#VB&XK( z^rM9~{udoTzZE94*ViHI$&7KwkeCnQ%5cSHt9+;`b~k4J>)lTxtD_S3!tma_Z%ktT z_|LdS;pm&Wjtln0eoxRie+d=2EET;jbEhRta&> zf&n|c9I+Q;pOBl($gg10J^7x~`_wX9jCw}3qobZtejU_x#r<*d&Ki22s6^aD`dvoH zEd#TEcx#4NZs=vhi(~o))+1jUoe?;`om5xZuakqsfVG{p`F0b^#=RW6M_Q^l?K0s` z#R;4&-NM6STaEWGr(@pC6+uI~6s7*E=b>O1W8;<^6CFqaFkD2UA|rV6)@Q64TF)a=%)!*BqnhD4&BIWQja3WQ?Z2UfaT^b?XUy6Hv+mCz5I^TZ7RAUiUX7WHL z7e?T&5v_1+5J0w&pWSTu<%v!0rb4Ufgg(wezTCaTv`l8bqJVqn&zLYK(WDnqa{(cd z>B{o_yc=pIIbj%n>O=KHbb2;CU!ua%y^vR;)jsHHdXke$WPa>k->hpV+9g!YnDyJj z$M<2JerPd`(%fc-Csyy=)D(U}-YhbHO=jSDupl7pw(mflbqpB6Ou5V!>h$6tb)82{ zy(&Qf8dGH96CH@Yhbhc1QBiCO7)OOwj5^;HAtEmGA5*U&aL$R*+XZPDR5RZ>_Roq5 zbT>ogVceRE{-FRCpqt$O{=gaCkq;#0(K`RG7OQ0>jXyG!9DgF1cM}E{3X&rQO?Qc! z>VPSj!IWGZ08#7UP?aS)d=O%PP}~*#VxJBbBk3gWltNJ~!+Ow(NvBwM}<*YoZ&Bo9P5cXn1B?k|k@RQc#5G?rR)dGB&7=NZ-fzTv9Jup?$$ z>g4kHhtMIE1s)6(byLE%{YLgo9;nbG;!vAei3vp(!>Lbnu+d2<@7)_7$SQ7UcDfs*<)yxNa~Mz)w};jdBu){mi0LMjz5aY-+mCQOZ)@wNU(5_TUzbPFLv)5F(DpEfT`xy96rx<9Jno+g8DMlrtif zr*P0;hk7{X_dRPlHcDD+VHx3|IGX?~&{CoT;w^>ctPTK>Q7a?*ycbCs9k8O?h~@F` z7wKOq>t=H0CAovauWEads^9agN}r()&6rIYU+jJ$+C2r~P(~|oIrTZk&#NRLL*eTY zTmMNK)_&wC;!IR8Mv#VP(h`ioAm<4G)g8$e>6v$KsqWG{4$cxDU!t(}5y<79G*81H zs$@Xdx}T#Zfz?hDK|ZSFa4)sjdPb~C-z>pF%Li_C!Nk!0Js5d?J|Ake3^oQd41XUQ zBn>@-BxT&QebE*GBu~c%8(3_i1-Bgirha266$X3+^hsMLJ+CN%BdNoJ zz{)|$wn30*nn@RFoc4@^-~Z8 zqd*x1sZX@N?y?5dqC8BY3vy$)H#?o#gvxrVGb7@d2)8T<8`;&3+53NoFICFI)P}+| z_QSN$!gb03#`&mWP@Gqh;f7`5MnmCm_QPK9L< zN1M!#F3J&}wh>m$5gxWEFN1(D_9Fss!xSUKf|Mh}(IP`^BcsY9H6kOmhd@NaL^BI0 zHr`(BFeoC*M$L#gM~2c{n>RB-lL3&sb!<-kP@%}^(^SOs|D{kVWvG=>6e5|~pd8a= z8`BaQ(^eMKZV(fgh#Gws-pw4_>l1zfK<|i*9WIL<9f}>_kDWw|n`VxiRgRmtja$5p z%>qQ_(Fd0A$BntGU)cnLf&-!T%aI)bf z>fy-4{m2zt^K{|~+*5}$QeQQuV(JHr4!;yXfTz4P6gufc-%iBgd*$BBgl9sEXNrzz zu0o`RZfAX9%iR_b9bv3zm*&jEdy*k|;pL+drDQ9DXL*3@w~QMwjGH!_?!uCpNtb~s zo6%vB(Vd#v+n9Nv=YA}ZnPjKMN{ZJ?l)}H9c@&oMwme->Bt-=^E14xbN+AnomgR7l z73rJuH7ol&ep-P@c3qT(mW6wkoo@5+t5!RY%;9vRo%DM2T%{M8r3YCZ%h{^sIUh^2 z$53**4{~)?az3=-&XnWMso*Y%;4ZP?{v^d+MaK;~$eCox>%Pn}mC02e&K@Yw^UTUS z9?mu7&pT(y{gNdVagaUC5`5H_d++;h| zTY(=gYXQD$0ik^XadZJ`MFIIp0p(!pW6~F!yDu40`5AusS=lMVw`CJE<-c*u zEpRK0c`7P-%I(_VS!T;w`zl4zhGk)XWh5^vn0da^ASQbg?0aUTkMJG?1`XW z)k;LObTGPdxT12@zOsw8atxztnzd@=uyWSEY7wJqKDugUq^h@~>K8`!?0waSYW1jS z^-gs4I9cWBy&cJ*E`%EcQpj+2dC}XOrG3&Qk>*+A7864_YqwD*> zf$XO2Aeaq259T}N#OzeXC0L3uKUnrzt{XM`GRObS@0buiUL#v^XzyB&a zBIAN~&v2-?q3`ms@1T&3TH?3l%@#(@HaX1>E6vX2E$(8_j4tfkd`K0yIm2$UAF$P2 ztr;ZKYCqZx+GuuRYoXXRgDrRf)}vC?+DskVLSveDM>S|QX8R{$%v~3p-==<`g7)_-?02upr_{)2#K`B^$QMS*mfFdF zekEItk;|`zxORb(*CB{F8ps8EJ`qJ=9Z@y{A_Ah0T_D>jtQ~G&a5vV3OABZN{-5#E zGZa7I_f56$yD{GnN57w7{(OloJT_`--=r^X{<&J*<*t>K```>hsO`KtX3$Pjh0D&_cVQ&9J zXfNFj4llRc9L&iF6Y%d`YCf?k`+%k60HQ*Qls|wn4SuI?cC(IxqGMl*0w_-(G((7s z#sfCF0}iWEVUKnhc=ko5a8kCU@$w>#uN@=((XX)(LZUYB2KGI6$cU8 zVczi&05FUI55Z<5Wfbj5(-^ZbXkCYW!*PGVKL%9jo#M&1JS7w5HYD*VUN)jQx{}2Yr_tT~r(W$P^tE zjIuK2GqsL2$ql8H20Kn+{j7B(2hS#1y$>q5Zv8b1g(hi zDIkOa09XRFA#eE7wqQT4`#eqg6rat|P|o^ntV20BD5W=uoS>u-KqkQ8pv(FS3viQ5 z%)kl7)r2yeY!GWg*{gluANuAqZSk9I;e6O)%G*qA$4L6?^CXQ8NSr4BHBG|_rG2x_ zh@g5Q0JRgJ$1@zw6VC%!9|$<}QgU;!2UG)XEzTb*1-kPpx!0egFRw!myRb&bC~+5D zDue%Bp2lP&Ph)GXkXhNQodHQ>?7QI1)VBG%?w42o)4{!Vfz+FZm^DHaA%M>S2#O4N z>YdxoI=qD!_MY=QiigqxqLkYgK%659&4U~kLc)rvh9lI?3MD^)bP%`OM$+}K+)O$p#R}Um6*cX4D$8UIVYBir-WfAYl9tvu$R}B>P#V<T>oYuO=(e>WhbgQh?Nr~Dxu=+aI=)7^#O$XR++3IZ&X=HI_@(INr6d=0 zY#rMn5j?(*%@rKNDvZuvMyxyu;-bDh7QYk-ycGFyDWT;}O%g(95WErJ!}}t@Bq^>qh-_203X2i4&8;2SgCxAMAW}vx&Z$PsV;X z*wjMKaE9ZkO`hgu=U+{R=zae_A8uA3s7x9G1wl#{fwus^!nzrx>1wk^;8$sgxe-S6 z82WBL&UV)>B5FL52)Q?fGz9G-b&vbDW4E^xw|sussC@uUKm4G61aLq02R;r@0&BV; zN3~eEdf)ORiKl8FI!+(DYKE4bABUu%nPpMA%HNXJo_7)+_O#$n2Z2w~)a?yM?d1R{ z8UV|&f#Yqf8u(x4;f7o!hEOG~HO>sS0JnV{rNu^FQy`z@N zV>RJnz)G%>%SU=fE~2g9kSh~9ahoBxuai};2h4BAIM9t;(__$W(ZJWM#FmNs3d~m$ zRW?hjD6G=*}r_tjx+iGMo37`^GpZ^^*ViV??cyVMwnhbdJ~?PtNwhF?8T zcYm$?bzbidCl~abxs@Wv&Rf(!V z)`bY--TN^u7>#={Wev%6hk`6*1%}G(KBP!gidC2c5Vy7)^ruB=ldoY>Y*laLt?VmELgjS}h@QII_1+}(yesNx{ zUrc|lutB8!CtZ)(^;o{=gY8&Cz*!h2T*SjvF?W>WfqzctRsLiy6&~`irm_3H=PQ$g zj_uY!udT4$fLfhiAyXraYMr&seU#767)S34qdC95Y!Hl(K?VSoWl*W@zGbr;ZJC<^ zmjwM@dcW~n@%;P7XDiLy#P6u-uSvk=y!YD=57&R+27!ruOhYgQZ%xDS^?l4fl6&2n zMbf4Fm`AfU-a%jG@&UF`b zOnpZr+70~lFY_=aKFX#jMc>b^gpF|>-}Pie5ifij4fV4f;`0_7Onc7w*>%ive=!A* z_Q+VJqKzqsY-VWplg%21athoz|GM6;<8r~@Swt&kdR+<*fEW(6GOskUMykO-0z_^w!Qvl- zXuW&Mhuav-gfY#bp8$Jk{b=uR& zMeNzEnJh0nhVaV#0ILULFHaj6V`)jJL4@Hh{31D}*m6cN=_83=A?24cOD2iC;f(T4 zid)2G6cR{PujGX(5cvNkHo~7C5n?0!{~|VC|4VGV{ST`V{`cS>VK@FuZ$zMt@c%#? zFD{<0u5K?bo-cP1jN^Z~jSr{$|E3#{j-K}RZuj;cwzr=T`c6(xj*pN3JKcDJfE)is zH$JScJj~C-mvYwD*8T_GxU{tNKlDcU^z(|4*)w z_qiPZxeW8U1o@%T^Qn^Is-mRtYY2j9tgNgoFE1}GEiEZ2ffu|%Fpls7z;%AXQ!#Ey zabZD0L4JPz=g*(>^73+Xb8j*-ZxRy`j3Yc*{yseXIaui^B=pJs^|OuQv75)SmG#qW zr6WV5D;=F%b%E^c?DX{X)YR0Zq@;v|gy`sK1lkxD78V>Fj1U_?eE1L$5b*y(8*OcE zt*orf&CUNi+Gt>4pr@zzAL^o}rlzW@>Y2R4qb$>v7=mtOIusP%<>q~6A$z8$++}8Y zq9)m zBO4nV3k%Eti)$n&Cnq5xAtE9oBqYSg$Nvwp5ekJO&_)OZf`x^Ja2x*z)CdOy5sc#@ z7>taJjD&;)27^H$5D@Ws007Y703aHLa&3NhC>lP7$NA|PrUIA2{}vl_|1CC}|06c4 z#Qh^S4$~sUMi@eD6v3k%&k>NQ5Wk%K{}CGvA1w-`5n`h%LTt>@V>c|eo}|+FnvM_~ zWqXxij5KQQ$T6xEkbN`mkO%AHT-*;0T0JX|M33Kuti@BF~~&20iZCi2O$yJt_Pzr zmaT_i3GT0lLKT@e!U*(jH^ToVHsXbJfq(&Tn7S~;Qf)V*m`lnwquHB>~M zVQUBgW!XC|UTpJ~p6 z&cDS*zoT#>Ps^jMHs77Pw8(a1#KY?xtL8L0HDZw$fj7+^CVO3*ekHDW7i{?fgGR#SWRO}w?w6jo%{fxVtxAId$&;i zEr{~5x^v9#@RZjepo`9PK#Rz~;1Mbm&34V3@zn_66QoOJ!VTWU|7 zLhO7mR7?Exn8eS3h6yRdj?aS>s2o>QHoz*Pp_3j4Y&H;2J}4gi={R)+6s(P48|jc5 zr1^>Gn-+!Pq+T!IwtuOaoF~<|`svv6DfOo%&8NkgM~)SOd1{ zvJ_oXILYQ7qh%#l=;T&9#)3h}xSl-LM1vtu0icYz3k0gJ^?`!$(LCQ&ZCXEYEIUoG|rg-z44t_MtUb44@7Hdm(8%XGbJs!e^(oE*w> zn)qfxzZOTUqYE{69e`@T5qr*)5Bq^nrI%O=#b{OvX`nUU;P)xpxmNX?!Yn}RMeeCk zp8y0a7ht>^>LL2Z9gd=n_6xvWpZum8rN}Q_To?wmX$1i|*CX-}#RhC$k}$F=l1Krh z{d(T3VwfMFGLpzGE0*%*0N+3DkgCKMVZSp}dSi`^3fJz{N)(1C+B4&e?Vce4ObTM`7^@I< zX9Hn;Q9cJeWR$;MgM?jeDt$n;wEeL%MRQy9?!V8b9MEm!6}iJAyPH zNZ_(WErAydeu1Q&43L&%9$OEQT-w40p!Ey81%Y51b%n~v5V-RF)k zOO5EvH33ijrXk}TR>SSEyzuRYxzZ}y8s1~*1=neCjv8Nl;ZF3r(-K78A${!BUou{< z$kbeexY)oAG5#{Pz}568#wLw#wd>_ym-lS|zB5<+k40 zIS8##5wt8)nmBo`th9-Ps7I88ypPxjwo2R$cCl-NfdgiS_VFCf) z_6no8MoeC;ewX*|W=^lwc~QCPkA4SBaj|EQakRuQJ4CL+`K&Ar;|bd%!Fih zo3zG<3#^SI`JKgrXm4+rIOZaCF?ODHau+^=HsRJ25^Gip%_=OLSED-X#=<7K88UUR zw{#xcm3_4^?iK9*)|ONNAAHy8{jny4e2mxxAe57$$)6oqVlC%SmKMnwTe!z7S1O|c zlUn2bG)_S(jf3n%8@W%+J#HU<`&Xpkxv^Rx{V4y6gpE&J83ET?Mep2=`r6s^n&0k; zu87qCIJ~Yd)u`6ga-Mrvo}1kFT5ZA?;!#NVNm@NZbe^=2U;!2>C|{RqE;TS;^U?b( z_bCMc1yd&~D;G0hugT~>{4P!PnyjrNLVSx4*p>TyzqBWLJB;`-(*E`tqbD?QP8vqo zBGdi~+tBZ=?plASH-R#_#cS`?!fAN3VArb&!Qd6YIbdzjn2qLT_R8Zf@7oI*Ydgu9 zJ(mcHM>A*yS`aN6J^3*T;9J(_$tSCyOYiE!lCQBZ5-~-0!mQgC$oDS7)F(h(koKiP z&71m&Um#}!G!9&zLD4lGnD43uHJoHf=Keh5b88WxXBxf4{c&js((#(LHkRjA?cs2{ z=ww%i8BTDgCVsa>64MxuwT#D`N8?84f>4c@7k5=3fhGXyVim>d~BY1=$c73|P zwtj~EFQ)D?tjYI(ANYzfdLS*}=(-HpWPkZu%Vz~~NX=>`#y7LgVa5s;FQ4v`W8 z5s>}(eE(1WPwvM%?&IEe-PifP&X?@-y;j)m_1_Do`Bbt*Jf#p^-~sE4~? z_uNER}w2=V-rqi`%^j?tP5Q22PkW$dnxe zUWh_rFsfZKz0>HGa*SB5)9^gTdNkS!LiK)xU~Iv|^vcg%UDI+b#xLZdjRgFC2h~sx z)uK3yGxbA8>L)9r-k$q`xMObo5^?c)n!a6{s4=QgtOV7wuIT5kyoy1#9|6E9i3HoL zSmXBigsX%CgE)|H+|yt2KBNiHg`(INBFq%*D033@YTcA!iEXvaLj{t48^q%Ia56+I762 z5J#rwM+25_HSc@F3x$8(4+h+)9{o@!eWF<(=Zp?->$*e_Sh5i*`bq#z$C(2iOZYIC zt@SNOZ`$gx6ox1z2}8i8PDxySVr<>ARla5X0_A)Qp}61f!@{zG`Pp9id7h+?ao2G# z`@zTJ@GXQslo1GQ1!GS^4-vQzO9A&{V<}BRxnx15MM3r7{K9YfHQfb`-wG=83z}#O zTiptpB?~)33-R>}ySfV->k4~A3rJ6+TYnV3wM3A-gcMKB^EMVm%X7WAI*;?6eudduc|9@|7#1StuUUpnmWbL;Dl$@<)S}2 zQqg3)=07+01(MELN3x|3{wePo%@OLUgic${APD>|a_>v7Lh35QEb`<(ro?`XGqp>| zGp`J%Nl{;l(HyUI#s`=L;=B7GYt~6T^A0kLP1+)XNE0CIX&kCvx6q5f47<{~{A*QbF5v;`& z#6vklgX;BjxDuX@lYj4uHLtH~D+{OZ23bRf{|+#{2hK zGyKL`8jc{-hhONERAcp_1xS*(=2uLG%`DQ*_4sYK1+SrkmJ=vTP*Pn_C(D1nBeDiC zg+JH-Mt1p?d_&vkr>)`YZ8&yr%K2^0T<(Gd2w^Sw7JvZUg13uoH_>V|d)OgsS!Y?; zU;vDF<_zb1o9Nx)*6z~`YQfiklH~cM{o=q1SF$sJyNxWV3t8r|zIdO%R^$0XZ{YZ1 zr?_XO5$Ck6(S>>U>8D>q7YBEb(sWG=Rkte`cUhlg^|Zxfxf^rcZSkoqxS-Q6zg58( zrxFMJ$mOjZO+!51TNkdka*1!pX}fFjDcovRYPm~aj&%<0$oIrtfOJ_ zjP=tEfnT51nQOhn(eBp*!mj236F=X%`$9KLiL}3hI{~<&{m?ZO0cZgD6HXx65AN_G zwiN`6Jq9}o5G^9$!U&T3W^hqIiP!q8`=*;ViGGD=?{>!9NuU%!RL{HR-nD1sbf-j~ za1Zc?5exuu)@PABC87O*d!x_gvrb|giN7KMCuA9#(i#H04JkDYz1n;m8QQPni$fX+ z`NB3TQ;_2#NYDTPsPe!I(uqOSzykq%LL{(pibz8Sd|3*^1%NtE2|X#Xd1jeMe=W*NRAQijwZejlV*KH z*8uq7Ur=mm64)*uP)_l9Vr+7MtRiWsJ*k(-#2SupPV-SA=8@b-KtOiG3@D;W0ZMWd z(HkGAD~ezxormj`s7@d1jv$&sGry+$^u`LlTF27e_^EyD(_?~B8tBB^C35@;LMqfm z+rvin7TkN-@%n$T)w5kr1%tPDJXr>s+EXrCwUKs&*` zsKzmD$ma<;80EIF`6ZL5`@V2b)@Mf6hv>}|*wvC~rWtr281Df@VOTgx1OQN=ig4J$;@Olk_$Ck8%<4qXrv7II(=lAN~RJR3e5 zN#9$rnp5=eQ|a@MuU7lDd~x|>+sa+HN6Z|GuqzT89#?Y1)Cvcg^QyXD;dL$KQQVS@=G6v`S6C7Re-xf*Z)At>@{71G?63 zdHV^Ab0+?+Y#e=B)gh-vx%COG)1);1i(MwtO}~@f02I&Cd-f}r;Utg1Xv3F2@X|90 zz-Iq#Fq3bd{rk>MyponzmIK!Q`=c z+Q*;%@^;Nc0!PqDmyU{+rNZ%lv5Ds`J= z^2LX7Z!v~l_wV17?LaxIgy8gD*6ya#_L0FZROsLTug%H6Ngxj%xclSMTVO(S*4I$DY3r4e5_=D&j1ht-w7-JWs>^PN}j@pZ!hij9|vrmQ`$w`$vKdL z{3v|4@bz`!)!CFCWIPpEp?BTo)m6Rp2TgM0QgRJ7*v(-hjGSCTGW`6?2zU=a?!@wE zV3&JI{$=t1!?OcLrf<6GomxJkEy2oDq@Yed+j@4F*!<|*_*wj0%6k(Egf{dMPI%p3 z@&0-J>~zeBu!Q_>-O!}ehv*`SKvDn>U_4suk7xqWDd)ifNfA8cV+N)Ao63n4yf!jd z0!;T}qb%F(mBIE{0;5JTiyPUFW-1rAJB*yLge8aBdVZMm*REPDkKY|cb9zXgL?PvF z7~?Vh|A~!Mag?$@2uaffdq#aFIF4T6x0-Wbu2@{yTeeev>)^#BZTisZuQ2|uR%J>y zOul};Jqg}CQXDyFBgzv9Z?#UKmye~hINOene^Px_!^Xp%=K9N!fllIlWx7&c59(1$ z%pdk{HYb+gu^rZKT$^{{j)87+=b!%`mv_w{U{8sFn&rjs3-Ri#4`03 zxcscFY{RF=Qz4T}fsG88y|P)6fQBcP6%hJz?>x2AWV_*wh0i;PKHB!wdNR`DQaaOHS%%Seh;kh!I+%b}DnCi(Gyn z(hI?kY|k+9KTxTSv`bHjGSFbJI&UU4aIY$&;n-Y%Bo2F`-tk^nDP?v{nLdztN?U~k zAd~3mjOoy?N}P`=ZWJj~VXuPFX!_xZncJByyLOE(M@zl{vR!B>MAX zSM)znq^w7o@KS7Ge4lA0zdNM?S;ervX=>eL(|>_%(&Q&8wi0#eU>Pyh7Bvh$ zhJr~`VsKBX^50knJbA~_eB%!Bx*%M9cg~gOzKCTuL$%+7u?pgoohlLsUFs^_`Q7q>b=Jatr}Z~ z_0(3IrlZ}%?B3JkUjMe#iRn*edeM#c|K^f*`z^@qy}r03O8s5P{a@={%{=G#=k=4m zPZ_RvE0#2pydvh_{fT~0DdjN`{SK0^n#%q@tTgkB+h3!an&N-?s}Z(0eWXI@RHhS7 zyPE|y{FjF3+>JB*5R@E<(uW1xkZ^4em9J4wV13bJn~ddS(IBQ_9o|q^uqFc7Qxd7G+>r_<{FG)ov8Phqd+rQ)Z3&gD zPN#-7vAD+5T7HTZ1)vZW1eU`Nf4exyC=|VtZLJVAbr&>jn?qDUlmqns7kKTto_PjR zmGw;G)|iSv+Y&rLcxraD^6rddsHXPaOyH!kJsSxbRKXGJ#n~6eCh$;l z!j5;-^&^CREGL1~(taw3$e3kkrf$;T-Nz*ol_E&jJSa~rm>0QK-K^agk5n) zjsG3?P&F!;sdO%3ART+E+VboQVsRygtDlH(RQj2xRzVnlw9fZukV^$SA5M_ow4|ST zC~5-0-D5~!5WofgY@;MTKBXNMsTaOktNvWP@g58Ty#<1_V#ceAZ&m=BZ;VjUp>C=%_xC%g2T-es8EPz`F5quo|4VUZ1%3V7BHB{&JQ<4rme6A3 zvcq#VGC&3aj7e5x*n{EnTEQ)v&Vi>gqU^NYZXY_4c{!Gza-v ztQ>5BXqH+Hw_3#dqieFmbj*pvViJ6*W2z(Sg3l45k8A$-Yv+}dvrm3sx{2*+U&j&ikS{pCzw`ptCn;n-`#NJ3Q4(E{h8Xr7sujccs zlhkn6w3*2KN14!B{O`nGa1a<2z%=a2T(qGp)DDr_KRXc@93&gRUo8~2}&O2#G;y*j6{n)hN zG#=MkuH?&@XO<7|XF^LhqZs-8x5`Q1B=dg=`_A-JDu}v91h6u;a7ng0~+=G+=P-^K5LA&*j;UvsD(&H)u^`1f)m9E zWw`KKRWH?C>0L#EXS|(%^?{_`U3x*{#-*T#BC>&pEl-5&6>b8Ry?g^(pS7D}6=PushP?KUT}2_On?+oEwm z#slPj5lO{?7@zdV%J$o}`aW5;R#hrk$RfJ5+FLlwHB0)M-{Jx={>SHTdoxGFkS&Z+ zdRX*hfOlOVEEYCIiM!D+WuF0NSlpz0=oTZsDS(X@YTG~vr^j&x_2Y$y9bkxG8{?(> zCV$tona_T7)BQ^NdHvyny!%BjYEhS}Q!NI(<{B*`QIRgUc&|bV3}uC#k~{>UaBs#U zmGuXRFtdX+DSB3hO+RkUmE_l*nq&?N6A>Ju!{dEzMpE=ii5BKK0Jwa@6ed6-o>)K5 z00qED#dt})AGpEzz;VqbBBS$Se}U1;A-K0nMKc@k_muk11v~Tb-|A@g*P;Q6C}`NC zJcJNQOwcg>2~U187S9JsCIcg<#x+95GXU-#C0uWFK7dcm(`KkBQpQap-Wz~}35kvv z%f%ockf2~6{HZp6q)=3fV5NnBY$;%=+X#5m@of9K?;SasLM17PR4ob^;FH5ROYy`f zHl-BsBrir734XjD8x|T9(H|Mj5gidP&oisY$HSLNsucWSNLGGJ|v)@41fZJo`U~#A(1frE8Mk* z3K)R_VbUf6nU{bi742Ig5o2+n@sOwoKJOS^n^8RYu=glSd^#zSct6tjF!KIW-RtD; z>9KprcwGtH7mDbRD=@$(T1YZpP+u8Ls8BNn zc=-GE7wM5p;D`DUB$lN4UWkf(mZ3sli)*$BWXQt_zVFaO06g+yg*d=ZLSoml;*6(& zo5FHsQ^T6RucBC5qbo<C!ONxrlB0{MkWQ#bTRjFc@-iErXzC#k{&?%`N8%*rSw^(fCT(+o zKnvl>ev(je7(OzjNA$jdVtdr9NZmjGqo##qkBHz~kxxYvS{TQ%i55um@8OO@?eSiv zL5O;=U6s8L>oA6Y#N*SHhxVvQqJ{v^u#ifJqmt)l-C$!j;`hWA==0p|dtEE_ie^wB zKr^jj!n^k~_Vd{QZ@0+$DVt}q&Y~uReit-E9oH)UeRLk$)I2Vv3x`*j%iH)~dexbu z`&m2BEBc|Lg=%AoyLFEyCf8WB zj&Bpx`s1E;McqNBu#P$tA`Jih^|pDmC#DGDQ@C;xF#0Rp+CznY5xtM(38cC#5w-H%zWW4Vw=HH=yfRF+4yXjOI+D3qkh%CD$+uHNKGy=FvCNXuDD@%wK&7yo+UtGq)M%i zR42jmQ+z$q|0*g97Ya;M(wP35(Z)K*4FNq6j5Oq|n$eKSAh*jzQp_r_&MJz|Dw$*| zsx#Xl$&>?U)nbgPe94%d__pv6FIvBrU6*Ko%Z`qprg>!$bESCDW%%32=#T4HBUTa# zlR4!5S#kO_9ph2{V9Ptqt7PR&*#q5zs^r+hj5BHN_1$?8E;GHIBLM~s`LS4 zkp%72ULjO(Z zlUZxIQAqbXCQzHtBAT_IzFH8km`yCzTSv~U*Mh>h&2lsuDjj?G9dSdua44ubiFW3( zUOQ&XVTqvAX;di~ylD0;P?&QlAp{*G0ykfPP{ubjMqAf?JDhy0t+XVA4|IYmq(|y! zEzCA9dJe_Q_TxP7AIxY>i6lxbFt$M3e@m+}&C^+WaTWP+8%JiWGxe2DlFD?EI#6#a z_W2Z!oP_*GxaGP}Qz+L`gp?)ZrDekTd>RM9wm%L9!xXfCOBk_8<29_<$2>ia3qarm zW%Fm@P=Xfoy6Ki3xt86mEh_`HbKv?;aEKuM%TeXyA(Qrq_IUCuj8{6YB?_#x9{U25 z{2C{9h|bD~%L>qF-nMFxpdR&*9D@`9O3PT!zOu|&2U}0Yd8|WdWaDY4;;>_Y)wRWm zNxD@tuGR487Q?JM8Lohiofsq>tb9E@Cb|l-P6!T(5l)BU!*SLwmIpYCHdLxNt1N%e zuf1u9X$oY{Ket|FT|2}1R&t&nts)Ko-cy-E@W;Z^UU?b!Gvlc2kg35Ve@9Ygf`aXef% zK$g?g^W`+VwglC7TsbiQkRE9mMrz6w1huazSj~dP`JCeVQEy>=u3}yK^X8?tSw?x+(ow|L685Pa(@%hP~< zh*EuN%Bybv`~I1ZT99I$b^ojiTiLRHbdxL$GL>AjuKbV4Q4PAO(vR!x3X%$0)?>Dd zPgZzY1v3E7hZO& z#cm6H-v;#<`+qOr?2383k891be}6dA=kx>2f6v5u2kX(aRbakC)?B=|x)*%xa-f0- z7jOhf0F}KG*C^B?9RIQr}m3ldkbl zhtx@YUG;dKsTf~AgrADr?`|Rk*kZ1|^EUmbAELGdizsavV48M4E6Ig^!op_<7PJ_N znTiZVx`VjPQSnPva>dJ~fS>@NUc5$JlUw+`0Xb*q00(;gU4NUiAJ5>JlaBjH9rh?M z?v2=^@m8J=ub*0>u{r=W92w_ViaS>Q!!pO^?XG*_sJ$pHKyZIUXUOBVm#tL?%*{0h z;~Im`XcD8OEO$Db?IsFb|IdQ-M4;vNp;(z@_ctSMA9ZYErncCZA4u(Qex7%omRrwK z2S3gG4})|ojWcp~$bjavUyU#39BJjp?X<=mIYkcj9X3&F7dCA!(V?vcDxtL{7N%aG zRlOoq69j8xyt<&~`jo?BC0%XIN8i2POvUP=B7+g%gd}jkhwr~9K3IbuC&8zj_EX$# zeqNcLYO{@>^Ds_doD6pp$=!31r&ju|`^-O&purY0m!7HS)^rfS>e-J!x?b;zJ#r)f za?!q|l;@$P^Ir`X@E^$JpHZ8zq)PeDHpZZ)u0mU$%RX z7#i9S^+?C{?s{`@$Jhk+8+O~q;<)&1srUlMe!ltf<6?DRSnc=65j<<3*al^wi^Rcv z$8lw3uV5N$c~?xi`o02t#;@2D*0|r&9q}^zS^!wpRMQ!LoQsZJ!hmkPV0;|C_#-kU z9eFDD@_3w!r#}qRa9AE4oynbRL8r*Z=t@_zqyQTlW`4?RyDw0mnd~Q** z6Dc2P{2oTS|DaJWJ}Jk~MbE#!=_2B;jD7MdxSPnFBL;)OF^69nn+5vu2PdXG+W1w8 zEjS06SxTzm*~VVmj{e~>oGDuPs}&k|D;NI|<0eXTHVPJoQEm!MV#4ajzf%Wn^5b_}{XK%R*BaYu7*m2yK=Y*kAlt!i8=89Xzus zUH8th2kW9=8fVIZQFO%#9UIIvyD8TTQ<0Bn3l0Uio;d40E6@E^Py_2?9!zKkijU=v zVXcz9sqFZaK7R1Q0`|e~DBPgZSULR`vYNkNaKk2~pW5Zs-;a$zIPU5g!fQI?XQbaH zB7v@_ap9#v02;?+F$l!vveNmtLw#pAID86Mz^pG$T@pqWxBQze{LBog3w)1T8E@eO zr9{Ua21l=^-thRTp5np)AY3vY*HgqG2A@huW`Cn3E|!d)((zYX4CsGiV~D_(Y8sPl z6rG!&{l_dWs%nud2bw-L$N&WY0m^A8MbwTQ0f7)P1c z(Y5H|B96}1bAr%co-5Do_P%SGk;yqQL5blH)U}qr2fpB6`|Rs#K%$1%iey(te8u!= zs=QR_&v~`j=9HzTjziN7+F5wxePXj6(%td$tux<3pXKe}A0&fu-uMba5JgW04#s= zjx9&R=0hx_5+wf^YC{x|Y6zi2@vSG4#V;J9VS)F}?6OwES|oUp@I>C8yw)fW-loL@ ztb3#9U)DUkV$ov8% z#dJ^N1M18ev4DMr_2jc}PZM+tD1q-0TO+SWXdm-ZuBHK;RF;XZ2YGkJ0p zm9{>VOa{S0(NX`gUS26d=WrWjvWNPm$S;JHgF^cl9-Fd^84L0E{cTczEGq^NP?G&J z7}!(_q2g&6sH_qhk-g$EOh*U0BD@BBOgw(6|ER}+IoA$NtAaabC9 zh2kxN{W=_wnAVj3uV;?GKW`aY*=Pu`M5nQc6FCCX71EOgzDSula_hOGzUqDADP%=A zhpImpoe!KI#g(6oXG#>lIW%}P)51jL{!PgSkjGCujk9`kT=F2rdnib$+2yM?XI?Iu59RqYe4Lj7pAzP{b-%@|?b(l|az0BzcE z%Ljyix>I}{7Bcj)u}4n&h%QAtXvhESbFroD^*7p`-=m)VIqnU1>`}in-_pQ;*I{#` z`4%AzJD+=eGWB~}WdR88dZ_1c?3vJ)3F_N&5FL(G*ADa8YB1&|;QlrK9ecFE-v$%P zTYMjJ(f0Q%2>`s9=9?Y`u>Na&qaMtHlQZ(1Js%|e)EHilGw6B8^2f;=6H|em{g-Az*{0NC?eejJ<2DL=ZX&oz6 zen`3Gj6A-}t}#SchT;3^+yEIFO%mV0IB;7NFFrEO&aofyGI|atT3z{#AV=cwf^tgS$Yg8RmJGTu2H9O) z^uq}-K)AM2(Mtkuv2M=<8%DrAMbzKK0|W*+AQ^oW@jlZBsnuB8oo(f)UI#{@Bqk21 z5NdtQdgd&2O#(+j_ZJZ$Z-9QXkyMxzRh`+$h$fX`oymh3=X5 zrXZ7_3_&ftvX!EQ;H4pJF!$mBSx0m1y9TDHB~mRrO{1dgWh1;ZKyy56YfhjZFKOmn zRHefMsDi5j`MCbev$i&}_BuDMq@~%-fc8e#x|8D#ocO-;wAVUyPrQ?6Rt`EUdyhEu z#Y4!PNGmPU-|+x?Fe^Kw+%MfraYUOP<3-dR-+=8RN3337I})!*My2rN2^B^kQTR^&CT&3kw5&ON z&1*DSv0{t*S;heUSbrWzBGd~UoZ<}P=kZ$^|*=IqbUFjVBq_e?ND{XRA)NmA<1t8Lbmm_$%zvq+Bl;}{j1^0{f zajoE#?ZTmR?~nDy-~#B()p-2+!Hr5jvq#9@)1U7)K#`?rI(GnI5~n;(p76fJ=E@_0$8UBg2SCHb zBemJGX%9UG5H&=vkjV1+#(%<&fWEPe!sN?w&47MO27A{Zq(gWSFm@C5{x7pg zhQaebs_Go56pJDtQO7zI2cT~fxlIpvc5<^ua5hIz9NvBCsJxjKK^E~EGi|-rwl{4E z$Qea4l1@o*E4*$d%`%VX{;^3lB%unB;ZVHI(~kj60o{>G!XN{PRKYkP^a=<#7Ko5X zWWxaaVF+2=FasDv%FY1OK>Qhf=@HG05*a2skqqY6_&llu@TL z(&UuU6f@FRZ%~^?(xJ;}`xxm)%V=8v*JM&{SHCjETx&;Zo{wWtOwhNUld`OSYbZcu zBuJwi)Kx4ti+oszj@d`bb`27r_VaXsbKuG+RReNiQN+oL&Ht=^@tUzBlvo@Yxe_<+ z1Iip+OUZeFJfr12lT5tx<-FgS_{N#Y$AIM9<@|R{0!y2Gm-Ygb%zOo3n6JuhHxwRe z6eFaVGfB(UCyZoQjpUAu zI$|GlO;#X1HZ+L6iCL05ikyk46u_)nhE3i2#scs|P z3GR7F#qdbGeFb6A=3by9p=O1;I)#bF3j;h$a5k)EszP(ALSuc)X1_vtv{L(SOKGxF zN7GT~d!@3F;*eF8q8Kn8Jpff*xeQ(94qanT+4RGkoT}TFX|06TEhzU_>Y6$!>{gmM zv+6KansRL;)C)*CSajAS$q89SpqXmrNrYm<{wlfD24+c|tbURDe3Cmxx^~GdG@<%V zW|yp{mrka4tf=b>Dh{O))<{MB$OhB^pO+(|-0A%Jw&rPM1dtj4TlD>G&RL8tw=QQg zCN4MDgxC^So8Ys#EmgV^J5y0B%}GWoG5{}u3JzpD!hV(djXR1f)UNx~X(LXpFFy#N z05}aSB$e#@~+!=M|V|rT|d@9)yS8yXmTDFDnj)KW7QT*&Rq#L zmQjvs)JtA$md?j!&4}p!c9nV`=j5)R3#y+?{ioUtzD=VfQ%P zi%@k$H*qL*)auek+Hfi{@HmpXT2Y@nL}%`8|Kd9?(T8*{e&zM!@SkZ1RUTaj4PLCu zraw*C>P^pBCF)=J0+E?d9OWK)syg%parxT;%!|}5Vf}vxqI&sidK4KNxFCJI zPu|?)EC2r(!OTpkSExp!Yr4U*B9){Q*WR)raRB-k8&wczC6ZBPt9 zOuY6$N+|@XDk#}k(#Jm;mva6jmQe-$iMhjnXGwBM2QJAR;k}I(Sv>qK~7 zb>^~o?Lg*eBov~c1ad;aJ&?4AA$+`FH}^h~(M$X8&T7ZbdmV9UHiRGZe4#vOzvIny z|EW_wE)?&kRNRQ{;T^oL?Izw_AuBQ@0=K@v;k;F9*ulOk+2pb4VzCMHY)|zJNaTa( z=~YmAb`i5|wH_`H^2XqCm-`(15uwi!wifICjv_C1y)q6N;A_>jYxsPPWKE}_$bCM= zY?aET)}zgOkDqe<=ds_v>T1r~kN}}B7Uo0pwL`~~Pfq+|_U3W+$GLvtpDa@Dw&Qqg z@{x|$H~kjlYd%O_VPoASLN}uf%x3!?`==}lvAB<$Q%hjy!u(s zX?XAnYsvq#>$7S4koZj*_+~)XDc;WpAokUlSTk*PN3gsA;d_3f_kwh98;O{0 zz_3pt|CDL9Rfz+Bkwl-CNBTa23%<`0{1V@1qk>0PY!}q?we&`2*YOm}ccBpChxD@7Hl}oG*g(xnuNOn7cbLd+?bJ z%=aMhr=GIUUE==`yd`qJgK(f|K)fvOrfW!Zc zhtc0d99-GK(L(UrQXZH$GJ* zdGjt`?MY{KlL9xdl#;I^|L1c}d}&(}Xf}+sa$8*hEqe==Fc;y8_{F~G&yg!2AMDgf zt04BVMp=$aQmaxji3F3WXCxh1*byKj`zCyj;Hhzwn$?lKM3(MrVUyp=Vl^YG_j^50 zoErHKgl6}Vd+raIe=B_QIUj8qJQmp;NZrWaR4*EEJhU>?nl?L8Hm?{lPx4fwYLRF5 zrqyEUVtA#^Co23}#7M1OmWp1Q#zt@-YpAA;zQ<4nF51n+MXok~yAg^7<^-a`-;mQ8 zXfuia=DK*?5MaeD@j1tUAlBdPeKembHHgfxU%JdQsmeW=9n zr@sqY3j;Sle?SjZPun0;dP9rF09=P0)o0?F34FxY680Pt3t#*G@uPV|F3A52-5ZS2 z6X!OP2z-2%`e3!@dwVvkGM6^=5uId0+MkpYOz5LuS^mO)znN+I6}6juP3A)+s{Zb; zhZgI#pexGVS480)%J(R6)mQtD@I;w{*0{=*I z2@P74d{Th*J2oo)DY`DJ_-oVAL-StB;=#$&50%rcf=zo8)h<1$UqwOlzpP!F6_V@a zdP!T^Z_t0vU4@@9N=w^CU`4L+1C(1kOqaS7e*C>j|D%DXSM-Py>m8CdR+1j&D`$Tw z^Sxb~RGGK`XBRf8Kl-9Rg0JV<@4~lF@gD@v#W?xD3GB7Kmi&3$#6J9NVBq0B?3@=R zciP`v-4l+7bSjyE38LAs;CJj{DL`?eZ~C-&0L~(?EHXMn+EbMoQh{yl$?fR4o)jv5 zrQ8#2Hhu%QxM}~>qu3nHRCGH?Vo8We-&iF8V}=~9x+c66-sh9j5)HF=Mbp6)_%P8o zz|${}l&Ajq4~surf2siaR6T(123|$V=E?LgR|PRglly@4Bi;?Z zh6v&HONK=u(MZ`@Y{>`l-YYqoMdIhawhg2JRsM;qC!4kVKUuztTX3sguEJvss4@31 z0rFi#@AZVnPZn^{F&imEj;^3B@jgw&SJTfl0Bxl*5{PRk+V!8Q_j7XC7?1`5JXd>v zt|xzC_Wr_F{!&Z+!5Hv?h?sm%;MqH>pAa3Ri0KI#UV{D&?=T?ibYkXKUGK zUm{fJ-v9eEs|}nZwop|N03a7R{JH2!0Jx-V#$D-lN^vBNLg%Mnl$4XG1f6HQG8{f6 zN2fCi|M^n#D2?6VUTn;C(#qwxV<<8g+<7mH`}Ov50fGCh=yK!CZ1Vuf_@=?asXo z-a=b{zWc?^7UgX>6i3Q#N(k`&TnO+xmRa;K!*ntP-9Bqkn1te#DBRDl76iC`txi;WKp8E+_sW}e;r`L*}@(_Q7~XpuV_aG9HV zXnf2WdAbttAK5sPm;)WJKZwWKI5kKhIN_tnvW-+6B2ggxrARCr1}Smsg$oWc@4_5Y znT?IHr1+9TD0mr!s*Myt7bp||A(dFH-W42<$pat~dk^vt1V5G`BHE@EU=AK%KNCrZ8BJ1aoZHicakynAArG4Eb%|UW z4L*p_u(avp$l}j1nh&?I)4OJ`obe^HyfUsTisCBEOHc1s252b|napaq9mGcqj$VDp z60`!WX9aDZ0&{)X1mFtFfmXl2Sj)3yEZFjHrzhB){u+s=ZaF<5K=Bf`sVV)A7PGXH zGz^$c?&&pM#t`F;7e4^FVvHPn7Ux&|pG{C!h+^=$WP$3EH4LskXqb*W&FqVB&m&K< zFKkhgBBUeKg{2PN5$pj$`e7GYl=5-Bt(4Yrvo9A7fi`&cFNui<0o1w?ZvC4X8mf)< zeaD{-KI4)?B_?x%Rm#&HPm?p^1waE8czKcfi>mQ!U@6yF;mj^ajIP|022LrSCM|^Q z%-%{hyJ^WiCv%>Ahv8x;R5#*X_=5!NQ&P4B>Q2~jDtGVYU;P(rHioW`W7?#CHe5XX z@yJ|GM;)Lo!Rrj^#pAy%e|xkfWtKCP^WbpQ!3y#y44Uu@UmCQ*}p^4 zvO^!^Oq!T=(2x)TzEvCtjd;S3?)R2Y^E|%f`hGWAd3j67J-|-GY1}IbmkN@znJRhl z$nt#hqSwVDVlO@Fp^e% zCN@XY?Nz^ce#=q$f(7TR{}E?P$J*9!^9&S zZ4MQp5j|GBez=2Eta=#c#*%mA(VY+Hr?wk* zPQ71f7GO0@s$?*OQVZ5Fb;dsfX~CKSObn|IgTwJcj2w=ok0|gSSVDH_IM>HmLAcSz zlbH(1$_dOzU=7Vng4B#&w< z7K4%VG_L(v{n;rp&&;1yChY`9YT{oQw>;Ia zH5=y#-e0%Q*h^7H(7!mjDfk0IpBB<0QC`ivrx|fQ?B!2*8W(zeYSdO{6+cQ+JI*D( z?>IKC_U2u6mP`Vd&2F|n%%D}&D_lvb6tj<{cw~lqV_BT>nJQrWhkc|EW@7`W+VyhH z^5^L1Q4dE2R4`qC8m>4c=n%-GB;dtqTSj) zb`#k}4!kAhE^L@E%j%blvL~kC+3jMb{+)W$t4CR6!SB|zUXUNS$XeMF&ogdudvI&L z+WO+_({SH&9&N2GsLF#Q3r-;}Usrr~smjS1)bqFaKWudrupP{XTM<9e^XgLHT0_1E zcz=96Ckxvl7c|u-6jQ-5d7nF%XWf=PP57j6yud7vBPURau8frbNp7zyVa0FIv5!{h z7cs(%M|$f-Wz>&lCBCbO=e}HV=7x+V`nEyp{?*8=MEg;n&1LR<^OWXq`5HP|?|s2E z26|aau~v#JX$b^jih#7ot{;RMdSk7Mlo-BoC@WsCr#$u8B7*1t=~n%h=Hi2pr@C51 zZ1SG?vro=RWnc3BmSwj;DvzVj{7v`vz?1UkdJ`7jW+lf{pT0A9sOosvg zj8`EJK_&U~aFAE2D-p>|lSr&%9+fOAaGp;`#}!#U=Emv=qckTG=>RZTP@H%9rG>xn z_uHaB7X{lv2i}q*c5heP>!yg9k9#=6e{J6dSWBFyh^bc~@qa|imO4Yjuh$=mnaA^? zeA6xWL5%Z0BTFuQil1>unxvNO^NuDhdcmdN6T1KW^*d%`3Nu$yUj$F?!`DkmZnKox zC7S;VC7A%wX9UyAQp7XBz~m?(IZ8#mv>NVSyNTF7g(#|*rHotcA`kB>grf}8gd{ZF zhp4R%UrF68G4Eb(e|lc%*F(ti=k)yuoyV7WlKfha@!?PVSA!%SWu^uEjQS`#Z6M=Q zz<*+4ZfE5M+ zNTC_9D-{3~#Rx$L9g1a;2!J2{szTXX;aA<2or8}4bl8pnbE;v)6RsTX*^&H3%#o=% z%(W2qkiE=~SCdwl(ToohmdG=Jz-&@0Ot=dYf>nP) z0#oR!KP8p@zO zmDql2@Kd!EQUw92o;g3MA@%P+$`}@eeS|ifM>C(^1t$`)T9H4DK|ugfcZqob(qPcr z-^+-P=hJtI93X&MG{d|;7`K4z@fpIdJAbslL0a#dj$Y$pCh8z1 zaaCa!kK*yV`@V$yp$n!D+evW|@tRccuRppWPn>7ah($B^J% zd$E@yVt2*?w&PAzSel?!P^A)a$Dha4oXQqX%2RPFeqU#QxGMPC@!p5Z5mukEC&rc} zI{j#80S*C=3dnthCECXQ+TBFH)`|4F={6&|soWICf8df6)wYDC@+qr!U5gJ~pL4d; z1SwD{)YyUArHif9&qcHh&2M0YG;CWEce|geQ-N-{5seONmsN_4a8;8D+G62nrB;L& zY@FR4Nv6Hx{wo9$_1+g$xyr8JU?NH+Z!@_b33`l7;v1_ua>mqXlQef~rIJXb16S89 z3jvLwP2acg0+Q-OUJOONP#mdMP~urmeWA%nZSb+aiREv<%nPkmtk&HaZ`3O7a=D?| zmf_BxdU(D5(j)Leo<{u;_lW3A!wD6#GPRi`1r?kak1WiI;L@>5Z=_Bf?VXx?6P;6Xy0mwc{2AGW zxQ7NkEOOtp74Swcd;DI1SAFW5B^Jn&hu@s4rbClF<<4@7 z^{h}~Vh7o0Q&(x-N1e&Kz!X+5U8jXl9{#5nlv1{xtg{ zY@ZRrA`fNSKZX=O6xI7E>E;>gct_mxOg!Y{tp-!qXp2z)wa~a}No-e08l9+3V|b2) zNR~uIv1deWpbV-Jtwwjp=MOE3X=G(^@gf!;)DA5&W18eLLyQ_MZFSK&PB8CNO4L=luIOaSS0D6OB;DfRi(O7q_H_g`Pl16 zX-u=Q+wh01Q9mb*a@dg%wf_ zH*cEJOGIY+y^`M2DjwO8)bCA!l4pUo`dI|a#!EE0e*=r{R+#oXnCx;$vQn}IJF_V` zPRr1=SDlzFpuFuZl~`gZ$n z&aZNdQR`Ub3pN7Q+o>i8@1FfOP>M6CjJ_!P;!#XEX9dkD&u{*8!En3Gpr*H;%tpvH zY~xmiK@mkkjkb9mt3reIWhDiWs)B&!2LY`M3iH6*IgS7%cPWREeopQEJn}CXQUI&M zrXH~=KD{iBO-`en%^yf-`#?b9X$o;OW8xBvdnoO!eN-H3C>wEU5i4yulz`tru%7Oj z^{lARZ*ewdbl{(>DbMg*5+%N2D^VgA$7z9m$8-l;WQQ}}jLp4K`vY4NR`GAnNU;7b?d8!~jHP(wTITKh{67jGKVN>k5$H2JoTeL@rV zNY}vOswZQBcR800grY6#_!Merq%qa4F4Mh}(7>2mcls)Kn$dN;JsGUEWeMQC4N!`tc8Ta^a$1)%HC#s_z%#XYUXaS z+=z_`OFg(kqTq?K*Z&63%u&A9zC&yDg2`T`j!cUh?xv>j8^C&yL(cR5^G0a%*LP#z z^Mqb@Fpr~d+tRdZGe_YF&j!_*M`PP8blXhkS{0Dj3EXs`#X2*Fz|MOD+|k*Q1>i~XYVMp>@QO<+;~ua{^x)=iL#t`jM+M)eB+GV z4jGQ!AZ5s_3eKKKCb-;h3QM<>__4`cl=O_I+2LpVu{iwQq0y?A+Pt1~at6j*+yA z-5?wB)61-}_e;MzWX}j0K`;|2HBJ@t;5^AUgV;62bm5=_OE#$Ol9)4m?wcn5x!Ego z@q$*1^?{Ed>aS+>dW*}|{}3Cg{>hjI{v$SWV!l400k7k41_eJV1<4T&2G(L-vw)HV5g%9qalfMHGT_pJd2IkB7}De~VER zVkG=WZ2URN8$D(IGr;HWCCv8j(*Y@?n6RMM+FPHEzXaZPguQ3qSRj%eYw&&PF%dq# z6Mq1cyP77q_jvhk;alX{-~E{-n#>H_)5XzimKF2DyL8;_*&jvBA#$*wVgql3wtHs5G*Zte4eSNA+JjkqZRR`<)y9`?kC}@oDNL%UzA*_TSz=Wp zmp?{Pa%NGjMaSHoei>eHezq2=SrG~Zv>e57g_sfo5UfE-Gji{gxHYqtISl zL8HHG6g0d=QE)mjszrB2?P;r)xO`_YB~>oszN-DfX7Q^&F7gs3*Jg&j(jPcg>fn;- zL;;6}pNfoAW#jbk?ojwcLx?rHf%t{IGYzeMv$h8E@#=bBd)l_YVi}{gg)XHIU+8v< z?Wk{Ht&CqBy;>L>NsZY^QVgk9=36*6{Nch{?cRK?KWs~opJDw|AA1oy_9Y!e*-te} zp7Px$?&nLf`mG0=DsXZO-?S#BQ#*Uh$8olw>)gW-%I@fnyu&SIcM>mSH^>j?`Dzg9 zM)0sy-K0Ea%xvhX;m{Z6YT^q2?TgfIcF7!wTqKdh$;drw*^D-qK3R_+FhOY1q@KET z=k4c-$o9p6@A;>?M&CE2_eaL6gUc)gh#u+a(WoFEOB<4%CccQ^XyoXv zlvc|ErfXHYnOba5O=Am--K}606_No;)~^vl8aJ$(n>720lAE*ND_T`M#;3YMbyXlV zm1v1|Z}KtAo5F;Vi#$$0vcWNokVyd#6_=(r7rEjVEy&HVRAugE* zIH}?8*e?)Q6n+|2q$yIW9cOCryu$qJH)~X2fyfiB0d@VcD@Y>$ zs~1lV1O=Z!$%&X*LIi8?veDahW#3(){yxYl#6y|C&3Z(C_x%aZ_2a_$_5$#t+#-Tq zGjbJ3HTMdsw0wtN%xz1$K2$AlLObhp+{y@b1lIv9|1Wt)!4Q9t8N*-B-g}@Qq>kej zjE+TP4uZiZM1yoIjn4<8qJeQ#NF{h`<~ zRwC-XmKkYZ|Jw}F<<93j-9t3(J?D=#Wh$UkhPRK#`g(Q|1HF2kUt7&a> z<)+(c7Ig#3BY#2@ML%>+(?pMF=;+&HWg(U{O->Ds3Fc_zv^*kUB#DwQ<|xYEXN~DsWAB3)XU;2M-RlT1*~3T^eXw}T|2{Ukw5s&upRSw7q#?q2hV&p5P)80s$G_6#jUU4 z`FS(e?2!&mF2?)9m?8XaWJ`Z)SclDQ~f zp0WBJG3jx!YgREde`5h&#sPG(#4{obVKSqju&+gt5L@G^u;_lySQ3@Ed5PGUNnr?; zNN8W&WX7~a=ld!7dC9&C03HDF!A!hPPRe_)1fQK0 zf5`;&{nX&56n5Lx@Z$KO;#2`LAdji&oz7&}rbGtGsN^P$<2fQlLZMw*0@TEdZDPr~ zPn$>2@)u;6+7w108F9@?eF>tdqR%*>Q!OB)#rK-#-e+mtp=oVmEZQ-vI8X0P3oY}C zSeJ+?IS+oT|LF65n&I;g&627=$XG@s8QW)E`fb&}*~a$VH(xx@e0pE?mH_zHGS|9o z)|P(OZdz7BKvv!w5a&d~j|K6!15d-V&x^A!`?9ZhaM`%<>|@((fGU>Q4tsqcOIm^@ zzsM%*$HKumJj+-L)f{4}9O{T1kU=(me-48b7XFR|hq9nn$-T=(%@&c27aO_zb9r}j z`N1CrxjqV~=USWQibs58@CR5g15G{=GK2HZc0S6h<~>x+W46nC+@FI-8>##A)EIK` zXd{9vpL7>!U1ca)l5g0Lm?Q%jU*wOI(U|V$zv3#ecvoOlQXpQhBGIlmRTUA2h5p6B`jot%ZagnED+zBd z0*)5NG888m6sM#Y1LdD91wU5}E^WNW&=OJdxum2+6#-m^;IK}>6=1Ufd`fv19m(D{mg+_mMXdVowe*-dDfhDF`KmzS2=!E*+NkT zY^hwJ0`CGy`P)ekN67FE6cYkaYYbtf0E`KVNXL@!YmhXdU}a*6Ml5+I*MDo$)LVy7oe^^Ys)i%7hKrlQz`jl( zqfS^FVcJpwz<|oIBqAE1Kka093~TOX)Oe{j26Hnu<9kq@$?E_Bi9@&y_Vo_BUiB|r zQ~;5IgkEnHxVO&n197o{Bjby(xj505qa=013 zmA1A-HkS-keE0rDJPQ7SL`-KG&DuBa4SaT|0I#A60Rkl38X&--VKO&j14&NYfg>nI zz-k8wx0Zp$pPI%n=J--j?tgQQbItfNN}|y(IC6l#4QRm>)^I4<%z?Q6YvS0_{>Sjk zsWjqZ;LDAn(QieQlVFpk1{3B%dws@E=+jOF4}x(7>H+|GJOR%LAcPO$uK)lN83d@T z{fN607WD;S+6h2+Ny&UBk|*~S?I!)u{xkBcJ`W9%)4!y_k=Fn$V9k{LUOOQB5dQtp z;^+{*i2ia5|9C!W2OdGq@WG=)xEBqB(f(J{|5s-0IU@&OEJNR*@g=U%ul3fzI16bG z2A`|1W{_`IQ9X7Lo7ek2d?Xe^V!5#pK%7k9OCwyL-_xE{nQwqYaCl4C)CD+wzZ<9V z;;jtAv#j@ne4j5*PchH8^!a`u#n;$+_#68Hp#OkD+28;ZwXX)ucbPDx3Koh)yuv^W zHX+T}&qyaiI}G`>lX-~-`5&$tfYYGIhu++k!4aOJaR^{CYG_slF~2{w3<2aE!rx>7 zudy|`Py2VT21jLv@UY_*W@v7HXvxRiMakMd#QL4P1!mqlr+OIpbNKM}$Zsan<*GUl z#sR`=g1Xnk?jHuJm`8p-9XVoZ#HY*DLY|7o+c<)q`o(Zng!q&5^#hP5l2gm2DuJz(lqy|=^n z!+JzpY-8|5Y4`h~@!8+NDyNb>ftH$4OLZ~tIs)(%0KS7JmqfBiB$?M&1M8|_$5l`( z6!W^OV_^Yez=cY;kMODz>C^z|gs(W}rkpR48iV$!AP9g@+ zGa%ef2I-R8e$H&mm!I#6o+r+ke>31WRNhk6qCJr52&{H2a9#j9&-b;>8*MH8R&qQE zaooo`%4X7UK><7E3j^gi;PxaTZiGzOsdvn~`j=_ec;@HHm-E}13q;imfU2eK%_V?b z|276pY_@z|@OgHXq0Z#FRnt}u!wjm?PW~AQvwL8aHk_$Tjl)AzKk( zM76zkZ)LoH2)7$yu6<$nQI@e#0J_)F7WIVDgB!4g_C{*J8$%enUYFhGQe|!juVIP` z1X?mRU>5?ge1R5jEcrGTzJVggzC^gnROT2|<`W#O!eHxsh|QRTT|UJA!NDQlFB35N z&nnm_z@vH(@4~oWYsLp#SqFQI2ftW;5w5(ey64?*=RL^40RQrf0{1IP4Y8I{K34)> zRIOa)VnBZX1z7$?>4)%$^ikx1W!wGYi4`h9Y!vxB@eMgGn-Stn^~ZCJIhB|fs=y5x z*t8RFyXNS#@_hT4Z@I`JT;=QZARog#4B)T~4|+FdwiF_E2vh$~kEcI@Id2!_0nI4r zf~NVsNvnEI_+L}-D=gXZ@^F3iKsO(wM+ONFIS();Uu*rzCySs&Lx1p{MB@Srkx5^{ z0B!)RB8tJr#AjgzyxRWZLkG~V$I2j<;o|TFI0~LXF;hqXc#hKxcz_7TordxEEJ03U z94~()0j02)EtQvhH_%!{TH(>3i^t668n9cR8S{0fiyQ3f1!2iw$Tm^TXtkw6=TADZ ze|;RT!zuxdSSY8{<%&rd_aU@?xw_*`X_ql0a0I-Go@+6Cvt95;QJt~=a35HW1LvDC zoaR6_y8&O@@jJDieePK=$rNF(Y41IHpLir{U7Tp ziT7VrSkC;wi;X~CbYO$R*P&E~%W>(twHMNnlA_Hng_{Lnu!6j*MZViw+WVZ>S8=-E zik0*?ms_V3U=uGwn0lhlw``-x0ok)(kNmmkiK;+f<3;xr*p znJiv;9q&w3S}!eLd!HR`d@nRvx_SQ}u@OK><%Iu45;;T>Q9gH)Ct-9uln32ObW#9w z*Hy8H@r^q@gh?M)b!yhgD-)B+i5xwm(ta-Z8KLWTq)2Cxs3`zMk%h82oJnxPoOa_j zF@6e&u-G^I6kC+RRJ9N^#C6Yt;ax??N|gPoGY2O?WT$||Q6lZ=i9i>X@K=py=RlH2 zyPAY(`eT*5qz?wkZlQ%PD2PcPZ8kyJz|U7U3-Z#hdIyY4^R#D@B<3W~A3FCzfZ>bZZQWYmPkKg=e)W%mLp{~Zw)?H8bmcLgQRtg|fk zLG)Og&r?OSR{K{rJD#TWkD+;4=Ul(I0|P9RA$=bN;uc z;Msp^f*0p!cwF$`py0*nDei3l^z`(<{t1Ni4va-Iq`d_%<>@03R=l@3*oS2xn9veHy|M0Bf7-oEYd~9s&$B!TX zg$sTk`romFXT2T&$bvmR=bfGZO%`mp_*Qh$g~bgzUw2wxe(}9(v&PGU=XG_L4FOkm zDmQgP|FD8RJ^$ydAg)XbS4fH{18+*`Zwg^I1td55z_YTnt1^!1;#fQ`SYBTKZ(J}x zKmQ^#3zxzFJ0-Os_kS`4&tqecVq*U>1!K%FLPM^6d~Wu!ItfJKAP{n~;de-X#spfr5VOA6wxklRsh(P%P}Q5c}3u6V3a zsa~z!LVtbfRHbQG1oM-IvYA?A#YUvl@#aVh(BL@r$)}2i7SBJs3wvErv2AEV@`gDD zbVrs$^zCOxZh~u>F|12bJTn{{Ne{X07yAyg@uuLzNEWr`x}C8i?NZ~R=K8&nf(th_f^ag97Z_@O3xZQU}ALX~TnGdGe|No6e-d7_+|oZ(!YmSSQ) zqlJ00J8qd~Q&7B_{@UEr%J+W%^eXyAe;PKGB|twdEB2@_HQR4BT>qiNbA`jk~|{BZ)3yb-X#`Ckj<{dSc=(=e5~lfaqX4W zZIar1#BI_>aRX)B1I!4`E)oiW;imT$GH(-cJu8t5vn$Enoqp~AT}+Huq5Q`?`|^4B zy`P_i9K2svZ2nBgRLN1aXw{JNa%q z8MeF@N$*^?Hoz;_?F>f(`xJ&4#4XL$VI&0RvA3mzfa-mH4H!6w5Eaf$g_L=|^T{Nf zie31-5L;H`u*Ahx&Z=Ow>h>pPMu+o_)E1Sh1eiQg34wbM-^F%b%A0rFB%GFffJB3m zLnyFENSze;_ZB%oaGNp{^(D+)L$nHF30=%eKT?MfSKE)^{~(Y`st;XmduEM3;U8aL z)X6$OnfJh@p2WwIU+k=>#5V7?)(roZ0f6Yh;)E0NqGZfOeT>;JnFfKX8ENQji3>BCo& zhc9X7wW;z!@(|fy$gh}?J1mVI+XTEi|1t$RI|Vp;OqY+oaufaT4C%v!5UM1@ZmLO= z0FKBB&fG_X{$zk|bJ}N#R8*zgW%pG#Bc=uO)UA-wzLx%ximS-RLFFD*gC91DGGK-l z%1C=WCE&1Z03jyoB?foXteic>Yaihf-Q_IdBLtiWR{bJQs}MmzH@=bu@GQ!Llq-zp z4@iYqkt8A&pujHAJ{oIbBM@)gZTv~dtIy8BHJvqREJ5b9`(PW(aC{cpX(ZlHKZ$t> z1}I7#I>#7Mtsp;WJeIK$j379{((YD;iu1AIFw|$aS#anXR0x@xCC6B*gJuB=I1=Tn zyqcyE&%ROPH56gsW;4#y&mkLBK}sQ#3sSRD&e>q&J$}f*kLC<#-|e7$d7LlcVB679 z3`lcMe8zIIt@>D13&Y?hT(sRQP;oq#p;#L@?PmKlrT@9otK)l&KQ$hc=Z$F|jTU19|k*T!-|xqONRxv5neZ;BY^E`t0)(iJuxT@CrE)RmNHm|NtKeG~j7jc;WxOJTS zh>aK`%RCiC6irm>;W@uXsV?%B=h<(cmoi1&pOd6YrNg2J0@pwnXQ`}w>c$yy&1@!3 z&mSvR$M-_aI4(mvNuQ*0veHzCzu3o_1N)|Xq^uB{dV$EE~YzmNjksAASQ)yso5bR%VRTd&z?mT2~O364g7$OEJigtJt$S5Cj7|RF>8kd-^ z4XJ&qt7C5szL(D%F1lx|Bz-a27VM^w=E_TG*IGxMFaQ`^rck=AzY0rFx5}%7(Gtq~szNq<;M55U(InEYVS@~`ruI}Su zjGW`klid=^snGroJ?&4>Jh+e-_WVpg?A&>{?(LT%HM27u7}d@)@cCqgy3%#hBs8se zTPT<9`+|$`^zX)4>5bm}^IztTjpUUQBesr2yV)c#>O6S3%x0bUeHAU zRq$C8^^3*oQXZl^#eM2SoM{^a=wA4z=lE}Q_|LBRE4@WuQ~O0}+VqS2hS7SFpZL7# z4N&m({y=z_JHUkX)}5Kqz?q()$JIpl6bb#T0^@3JxFmw~rrm{;^sbLswSRjPyC5m( z0+6W|3o8y^H2~UrAseCo`ez|jbV1|QtN;X4R|k`)#I0{ROkUHWv@1*_{(fJ3Lw*-B zlOvt?UIjeYv%IhD=7c*7v)Twqk`Hwjq)YY;_gSG$Z46J*qYF?Dd3NSM)!{1F8z!sg zeMuT#62_TkNj3|BA8J5bi2zgpay-V?q~RK;q2dsJ|(D_z%5UwoaX&SkP@W+z*M6IfUCfS%u>Va>^Kk`ml(zcSG#nWVV>Sd$Dnx zp(he?r^>M)XMn#GTn_C)CO{}6p2oe+G43=smPc1_8zXOiEXCp*!nxJahB>8H4RrFf>L zylYDFnMv_IPeIeC`l^r-Pm%_BrH1XKM3^T1;f&KiPi-)d!@uAqOi6OFFgZlBg?=*f zemuKmk|uo;o)y%%ZjH?Qy`BIG{>Q;G;0LZA@Z5J?n@v%rkKCzE@@^4=4Z!r` zyaH-_K2+p?Fq>k$vkke+nYlUbGZL2hyO=qR9c(`$o?8Wf(;mHc7(Jl@T~p42T4&+z zVhMMn!gB&Q{$}y_q*6#`BhuMscWhUk;Jb(9mnxA}Bd|XhaygMKP+uVET@=LbRR%%u z52XEpWUhl}FvUe~yjiB3UM`2~$6%X}a{eKw_i_)n16w4$V#q!!*ij1gM@pn;J+?y= zmD~!Ia3=511=43fl**UZ%p*+8%LV0&m*h)VgJe%#)n`8zr6PDu$@ewjb50~>5;@Oj z3kc2fzex&{*hPs(tH zXlN3KGwh<+sj(1Cv z{Q@p4NY9TopdzAyk}8#zH~V6b$cX*n04_wOQ-y;|>3Br&Btyk;SJ6glxko=8TTfJq zL0NAonyt^esMpS@9olKwnxUaYIxEmrAF5_P&LP9KbKgG%FKWQo55Z?_ z2pa(8*D~xgiUbeSO(NjC7;+&2#A`J4^bi_`y~R-4u+`fDA^$|2Uca%^L=va_y$WFM z{Rx&%XM=#vwsSwikUKjOIxIsQkqG8?SZx*ILwo=lK_S{+CXNRi(NLf!;U5jKtP|PA zAqhCHNxT|g;7^=hYX0G}TD`Pp5ie-B=FNRIgkyqLkI{5z%K{t?g$YM zVj=8^c9>2ZxV3$9pi8=yGVahJBBY(HHS&Q0m46jf*rkI@0QUI~;?W`WvI@R{mH}3i z>|o(I4QTHwG(!O4bO`5BK(O^uLD;(Pbb<#pKoYH%gsu9{423SL-O=ENLpuZ|#yD1> z+f3Ty7Uadw;WL`~P5=Nn*-n06lVB33L2iQ~X>5n`bOIMqV5=&UjzjX075t>GhuAqe z+rQ_w5NNO+>~Lk{7^UZYRomy)>ulc+jME)O6Zk|mw5^chu<*t!_$3z3u|hC$NFJXH z+Cd@V0&sr-Ajb(hL5ty$LGaI~S^4w>6oCEh5M9Im>HIFk-F|7M-na8j(t?2G{KDF( z=EwV#EGVMgr$kd4KyPWDOhz;;2RPrtOe!j0yCm-fZg!>Yt^Lqs!$ex`(Pt z%yzpp!7Q5!_j4$k0Lvufhp?Xj2*G`XKN|WQ3u|d7jDOO!?9?P1%?ZIk2Jt=PLxzgb zdJTv1`KJwx4Ftg?WTum&u7mEIB>i_3$Ochlj%|j{?@Lq`hTi*N6jz9AlC+rGrYq7L zY!!$HO(6w_)7fvQr=_P{)JA6_5oA?SdP)O){TxIn$RL0uy=?~m^CJcCj1>2rqc^1p z(m7CLcJt|stq|ED7F@12Uis3yTDGD2|#)7&8;+FdLJ~De?g#&NOfLb!Ikl z-dk<1+=r4Ar(pw6n$OBCZq4Md`!F|I{-%r9|7+&7`_Mx69;Nw+veMz=NO^Fi76_NI zxC@0T!5U5z2k(9)CO1u)}ml*2sGm(mbp9EqJi zy`GBB9f?A&JXKtwm0PA~S>7-QJKbhbL== z(VWCMQ^+7@!!v6Ox`-tn+srP;vMiLuPNc?PXUm88;5$2Zw*gxYd!KH$ z31&xK<`=nqcX{Lq9d0(eShl{0t%t9E0hH}01?^2e+gX)6kS)8VlQot9d2Tj_^Ikh- zuxe*fPHFks_HxwE^_woRKhWJti{ja@4OsSG3@3P~=ZH_~&%sJF-_MhqUu0|~Yce~h zEEAy>oVkNwN#nys*F&FD5exi~GMkgGeG-K}deyy;wA%%n{1(E+ z{sL7KJNRxfe?R1v+NuCuTheH^})5?d9v`i;DbLA{AXE}znB*HGFc8II)4`UNfyCR%d!s~W9xa? zNG@+6tbof3-&4rJlIm}us1dL}R)w;eY-+i&xr&gG0)lmx)~W3O9&=qXKP85X*jaYi z=~~(loZ}_@a;2D{(uM{-M3J-#!0IeIl6rtHpk*}cnUdeJYa6jUYH6AOtWxdiIj?nJpsZ`RAp|CoZFzc+>=PXq61J+Ss0{u0WX z-Fkbf)&8OZM*$HwC;E*e6+jXE>Egem*PYgn6}xHbz&0QB+t-h4B{(UJbJaNsLxj6u zKZM|aH+ z)#@V>+4L6m1Bo@c0m~uJ1~Kw5ryzY!6(wg%5zP-YnMsrPOqgvT(s?_*ApJj)^~lHK zcZEvvtKO_Rs2ATC{IVyK>vFX|m@#9po zoigl*E|IhT_^Ot|O2Xe0y53DqDC(CCtogtSsL{HCO-Jn zzfxWnw}=+cl(>gxWl3Ge3`xmAIn%L!fxuclote{TBp z7jL8BG^L9k8P^()Q%)y6_|h%6^1u!M)-h^62wpz%$K;_ zXsk><7R=6hn?dP82n8CZGjbO>o(LutA+st120sqUMx^z2(#5<9;jlL+l1-KPK!nmA zHr2cS{i*Xf{7@fNG){_r<^Bjj%V*#jOi_J$Wq zNvS8DccOIBBWmwvt9e$4mZiSxKZ`5hSN-0e%D>g9Vs8%4IM0c8*lp4X^sVJO`+yZL z?EB7_S?j!;XH#0%^kLI&%^LQ0k`@9I4oQBlM*4S>kW!^ffuSZp-~0Yk-H56O>nqs= z)ST?h)5HEg0gSok{$RO_VV{X@B@RWqRE-EkSjd|KjqxqHu7-g~b2n_=yp0%3{qx1t zzAzPH`uld%$=%h&A%*PbEC>{6PMt$C#G1oA}S-{D>#2$>qfIyAhM z?mr2hr~)#SRy}8!@G+)N!F|$a3P1$aUqW8G}{e`95kkrD|qlS{Bm;3@03K62;P|zC3yEVmu00{Blx0 ztv?cY`Kq?@|6%JcnA!@vb^#|Of#AU%0u*<52wL3T-Mx5`1Pw053beRW9Ez1f@gfC^ zRd7nN7N?XVhxeWD%$aZI{Dkb8tl9f{)_q@9Z=#3MPagQ?L#dVM#p?Z2X8p25?X3wE zjYej*nv6BSr#l0-#@p@$^O-q%-z<6;>Z`OptvT9;%NdU!k>R>FUqgwK|9+g|si~Ms zF2oCfV7pE{hOxt7exgbG)fP)GDO;i1|o_x>@hsMSn?%Dc#n!FRt>r zN4=RnQ@*H{e??~7mYlHO3GF|Z`ORX}wpu8uQ28L(>>Z6;v9vjg?&m5yN#yU_gt|ao zujkTPpu?N^-QuHv=`lg1 zYOo}%8KY4pK+0p^1io>87|`(p%^z_rHp~y0p5M1=7WL8H&xW8H(Uz-B@1G%~id>tK zm~X`~5u+4LS1mq$oUYIWQFDb@%i&E-uMDnSWkuw*h^w5T*dnKpF0PuWA$xf=2C)Te-Muq z+q%U}w;(LQp1f?3ZHAt&1N`lt^1_4GLxY`y?ANUI9>Z-OpB7KXgy{jd6^s6pA3`>Z zcjRh3>OkZ?g%Z&L42`vPnuujMK=xhr-JB2+f!{b21cOLL1Dpj7*^4~A{ZMf1f`9u0 zmtpPCvOm4>wQzLEYmVt^XaPz#0~+g90yr>ukJ3f??eU`E(LO5)5qt3i7)aA*EDuvq z6$le`60b!G6~D&PXGCKGQF$TnBQ|l~Wxm%ef4^BS?bX&-w}MeYiJA3P8juZr`1k(j zGaL%l1S$Ce`xZ>=fkd3aW%1o|lF^KSx zzl|C6BvGu+2RzPdS`H|krs4zbl>F>JY`JT!h>W4A6|4wx0N~N;yN&~qLX}mq9v*AB z^AjGQpYC`9ssW=JqOeilq0Gx*OPKM8`k$!JuL# z@xiWGwyH5GSJZ__?wkZ#)r;kel(ZWzdR$`*UwF!M^eT90SkXZxry&U+k>r4Y zN8`zE8Stw~%11JmrZZ2_ejAI@oQS*_EB1{|+=j=NjM9X6TehhbF3<*iQ+q8uaU?%c zvLjhs@v&e9z-=y3o;}*C@zL5sU2u|?Umepe?Bm^mTJEh{fu%;Kc*~9uy4_Z@B1#FtnPG*;kj z+!qok4iXZSkzkp@AC#r>Lql_fTPu&Ny9f%fYm;x3*7~WT738luWyj()%QIovII#~= zqQnr~h>L;{{2GMXKt<(`XCJg53aegOw$z0H=g{EP=hJ`&?ZYCzs^M4H=h_SU#g7>k z2o(xNiKVGJa}zEO*3up9>#Tz!b0y;OOLQ>rG|mhZxf?uyq7 zQG(9l_UmTi%FmJV;FH_weKeh;_?1DKGpCH!7I4L*$eA0Qouf0tr_RBncsV^)nmYMK zcj&`wkQxj|rbj&T!7Y^FZ^ry13&`0q&o!cd%@4+>#{4rr&j|M5br))bJ-x*88AbEmq-OmHH2aOGn~bqmUOB|Z{TJ8x=rUo zikQ7xT(wZG*`5l@Pq4H_S<_9=J<-yOcvH!aq?L@9;s-dAnY{F0OwPbE(**%gOSitF z&dnI^Jhkl&>h(Lzk-wmOv6xcg#(_>o-1YTGmQcA_Ncah+7XR47mWGR;`a`%CdxY0x zzoBWzEt+ArM0F#^l-cx;=VHtbnrr~&}8Fa?|du^*BHeO%-}x!s_FE^ICF=ruUDjBN=CjU=|;QmC8#!oNC9Ha zPE-F@vMa|TZ?)Ek?7O?=GU2~gNQwNLAEm`_ zEP5At(~t?K2vAH7Kqtg<(kr*G!qT+hTVbI5S1YxYfv?WZG5sQsrlt(thY@Jy9pQKf z;dsibX~Ak8-Rhv_T5LXs^`?aYLUce`bJvkG)(9N|)p{J@5i9sxKT^Mj_ieM3?})7Q z8d+aBLGi@trN%+nzpUz=)@~P|zgW=ZH3`RotILa2XYZbzv#fr5W0vv;s-Dc%HayyB00KgXfgb?TV9gb#SZaIVV9k|5qJ`SFARp32Y|T&z zK+Z~YZN*m}@5$OXX!!viHcEzKItM0tldKN3K6FMOv7@Boh!m{BcyZ`a#m1G!j} zyfWgIwE@y^B*KlW&1hvezP@L1$loqY0mK6#@rK4f44oaX6OB~0;kWsYs9DrinKY4(euY2j-Yr_1S`0@BGpY6hlhKibFRELX6sO?NF<;(Vc_^u3N+OFvRpO%eyp zT|!WmR57#oJG(4)Y`ah*v^_u-NEd{2GM%nwgyE>|{31WjY$d@W|EC!`P779NF=JUV z<;hqvV%^Xh-A&g< zLrQ0*OXKcBVEVJx?3@-FnRu7y$s~SxgK7IGxzz?fq&oz2&g> zQHnT<852OHXIDw@{>|$kRW~LKhN*J`wyVLC?Dv2~V}O#>-i^}TmLv@HK$ZegwY;8w z-gZOI8_ASNKKghFKophgwM@VGpuYCAUcGbi8os~~w22TR z;bCjf>bEO$)NwC7zUg|WK-O)Q-f@k07aVP|GfI1V4GLeu>RbgUdjCQa*dJ@V^(}sr zxp6{xdt66)yhFR zdUI+4fXhU#uXLkl>HyFuAIozfK6Edh>Ypd%O#HLp$-BWVzaSsV<*l+&O4qY*L%fG% zn8zs_5bIf0vOPawFvE`fX@7T;C4Zue@!5{+ab@l)0fTcK!Xt76&eaOyMITc}oe_RQ zSF=I|Gq4!n(oe)qJ}@1>tj~wc_WTqnhG32TpiN(&c#fJPffCh%u1EY<`hEP@&_U>B zlx|EA?Aam8N+^#-*tk_}`TY0m383psJ9GzFb?bQPYm*-^lQ_IT-X$>+!A1rD0xR>NrXq9kU!`8n|2d8+?`8jWc}()$G=_3c^1qpHX#%cQ0f^WD#C2|PsOh>_tSQF3 zAMeLHW2Dy4q|(lcmOn9nB{a6(F8LIuRg+)>1IvfRh0exS*aWD!gsF?6ao+o)y1ZDt zZ#tqb=dI8$H4u+ps2Dt_(dS!aRBniUeCXND7ckh}H6f@36R|hAKeIdb$F&3xfR@8- zyWIiXy4R2Wb>}o_H|UMk1=^w!Gys5EzHBi=xe4!WFD>r-qUSyD|I}|exaCKqYL5Rj zUOX(b?Z&`l<|qF}*Th--qC((zV$CuOPs`LS?;0p@mtCH(R0k#A08vlSS)G4=z7PHG zLcjj8J|?3dt^^IBl-$As&_JK<$T8VF#_yX&F8M@`VeNaQg%^pi82>Q^F~6z+5&R|~3Y?TY5JH*;Fw^Ydddf7KLM;}3jb+a~p274qi`z|~nZ-F< zyVZ05jAbfc&}F{C?VJ^v#^9F}aQfdB)sRs<$!vDba#b5ntAkb!MYX%!N43m0l+VxHqzm(aJ;wgH)n0}CIjj6IwSv(fjrBmn>v?^G zco!RiL6$_hy)uTuELUauMPNw&?%K$VeVE`iwjB=xs}=RR+9=iC?dP92>#`A8yu@l_ zhxEMOd)}(nHCh(N6v~KmXUE8diL%x@MiaAeX}2#W znUT$3Z0{-vujq|orhe#o@*>TdbXP+XxuqrBzk+R9UF97ZEjU#K=jr^?e@!D+#Jw;f z`dCK&xod}7%CuXA<5EHBPL&uC5}cB^){L&y_?$aFnvE&?kCx(1r_!4bnv6i2@RRof zI2Q@B?*iu4`2OB9{_eiu3~th-bm1n&9J&y~1L4JuKLwIM=5Ze;YV{-ys2fX!KJj25 z$DZiN@DJex2p{$drQ_f_#`CP$IwVuUekZo(s~ziXiFR_!9u$#y>=xlg z8v~zd$p_MtV^`3{$A^640r}|+Ha=4oxePz%Ix7y1bbs55Myy^>HCPOuo;}RzA1dd=$cGz>iA@c^W7xAj`wpNHC0^{-yg;bmZXTWw2#u7{;gJv zsa=h1tRY@dR}6!7-RDQcuUhtQUxTdl(~E1UssdBi6hT2|wyAEdw#Y2I5b<1GO*t_+ z_O4mH*;MFKTm58swMj3|QuFAu2FG8Ioq83(c*imlNYKE%*@)XxSNyZafXgbYH!nZw ze5laI9W>A{{+Iz@K&wZ~G_X%}Vpp7Nw9K(4v(wQR z>I2@7xVMQ-cxs%97`~`*H+qAkZMZ*P70uY$iGmC;>@ng#SKT4*TT#UtN5n_jM&k+W z0XXL2ATiq^8aIhtTnRV6&js~u!gHE(^eq`x;kyK7`xO*4dlUHqhZdXBUfTq?n9eW| zsxzX=E;1$+OBoDsMvSSfAm^fH%P{(Nv1Esd9^=WPJzJLyfr~k|xk!1F^)HPMqPkd8 zvw$otf@6@01#!Fto;~ppn)UvnG=sG71I;CTj7y0hCJfl7`+WkTqKu9S=_`*}Z5|Wd z7|6W9$px+n5roHB=C99gmtJ-ZdL;Ur;o9U+#J*GrHr})@2M<))BTd}i{8QoaF++#P zVb8{@2&a@V(tg#268RG)(6kTI1OpLRD+0-MctDChL?%Y#U@|qX68_D&5}^W$@W$~; zX8<^(Cbq$~{}z*$?9DM_*PO(@XzIK+hiw8m)DCjZNmww|S{XG?3|*=Kt@#e+V`8A6 z!)=+kxIV}kvSjEjU=W344)6pCz&wT(nB$$daPv!3YI%BAEdEZjc4cCQ)X2jQx`rzX zj~u6X^Ph+vJ>}%}&3q`S5#pk(63q)O`^xu;<5|Hrt)jc$q#^GAKJ#-G0el4zz*fTG zJM38qL@B<_`E@hsMNtchcJ?|HNpf~=C9^~91x_ezE8U%-{HKREB>04#S!3XBHNH3B z*prY!8tYSlZbnSA1!ViA9DzPbT@Pf&#LxpuECG;_xL}58N;J#7pV8D`a7pL8R{{!E zCzZ>wa)c-H)WgogPt|D_jDkNx*t_xUeR>IHDy~Nq#oX~nD9E zDUzFgd`ZtxneY)jB4_MS6=`M=#stS_)9 zGb1d%o?>HLgkoZm`(p>}-~rFBLkTyAutQ*|xNdq?kuWRQAGo<-S6qxUh^?CVYfS`w zNSx(PoU%E`YZXsqh^EfDatXK*>r1K zAEfri6s})U?va6n|Mq_odgq*DLURvGE#CDeS6LxFst)AIEhvV zVJ4?arRqCK?2Kf`fN`XiaiqOsY8|#0A&1J7hnd-XVFL=`mR$3jTwz}rBbE7X%1Bzl zRi)8YPO%n)Mk4M@eCFFC{#uYECGTIxK6l1~)ZfUOw}gJ%3gbL%3nz_;MQ@Ae4tF@w zs6IjN-c3uV4a+4dA#fa-Mu)@YW0k%ydvQ<;sifIv3~*>p;}&6zy>q}kU0=X|qUyS% zvc#-$`zhYlQrTV!9YO){txzd(RH@lfCx4;U7m;`Q_$#6Qj&>i^*Ak1Zc@teC6F5OHKa8Nu~M zpOX&h-#qyQaEjMk<(}UHE`hTzVuUQ|RW0M__;C!4o!pgKWVW2F)$JtWm0Ec$+GJ=< zaK405fiO=-NOy+hlt7m+S-zF9Kn*`;eZDfRnzrq>`G;%^Vt3mYwJo4 z;qODg6o+N(KM(;5`9D~LY3^Mu%@kOtRd*|Ncb(js4mXt6PC%gOSdc7>Nd~L@84DAW zi+{nchP2g!ACAh`B|A<%)1qj(TSdu}3a?yzZ-1h5BWDZqT}|6%CUh)u8ZdYDhfHUt zKYgW!yGC#l;nrNPNfF?FU{EP-Cx}`zJYI=g5auImqZP0f69+yBF9^fjBf;DbDYXw! z|7jzPFb%-C--w1j%Vr`g-PizB02P+fcpivoHY)8+kMtuH`Wia zhDZ2nds~#AHT1QKtQ-kF!!DPKzSK33 zy-xYW90k;FrB#m2IQ0d*`=?)aI!4^!-YWJm(DyDMwl z*OlsfbTrn)sB?xZ+aqCdBDX`5;)nGL9$Kmo^~mTt?$%+v_GEM#xH{}0zp)xH=k85? zcnXy7AYIV<4!DOi_ljor&V&2v*t@RkHEaP1c#5_uu@o5qP|9{At0f*y>*2=gZY{#)Thx_*RrXocG8s2k>>LPV*XYzgIND z$=ywzo|c=7DGc~5`sTAN&w|RE1#O;1$v2o&gY(93mb`hERemixdo9a)t$8}Hh$4B< zfa6ZwlLRa?OGh%=j723!U@`^)!z0Z{{?5~Ojy~nPwbD>LgwGm9hR3@}-ndE6yT#hL z#p}IkJxB}X-BxMb(dONfvp7-RSk#q`03T`^3=R3RkeM0VYcJLdn zWOgnnPdc7VX^M)i^ZJ&=JBCq{71;ogtc`3{lDLhL9OWG#!2IPsvZyW(Yj673&v!f8 zbUVX$w{-lEb&&Q6>h3q+!`1QaR@41W(?9J&f$$V!s4r|~fldi^x!X|Ve++T}fA3dY zPfGWYbkw9glFM&8;#HZK9lc>{hNko1V(?=Z^J5h9V=%}sa4V9*eJR3uNrd^YzIx`p z`(-oA^J!^`6#5NsAQlIY2kZRd7s0;`EM^sGc{A~O6AoVs$)pd-Kc6+FAvnC51f4(u z9>lY0`sVFZxl}jy+w*{vdPmquz;Vic(mJ2BzKmN{q=$J3P?chHJA;!0Y=?89ql7#491HQTnadqXX z=mH**QaD|^s!gl+m5Soi3rQVeEnI%7w|r!j8BmA8*g)W||AowRVb$&P!=lD&Lw-!u zM^VKy6)46%vQ1-BPeEh*tNF0zdi&jOyK!E#)+atejR}$le&ZB*4xe@z#ZjZ@v+;a*M&Le-vyskr5@_@1Oo33vmZH-Hi{H&h#BPX>5)l)O_9Yi*(H(2j ztq;7K7j=9Z)MD;WhtV#I8=#^DkiH%24GnU7?yIRW>RKH1&tJr?`kcg9m9wbhfeE!c zhYBbcp&-2E3O)+*VcYft7x zH^r?syz2MC2nhL?n)N-wf(e`%6CXxFQia7v0ah6E#uXD@f?~{zZm{g?{2$4e^Y}6DFdFS z3$+P-Ys!c^C?lyu{}FQ%ie+&HNe?KBbd{EGhkB8P6mFQuS%<}>pI0&aRX@M6{VCqk z>qF0g8p8w0=meXIJx|E{n?ce+&nj8|!kuNe4-CkHw~{t11r0uc73JT zF}hsBS~&g&ic0n{K!I5q*d4vBeM7XQgS<%4ky>-k@yP37k+>IqS}{O|UQy3Ke1kqm zbqQP|dD}qn2bpWckRt1j&4)g8Vd`Xb9w*uW~3-kPm{PrMy@(^>fj&ZvDj-SY2ul!!<^xe8c|NXJtriSdp zgB;=sk$8r!e6-fCu-d$%>3cgId=*+WB%O|rSU|nIOkVzJI)jvd{t(bn?ZtmgK`Q?p z^+!`Ml2lF5S*wuMW$lQ4yBHTBhr-0iNy*jyA5*Ya7xsV<{;w%$RBzJatX%MG{k@!F zew>qvnul52qbX?Ao9p$hUZ=d^?&r_y)F?+J&a=t|WgW;f(k|tCyR>Zhe@wx?d_RY= zbP~3gFTnmzlX)~6Rd}`QLj3uJ%v268c*L{v`KE3I7e2Ow&KB?E@lCHhmrefNC~>-{ zrZAOVb=S(!{`TD-%f!t=H66wj*9{9wWfg@59xk_d@bKpG0)TshcVIg{n9ck4HZB&= z>wxEfGTGkeMVSlbyWGJ${@7y?=3dpBSa5b;WKm}fl;cUy)`06j@^F|9cRzh)6KkL= zRl_~SuPD-UlK?2uR#o9PmR*<~CehO*LjGz#K;jAB4?e`EPy%L$=_Hb7A+$JC&rpMS z%Y{1QlfpFfs$)+)n8*^+#IetYC1J1x+VP9l^F` zI3YXwiU{msVFQiYGvb+som<0&T5v`sSFkj{JJ5buFg{k#E>&bn_r<>#2DlKJY+c1b z89{8tqQT>K=Dp?^LN->THy^)gE(lAx6u&d#)N#s5T5@kO+Q@5+egvzVhnaA{`AvwN ze%*0L|uPv(5E9t9$rXKumQI!I1i_)t^-kT3yjo&Co(iDRTcdFzKw(=v5C4T8i?YU;zIB~^=YBZ5m zNJz9qwf@~rNu6mXcXyo)#|v~IP(dVnDV|XH z<*dDGZe~)S=&IB9yFZUnzJK=f%44QQjmXDNrSHwdJZqt4i9VATfw&Iu-Yvc{IYP4- zoGJ!Q>UNH+ekTIc+n!@%N_k$S60dFT6;m9gMD!ehxe|xU#P9Ej;-lW|qYU32*uMK%!ZtK$k!gGwGjx4TI=Ns59Kjb<9 zFcS=6TPK{ygL&a{hC1}79Zqo9@T#{TkHPw+et`U2>6r*J14f(<`{c$F2Z&Rsg`hT4 zi6iL%?P^yVt^4PL0*`KT67ah~w(k&pL&GK}sYEw+JXg5UDb;fduA9`=%&G0i$x-su z#8;rbfxCpL!8V?Ak8)gKdXC!!FB|uvH=l}^RS;^6R*@qoilvcNb8~Tyd)OMi-b;u3mNR$u1MQw%{Q}xGM$=Fc>i>wBbCbaAWw1$ z2m?n;;Gae1g?9zys6P6;k>qmksU$3I1NRciyq(7it-vmy^P5wsnW~Wg zI2bzg_2Q&a^-DyI-S3S;T5H#4E&fvTe%@lTw3|D<@nos<7VVj@rB}wH>wy?gm$5p4T^l2m zHH@SJjnWviGA&3CarFi(ngubj!})XF!UBx}?Kzy;uacbj{uvW6O*bigk(cPvPcx(& zdzP|yh4oh6nP57WAdBQGggT-u0)amV{ex~52yJ7bg8L(pyW?ciq zbbbN~s0sXS2$0HIG=Ex;xl`Aeri)j{v+LI0X64PCG#Y$Q&?H2|7uv?8RK~K z>|{#^ylx5o)X}8B;=w=o!2717F=t1sEdk+Ti0TzvRQT8j6I^{w5%Z%G9z#>KR;J+7 z#gU36?j^?YFvr4aC>o5AFKWi2ap_sC{S9c+s9|FlmV=Ockivf;APK>*VBQ)&y;l~~ zg3pHUQxLK}_5|cGs3a2aG!vC&Q>IBCMr^Lfyr?KCx* z)?`MTtU%Ua7B71cj~z}mp?>u_@_fl=S>cPSQ5T_U?UeG+CV8pw@BO^h6{npI@i8iV z-ng-p$ID|?(!?18mV7-e(S((08KwaJB2O7f!hO=D>9(W3-nS53^A||t$;!8$d(+w? zkUvLB<(~~Oh~9)g%>Q{4aIz6DDM1nR`5YJ{d}Al5tRJ6+P2N#F=kBhPW$r)a-5E=0 zRS5gd0%F(tbvd*)-;E*0gAvM7ASSwP%Sf7&q#z|B1dGJT=sv(9M&&x6h{^sncH98|%{Cf%h z+Q5j8t0&7xHK5^_@_lqYn8N zW;p4a_3 zlftScf$FO;i16^PJ>19UJ?Pp8`GgFu6uAd@l zJsos%t8!B2>~2^pcv6{VnsA^CUM%6eY2f@?!A6&~!Pc%L-GHL7EXQalC7*@k`=V$# z;p`7zZRrVs>~P@Q1H)|3DNjx*3Esi^o1bLxkZUp2oG@I;{|5q;E}@Q;uXuz2=S!97ZRtO5vn?U$ zIT_jYeJ;)UID%l>^aEWzTO{r$TE-|URz|F!2l$hi*XF9%@j6f*=F-?70^>;p1-8gs z-J60F5!w@A3op*{2hd|MHgSX6eRCI4LLJSRgWMvX9V~z$=$F#*cQ%P*%YGrtsJCYD zf9M1(4A4hw5|4qo^EC)7lL+M}2wPm2y=$+f)KS z!UcRsQm>WLAyJR@y5w7Ylt>I%-{xb(%uh?dtD6-PdE&Hs` zbveG3F%(v@Qw`0)_XV!XgYLPgN}Y-L;y6}6at&&3Jvoc8o^$0aReYHDwafNsYCkLJ zBIZD0a4V{CQw*`8)C7oitD)xtD}v77TR8#epLVjyf7I{>j=q-M!RM|5m{!7W=3m~Q z3Dhd^%Qy=VmE%~mWl@8$Q+asEPT7@(+BO7d13U#ycp||762wPbE@xOiijsUo$c97M z#eheZ#9H&5AK*esKqAmu!n6lqfAKZOBBb_ zV7udz&}(DBDHUi2=#K&>tDXteJ&QUQ&uaMh$&SXG9mpJSLP=- zBeoNnw3a}M-T}r;*ugo1>BT8Pc+~r@czwDs9~6-ZMdv|L9ysBPeUq@ zVf*PyStSQ1`s||G-hh*HK|$z(gYPN+Z^rSD>E4d>l+kUfdV8vOUe`?RR(+f+o*sV- zJ~cZBP`x~n{Pj$O$m{W{hC*_fWKX~g2O&Lup~-U|<=dJYep+Z8ph}r7L9xvpc<_0* zefFT8@mxqsMA%Cl8F?>HTQD9)@!)F+VkQ z2{;wsDbabG8uh!GC^j$(-9hofP%qO+wPqvmtB^oGSv>h-LruFe$ALa`=2N~=Nd7j% z!LQh>R=|hL&`}Y#)J2hRBm7^;)cZ;#Dh(C37xn3`>{yPCf7a^CRg$RMf%Vv>UvA>w zFNR`}>rF0}tS!n^!A%X%`7>afa0gj32L-ndeMV7?UmXsgqbp8QofUsN^m6DaUs?Xx zPNrvfLisyA4XUOlcc#j;W)5=pTjCDTp(?9!`>EoBo#bLy=PDnA?dl58$^Dx$yJK-{O0HSENbv#S2tMHv1!R=Rgv=H7Ynq#grM2kbv4JE`Ox)+sI%XN z`KNgMZ%gdi$&}g$zUQP;SAODYZC3Ys*rs?+mrEXhF+F)Wj9CnfwIk^2N`7~pJSd(r5|T2}l`?&uGAEw87?S!ENjy41WV%AQ5|Xyx zmGvS|5@=tNWW^R5`Vkaz)!7Ze|2 zMZUnh#t4{L;svM}mAYRzb;X<5XK_d*7=`ADbmdr?vDt>Qq~yC1NpRe<*LnXnI6I{7 zBV6A4gZOFkoC<{Z2<;*y>>d(gok(JW<(8jw;f4E4fzLr;%n#{?kBFLlo&dFS+5!2@CjHbV zx%WokIu%D5h2Fwn{$^XXG)8TP8#4o~@Tg_a;EOW38#Y-a4(297BC4EbGb8v$sb;Bi z_)CwuB<}BxKyy#sd@6yWzu_fjqJGqoUR32S$Z|DxDppka%aR)To?>Q!q8~v;j9~)p z077bes_URCyBuxMa@B(mwL!gE1JD*oi7Gd9A`|~wetLsQE9jUpul;;u`wMRRn!3(H z(riVdlF_emKg=A1$^`U}Z2(!0Dk!I7jNr47$1Lp0q8@4gqb4swj8R=>dei*Yq>(MG zl`G6Gu%`xvtRLE{r;*2&rD>m#w4bIfT^+(!Q6%iMRjX48qj|3Wq^HrYP(fLYU38Or zOP(&k4oko0ZKZM3U&;CVu(uGJ-qMq|sX6ueUkMHnxG66giqcxl3KQsi>l7*aLvdS~ z3k%}PC}4KbaU{j4oehaZ;w$ks8oM@{M;3RW_cL?5mS=l0o=5sdB%zB9Wp=n@vDlHt;$Leg4XWZKqdXHZ*oNJ=Y0{@dR#Y_L%LFl-U)192d&dYJ za`@LFQskeHfpx#Rt57uJXWUCu+SF??(xf<8m@+8h<=8UNg0}DwFQ+73vf{oKu9A$v z$gg8*z%u8@$cP36p{N^a20)f=sdnYKeNj2zdGcxZi!AraF9$El2@BHwaZg9x!Zv%p z_w79I|Iw-~3*@ksr%k)oPzoQ8>zSjGk6NRZ*t$L5l|C_Ez)pgA5Fhg&7x6?pY^j)oD%Y&D-~`5up24fRc6Nz$fggP&##kSR3T zW<2&vYW6|VYT?&Eq|GL+KOm9Fa)9m?5oO7e7u~c8)Vsd3SYO4wK{VK&vhL4b*YU4~+R=XwTVtS5#igAz9hPD5@MvM7Smje(W#B%%`~G9Irj?ES z+beO1bam{{e-w%buSoR6SE9;`93!JG*+iL@Am4$c+@49L1X@8F528ECW$8rYw^K zv2-7@6AgZumn2afdmfpxIhMFGTac?>weC(ANj<;Elf0OjDwxy8TmIZ)$W50HWUz@UBLb8#XCgL`}HNn=HxR1|?s&&9q+p@nE_c<8}eYzw+J zc?_2r-DgmDAeJKa@$A6hUc1Pu>vZOPe~hrMNYe1|=HI^uLR)0X=}*d_!3XTOR?m4D zH=c;II~^UhB+a&T{to76q!?N!I^~*sJ6Du6=F&+^xAO9dYWJP9pfcT*uROklx@1dfb+b4dTw=SHL=%`B<=I8l z(kXf??8H)rt>`6CXvczGlnfD{Kf#k_4fh{+2x6;EOXEd2Yr_tPU5ew0Kf2d9x_2L# zpqXm+%J8=I@+eIkTq=|^E)4Jr3WL;lsxfnJ$XcyAdXH))Dtnw7njW+@ygF{wzAZMC z#dU8IneUA!koR7y&k>DWfF`PnvU+Pni# z1HR~D-;-{}#aKONOnRn+w$pSb#SMLfS%YoY7^T-%#T11#Xs^1(FB9~U*1H-I2OA-ifPCv$shU@Ovr}rV=ymytkJo_YPb*pUG^zw>r z&I`*k{9k`J9A2tG!DJ1PAtTw4c8QR)vju&t&i;x0G4i6m1R|#>f6G6DlANp@OA8U<~6gktVWTm6R63aoUBg{Zrk9$)tu}}%^Zm;4JBQj&ySvNgKw%W^p`Q*w4?*As6)&GCVW^W9PfE9Zvs^lpPxC}GG zu?(wp0E@_Z%dm=5)Gbkq*3h7H8h-N08_tsF z9ESJ~0s_Q`&XZ0EX#oSoze11*r8#`mcY6v@iwZZaeqjX1Bt6w>)!|i@AU7>{Eb~-D z{LBmbpVVz04@IvGOk1LLb*(6R%OD#6$vc0h{@=Tgwq85|0vV#W%n$$^ixm?C$BXg_ z27K>We@)^$z^1heG`Q}hU*4PQYFPhH@`J!^j@fiiOV8KK28Y(?4Zkp^Ka5)KnP9Zw z}f+;SLP{_Ehk|TgmGTmxs1^wi&57#${Lubz?OWa8|V@$goAeVR#Lh{11Sj#J@ zRwLsI#hWap{mvFEQgR{J7ZT2Gs>Ixp*9o%Pcj*y(+mE?ugh(XgqbbNl2ZoJX zKC%AuH^&i>ESn9Sm$So-wwP~DA5Fmx+5*>$yy8~WF@Iic4mtZtMJ5f8&L5vwktQ{E z*KWEtO;cv40HPVKSdWFRW_XPXzc?a8qeKyaA&->y*R&|!Fn-%drYhn{%Pddvd?T%V z19Y*OfLbV9*YRrg#cPgR-9Nx4ZR#4~`yW%Vsf+X;9+y;X@0_!C=HBC3?DO>OOUz-T z=`b#ahwC;bca21Ss4b!Cg)OurL;(RqlPV%8(z|pK6qPEWhu%9vC<3Bj5TvW2cL)}W0tTrfLO?(eB`2=E_Fn7T zv(GnYzLLowkjYHmnLPJ%|1K&B9~k>CZcsWmESDT^{}@a%f+9U^ z$izkjKr0B4p=Kqg_Q?Id>(}1|PcnR2{2=9w{5MnZz5B5M#V^inE$nD^>*3G%tAG9{ zQ;;QGx9HR@@X6PI{@nD7mMU5RgU(L9GNA^SoyPk71j))l!X3d3)!2WTg40-d3zo+* z;v_EOpQhk+gpeFeh#VoTA1RUt$~lRJR7d8Yyf3vDDXkwQD;||G6Ti{s_QMZ#lK;ciaTYG;(=AwJ6t5$iyY2cqCNiC1k#juN_DPb`nZ(iH+h(-7SVM z2BP}{lf0`FeWw#gEw$SR&Jqs{2gGB0ER&kyLOJ^E<$b0jYe}EQ(Ql@4G!allD>*kX zWg{~ssWf@LI_dsWGFd$Jk6=pBfzr2ul!F7V?|G@q9%jELAHKJkpAI}@fJD3%%1)M>HH3l<0 zXr`d&KTJW1f0}~AG*dADuPG=i0X}2ut)-H}&z<|OB}*VaD|^sY*CK7|ZGJI#>Nr_L9m+nke?X^1EJI)^#cR#|uGGOQbM&hmwgRt0ab7CNREj`wCF&exQy50$G2mtJJ7;FP32UGchJ6^MiigBrXM4_+P%eI{CNZk_(t z6J-(nm^7$s-S&7ah}+T-<;YWMYxwx)$0XY4Jws6#igCe|g-l}Dg#uC-#43j6RT`~#h9H}=tP>DwrYK2A zBvlR!>4Z-Ev3$nD3!SQQHPq^)_3AXqCx1=BnkSG5_(w;Uby_BI&s?*YyQ-i%Q4;l( zW(rE8vV))GdzmXgHdnhI(kgkap!4aIUr$qcp3w^e9TXOZ(ylr;@*NaBUv7QA+RFD!k`IvL0bd~e zuF)$ZApOyha1=`}t#4t<+=Yc+Kp_@MAn;WNZ#2Y>fLJ1WK}r#mzn%c5|7v^|L=YH< z2}nf!38Q+>#J^tPDJfK*A2QMpqKk&*mEH(lzEL>w;$Q9{0^n}1=O6a+SEAmyckf03 zPh;41T>@jKw9NQ}j+aaADV~Mr&AOsPOntEz8^AA(- zMkm7;JY={KsnXXDzKU!#Me&<5k^ySF1{Nug4;GeU63Ky6h%YEoZ*~jYApUP?pkNa{ z+-jP6#Sd|>(Hku2uzQbti}#JI+#A634L~B&mA?7?$!qPg{l>CAC8qOL#ena4i9!PpX)X|W?TEB(# zNVghWgefw@lrE0=*AaB1If9dj4k7{~2v#9L+p)|-7L3i9=f&%NeoU`AeYpFQMutX4 z0P;UTL7&lSY3CveOH@1fi0~qj2`CBWUMd@zkp3Q0|Ni~PdnoIN2G0EE9Pb;CKIqrJKhGTC@SPD;%kqSi2_SZB zF!ksrH|z0p+sL5olHURNcK~U!YJc(wHKmw?^pZkphfX~gg1o@i;DPpHe^-M`A^3WR zDHO{(9&rKSm(q1Eod7oxk$VJYcQoJl`qM}LqpPGIFp6=_l;sWjSwa2B@uxsJf%%6Y z@+IZ2bq_L!rgD;*q3Mv_4u@USn)6s+^IB+9>?ep5Vx5=!4gYMn9jaHog^m?85Y}G% z&8+Xy?XGt2_cExi%d>rd+-GHOCwbjIm_+`noJ`T22OQ_8Zp}(#eRU{QmRwT^N$M3B zf`xoI3uc`wkpH}Q88yue93=Z5&3y*s=)PhY>E+3QDY;Thk%&%W79kzpqu+LXJQ3$Vfp&QWvkcA0BPCb)QSrdP_FtH zC|GcHE!=O-uXydQFKXPV>B1fr>M4a1O8|x(ADvoFc!(N*`u3&iU1?HGb@7U~ zy-YrUEcu5EJys8<5}?DH)|GoRC4!9aQT)BbuaXcv<5IvH>6wrtOY0kq2_fFK19PM8sDt%d#V)$PRVO_<0#4axs{D9=S=zZUUIimDgMAW1E}E ztpG{HCK1_6Fl{;=T^O;ops~69aFc+bd_UfVYzNn$4`~SwX??Kud6U*P+F}*>w)nJm zcD)vFxV7)g&HQ|eWos+_GHSdq6eETd4`?dEFUvp9{iZ04gQAV$vc zp~alNIC=gn>b=Ux(;WTo)F$=dxr31u5z=tw zs6lpn-V~8O_~X}U)J0jI=cY)OGdz!Jc2<*DsXX$NH^VBLFWBzgcI_`)lRZf3^u!gm zHaxQ=aP;YlpA4C~nNt7yI7)M1yI2r-?uTrU;aQ3GT|c*rcS3lv0JQmasXux050(3^ z$@e_}@5K{6i~y>wr4}$H{ii8NTF}O^ikehdPJH?Arr?fC;_Wxq1V_(1Lg|#NX;K~%#ZYkZTYyv-zPhNBtW&cg-p zZ<_gL!SDihV{ttK!EsWSx0mVxLZKKRy>d|9jI=N|y0jMVgC4K6`?P;+w)NiD3ayBG zo7@@m|Bop+chsK>{SQ;{870#P=`09FT-c>(qqGB9v{{Y*VG2ekVJ~+*(JQ>jl(EPg zf>l{6VP*UkRT$DUC{p@{6GGMm>><$w!F3a$WbdVgUNM0EYpjCNwZ#x-DH1W;ruaMf@karUt~}jeH=?5!X4OOe4C@)S)vD*z$_i6Z{GKbZpt>Il*2v0w;h> zU&__0lk%Xv`b$Q~5(q5+Huq|Ov=FiPQ8<@Wu!B!klU{hS1O8L zLr#YJb;-Y=W9CH$ozCi_nS$G0Mk@WMZmVhnG*hry4*lh!hzNDn2xVV@S6}@@y zL3u&m|0oGYM@L6QMEn;c7#tk@;K2i$BzX7k-5=gQhwj=x92|eysPCGaADAd_>*@d0 zIum~D7EKbob?cUwmlsVEba8QUbaZrZaImwpqe+4{Zrr$b?V6dH*?(Yy#>U151_t{2 z`v2t#VlWt*C-^T+Q05FRP)z0L*bo(45)k|+CdiJWGSMVK=rJ9{{M>m}RaIqW<$q@c zWhEtPjG&a1l!Sx?O%fCn6B8AsEouIDNsxz!=f5$6C=`l?g$0R3GBGhB5C}#_Mg|53 zI2;ax!Jts+e;I;Q5Qqi{c7Z@(Fc|bdFoIdzS4No(6z%nk^#92S79Gfa=}SdxJ8y`; zs4z$txl&_$C?q00uBRJgr{PPz6|Fnde4uvHmue}OSt5W_FI+Ag^!Ta;rtM;E;pD&J34}sSm zhd(~DqWOw*!j6{0=TfsT3TT+Fykk8PC@&OEr2om(SEp)QFp zM6+9XEW~i}4BWT}ZXtL72O}tw((TD|j_v)yrC96iyIGJ@yU*UHm=!B#Bn1j$j1 zxvUs42;2MQlxEl^j+*N56{U6asxs>u%?L(SQ#du6N?w1~IO!#2-*KHBMW64>m`AU1 zjWAtv=ka=0y|EyIv%Xj1g6Y$SF3E4T?=8H)zpRg$$*${?tdyt<_rLHgB~qeYx^?KL z+Zn4dM!MRkZ=I#KI(97zy$P=(zvZ^zo4hC6+z)L8+L9U62&oUQ^4@;MbbiC{?$7(} zxxCag45``VuXFg4a)Z^RP{Dk;rr<5f>?cQAAYO7mXw^U!>lhD{>wq^+>sv-*R#4k?^w!rCVgY zfx0S}h`xFT1wC}3i0wOABY%X}SUDAl9hM!_HZ@&uEMyGXC~)F8rBf!h&TLxTUwi~U znWyxb8(={t;ptB6cQR^`07eimAnsOAT)>#WNQ;BfftjoT4D>KB6B8}S7-cHV33+nq zNG&$Dn7zjby5Im%A4s1P8;)E3m=r=?%PFB#py2df^B^(;XVdV-4{ApYRQf_d74!+3WO3-0cUa4 zQAQzRIf^+?j_%8uc${%XM<}dgQDrB6V3<65j!XT4WjY<6Y`dx^h6|;jVfYbE1b`ai z0DxpKS7CsT2sQQ5=07*>IJXa%uSueCCC=Ie6Ci@UE$CPxjoO#OYseuP=q(^L%j2+CKMfOqf0d>b|#b#LWG!nP;C6 z693d;Whl38)8qM-yH6Y}>QgO}jEbY|p31Wh&y1z$)`vN5*z?)c-K*(syd>`lEvrw} zu(f!hS6US?y*~4i`tkmG+i#zo!#K`Z=dit~0Q>qmwdY>ifbcK|%2>NRowT0VZz3gc zhTZvQL&RCgR$QLC^L;(nWn+;&;Kb%Sj=}tE!Osp&kc>lJVeST}aR)H#YmX(cg!u?| z%oo{_12D{;Z(3&zag{n*~mR{jQ)vip{xM;V&9FvN6+oXTk9fyi>Zp69t6C zxDhL^@S6#0i{D?@ggCQ>bMs?Gyo)3+S2($eCg=@T}@4T-+lm1Tr#M3Vv z4dQ7s_qP+BsC+KmogP}316{JeRC_fJGGN7I`9_)Chw1f=V>3+(KjvrqwTPPRc3dr5 z)W7npSN&A4f!4dKJUU50^>ENM-{~!VQkyRqq9JhLxqA4$ z=0n?>U%z$h%;leL%{GFgbU{~OhL=;V*a|OlUy^X%POPLWN_9D}XrEA@di{6L%K0k+ z@^Pnr4s}aUUHQ6t5z_XvWZw=A)veaz_CgsIY4fMbbu@n1bee3|*fuZK4Et2HZ)x

7o9ZSA zRgDE>9z1;Z_Wr#e_jjAIFS|kDuWNm(booA<`S5< zD98_ltAHt}o`~GWBc$c*_TBmO50d8uPc4B`J|9T5i{oA$gnD)c=G;q&7)XAiESp7U z$|5DjD#7mHAs5h$KQVLw3b9OqdYCf5Cnl>~-gU>tVsSAN%A9g!lg9H&&M>EKaajv8 z(*P0JAF$d$GYI>!M4(YLM$j7-HPj?1X(OVgJRi?N8nt=;Nti5akzqH|;#qoSd_ zo|bSq_&xtP zdFv+Kb{fkj;c7H(WyPPl!VmS>TqMI3mZ6fLWtE>3lu!FVQ_z}UG?QO^m`^hV%V>t6 zRRPTqtj;f}G+k;JIS7hwxgi@zW~w0;-%?_FNl6!E z0MsxUKl0O7aVb3mi5$P!HI<{O`6ZfKg#sRh4bI>(G7~liKX8`u7W!g2nZ=Kix`a-9 zZ<@x+h~Mllm3WeYbLY4Yw}0NBvH7KR3>4W|#yFM+7fUd1kVEd{kzJ%R+QsV~0;2qE zxdu;+azXjYkL*4k4x-xSN|N}q19Hw}raqLL9*^Az|Ho{WkGq#1i?3)$S4W&^O=DNV z@0Ec@$V`TQm7IM_J_RQ72BmB&9Azym>Qj%;SzlOg#jR3fB663&?1`#C8%kMY(+5SLH0wSoSWm1EE^kO+Ps(MayYcv1 zCU_Bp@OFgwlYB-6D;nh8LjBCsQ`8pTepM$DIT^ zO=N={D%THLE!prA3=#GMpF48qmuj?Rd_ns4{IVd}d&PP(_QkCSh)=&5KNaxycuDDa z!OgubkG<-Ac?s6urCe<+3bXwI}zm{9sEq+H$g6$2W9OrFK9l8RWEsRj7 zT3Y3!7}FTr&Wg4@PHgu6*bpen0lUHECsxYlmBDc+=iQIzJ`C^&(QOI-( zo4dCZli#xuT*pC0$BU0`YVeNmgN{p1wgY?Zxd~5t2ROaZ$QeIHT|DA07IGUvwxUs| zh{#4FgoYiikvYy$2+CM!4~;f-g6x*R3L-Nk0zss7afV2lW7ByI zx(AltBn@{oBZwC3>^5W*Ba$}5hHJG4XOo|zo-`_lW*Tn)H4RaYpywoJLm$XKngK2c zZbdPHOWiZ56r}A&WAmL%6^T9Uu|jsn9HwphrpaOUC<1erS-&I(DI4s2&JTO=DsF!*ZO)vc3&^k7ha{ z%@J0e=OGsupnjFDzli!dt5(yT)C(_n4_n4m>oj4OF2(EPc4cm zdB!eaN~dZ^H|2=X1pq-)<{lD=HcDP2C^Dc}q5;~GyBBx?OeI2TH|uDGVKbqZ0o2`W zhKD7*m9QJh=bOw)8aaH%u0(LNl(YY>MnwGPbYy$~2@4r}2VS3m?4b}E7`i4h^6n1w zn9QJxg%ahE9g$rXBuFl)E4fHX$gs@*vajP@M@I6X^W_=cQnMj+)iaxS6QS=+KW+l$Hm40ZZMplhs=|)E{j5E*D zF;~A!p4WE*E=ryEmWkr`Ai3Fm`mjS&Qs>*u=U>vWXpQEqW?iK8mBBS54!67npO2caH{0WVPOlEd*(-`uv z&pf_WmWruT$S)7dKfhJ~;`p*#wTRu7Y@$c{T->oBpZR=*@LZuz>8#0|vOUM1K?%4U zWWLg_p)vQoaMn7iKHYYSd5N6!hkSZ-+^!g9kFkg&y_GptX|3H55x;z=YT5pHS?bY} z>qB-%$At+(;Z+lo`TX4OEg92qOlD746z(pG*ngqT7nDrcm8fJpyRg+*d(y1>=bccQ zuTPq=rxYU}wrzcn`l`N`{Rjmzg+Ake8lE9i<|f_hl%l;`vL6Qd*!Q83bLWZ|btAxm z1eQ@bpuG6&8;*dxoL?v3wvJI+pB~HQK3pvH-Ka1AroTyFv@h_IhIC9ml$oyEI99j)Uc5l#B@JGI(>X7joI8s;hxM6_0wpv=})FF#aLnBCgj*-Fybj5FER*I-vN{nl)< z#d&*c;`QqEopf%7?H@wh(#Tb|i^`8ibUat}ugDl)A#2_K z;)~pec7g&i&I|&(PPgAFge!@?+S}`2YV$4GdcAvogP!Mhv&Z-{#bfV5_Xpqcy;}Rp zj~aV-xB9d-LBZsmXzF6M$O&v=I`>8P%x zUy-uAeGrpMycWLA=tMDl^S$KCW^(Gft5@aY5`n7czn-x4v|o9JN#8ED-+CLB2j;XHK8w&%+{&Ye`5sw$dRfDc8$>OtzPW} z4jKC%oLtWv6!%|7&`bn?4iwpO=bJ4X=E&H+j^;LB(KMMNKUwT`LDz??QwJl((@VSa zh2uCc2eEtVKQ_`lcdvj|QVSWH@m-taI{8{HXRCdZa{agINZtz>x`@mSMRU)&*D<^| zHjNz9ae3RiV^J9A7uLVk3*|PZTB8x?i$X|**b@3pZ}0BB z11G7lb=%Sy!FP9mOLg6tQ}r!Z<;y~8b)<$Xs=oh9!2Ai`|2{`!1Rail{rI~2xxYl< zVc4HPe}-4LE`ngTXbhO8XB=}7ON11JF>0D(=!GjtuNaOBHOtm7S^IXkviplkvFM4^ z>r}zlVhSRp8S6E1~NK8LGZL|6l~`^#sD{6!Zn-L|*6%r|Kveh~~P!7!(0b zKvKhs8F~z)p7-1_FgSabwH(>5lL&RslK>ejj_bTDv+QGiia&qc*@>t0No{p8N;Up4 zVf^v_2S(#agmMK#J!*ieQL|>M(lxi(0w#`ml4ZNky?c)nHtcuq&DT1!+-T0`BHs^< zRy#P2jDad{Dt?hR%5J#+GWdf;H<+Sr=xIz!7XN6Se9P<#{jZ%H`Aq(?98RgaoM%DK zDtd9z(+B-H^PBHD8ZB=w?-9IeM|0|Zndwb>zBFBbX_JtqO*`YVQRw7$ceFfjAJm`F z`{>-US0@JmP1Q$ph@F@39wKV<43Sh@sx2qfE#`vE&3f~7 z&Oud{ay>RAP5}1k*hj%cK~cHUYTeo|`K~GPD+MR-C(5x?0AG$zeq-EgQF5FXF6kE~ zd$?Wbl-oS32DM%~-J+T|96qk8cP2vL-%e?VW}@{;*ahGlb=Kk5q2I)$Ej@ zxdT!-bnfChhxtGy);SFUlK-tUWj zQ}$IBOBXmc1#ao21~HSI7>c;zx0^7~k1PQFfOd~qr8=8iMaZLH^E+a!LdZ!u`%@h@ zO93t2tE_akM{*W)Hn{YYcO+x`+1L~@j@n|3h`7j1{I9ZU?Fc5k#l$p>^NaI^9NVPG zio4t}#g|XSa<xc3yX!H@dK9<*|*K~Z0EUT zTMb!mzIa&p8_&;Ssg6^35r`cq72bjwaBZfiK6Je)m%nI8yr+=USM+i0fRO5T7M*)- z_U1w;H&Nu6YLYjl!z^DOH*&S>j+d=AyKsuZP(ogYS+%if0HM`{^!YNCAgWgznX$ zxHKMyDK}npU26>V?D2$>RA{)MVY~CyVb5!s^rDVhY&T8w_9X=scjC_zcS(zf=8rGl zV>FsOJ&ZbWFL`O!8NE+xPmOG>eEj}2pwY=3`oytHl-Uv0R{_G`zb>XFBWT7Of91OW z<LiRyED5VTxql5Orpto{or+Xmv-}nWS78t4?zu{N!Ot2cUk0yWN+gFC2`6A+siQVcsZL%$Wvtv}y zTU4P*hpHQNL&&yrV64dZ{XT>E_zXty#)ugdo zeB;)J;wL#zP22l7J!`EL*bcjlX7;XIYwCI5sF>RnYkGXc3j9Fy{H#6y`JmxP-tKxa znwkDx7F5Ecb%UQ4pL%2OG~b$*x1A5EJA7@|$(HOL+17g=7l|i|7Jm;r89gpD({s@= z6Kok8b!r*g3x}3Lom$HIiE`Z-Iy{3PxrGhl4>`BNip-Sg86Oe0=;NQij*EJ*$ak^1 zbyfPYhse)4mLS#li~Jl)IALCbMC6$jY}9$I@JXfeXvkvcn@?( zJcdOsoyA;qX>~ZNGjBsBAe%F65OP|%SC;YQXJzqM04`YT#PfqEvb_*879#Ixj?$bK z1_Anz+$2gWZI=diKr+zO?@W#$gSj*=HgR1Y`uY02%^N@a+ttaxmtV=+%VTp57t@`o zh-v+KbdG5pMuU)Y1w#ZsU+Y^|+Gf6tbKz^y@AQTW#XrE?FPz(z_+~>TSNyQq=MF>A z?_+zl*?ab(Di?pYCRu$g4~h@P#$KiyhmRz(Col4<1oPywC^$X2Jzm zp-Fv$I2DEnT+3^o7qxFm8VNh?y5C-Rwi9zHV6u4Z8$sOe5oVURDat0{q(00u;>{q0 z)BAwFi~x8O=#?y^Y{}5D^qBBzPy{9_oD>gMBhnd5X9Qu8LiG$4n5m=J?oqF%-!U?h zqXsbyKiE3GFSMmngrdzEFb8p=`ykhfj$h3f>YsXahfzGkQf(1 zz=nIYA3%WhOt$VjMDK#qZpE&9H5fy-j?#5y=AM>MPrGJ~babDctvJ96VS9vHpf&?3 zsA{P5K}rOXE`ZcXhl6PWSY<3*gdBvA4ltXJjcAE^*UB>YP+3P&H=2d=5p(4>B7$-B0%)*}AME5mh(Koy^GK;eVaP^F08UA6uO z9izNya6D^OX|!Qq=Fk(JA${wrvv;9VTtg;ZV_YDKo|B8KtirH6)To6o z5vbN@xn^9vVX)HGrP$j3$7-mkXuW~6gVm1FVQH~4 z%7*VkFWa!=QWZ0YLU=Bx zC{@38hmC6` zp4D-@td0j-XU%h@uW2Xu|IWX{+jZ8(&piD}Zpa~mK8gMg{IVC<<;5k9A8J=juB+zb zBY5~DSvSnDWEy9$jVuvH{}>cL2)dT`q`&ych$cPSc|>%HT-m$uekW9&QWy^wj}0@8 zRg(kEbT1$L?oG$RtQ{fO>CMEPTW-*!tC%{>M9+Jx<31!o)wr&^>|NVxc#;Ls*|)&_ zrs>?(lCRH|;4>%xlv-TsnZy;EBm$85S0)%WS6Z~Q~ObeIUchX6EXlbJ}`+OMud=)N^hQ`w~0+uvz|1VdG~C_`_`uj zM*x{*rP?+DJJRfO z=VjFQ*}lWsX{I^qn}(05jXEYEh4&hkfL*6>|nGhwbKc zZI@;A9zV8C#Ly(Ag8AU+vy27&fK0&hHG)w_i5- zt~8v4f*gK@sG+Xye4h_f|D1|~`BUQV=sWr!Kpn-$A|Kg{{c1Yu{d`%*k!ggSbeVyT zAZlKn?R$NWd2+y&Bi;!;F!IQex9q(8fh^)-!Cdy({7d2vKMpXB2@{7x1t+aTZNd_- zJpcV9#YuzFrT4iz0^84@U$z?REofxkyC{cpK?S*GXpQbgl??D3(3Xp`vkd*iEKDJU}jZzc&|D=|21iexCx0Tm#+5tY&#FoOE+-hY?J#}I_kjF5{A5?{+QdmJ5`=!kYdp%1%@huw)?`}{%K zYjZ8=&u3{KU_1MU<@}n=sdy(WeIzc%n0eOmTzQ$UXNx6Fh(_}aK*1=wM+sl!D?QXx zmJ%qAZ^3{zH@W!O&5uJa+Yu6s{tN#(<6&Ysj^$^BCos@CW3R@%xc(t}Vi+i+*sFNn z{nh?TA{Ssma)M4P`O-V5G|l)y85CP$Xzri2Urt7)I6W5)9{$!i4K)soc;I1i76Yrm zx!eEoVxD)z#6WqlOlmDtT}>-tI;GT840P~ln*E1?YY$XbSFpBCZzgbJAak}+rv|?3HFH3%ZlF_{~>-$;blh+G0eC9Q9Teo6G%c^`W zzLPj_h3~^14(KDVMK~zClekv?1f}@B-zuAqNx>{Lr>1wD^KG{K?p2ASet^jsil`k# zQs*6xU&`*Az|+Lwia6L>rTEw@zdStsjMoZ(Rm}Hdx0>RQVNoEPq2k)Us0+&WC_O)< z1trNb&W#^_4(-9<;H3DA#Jk0Qoa6C&)BWiwKm}|-4__!)*`c0c`Ibdv6fOVqe@fG_ z*7)ssuj?V*JD9h(_UyNxj@<<;N8fV7Po1&gplj;7^ndleE=67KnlpO8#1}Ezt!z# z#tYZhyz?X5RejY(w^sV={lMI5x?pUKULc)iTHNL8Ks3u8^XFcX@U3l5Tqma!>*>Js zlTQ-hDjYgEJ{%-$qA{jKDmt5(>A;|ghu(LDd7+|DbUbj|3Q`jYxIMn$N;rK1xf{U} zv~?;dy1MPD5u5`B4PT3+k$=|WG0IidnQaD@0<1Et0r}%MUKKcd5{)9bHZP0)yrs8C z(~Sn$enk@K9Ropujz`LC(3a=^y`@KO&wt%{6CBDy2%d{;V#kG=+;?2vH+v(ns`@O7 z{EFQe9)MHngJF5|{3}YN?iK&Gs0rF^eSeMpcGbJa6 z%bo!L%H8^MG5iq4C!MjG`^t8Xv=HdABVrgOcpRhupNycI@*wx)0@VjQ8()8%CgBz7 z;izD_FNrbC$?MmK0;=9soh>(fWN;mg@;KsQt-!;^(`x9RC)_h=@)>H7NEiEUx^yeu zyD340Z$cth_UakZYulL&Su#yarvKJgzlKM8uU2%z{BB|{BsufE& zGptpbC{yu|5ta7*zkusU8QExDB+DswY;9`Xskz_7Gh*JSnSL6;wj){>-{sZ}S(X0! z_4CIAapVcjG~8m5&eHZxa>Ux#ShP1u{>7EECMb3ccVHSTSCsS3>e5JWgGO_)se`+h z#bi+D9l|9h18|Df)dxaJT^}+bnyT-$9nJW?nw+kyX)G_M);pDsYs9i&gPeNchb>LX z1r1({UH{q$5hs(`n6RCtT*A~`F^L5x1z3QJSiXn#fh(UkOHLGYZ^waJH4b(&^lI*+r7m@l1v2|P#6f@6f8 zGq3i9_KO-38N;rxn#?jIP*9@Z+8-;4d)A|kC$bPz#ha3-#1*FDs+lmt| zzuvLDHTbEG6sO~gdH(F&dEAfAZ70D|3+Pp%yXEzF68EfLT5sH)=$gwipYg1M$E%c% z$m@wOTfQ~8;Bo5xCE3;AkO9og-#>m{B&yNvODh;8xl;%(#wbvCK^d_kzQNzNV*|H zb1va@&_eT+N!nPC+wq|@^8u9a$HccwEaTv>axB0($1T%u;16AiaVn=SzTD14oc^fM z4;PY&3FNZlTFW?l`{{|T5P9#k*#)|+;2 z^tiuf5IUoLQvbT52lkZ6S53E`r)YYo47GfesK(D90uD?QLhLV4asdRrb8hm9KJRJk zYb`nwsDbklOp(Y-fX?~4&h$uqz*Xa*pGnm;4k?X~HwhJDFBk8XFsr9kDTUZ-t9xbc z_$OFy2yt~=_R1#ICpo?cr1rO&MAPcy(c}W|Mg87$L-i>xwq^W30{f+N{Gqu|<6Y3g z`S%ZNVvcaQDXzB+7bxW_*+yiN@B$6L}pIL!J=_e6yLI3 z)s1jZ5og++A$M0$!Q}fSQHC<45myCH;DYms?dpDijr5cyzABY*&;EcK#UxN>ELXww zC3do)+V``<7q+bWLf6fce!njhxOF{~O6P&GmRwSTXfwDQ3zZ^281VXPCcjdPWELM3 z)A_9#S2S@Z`dxxR9EOKor*Y$EVf>}!I`eXfH7Ck-gznC(r`iM%I*^Hjc`Xpft9qDfZ3%F#xAZH! z%GW=w8Ie4rWax79#7rCxyPTkS!SQqgS6FqYWB*$X7!vUPHmN19Ix}KSw zm$x7>O7g{V$I?0G-XvvOUF4l7?a)~bIdf{gN2mBqSHj!!Ajo+j#TMQJ*}&7Y;L;EQ zBc7lsitcUtuGmnIE?8*`%zEvURHhX2^0|{I=Fs_pY&jMK8u!H#g_FTd z)G~IF?@ob>wVQfV3C5Ly0H2@Z6-_#)R66!F(@O`iWI8QI8yz7cK-86mnlW1`yLPfZ z{9mlycTiK|`X}%Jp(Z3D^q$armtGPGy(FB%(m{$K(xizL0i`Kb z1f(h*B%6EZ-n(UXcYd?8ne+FV{Be@^JMDoZ6e_&Qs z)P-U|&e#@(d=$ja(w(}_pCZHMp-MWUEZH0}-!Cb`70Wq`Ooi5NP{JB}`QM`L0o`aO z)NjEzxMjVB{yokxSytR8Uyn{_MoU!4kOLy;)d+FZ$GBPvQwg00MSr-&!;!ErKU@d^0KwD{m>uGUhPo7* zCM{3$F?XMvOG^k@IBRXVWwy|%c4NUl7LpLZB-95WYJZ+ec!MWj!2GCUnz^T-@sp=_ z2IIG>lL&u0G@=C(e&=Zu707ge#?4eksKXXlX}pW*CjvAjCGACcH)o6|OX~W|3di2F z;QnlU9w#b9O;~nJkMbTNxLH*ctIV6Vk^7^mEcNzt0R%wZsi7#=OaXWj#?T-82E~z< zd|w5{5(x;Cv-u89(7*>ouxJ!#{B3eHvEb&ca-S&`>Q7GZ-lP})2ry`Zx|psZ?e}fw z?pP@P-i>;Er@!#b1@fX}oDhJlA`+EF!E}l?L`Y-Rn?eCE^tww)nhAcRs?ZLE>}IG0fZVT0){Ashbu%7o3HrE zCq*nxM|cz-Ysv3mo2wqZF6#;iK>cR6(7$V--6W+0yY7`4vo(GKg+ z=LH!WR?0^AzsL`MiOM1VjlnM&BrRFRkN?s|mvf`QNOW6B6tIfNWXe}-P zIY^62CR(<+M`Ak$v!&?AQW5lEFuIvLrbZSY5RTMDR9xS|XRO3#Yxkbe@kh<8Ol2t0 z7u)|RB8{-6tDysp4eArl8Bk}5>lUkog*}YTW4v!ctz~@@3cKg=K-7Ohg(qx;UWY6f zgHRkqz}LwRqO9;xewW6K6G-LdVV_P6X;pt)Zy4W`T=q5t=Jnzs+hT*Fl*$62+a~$} zwVm?I^^UY+2j&tzffsC$Ilnu0Tr|Lh4hT5FpYWLYZp?^{+5RTiS7oKuT?W zf9Ol#1%zY2>N&9(?s8s+abe2J%Q_IZGNwa1Oj;zU@lX8@XHctya+l~?eUAm2=<>kR zRn146M!+9!$4(Dv9PPAhxVUo6`^!{D`c_hV-3#p42Vcn`dQ^VYE_DS!Qhoqh?NYIxLKjWoDbBvpGbmT z#o}Gpts5N@1#_bSH{>C0l~3J%2IejXRD7`4-RvzIgl6N_x@>xE=|z%p^4m=WIhE)+ zg2knKHN*Oqrc5H#^gW`vp2?Q!3B1z7=VCcR2ORvgt=I@*8&j1>L?eF3fJ80 zU1`Od#Xp^hADfK6b&7^y=wPJm9fKtC3%rU|WJ0`AcCOjcl`-(20^ik#ijq`J2b5|D z(rUK-ey_+LtY}a57Hr088*M+YD9J7yjDR~OuzYwXq?Izpn&6=GlLH93Nun&=v8>?D z8>-CB#SkT`i7u}^ns7M)f zwHKc^*3zl2kgPWQw3VE$`3n9@qSKL$V-R{n-k7yp{I+t`GmL=hH7+uxnd^145Pys0 zuO=@PGwgMX9{-#BubY)$x0>-c-(^vCdrfdt#2TB6{Nh@>#j9H}T=;uCW@25r+(|hT zJD|h_Yb5$rfRBQ?p=mZ>_Z;xQKYRWDmcN&1ug49|y!yJAMWCOn_C36|k8iI>apbiA7it&2a#w)WzmF1JKf_Z0Ky4p2yZch$;OLIyUms-MWzD9WUV6Oh4_~3f ziMpR>LPr(*hhGGLXsRGDJgJ_1pe5%|QJD;gV;dEg zg$@dL9rwJBvKyBA>neBaMSyv>nA!kLFzi-)uuhZ{Q$O%{iT#zp1~ z5ezq-)J*hMHsYQ~1c=b8$h#*3IP9S2QpLdagar9WLSe(#% z6A4!ro9=BgH1g$Y-{)HK-Lh+5j5r9;2w&ksKgU^N`JRZFCSG?JWCLSmg$t2Qop@#> z`A9Pd=(X2;v(S>Du(SA*m+vu4!^+t)^G%azhFCP0_+QjR-g^zil~|sa(IR&ye{%>E zN&5W}+Ne|5_$~RWjt(<$-&BZJV1uq~U$mhGsv-!}u7lxzsgrhWRVuP!aSlV`!&A)$ zvwn&hoip}Tn0Ri5Zq;@YopaYXfe11C(`%4$a{LwkIBCMWXzMEXBl z^qu{{!mp5~UbJEAw6&ghpK;0RAKsO_^P<*wowR>NC(^uT%lK=89>ItEekY2~CztDg z7VP@+%)F?01eXf$lt(n7{f^N5{&Mdt?*5IGit-pr^suD-Xoymh-{0PjlU8USR_x4Bd{j&y(HhqUSlZTSdQr^dQ$G|_~ zgn5!$+yONV2X^gVeC==C?GbW84SN98Mn#z?BgpGK%IlY}iTk-^O!)nm{oMQw%M5Kv zTvEt}0A-7Q$?gF;BZ3=+I~0>hA^66mq7bTc~B`Gau%+ zx?S~@o#>f!^RoeIVPdcZAn<#VY>99cHCV(L^Lbf|N&E1~ZrK9NHYN-Pl z+j`~Y4`sX|*vCT&9gz)?e&MF3?C0+87ryB?iBP(SFYvc7@fL5ur2B)l{E&0E0CPsg zGjJt)lnD5HRo=#(sY{hse)c~h-WPJc(81oBw{@>@@h@rhe;&VCk)Hs`wf>Z!{CP8> z5+0`B)w0oez1-dA*F_zCJ+7VhSy+MU&byfx8RLP5sNzA9S^WHKJIR+fDpBF)Vv$5u z-MBAS3k8afUlp}?*w9@uu|Hla75*{TQOek{l6&cO|1J4#$K5~?n-Z2^HrB+kvKM6mJzt5-?ZeexcvBBiSiE1Hahuh-8c8z z@AqUMvkwX+Mk-WAiol+(O|HGCb=B%_d8w#qhse4sYTV$dEO(KbWiPY-#eGZVc#H8_ zGe|o8=f3GiAIjWo$69f>vdyizSa?(iyOp3Sdq9-c?Le| z+bp>k_5FnXVsLGd&vYZ0M|i|E@-MwVy|D)=b?1n?+Ye)s6tnZQ;+jH-a~%jHouRa& z=3TOw{Eju3&mi4bZSL8dW^-X{J=qG3y`71zz|?$TI<@D@`*32VpqF=!K4hfv3qFZ5MRSOa#EKXhmi)=| zXhz_RT&dG$8Q_spb2p8rOVUL884hjP-S~=$mMp};w=x$KQ-soI^jg`i`O_t2en$N% z=6GWfJ1Q>&w#`qBdQc5ZO_d3oRG}zH(BANd&vc3~dxGQa&UlGn5@|IDZ?~3#@ctu3 z>d$)YDyr}b4D}+V@yX{S?ovHdK0JD-{2aSEa~}oQ>Aws~R5BW&mhow!B^2znLa7)B)?hN(yTVKm?I10ISW@x8%o%>s<<#d?E05wKgPv5Dd9*@@O(f_^E&Un z?|*rRnM3@~)T6fru(j6xw}e4v(aoxl%>DJdINAO0;|kB;Vaas1k6i6(znAa6yWloD z)2xU~3|Xvgxt0A9X!A^;=3;RMU#)5t1I;#Vq}m$gp~asNTPwYEIJmqY@7!W)Uxs2a z;}$Jj_z6SCf2js3N^)L4(0}eOBl5aIPp0?o@Id zx0(kD6btGMq6dmJRU9?zqP;yP<}yuvKkeR~_LHw)O%3wuR}(%&d6d>8@*hNpFNXh| z@|_czyiuA?`ik9&b2>viR+gxq?VVKX-e-3FWi0g2d*QN7;UW##3&dFS0dxQk`J?OC zr!$PVt?L<3=9x`b54HH8X@@(m@*~X0b%u)%5B>VcRC4I>axV8BK#xtoyts`?#ZPy9ZtGeMf|7&*-CV)$EWO zg)2~CTd35KT)i|1u}HU(A8MMP36rDJ?6(u>uOgiHbDpl%36e_&o8mA zwknh3ggnYMRo?p~jxwCHjNQFsrZjxC(eai7>Lxkxe{>b53I3<6knk8F=h8>Owu#Ry zv4i264~x_}v4;@aswhgVMH(!Zl8^`Qf3@iS@&wzOt*CHg>xCyU@GYRaz2_b8a?u~$ ziiU^2pTp)${#tqKOIa=S^Y;fo*YUi2!|BpgV-b5zFC>^INU$SleYyQ?|XSue$NMIe~8bJXRe#_cn=N?KGOS-_Oe@_wL=+;%c=oKpw3s8uRn(S$eQhC z&p#H6pw&Z2%G24wBcveT>1YSv43jIvcCa1ekCxy6Y(}K}S2H3qGAisP31KHO66_o2 z&#_5~aC=Qo0RzF_p|RuiC60wZ-#WiNSulAvF&0)7ktwS1qkzPlKP2S&e6; z90bRAzrh!vX^a+}ZH&h0clgA?k@5)J)O(eW=SW=t^VZxlng{`;j)q0VTRoO$%)EagS zKSV3otr4)z&dRr35RrO|zPj+xNC&bp~^0Q54L^Lf3O|J)EP#hmJ1}VNrB6klGBhT!qzbSdX>*D2NN>@-tm2Lqbn_D7y%1Jb6e)~OB_V9A z(i5@sBF3x(j5P-7qYy-%u0#VRM2?%pq4=ON2iGwC)sfzV2*?HG^#xBYi6$FR)q7z| z%M*y8L~YUvL5yoK6lIOsRgGM=N2-mD+|m_v0p8ply-~Qq_1>v@*~ZFoZ;mN%FzMk1 zitJ{JlTi#m!uQ9QU0e>w6xVk0*_k(YtAT5n9VoLL%%bzOA2x<4#3|*BO!V&65%jsuA)gk3K82Z@fssqvw8b$6)^Uh<49Pwc z{%2g3I)4r3Ye*F6V=38mAZtjXI1PKMToS-B`g;WS!Jt3;c=fIi^MdG_R-=2mw=oTX z7B#p4b22bOGJfEpe82`J*kp{H=1xacmQ|ijQBYq`G7~gXlzITjomeQJlkfGt!U)>6 zjsh=4V{d#o0dTb^4N8hGtb4c<+?b4o{qkqd7jU5_P8Mfwu7W6tn^;Rv1+bzBHbqQ*B?bnFi`Yj{ zb1Mt?XV)rTqWVd8zoB|TL%Bgb?j#nk;Uns!>O z_V}0k^eklh?X#8_{*TZ6wt0*xRH)dR@5vF)(KF6*q#IG_*lI$J*iDR86~h@NCT~6y z>Itjs$!y=tP$nhe;FC7iSIAPazsDOX@gVEY4i=HF`orP_^QBg#* zOrV*(*4RFM`lP(7;#5SiTSP!(V@uy=i(>?ll6IT{cJu+j-Bs{Qg#DcWdzm(Sg)@7! zq=OU<*)D(#bLJpJL&if$UFP>dhsIGM+rgT~$(6?OH3}pdW=9LKrM~YRdgdISZ5u4< z64&N}3~))3bWNghO$s35XbIu*v!+l6L0a9Y(f7;S6gN?@LW!RRouh0T)Gs0exP7&mQ7Qc@qYDleT-4pLE(J7J-1n?lUjX)ueNW%` zif=NgAx*fm+8+OVD#-+6tHuZM!?MnY&Q%W}@ZxZoW34EbK){XRjf&;#1r zb$d)&`#6;1XEPuDm%GYI#!8NV1cw79hb63*&XH^;zPy29;iXiIHbnC%y4gOym{#+Z zpXNV#EO0N(=|eovK1axWP*HzFjm3K;(iY?6I^x4`5IzKT;4s}Su8YS{~K1sPqy>n>* z?_~3kwq&*^^#?+kY*~xep5ot4SK3JUdy#IQV?Ns9^C>99wKH_NBbFw(SU{SLD<0Zw zftNB6;)~a)~I;-ax zlz0}?1Nfz&u=@YL!!gGkSub%VUBHag3!k=xi?!% z1I=4bIa|ZuHoRkGnUsC=Lhc>mlf+4Sz+#v7a~sm$-l&UJP<;sZg&=*vVoV5w@%!s` zh3l3AUm@d=UaW%rQ_xMXb%xAa1iH4r?KC!{O}d3YUkPiL@Ok0A?#X~__nRLkXSF6# zZ8r6%Hei8kZnAJwFHF}lqs$X?o%f5c=VYYZyGM0PnyA^|h6uuX0B&cipm++N%&L*t z?hmS`A71efsfQR8bdO^%I;*wDm^n#l^5^%8>Ul+60k1#4J5d*A8qJW8z%n)wERQQO zjWH_^c1;cbwdsjjm$B~};g;#R?wV%)JAQ6aeZ4$M%rv!N{>j<_r1k)M3)s$9Cf$>m ze#cbsN8Ug?)LnzFmp62-TxwACol?mvs5TNh5=N$Yieru&LOi?t>bw4)PaInejponA zSr$Lcr^Ox%k`5KU-R~9O)`%%kpZ)d3lGU>HHFLIe_xu~n-sA$t9a=9f`JS$#2dO;Z z8?ux#^J$Zu7Et%Muh-hc%TL-1<^&6n5Q~{OU1)EZdRnYn{94Ie=*!T8lm^QuFDy_$ z-_8FDMY4pD_Mo&~3&^H4c~S2w08eM-7{>{>zwKMh|4>-_`(%yUt|HB5A+8Q=a6=n| zFRORCUiq!)GH(_1v?GRj^P|NkWq)p`O-X&s7aecED&P(vzK{E` zAU%TGinkz4PX;q0N`G1`He`I0VcBwK>4tuP@IrBOdU@E2nU`ugDw}YER-EU8T-H+Y z*XhzPto`lwu=LWv?bdMNvZew(HirP99Hjc!KCN=<3CToYALCcew*Tb z#uNP^nSS9kgz@Z$)mfy%_pF{v{=b*|`%ByeE61o6*6yq45qBr5PeIRqg)+?RD(uKS z`TW5;*Jq{ITH%Yc!YQ6|Y;QOa#K1IC2FZvd_^>xa8(oZJ1j)H9Ohrr8BJ`W30RXWw zjZ_eJSAZ@~tb8m>z&u@IN33EzhfTY%EKVGkl#?&=TW299H}ju;9TrkuzeX>#968j)1zz8h%Xb{D4XWH9`pej|CFn4|i`P>22>pc!x*zfd z^VVW_QM_j&VY%INcw;nXxVo$3^Y`7Qu4hoCo|_G+jAwOSn;)6wpNwF3^k9L&rsfnr z0Jes6H5?pDyA+&}HB1*pAuE0F@$a?4@6Q>$Mr>nPgjB7)$Eu$X(gnXXRx=|b%PfMK zXtd}f`Q2vM6A45|(xYN_T1)VoQDqx8kgmJI0;SSJp;|e^L>pawKu{> zf3KG6Dp1A@UY$g&iAQ!ntpZlihRbooEY>$B4PmhsFD&2T6~+r&k$-->^jW<$FMFO)2u=&GhyY35Nk+r~Azo=KF7GuCROTLtFXo z-~bH{@kdv8t6zJyY4FJXz?1fd4gA)Kn9l$JT+2KMm1F?kq;jw@iFhf*+GlNzxsi40 zyBSK*&=Yp!+m{*UjS0hk2k{dHyw_ChSKFuAxA2AZIxDKHopvva#rq5WV*5M~N+24n zwSP!~G~J(d58964=~DlY*?82slySwLB3!Y@WmTVw{T+#xx9hB5qHoF3bA=;kyEV#J zsMOR%)FW>*el}LXtP~X$nd)RJDsJWYM2@sG*VsDBrG2vUKO!HCN~r6+)} z5EvWB3k_l|#p4tnHHrwz+7jxls5qb50S0#)O+v;+6>*6_9Uh0IQO2F8K9v7s{~K78Lk&{`&)FVK6PXI1=qlk9UMODD zTqkaJ87Au{q>}yYK=5oE+??sC7Uf+_XC}^0N`0axr#SYcCGCg6G)-m=V4d}H`-jp^ z8WadvC76W~k)zq-{9ynNSn4nWaP%GkX$&IjermhC>rqf&8ZMe#aTLPS6_32C$5ckW^DeY_x0Z zwEf-wku4fPzyMqaatJlW=_jsJy$<>ypmrRq+Z|5#F=$AlzA5QpqCHbe5rloDDdpLX zJ^5hv0E>{A=cU^w2kYe3!P?8dByTDW^Je*TPLwIN}oQS}oUE_*J& zmw0Nkq~#AjX_fnOHi3Uiw_sqWVNp=oQGDO*OZ)x>KZUQ|bV|>5#`P&qitv))@{sB= zUoWgglqeb!;ys;E%;7%@3zb}@lQqot8mp+AbJbrmoMyFaE!E%O7H*c2e)Ywq%JAH+ zyj9lYB_y##V;_01^zm2I`;Ut31>J2Z9lx|Xy=lA`Z4w3 z&7H~~GsbesOZ6LXniO`4^mji^3kBBj|J^rdko#sl8gTiA{4nSj@GJAWv7UD@cIX>bjPy&Wke6jz-Wt=_`hful zA8}fXaU}8N$ffabrE{6(PhJ`Qa*#jUq1`&%>cO8t1-@B-uD4!T$qbnvtR@XV*A(hm|5I>nv5x$BS-iAYK>_$sZ`AO1t|9rf);;u>#o^np?;&T638DX;5e(h;IDBlM z*uzul$FS2_5%Mj^O0uiv;AhrVoDUXq(F=Nd6eZlf22Hsb#4&=254$&5p_e1tPk(3P z7(rTWfd7WVVV=^fWpv&7>2s?SgNKxORw5B?feQRJ4;2<49A3?5FrPIyy!-0<@Os&q z`P^!cG93vjvCDIl*yj(bo|}(6x7>biO%iQbMs!yr+L4Zqw1`M7%tSFY z%2Ol4eLLERB*y1ul%Gb7hD%H!T~u&YjKWAv=t$%<=}566qE7qhnAq5Eys)I=XS&m| z+Q+e}9kGcNajJ%K+0t=1Mldgk`h_%A;YD0d5M2=uRaq5f#Y@Vnm)Q7{k+{0;c%9;S z35tZ~k@#@Y1aY4P(X<4iri5V|gB11}0DAG?ctidGz_KuSGYo=5({M3t z?8W#$kDwed_`ebZr|9~m6F&qcj&>w|x=5UsPMV{Gr!|tF7C}~kmWl)t$;jkEmqdhZ zGR_=C;3a+5NV?-EF4H3Z=RzDkKzFW@d{vcrBMrwt0$~ko0SJN~5$LV~Su_b?c{^$K zWomzH%8&WfZ5}v`Hw|G+)L{cTStXwX!kI3UQk%kiMKdIV!zFXV-y3H1G-Y&6XD9|| zEY6Ys5+N3cksO7Q0uTVAaw2&IXmb@0VN2>Mf+cX70{uYfAp1Z)sY!_cA*3)-H1i)h zqMez8QC_<4ePB+@oO|01q1cIl`YI%n5Rjp|IDolFDXEF;$}Q&K=+ zhE&Lm6yQiITwL1j5nWhLcI0UG^UG{R8mYwtTM}HJpbe345kwXUu%^$pe~_JEn-kHQ z?dkdwIi15z3P=ZlJiQ50M4+0%xi-Anmq+n^y!niuK`k)&TW=7ckpPPVu9iVEN5!#W z1UeWnepwPOmv0#c?*M=k4fBU{@;@%*Edr9cEC2LL#wLQ(*LZF=~Y0f>DKuK@u$yd>C0 z5PW!45XwP%Xp_yqSR%|&dQA$Ka4VITmG>ti{q7CvOx334LIDSJF}o!qe5IOZrEET> zGO{`srAjv&N&q0-_;I;FZn?T_fdv_yd5ZiI0MHt&Yjp{AF;IDPFHbqQLbaw`gAAZW z2Jq&qWaWdm8%PB+z|+G@aB^iA8h{I2y;z0jqu`sVAYK3-pM7yJB^0|#?#YL@04P-? zgRk0Ps}V?IY^p{KMRkT*^^4rz@_`l&Rewz4aZP4! z4JfQScdS|`>a`~sKz>sN#et!p(@5~CZF;QyQR_7gA81IXl9~%tu!x8CmZ)NYzh10~ zPOHNuYJVaFtdPN@-J~xXbGK`1QfeBm-_k|eKq75`DZP+X0Nf>&yc-DaIRYU?@nxro z-i47%7?E`xrCX8$F3148iw#(YMgsFj;yfs6S0iG&5z5$v%Vftk=JHQL9c5|(-gS(i zMtto?fK4OG>qhXeMwqrr1V$q|N+aH(?!#lcTiF&C_Z9?yGXO=rdX(KNQ;#&n*8j|{ zq5oJTw$yYdqy?GRqI=y+NeWlR!E7)%U4rFJe4DEr^;T~l4}X#Qspj`6_@`FP!W8t~ zEVLU)79X$k zR+-2^FD?SwAR#*>rGL<>I>||&?@fLrk|d8{;w!DpSo?QI?J6T#PD;vg(LVX)7{j`2cwVgXaSvJjDcpU8p|*Y_c@K06awWYOn|C11fN% z`(yt8Tn>KOmCJ_2yK#TDw;*=KXowIsObYKs*uKAb{XQMoNA@TYLTI>$Fnq{JM-K+z z&Z4iD@Bzj^Y#6CzYSZ5%P47zxT)G!w*qa#M&nEx}g8_nI0}+7%0O}to8++OSAT>XY zg18k%EQKQ8F(6AT*3943%)kSup@2@Spr##0_Zi8aw121S0_xJIb3K>nd=X^fN5y%o zkViJaZUkhwmCjpWm|7CQA3-ADNc6><+`T-}r5d6M21Kk9Nf{7t6oC*v1o>e^V!cG~ zdLehZlW4B9{t>&0%1-ndQOg-Y^kGMm!K3LqquGh0cg8`>y+o>0pl{xAiyy`|S+BxH z$HEQ95|&3&m_`92qghWzbHIRm#>OUD#^!Uz*3|b)o zA|D7Z)@7n^6SNi6GnEpgWr=1Ik$nd z1KzRQ)(9^oiH_1yT28NdPb1Q%8NW>XwsXV9Y>ZY0Y zrxAjmIhf&NA1o$5h$|9cXJh(4tB}vAD$H!jr%?x|(RU{C?x!V)&I#$xig|Xkq4PF4 zRX3*Qm`RyR3`SDWw(O1-J!u5kDd`?Or3QZbZ%1UEIFc>(V`_1Un_F2rI#22dO87v< z{L7S0*X(Vot{eYC!%Kog*nISwrLU?<4;t_eHr0bvk(gCa|4(?aK}*JTeHS{<;|O{T z0(7Eqb476KFmj;6LYJ<8DI#c(1Q+ZIS-qmmA-BqV$JitSL7meH7peFBVmv=u002O9 zfJG+lmW<=YCT4gmIsM670E}^=TlYJt9bX~r`%cn#7INJ4-|5YK*LR<>$p)g@&DiDN z^_~i=lYxc|hLZkVWo&luPxhIQV}=j*&I2KBpkB~I5&jSIwU}-E)iBTlnaM=U$qXc* z$s6*si}4m{fdA-gx({gPFWHPBy+Um-p`|TxQYx}>YDFOpJVBnzv?itJPbmZzDw?=& z;T-q{0%M?WT7`HPP5ioIEM=zuPbRX+TgLU;k>oWzCmSMcDyb6;lQ#wN_Z|*jrZXx0 zVJ<`f_JTMSO*kfPcqTtg0|cexxu#ci6aEdfF4(+fqW3#W{_eeyOz}ndFWm=6i#vQh zIE%5rw#aN=htGFryDNF!PV?eeHFpiTrC}JR1 zG$8*f0>&j{ts+uVydmK>1mR(=r;y)BC4V>qxfdaGr))`&?f5(Ebs0J^Aw8vx0mmJZdUw z4+Wk{zS(KGU7RJ|YP>y!VnKnVZmD?(Q(ea?^4QB27o0M93V;*>V59&rhv|QX5&XP4 z8jS;_ke5IJ4*&oV2mq)9jtQ>*4XR;p|K8r-V*lRYvOuvnm)Pr*+w1H9U#8mMC5S9?6*?vZ0h>j+RDnx|HW6E zot>STnfd(r^X=5sCGPq^Q)(x}!&gH?m;L?MJw4~R>s`;~*qf`7imUzt>?dFBfay(- z&qaIt^_%#ccHO_tXl$$S&=Bsh_~XZqV`F0@BO`-@gMEE{@87?F_wHR+S64?z z$D22AT3T9~nwlCL8?m(#*h(U7IpDU2{ZX=+x+V_isMXfiR##V7 zR#ujmmtW`SV+(lyj5&H1_9HOxzk;ZR zgoFeI1>q1ie}8`;AD`bI9v3c{-_|zQ7ILTej4t(LeyeMoDhtQDxZoT$4-XGlS67^) zW@l&j|KO-8Dk|Pe@oq~=-wLp92?$}4w1*t*I7e-hk@?@08uTBO8VNC$2#5s|7)VOW z$jJOJnwpT1(0@f!V`OBcr>Fm4Ks7jyQ~NK2YGeNgP>q65I)goWAO^;+^&e1ed8Day z7ze7wGif%Ljb`xNdpho;hVFkMVn3Fz*;4T-Pug#Hd98{|u_VHf?eH zHumQA*9Mz`cxLUky|3cxGc}eU+v=9uy*I`Rv`t)+pE>(;d@hEUTlIwM-;#Uyimata zLlbmr={PoqSXupaa!c!f{0CGk6}|mngNW&K29)W((tG#z#C5h_sU@2^ugxvL*uMMw zr>^$HmEK6}356v;pN%(itR{u|e|~?OES74>G4DA2^$$?(Huu8+({$f6>?Bj+P0;uc zVcfjDqSK>;qm7TR^xr>KK5WnV`E}*-`#)#dbtW&u2=FgHhn#W#6I9cneM-P-)Auh> z&8ez58qtf_AB~9Sv3pL6z^qzum$)D-d57jo68PDoY$6E*u@-0`BG& zy_pYqeb{ru6>HtG<4c2EobYPBx=Y#e8=tLpUSUYxlff1m@M3%}ijKgsDE z=6f>RjY`|g7*#0F|J_CT)x>8=WLQAliIG_6D+4wYHPx%+8Igo)-i)9eA*k-om{w2d z78u+U{nk2I;(Gmi+{nc9jp3b-)L?#m)g$~og5$l6N&K`Tab+|+rWK{}bGB_si}v(P z*Kg*N@9ctJ=;`+-=UClu?cmz|FJDOGzELiSmWQUUKKeS_vEifs%RfBh9^{Qzu=TI= zt^7bmgD>8r{j*3J0`FKk?;!C>K^8i;WVt#zIW*7K$h}VtB$nwA`Nk)|#R2ix#pDWm zH^2M1bk_7>8)?u}Y2C?>RG~UE_nt{@L3Z~q&z6V5j{(F{!nYTjFCIR{7|5y2=x>W7BX}kdOiV~$MG|(Qr!~P7 zU4^rHRsCYQO=y9#Vur65%8XpV7+Hw|c>qj6&)Xi+(n|5M{ZjA_UxOU;^pv z5GAo}0QgZt;Jh-NACNmmGu)IKEUNcnu#86VPZWje?>nb_wvnxYLw9r2-VFHc(YcyFiHz^D_e5r z#xU~csGow=>IvQ#w!|*IKqjyT6axsS1ZQ#prcz18H&>x&K?DFX(PTuUjnacwUCjH= z#&LNZb9J%Fg^hk^n0{PhkhJS9#_*{f5YF)Df_NuD`lD>Je>!*-BYoflv7lQ+hkf}5m_$*k1?WvU}pu zEnw@*KVM@l)j-#=YGhoWc{R4QYxdQ=i_F4U z-@HD;)1;Uf?_p5JN6JV^JJt!)UO#?*%E2-2_OD3|k8~4qRwo=g$RoX+f89+CeOYqv zgXQ9nAq~Sz2GgDsLa#ujGt1vxg1x?eje0dEk)hig#lIfmlFb-dFIX-H5_KCL_xNdV z%TBXM>=Sm^OQv4niE1OGtOz|nDI#;}DJPYY+Vt$CvZBX~`uZ2|kq z>V5*>Suq(Up3DgRj&1npxU*mG0*~|w!#t4fN4tRxDzI%SuTGPe5>wh4U?ovns=cac zzBp+_y}fD^oT}XQV=6mAJOQqo`bYA=@pRX3O*dfMz*oTN(V@WT5RvZKXz7;jF6k0s zFuEKiAt~J;C?QIhARr|njYvs}2!ib0{XEa{{<1${$M)Th^SZ9{GmvVfDrETJ`Myc< z*_1NHs=+&V>A9M;z(#c8k*kZ$2eKWic^tkb+DE1L!hD94UF;%@6a~2N&`jubsinxf z&3UpkzqrO+AOGg#<%dTRzv|ZiowxVg0XHIn_icfMiZPKF2>8!SWXlr&fy38VJcgtE zaU;n`(Ys4EUnk%7{=57@LVvpf)$Qn~^Y)=*fux=Jx06TlD6=tABm(qaBb$+)fbeKW zIU#ZA$?8yNZuAfcn-J8K?y=&&o;(JA(K(OEiF&?xyDK@>IT`Hzi{u;Z<#B-n(+Lko z_82$lA=!cdQ&-ju0OxI%9CnL6Tq8N58-CgcNKd`*#<2pK_(st>G2$(h|LgY1wWo8+ zW@!==W?aRH6!-O@N2>u<9663khM2&^q5C?Ya6BQfuB4~rt7<*I8t#LX0q+x^P zMfc9VyNtkhg>`JPGJrid-CTeYb>l{?uChG0o95I7f$^o_?W@0iIe*q?NjtV(rkcFS zW6PNFcz4$Y3;|ge<-ArkNJ=}hK#2Xtg^8Fi7@Nspy4abZ_WY1wB4pX3=P2*xxN)n- zVet7~UNyx7tl8%<4CNepi&gh-zJ=_nJq1)#eJuS;p=u{*{O<3Sn!_btOp#xV`^v}riVLl3CA7nn>C-P8gc z>m^aQjr9(Jn~qvBw>lefKj(9avs$E`y0md}jS{V95?7}y>m|XQ#>M4w8;J?rO2h~H z3It+DV?yu~)AwS<`yhFN;92MRV0E|oKa5X$Nrq8?c*!IHisi%kgJgAnC0l+NCz`)H z+O5TY$QF>tlbCcF1sJ&p#Wi8t;+2Oa!1{U8{CEd>*fI@xhjLSBGk9NRxIef`QtqH7 zZ4MlFP8LUc>0U8ndP&MoljB@DO*6Q*B-3n#xttW!_IT1fwo;nuQ>P@UV}FoXF2pw` zSS^JxYW9+hH3Qcc-7`!6gW2Xv3<0*lMjXuMLo9%@8e(PrbcLatVPyfOlaD1O<-{NU zNONlm3pY&;kwg>i36pd%fDyQ&PP~61Za$~@xQx2U2lu!JG$P16_3-BeNlCD{75mF{ zIp9cLb6JC zvoGJ#o&=MejYP@1y(sLsCsOi)3y__IyAQA>S1x%579#uS2&2NVDv;RMXR02D)R zv{Y`4S#DftZURH@^Xr_%rQEdZ+_=tM3=ULF%*`58%FCtHLuC=> zmxkuYxaDWofLWz<*vA-ZdP!n7UWPmWkIhzM7=^Rh>_|&|V50-niEx5Jvx4E!g3-JJ zoTfH`)6}jDaGKf-PE#{0TnH^(%qv{(EL>zDG#@7T#!$3{O)N~D&QJWE{|X76z!0@P zcBa?>JDn09ARzCTUiBpAgpK7yB<9~r<<>40S6vqamh(W;CHZD0_~v=gPsIXIU`1y! zVNyPEQf_@-7F%alfgQ+068v+?rRS6=fEO0jnJqn*_7j@QnD<&KD(0pn=Bw#zE)A;4 zT&AcHhKgR2lgbbMlb`SC9aiM?iQ#=n zMr~Iu>Q^m=bKNWYy3c-=Nwy(x!(OUiQwk!8j}YXz)m|~v+E*>9t5*lcgOED8f@sB$}TQFkRX0Z3EH_Ejk-wyn@8o12o|1In_Pkz(iFejxxy_*ueo#jfx zGs6Cox_H|zD6S$zj3~1XdmfoTjB#B(hOM8X)Qx?FG*E% zGs(UB;jsEaMsx#FixP$DG;K4lMG{sJB83(HACv8r&;iG=iRack}nkXT8<@9E8 zp*ilL`F6P>hL76pofGq3xmF7yo-esQ5ugF!hkV9V1%IXfs*Pvmjlf}>ZgP{XkV~NW zTakN=;>qliny_sEF<6LjSFb^Fg+V`;$e8h+V`Uq;#XHxPHmy3UG<-Kt&3AuFQEht7 zAXXx?n`+iN2G-^{(T(;T{EkM(ma%tl_+>hz?A&YkT9Y2I6NTVkVF=}6&~u+~t7l9S z(lxo`F8P`ru{YTj$u-Jnp7^;P&MVcdgapfah?{!SxM-z9s5Px8& zqc*d(%ee_FdY@U45V!CJ(5;R)fxT&WxOv|t(@N+15$fyr=B@D3y)t-SonC%>5e4Bl z`i~B~-5r`AabKpp1!o$BqsspK8RG8Kd(^lD%d!>Jut9o(AZtK?z`poB8)V1R#11%& z4MBQZLe{RQ@-u++5-qBR{lo6IC=aS1+1C6|8j~%06@2kG zF{GA;kahrpTrd8*EisNjJAx4-aSRuVtg;0xvjTR4lYE84WZ>kl1tD1&a_>`0&UyxD zat5EJ1HbHtPK&5Li%J9q;GYW7KaYXR)e;QBPaq%utMJEij}c{UKBdP;u2OK^n{ z^w}V<1pX(3y`3hu#L9N!hM{)+!`m{w-z|on>w5&F@JO>EUMVdeLd36evmRMkBF@JiGI->XcwLVYh!1CKjpYyah>=ip zKOreR9EMELqDn~jDL>%`(%Tz^V13BOH2J@2Qf3l>JBAE5IhyqmUq=yw&+xG&3E=b` zNlM1|M+_}euX;Ug`z^;_*1wtXoRT@~x!Hh@PmHOhgZF(*N+#R@aL{}&ajh?KUXa)Y zh5xRZbo(5%4kL0Z!S6dI_B5FMQ80-|QJ{G?Sy)0 zo8R3%{G@eea`g&Gz`s}`O3jH2f)QyTNX2JC#g?>H4?>_#+P49OAPM&X;zTg=5pJSB zTwU=gxf=jbQbGzw5+@bFtR@&F^2?0nYX}wNR%^wVl`nw z+BiJ%QNh<}{ImvCF!TAAHU=%Cz1im_NP4U%Yt9Qp;ezcFocad=x8TG1`#G@u^97rL z?nTJ^&lVq2r}|PqT&K*-d;w1FPGvtF!`rO>s=rtul#s5s_C9b8Q@A$rdGXydDl1z% zwVNrC)Fn}(wE`i$l10E@ZS&jbAA3k$?zFq4d;xXs?{Hj9Lc&JIgP9_I02kpf`I;$( zcg)Xc>8U>#@29~e5ROFeHvwz)ZZ%9RS6Q6iTge}`2Kd*Hes1GY0MICFvSR_>JA0Sh z zh7{LcivLo0Up69(FKi*&`(&Kp^0co^4^fJ0|b{i=}hiA>Z~u=trt5zXRd;6DnH~5eK5AZ?Yp8 zGo+6OC$qtUJ64HDt!rE0Qcxhu2m(8N&-`;lhNX%zX(2+RSzy0dVD?SXo_HVL$>;sZ z$q#2=>Yg+oSI!-GrTuW4{CR0j#e^Y%$e(^c-u&ILQ5Ds2Ywa9x*S(gub`mim-h$U5 za6)*p`;E0}3^q&Nq2Z@L3;U}>v2{6#o;`zzbDl@*8c*n|{ zrGBm5XI;XN{3HN-V#IPP_yrhHOm$$N&i$91|sHspT;$9$eUv9aP<_^+DdW{`R&l%-{$q}3Y%L{={W8j)D?+y8)SdnA5f*DJ}fH`ohk%MqZ|-9`umAYoR{)!S5z zBVZV{o7US>PNJcZPjS_^ONkT`{U1+k=_pv!GFbPaEt~F9Txzvf(AR9!gP~@HJP5@q=kQ7ll!2$I-+tJgiVLF z8lC-IAJOd|QV^RqYdL|+mO<|O$i0K!C+aIas@+JlztoR?fJZ0V{QB~|3@T4@kBF7Q z*>zD+nL<{VFlYjVjlc`cXdn z8WfPX3xE7gkPYVVW9CXVEw8Ceri3L|5!F|rb86F9V~G_tc+6eVW}x|KNYqeU;yd-M z{PA8LgMu{YTO&g;ZH~{<QYN#pOFUWQe9r+Ej z*EPm9muOvZ^r5}~Js&k9dmg4h2-;c|P_aW_{)pHr}tm0YLyig_+*QKSRcS3Ay z0D{Tn?KI*_;`LX`jr$L)naj0pF-n(QiDB^C&i-zmzaMI$O6tCVeMwf9<~l)~ypvI(v$r8dWzvdz**)6n+1kl?(W(R( zMbZZyTytd|SY9T2T;y|IxpmLZgjLq-tPx~a|GA^*Z2Atd&{iFle(yWNoB2ol{mH_s zHy@ooB{d0*O@^H>lSGEj4?Zr4%5&5Tkqw-mPx>Z0HSkQXZ_$Z6{4`d&S_vNQ*%V$r zuyVg}&?wsCL&)}uL09mY$4SBUZnm1MY)$pn^U&!JG;+J!$c z6}MJGwg)vvw+f8h{$8IaiBP7JEdYl9`_sc5k$a1^xjx|R1s1*VBV?FDGhWJrc9jvo z*!BOZUT~?NPDRs|CtS@r^kTtXY3SlsW<@eU?eje){8-K6KE)^8gh_kGgY*D=CrKr= ztB)XnL<6i=IlvUrjQF-RgVyPjU|!yddZ3(p>HZr)E*2H1+g3tqwmZO5c^aouPG~@4 zOHgM=8p}#e2vM6;q)3fsNJrT-_Hhq^?SzuOQ&?!+2;|)4s-M|hZ2Wdt8HVXcIg{!+ zz>`N*tIS$b{UAhS`UcdXqf)Y|MKzjpXLVxMGY^e=8qn~N6f)?IZ%hFP{fOF_o`whg z4ZSKrF;8vXjM6u^o`!>d_py0CX_m5b`L%lICsIZZz}>-&X2{aGiT#V%=JIS(ErMKg z@n3fBgWEi2yc+h3Se0NrhFzNHxOMY0A!RUqkzk?Jq&YG(s*`_1z<23=?PC>KJjc4Y z6``!-j61&)hl~6Zr^y3t!~DA=P9v?B7fzCZqJy?c+5IO|W)-+DU-c+?PCo7kdGgYK zw=R$R1RI`9+9#dOu{U({vTg9&zvgDrSNRgGpKM_GN^gJMM*h=GDvxM1Nntj#Esavv zCA9*dF@w5Qt@ekrSaanHx38Ykss)X;N)yddx)qEpB|)$fbtda%To(41INk^rTy=H?hEK`xd~D2HL@@Vkg}?>Jw2zy zS{)ZB-hGwRbp0V|{;o0T;Wn}%n3!R>&5Moo=@pvdn_#Lh3a$`NL!p`5_xNamE;R6g zCwVNNb$e|E5}U;1i`zg;qnA(}b5bW+!Nv1@a{lyTRr_TrFqO|w9!=HfrH-JV{Wy z9bG4vkPh}oipu+yMs@N*4QoI32s$FMJveEPo*Hp zb?;jeYDDP!okD(qyD!AW_9Bv~zJ9H+NU>p#$)kc3h~*S zmpN(9KD$sOBHhRIr_B7YXA^mO>TW;l^|fnK?2TsXu9L_!L3ZjsZ-p!*b>Ss+**yikp@jN9&l~XxyFg^+~5IB2*tuLWjD9= zoY9$u8BD^`Ja4O@?IUa9V^GfpW_G(!76D?$h#95qWiy}ujEjiH)h6kvY zk5z{R3PNF~@!AO}Vp}|K-0$xxz9y8w7Zpn*2(@dL2OwgCU3*6Mg|A=rY_7Bb>)vh= zClmF8U2~I${XYh__K;8_vH=jUW&rpIfwqnEJ&i&0fPD7iBlhr_1QVWA6S(W4KY;Pk zSNK|z2@+QXCCCID3SgR#f`2Fv5^1}ng<=Zk;0wQ&ui4!Hm2xbS|V_vNTt+g&5O$0d<2s(<2 zIq`QgK$6Jlt6iXiI*!9U>_YkP6T!EtUVFe|qzWr8|9V0XV#~z~MgajlC=XbiFb~-M z6mK~*UJn-ic=`iOi%CS0J)-SVWPmv8LMrbzL12&aMQyU!#ACOD;R%N%uqC>!lmhLF zcJmI3%dGlE^|Z4vQL1 z+mFX*#|m!;HM>4(G2UxD(s)cg-c>%RF-Iskt^8I?QyelLV?XNMHR7LM0nOB$I@eIN z&}=Iot07LNzz`W?IzKvUa&A|q-P7_fjdGHnSk{=x)Ew2h8Gi-G>pA7?A<_QQrfTz` z$md{U>hDCYrZ!+up`aH;H~9FY=fr@=_>(YAtbZQ4Yxrk|u9S(z6r5i51P8cv;L%k- za4%PFw3u+cubmGCL~1I{-Ea3l&<^|i+1!`MNpf^Et8~XSZ8wAr;DhI9i^fb)nW886 z%O{u0KbPvoJWs&q2fSac@0p(v-;Po^H!AzLM^4#6pdbiky&|Z9Ok9;ueEK$NwnE6T zM>+OQ_wR)=R<`n_o~E#i9azCig-o~NjY8AMYoK(m>s3jthM}p6fW;m%A0=9^FR_kY zTT6Rw8y*GJ964V%C5cqHYkYUo$KB zeOBH$%ZN~GVrSaiPE7a%JkX8~4cDhq`4ZFI&%iswwmHMKH1n8=^3mHlkG?rAnhcFX zN)Ty@vNg zq#H41C z1QpU?GEMzno4)vGs+nb$i@Wa;jg=EbC25<8eKRZiIf-$N(wN2%pT<*|mLJqxGApX8o`tvU!iOJZ>STFf2seF#hGr3uHqo*~lm;X?h+pSqo1D3N-! zpk75os-^FWWp+qB_K74owgaFoXcZqz|JBh7>9%-U(cJ-!`6CVV#v5eI61cy%F7HX}ufUn!88vPzFl77e6|^CgsbMa9}N_ zu~w8~9$~faSWZY90yC@zOJnqhQp}(J9?LoYynF^Jd&>H09rD zX}Aef(OSpqYC1ID=aj%ta?9s5&e~S5yl^8vw6?l-lcCG*=eJFXar;=wC?|lB+JWis zRr`5Qn_NH~wt8ZXCxYI!!Jeec9?G=+H^w3viZVh}JY-mmOmUF9To%MDej*gtr5jRAmQ zMmxp}s}rjmlJAy{OpEKCY+NFo?>QM0zZN*;+r8S0x9W}cnT++RR-<>=J@az5jQF1J zW6iKZywc$OME;4V2_YrI0bm+MKb-itf$I8oleaioWOb}5eD6swWWs#c^x00BhodGf zAy)?@7KtJqPqp&+*hOhVXq^j*$&ImsIp679qJqe^^}d#yIy${|W%O?)fxQMSR$nx@ zhJM_|7!wB3gJNKypsT%qb}h5iZd)Ay-?=D_#Sbwb7qK+l14#HWh8KmWO2Ho3)|#sNCbfu$Y9HtOfEeK$cs zpCIywHhvg0Ae)%e0^uNldWQ@9cG#A3!5a0mJrxY zL$qP|Vd{=N3qRtQTIGKouI3W#y}{f33~W$6ic_`y`q3#F4v=Av!{3ld`)B;gL>=3u zlPFYz=iQ8NTAkalRxI@J=cj3WjnSxJ+eKjnfw76}>Vka**Je`3lna2ue9~+r%RRpG zfHa#GAwRzTl0=~+K0?q^YXfi3#AE-ZP@M&cF1*Su&HDJ|A!=tOT^*n>8l$xbHsbL9 zheUO7JpB|BC7hrl3IknQdoC`R4byHsm&7v;`?2!&>7R%bHdR8FQ=HQn=Yfg$?iHCX zD(!o4+A6hweRRA?W)ru!;RGPbtvw;GI{vh9n!boJ-K&?>h+n z!LHzkuY1(y?UOZ&rpzb@R5RudpWIA(h2eIl@liqv@ql%fm;C2L@I4_Ge=KM4DS?eI ztqYU^LsXDOTU~TWtNY`GnJ~z95v>j`ygQrzn8&j*A=r~g{bxxee))g{5Jex?BMcCn z)O%3nyT+VowumoEj{+jVUKqSbIrEM90SOcVHAAPWFZ8;8ipX-A#_9Nfiw#KUiLyK; zc-9;rF^czYwzM=fug||V=ohU6I{_(j~ZxxGp>6{t0l6az>=_@ zEWGnKODJE~@0M!Gx*-Jadpm9+1k@fsZQ{+O)La09z=ro$A7NnNhQsOe75T|sZaytf zU1HNcNX!Pr^z^sw3%9_cAF)uBAw9G(^Ni%l<-T=b>eWsx!FTh>*Vxb0x?u{*!Svqf zE1;A3k3IPiVY1(jHc&e`asbBf;`>#q#8pf?)YjzMHt32Qltz?s)r^R*g`kwwUn%l+Xt58v zD5{yC*%Mv{!hMdj!k?fGJP!%Sbk=$Q!A?XL#0rH_1D$xzXrcXU9jO zk;QJ#YS8_%k8jix%=TjGQ3NBwVDD*MMU7u|ZTPstk7l}m*n@~aj3|zh_2lKZK7EmY zHmi_erN&q|LfR1;ko$gt0KmNGHx|hzB0RB7mp=aFXri6%EHhx|IB1pN$KE zf%=z5!o7(;up>02n*N6bSkC4~^fl1w3U>H}>d3|KCrd4zf_6K8g0uy0SL{DfEry6x z7&BnYI+#GoP3w7uVH-}Ndgv}nzr7BlVB@|&kv<9Sv#qB+K7at$(m?M#1MAHU2Nfv9 z{{z)pw|Sh)A}AlaU+~P7Yvc%P{}sX?sgy0#SbhA~eWcD*%pDKzTKtg@-*>Ll(Cz`M z(Ur5->R!vw!7AdL+i{ma#XaGKl(dgW#)}?$?}cGIDiRD`HV0kZ1RYeBgmy+VxOJHY zZ4V7QGR2+-shhF7jG24LuKXCajg<-XsV5~}`t30#{+$n^zY|2^(VE21kv_H{percP zE~|ChF;$|JF7ovFRtliBd@w)jT^x5vguJz(g@K1mu^-4|>s_$XoV2K*>$G0K7 zC&V)^t0}uS3$Fe=aI8NPiUbl#Zs=x@f;H~@#<1yf8aM@i2|8nyST~_Isb&IJ;fg5; z@oO+@Oneptv17^!#6+j{?~M?M=lF7|cW06$1E=y0|V+D^Rw?%OA1RNQ#E&vZPi z`?&Xjx${H?MnR6z?NMC##<%8wubud@IEca#qnyOYy9qfO%jVzpq}qnQv!FO^C>jn^&J#_hP^R4_MNz{rx18DGw=}Yllbm1}43J6@!%D zBn9O5-KWsEJ^WTm_Ov4!@B6m7Hi~|5`(aXoY9FHGr4afGc0d+SnM$Egqu3Yg6GPuZ z5}>iDn1YCAs6q774yYGMF5=jE6rT72kN}{iNG)-}4BxVik@p#3d?qytDG`r}-0KDV zodUoh-ccmw8%&%m2OAZyx&p``JuRGrgM4gM-QZ0|VnI2l$m226a(kA~2oM*T0W|FP zCM$uYg4Zx~OriEob{*E!kt@(gp;$d$dVzK6!{BHpj2_JpGtDW;-ip@U0MQjs166%O zV9d8=q|hbEk#!DKO0PA4p_@y*wdS*zU+b&2TQ11~-bvq#)`DHxAL2I%l2>QQSB7tt zSf+WWLT6fwF1xv@A_ zEfWXdBlj;U?nc@7f4Xvd(2_oa2xswCDbcYf#+O}Xy8z_r_<>B4R9oK@{~BZqm0f$GJ$+!GwmR-O!{fUsM+IWMQ1(W+smO* zS;x`w{ny$-?HA|c=)kGc zfpH$cx>ELMkO%@+ED37x* zlmT2q+rvz`-Z%Rs{lq;yP~vwGnGgIu42eziiBt_HYQl?vKpl8F#6)6>gHV_Bmotd zPBRf6Tj|%*o)N|I$re`^2Ts^=IYPUb_?a$1f5;L@e@Q1Z;zAO3JTZV#7@=`tGeXSS z7hiPI{vI6wB}52%3K)I0b}0`PEvq?+1aA;|cu7v7kK5O{?r+Wx6M>|cNW?fHpl2Hg zUmjQoOe(f>&(^K|CP|m;TI6I2`9cgp2&USEzk(;KkGx}tlOq7VOjajqRxlvy37zu7 zAKJ$sV|6gVT$7WCM?@%Y9bfXUSU^Sd5;dD5EjL+2|A?ykTRO^KNgC`a%5Fs4I|vM* z&|{}(7KCz6`!WD{;LN|6LEge=X>6FO&vumgeHzla2tV9Z5&CLW zs3Dm7LV&Ui*clnA7WDL@+E6tCQ0-pAMhOsrl7l|H*uZ`n8FGR!$Zd2hZqs4PySkCQK9JNi9VMNTQ zeJ7l;|C|O%X5gj|S#(JZg_x)WYHX%M`=-)MU|cWzm~4oMu-3-Vukx@QMgBB|GDRJt zRDTYxD))0`bjWe*tMD=Mz^Tu>~A{hC!NHo$R z`t)SS5Pb&Y0FG?eYuoA1Idn0l@U%?|wo+CBmCS#p$^}LmLw34)o2rsq>}wmkgY%a2 z^H%$FH$os0*Z>&HMo;;Ao6}}TP=%=blOVsjGJWqXDTL!qEQh%Y|EI0&RXgqK1KmI0jq3mIez*M;s+WE zuQwGyJK}!_F`;GYZfv*nqrBmz2BV13Q!xIfgN)*ojJSiWfP;Z!0{48cGOX9+Cy4_7 zMl57U*R=Fu5Ty8;p@fi8@uLkS4i^3*X+Zj!(Zr)?&&zSMYgNMBI1X z4I48JNa;@0AnRZ%5pUwlz4R^343HVJ&jtP$0_&c9r|srqQWI>>TevV-%t59qxrx}= z%bh9JRb9&~*nj@p!lA8L*9gb3feYMqo-(=>yF2JkAWjA~RBv4|(W z;pCDvI#|Dp)3GvnHyMin->T?=dUR!&Y7BnXh+qecYC%>`*KS$;%mIyrxBQH`e;MdTh+4!q3BL~ z&w5zn-x=o8%p3_SBy4^${*r-m6Kq z_jp@dKOoOva-d#~Z${TwC8eV*bqjtJP(NaRn6O)`u%KLj4Ca$%=q8%#?%!$*I~Y*p zPui_xAu1)5tfq4tthqx^9`ldeyU*}>eNcTo=((#LfYa`e7G@5!?Q4cAcxdGtU?vs$ z_7Gys;rt|No$${Y@hVj#W6|yhDkc0)f9nzMb<2JaRx&og7X}XW1FuvEMRBg##KYCs zb)#!uhA09m1lrLJ3ke1BrU(6e64v-$>!@PTvuGdK@sdxuqwi3XYDZdoRh(<%WqDUF z;HE&)7oUeIrD18UPPWKvk4#{QR)CQ5!2HXBqB2VEc0i)-c%@rl&7d(#0|E>%5CZV1 z-mgli^jymDI{M_@#O5}XRx;JcEhqrNb>fo?J)M<&`rWxdx^ zgBZ3Lyl(>v6Vt$^rXAYXeV2`jxxIA(r@v`gJWPD1q6K^^8)lE4^?IwqX_et6C(z8( zkxGxz{8JV?{cXuhu zMl_-mO{&!2?R5n6h`dQpb|=JDpVKH4cc*cA3egQT)0MT5Y!SLSHmcr#;uj^ve6vpl zKG|~?BwRKtO4=98)GO_y*mYot3>>_Ouq2>KQbz)5Bf%J}V(!8IJ3kZS@?@>1; zQm>fji>oe@AjG@V0CI0Wao|8)Kc01u&-`eBW{fBq4^^^XU9Av4@l$$flrE&&W+@mp_ zx<3)vGX@WT!6&Xj=mU{cFfnJR&SM6C(uq+SkB%A+qvQt;aL1;QZq}R3Qs2a#g4NibSD|h(H#g zHPWUvC93_kO?zEbXIzwEv`_O#n=V#V@9TxmpEj+`dN)X*)(aFd!LizafGqbQhwFe$ zH&`sdwuDibegV{Bex}hXs-lE{-#UsWMa(Scty!^{c@?hIH_*%`>VATl#mHOBDKYc+ zVwRb|X=26&zx}qf>AOGIcOOG+cq6P%^=`Vi@7^r{7Sb;Vi{f<nAAiD|I+B|@BFcg(W0Lvc$RzH**;phMy`-YV?_UBT>M2-=;{Qr! zreYI{LB}fXq7)FeV0-zeSH2rCkwQ8oR7sLfSvj#+d5l^MNl7>gWZ(hj<#gs1OXXK} z<~K>bdeuoa8b#ICSuiD4SaN8{70YCM;dlaa&H#m3q7 zy2pTb%s|u&gnMd`XZ3McgJZZmV|t1Sz8xuGB$4I9BK0*{G6ZC9{8vEK!#U!~u?5jh zs``4; z8P@stA0B0t{&>c*DZ~1OS_OdSmkhSCA2>96f=qFDC^>GUBFM&~v%!Fu4~i41AW1!v z!`s0rF0vy%!6_q6blRfL4x+zKk<8Pe@GIEmm7lPxf;IQ#|o z)r)(VLw(Vbi)iWF=+Eo2!tV926qTt_57;4cPJ1*q*Ymkv?f0Jtha_J1i}>>z8vBg&&c~ zx|Au&-GX4ZdNUTcGXxQ{VEIFr?r?N?k^-;+6%{5TAIFBmJ>=eT+V5%EHbPns4X+4^*o> zqE~XzOTWLP-qMogW>}?Ls+ukR7F$CprBUrX-zCOZ`us1%*D4=Rw@^Uum1$`2n`(WG z*Q$NYy+2#ul9l#%RZP#zt$QNXXh#V|DAZLYp6UR*bA25~0^*mS^TTQkT5^Px-X@9p z{}|Uy`zaH6omePshbb{0f48}V&fp$MTb1Up{))U_Tlg0Yorrv(=q(s0X&kjWlFt3~ ze%|HTr=rs2)%%5i=k#y#^(m4eT1+y!uPd$I8@$^-Pn{}z`ti%V^Ov2gBQ9nD+6fCD zLRRNpm54|z*5en?hoPdnNyO(yX+7kR02=nSk9S?cxe2b7Z~+Fj~bynwc{jn~%*a*z+M z$X?Vv=FVwTS7v1AOaH|1`IMki%jA5k((!eN!GsV~t5E0tXZ2|#qH>0gEUw+^dUZ28 znm_yJv%2-$xqof7PVsQ&XH1~$@3-{;1DC3OxQVXit@k&?c zVtvtUqC~-NF!^Iy<8u)K<5l~&#t3%G00RI~A&r!|tzuPdA+6mmwM7&uZMjCFrn}*R zqMS*c!KIXQqGM@3jGVYeL)h5#^MHw*+@CoURx|DfmyqG}*~Na)hFU%ziv8L|Qy(?POdi1( z%b?D29AX(7_@3IP@s25vm&0g@AiF~2U6jsT8y|f|?DN;1+^?Q`)0f7xr!G3QbDe#D zQPOBToQof!V{U+XO0~38Z!W&1Eot^rq*h;ZRbw~ZXRXGg@FTv(4|It5oJ+;Cu+n?$ zbAq))|EAL{v?{Iq|L)hk9&S%`y5xR^K8EffJwO=%G{J!kd`?bTDQCm;zif0rzT054_Ifi~|kzFo=Z(YBQNU+pwMIIyB zo2awwB>rrEKfG<3LPlaWE*w6D#I4urJtaz(IRI=6e^tu=;4|p5{qb2kBR5s>)+11V zyLtCih{O4k!eqz@MwdB^?Ypj1vE5O9{#`}JVp*D8hL2qT=Lw&%FU-K%oCZk5IQuc9 z%?&kWj9+j0eK;T`Ck-D-`tmUXZ$k5Sr>X}gpaQe`f;P+;DwO^PB+l(yvyfHK0sB3S z6Ru|k^h;C{cw^v1xv@`&dvn{*;^S53#%~zG{V;(S+Uh)Uu32<)_q2G(%||DQC4>jQ zu1@oqf7=2vE%dJB;pQn)U^%}E@W_2Gf2RO;J|G|LYMGJqaE!xtH&<3yAR$1Tp3^WxFdmzC zkc7HrdtmI=Yr=Mv{Vti4;TbQcgu+?EnoYIq4a1~epkO}BHxBL>dEE~rn{4*mkin)< zCjL)O`3gdgw1;j}?$WSV-ACxB@?YpyMQtUuVLy;c%9A36RE0cQTcbL@3Wk$Ud5zj$ z%NB-?`YrpE)qQgLd?}?G_0bp413ji5ERyt_HLC)4{oN*-u*;57o&4{jnyF$Ae4dn~ ztoj?XXcQxM&eweQVWK@A;QyzMeTe@{8u+EVZW#L zu>ax4G*~=*fEIKOkg>=8%~%96k&P*H&rG8=F2H1<$4c`2LNPix?Tjd$bH~HzVx=h0YzDO0a`Ommc2{exm+tJ6MV9+oTBd(pmg z(YJlfM7U$qyL50AE`pR792Kx-#hBw-ljlNWJ;pyNo%Wae-6cXq*h($_VL#4268f;B zRkp3nv(-Reo>b*0LNu@^?AiC%vl(5bX;d*;Ym`fXW1a;VzuFfZIC!(YE3Cvx=vd)XfJoY7T2JNwaGDVdF)UZ#lf_o2tqN}ucs zvY%z31L%=(3!M2?+n1bVS;E*V31;+cNhOBGke&+;A{JyZk2^ZCaDh1A@G%#N=$#UM zI%FE`=|kjP9!-&A3Yh^s)IrXwjB>I2xg0O1@ahezTbjbkxfR`(z0_A$oXIOg&!@su zZdmR{)j$A1wA*dJALy~N^b8F!6krc`Pl)G$M%&Z0O0qU(n?fR>nc7!>6+}%T>_+)1 z_9D^vV3HqZdY zqN7@(^gvAMMhMx(?zj-W*YHE8QPH)PrR7$F4Y158bs6gmxZvh(2?i z8rBl3^81D*t=X1WDbWl5<;e5ItY5YBbo}iXG+jN@sv@>J{y`if#;gO34{-g>y>JKG z0KiGFnqy$%edbr6O#KT_KXXF8*%YZ|Xa)o>TT0h7Yu?8mT)pWst=`~O)8foq>r)(( zL;s9VkegwvdQ+jKkwe_XIw>gRf3I?rEaF`;NJcCw!DWDDfxtMw zI^g3xv-I<@D{b;yWsQH{Td3|cZd&KVM@Z7|S(lHvO)lJXCSxmPdJ?A*@n@M|Z)=Rg z@(t^G2O|W|WNYg%wdUGKXD?z3!;c)fdL@rt^=MMa8B!J!CqDfA_>b-G^PjsdXDR$O zZpAszWkv+)iN>ZgwDg0*Z}~3rm9t$r0EaLQ>Hv zWPUiQ(zHD)A)Ai8x3d=7mPDylOGZSz(r5p3$R096z&&Jp6uM19TT9o1qKX@)3M8an zRHepc_aQyT_@t-cW{}qQ+S#EaGU}JaLZT)&2ao8`G(izxR_+ic)DxzXhi9bnWQjh` z^WfvCCe0^wIaGA#-Gw-k!(GT}dwAeoskE+l$oAKNVh2ekJ=WDlnMWO&eT$g`x0o5X zkURRLcVDE`&McFnSXnn`$6h_{)>prap$SrZ!vF@1FJ@6 zJoy1K{p8jvj0!rO)Rl~3+nkRF@Re=c1GdJ}4uJ7`Iw(P&k*Al*r#lv&N_i(FOk51v z&y@Yf@)Nc7Uk`K$Q6cKA#=_9|({jSRR!Ij`ae#QpQ2z>8kMHdv$y0*7Q-+NZk_LQ{{CX_m zoAyA-P`2l>2z$ABp_trX0ckl$>6tj>$4$E54`ps2322}MKBvfvQHb=9$OeMszKSV^ zB+8`>%SmaH<|>|Mh0FKbkQYVY&4tSLc*s+Y z1fdG{d>waTB(S2o)D2LJ$av0?X>&tGOdugUoS~h2MnUdvG~+(3-A&VybCXPzO=$da&(U!cm;eF0e}DhU3*<)YH43@w6MXCwTV~+~S4fq?%I%&thrk zdU<`z_0xaq|BCe}RJQ)Zj&QoCdgq;5*cUPxZ)JtAZuWCt{=Vuj@KjkZ(~BZ-HI?_a zhIdq)cNvd;P7#N_uW$&7SKx28&0V)a9```Wz^Z{q`pOKojakB4MYjd2XF&NobLL5|@8*S@c=&;?%_T4onZ zemwG;pDsYS(M?#=*XtyLnlJL9UyN@_q|!#Duw7PxV)kz|%wWjP>UT&!M=11JC~<43 z)Oo1NS2mGe2E0(_$quOn2K%=r;QC@D31gp#M`d%sv^U|6Y_HCXTGO%;!QeNiU!o-` z;!9c|fQxD2VUQsk+94$g$H;`P2dGWLL{a6$BOjS|wBSBQnd8w%7K6Cl@HlW^Ty9o! zYDUE1>v+my;(tZ1PCyi~R0iLmpTw^)DLpOYteHN5>|H~SWs_*<8MQLs0P+j=AS|od zUb?qQhX0}vt?BHSEZXKd>wp8Ov4*%DzL1(F}CWh+^p^n+2ylrXk1t;$luv;iGxtmBSX6If? z^=)L|!(8^Tok2Cq;6Km|@17YXjWV+@UW;6$No1AafwQw`U9A$tJC?mS2iDNbJAx3vtFiPK%~r7$s03X4f-s? zfD!&fsEHq9--GYWhBY>!>|2`|%N4nhX?3Ag^7ca6`5b2tUId$5x z4Dd-&BSw5T6n52;+Fw`ZiY;?#ug0xjRy&)fLyOP|^|M`=l+iiwdudmfDgJ7z!$Ks-a&wZyD+&WURs&%A=PSYq+89p#i@`Ka_1GZ=HT% zz1HE7iTF;hE+E5WDiS8y(d@!g{_sjkN(FYa6OtCdQplU1OJ2JjP;Pe}_p813grOmD zsX0H8O*zL^p=0-=8hyl8R#6;Tpd@1ym@UCyjBqI)4)87P=pXOideS7VfPV!MrHWcPDJ&l!uY z8Jiu=jd0g}QZg9MSD28-7TjOO`l^ll6(76J&HH$A`v%Q@of-Q@W!u>~T8ao^HMxif z$pUHUhYve@r;Ode-hJR-pRRKUqnKi(J9=hi9v6h>;e~;MP+e;2;Vv0H-J9W)zY|lw z@Bla6>EqIxo!>Tbaz0_+ITEoyLI#AHT(mR4_OG?0t27@bxads{oT%dKdz{y^nm3J; znWW^%QtJ?W%hXNaE`S0IPg%^q%bML@oTV2Wbj#|LT5XnlqeH$b)-5|8B12PF9GOQD zU34RPNip3*JTE3$h`VO^?3kbHBIn^IC-zA(yK@uPZuokOvGIvqn(3Rgl#Z`&I#Dlk z#53P42DUAd^#v!jcXgmcj#Bw66?^OD#^j#7t;id5xnv#AUr}3Jfhl{aB~fiMq^Z`$+|z&6$zEK~*VZB4rkO#3pc^!}P%|sM|5l zwKkq$wmK?U=`FnSO=82ds-mzCPRlhJldWHt>x|u7Jq#PV-3f*)XlRFYL1>rmRhRw) zft8%fhSegil}`_?ir=rS`(N$2$owQwyo+1K^w267VWq{sY_|OVbtJRfAGqsprT%Ae zcbj&vB&|i1WdLUz%zx-apSD=&L3)gbBb4OU@oifDCz>faIU>yD^(m_(0s zHxssB5u0hspQT2f)^f6Wb+WVcm7VlJxaT~3bsC%`ja`#z#2)Uj@V{b`$(BDVlG^!O za76s(Wt2jV^>;C<{2992%#z~BoL<#_)4vHazu7~63ou_8-(1C5_e;2+mT}DSMUI}x z^ViD#EmC-+Z{0rky>GFnkbnapi;`}M076BI`l3h~rGp@%>|iN_mnNODqMK@5*86i+ zVmt{$sa!a%XGR3Sy`e~!;gtPnZSSA)E}NrlPsBpa>fa<=Ef3}X_EGOMXAk_dO7C|(qYF-Bak*^$y*-{Q6LM%OuD4xo z$NkH5hm%gQ-F0ZF($QL+f0a1o+r+ZS$!4Eqi*L_b<@29r>0f$M6ng&Mo|TDxw4$Ie z^D~N}@%7OZs4}0_pnFMRd!^IujSdL_kXK`AWEli=D zy?1CW5!@z}>RRFrDICIU)J3k82AS*6<)r^`q8Qa3^5SH}oSvsWx;y&Zi`U>Gxn^b6 z&=RF&Uu7!CwP3?QW*wi&TCyQ=99{N{Z2uo9C2yzsJGeSR49N#S6@=6W6l$8jr*%_D z*pBOYq{w-OU7T{rYr~ZLZmN;b)05>%oJ(!x{PW^zEZT_GpH zGxDK_zOVI-J4Es&$K?Af_xZ9`^T#r}Y!+{*C#5!Fsok~{93%kTy^L6CNLbw@H@O9d zL=rfarltJyrhyQ!Wt4{GSricugIK{{FAhITd3-;ZJ;Y&&(gLghkj26TdOCKG(}UF2 zgNR!!;J8|nIZ)R8LK6GtvoV)xsFPjTG=OKI??C~V5%9t7*_R|Z6Qw zrcHDG5@{S&D9>f_S*-pz8DNqTYp5&XbS8_Mw5*R>eVDt(?3H*Q@+n2k@L0#7Dtx9h zkEYS(@R+4DQ3yT(7wg3QrKwZ}^cZyQF^}boVtpwcs zo(jpp#3E1PWrSp3H#;&Nv)4+a68yUQA(g6Xib-@w!Xqw^u)O`U-4ft{C`v8Xf2k>? z|N2=kH30v$>%|3UkJETafTX~OD}(^ObcU}r(GrnPkL{{T3d!93`d>5>vJ;C8-?=dE z085t>S%{drQ1G_UMLlHQSKiS4&0W-`uMw;4x#q~h+e`UGL=dk4(I(g=;Y^LRfOC*& zFqJa&H7S6dBo_RW2}BjAKmH7ot^R|_Q;2ETBgHO3QT_^rqLD5Q$&td)EWC|5P_#`= zd|ArL3LVvWKPq5^U`*!*JFDqoeL#O=4yb8`<^01eNP6h3H72fPuDBu=# z?~R1vDT_*lQFmf^mRHfnii0FQ$xQ5{vs`$7rJAtxWc)MS>k_)Jyz1U{gP%xU$tq;> zw*k}9&aDy5Jz180z-<*3e|&0Vl5sCL?n|EXZuX4oh&Zi5dm6VgTve!AKP7&yl;68b z`_2p2Lz@`-gGK{UNv$~-+!*k{QEAu z0wD!^xOVJyZT907&(|M!NP9^guwW|4e?YYwTSUUb0RMbl*d0MI%YTDvA8PD{vlJF1BecsKDZ<68ubYGM}Gx0r2_Bnns zOjyu6sZyqNw+UsXg-4H?n_O$Xv2O$c8Xvn7e4YolIUjD7NCqxPqyKkek(Xc^K? zI=AiqjmP!zt}C(-O4?yl3ms2OQU!XL|A=K#{Ttt)X9v3r!?Fd>(lTq*NL6+RRck+G zdTUv837bj@_+ZnI&bI+ErsLX5AJZy>w#BU%M{ZX?eII&h`yjCFvwD$NzB$t}+k5}1 zpr?>r#{C~V5{si|4xjRN5_h(D+olqAaHoZD#D5yF1o)?d+=|*PoQ>{C_b0q+tcbb! z3AVnP2m>YMQ;Io1N?91!0=1lz6~sJVc>3a zeM-_xb3^Vqio563VqM?$VbWivl0BP&2D2|+0+&|~n_GIw4&4(1SGMl9v`r-)zJ4FL zy8o)B<2#v~hj3uaY=KYLV=`Ca@7Ig(SwzxFkVF(*GT-#*TYKXyk0S(_7NFLx{obp` zF|Gr(41|Lxp+a};#c@g0}! z+rG^FU!dCc-HU!as1~9t`yWt^?t%R84B?wCffWCNZ*r%3-)^w1A<+?U0?tZx4SsGW zUCq4@KCf}>+OtMnFMJOEQ!b-Tza0B0 zdz#C7xue4RdsZO`KB-u@;u3PL_mSPH8cuT@sCKiNa^)~GMSWKB{bt3j=lZ+^-+E*% zb~5$o_CO(Ie5Hr~@>>Y*I|3ILk%F};TJ|9iu4__)!GT8j4Iq zgQWF9?TR=!O9ry74kj4;Kg#t`^qGEf*{yN;7jZ=o;>-Nvt6JkB`p_Rph@1`3BNRED zCis~{JF6%mt1>R{XB?V0z7zr|kBzVXsnkOu*l!>Rz$T9M3AQ=K%`GH+gCs6FC4PKh z3`LXmh=APC@IqulgGoY5Y;uQ5Qg>`pZx%8WkOB#V)SyAKNXThj9DprBi8GX(FSWV^ zR)<2iD8c{$Al?y^#gC^kNRlr^MUd>}kZD0RXfJ>1H~)m}u4sE=`p_{h?<1{kE7N z$Ake8fZH@;{;S9lK$Nd7O-M6S1qx8(OV`Lo+F>%S+K{yXQi$za%D8v_qoUbta76&X z4h2UyWI*)cpX!jTY$WT)>8hb{DMbSwKGK8;$Pp?5UvnDvE8{^nGRi+I4k|ih4_UQ= zH;0M{Qb|BWC7y65y@h6lS7k>!XOVly-%$dXcbHWpo7DElTM&R4EToFr%5BHS-=yP(z|b*l$)t;!y(#g+!&p zCk%```95@;eXx!HKwAId&TC}=N?CxaR#=t(OFVL$zXqUK1Hh0ll`7pLN%684-oKlA zftq3XxW!P@@w)ahM+x5vc@rT2>-YhbAV05&sLm!L?>IgGM7n;{pfC(N4?u9!0VmeE z*DvY+cem>BOqBKr{qq30rxYMB6n=IL)61g2x0gu@AX#EV?1;eH=dAWcpwKYrcMMVi zS!p4L5L+O!p2K}`u2WFRMKXr=53wA@&(+%u?Z5^lwH&k^d4yq z1B6_wg=@7&=D>^UkO>|1uaK};7$Of;+q6C6Z@NOv9(|WPL{$XT!G;D~^+ zb^l7hKmW*_^?>adGH|a}H&A;0ywN_iBR@a$U zZw5W-KIV@=?_~$liZ3O21N1j5UltG2#W9>1IQidzrqFjdW5!(&x*Lg_3CIcb+$a9;4jNajN(veJA+=%4MXlYcm z%R;nU<#4v>Sg`hJcwRlpdZv=M^aeKkn<7JjNLL=aaad_?={gZkPiUAxJl>0Gg^i>c z4gZG5bbQXqavt;=B*KM85q8j9Cn8<3h_#mY>w=Srb-W`sk=1KBtNM6YAJ8sBHsuqspyh-{T9ezv&Hbj!)}dL0A4n002Z-^xNFj zN%^M9(sh!Jy4QK4a$ifvOFa-riO3I%WW&8xAIv5uDW;)H)A=WZqMJ8zT#a3ui{h>di zwr0Nmwn!86xp%RU0Ia+~wzEQCe>0q?WN^nmOCkY&ehdq)qW}6v`V+ulu^H6!cx~Ht zZ6|5%*N3&eiM4}+wIj0cCqmy(AAdi0{r)%U`{f7R_v?x8w+G*GWLSc`SRx%P@hdDi z84In&LWU+_hgbxB-L@V&mW>pyizQE9r>|Yt5M5_HTxYey5{E)*vdDr_$YL`D#s=cD z3tq87Y}7@OkgrsTMFc<$LfA;pY{(SdLGwsNXJ~s|DDSE}egv@fumCSdx5wxq9(5A^ zMUp51AOZ{F_S1+Q05C?RnZ$#jsE({oRsQ~~!dD`|IU6zz3S@tbAK*ZCuwWT1I4*w6 zOJ}EDn&9`eA)b<>zl1KKkOhE*Ml5W0fUHzy9m4)Y6AHm$KnUqftm0Bn`!{bqs3xD9 zONq#4LHt#G+=hPZ0Z90UhC=DcS&Ik+J8sCyWR?B0cCTUK5*!Jt770 z!b#JQ5u9@yE=-%YF0ezq?$LdS3`sjmMuq_*_Ss0m6DM*FIC$`N=+>3A;V|aeVwAC+v1_?{;VBVrS>*@DR86`F88e{{H^%?(VN&zjk(Zwzs!8 zH#bk$|8w9`u$z_nn>joaR*0L6`~L?B`)^ikCU$0K=Klf<8^4?wyc{0B7#_xBVb?=L zSAG5e0}E@s8bV)T3UQ-OH{H&cEiE_AZ*H3(;+jSN)rvgTZ5A-QC@IEUdY?xv{bF)2C1Wk;1Cga1~&@6oxAS+Kf{!~~0 zDGTg>ABo4pYHMrXzkmO~y|Ciq;=j4Me^XQOG#D;Z;wm=wU!=}IUyEXNeqmu@K|ulD z4$IBWJr0jJ^!BMpPk;ONZAL~$YHDgqN=jT@Ty!)(TZs${3kwMe2@Vbp3JMAc2=Mjw z#baUK-rk;`p6>4Mcogin^NVXoxid?vOEbAML&Gbb2Nw@zZxrrz>l?VZxHvjG+S}Xz zZ!gTs%F5i_+}POI$jHdRz(8MLUsqRGM@L6nTU%38^WnpX>gwvMs;bJ$%8H7L3JMBx za&rH~d4GsY{Nrc-!7qqoqdnwg-(q3=Z!e67{2!7O2ZP{1#5f{CGZB&h4;CgQBrGia z{{#y|B9VA3jEsy727{51kU*hO2m}HKgFzq=F)=X^2qYpRA|xcl5diQ%hqB}E2LJ$q z0}w!%H0sd35fDleqfiI+#Q%FHtQsgqltdWyf6auIXxJ5B4mVbPsn9EVl>exy`s@EM z6IQd>U^~P0KbWwV+SLw1#~T$DB8sF;zUzO)i3TF;>CuQ>?HWHk6UNS}0^)1ioTc{@ zb6Fd2YuLe;F}Nh32!kS|NEHipJ}`K@%oiH>6g+0+`9)XkwfEmlnD^RS=4J1L$$^A^ z^;auio;wq6Yj8X&_Fqg`iycCj5M?GdqssMYCiyIY^3`@lfdl)- zlMPFr;s?drhtwvDq+GFVn~CD{PMb;pH%yo&7gUr=?_D?%204&v;_!bmVaj>z1Mi-{ zbuND^LTaNI?_Iz6Bc6Z5kt5H8ga;i~T2!`E5cKDNGhv5ujFu#3qkY88_ji9rvb17* zOEP@?2w+N>I_`Y8F{z3QpEjv?l_j1zdI`WZy`1!#=H36ngt?@bri$1*zrTY7!t$y0 z!ZZAAuh^AJhcatEmA@rX#s5CdfBh+&9XYa`SI@~3vbvH+A-*U4yVZY1$YscGu4W*!r0ZK91 zgM4Dp&Cw8(?@IQN=jyw<-t45#t!=O3!BU8b)SXppG-X1>3lok9%tch z>3U;GsMN!f(J?+3SHGZSvD&L$rixeAt)xzqPla@(IK%$Xm_1Q! zpoqB_6NTJzPf>!X(#)Im!|&Oqu+XU@|AY=86va)efEM$>21v5e z^}A_2T9PZj)15ctbdl>#%-BK`?#CB^y=)2eRI8YR%s`=J<=K!n1B3vv>6mgL2dN(207D(!h=lftxY!Mm7_c`_=|!cA!}&}K zfMSM~(LwtBiA(IM)Swu5{eU`ueVm&A1~reSCZB^SyZJuH;SU0Ut$!aQQT^au05T?I zWHaOU2>31_bWE(f1WCk4%uIj+*bZ>grfP)EX1#4IluL>+WZW_j(x80C!9~LPz_gKs ze&C$lK>n#;^gRab$cs<#G}Siie}IvRS0KHF7n{X|>ocPiejEX_c1vt$Cqyi*>0n_1 zM#d5lYCPom7C;xuAlr*0^Vwp{_d6|H3x!hIO%9+%m7J84m6GId46=^Hf6kLueRLcG z6O8x`(bkO44BC3}{*6cw+2GX?PWzJnvoja*uO5_z@nD;Iuv;=a?ig!pJ z6#NlKd6*JNTopyd+%+t&h?si#hBMAFued~yY}p`!Vzy<3kWt(wjB&_x(hCmsYM}$O zd7?m%2YT5eDu+3PuyGWJ6aeRi0eS~yY#@dJkjp!aFkxenCpK`(ezy2YC&DZ&0k zSt=6x+6y?5qf7kGvXIw^&Eh9m;;Ev=PqxfriG)`{@RP(RvVXg7AHC8o4}7<~WZ&}R zz}4fRFFu$l!gBTeu2@Hz)kPkbe(C{15N)2&-Sl29$5+E!Zq*pYp;GzE|05JXUPZof$m{r zHt?(H1Fp8BmKL(KbU4QzmU69oS7GswfBC)k+4WEhku4+>-=u#e@+pftVQaWo$LCy* z)+$fC7;t@n8~fqqrTuam5lkg9eD5th7GeD3fY*S+4leG))Jb_~Dr(fzwt?-GX|o+& z%sPr>D-a4oZN7+^ZW|33CujSq0|tK?k~{UTdhf8eOV!~%$zD<@NK2@y(h9z;RSwm# zxjO|WP#+Jk@Lgrp3-Pn5XY|fVy1%|R#-QrCHd>FL^F$sOv3~gpXfXV+tLGxs)m)%! zSU9%#Dq-kb0O)?s_u|o(%&YF9SIrld%wj&^hP$;t!2+m*Ltpcbd5}T49sAxva7fM6 zN6MDEZ=ckf$?0c2^u=xX$VS?-Y$|Qgf2)aJA0Qpg<%vd|yly8>#zS*uisik{oBfcH z{c7vpxMvU8_vF%hl{eF#7F=ix=I5tGM0Xt?v`+3l^NRoIu%c09Y4{*PX7yy!7emQ% zk{Hvu0tZrkV;i~upqDZu=F#fjQ-3|eI#Pa~=Zjw^?{$;C#sZIS_C0=Gj;pZH5;7pe zNS>pK*m;#m%%;ofS8TvAj>wRGMYcCPN?*TBcoNXA9h-q4Q4a*})bUuciL;7hzN-(ayG<`fFh-ELNzux4bLg*t%ePTvsG|u!f*RjYacU4*I}lAshE7WQ z|LOOiefNf>HFRnC&7CK&3(lYH4(J>Kb$@T^oKX>7+kjr65oh9l6(FBcH#(p5TS4q6g%iopco+C8d2yN02Vb^9e%=lCk#+$AVf?#ph!{= zAeB!IENciEyB{Q>q&>{$Cc+-hN%zXmm(7~(d7gTNO%~;SKmI&0?SCoorYaXt0m!Fz zPo6s3BU4fEeSp>pZMcDnwtr=eUKXXi5s|kK(6}`Q{550}7@_)H^(its(TUOy7mJK` zpvo#URedKzJ`!DoUyk%P1L+g~!36kbMcsK|SNfACqKQ<5$D@PRA7B@HBns8}8v98@ zp_We5zLK8%FO80$?RkrxyAq&R!XjcJCfF%fzFbHbYr-g!FdmCcF>!9mqHp_2)6uFj zkmb$QN@ERh1>y;;c|drVptnoL-gOiUipG5X91@?^w(PE3eNLm}QGmmAHz?yKgp>{M- zw4Cl7k}vNNrIgXxpJq`>(2!9hQ@?2hQSl|mny_*?Ko}MinWV(_A!#l+?ldmbG*_P_ zOJjTf(Qwh;_<8+wUt7q5MEbZ>2IU?1?LKEY?a$gxD5&TE%G*}3m^VeX&B^t|Y19T_#g{SN;&^kBcAiQy1#og4 zjdg~~0MNXN27K|O?5X$o5-zilo_yI9UZjgC8D}c8(2zd5jQ1n&9{zZDHWM|1O^#R$ zih{npe16CAQ%=pVJGS?@KhWpC&*sjMO7n8g*6;|Qolf#!%)Y+JzS#h%ixZbYqZ6J$ zSCEJk8!}&F01W_k$cAV?4wH<{A?#&CW#^N7veOsmFZv5M`De@FvNOf>qfUon0!;I% ztAy%CGzO(267GQAr-|eNBo}Nz021~C3v#p}n-|H5HqGX9%=MHiaM35anMRPu6m+*0 zEK)rFa#jG;a5@A)xk3?PY)D1Ch*S4&UK0%>DSpjYtn3kA^&s_^W^|9H16q@n7^Tm6 zr>J}}1(XVia7QSkqKWk3681<+5l*FJggBPK3rj%iUW#|L9<`ThFO}+Cm1;aHRVOJk zGAnz!RB8}VX4YP&n^R_SRc12=uwp2GZdQiR%=P#QdRxmJI4kJ92503MB%LZ?8T8G2Mcl2c>bUNb&cHhEQk4k37HRyy^fW@fk4tG)QcQt^4c z#XYI_P7j^>kT7X}r0i~yiIdS5y`%Lgn(K;^UBrk9^p=k#t|q{__KHO#+iRoUEAl>R zlY0?82|xi;v>T8quu%Jz8{O_p#gm<;P+AAOc7az5@f_RVJN^jh_*hg25}+cvJ_cQy z!f$>R02R+a*6q=3_%%`*R@^F^>=Y?qM>mRruSY660j|I1U^;a+RK}kLUbT? zp;`^RV|52UALnDK%r(i996yo;G~g(nt28$-`R44k8|rkRPOj?IY~TGgX|R1?O#5EQ z3glq6=VqZ*pS)A2d(kA|OO>4+BBh`|TWVBHZ*y6GLNzMbpTN&$G&Q9ACJRarqC{V%Wchjlq4K2Ua-zizh@bJ(4yId4I4j^(Ake9+ z)njAcE<<49myq-)P*h2TlTr`)#|DA60j268l5N_U4U-vZd+hG_d^7JM59$$Krd+3X z)u-!@fqCl8K#9W;I6h=KvhQneM*c~P-!A4EsCQAI`Qm+7Aq;TxgXE^7x73`n^rYt= z1qP@OZxBIdqTnPeqW7>SB;|eTLw&;geboD(*cqre0Ui=Hov0SaR%|DsJ_(mLGxrL; zXxxD2O2?^vmk|C{#iHd_fD%7^$7&5e&PF<+5V;tlND)M&$N+Oh#s|QVTKT|ZS+sp( zmsSv^!llEjAZbqw*&iI1Y&T(;N#*U7&D)@Ho8X&)Fzw!u@d3FaVsCXT!~NEnSg}yP ztaMWA%<)g}5{H~EBxKJ5arPtVphQW|oKn*Hv-* zC+>6mdmJK5b2>?L^YcxWKZX<}zW&{(^fA>tUa@_kJuWK>S*g2gGeNkGRVNe$Zqy;J zkIDRifR}aft7F8xp5!_j`t1gxD}_|x=Pa%NM(kM;%=|=m;&YeaRCE642l@mb%OUZu z{UccZq&b;9V|$nfN^NV#Vz6*jbJ4toX3yaiJ*Im zg5)9ynltEvO**sLH=?j_J!4CuWUN@TwI9su>)Z?BatjyQA&fdmposlW_E*QwP8R|~ z755F5P_h;gV3Hl#Al^~)fbL@NldvItwMq1O{^O{<004?HWNH(UQ2oimnU7Sj9`Cr$ z@(A^E)~?|ZH3lEzKli^2GgGB`t*q1$fzJq834wp`njRb8*F)rNfUYr6IU5j05x#9O zQvv|ecg=v6whHup7z4MGGPbk})|l4TyJHt_0c7?9608>`PTF4ks>yn@ zWr#&#AumwUB>jbmq7=K=?CO$3oA_rR?F)ID9HVxIm6mL z^NGQxe=MyD#Jf6s>z1ZmU0Z=V$EC^3Vnu|8L$0$d`!qcFXReQ``wu%N_YZduLux5) zMT|73>n?P@H!&WAJ^{ygPxiWxDeFqcWA(RF6BXF_~WDL)XwEUXBl1pDP*m!@E?!DPjVrDXx$bHgD43^Knye` zLc(Xn(BF50{w~>WdAt4PP#EIZx)_CDF8%Z4cLztR0i06Kp7GsB363Txn8sS?`%nFi zoc!&oOKCan-I;%B=61*;Hda_DX6N>&w6L@3`;g=e!CPH2n~*C|Pm3n&{YIv1NwI4s z;Y)m1$*?fx!@578t#^0nZ)`a8rjCIFN1{Ut=VKpl^>96ZC2Rry$criKWsK0R&FRcH zgk=)Wh6r)nxH>t4JGq1j}_G12nWr}v5cRfy{ukig+LA;FQc6YwaO6vSnmBm_Df(+>` z!+qy%2Xnd2FBVs?ccbmh^Ic6^<__{wb`Es%eERRc%4a{8?>_O39(^y<`A>eg$T4^O z`*0!7DX4l87DKBm^JkV2$@iImx}Q65R_3M5-!qw51&F`&dbZ<6j))4Gq^gE;)y;cX z%&=;ncGsB3{@6XHl?`w|fLPq47%X*$QptGg{{zYByCvGgP(+4}T(zFM1qgfa#wtoc5fiR5tsSI2s?bL8gaxY+g_ z38z5sSsFW8j{i`sEDo3U9#O%R;flrXV1U6QCU z`aIsKYHV$Jzer>yO})u1_jYuWCE-pJfqg;!GZVL-1Bf|5yqBBB$M4b>{p_FZ-$Ika zKBt*?Tls&V^5Po)szpgJa5i8}%ATsb_*41LX%=JyEuv_3G%ReG$iow@$1WAo&z}3U z+m(nXNq#T=c`#~6q{bp;dPi6&B_}uyO|q5A#N;;|F85}G-k!zg!A_ndO=VQbeBA<7 zm>7rDL~+u6|H;x!corK_%xk;31Q!)9Rq2xbr43Dx6@S;|W6U-^faM>3-!q@3U))p( zc#a~lCE_9mg!pkBO3-mMB;(fg_eY0Y&rw0gVGo$6)4iKWQr2VeRz1jLnAH*OF~Y-R z;n|%6sAW~*^}k`a zg2D2B>oGjtew!%|<^8wcId=Q+6voI0{HmzvzWRw9>HpvasP7Iu>M3MNn{^&&KWESr zEAl=k+Log6thqaq6yhUNdC;;+!~A;s^c&9W-*w>%4girNfV+DTc7`#(yay$M*M^d5 zuMl0UOJ9uE1bygFWuI?R!U<21((H^7D9axs9`J6N#O5sJ7(giB6_rMD@g)F`v2UGQ zAvPCgX8HV1?XXXi$n$j@z3Q3gsG6@+6N6 zoikQ4vWXdQ-k8So}D}y&<OxJn0|ehR;#2IggzVlrkdn5(AbZWp(PRFvLF z=6!2k;uls%ODu0UUTafy{nCeehVFL_Mvn$nad=k?6gYf)HNALS)F+UlA;)8) zJ1@vIeWqzkE#OpsHCVm-(&h2u3yX%?C$dZF96ntFYBJ&9;*KTmB-+k0lU{yq+&xBf zSbnz-<~JTvj;h5mUBA%Id|{*_1WUMezhiqxrm;U~24dp+(kcD7Nu-TfReI8{L#hOl zaQyhOF_K$bpds4yN}d#^La z+y9K|WNcvsfW&<=<4o9O`rNq#L{(caAWsU61+IeT~CxZ@LHG~xBQ($c3`Jj5exS{04)A^Y9P8iCG0z&5v-%T9M{^NwaqU;5d%*Oeb+A+0cDb-eJ7B)OxUP1>$tIPg4 zDxP*^*abhL#ZfJ!3{vEN-Tq<8LqZs%$VLF4=LJL7ybj1l0TM>de_wt4aP$^0lLB<@ zt&yrK9w~v#U!_}?=aNtq14I;*!;<|p`6q!7JBE6>TVgXmxVD?LV?p2Blo-R4^e`(w zth83AoF^BO9L?vYbk9eB-TNJ^QL@Di4rp4^Mj=`^Dby>Qi)2;Ad zPE2^cLd4vPX8m5_FVae6RU59`SwPGBd1j~KteiD*`T8XO%io4RGu_6!^{6sJzk*+) z*3jV+I^3CNLze)x6Tdj&%vB1NmC$bIJsFQ45m&hqXfy8Sw{CHuz>wT-_Y}#G=Vh_e z!UGppO8@5b1*UwJ6>8Bu!D`kiw-qV)E+0=2xZUmI?7emMMohD;oAbX9#jL;YT=yhw zBv3<>C$f7s%@yt^$XSM$Ghlnrzk8mgcQi6K*V@R(x;P z14UqG5Aj?XiGQ^6vJwlG(x{AbSf#Rnc3(tmU%N&h^?FROJE34+Z%V^GMx*YMezu>n z%DCuVrAkAkg8zf5yI_kd;MxT|^w2{$3?sin3tk?{YD~-tE*_~*v#?!sWsdhxO03f0Sag4!Gr~=Fp zf(Qp<3sWbf&A|f(5FuM|s0W7c08Zc>TVj&MRG6l5H*_J(V?!+ykQIPp>Ro#@E!DXaoQR zizcHq9B`ljXxJ$nH~=vIkrcXs888PA1S2ewVgSLUU`&X5GEQ8K+J+%7gkUbNj4w$? z!C+)&ZxtrNrD&3;AQY|9NR8>&2}v>0ggQWj0Etj)^uR4d?0r%M2E?Kh;cWraq{oH= zadfGHlJ^J+7T_NeXj;U4$M06REVW`$R_N3`ljvO8LMs1Uy7LbKHXn`YVa*!h$un!j zGhwZ%0c;0Q3jP4LwE|3ZF3~T7)$$&P2?P|mM}%y@X@7hZI$Znerleo#SuZ(DUyOFY zkG!`^D&7E0;DYkiz1rG{_K3|y!#ym11+n#rh+X+F-qwlj$f*T|z(X5lQGjGfBsC`B z2Rw%QKYE*!&OFp%{y|aVl}c05=LO-bg%x^@fe_`2Q*`KiMSdIIcW<>Rqwzr030L&! zJ_CubNYK1FlX_{AwG9w_XaKA%93=omqKF9!hRt9C4EK{_cGcZgn%Fyw$xD~O&3YG) zDqnrxR^Mkd^E@x*oouesAQ`~++k%R}dio1TSOC$PpOiJoli3FF5yTdegn5Iooy!o0 zfCN{c8KP>DNQf$g28a*A3eUo^4M6KiU6X4Y zvx`juAdy4lX1*WIwnWUT(AQnpX%JBAlxk{dGFET^Or#Ur8@a*K`&LqQ{b^{f8iCIT zSa!TMUg9>-dzE0Nx>=qrSBXYTibN=YfZ%%sS7Iy5=gWpJ#pVl1=)OYY>nLM(ObeeK z?MQrX7uiLaX;CLl>8tEYQtIR&Bz)+VdF7*paLZOM5MX|a<8cbej9r&cHN~f0*H@*^ zwJq9AVSs|+(O{qt28d(Gd1yGW*5(+^MwE7*Qd*iVKZ2Rmc8JFl^JkrX!HpUx;86BVd; zr%ZRJ*%^Q0S}tO6*{@J!nodq)9`PMx`%0NR_@i)|+>4`zfn~`msUqX#9zO0|L zCDQ_l%#dh^R!gV9+u4mp>-%;BxKJVVy&u#4?4v54p@_(>L@JBDiogBGp>`DtfUQLs zMyLIKZ^z?bU}O zuQM{>#^onTgD?VIb#XFBHf(UI<}m$>5Y_=OrPCw|ioEA`MTFhX3ggbq8_wXq{X`G+ z{6P%qfCCZiBf(>n8~~<0634d_vw$L*0f`tJIOMnN=xP1TKlmA+(RDL=9b2&d$*>dD z;5W28#4%IIOGa2IV88|ddJtF5dc%R{FGN9ZUlv_$pSb|YQ#I$d_06D%(vG5fM@Eb( zl9&6Q*i>ifZv2C;&lnGd7hMpI==qv(`@UoFjEjnLO6?mAp~`RF0tys=i2=dJz}RO%>PAGo_=!KWWrEvIlcYyj+=-0b zda6cZoJEpQCyf7;HFeBfj4|aY_a3{2S^AVI-%50+BY<4y1XFlcF{I@@JI;&S3#&*L zIK_!O#gH!gRMdW)Qs9_MjR@Sr2_85P1Rxx;EO`E%`v1)DXE^`BeQvbAS*zyNJ7WQr z!jkEPv4UNr)jV`pKf%CBbA3Qs|qbDDDw!yv5Mzt4l671yYd+6eM(E6Mi- zkrmNHwPE+gPck4XMvu8=I zkDg<91ymv{yBofMEyO4tkjZ0yPi;6??aY?&G9}qz;T$5R@NKQYvzWp>J;`P;ipTZK z<>OAG?H0m*>$~k~Vj$398T;};@9U)a_k{gT4@opA9n2xlXG;9X*CB5h7>(~~S=Z?M z>3thav-?p_8Bm2~wS{9t9cYz|rHc#z@dRK>TnI3_aTw6Z89-$_VSbqhE0n$`cR+_u z%!Ed`eU0zgPD5W$T&svQ2Qi5C(L-u0IV9xy;C!qZ~?Cx?Vf4j9`4473JNtx0yeprp$la zu>;CNv2Fwb0|nl7`cYGr(m9=pei|?|YKZ85l2!8KjFOq>t60Q@pY+$q?$=j#su55R zAG~LARm4$H*%Z>##Ml8u^cKRFdTOhIpR_gZD-~K}1L^@0we%~RY$=|+AU$G(9tudt zi@ewcIQ*9hqvCcEM4(MRF=0k7ry!^4bXp0!-J<`L-ZHY^Ww9b==kmDGlJ7a3*cXa~ z-QSmaoNhOlNd1QiyXIJ_;;~NMcM&y_@vhadOrz4`d=h>W+sm{}>(*NsyS={Lch;o1 z{x!l9+?vj$MpGCJYn$uio9?H1InkDu)%bBFN_Hb+V`2OgG64rg#_t2_7`LnhMU`NQ z)$WdGv&W022fT7v0HC*?7wW(iDZ(xqfz6iRJ=gM$-`ft}h+Whb5D%C64u1oztlBq(^Ts!U~HM9GOTMLE)ySv%1WT^U(pp$Pi-=cEm9f ztBSnO_*{|1pf`o1$CxU~l0q`rpebAbltSgb_CN zzuMyxmCNaR{p`SvWnmlI5I92wy&zjo!T2^=60;$EMsi1T9)v&ngkuo_7L>H2Cu5)2 z_}S}3an*NQ;+mKEHE%RjR>*OjH&!vaXvnXb1RCIkg5cn$)nYG)Rwi8TcQ^+lh6~mB z+vqw3KSl8n64_&Uo`_r-5!_dcQr4UGzM)b)nWKLPS9`aNEa0MlITH-1!{7%;@HICx z9vdh&Gx{*uy%io{M6H&H2JrNeNOVR0=OWf#21f824S(0T$5z*yZ|JDl+GWCaG=E&^ zZ;ujEvF4j0Z7crkZ9yolI_7(MX4Gnm5-h-35j8T(ZBjOxQE{*|hJn+dD6(7z7Fl}k z&)H;)vpN?z1B`w=Q);?7O2@?^0jq@*Vc53&pTFWs7zR#v5|Luhzg-bXo6c268~jY# zy)@c(MZo0RGTNtv<^84Gcl(@8LN{bnm$CWL2D$=^G}*sd3EP%6u3{0onU#Ow{I@Lk zz}C3}`U(iv=l|5$jj`=Rmoz8R;PEeVyOc=bi)nzwFVQu59Dd2r-KexIg${K7kTrUq z6cAAPR1QH$CM{n+d zbTSRd5-+PK#SVri(jA%E>(Acrocu`6lBxG(0p9HFnHv2hP=<8EZG)C2JHtWh=`SHY z(T=+lR1NE#hf;b98h{B3Y|C-MBr;4SmU;rN&jkiuQG}wuoQG1?E*ph*%;6)OD{&ru zEzVtlBYN!C@8VM|7Wjr{l z@bf`uF5Snb?DbHy`YY%m2AQ##!-8xbKtdCBY$;`PX7Xzl>Hf^wFv5(U0=eLQz$7Pf4hM`rKaHn$l}?LF-Vy=?kIB#=vtewtSO*fhqD4v!*GQ~qif3fM!AeCl zyab4)0DPaDC4z11CDs>HT8jVD(aQs87C|-WK&Ny>o2br#+p8II?3W-W$xmIGXJnu+ zD&?08Y4lL1ArZacd|;`Hd~KjI{dtzh-c+5|v!?7=8w@i3AKcHa zNY!Xka#ay?yh14k#vA~^0?&DwIgC`j;<9MD%al@H^b>yxeGauK8b?d?5lK+Hy%=2a zFmm~w-w70g7SNx5*fyGyy;a}>L@5vhK0EZ2X16MOjpJu@_A1H!YBO(=G%J2a2+utc`1|y zvpHhIADmODSKxU-BV-2+PBQ~@vR~>PJ<}e1qiole-yQRXo~jrdgK_?*Ib1eGc!0&? zzVP}@nJv*5F!}J7DyK&k$t{Zt4k`ksBn91wS8yVV`zKO`!FQ@iHnfr?Ct5?+cB(2e z^e!__w3gNOR33aJl?N7OxX8j$&=^{+_$S(^%;%-4eE62`CllZcSOMJ&Z`ez24%^EN zW*+_viC-j(9Jw{|)ZWmRe&K>cQ@OUUoL0(9`(AKo?rnQm zc1MOUirL$G*3OPw$7rjPvQMhK$8K(WBEoMo$b+!IGwCN@S5o@^2e8lA-A1(TZ^mWl3&YVJ0 zyh8$k$UTzty#h?aftB9WStD?-WV84?mZ`GXoJl~{*=vT~y-zL~O=1)3^60{cl=>QE z7ZEqFht%n|h6`!dgtEmi1}Uk4*wQ}~i7e?&ScD4Omnp=H1Y)u+3x8|j+<=EGzEWH$ z;QZ23v((Zn6VAtX%*nL?;0LTt($|B>6;}iaB1TxLZAs&EH%7c{n*MwNH9ge8dB$8=wvQxk@=uEFgvRgL!Ca`TkHE~W| zkK!4&R>j!fXns69RVOu1`6$Fp6=}dQG#>_dDPI_XqtzZ(Ck(?pWW*Ev-Ub?%Hy{Bd zPw+`jT%!T_? z$}+_aK+OxN!|B=1-?}N4E^SpVI3H3Qn?{AL6Q&4JkPcD8w1IF%Orp>rbm=G<5WKHg zgwcWq;qbx0blV%eRTYsm!D`QoCO|%$o2*%zbc%7Xez*6yJ{@#BDKuB`XK~!}6!#+0 zk#0$K#T8TcU7qd%IiQH(&1W!v9tJ1<6exMJCT5a=8WX>0a)hf|aUX-39?t%VlcGzg zQMB{r%Z!M_IE54Ql?nt@JN{fYcVc{sBjGS`U4@fh1^e@+unQU91DZri^+GQ=aN1GT zg2HSbY8IGpjz+TKk?|(^X)cMOW`h*lLZ_`&`Eq>?^S;PE#w)qGY2c=C@TL`!NlBGTn%~oJF#kXo<)_OQi+oiAc&#_fHMzIF^(jO z01${65aSIsCR;0vK@BNGfDS+^%U&uU%Af-T4-{pXI}~fkE36%CkCa`HbbOp+#}BE! zu+XS8L|ao;PHh$8MV*%GiStQz8Br(HB3_e!O(*Q=G zLP(f2fif*8rU<$M7&0jvg7F#cnd-BmZHi-KHMZZ-3fCZK%?J2m?Axa;B;&o}L-rx( zr^P^)2Cur$8a>;k(=^4lFDa^M{Epom#t8k#4%8}Y4YF+IcimK`mPpt*4vJ1Ds@1|JUsvFf#PcutAQjM^1OTenskmpe-oEJlhFQQcAD;iQK;H$j^02Nz7 zTRTdR6nn^wMiG*GcLBE*J@Esl_u27@D<>j~J$yq2D7ab3jahL|2%z`0Ve@>!e-`y& zPsf8XFYHquziq1}msymGJDW1ag+@k#XZJp**2I|#=XuQ=Pc?!}jL%f!rYfEkQ>9Ye zIq$jRE9`ltPSnyd?!{8?zn#5L$tp;0P%A@b-oV@&YpNNWi;maA{?$uFo#^oz$g3!m zm`uG_DLnUVhN8D51aZ?xHLH1`V|#&dqQL2P2f7}(!nMU}CW>;8%JPuUEmHV3+!Qa> zRQjWM>SxY^o^tOtv!6`h8V{TOH4X#f&7DLjo}?u>WzfOX_C3VT+1}zz(odxTuG8Yy z(l^tr&vv|=?>T;{LiiKIQBUP*W?47(HKngbrIlw`+*8Mcg(Jx*jFExeYu?#yiu?XQ z99lIxZ>wJ`hZgUElF!tu)*N(>mLMk8PCM$xL}XK|>b}o3skbWpOTJHw30GPHxtHpk z!W>euu)S&iUn}wsbG(4WRf|j?;%;J!`I!BAQmyURj|)4;XDNU-$EqE35db3ODez>FD|fZi33(94dA*-qD?gU6pS~w0x=n73 z8D`}1#V5DsEB=o1EBwBA=e52)ElN0=#3Ir&VFIqHdYfcft(`k2qpvF4Ib2{iA zI*aQuFNTyb*g6?((ueB>gM->)dK)N2icYzUR8|BR41{n_eiZe!eJbhlkHT!%YgU`e z9M`?T+q<|)ZDE)M)4uJRW=P0a^Hu>W&M9!x$Ip{a(oX?orOjMSCsB3c&0@==tPqPKS;pe_arPB!F#Pd{llJ9g&YNYUU@Ac?JM%D zlhVIYZ2|Xv1RQ;ti-w0oT0}%puPZQSauY zCitnPyoY6q4o*;U5F!}ggY!K^?XE{rTgBps#z!KKZ~Os<{Ws%`JxU6lq#~hVTxe=< zA&M$U*+*qb12Hb^P+hnvXX!18F(w+@wtK|X$5-H8mR=23F{|kA48NTGq<8#qotSrG zs$Xx2yl>5nuawqMS)wkpY7TyoD`CeIF;}uz_&Z{4^N0dT5?Z(pnUeVToI6#gUhUOa z`aEz03K5G8&z( z{Ov`i=*d4}ot;x7FI;xXuppjaKZV0B5n(<@22~aNYCs6lw$Izku<}pcM*V%&?SW#C z%0%$~h!@{o-ro73`V}p3!qVYOiR2@3eFAiM{zvKo%6Z1#xE!ay;x@7DI0k~fua(Hh z6Xsgg8X+wf=TLjeujjXa7Q!)y?^@W)+n9$?H4p2mxSRe&6&UoI47y1Bjs8`Ynp>MUPb0} zz;VH(%}O0&*LN>C$|_O6cW{4)X70*IV5sRsE4~kwHC$``39R>i058r9eU6mrc8sxp zuE{fy(r{bnzWM7POj-q^V=fhN{k;ESu(ab^qWTR)B!oIGG&%P^xwKzJI?8bfrfa_e z!>4S8rL-2}L`pyJEDR-7nOrms&&ms|k?w3#S78rOmSLOrsdokO8+NAx0{nRs-622R{U;ot4yQ*d65j(jpN^el294DK&ry@<1{L}I zyh9Cn6o_>T->tle1gSNc;C_M1W>lMq)S_b;_sg%;O+V_j1*&j{E==Ll3h3kZ&Y0=S zbI5YfaJ|W|*%b0-E}AjVkdyRaMS*l>`P5f40#PfhDTKVqzKBzV^Kb`KZ*s>GCkGO| zJNfh>qAIK)0oMU@P6hCMT#%MY$JhikDnE4u;cj6lPVBEpJijDWi2E|2P7isWnfCrj zI!WN~W4rb+Cnm`pOb$8O&no_Q_)%VELdhj1Kgwv6b#2qXsGNZjKt1^nO`#(N*%6A` z>HAsq#r|KW>)5e>aoW0p=o}5`XEXeW6nygTGh(Kw9y}U zvN1~Mao*>TMqp6L)c}l!T^@gYTYBntEK@GO{JTG?Ck|1?*p=I$ym$KkwLGyv+~C@h zvU~RMtX`4lnMv&HLIK;w^?0nJit{M1|1e>7X#&l}bKoN;ow*`3h|Z^M7|?E}3p_|Y zbJV7U|Mps60BChKOMzZtG)^S#2fR@FsJFnUN+AM2mjNu3qChh=7{Q;Lqm4XLU$o~b zLS~qt1f+6xjb4*uEpfC+vd{~X8AOeg^-poG2A@E=Q3Ay$d4(I)gg?<}!>6-8!?vo` zU`HOL(YNMf+>GWjc+LPSld5iUF9|SSmQBpd?&VyL=~!6B?oCHitU6QAZa@c463Gw& zL=1jBV<+xJVe95D*FWyA8JAOoj+>pxAr#1sU+br>k~xMrfcJUpLK zZwTmoNks9i)bzbYN9&Vbz~QpaX`UZSR^H-91LoEovZ~wm?$S-$UU0xN*m6W0sbPw1 z26jFDsaEA%{2sd{+Wsg!%C%F~S57s9elv)d)6{y3!lS{tAhd93I4^It*4a}PI@qDr zsAu|DCIujto&YM?`ct(B*@lT6Ypz1@8Sh8I7tYXTY$L^EnjICt?Jwm@L>CT((r#_G zJ>+K`B^@PrRcYV2=PulOlH^)EUV3kwIY&Fk(e$Ic4Qds3fg-V;8oIEHH9oo(h&j z8GnvmR(kqq3?!uRVACCKPfy8QH_FZ4-EPd%q7=yfe2`50pb7AB(Ei+na~1K*iOS^O zpzz96&h~oGF@3We+R+i$Y~5}&i`DaBnnbJudOrU5FPe{i>jf9q$UbhC zVD729Fl|7M-QPEEAA_mT_6p?sDZX3%J7O|6Qh3qw8C~9O8$x=&lJ2g99&a|VkGtor z*a^szp^re~J5nptEM+B$^&Aj7&q1FLfDp1b2gLS8m|iz9V&WBMV*kbj*{Za#li))# zTQ-60CQzcHCYre4XS5zsKzy>~I`bm z7-!03q?+_)_KVmlB}(zbRPjT@7a@-c8mQA1$g}sn8N1%Ktjhy((BkZLKqEXBouudw zvy%LqQxH)GmVXO5kzSpLKNm!+xa~QS&G>=&qYl0Ns-eeP2=2+Pb(HD=sqRcOYci3o-kLz-cK`4 zBhY43v>m->Y_nztsU*_A2mMffN2dr2B@28hh3+?c37}esgS!%Qz~er>`E#6dvzO2` zIo6kS>ldEuIos%$5`r)rpH z;14VgvUH8j3-D-EfApv-U?qJtm z6O6BYqa?L0y#XKkH7b+n7RDfjcKq*%?EQOP;Lw2XW0w!Ik?)6LUuh|(gk&8-eV0@n zV9dDFxXY~IfzIv`^K^M$k~C^{JZ_W+)h-4A-@knA_fD++10BQ7w82sx24 zAx+=MFTt^NZs;x6OtrL?aG#kz!#c#TlF_UuR1y_x2HeMrmv|2U= z%gy#5J*L%4iIqj+(uP)!(l(NtxnpJ7+1P&F^uD_qOCk0J?o^aWboyIC1eZn?nJ57U z<9A?E@XiW;=z=mGd`lBN=1A;^tma&(psGMIrxQQU;?4c*ewFX_qq??4Y$a2?O(1S5 zqvx>v-wpS)8{gS}9Nkz!^F;?AEGf`ul3#fxkv?qyX)?*e!4!bQ7YByhG{T-dXE<#b zBqer^nZs*E{aL~f+!z8VC#gRrLGoYXSP;EJ4Wn2Z^C!awoW#SHu80{&DPObAJA8&p zWpdiL$6@CspGQ#@*7G>!E)y|edVkI&+X&L+=)7|RBen_o2tc0w0t?5$k3_w8lC=8D zlBn3%Z&W-*UAeCvap~rwrfA|N-Cv)4b$HR%Lfi&-zJXOTpfLPdN5lNpSH7i54+bvB zQd;Ms1Hy5%*tW9CKs_(XNCqHWBZk}+)G+erLO9Pt4pV#quIMZQa(3w%N)9&DjBWs< zNs>V8xAt*O*1vX->sBK>IjqJJ*=lg<%SNfjU*$gTvSpDUA6zWmK)YF4-@+#nf*?v9 z%Ai@fy8}9MI0xndBOJ`}V|*`Yf^-9oQ|drN*gt?2OnEU$2>-6Gg9KtC{%pMYBZK`| zq5LSE`G^{6!7Vs&JjWfq01%wd|4ll1pL%gCv*56Sh8u*AN#zT+CxJYyKlw+kLb6>N7u|lrGch52iasCQ<-E0Z9vo)&Kyc8`Urt2gWQ`jx7bo z8y${Jf!_uGoIM7*EDlpr<9J=2q=82y!3p^KllU(Q3GB5i-(XkB`4Los3C+J_9T8(Y zgYI}SFq8Hv5CA$q=$Q(VHdQe#VLBS)t|N6S z9>5C?Jx!4V9gY67ny!(Eh9oC|AHvY?ME~z6b2ceU9Z9spk0$Q-EY^hdbm?_D2VEaL z`=3X$ljRE_Lg`#_)%H;{ zAyL(CuFq+vq}R`}0b~~#)Q?$W#kssTxk|umUQXi$UXf&_2nM-vVkGQn($*KD@S z^e4ny7VdQI35_Kpva)!>s1q@39&y*}g?rLI$~LCKzGr14Pxn{O zj1!^sI+wr;2k{fKN%0%K-aPgAo7Myq7n!P%e^C14Sp&^b%g2yJQqy(HeBH{M3Xe6p zO|B}*T%)#|MX4Ub$sA*va~*lC=N;&{+F};O`Kr}qPbEyIjy4v}4xbeaj&v;s^X>HVx!FVnOY&y&C@NZ!Qa(3jWxW+c##WPL+6|`W^Q(4F z`(pnb4~E3-yVA^8S#16|+0eDx?4{I!Z_6@~6Wl#oFK@M)C?x3D1QyzizqyiWK!LZn zPH9KhtY?ms=nfP*4m(YF;#d6dJnI!MS$M?eF379**OfCUoCuAbgu>iZ^DLfI^2&&h zC=`@825kfdOMh>&r3n*_?{>w?)0eH2^bGT4%C#5ku+Yb~JPLN-;Wg|zFN@pYHtaJC z=aZDk_c+mUD-QFSH*$9T?$*TOKAPsWs!3N0@Lm=q=n31`*uXP6c|uf z6X5tYAOq}PHNFrOOhErDaOb-b`!ByEim+uvACdmBHjV(aDzc$!rWZz>k79f(zj}$n zarFXb2lfd}`)6ECT)FzKGBzUl!tH#+qvBnHdle;(dk<^P#EE~6*X}#enb*NL{6;DL zE5r3Y3!~P<<;24o-#gO#IqHPh{4RUp;sJT)!V*uCfO%X+P_!S9CJA}UPvZ_i2=5^n z)Og1LJkS6XC*sBkji7*&fO-pxYXRkL=y;#rP=nM0Gu|a~oSI`^NF?f0 zv)^yV^WA6u+=2>8z91P;ws2J8EP8dSSgdPfna43TnxX`}Oxu1$V z{0=|ql*pp9u<%#EO~2snTG4d~c3pV!`k+7!F4g-3#uYTGu>IiB-xiB0hR&j{-!<{Y z(P;zt@+N6sEksr!`to0FbE8pmFcsX2IHMnR5$Fl&E4YEW0jMPc=%OL!H{zN=auEV}J`DIZl|%u+jlRxPV<$$n2Ho>RkPRf#oJ zWf}R>nJU^cLjR$lzHp;n6|Z4dplaI_mwuXvRMFkeD}*nqETz5z3)X@^+45S-O~AZq z{(}w)g_nO+t>%!SE;k;nGx3N6s}^w!3i?pfKUB?y(RxkW@k>f2T#2lcnQ;qB6<4KS zI@s!7(nPY*qz-Cc^~6_EA|617-B(`_NVJ$!zI3#DiTKcnK&Pfx1kUYKy+O0LzV9U2 zc}X$+miiAq!wxVHK(JKTpAO!T^z#)et$Mx_!y!?h@x;50m)!Ri82?E$|Fdm1OvWIM zS1(1dbz$R3(f`$|MN#yn`C#|t24}=RQ<2|*;qbub?}6t6gB>Kzy$(+Mv~vWUGzPzi zgRC20Qw|^PAQOb(XatW-ssWHkuSn!&VLB59rVchnb;1T_oDmL zqQ=-|E;DP%;4GAL2aVfQ$iKs3sA=g(;D~VHW}CVTLC}q0&GOJ;Zq%mvVWucr{h)r|?Za^v#RSTR%*{*sgnL&I$g(M9=IQ8nZOpx3qV?L?hNe6eE3XQr--(MeQzx z4o{cvPRmBO(lB%}d{kvFH+{E&zXWPGeJI-)9!0ZST_0I>v{{KQOy}`jy-KIA~TWQpXK`PLQL(0C@xBVvNH*a^c%U5SVu1=0_J8tj3mHJ?s z|B>$siAJ;V@eFV7xbLFeJHKp2f?;pAd+#s9hj+31vNYTggUx;5t)C8C2PqEF$4_(> z8w_S0e?C~fjXflz-S0Ku7tq76mm+?wBLC@$i#+k78uMe0Tlpos_ndak)UMhx4ryDl zUW3G6awRVN(`#rm9n2Wi^oOu8_9U`mmtF4EbolVK{zt0e)7QLxsuMyn-u%)o?UiGp z%OgV)rRVmv#jDM4x+-Q-y>|Wr|G0!1E5+kfuAZ_r1ayOgOmmMHALrZGb zle?ygyOw=@efx3VRqDnu;-;nR##9S86MQj?JPIdk%m8cG95gHcyB(Lk+xc`5YyH!g zDI>6wW%OTf-~NZ|eW1-pva`_?=4R*L;4imd@1&8>5(pC>1B>=G?uT-;D4F0*Xg@mrw4Decl2nc-!e*v zj;Nre4<9ziwYBdM*&F^k+%Md=4ntKutQ;=4sCE38341KuQ(XF(`^JbsU=%ZwoqM-E}J;6Yo3wb_I9q@pap}noK&qU zbu+XJ9!aS7Sxdgb2Y0iGv`L~CGD9;+Sr*7WXq;?9T=$_QvC}JWdVj4jdNJ& zRu>|itodw(>hF(htP=U=spD+FXOW)nK_$ISeO%BgHD}%d z&P=lM_b+&I^t_l6#X)_Z7NZYZ4Z0PdJh_`@7}I#;r^6DP-J46qUwYY~Zm4;(Ncj$Q zP@_tY%zuR$Guizx^a_wc_)r5B7G-a?@pxI53TZh)RYmYkh-p4l{Jbzn-1;=02 zbJW(o6&s;g5Rxx5m@;yU30#u;KH_AV>#IXs9ne*>Pc0tQQctmZGpYWDi{fHs+-bgy zV%@?rR&3E-=!|1YCZ14y+0GiP$Bn_fN7XCrb0B6fTZc}Lrk*_EFBKyUo_2pL?*WOu z$cDF}mCgv=h=XrLM5f!t<$Q+Zjy??nuk~6Yb?k#*VD^%P!xDQ<%TeaH&rf4v)Dca* zw3$)o_N@Q%4vU2RNYrQpLk5+dXVexcdU4EtmGB|{T%Gdcpd@s~)#r!K-w1R#T}=s5 zJQ#Pr&9AZ@-mwek{%osncwAa(9TPo)q5pWT8yYKhecmC^e66J@KW3T!@~&>DP+|)c zjtG#?{`H!be(WAIK=@s>R)bbQ$FDAbD1m4udg9^G+mMC8owKF6`^_rl8w^_XBPQ)A zs_gHPbr5xCW}`zKg=-2mGL#?|;Qs}@6#ggR!ScFcHL7@YY5x#1BT*gT#VNyRCI`xtAfHUc!kv;O2S7vuGJvS3vrX=UOdybr zd=CWVj}gl9o|?!$%dHiuw5)UES4+)h290gZlo*vbrRQII#e3o>>~5%3!dEItNPtnsEe1Vc-6=!tRe3%CpM}Il*`f9&m()zYhZQ za^i4e3u6XeI5X`PK^5R#I#A#NlOg~h2NVKnw@!k~?-9o3=PSutq0O_!ji$VcMA0^^ zgrF9Wg2okY=@IVQ{_OSFwakfGnI`5hj^TGU!Ce=iu%wb8T*Z+lM4H3c>>%L)glg%4D@*)e1>iKpQ3XWg>CI%Kij zOx5~QwaUSTRf#u#g@`|O?n7-MsLB z6L$QMr&lg1s7*+s0$vu8Zh$yn+ZQdI5f>a;h-XhN7U`wNZ{0Pb~;7D*m8pC5BHM_KJU`L zwf8;4kxXE`48W1{P{d>7?@G~6KO}F7nC9gdqCi(nBz@5!(|~o*|8MrqU4coy)TclL znaQF1GrUX+rPf>hdMnJo zom&jkZnW2rOT9*47MHng5(UlCrK1st6Tn)~e^<+{2u(pT(dmDks*#S%9DAq_JWcDb zOK{(>*(y5`{r^nZu{iiD3&%q+>WK*pAI>(sjCdRU>88DZ^n1qln6J@$kC*+gQG@{+ zyH-vw^83bFr4I1yB_}aGTT2ggye+kNmszu*1nA5d|;qv-B(d^7FmH<><@na*V%geVN|qDEzn|wbHpm z8(0cxE7c#{0{ds5$9ad(MuxT;Gx+<4e*KgFkE@m^_CmL|RhFIvZsB1zX}S3(De@|; zbjtS9x5MgVcVB3GysQcFv*EoxELH8iBS!0Q=WE05O~dxCm+6KhC-eeCBQ4}(_0gAm z0 z$CU0edi}5uYrFM9JyOfcN4=-B|2n@(w+`Kv*~gE6c+NVu7Hki?aF74RVIy~K`u1;7 zlKtZ{)BR$t{@z=~(fr*BkiN+d?tB1m<;7ihG`@xdL$!~lT#X#)8>*hPLp2%Q?jX3 zR0m)lb37p)(M8G8B?BozTd~3#3ZqoqSRf2G!6d_E%7#W%s&!Fn%W10lR%!=lT4OT2 z+apbnI;~$Lkqv|~9-4&UfKyAtzf+_ao~Bf4z_LRUlDpCuJYav`rF)ZPERDl1#nLAt zGCYB)-__yEq8UyOFd>F`(Ey}pq%Fvd`{2iESZ}=it^u>MP zi;C<_uC>gKfy|lv7l1*wya5HW6Ru+C>wH)XS>NL9LkC`DA7Nbf=rq(gSD=bq+TVzjQ-^bR$hdIx)!f{&bp4VVcEIdTJ5if(AWiAXC)LU=_%C7?a@~lc89d z;Ra3f*vycIW_p{aKGDpSbj=i!2DxChtu`}*1rlYVna(wwPF)fspJ#|)IvbCMjuE2p9|+afuqd^4wdD5w7P z78DO%Hb5+OK>;uzY5?2BAiBmtAR5?`0b*wihA}`2WB&uwfyTizUWlayNTy3-parXX!4D{sJSMD}Z%Y*zk9tfE^?Xy#(UGlSeQxHkqwbWSpf#E&iY02Zu( zgstL9h(UpF7?9HfYz=Dx>V|#n$|Fq%9bhOGZJ}p)_e8tmJ5|MZw~8@>B`S|fG^$E; z1d&-dcz8WX14Ti)uO1?)VJ5|7ky9)?Q>?&TqWqu)@FG?-N?QEXpTAXq8J>gX(Fk{B z@|`JtMp+i1h0FpS^X}S>jN4FDuTTyZt-}8l9$yEs$BjMAxn&>G@t^$=K(0nUua|tK$Q_v z-8NkPfwD%AuLc}K)=votU=WXOkzG7G07fTMyq2_~y7R2MTc)Oeptj9dzGFpuNk#{< z#<)%iY(A>pks&@)xR_U!S3M&4pY}dV=gV2mxD3-tRo!-MtG}q!NT>q?3|Ellp zP-&^b=O%gWcchCX^JogdtE!-o8k7to*n$CrCXjcNG)tr5Y?BcTz`y|K+~)EJ$oB^7 zK5k8SW*eg7S_TY(qI$$>J;Lx4u!@5TAW5?Eh;E$mUp(TsS0imbb;LrUAtkVg^aB72 z0@^IGp(WwGg_Nc>)uJ^sw>3AgF$atI4N$nEsD7h#B5oL~JY=fgZovt)rn$9d2_Z8I zTl3fvbm3vl+N5&z;15`8aaGC|)a%#U zA4m;9CKi3X*!~Czcb#Fn!0}y_tVX$b#NS!cbDYY!Y-g%r_vQIVQkpK1B~d@?f_8KP zUH5~?%|cbpsGs)4CHGt(>0#>V22d1>_2uPfouEaMCE1Uwac%q^9|hyPMOkZ=E&FJN zkjh=~Tr`r#y-hd%qYc%7tv9?*5SeRRckc%g1-1f&Eola=>}+(<93Q5X~U*pL$I!BjX4Cbq0X?Pw1Ub zKORzg)ga!PPyt=do-o3DKVhVwEK_XFQ2g8wfFEk2A3jG9E4_nf3nHK74nGqXltjaR zY(kf-n9NE|`UaSCu+;lq@D4m^q+3biI}_RqwrhZx^8ycyzuL)Wg66@ovOqy0{2z)6 z@5(gyqKXPdIfq7U+QJNZHFpi5pdu(SK}@cm_yoNU(fP6%n|H;|uLwTU+N2MluoPf#oRjiy74)n>GPkGTw1gZ(9)C=yi`VGNJ;F zCq2AHM(~14+qQw+O7;tJB>4?IR%1-mZ-jJhM5(_`w8M)HkW%@!%tC@*7}(=NkWW3l zq@F3=k6@myTAxcom53s9#KTG+vARvF4g5D^*Q+s~r0Q-ClNUgV1zNHJ#1kx8CmP;) zi|NsqA7Cxg9u!0Y2mXnr{%Q={z!qb>;KYh`$QW1#O|eo4BP{~uc!4Df!5=pR@0>2uwR8>!$6J+dGZCpeHymp{kM>vxfr%Ip{H2>1 zGRssh18m{kd2A8==}dcp%4!0dC|jbdmRpE^lj#LNF@V29zd_?++gQZ97wn5AQi2$i ztob@)aRDg`zb1;L^IT*UMKXU~WQQ+RNW=CP;O%4g1|r?Fyq9R?7wLl*nLaGCT`hw4 z-MXdR<;hfJJ(m!>%R=xKQTBP-xI#)TN@|(cG%`$b1xpI^OFcTs@*EF+RX8`iXpfXK zIG>45s)4bL^)4Qf;K=%i$7o=Yx)cZ7DWv{f%fu1*{w~V`xQcjKcvTV4M7isBj>@qc z*{~V{?RTxm**UrJA|GY2k}tq6Jy^x)jh=mH`rjeO1jK`{Oq<(G8LSN$I9Pzq_u>7sTBZ|QYLFe}mt7{gj-C)t zjT(7m-5Vy#ufT^w>bRio--*vf0J3Gh-Q|MCMO)a1mNiN~q~|VEy%${J4^zX9&+q&! z@(tl1t)ZK?tTi1&x!zS_)*EdvHcUr=_IhezU>C-bjYh&-#!B{n`Reoi&K3viaqyKL zroXB-M>p20IuWF5o_5AlB{!T%(> zfKD&Cqrtqb^?{pMNMd1B9;bh}^9b-Ns?3vBZIsCeRWOg-yt}(%^@gdf*-h~L%a$#o z2icg(d7^IuYtD%B=sHRkJ5AL;O@DlvnRJ?6cbYqTn!k7Y3UO8>c2=x^R{Hp?Jn5{m z?yP$Btak6L4sqTfcHX3a{!Z*gwC8zi-FfqGsD~_4tm}2V*hMeltW*EuQ_@9>4Ul7- zJBx&X#QTmgRGuGeLKdixG4LTZq$k1nTV+u*FJ!;~F||NEr&0d}s3bU`^R|fJxS=5g zVSh9|cY)fg5R_<3K)4rHo}eie(2&niBrynJ`qNMpcR(T_Z0R3j{QkO_C~$I20VD*^ zFOW4vCS);7EZU3kq`?i~m|eP?j?)vX+F9Zczm}MPThq;x_S;>V{0!}@(KQi zOJzo_YP<_W+v!jHMeb*S{6(?)^nBZ=R=>TqU$e)L7rG-5eAXAvIl=D!!s|4krnQJX z@*uce+u?)LNDuK8^QkfkKphXXoTx`jC$SEEuXFxAe;IhPzdBmJcP+eANwo9k#bkEP zw5R3FO7)Jxd6X>BK}#%N02&l;&$!aOlqiMX;+3c*=BU%2vQBr$Yts#ra2UQouH*%4 z0A2B+aIL``N-LaU5m5e{NJaANl#h!vHd^~AxY)Z@l)2(0|7!508v6|W26wHnyqF?! zO4#UWh|1EsYOpQBbaa>J=~(BWGM`-;YP5se&pp*s-nM>Xa{%mo^klZ*9_ZaYn0!*C z`*r$29|NNIHBf@(k6x4X| zh%r+DAp8W-BWidDBvAz7=jw`Zb$LbnzPz}+yd+$l63!1VE-uc`&k1M8XJ==ZCnu+; zrza;TS4T&eM@NK{o#W%A+)w)WG;rt_h!^X{0dA=j&J zlZ!Tw%Xb=t=9^ayV&6tbzkK;J`{~pFt%KLm(b3x4`u_dfs)Y1EI9?I(ucG3#^g(Y`7!ky)t*x!9s`@X8S6p0NSXlU9`z|LZ=Qtzd zUlNY!<6T5X65^!)gh%9LWTdC3r=+ALCMHHlM@RnuA$W%Yf#*++&OAH_&H{g&T_TAh z-isH3fq_@|)vt8qwjNk)=^I`tOKd2s5@ZC|Wn}&R{fSndudlDSxA*^8c^>ZWuCA_5 zPEP*?@vN+@h#;PsnVG4nsgaS<|A2V9y1H6gS{fP}L=aC^RaIG8`M(;TjEv0x7gO6!HGIi6&dd!otGH$jHFJKu=FkOG|t0+O_|e8XgG= z2~opKB(8)1vxfI#f3H7O8V2UVVH#fd$1zGgnrlf`W`(mV$FjQ8kn}{+&{tUw-McZI zfp%zqA<$IzB}DS^R(ST4a{WxC-^~~MO%>xAI-|KK~EE8l2WNZIN z!}CAb`o$8igX_eCV9ne1*zN+41TH;GU-9MqM2_F_!qdE~>B>TG^F#Po|IzT`*mc|9 zZhosUsk) z+Jl?_(tp(Pjl8);9q&#U%@9VYKD_8gQjb@y$3A41q}^Wr{7V1hhs*Pm1NDcDJ$Ji* z!%#pt!udlv35KfS6NkM*E!Z>3X*UyYGn^$!DG7h-m(@ ziltcL=IF5~PC-Z^8AfMpDFhmOhXi?zF5K>!0%;{@oTBypl4Rw9zM{DJ?!glMWSxVd zRAW=u)pRr7m6CYsA{B=u;iaslOnKhQrR2$?*6f^|hUv0w5s~atJ&UhH*Qj@2+WwD* z=iqmCn>*cu&mh+;s7?tm1e@=E~Puw+@|kL#!Vl1-~5@ZI%~CR=Jj~Qd5?N zx?OOSD%vxYLT{5!6DHzx9eD+bm#W%-@8rOErrs^+>_GnsQQ*UnJ3k z)q5W8;S z(P24eK>IgiBcrPT6loIc;#gB0I4bQxPncR}OiSi~rwOc-QA3LmsqUi0^o05wCCT=> z7eZYWXy2j%di|#j&rK|z-tsqhlM~lrlCWre^-`ypvYETQ_Gr+-jlm0`=o2}f^Zn`Z zY>tG7u1CD-En!TFMVLD@3GLW7o``NE#=i>>=aS5u05|7D$gOsBVRri-GkZa0PeMHl-Z zU){yuk=scZB$U)tn5ybGHN7ECBTXTg?h#Tf)tL(47`mF#H(nTYsP%cJyJz&&KD#0;cF> z0OQ#W1Ns&@{z8iG{w;z5(PM#oclt2a4e|iWmT`ZopX(m7+FXFjaAks{{v?x^{moF6 zM-eHM;I3LayAQ^qQZnhw8mPc1e2hU}Dk<$jbG!L|tk36MvdUYXUERx}Tz96%oo+#1 zp4d{j%qhYE+yFg*iV$+=1i)CZu5TFI9me7ouR%0QYB(u)(k^P}8P3?Y7a=Xob=A{c zBj6MR+!$7(BWifprT_Btfs)YnoJh(xs(5><`-rP#aC+Wj)F7@{Wx@~&jPzU&ylcWi z?kbAWio{Jdlid=(rAhGiNXV_)`j6;%~ZP$tCNs=`q$f z#50ow?CYM-Y0I9Ne(JW~9#hCJ>TkH$+*ZtH8e%b7@Q~5A3strfx$J9e&U@0zW{+ItW88j;8$@YoEy`XpxFG!(#r-8kO1t%L?gqszu9K~qr8|?HZe)#^FK$9cE`#Zs z)6SwZjhX%KPPf|4zdrrZlmmC9A3|x|zPU(i^7HS++2rHrqzhEiquK3G2W}18q7z)G z8h&p4s84(cav$2MeH;v%TcCW_(kJr98}PSW;k_>%O18)$gB<+$%)mp{A+VZ4y`{O^ zAtJ~TL@uUxr|zbRCobEbIbP%a0BwsWHdzLshqMl=>-|m1y}LqBkRK!iQF!gRCI!xe zUY!6K`7p1r8322vUz4C8v+Ora&Pkn;zZ zTV|teKWeQ*HoV7E8Ttyr`rCC2K{EX!=?UAlU3f>7U< zG0UcNlM@*Rf z9RG2f&D2KuZ3Oq39W@gFYdxd$ow>SHmj>$U=zfY!hkVfA`E%7}Rg zqg8Q3dR6yVjxREum0@Fs9Q5}nI7yH2KC<4lcL+2A$jn z?pGpTWIPQQaf#$!hI})ibTfZyNyvO@745jNPck)zuo-(q>>{aC zL~|*7j-yE<8Dp^%k+70zlZQ^es-b*lp%@5zn+Y`yHs)D$)I&3G?kC<%e6ejVbkY0| z$`~!;vtkqP#5JeJfLdaIhFDEGhbJ?-XlgttVHEU5Q&-f-{n()GY(Y{uaodH)k~ebq zPQ_QN#mE0((_QeA0$f+j5*MWcA1V8P!+?I?N%D-qjx9YPRYLt@j3@6wmHiB^IkEQR z_Z`98HEu*HIbp?Ik}fC2o7Iz$L)WG^p1&any2V*Xl9RbZSci*}*`L#VC1HEVi-QQn z{M-iu?mJKjBpQ|Dv<7h(ugRTylW5FSNyU=^!cBD_amKsTsR85HgBMekhEgNMQ>dF0 zw+2(x79DFpC6b&*HQ%|37^C`zBA0rePVTLlI!3*ZL=58f02E2%0{m}1Oc?)ATAYTX zHG^@H2GyP6HjPqiwZ9>q_+#BevodXcJ!K4%O1w@?5}9uHT+;`jxH|@VjYSZz6Eu3k zJuu)wFDe(;_?H!#56m)uK4k-@%=@F$gj!<^rElItQ-8q&q0(97{>a@z2qzX1ib5*j z5zY(olN37onwc4zQ9s9_KxycRf3D3yjH@!2tACEva{~wla*QO~;X|&CX@M63T@o?^ z8pMpIV6F#dTJz_o^XE_V7nll`2(9@)v-6jq7i?q~ESMK;O&9D66zrT9{FQzML%uqE z{%XVZ)roWgH70zw^3^$0;XJhPk2L5-rDxEP*nnf+r|cXe-t-@94xj)GAjcTwP!}b| zzGPt$lSCB6H_HnIB4e0e=5K}N?#DJjWOIir z|7e&&hsC1O#c+=jGT&0VqGYPOh|^73Yh7SRFRGNv%GS!RXmeV704lB)GCb1a_HsWc$|oVkJmR+H2X2)IVQ ziVfR16Bx?j0vPH^XDbwvQx5~OS+=X8=d{(%)JzNYYg);g8>B4@@P7-`PG~_!7C|;A z97A;^$Rf9ia9GcN-tb$H>8E<+o!n^AEYej2m@}3rj(KI?Y~b&4_=eJy&~6fAF(I>P z{88E@t6kxt2s(a8E^pCj*F-shDu?id>BHV_Jz!#Xdnc#%vEE+aRvy% zw6`zM1zcK;L$|Tv7WG0EEhg2?|8f|KweUo@w)}mj90TM@eKk>P99(F0o)v3Ti!Kss z%MbLG(!Lep*21&d{5Zv{eC+<@zork2tvceZWOnekXk;o5-U3rC@b~PL4Jvl)__W>W zM~G|_A16uY$NC6;Fs{J0BAZF~Dc^4MX;pKzv~;fg>?{jxBX+pdPZok#0um>{rjIV zRXl$ZBHsUqr7KIdjhHa=JD1U9!Hb`&>ns;XW6@(^94JuJL(}n+cBJP$d9S!|ALSx+ zSoS4jUN=TKkAf%lGbUAz>XFckUP$goGs_Nj8j^s_IJTWO#TkYSJYq71v;hhK=LK&V z;~=#I_X3DL6qPy}`4~qiJQF5{^PJ8+VqJGI?!~*kj%Ia3^3D>nVb;<1 z%wAbdAP}aUlePByB@ck=jv}WkB|AzqZu~^gZX= zo^$)t@o^!}wO6MDLbMgYWFHlQOkS>i;I^w|nXsSr@N!6E=d}@^6jq}Du z7(2R!I;>tcaprrd?GOI!au%Q-NuOiE;t^-KX+js`%=Q|q7gev9U~D}cIsqJDAOMnb zyey$fa~xzhZrnB*Su5bHH5J7BJznQKzGn9C1uYrYs-)11U5AYoMK&Np<|aaR5K7fw zNJ6Fv-NK4MQHTftcvC;aaEfpNfW^CCR|z9#Sn8Wek7i#+&YC2QR>sYx@vl9Hb&Vb$iUco%G=NePN+N~l$;{|1+$WjrLD!uF)$aHPnB;Ym9m&GkXT!*yxcin7jXh$k%x0Bv7YX>05Yw4T0vpb0kMGQ)1H zm2N1`Po=+EkNwijkG0A-SnXw7H&kgZDA=%lQxWa4S-QKC^kz+*1l$=;Rs~`jXIbjMV;j)PvU#C|+6>bxd} z|117#|3hMx?mLw)n9ax}ooKOB#^8U!gk>Qbzz%DroOB%japL0}9h`AqwvA@)-f8*h z-&YE&A|a&4kN@R;JVJfsR1a<49s+xQ{l*-4wr9>iPv-={x=@#MeB#l)J*Mz6F)uLdRO zR}qfuk83tZ5A=gCG=h)-4GE$tC<$Oy$ud|}iljz}W;JyYH9UF|-f;f?rJm~qYj-lH zdn<$C>{riG+4okpGGLl2x!~eeot#@9^L^Py>v{#0y03Sn8GK=FJ|zK18^^t(h*e`8CtYBK}6H z!{fZ*GH?vb7FwJFmWs==o9dKZmx|1*AC)u)aoG&ynLnBMWWT+YP-9l(Qdy!M78ySU ze&u%A$f}kv^OT@5kZbX@`Ogp1x2~!_1Ted$|4^#4f?Ha`-P4EP^mBVnchML|{mV2O zY~rajcBWT(>1h7nx3?OLUtXz;F-OUZAA__z!Xs7*rk@>cQ=G@GxsLX+Ij6niw`LT`=u zlbR1xv~h&IEHE>K>fu|%LCR8>h~SAkv>6F=;bI0|l5BBbbMMwxiiK3kuD(_HE$D3^ z!s+Mxn#4F;EzZ=r)TDFCY-W*z^Q&Vy+hfylEGNZX6hm~d)0i!sn!&c&-1$|6)C1S@ z(&lN$%vvc6kN4?E4?I7TXFhn`d*l5a`M|B)RvzQ&KOpion^ADTp@+|`1B+^pXPJy^ zQ@%gA?&Fwq@9IX&Lf*y03am|{qD%7aNHh1|*$&}+Hm$Pb-fMbp(Omv3b2I4iturp; zvdv=8&SQ3*XNtWdMO38J$vU-S%#!chK6-`kb^Yz6>AdY^$Ynuy4eW)tQSpwnS_#a_ zk=f{kx6>Dp=Rjrn`g=hVf)nrD{hRIh%IXP?$H&fn*;{={g&`6@Umh>a?ywGwLW2Z& zzh&M&dt$y|sQiV27r;ajb8Zw9z2j*nxM$4I*k8;gPzIO&O`1Sc$(=e{w(pnT-S-dG z&K{sy+Y>u^68BOiT-IT(A?nV9?y^YRSovjc4$?oxUF7gOBf2ds1+DKNxMRqIB>u8o z!EZ7VOw826INZ}N%vxxUw<6@%=1)Z%*97xpyg+{!%c zJo=MU`u1H}sm4RPab#qRA=lDWW$clO_n=&9!)86)DTbUhgP$*;P!r)3`MDENh2Gi7DmyNJi0 zHv;k*Ew}6rJDz$; zy&$KuyiA#LDH{QUMU#5>$_)wuu$I9R=Y)T0pAF45zmOo)x8ejcZOnG7-m@8%?9V$c zvNTHA;dg74uwNC@Y%;1Zf{=OWw=O!fp@wlSjfGTlMKTf*d5tD~^duMoI#=%g6Ggh< zGnG=EbQy*mPorX`Ujlkhwmxm*6%~k7jkKlj@0#64iMbHhiX%VxvGE$xWRuneJxXI%ke!~cL|LzFKoZ? z)|z$1c|`NJjL)|n;ky*UJ~7IHrc4$;hT1)Jz?M5UBQMQA8j_JV++6@7Tu73_lM{6 zyCvcy50wL@2l5%>FmHUQYqQMT09}cOsW~J~pE6AfafQ8!-#mTPHX3vdpABQngubdB zYM1&KFOm{(($)6$u8LqSjr;a_5c8D&(<2Kt)iniBKn0oJAb3s@>cAoajj_izu6}mc zQ(&2~mAY*)7cpQ{Zt>H=NkeE74U&X}u?cNF6^D&!cstAdkZ8U2gi!6V62kXz<_EuG zit4o1_?i;iv4*;6VaA@lb!E>buV|}tdvd~)j^?%VJA>bA2r}yvdLC*k;cq z+BF6w=z{&=_dE-czPH1l%%?*}YB(m5WW%a&e41|l$f9x?kjz3KOg_51vO#+`2HRbK z-=eLMa2V!#pc~3=zjWs{OhoGj&{l=or01D|YlAB&(VO=55y~t68WG~UIQDc%Kr-Ckp z{O}t7BW}gFz4CO+(s##_o>nW+St?#QwDcFpP$Q$H_`w8iLx^I_e~dHZ5pgEM1-M)vd$1nxqi>w<-1BOYUwwINYjs3@Pp2)a8E2U}%8BitX-7o;Vnw8BSB zAw7Y0+e+T~u@Uu+R(ZI(^rj@G5*`f2_dU1^p+{2~Vj!H1Q7@+`ys{*KEb>5&NXaaW z{T+yR3t2ceEV!^B9LJ2@d*%1IIWMLg!$cf0B6&}2m9TB_{LI^{J1y9lVNUHm~H(h$GBWK>b`X@Y>EDN9; zFp?b#bc}_x#0L4(eCSfCi`LAh(l~kq#hg&Q92*K=pm=G3gx`s@^BM><2=~KD11{L- zC^BFy`~@Z&dJ@H5q8i@PUt!qv^lgO^*HDUN-_5rw+8rtyBPtE7pPM#FC3|?Yc(ilw z%C6j0&R76AaoU`=gI4>1BY&i=B1Fr80-*&w=O+Wa!pfzixeGOb1!V;?75*Kq56Pjf zE@04{dN^P041FH?V6zh=hQ0pF=fgWXxy?Mi zajIB-%dku73}R!%0ZZ|WF;W5pxjq%)ZxHnW*B_SEMcIKFxX@s4yt5q6vtq2dx}x-A zB!&tFamIbxxcKCIZ(uG?Aj={$C~cJe_2`SY`k|jka`2!%*~-~sJ*bEFdBEqxXeCj_ zHdn7uP-!t)|HzSr-bDu#IhOR+F}f~qXp72VBThi*@0c*@IE|G-743NLg3i`~{+P??2Q`1wvPM`=rJ0Kmp|kNu35rJIIL z5dy^#k+~=gm8&rJ_HDL;c8wPk2o-#sOGPqy@xzwMbpsU6sHAn5l>t| zH!@VK z{;4~pCmNl!QsKUXA9l*n8jbJ?QlWAdMg zZyDpqv!f!WqSL1cF{M+n{Y=U()cW;IajR2_|E3ZbnS`uvaEs*AWJS92ON8EFJ0)T5 zmWJ5Uo7$U1`$=Ya_h-B$zy7k{+->t`zEy6)zv)Ng=1*J!r-zZE3mHZI=A~8-3V&q; z=bM&l#Vy`5?^I;_ZpRi5`Hr~*;Xr@4&;RZiZu)aJMlI{Ud^A9BZ2GTCGnqPx%7YHs z+f-G{vL3>|si|&`rjSB~IiQV=Re#ji7=W!zQVL1TIzv>cEbB{TGfs@YU@g?Ldjv~n z+Y)a5>A;8+skwy+2Fy2Olh54`P1f9@AoK&-J3znH?8mC_I2^@;Lb_nC=?RkZrsT;KQ_&4y(DB`dlEz&wcY} zBi0$H(D+)=knyj2^1&bUG4vJTo`X>~5VAXSu#H=ELeZ_8A~{T@6Mv}3P3fT^gUBG; zNI6F9C6T%L&gR@gvcLt3rx5ba7qH{+V+frUx5tcyW=rLz%+s267 z8MY+aCy~#)$feL^kH>UdY;8rmjUZoN&9T-0vig-~VZj?Mr#}Uv7Nd|(%`mZ`Omvc+ENM#w=xh4za3BF?D7koVkJjYbFsKqdwfg*WI8zzS)t(4f(>E=Qzi~k)u?^=+tn&w3=;T=)xv{kz1GrK0k9z<_9 zChut39$sTEHy66WL(RKYP_{&(2epTo+GDogs%@A5s5Z!Wbe$Y{pcl>Fr8?YZZTw@t zBXU@gl8c*(Hrjz$!yA$sE#MCj_ zfASGF1iEcMy|p+R?vz^-jVyElG)Sy|#N3cdBXOY-Fxcq_V;@wI2MvoRKu3aIYanUb}sd6a?7e$N*%BA0{dwdiQtGT9nip zxAJ;W3u%h|8u+?faiVhuD$+~?V!luicgm{0W0E(4A)q^=o6G&G;zsY zkEW0WfSU$U1hD7Yyu0-E-B^EPx3TYaV4HuYe+3>t?u`_NEKoC>`AU?tC=$UrjYVw$ ztS#m(sIUPvFWQq~Kbm?P-rlFRaZSfyFRMLq|jVwTsH%emh>9VPoctE+iBP<#C7 z{ZRrx9@(8F=k?I`{XYxBLK@MW)6k~}z*|zjODX&=8ao94_WcXK(n%_3rxt=*>yC=T&uQ#nw<7JbBQ6 z%sC2c6sAnSb|S$4eQ+QGbNnglh41@Qw@*)X_nw5;hsqU&g>AGJl?8qt^<6K3vg1I~ z^}Xv6ffFGf@P{uJPGUqx!%deCkq z@wggLkM`&H1r|cuns>B6T{Wy7j442xIwPN-ooMo&ol`&nQi^NBE_jquC~QqwW5Zw} zE?A6Rp2umQOU<6{w$Bd#Sg!(tT|GtE^)JtGie#B$Anxz~Xm~ZQ2W#3mF7hg6738=~ z9*Fyc*_45cRHG1Uw zbTzu(o13V0I~KK0bR&OIb^SB0$m~FvAadh@)Sg`*)d9Os{Lcn*r%N?*q<_~}c5Xek z+10t{4MR%%ZDG(=GwGTr$RPIqn4&>!M~(qrk*dNwA~ z-GM{|K7Ik>czj-Ic8yB7^(|Mt_^{c%VAsniiwN7*3N|dskp`0H$Ke4)(RznO?cv=e z{~~*Z06H2ZyT&FET?Z`KDQ&Tm0E8G|1%-%}{c@*F(M#8XJlnNO+9|>1m;Y>{R?pCi z1DR=|jzS3%jid}*Aqh?N4O(+_lU6%Kye7EVBRS_ayjG*Y{k@>fo$N)uEVnn(79KeP zXO*5FiT}!yTKi)rD=V%|X(~*_qmd-`JL3@%;Zm+ug>XfIQVQd1hdnYDN;zX0u>TJp4l{wYq@1s*d{YuR4F|S{MI~2sSy==AL-lcM>E-0Qu{uV*H8(2QHxSc+nWh&LjK=D1V{N}RT@Ka0I?@v?YFG3&&eb945^6Rmx=C88(i>j3e-=4bJ3 zOl4i`{zYxcOYm@!#_B*ZKl^X?VMapJh8702Pe__!4X&0wE?v_5%8_VkR_NM-g z2WA$=jzp4a{Ed^d>`J>$N#>|MZ+gf~Q8cfTR>ZM!}UZnz|1l0v00WIRFYX=yQU z8aHlpanPjAe|e~GmHfqo+_gV_dopnK@;HJc{FauS3zwdJ zj|+S5UVm}vu%uawLNKAb?s*uLIJ5li?#ay2-p7-+>lhMJ06e*&&X>Z2jQ_I;e%8cH zrmgfLGtZ9Y{N(!OR%47SRwRu5V$zMYD9P55i?(}E9d&XW^A?jNKsfk8X+DUAEod@{ zF+(Q%Y_SwR?)LYq*>t`F#9&zN>x>sDi>)w9o}1#j`i{%MA)P zs>aSYC?8*E!lXU3`rkXJ8#Jlt=>=Z*%Fn@-&Kw^uN~I+Yfjqo;T1i@}kevg0^-3d( z%C~Sau~N`g?;r|Q&B6NYIjx9}L(I&@nw9kvh;KNTN70>6T>@GB5>e|6~EfJ2o}iv@;$}VZ|(6udj||-?G5J83hgBb~rKiG7X|4 zNdRRmi1RU06}2R-Z~L~eM4)SZwjw5#fmbz6>q(`K?LvHzWN#uFlf%MV*@Oaf8W;4R zu?XK5jj@h0Oi8ZF$l55$oD@rO2mtVcEo3rfA48|v3VmR}^$dCPGW02inqr^(dxK}S zbpn)dznxNBO-rakqZA_gTkw8vhZ<`&YEZC;1du3M<}@b9iY#;|dJQU(^MBcrKYc#d zVX#0qQPlm^)b&UH3{UMnMQ#hj*Y$HPes3U)Ww+&oX7W_^;Kv(a5tnZ2z(Eoq)qm7@ zRRF0pXa~WbsNLK$K~mr;A%v_D@LFLAIr4qWfSjmLYW3Xe&G#+cY@Sbwg??=c9=A?* ziayPD`?ce9+;$zMs!)*}{^#0zP?osTvv2K|f2-bi&d|RJTt2tn@OcK#78&{)aMW~L z%jYf6DTcUhkP@zC@$7eZ3;K7*nT!;22j9?uUyXyqTwWIt4Ek7a)+|y#Y3XIZLPskT zgqLViTl#qA#bb?Xmgt)p`>+^Qh5G#{#JL^f8K4sPta$yJl;Inv8YJpxEA9oDKQqwtMOt28|Tn5f^=PoPUGxJ z`oYWd3VC2>|L2~JF}y?ojH9n*m{lJ(WoQbJhyG3b)S+;EJO&-=ku+Z1GLOQszpbYT z6PkR6bd&BXv{Jdw&;4;pcfWt`4pX5k#Oox2&bIp zKK}gs%1q8J))Lia$NH?$riuECUkufj{~)uldmNNlG(F+}B#f%8PJ8s-VN5NKq5fw~ zD1W~qlG*R0-y_|uXk0k23a65WLk?XZ7wf+}>cUEBq{M#$p^=gG;Knfjt}s+65GB_^ z62%8%{zWF+fSnal%^tBeaFDw!Z3ivOI?ImW3Z|KVPF~qVp^g|$&KD?7znw%K?ail_B746 zlfIGM_*Uq%O(dU^R@3F>wUuby*NC^1fyE1bUAoVj8&lbS5jfD%-Y#~NMMw70{9 zdGt{=E#zF2a3F)4hpEX6@+);G+*Q~i>p36ZO>{p&qK}(8(w5?e{N{=K0lVg&cZ4>r}1PBBY2rWnp0!r^FozSEU2ndKED7_pG9y;_t2k_}hY=(p~Op6-W#S zRyVeW3WTu|FQH{6#xdmBW#()$H1ohx=ooyJ#g#VZMtkT*)~}zySoR$nOZepg6+nBi zNT&GPTHq)AB~HhF7&57^N;Ai@s_!ddiRWcmeXlC~Cry|neM@qvREHg?z(~jRq9Hv} zX9%eQ47vgpNTPpP(O!v+Udjp7r6}bnx0TWk+dU-UZ=gaYr3#u< zGTY>U?=M;RM5rA{-SMOYTA`gA;hkepzym8v*;fjQxLzH;C5e?IFxglYuHC*4E@B{i z0bN#@S+mIc_S!NBAG?k~=7F5C zk@5AxjFCYALxxfjbpVv~!(;?>hzG*SiHQcSl;t2jnww$5l>MUl^K(rl!#RTw2bRsp zuj@=Nvn}Hv%O#QIikd0gU|A*fX%SzV6Z>i1A}p3NE%!5(tOgl;!(kal(8*!=bhrSZ zL_J3=*EymW!**>|h5HI~qyOhcPw|x}g={mY46!8}j8pW0^MT6)KI#7P9VJ%(G`Smv znir*CJtG{8vz+R(oO>9QtTa2#Ov4EhAqz;ZwNE5JRH=vqfGA7Ng%8!`t9P-jMXVaM zt!QIQb%cuV3q>~445~P&v0W)qe^G@;eSi}$_4a_nc#+}zjK;)RmT%+ccQcG%f$uY{ z==@!{2WBBQ0E3u%%$g@nhrU=L>>fNeH0rYC{#>s5jazGun`oz$lKzzv*g}z#Rc&>Q zuyuArD}&q2!_GeUfez2LQrF4S*je*s#IoqRkn}6bfE(&qJD0F^TZ0=)NH*T;8_JDL z6azQZ&el}`dylwvZE#r4(lub?TH5DDV1PrSqPMs9l~CLICy2eW=`WuNJI&h3JrZ`c zpdZx$;0r5srLa>}(A0J7Z#Sj@T4$fOFKWq6N`N10CSZ9YXebkU0j<{~`u1NrzH64) zVE(=U+#-A)=J`9lhG*G3h&hC_-O!q530$8G99jUdqbh?aO;s{+iBOva;*e{j8oMl* z^>WLXJi2n2C!ynaFle?EgD@EfSFLp$zIlXR1=G_F(na4;;m!Y z5<>VE{IB(=iM&U(Sz=4>Vq+M1 z{V*$nezi~03dF(6o0h~Qnz?$v#9{BfDo{Hl88dtbC>6QoxE#Qn@zn9fj|$Dng+FTx ze~WJzD_}3>Ge$@@B~V(5bZ_!cZWhdgZ74P{ZsWQccXK@>dK`7enSQ$_oiL zoJPS;zPw6erc|JtcioV^>XQj_c=g5c@j+p%!u;!ds$n*xcfbI0TL}rl7S%f)=ij`4 z&iCZ|Cl$$XH#b#s)DZLPujeODjaxhJ=a8bWm=ai`1s-QuY0hKokF}6kMzb1~D{f_oQ|Px>2^!wBXd2ZJpJf28La&KX|>myL{?g zu0KkC->DE>l5y@F68O}`c3YlKf<;j62q?7|%YZHKV!J#3B%5(`xU z6P4uKfkL)GQ_DwTJK&YwI~iX#6C#Kh_V8KP{(OHo+wKnSxE3`LrIL^DQ|z3jX!!npFk2?2v8k zXiTDek|Ibuwy!lqudZ9j^Y}|0*d08+zOLc1M>MeC zTe)BRLo{!(E}a7{K5+9FBI4q&3JO|3iV!1V7URmRp7-7|*$rjm;ef?Il}z3JdiQ|o z*H0HYI#z}ViZYLz4ITntRj;*(@iXsga6$5W_XBEvb6!5>>OT0cU!Ptsq)kn!#L}m@ zs3Np=fC>?$jTby-Q#C$P;Y{csguNwW7Z;hT6B{159HPezzUHRFM=+y?B8(fB#STM0 z3NwsyswH4`3_fc33k^Tm*WM8!OLjjxxH%$kR4hqA=fb51yc){9%0ugEoy93{f{8GU z;3SYmFSRNb^aQD=ek$uBXd@fEkR0QRGhW61ks}gd60zJgzly(2!ZjcFWC+o zYP3#jgf!R%DHx%03BOgLw)?)2$y-%JZ#8>y;353=@!|cWccRgP3ZFa}@DfifD}ru? zfeGf^#y5lRqnl5>IMTh=hdx76wy}v3J>1pmhY}Bba8k^i=XOpjxyl^1N2cjbN4Y*c zrINr+us2-|E+7J^h9O0^UJOY-xHz&HcFa{Ul9(oZO?dR9OCR&2r_#`77;V+&+>u5K z^mJrH`1P^8_^kA&7|m{a5YM|?Hp+I+%^?EE#_r;Va4^lo@Z0HNh+NE@TPKe2X5*?` zn(s87yT7^A_Q{;}xqNL-oc6uHeBufRlPr?+@=&WIF^`>3@4`>*ReY7A9oQZE6z4z^ z{mWjQgck;0i+BnDN1n>HaaAecNz_L8M?duIle6ku30$}DeF*D3>&vOW9e7g`tliRa z@6;Pg7#mcP4FuEYy?#FGt!21= zMD4A;Hx50cTl4?^P;>|nniq)a6VvH#N$>SfSin14&r)lO96SkZ4$3=B$lFbY5$^du zT75yPZK>oJJ~}4;dW_&!t8j0p1Mb)-H2pLvRnRe0GzR(%UeaRA0*bm(Th8+*WU~_-}$SB<-6KtoI z8~pARL4fG`L_~~3(*4~ETP?pIWh9^6hpePBo`&6S`ue3+mWQ~i+ZL1pD%mhQ7<$bh zg2hd?KOb9GkIZ;$PAoUlLvuzfZBydehnH^9dq#z8j`EF&XUi`%yr^%H^`GP-rtX!m zz7SJ+7AlCjjnbl^??2B~=2UHMu}3f(egi5%)&LqZ4dS`eSeqwR2i+?F73*i%Pc#t6 z=q;DMA`7|cm7x=>L>Vf#0g|hpYixMZ#5r^w*$?s;)s`aW^uOpWI z%ptRxDfl+y%_={k{bEA+PY}JyrV)tJW-8bZn=SeNtI1TB?fU{(`Kc$2-*3JM{`R$m zP8GBbFjW)Fo?Vu9my>or`#>8(E2X@G$mPu5`Eq!5M?Vv3xVoX{rqpU(Vl|yi-?hZ9 zu*~_F-SorFvT63Bg9PrbRXv3@6MWZNm1#;r&^xJqk?be4hPH=)!%-|?DycBeftp~c zu-;$q&AY%0`0#}-;ze5UIP?3dkl=|0gGFc`U*^K>sWj&OXJ$$%uW_|qDX8^r;dHRkB2q&X)@@#Z`(C3)P(t{>wcxv&C zqIQ$5sZZ3C*_EQ`q|BvADjYOvEVj|Z#*rZW_r0lzeUDZlz2C`|^pTZ* ziE4On?e}CF4bH$_8>t5w_+OKScWU1D=YCtgpCa|>VVUtRTZgq<>#Ks8d*u&W+?VdF zisK%ICP=bKhppFUlnQtfkuk_+*Qz&j-DZ(KcsD`A1PHuO7cXO!Cco|VOwh&P(5}c> z{?XhF#;Ds6tWYxD@QHNlOYs|uNZtKo7oh2OSkul4&TXL>PSyEBnKS%OlD@RjTFf|R zVYFDCea?LKT06*<2uZC~@ZMTpEbIg8Gr54VQNM{z`^1l*AigKwn&!{N|MZ^h72f#sr~M!-d2V&Ja><%sgkb7vZn zn@bOX%;y=Ri>1sb10ZlyQBak3OBeW1E$OjbeJR&x9a@YxX~~DSB;kv10EX8w!8SFy=x?2}~Xej9{}(r2$D15N8yJ-vjpPKjRPBPNa16gob& zwoZ+)$w|ZDp(8=XVi290mh}^K&U2ab4M6k+cO7#FA2BIzVsS{{P^)hd-}{&w9454^ z%=ehXSj$mF_q@GD%7)T8i*1whcXzc@QxxTofJKAF-c<9~1SmL)G{LW79waU6Q!i9v$weZOCi!Wo{G zCC5k3*tU)=+M{&tKfS-!S#A2`w_IkkmK}Zk`nTK1Z{IAEzf_-y&L-OWb)cyEL2-R;N z-WI22x5IA;ZQw1=H?;7Z-qZK@etVWUVPCNey3scODs*@Exu`A?eltAuXg&D+%{`4f zQdF$i{r6l~4?Z})nt!tXdQJ*R8!XkHcJ0u_NRo_jL!xf$q* z3TVP-Px?Pc3^VOt78V)x<%%%qCy3JyLM7MKpp|>{g@`!6JBxce62GLVvR(e za&~XDhAUnSU_Y;>vDQ7xJ3R$(LkK4x?KsBB@`%MbKYq zac~Z4osBi2xW@bvVX8EY`Pdp{`sh`J%%-yS9m8CA4s5kk`3Rk^4xE0)O1fC{uIGKj z=&7S}rr&jKOhM^|aEhCBBur@-ipFdXgV9z8FAlo11cS45d(IFky)YuLc-Yt+TG{jU zb2mB}{1pUwlWa&I5k;&_X`q}#hi;Ij%M$e2RJS+NbCE%@gEZBlQn`lf29s7RL7V(N z-|%pIxkd4MQ2?psUE&x=7epeMZ&-M3F#AE$Yq6k3G()jrjl!o=HljC(oF9|5Q4wHm zQ5ysJgbo)BR$1v>b$_11=Lk zwvPinZi-UH)Ac6V6rq?FjD}lGSY8!HfyP}PDe-4_4~f;LCOWBtR3coCR`m1V3@M*l zfs4LmIlq#xxw$!%+1^78@W!Y~{q{^UjaWq4AxY)tITGB6t^O4>%e7iVA|S*pCpc0T zF|i*`7RT(p(`bjDEv6l()hfOS`}U(wUj{t(knDMPOB3^OeIs%udr(MpUGMTre^fZC`rM$Pt3i{%e@J=}X z8qAK2YT;Q8wK3>7W^grrVz+$SYa&9VK~f`D51>;9V54&f_w03^%=NA@5LUjDdFvs* z$OzERm@4Q75but2xc=JoPnzlqTwUGsX1{;Lvb_4~>Y04` zgCYAHAqblOp77w~wp)uTVS9M3{@IN|AWHv6N`iUz5@iSOBbd53Du87f_5QCI1(N6N<;}^yc_Rn>8AV4qXLY@>f_-&ps)!Jxxu%TJb`i4;sJ@z8kARxqgL> zGHkjHyqf96-Gy2nryhpjRM;VeI?W_eN1aI+E*G$fKStV?{G$c8RFn5;NLW3et%bGoKX7uGrQ;Yoe3z2B$#Tu`N%tAtHte58*ddd!P>6T5G%MDzyWE&L_+}-&e*h@WJFm-fo~tAYvuoY z7)oLxkm~bw6n_-I>*!e8_iTaiB+xbbXZKPVupXtTBvN(JBR3j^RRVJtNy7mA^LNS% z|6!RJ*FpeGmGqCZwhIAVLZ{=FP+$%g{O(eFJ@k0nmU!A4HK0VYu}5M^LK3TdJgB}Qyup0BlQ!3 z2I!GBjh()=;=R^$(q#odvVz7HL6|+((?nhtIh1U>TeS{vzVd*nEg#+pBmGGX?eKs< zNrs+}ohXEAJx@7lwUX?@9*>Ef%MDDjc#zkSdpX1ijfKH@X}GqjIdJ-dM>zO7VJX1i zq$`Ej$sHQ>5o#$+GbK_+=See*dmyxbo3seAL5z%gi*WViv>bm@J$CEXK5f$&ZSelF zmJ+oieD4IHB;BWE@}Mt>p}~I}qp{U;Yqv&iZ!pxPaz3R2#6$(3i6T9zk>R3rOra+g zfI>f-+zL)#P&cWO$ogIjx2!>WtZGJjoiTUsT8#j6ODcc+IJ1}j>6HO8*5D*&?_mY% zWO9FxuAVismY#8gN{W2vrh6KpAC3XV*hAs%^G46Q2Gg}7rX)cYy*Ar(F4wqF8WhU$b3SS{p;4E z!42L+4I58XS-f~agRp2Kr>d8P?K_DM52T@zB-Q@OwL_*y_ih!YHEtlxRsrGI_}hVB z#k)87RXC+0X-@|ZXltx^wGNIcJmD|{=|>IHIbOGxCOC3xO)b%=ze^p}UuA*~zbc2x zc6>dK5r>+;=CMwO9-&NN4T6c(w>W5(XeZ^_Y0N~5>4CQjJG8Qz#1gNS2^yZFrw9dw z2<4+>y5u@Eo=Sp>LtkmuOUNQsncG_}RaMP%>-KG8l@3D{_gbHP4kjf!reJqzZ6o=> zN%g_1TQ}3yVkH_X$Ak-2?nI{F0gaI>tkNh<+G7D$KMDDnbPQ&aRZmdOy+PwW9eVeW zO?$y2Ic8Ply#+?tn$2vo=9@b9aXt^Ye1*Dr!)6g+8#SrCVU66>u3{ERESvB0- zc%O?I|ES4qlh_UlDC+T)f10VTq@KxM2w9H4!SR(3|mqOE0}~8(OJ`@KgW-VZdsA|T9G$DQo-(Ip{(hBt(lsw zSx>AvZaro^Azxo4=Q?@J%uoP6LJBfGVQt<~F0xYdwbAsoI`ny@eaqJPyUnqWt;LBg z+Yx#Yer@m&znf9B_ zF#N9*lq!l%fqRMivn8G&dS%&>ys(1%QplZn&`dqyZGJ+__*kz;;(i|#+2TpdU_*BL zl;pdesGrx9TOQJkUXrI?!neJR8SFESb+en?Ht%<&S<|~1>!>Y1P!uzFhDTh4!bc2M zFNGg6Ha-+2^;KK0ziXnmci$(`g!7IwmS@T5yz%%-f`_OUsu{~P;sp;lRn=`W4K`t3 zVepAR_3vr9{`U?2q!sBH8ab^bE__#3Ud0!b=4-zv;oc(IfqUjGq}_CzusIhP`@*8{ zG~{M~i12mB$tAW44o2_Ad+x`ab5ra~w@)gtv=^b*rYD|hOBypthD-XJme6A4rxo#C zCdO6toY$tA+0Tw~U#ua=@Eu0&meW+7BiQ+r&b`xc4j(;yy0PAhK02&i$*d*P zEh*%Z3Au(192IJ=m>OfY9|FNTK$nFv;E#!pjN4slIOjlcPl_TMJzfO;X4U zCTnEu)aged4yNT$)@MCr7q^oI&61&g%E`USilXK%fI<{?M7{AB+?Ph!Z$cOroj;Q11gFQ9V`0F;2$~IaepOa^1 z2D?RJBt9{n28F*&Q*XM0ZA z_aoltfwAyo;4ufQKiVzvq9Wkdo1Uj{axRWZ56ewTVOe4)7e)H@Sa!VRv$D9h!gI4I zcO8aBC8_~oWyhJa!FG+$&t%7CYT{8`ZGgg4TcbztY*78%@W>>^uw;w)dj7mzp|I({ zL^N6c)nu|3(2iiZY)xot&1iYp6Jd&e@%ncUssd!1ZDnKkq#6(X8{f1w=KO$XE<)*S zQ&^c##*Xe-T%z}WL>^vi8*Ec@y-f3*E%wPPZ^Na}K4`KPCeJ1+jb}Eq56m~tX=ZO~ zD=@ERo~h?wE=3_EH5(=AE3!ZRDW$9UkO_ zg6W_em9`fr6HuP5yx85q`nJH#y~%F(yiP}2&CgQp<*hFccaeC)yX;%+vkOemquGv@ zYx%lzX3lxNibyP(3f9j98mG5ceR=ZNP=NU=nL+BS$mJd1{7;4My=D&+EFOwjJp`&y zd3%fSml%8+%Cjh=KhZpCU$!kCd2P#S;8W`WXl3C1T}$vCcqfJ;zx@QM^w1@@OM5Q6 zLFR+OL(3D{+Dr3c^4Z=cmOd}DK2XC8CRxg?G()Jgh*$oTXZf5X%;ncvIwSMH$Y&3W z-yIFT_tB&eHkYS3Ece_bKEpHU^M3p1nYpifK_8g@__MNZqkgg*FvGj7j6OH|BpHrL zTeK-ze7Cpg)_m|q{r!iXhwtFQ*E{o1o?W)|pnAStOpGIj@akS;+*M<@OQztPpMvL- z`edi@Et4jDlhUc9CMuLpa}%YfCto_R6`^LH{24lwP5LAKh1+N9%^!xE_oQ_N@D{-2 zOZkN6*J*3_p26Uu8oAWO)~{{Pe#{n3&is7HEQ4LKfIfPLHkNPAyO?zzrC_n^Kb0T< z$x`L~bJ0Ec=dYke>BFCgB1@hk(hKaa=g(ENXUb}knjEk2OUucWpw`p}I2 zoCyGlkyqq>Jk?W4Uz}?WI&ph)~pyV!gzWBxI^2N1v zbE(+Bd`0hPx-B{L|ICyJkH6@u&a+I9C4T<~3niuN0qLvYIRZC^S$}q4E{j^OfBw7u zjeb?qU^Vbvi|pL0d#z$|5%8&D&3b-U{N+CA`QG`w*`JrpMEDb~pTD|k7W%kjP8+s1 zo%jE+9u-(_a^kzc{#|_3c@S?f*oIxg(=FR3SN@qiTpL-McF6o3T0PqsG+%A@;!wH$xYWrGg}{SW2wfPpG#792d@2Lkcg0 zkL(pLEPO6h8ZLwvV9kr~FW*TN&H?t1&htX9KHztS^N&6+XpiHSjTHxp9*?rgJ<6by zju9#DjiiJNik1a`ta440+iP-p%9g1v{*Iv+1an+iivWaJegn$$;!z$MpX}7pGj;Qr=uU8%{kHb zb1AK4{fs_Y9pDsB3R318N7z~-j2b?koMDp?=!>MxpXrJwWlURsg zu#B;ex|VCiVR}py{pgN;c@vpADKUgbCHN>jk^W|L6v`cTAjxSe`2$j{i*Os@xF`1) zVw0l$@%z$!cA?w%?-WKhtFxB9uQ0$6wu|7r`dJK5Ty9%7l^a_;%Xy+J3nNFT+PsXl z%XPZ9!D*)ytZ5uWX-q@vJz>FQ8%H5(psSd$7+{i>*&|I~e2?jwLv{>F)2ke31q#P9 z6`2R$Qct-Dsp&0oFQP**c3f*piAO4*)e5t?d2C~pn|>SCv{&-zJh^8(s8|c6C<`o2 zdfgS^h_Lx6g6rfQq2XY)PLSU)y`F|zoL-?~;l&&9IW~Q_9A;}WG`p6UPgdX)jkYrK zbb9%e+gnSqAS1p~z32T8x=x)zS@&w;&wQCotKME!)ExuGD$L8<#1o{ulgld99Ti{G z$bK&(z#K;c#E5Gbro^f|XOPge=IQ5@PY03$Sm;|a13J`LiKPeMwo%xo>MA~HtTw1j zAFrbOqPE%D@Lp&M`i*qC(O{&8ll-Y3VGO2+2T-|c00HT(UjdCO3@A;gJ0fF5fVGA9 z>Gb1dLFAx*j*eN3F@|G|)o&ufprXKr%&!dd2cgUb*Xa>TH&c z#(s0p*fJu-|H$3zQ1$zI;^*JbvETV_CC zBlSUzyqphn7Ol{A2FE|&01*L;Skb6)xfGtqtR#RYXk7^c=)8UUVt8&HJt2KQnSH> zCuMZX5b1S7cA^5hPRLG3fi&6H9>>=bM>VIgssm91q%1`4T zvemmwN@Hjauw)7e{1lVbuO#2aes*#4%A2cRry~}PbV@4G%F@xGWA7X3@~G$AG0K`1`bOJ=B5dsF4ZB3m8(sIfulc{d zU(4+{>N1H&7E$`Bp_>jd?%wnRGuh ze&^;xy5AYM^u4z0_%p!eCPgYYCz@~-3N}08v1#b_Om@(9j-uPCdL(RPkZxsEidx#x zn0RqtZN$1R!L|AcJ9K71%eOwBs-JZiO;zaR+mOFj&Bp`%F&5|BSSDEGs2BfZveLJy z+O@{{QB_QR8gFe#O^qvKpGi60VKz$hmAVS!L~0gYb$>7~LGx1@03toi)u{mg1}9a>lS z_=T%`Yh7IAtEip!5ubbI1-CdnbSQ(Yh#0kcVxQf_u~16Q+~sSzsHu&F_AR7R_Oe9- zVQ@3*{@bEbd=S!+7&D*8bSkF){5R%1(7e_hwr9N(Z|iJ%s_C?{SJ=+J7RH!YXCt~* z2ck4Zt1;VXE*0DdtyfkF;Sx`nwF8Ej`|DDlk6>@$BL{evp1w$A5f+)!9yXo)oE}PN z%U9L*(eXP?mbj)J%ZGq;uUB4K1P$*n|6JYGvZ3&B)?Vzo2-G!6x=OT26Q?4ER(zZLXLZm(@L1a?#e4c<@{ZXd@dCmj*M!%gt7 z;WmqxJHhI#Ylg4eU*-vw5qF}%*Q5PS+F`zlA@bWcEoaliNxtvc<#t@$&t_&7_NhCI z5^sz)xqSb;TiMsXrt~o|)UW1I5MB)z{`z(l#GR$jd}~u^JuuBA>2~)`Hf zNB_4xz8p0Xr0kg9Lo_D|G5pC_7IW2T$0QdKhNraA_W~CKH6*ba=}rMg-2pNKg*Q%}o zLEJryK(_|;5JegjOuT^zf`<3%N#q^>2os(_D`b=w%<&)Xc1guiE*nuEJkj0`(f$?DK^xH=p^%>h z91R8ilqN8IfQ+Axa)%(2O{4uFh=A7UU2*R%R$|BiE|Y}^8-Ph zt~4!QRF++Wa22uKAId50S2rn?G`}|RxoA&5uZXTjwbCQP%CtZ_c&-6 z1R*5?e+z&!is0^J$gSz5J!JBsY4T}y^5t|g9+`qNAm7x7$asLC;v(R*qO>bW>dhoV ztKgAC@>xYPfKC1jNwKjJfs~3+8s6aI6(u)D^6;keo23fzA~N+;IwOI3eF1kYtjZ&W zye)<5JY_pOjdl>9#&Dj-VwQnQh13?2N?SpWsFMLq3dLXwtSyp2;W3;*8>tZ;7$`6X z!c&98`(bhc0{9}(njxjDRSJNmn5RaxQBx+?Wx1Ybc}l+k^Z_4DggWL$t1{dbjW9Hn z1U$4O2D4C0SsuJEyd7V79cSw_sOiy4W;jZkmLenHlF1Pp zR#475qIYOmCKLEK3gjRe16WaxrbG5|DU*%`)8`TaZ3RDh5rlvNsI`s;V4Foya|ygU z%33?-T z|CQJU92QW{QC$9z4;hpDI#A}7?L`I3pp-rx?q*ePN`VJ*ewS7aRaU4#Hqa0iE6A<~ z1f@hex2V>GgJP)>99WR!B6N04?rjQmYWl^C+;a0uh`7|5+0diHMRclA17O(%iE8;(bDfVVN^9M-j!KPs83>QLdZbZSI4 zCU=WMb+9&;bN|k2AJrvJ?Q&5qH>LDJTS?@29XoS9v1C0rKjJ17h)t2(LW|A1CwG1Opn9F%d8`Jz|2F7-cZ zVN;6Im(uyjncPtnp&t2J1Ru=<+=YfYmLad}^mft{_liIiJV*z}49;w!n`23#SXecH z2&*NP79m^1luCP$+Ys)|Md)rV_T#gckQsu)M6Uk^Dc#v8f7PcX*RK}Tui4rEdlov6 zAyr<4E{q{S#`6KeGo(Ml8%=IjGetrg6bhayvx zobVU9PEC=yN!(ovJHxwW`rviZqr()qB|K`2ih0;8YXJWOh1uf0CaocDLd=rK0lGl zw1%J5QrOf&j&ap@SoKgh^WFUqU6sC9CIk=?fnm>) z+7_m|@=W#mFw5({-vxDHr zfeLnJ3aCCWdqBO(m^go$bIUW;VPNOxOcs;P))IFztYKJb@=a=Hf-{*G`c+1^rM4O= z*$#A$QSlYcd~lu9ULsyjffAbyg?SHwSeZc7(9OlROi`_JZ>`K!XagnUoyT+rP4`08 zY-jnf-zrg;+zbcJ-27Por=9t|KZrqjN+IkZ*@!jU39N+|&r}bo z>{?Ky2z=U%DV_3DavhQSVs@qn_{S6SJrtSB7?gh-31?fPwVc`T0Ovo=^X(| ziynIsilaK!hkf^7-b#-d)3_gQMR}Y;DQ`tOh{D6Mwb*!^z+y^!^q1c?mTRa>QfUn2 zq=@u!EWBnB6hTd}hDk3|$mKDRetrb)7{$DY-p&3^y$ez_hH?;1>3}9()~}B$f`wv0 zq55y%zTKJqvI-M{N00!G`qfoHHj0CSG!~lvgJJ=r5GYjnN%ejlfQZ1sKRT0FNW)eQ z8y7zB{Mp^h{Ud*X!X04XtRJ9QUNX`)svK&B7Y06(sJ_cqf@2G&uk4ClgaNfgcr+a3 z4i`S!;}AYj2`0rCk;-BYWKncvdm9v^IMfo38V*FTAqHP6%_Kl@)X{h=2yZv2TK+&u z_-K5P=%i@zdL6|}5TY2f``fa5_j)L~p5i`$zJGh+g)|(oi91jkJ+{E-myE%pi$FGL z@}@Y@8J0p`1hRpHcTa3}KPSw{AR?;t^CM$|?>lfXeC;Nk`|+>AQ$k&O)CTM$H6)Ut;dMu3V_+5k z((vZftw=4&;a*!8P41Vfe<+lMU^yZQEqj;u*r@+M0A_y)g4us(nEgFF!~dg~U7Y_5 zGrJ&YW@l#?r>Flr%nX0De0+R-czAelaPW73>tC4J-X4B;;&5+w@Baxi`}1?`&$n^> zTmgPE_Wv0(yZAi#Z^`WZAI9vWukWg>>y+?$-*qumcQu%LiOs|h+W+k~J#T5bYJP@q zmHOKt`L|Atpr8@1gU`c9pFSP7w-Y3@;o;%`g=9uZY&$wyTU!Z+SzTRSZEY>Sq!?c% zg0KEx8fI_K%B*`UqyA^ZtfZvme>BW8Gf$F}|7Dm(N8{t=HY205v$8TWGE!4h6B85v zXT$8m$MBM1m^lb-J2-{~2NMjlfPetJsUluS_OG%SUYc*u%ydUfdqq*n&(H6F0L)ze z{{dzS3JP*^a?;Y$|2E9dA;(98aJbQ$3Ul97?|-+CDx9UVb0qoJXJ!{IO(jFOTP3WZWoP>_?8Lm&_` zGBQ%aMM44wgFzq=F){JK0W)_3Uj_gWJU|3t(Wouz35U>9Fq> zh58@BO!WT>nC1T)Ftdv>9r`~5X79u)Sl&w?tpQA`%R>eK6)DAs22dlPX3$;kHi@sw>B<&GOKli7K!pAu(#==(&Osyj%V{b0`uJ5!IKPC|o*JWhS za#)Tf0A|;fS+zC_NmL&eJq{&%?oUL+Kxeb$D|--Q9VdUEu`EULW7$$%TvN>I-83E0 zP@4W7-n9&)8)d5);bp1P&>OwkoZ)IOrOLdY*xkQjXJ5i(r>%bf&DTt~w;7;7&VI*V z1^(+Z$oy5?bM80^-#6UZi*K^mZK7{wRXmOtYrmoG`g;&jn1;w0l6Y=Zx%n#pzSbMR z=WZJx6>m_}IT+-*aHa^ppI$9bN`8)?-mq?9GvHRBzgG)&oIi+}gBLgz5%J<`5< zUzgVY)t+y&e-`8oz;%$svPfXd$YK&!?g~Kfj#0=Q@~n_5zo_^ZTUJ4V!G?Pq>dE#6 z)yCT2rd6#)!(=~t^yvjo9eEpQTO2D>InIf`e6CYE)W{qycrp#R$TKw%u@s&BaB0~& znROzw;udS@rv|Zb-6W`G_5=7H0$WB$V9O#Ps!%bPGXh(NMykfh$3r-@0?=Wd`8J(%m+7}n{d{|`i(Nt8jIZ0`h=f5(&E@XV#5}Tr499VW z>t}So+V5pAqV5I~9{e6qppzPwV~5a<2msSXqh7>R;&Dm?17iAOnJv#gD&C^ws#Pkh zvP{3+>u`H@<<#qTy}$m+c3^&yP9OOmK)Lwp#1Fa1v4?@MygWek%Kgf8VFP$lcsfN> z%yGoP)3a!~TRh1@8^i!h|4UhF(G-&mI6#iPBj?)_!%$sm3}QCw*?!G`?K}0uBiSKZ zeVic6j}(*h21X)$m1?A;R4Ea$P6^_tM1N@!m79LT@{iSzSbIrf_q~`Ra^R%lK4BnC z`79I}LJa~E_DKMwHMt%HLsV@|J7-D;Z=V)q5)+J02`$t)8laV9uw|M)>!U1=Q2e>E z$Id3hK&+}-!Yy-<%I8#KpwP@}-LH&-N#roJ4b-5n!m0Sk7tW@6QoT%xfd-r!E8hDP zd+u;@To`wa%^O-4t5SATWEngX(f>^Isg~|D1Xr}C4*1W(&5Zsp0vVnl#!jO6ydx%7 zA`H|M5=Q2PjbLFhfvbV7X)^*jfXNhciD@h9(-;sSrUc_?wR*TyT3)j%t!Dy@NhaG= zRm>g7t8mfZbB-yS$}cf^{rK8Z(J2K_SejV@iYuHAkDNKIH$~m;O(DvoCQ}&eiRWbD zqTP;(7Bux#z7BrEdIFGfgAa(U`&ZaCnKk5g0z{N2Xe}f@>i`ww$#;*u)bRNQ%Bhlo zu@yzJhVJhNNt?7$ZUc`Hxtl_-DJJtimO=kuKTLfrDA6n3JAQ4hC3iK_FQG*+;>MqLX_Ykm%?ze;s65xtbD z#9xOX{#1MdoYrF7D@F6P^bx%TCy8 z3kQBOwQ&V3bw%F#r^h|amSRx)!V32`h#1Y8%yeoL)Ph}vYH#12>YObw2{4@O#wVV3 zf0z?4%NPcx6f(8BAMEum%PNv`{(es}ZZBRj@NL6sDn)r)sQ#@8l^qhmqMnyw1XZj+ ziVQvM_i%quK{8~&Qa}6ym~m(j77rWGZC^yu^Oo>OoPE+{5p~xZdDv3oufiu}5NK9! zQ`CBP!)N1@WV6%CU?qJ~Y&GM}eDJE!;oSlBL+8+VIX1F;TLT8RZs|9{D`)aEcmwyh zvAh@7ap{c#$(En%`hA0{xoXuxmaxWYY<|k&PhVx8_xq6UMt<``DUsxUKy&_$rjIP5 zR7MFGQ*(ln6)_`P+Y!~`2*H`bd(HJ(?*;6{tITxB#3*d3Bbak>npL+O?QVU#_8LTi z6|c@?)$L&XggoIcOjZN+9Z*l>7+G-J*QmfLo#WJ%i zojP~aE-sdTX6}1{1ZlO>6L*#1rcKz%$2-6~7Mnl&4_>!_YX5s&Z~ph-NIsBWl>Bp? zR=W8k$`$0W{~cfi!)|XHt}r%@d(15VRYUJ0@%(GdbJK8e)ahjk?Yl>Vmz5!Dm`>d5 z#^dm!&uasE&xfqtsI{LyFBxaixT)BNc-*SYfaReWf5ddju=QMQ80ClGwGXith^~RM z-ofIglFOEv%jOf!?8FPngGaU5qrP?8-D+{9zEc#=8eJ3|to|Gv+9de z?Gv^ZSTF&!sE}-%gbosirVxe1E$LHdy5!n~EE~x%H5st_P~WhE-}>bDmdqb|7CfiU zhOl!+e!>iX2$Z?u^5CN_Lu)wm@^g~n(Ahet*}CA<{xCrY+j%8Gj-EVpD!3}#ZJqI! zft4yVHvIkoyTUZP1sRV6sR<}1g2cgkHq>|uORTFAer6jU7!_V0zX~yWIcSbK!hUj%LI?+W5QKEMdAwfnTy?2oz zdMBb2Jt84Gkx2C3BZx@s`F!^|d;fIKKQL?7nrH5{p7(WM?^o~>;!lLnT^Z!vWuACy ziKa|?__bq+o?y9e`J8!UY;71UAG%`fM{SW(pq!CM8Zu#6`e^$Z?F=+P=6@tc&5I+oQ(<>@M-Wt~8IalBrtGgd?tQtr2bQZqF-Y z7maKdoDw2s?4qwQ$ugo(kV5ZrlaweE%QYW~r*l5FV3m$Y{5YD})Xr>}Y9{CFJ*DL^ z!|yYP6-s<+v1E}V-ks$HP7^VD#}v4% zKxHMvKOo>8CCeBdFtcYF{U5;W(<)1wRO;cV7kmp4b>9&d9Onj$cZdx8WS2-On*j+= zfy`_8-cmBibz}rJ(TDbDpsF$=#nMU4)71&>jRK#KjiyKKq}#6p+PDZLWV1HK(!gRw z_>%C`RMI^NfDS=&h@j{KfRA#isZY~f<0#pHRBmzEB&wN>&Y7YXtQCl`gWOcBtK>eX zte4GB|J1Wgzn~u@2=N5WYYc@tUN1BJFPHv+A$9r^cNd$J#gh|a!3tZXu!2)J@L@MA z5;{%LnvmS^4>{0P@&p9v3JJqwVfgp;u7x}RV=A|HUe!k;88F+<3?GIKM3H% zN@DkvbQ++tFSMqQTpdwN<6iuk@#TyF4nT}EmMgopEHk%yWszTY)=~CgsmPWX7yOnK zKKW|?cbPd;`44T}I{|+}9nqY#7&WUDdr8tajfJ48!X|;dq7RubauRg~Qsc!y1!d{s zf|dG2`CWI-AK&VfD(k@UdResq48#Fx=%~PSrngvT_E=iygm<9 z_odiJlD^r?!c%uY`$(KJYr?K8Iy;%0E$w4ZA$0V$J-@A$uFKCIo_yF#kP>kIx@31~ zrF@(ZCt$?p$5&48WIp<7GXuBXwTj!1T4HU8o*0k-AD$wKUHV|ZP^uaQZ3Q5A|GhR^ zSi9x(rf3gI7x}#SVgh3gC+|P;WIK!nc)ASpA6=&UwBwGoXxxrRp+|VppH|$T4o%t4 z&}R&f&0XTU8WX!{l6B!5D3bee&{R2SVfnhb*T6PJH;lnZxDrN}!0#~>+UPP%nw zB_9p<4s7=>-g&n~(wj5KFt=%PMbh2>6%)-*h@Y7L@NI(>qJQoL!AOIN_1=(o*PPsG zj}0fVj0RJ+HG0Ljz4Z|7qaWZ*?4XA>)|IxG)C^_?GrZ~xSlJr5B1RzvG9*YnxoYbo zb=`D@L}HDAQ40ywp9WXESaVJ&K2L+10OY?6$(vHO+>oTlE93)6D43G)1DxWZkwh8^ z_r{T3!pY-sRJ#eBR5D~HzC#u{L&nbs!qkT;y6IlnJ=dBYAlIwcNQ183_K|&dfOH`V zl}?~5jU=E`;GrRjsv)E+m7KC4oVE{ku_IkVz!mVbRn&j8Rhti-Qr~j^y?)Q}{(aB> zd--oeDxNezLz~i-A=L-0>;Q7#RCjRrJz@aB6(O&ALP07G`|XQ(+($v#PwYhqz|T5~ zjo$N%6KI%@HYN_$B?ienkozrPu+Y_a{D<1YSJ$BLW9+BK|IL*R2*DHaTp18_&`3n- z3v65=8~y~oY=jXZ{)a2`BQ=Kr;sF#3H{%6VoLtl6C%hluk&NO0-1R{msgp!YH0 zYCzryww%iK^8mDQq6o5wtm3t@6S7?{xEGEbKa(20#R;!qh`?zoKV;yO9W>WKZ6d*` zcN$Ya6Q=kd419~%q(wTW_6;49PJ0%U>muL-LZC4`ROSa9^CfY^AH^$V;#A<3N&M6M zA5<3QHzWI(LS7iou*4{qD5fGf`&wg`>|m-*yZ>7LqmtO@0>G8kYnGU3PKpwCi=)8) zrMSUS@B%@jNYWS0usvS{CGtOGti;aC0$c!7gp>R&RXUt3q^bxIb`N|xwOzPWtv{fo z0$9CI>_IuPR+x|n1Zntw)o7g4FqHaWNXmwSXJN=^N&sibzIxmjJXGcZ0Mt&BfsMw= zSQi)uE6Z42D?(?3SVy%E>(z_F1-E7dO^OrW^DDphi*lxtep>+tQiFNLAb6_`Z3t;Q zA^&^|y}=Qoe4+hFa&hCaIwYj3dyFuAT)^0(+G<%jaQTJj$C$!p`Z{W5A+q!9o-awG zn*E}$<T(0lvPZjtZoW0`O=Y*;ylbFB0P2P3EWYeo9|&G=2qDzVfzv`DARxBRcWK-Wz4G3 zS8I{)z&neCP57C4w*mPm-S_@fNYj0CJ9NzSU6!Z{b88!{hgCR-YyJT22T+5uE0L9ejcK^x~#p(V#}yM&}r4 zZj;ElU^|Lzce+l@&SQ6tXNRJGBb0PYJ&gK+udW_)uSa2Xu%&HkvaLGIs@8T#%C`HZ z_rCNLP`R6wQFl+R8=e1kzbbk+tz-AW(dHYk9mz0i9i*eNUb{ihfo?$8#L@m_a$OYp z!DiS_qX-;2NodSl`t4|^ESWE)m$O7Gel^+RUGmYc($1gnd&0%w)!42f^5gHl=>6x% z?Amtm<%YuWp zBKwNoprnOUr(dU>x9n$v%4f%H)DQYh^c8>7-|n2%pA?*}AyZ7nAO4i^Iek2_AUp*; zNG7}IeXhuU{8ao{%Xmo5;2ib&$$|S%>EpeIqhGLM$ZFe11p6<7cW6UdGUMQ1gl6Yj z6c_3*&uN9Jp%_A%hGT!xW@8^d(-dy^i3?!%FU5~16t6mcUo6~)oe6yY8Qk#87UY#u_zfrzw%=HJM;kO$q!M~=iBS0 zhM|qm>qJJtU_%@Edw&5y)CwwsfQ${D3+KQmrZh_U=yXI45182wVGW0rDH#>RAdKSN z@oqD&SoHq@X2LeTQH&mw@UNp?DXqw9+u?KkM3JEJB=49ethD2ug3Ljrx*5OzKlc*E!H^K70Nq?30Y|3-LlRb0#>;v8Uq=Y z=7GZZ)oxqdv>kqoytHmpU$hkcX-cLL^ysr?0v`d(%EyYZk1!lv(N%lje3$Y?>v!5& ziF;pqUJ#1XKcD_Fbf2q8NuuZar$6w`ib>rou8qUxuMHN83d5&=p6BPqFhXv)8d2bf z>)6^e@xg|A=Hk>Jw2c@~w zwn5b`NK4F{#yN5oT}S~Dbk1g&Z}~9D7I#CcO}Lq9D9-OR;E|xzxEqU)Y!mO63Ygq9 z>!#e6=jrIhwhC?ma4F zO#voMp4&~(TXX9V{$|DO|HMH0fs3ckv=rp|D2QX+)i#u3=L7@%KY*E)$19uGFCJ~1 zt=8^uen~y>t0Q>&;PGcC+=GCHO>-OftewI9usyql2T%8h?=L+c>xF|u3P;Qq)CcSxG7%gd)>!IUrB zOd0F}uDQJVq|q93yQvW(TG@WQ;yXz%ZbOiji;fw~(mz7p%riZ#@3Ou0Xq=*be&9De zAD-fJy*hN@^)XQXL3_<1y*p0bbg9I&yo$@`-K{xxH{3ximM}``ijO>+j%7l@tgDmS z!0?NjF$P)K35`av(x1EBAy95lb2A2Z2h0HBAsCBEAZM}UKT8KcJ=uyLKPdZ;8^l$v zkj&GsicA6MNivP_*2;UDY;OHd!4*l8j_m*dyM*j|jO>6|jOI(;ocKRSe#*a0PHxd> z35tKBzWqVGXXg)s$4WEQYNl7P+xLr&;Lkv3WI5~eJ~#CO^S6o@(ba*|Mh`Qo_+`2J zD@@g?9&R68$ac^9AQIdX2_&xsZ?B4@{9r;j;0wY5Fx8OinVkN$s+KHKYjp&Eo5xE^ zMosOBAvZhvGlbCLG)0vr)Ag0rFG_KP z18|N``klz*FP4_RU2>&L2GT+qqF9o>N}JsT{dm#nSM#Pr+SnVlvWp6e>{DBRR%}XSt&XjuKVeIwZWsuFM!0RcbDS!pWaS7m%&H>^hi_ zS>?q4NVmu$Lwz3qma`j5J5HjAb zGEp7Q3PZf4b#bbp`b_tzKFLhjTa)AyV(Gv&-iPAHw_hQ z5lf4_OUwQyxVlXNvb)Sl3Tz8q^i{$t*&efdAn7(Z@mlmfl+E<@S*QD_BU1aX^T+ej z9IIaJuH)9W%dMA6)~Oo-U*zrfo9O`bAE%@*B7e}5)#hE`1D-Yc%u~6x4tU5>2Gst2 zn1y2xgxo8fx|zsF;WGirJ(0hyf4;)na{K?x_`FaNTAwZ1rT~_2B)WAkQTnW>2$Zv1 zTPr-81v2u|j@+I^C*`h|24Du~CktPA9N2O)=t8LZM|roxlYLhPp!`KAq^x?6=$U`> zXxTQWhra*O3=^MW(e(X-^R12E1FXG59 zTy#4Q%dhd}6|E9}kgNVwX3UfAEmq(R_|$Z5uB%iPLyX$Da_QuWCTGu3$9mNDB_zl~ z1MBZ6rJA>_LOmFu^0vO7HrcLB`gRw7UUk!%ja|z^PH|n4AfL>{c-eWa@RkZPeegDj z^-@Mt=E00`OaLsWZa|dn zI9Bb!521}GSA3IpM3Y0wg zBNNuyGbO$4y&PQqTK|yy)h6JnU9yA>>O57VdtZyaUPS$JrNU8i&(z>?>r=1n^3fVf zTV>*fcgY_v1z&F6g#>*0@htG|eVf_-qp`W)&7|PIWv&=yg+-U5as7SPJ>C06Egy1D zS-GAG=?jdz!5e5gsMSxOc0I4{SPy!mro@wenfW>T%kOq(R<8Rl=>ndezZ39)*{ce> z9qHU#PiLWmbLGuHKi;xBthtm4;M=`vAP#@xk?(%DH*Cs}CmsFBkhto+kiVEw$|hb3 ze+u^dr#2uOwsW~bb=zo4;s8v3mdQour89{9zDjPNXpaClLS&A@ll4f4$d=k;eJ5Y_ zi7C#AweP*@1$A>6GWV{56+YHTX@HgIKVnZ!ut=TG94)Zl3RG7t!X_8Y9t8GXBnZF4 z1XdE@FG|~J5f)*ieR9EUGGG}vj4hY&J_4jONjTggN&sO=QR_?V>=l^ltx}WEW1#)r zCq?oAMqJx>mJvq*Ae7;U>Iz_0+6f5&0Ev?vuB%vf0DyBemPr85lf{JNc`^j*cKIug z8b?-0qUy<{N*K~7*P@0q1a0A8Z$TwsdMCCgAGL5tZcLXC z#~?1p{^di&&4)g7c3QvuEfn|$mWTM2v zq`u*r?x>rb_b2VCMZz@wZU(FQH6LdV$1Z|+WeJ+CdLNf!{e)noka$MJ*u^RJ2sqFQ z04-_oP<1_Oo5M82q`bj{Ro|0I4hr9sBYbbGX?A$v2Dg6avi9zNV3 z&2?4Z=&B5k(md0B-;vQ#0E>Dt8Jm4W7&iGI@&-r6*pI4*TR@(i^uTgsRb?7O7_cN) zgiISl;a5Y|P0gNo1irI8;ilB2w!6|3Wy%sSyu#W1{C$R}q7_Yj5dg>q(B%S*+ERw& zl`?xqtPYCsJpe$EN~i|F$mBAGGk~KY0P`KFgy|q#p%$4t-+;f4TEv*VsXC{`r{W#V zbB`7a)1En!p<0=t<_#!&5L+G#2v3x8@<&()5i;V5vPr0;OypfWQC8WHC(1Y`RoG^+ zi8ss-#4&v#Itv@p!H+(Tgb36Z#tEm=&z`B>*6As%kWOSu#H$5>Z?x&cF_DhB@9YgD z!&Ad;u(1J^1o|{EXVO04hHkVfz_J+hg+^~Fpuu`yK1D&Vx;u`1CBY@P_Q%lpw{Mk= z&ntLApH-PYRb`G1D10us0;lQ0zJAhKPOKg_sT6_1TWde_bsGHD8$P(Bn!N)MIZL<| z`an`^ND`_C(yt`LC9!B3@>>}aE*so%f68fZqwr8&g`k1@LMpS|r{~O#xD<-AVz}gI zN+-kfL?R)6vLB^}v^|OlGUK(x-ZYRZ(@T#2a7xDFwD3lNr7L0ZA_0R;6^XtPotY%d zlQ_T%38(mnOFbU`A(8av4mXS%w?5l#KT(F5K*n7lz>+^!8lnHF(wHMuNxsJfnI%(= ziK^&}2x>9DoNaptdh^O%PGSy6jwi|}fguc#aE6E%K@)W#LqMgeE}5zSkO_+59#d+L z!Kg`9LHE_HVYELaLdBG14`;JWTO}4Ajv&-!sMhH*wHi0o*N+DvqqFughKj0O8`8g{ zDh{nOP4!J?92sKq_5JOH5r$B6)L4xXopT&>L-D+OT~0^8xqrvJ7f*rruX&B2c;y{B zuV3?SVhfMw=zVE(Iw|L$R+ryF&O09JM))#S+MByX&tr!el2-Fx5G-P77sGiLBjy-U z{7D9VjFC=@F;5m#P8sR-Yi^&>_E;7yOf#|#h_QtGnptGcMYL-?$}`6^XnxuY>BDq^ z>R;N7zGU@eXQE-`#=&4(y!ee>^F>keE*}AF;to;+VE788NL^W zK^Etn+atm4UmvoX^<*u^{s)z121OY4t&a5nVrCwnhV~fEk;N&!wPFoYZToA~PTSD) z7K_>;2m!?Ep6K0mZ>bahfdC#e2+z9Om<@NTN#Tg*J51(y)pz!SD*r>3A%ay2{WRg+-M0TmShsb3SI36k{I8tVu;p&&NgQ}D~T&n zS^MBy+6x7$kvWyO%kiTRr^*)j1eZm6vqX6vcFF7%>S6pV8Cok~5tKGxi~;|>xKM_+ zaNqFIphQ-0nn-`>YMCQqVht!~yF}}t7zQJ=qcUCrEAGrm(Aj4^wo6-yRilG3R>rCq zZIo7(A17{DHLY*bZYaKV0-QvJ1wrLkB878@t->DsCWzCij0zov*w;gJR|wdxE6wiZ zAErj#k8yHt6^4GAx}ljumSaVNh(%W-75bJ?A`X_VLTPY9zm-^jeiuIgp?&V`QI>P@ zs-5c=?&*Z+S*Eqvyb;wfjHbO+eg({vD=o>Z9nQ8x{}1NScuyv*hLWF%CTsgCE6?q7 zksrE6uE+~4fIm7+hQO)w8;0B|g>94b$(`~LR}EQGsTJFBL(HU^hPJTZ_o$iMd^olQiI7mLomlVfX>8|I!D1~WJ$)WViR z=$u~ma!2;U9D>Xo0Q-$lj}npEAPsjiVW$XKM3Ad{9NYS?@Kj|hZ0s=Bcn70^TCW{> zlu$ohZ?jV%zhA%kKVlife`1;6;>YYj56_A9_}+EUQLH--2(VtG{I^rM<(38ykAh<8 z`1b}&T#999`;vSAw^cSAp?4b^l6JPzH4?I z#|pF0g#eJiC&<`mt|yCu?(NAQAu)TAlUrexp!g-H#Gg*^OCLNgXVG}y>B;tFOv&^; zU!DQxKzK4dfIUf~y??I1JEh3-EK=mi194iU4 zM;vHhl)Urw>tcpIyAro)Ut>i0vg91Y`TX^GF^Njix6pPurABK?(X+aL-l+_c4^E(7 zxablaXMqZiJFry2r>9b@F*>=xAPX=+CNjWvU-bA$h0YFqFOy5T7>McG^3qfeKvS4!X#rI5iW(e}Cv?*0 z;HS$c1HgvgJyDcoh%li4H5z*Uz1M}T&l`ZP|M<`8pYtjuMI1XIHh2>1l^g5B&`z^m zyEgqx)h2=Xy>AuyC0pAuX*h)vA{@zjVc7O)&($#=Pn0#@qX$6O>mN_7DMAhdk1L66 zcd&!dtN2rYW5OqaqJfStV9G)93C773_n+Rn_&B%{5&`(IVyUs#Pwx;Si$W=QC@Tq+ z91l|)2<&68E)|1PTVYJ86nr`b3RjP;Y#$$IU#0lQqS&#LzJ!TSYaVQ0En}UyUhMzi zwF52AnPByMuD1D-gUen#$!sU^F^mK<03>&y)|0`tYZpb^Wm7RtEcBOt+kT;RFmN() z^2mex6<)XnnM@?`;Y#dt{94_~Wz9Q51s7=D=j8mw829Zzy$jHE<>2vp?_M^T;0m?z zLGMM@?=sClT=YbU+(=n~+K$Vm;FzViM8LKF0F67iwTSnSbZEppUSO6k=Yo{Jz^<Mo%kp9k0y(M8bc9s z%{zd~Yei-;L!wvmBpd1FAxvjp(a+h-Dc>K8s?rZ$9qt1$*)`K3;X6LPSu+y%CMrxC zyn7HoyIy%1Ow=uQ*`KU-kkrmlFlUCdo}Jhin=05`oqo{#_VNTQBQuO)@22(CP#76r z)qniO<|$6kMlXXnf=uoTXADh$Yok8?L32LZ)~S*sSj%FDf*a!3|DN7+%DmX0*}JSn z7mYnxgZ%9Q^@S0Y-Gu^xpvg!Df+Yw?Dx&x#!$XBBm^&S=%|I7DQ+34_+O96Z6AyN3 z)Kf0QyJWW{Av-Dq@g`w>Te)U28`H{e|K7x@Ln6L7-RkE#QDB<#*?NHsxgT#52s~&k*dnwH z34C_p^F3$+p_A^{y_s;B2ES*NcpF1nDlBiOq?&Ysw(}@JLXUbJ%JBT=)bI<(G+rq4 zeT=GHf9(cHbCA||7^^$iZ*2)RC0bNgJ&j$Ss7sSE z^3N#vOaBOEA1ai=!lSS<7A|E{#=<{K+wUbxd((6OeUR}T1q|sYq(5&K7F~c5yiDgA zJ9(|gBc|ul_T%Zxk9K=?KgJ6cmEn*m#TfbInZtH25zp;HVp9SsM%tk?&3vv-`D4M* zdSiG2CL;wIaVNHO-`4Gu->)w(J{3ym!85g`Te%*Z9^K7ipZUG>8V#2G8{|-e`g_(C zdE2l~{q6bREBcmhJ$KJH6df%UxynS1m`#Ud#5pCYzAGogZ+O(zIU(}Tvd`nPVl1>V zfS8bG!`U8*`X}VdTz4wUBkWt(>HLTm6LhnzR&@yz`Ma|v*XNjPd?aZqgASLd`h%~h4ukk z;)8%bj^6N88LTRNwuKkzfSaWAd>ngxz{Fgj7U^<6$oPx}OSud-($bja?joI4_$iP^ zeG}!$spw{$Ym%Y^0>JPn8HH_iYUFmd9w~>!$lG@AeN@mTU*K%h22eRmZrj_T53XtJslI4=EquFTg`;Md}_Wf z8RKaFR%%fD-&ulps}pr8db>v_eA`^3YxxxF{n)1FEAxsZ57(V9AIjS+`tpa0zWw#q zYaWa=JBgsLX$NX`>ZG#WfXSg>AX2wYFuBRL-isd5u%9(Q{+_kH`}bEA0~T5VQn&X( zl}^II#l#E)l^rgX+hckW%$B zp?e_sR}IpVFZ6!%ZziHelC^8Tv8)HZS8%RRdExn0)BZI{39Wa|64%BuH26cOS969B z$>xGFJ?~wjZ!5&oJ+{>{oK?9o?43f+*k9>n?I?|5@_uMsJA>;@E?9xp>iz_)nLwJ! z2Fk(#qhnK@`uL(mL{=|-alAgz`ukBXEhkmB*nJA+%Fn$j$Gvb__^+$lX0C;#!;wfNNm`-S}p!Q zZ8yoHgY$$Gq~i5|9-TL~L0ANl_+-VAHMKxWS<+2TNeY%nNRJ}R6m;s(KXj2K1q+NXF6nR5t1 z8^C&nV8@g^*>hAw@-sVEk?QNu?H4kZxRc_?*0P!llGw+V`yjU=3B%PZn!C4z)ZY!&6c+8UPfQ(B5q$FBsP9gN<#K}g z(jGogeHi%WGb`VV5F-Sce*$B_J|fXB7KQ3d)<>^^8c(1PDD)|pl3=Hj2*majYtF~*t2++_m56<(RS z?*tnR!>B}fvSHXD6y&EOTbp-^2gw))PZjW>06~V+Vt>l01)&LN(n=%u zW46UG|1PuA*oNx_A%Akd@&o3>*Mb5MCpbmS7R1TjxSD zp`fMI10*UjC1b0lM%`9e1&HPj5P^FA5w^J&v_ja*vOGK#l(i7-mLo3JFCjCyG|sIk z_F7M7T|>L{TX1xH2L&2eWaO`IQABG*=d^F1Xy#83k{Ogh1I@NfthVx@+3J=NCN|}B zHcSxOL>4)oC_=A3i$H7J`Z+tQt?SjOykbUF-IoRd$L|N@*5+j>rZIiCQm1AX<5C*| zy;~ktZbp(%JZQ|88g|Py(9yU&s?;dI%-+h8ZoLDk_FBChIm~06?yS1FG}G>>(l?h;j-bnE1-GWb=_Xfq8PV zM1+gcjj6IwWFQ;FlRLp}XA7$O2>pG|Eq`cOxMD%WWR8GWg_SZ&RsOP zanyFz%Rg6(6R&z-${!L@g<9Nw+017{r@mnaE>IfkD6=klhS!A!E!iq^C(s18IKH{k z_093va)@C2pmOEli!p(xa)Ouo0z4YKdfis@DiF1>a6ptmM6*?LwtdKV;+Gn89XF7R zOf+$+HjCYMutRlii{L%8@`PvZ6Atvx7B}_=Frr16bW{f)kur%516yE{T)h=7!tVwiy3+j?-4f~d5pwY=pisZ zVwGr|EfJfici_G^$ZL|fdceJUJ@ktK><*d~l|Op$iD_iGM6kl$Q!jIhQGEy-GWnU< z>v_88hk=S7&boP(?*>TxK?4cd1AG*}kUy0KH?DPZmfrn=E1M1?;mKZ)M3xM`QKPR=`L+GKB_iXh zyWg7Y*UQn+UxUzSbk0HeXrR}jhU3;eVw>~Bnp74wTtHkEvfDX$Le(%^eRTKwuqk5P zT?-r^9(8lhcxZn7{JUp$U3J|fQ5{-TSd5@5jY>Y!`Kq~kn|ydSrtZdASQ|aDks3uf z4js5B%0O9n{;%$9dfj?3elgk`DtCK1C8x6TmL(z!Xk88>sg5TlAl>!{5n`zpE>cG@QYWoB6y^ zvNvGlMk9Ge{VAu=-4@ZXr2v2S%Vy5^9gN7PW3f5skm=&Ku-RFY47`;t_c*? zZy!n_wJS#!3z6&xD#ZT#6a`LH3BoJJWf6VVP=+Xy^J8Z42{{S!x0NtsL%r(ap=68D z=0J2?JhC(XRHgFHMTuCW7bZUTjo;A^m;jz9Jsp``KbjKc~f*nLz>JTpKQe z3K8t3D)|q{ROrt&j?om>0d%52QCjt?F_2UA@ubzy@6(SJbsOK7OEmuO=elXWs}RAB z*p+$JqEYZhU(;94q(QY1^DdoPyO3F!c8~pQnc}g#Mr5W6-x7^N1i@XV|A2SW79$Ty z0}~Ea=0@E+k5wR;MWM*u=qLa>pek%vmiZ1}&95!zC$Dzy>b&gZQUGcFiBvv8S-zGq zzW>%tmy1VPLi>}|>58juY~zPB$+4o_U$5u-4IVcrR}RRtUywKk-Yu5|HatwZhMNRwv?%1%B~xv*IfE8$Dn=1Or%`!GP)@$@xXM?3dnT@~cc`_`!M zlC}#M_g=YjDX2<4NKi(q***RA^o4)W`yri%X|sm`M3>-fIZ<|&v}m16aM$H?z5^i9 z(-KP+{?a&Qp+hdX_lwv-htGkLx06II6sECgO6Kxduzz#DU+UEpleggr+pDf;mocwS zUwq^Vp{{jU-&ART66~K!FU`$Ra4QoD_KUX;+@250k@ecG2HnMh_#hWt=pTt-qJ*}S zpqw^UwdUXlk&Yi*zV9VRzHf7TCAH4f@q&=QY$TE!C0oGPpJ~z&^))E>>kg((g3NSq zBLc0UJW;rQl}a6a#5u(6i#N>F#E1IRd@4jriO3pd3)T+{E{zHowvuN2UOp8Bc4rCb zovTgq$N6?XGLddJ_aPb&XTf8si6AAK{=9ci5cH`s5(S)XdrcS!Mt4T)*-PkCKcbA` z$Ehijf_0yW`>|iX61_l4w8S~PX$EoTZeP8j??AT?a<*LSX<%eZIehr*E&mI zNvbfKHar}VpX{f)!mFvbt2eEeWug**4S>dwgq93{XYp0j&);3|8PVJ*j&I8AMHwc*e}?q z);HKK{tQriUqK}RnE5B1Cgft`Rh8akCfVop)uuzLk%bT^hE;kzVD@hn4AQ`W!hr*9 z(hO^w{|{gm7VgC`78|chI*9BH6-z%-CLK_j#IU1*-?u{tKmQ-P3_ZpEcOkN8`m@rZ zbkE@rrCD9Tdo_$#9YD&vKRvGJi2C-B`Sx@>%+o9nji<{j^S3_AT97jQ&9?3e8Ddu%M)fPQ?H9GikSO7> z&x=>qawq^?Ce=;_518?q%A^8Wp(Gp{nb<}SFw^|CWWJ0c5xWAbR7@=c9x#jG(l7sp zHFna)3TaPVNpo@3`CZPFMXsmw8BpG$&uQc`U5(N`{_zOgWxAPE7!+${b)Me3OlGo= zB>r}BOC$s2d>faYzEemLE$-4+C}(tN73Z}q;t4A@RW^aBHm?k7#+tPIQU49O6yLLH6GcnN=vaVCp$ zb^}#81gTOx3^gh$xt}f|{XC9);?NBXd>))5M86)ka_?Zf5S=zXiXi`Fq$2HK&ESh&V zl7PUPpmw?_a8q(2LgMh}tT7q2ePL+~hxr$$=S;0treFSKby>2L;OdP*#TN*wa{!f+ zR~qE9$u@W_;KRL_PUeCVSK5NqPgawjmINe4WSjZD&yuSCQvcz0)%e?_DfRsjvAL%! zJDDTB=)&*W-?XX#5$Rh3QV zblXJ%y+WIrz1jSP7F_^4N$;MQ=5DW^*mMqNTGT(@ucdcaDfpm(v-UCG4y^L{I3OZ$ z5?y;(K@$!K%Z#^vF)uJ|oAW5dwKp6*KaSx2t(W>y_6Lpo;6HMD`_bsVl2;zCs1PmS zr#D>2BMZqk7wP2+g7j)rj1BJBM#Ba7oF&-m7Zp89RGp z&MOcyi&O%N$Gs4v{Qmd5`Mco*X5-p^T7CcOc(6PsIWRS2a{~ zL}{N9iOUW^sfnkv0iLTy2)}WvhWjck8t4}r>-H41z6qZbi?L2OpDFp$hwdbkCkSx# z35*2fg7sY~+Kkue)MMYzKAL=NF5t+t$MJ?aH!byCyfo*I*e|S})u_||3uO++Dgl6i6EC#tO)<-{)!Pdt*W9%iQBmSki`QTR?HcywB zD}r%iZ^Kw{m?l}WL0dl#2jC+2+)Av3^{`BcM|;k$4vc>2K!rHdhS6**3*Y^u=x~=4 zB3voQ1(GlsItvHo!PyUXB%?ZqaQ=Dx>TiQT{`hSYB0OnhEJJLV1`>Q_C{}U4BTLJT zZxAqree&SUYYnz-E_z!yBUKC%vjE@-ngE)LW0bcf%H{S9$G)-1Q5Zn_3dH(zF@^&s zj`dl5&FpW1MV)SpzkscSxqj_AHa?qad0^_agXXoQG^RJ@FXf~pWe|3gn`!5ys<@{e zDbwC$!gb(4t`r28K@(soT3*ws@(+kipQh?z9mtgM9#}0g=Kl?~5^<@G=Gsv9IZc*c zCad%q35|-v8uU0*8cT6zVD_9xWig zN){=uuMsXGSKVISP@*Jbt(Qb?#T!N>?|f2;ee25!={iW+EMaf`Rl?qloKh(cqoL@MA}o;NKXaK@f%%KQRv@BvR`Wf04PkNeG~;C!SMYYCo)Bqw3O@& zu#EyKtbq82ZYOW!Fbo;ZL@Lzz3+h#GQ9?Ju+PXZ!e|?8kzqu2_NV}%3oTaGtt!Us3 z;Y%8ZkDb+16CF0Z5LqZqep&Z9&u{&&IOl7NWu zCZW4ddBnko!H}s<|Kd4rTCci3vHW+g@&vtKwqht8;HL%@{cOz$RZ8zuaz+4Z;x#si z^r|H$#KHkq&?gi?uOMa=vPIQZfBDhI|2Sm*_{%*;m7s5NsV?SeD+I@~+NA%CqY8vx z`-L~SMBSvQfB@w0k$XrG3}DUO!vJQ)U&UNa8f}%|Jnih0OXnn~?<+hQ_rH7tuiJ5E zj;5x#9UxIHA0^x&u-P%v*e#`;RtFWmH09+Vamls~?EhMD{7a|nK`~1fwcQW}F^3iF z_{C$KE?cM?A@k;)TPL!>P)n=OUn?r2B?I(MTY6umjh4cQW2iQYGfL&vk+<24?6YS% z_piDyrJpHm9^J)}{XN#^{5kl#bxXrCM0qR*PIu!Pk=D@j`IYkTorFghEei_Ln{z#% z0gcr5I{gUiEbkBIz{`OTfpD`=E9(K;P}@AZJ@4du{j0cpD?K{ zVc6~WhSvEBNHN)Ecjdp6DA*W>z-YLEh%dBbLhPTYzfL0`w2_$HVSCI2%y?2LW4O3Q z@ycRShXFyar1r@bzn91fuK8Rdge-thfXN~NpTHC)6~!^BTM>q^gcG;q6YcpGwr5o% zg-9}CUQmbg)ygr6?wZ+kI3Wq=kte}Lx#7jx2~Ww%ihtu!Vxy^u9sXmfAKW9GffHXE z65lrR)HWjI9Kuc-DU;kN|2C5RnovIy7E!QcPj_H(g;J`YsxPMUd8fv8A~_B5_a;*j zSPd#ZFI%P-`W6bhn%$s7kmBo<9 zG%=Q?G13wx>P3#EVU=%crcXVr-j! zY`ase4H)wICbnOGY<~ekQE<=N5v9r#~v zYAfIbw?C)ul+QP~cu^B+I*vc-j6Y3WAj@AMuUR0)m~;n4TIesB=TBVSznE-H(iu%s z+DGhgM&)As!_`m7B=z63Ga<<;7BOCac1QlIGvQTnkqm%fnX$+ZD%acmVxmOjJ1&(( zC4G0CntACBk%TkM<5a?w)bw7d!mNYBhi76Ok40XKix-F!<5xs3nyq{Lh|*U?--$C1 zPLmL2@RCvUQU8>%jN-H(6cczOS&=ScVW{$lt_0-H%N*gpoAhR4MTT#N=kQ!ICQrP(jn3cND4A%-20q;_dWMK z_x^F`nP>iL>8HF|RCBIODvrt`o6pIe4GMx} z@}8$e!%0X%3x+8sI!7E*q75`$P16Al+ChV;)|B%F{^cXf8da)JRq`A0lypd18&yA^ zs&)&g^}DJKe^wnvL5K3xzEG(3_mOv^SwA7wyBkTWQJ~snQ?A-1L;2 z^wiJvv>)s1yXhM>=|4+>0_(1~Xx45d+zcBBeQe<7X5iUm;Cp5e@Yqn(jf~+;?2C?0 zf}6D8DH5XwFq9S{0*Ze~?YW>=rJT?8JdJvREA!ujV5GTGt|Tu*{*Lta~eUq6{& zy@c@(pnjUjVND?*4mM{ z?aOndJ>|9Ixt;Gra~B-?pX+qa-Gno^|HBO=y$76B_ z(t3_3=OG)-J&{dLx)-j;g3dgJZqM8~ELu2n(BhX!gs}j(m{26ixnsa@(uO3btH&N8 zckLtQ_@gg8lK4H-PKc~*ufK4E2Tuy_XEQ-rf7mfVtg( zeVEecP{$_;0dZ!5HA?r^=0iTuIXboY+Md54zpF^jOohk?53JoCVq#XdQoJx=zHWJl z!Q4e{>Y!rki8}L4egcq0RESD9_gosDi-9XsE20L*WVXiWQ6ewg8svW*MEfXMVgBty zch2`H&rfSai6~;;0y5L|0ExR!w(|jutq+(su+CS5>%5a^x}tBoO@MGXR||Iu0&;*Y zaSFZAb#_@l3GoyP{i67~?7~+!2z>e)7ycjG*NJ=7l?SqYp1136bpKqiKOSu1t4RKD zzHh=f#fI)B7ZI=K-9uiJ!(}N4ES`rbM_p4%V?20qMZ%NZiSr_4_2=1*8fktsM7+J5 zxJ6~j^6h?pOf1=0EGaYPSO6i)J?XkN31>4&f$Cio0Aufid=@4`L-_A{x?>iFU1y16 zH-&}Cu-q38Jqm5;mJ#PE!tFziN@xzh=z*$Sv6C4F-1!z!JeNUB6}j~^$M<5!YMp*z zZPUX!=pmOaFm!w5H4hYOUsxf&Y5g;&ml=_F!W}jk!SPbmVe*~JERmzhhx|_I;PVU1tPX3*b<)c?Ua(R(On+5cmNi3c-VZZ& zDOVS*TNe$C*mb{{uVb96e*dCgTMsgFsV$hvsXOyng0{3KvwZQ7m-2N!(_*8yM@w(2 z+b61MLXYHQ06v7|&RVnNZD{!Bl~L86Y17ecpYG~;-RRq4{>B8UCngfrYGUVguRooW zRz_Q=t(H%qagO@qtVzClLwgNnQ_hPHlZN^WToS$X;3$NzrAzbjpO`}0_K*dK+XmRxQG?o)4h6|&Eb6WFbfH}5h3ASWLNg+tdJp&T&jIbJJ9butejMbe={s3I1=+> zWbjgrffW*Y#SxUv@kK?%z;sMRU^pfF<2KFsU;Xi@!10Pih$%m;8K}+BL6w;|94-yP z#K+D$$A;-vGqZDTmnOZhXU4auaiph`bUyfhuP@U@duKe0c}J2oB2p_|2Y z_P#mp<>K#KY#>U_gdMCk!Yys z-$faorI5gJ>xKGH$k7nt&J-Qu>cog|^kX@+lTq|5o6GaGiz`wTtKKh0?wZbd{31>Y?fV}kztj31{A&9Si}`9m zzBTBPta|go#B3)fadh(I^!n{kis!M2#7|bL?PJMbIV-f9x$KO;i9Bw$OOO_r=7}b= zADE7Qx#y>kd@5L;i;tSI`m~MIEUi}M9wntuOGzEmzCV6udK?8k(UjuTm132ohAiDc z*Tidhx<0GF+uzUqdDm~ZTT;5u@8V)uZ)q;7!|Zr7pm4SWiUO8UZ>;^?dqRyGLeJE86q^ z_o3%xCim^Xu9I_nU+%1*$k*6~JJX8pDUJ`@wfew#CSE_f?~vHyC-DPV%Ey-FI^LpE=a7a%^Tt z6gPp6&9@;{)R}wR!+s85KBPNzVDN>g0~0w~kv@+}=k#ed99^=>I>y#}Y1gni7vbS& zW_hxXB9}z)?wXD~(Uzz(@^9g9lyt834 zPgFiFnYuH7IvbKmP1cGCN-)ZxN)5GbD-IHn3I9U4hSnZ)Vj*>o!v*rDsQ|^B-~XI0 zavY@!pa11_J?8AU%nO97*yO8UfvMtu45z^0q^I)aaQwrb;*9%}p{NuyDVeDV|&(F}dlu3LuAP{r<#F6-cKf0$#e&$Mh< zTb{wxCOyH>xF@yX-EiGR9H3# zaFFjPTnQ8TektzymoAMbC^q9~e4EfAVz{#&a&d4zssC?DZ7k;Bl3MKIZT{XV$PDuy z1)ziX8$*FBUEOj1$G#Rxdd=2vSu^3aPnC9<#9xQf14NfRA1AMCxSOmp(WcYwUxpvGwWcaf`ID^6?PO+|)h4jC|2gL{K$gFn?88P4?X=3Mi-^QLh z!nIEbP}bDNjcZg5#a{v&+be5vM zU}~jW%Q%-M=)E9dP@TIT_)cjq|;r!m<*Lpq{9wKlLQyGzE{>krue;JA&7 zZbl#)#88w!_zy5!v>FijL^R5~2ZL5av@#Dr_POU}XT60y5XBXc;jX{VJX5>d?k znKwKrBy}ET+?Rfy(7GhNXDmc2(jXczGd{_iQaMKA>2NGyMiH_jOFt42ZHI9!q&qBC zlvr?u&sKmLLFn|Fp4cwbpHb9U!` z8qW=>eASA7GqQ-AX4wBS^;L-a+{=>sdEA_mx)&7(R#?D{HshQA^xp2=eSooY&xH+KFI)3M8D_9_W`hxhJFJFEt64IgKmtjWy`WnEnmm0y;r%G&Q-YFHzh254^7O9e;9n){>YZXeVSeB?}4@moW60$Gvuc%itg;O(zJ(BVk#3pMf2sSJI^Fn zHx~26?5f#&&1U~>ERiDJ(~9!?T*Tc}rWv!RSK;-gBGfhZFXwkAp+9dWVw>K+RJR{! zU3h^HcX>Z|lkyzWG11M?T(@a@V97;0FK5);Fq?hw>XRoy_GWbK8{d6}q?WJsU*BmH zzu8gjHRx+)a&OB~V|N+6JE%d@=<@OJ8&lP^MZ!dPul1PcJaM$kK{^-h-D7WMuCla# z67Y2CdK{6=iY?9$RJN{)9gWDFZs5Q^_p!M+G29VXJ@0bweU{~zjiSBB!q(>H{&$h+ z^$T2TU6E0fF6Z=5H!rwLN=R=LLTMjt5IoxX?||7P#%;o-kjr;hjZt(a3wl<1_wTMw zP5YNu(q|R+zPm=N?Q=O@ziXoC50q=XXl}`P?^pO9zE&LmW<+|?I_mq=wWeeFSL{XS zKK)Nyn~qgXwH1C*H^H-eJ@c?%zk68xjw7Gn%+vnzsFRaCF?lb(RpW3qY9jGly+wxR zGv4J?lw>zGn@K;Z?w{-;v$K*p!+rl@htW#E)5e;Q>aR4(m$q-uo=tyz>GA%~YKQz~ zFJaeVT-?np;(403z^#7jvRJR$ z-n(*C5s-;v7NjUr2^_ z$kWSUa4OLOl2C{jd<=g8iYFP2Cy?cZd_TfLc7tC#f?lmbws=LDrXio;{>X07?=@n1 zX`(-H!i2hzXO|%s!lBk4p|)Va9*dJvg{5MzXRd)%c?ppg%&%fMeJ{ z<;)|Znkqa?I6T)T94Qke1;$3_AaABXVbZW<^Z#(t(tW;_#w?a1K1oBE>LA!^jm!~D zL0W9zJYwz`CJ9F*X_0g?`~R2rm9QSO#vc3KCKjuG?Svy#Yh#CGV2&t+iw+y$$d;H8 zha`*LG>qL&kF61ie;p|C7QqI#W&4#xMM?y~hT{;_2unvOA3EBp7G}oEcBIAj&pF$n zVjxN++l>Q=f?0>7|C9RSCPJJK#mI0Z52X=p!m;}e3HEAv-}b~JEuhW32*xAg^>|FY z0tzaqrE=^+a$W#FS_^v;k*uFl9B`X0>9snqOfPNr+@1yN3vohJvla3GH}ER<+pl zba@HMsi%#yMu&m6wycj=S>40wHybFt~MV9`whJFSkGSCT~EP7b)`(}rOZsY38H1p+L*HO%SU@?W+x)Rg_=5lp)}6896*+_ zCzNOEzR3lNRufm`jg%^>RA7CwTDVAD!$09G*)}8nTN!dXBbKS6N2R>at}?a|hKaA# zFNA&sBeIC9-irzfNkguMxYDNi7&leY0*FT7*#8KKtRq9e1y4HD|4NdgXoW9*lgJ8p z;*&r~;vFqmuU0?;S?$=+zh>cY6trbZ?&p{PK+6CqI}V<@@q<&8za&~BQcK~@W-Sjj z^&RgzYB2;YS2Qyp4g(~CAcBr=R1&!^nHW%y45*_Stup~NZ2k7#ZIJvqB^f75B?1A& zI_l|YK}(i+7%d`k00Xdp6AS~x9vIY15hX+|(@_ML5u*sC{jYjzv?q1CVRSMXVF3~>;z{&N znoxBOvW^moJ#I}H)nvw2B9VA@c_a%*X3dV!XYAkuG;!m10tsot&Adzr6wxblko_9u z5Y-|?6X!lpEC-KHuxKx>Xs_IFuZ1A$RXduaI*`+lm0E%)YmgN!=3PKuRv;mWtWzky zy#fLRO|{q1b~KoDv@8k=2FqbRvNFSua(JC36(4&SKd#z$vUf+f7}7h{LO%|5bVXre zViP_ts&=krA;xU*_8lRQC_wrhpFUMcrNN=8-MY6n*wG;_22Iexbl*y+CKVfgMKSPm z#HMvegHX^^WW+fjnrxAebb4nS_6!L?zN38$;^R}yp_kH70TKk3fZW4UUnt0lD8fj@ ze^Dza5vP}*4k}6l2uAm+jbTl)KG_4g#x>|68uAEVRWhWHPrUcBPp?RJyf&6JqeGPU zsqDA+BWF~7vuN>{133WJiDukuy<}(OmPLI8QK|*^##f42(qG7XXr8Oj@ zV<(^^^l&JXnnAKcE0*|L>uzP@In@zJ|F1|bP?Ub0m(d+dJAD`c&*Ot{iHLC}zr%1lpqYCW=HlCYrX+9BQ3K9UW8^&mxj81KkkE z@@cfQqUDz)K%waf;5agSQ$m7R?1!)C;{5 zD@oLCQ=`BU@o_fwvx@puz8+Q|Ob>@RwaD=?%4tho ze*}GlLX)=BcKcBOR{=LKni>Q7lyr<^$%{qKh%Di}X=_ldWcLx(mY6W-y*wv~2D;3l zmMAo;@=Le(hq{9n8miL#g6gCkB5t&NSC@FF7>J}VF9zjn5E&WrP1-F@x!G_(&g!g z%d_gsU*0Uw#VmiTT3#GqUOrr2C0!Y=8d+Cg*?NNoIfzoI5q$8FZ7g6$x*C|ca;(03 z_Ga~|HjrM6@m=BtGfjWMLSNyi?7%hB3ts4baYV{PzRQcCe0lJo7HkBLXN&EZ0wf-z z;MHT&Zm(7BaAo_j)G-TuK1I+K4y!`qg#i91?gZC)L^APUUM|F4tn## zej^yE4aOW1EMG~kOV4HGeOAK)X57mJEHEc-*k!yzCvw6?D{LW;h)IU<(s8zAb_+xd zMOF zfV2QVIe-oz!56W|)QsOU%%L>Djv1dXC&v>^UqZ31Tei59vA@JS=CHLqBL4IfzM5qm zoc{~^as@Pj3(zr67zTU0y~W)Ay~RHMz4`n1FXrY7bA9^XrLVtO-s|e>@8vn>@(^o$ zU0ht;{s;VpIXlCgp8h>MyE;9+Jvq5NIl-K6o}ZupKbWtd|7YfFdkM4M`Sa(`gM)+J z-QDf&?X9h?&CSi*_4TcdjrH~Q)zww3@pbcM7PIso^EK-K)A+*7%v@pb)6;*ZCa)(Z z{!H{>hKH}P_rbwG!{#W4h{|o2=Mp!_w)0^N?%@HUjK=Dxw*MHJ3Bi%I=+4T7K?h>+1b5% z^~%!H(%jtq`Sa&yW@aWPCPqd^r+WG~+G4+zRc;g?{F0Wrl6ZJ3#E;=d{@~`lU}M0V zU58Bn%q|Sgo$oYs7)tmpoCE_Q#DEDcb#!!fb+xs%H8nNW)YO!fl@%2gpFDXYFE1}E zD=RH6EhQx-At50uD*B%kn1Fx)KR^F}0bg8PTpS!6SmW#d{rms_nJ)|h9tIZ&0|46~ z(0`I&`2TnE3;5r#FI?0yY#@18HGc@h>djD z7ptanJ|D@x;=ezhB}}+5Hmv(&B3If%_WLmW$yA}zb1cdA|B8JXRVX`A#waKBhk_k9 z|0nkKPNZ=S)q=&ooP=t@C(K(@jp6>xPs%;`rUqg?Wn;5l>PHKbA6?*0!-M}j_9YXH z^8=!=H&<&pnycQ?e7M-^vcEFk(PA_HU`|#Z9*pmpjju!@eCx~`7?_#?dB*Yg<>?-{ z#!^Vl*L%Fzj@Apq$P@nve3Aj#!KEblc>N#Pm%r&{AXr9l>TbG^=MAZhJV5Vpjgyz- zO_-Rr<^kbXLaL|VQOfW{5U>*QX6u!%htj>S zh-{T@=+RTMI|b2#3;7wFGC`5jq^+nK={LA%FFoy<@3G0c5ua|qC`_c;@h<+5g8iv+ z3X~Rts4*%Zh`IoBP-W|na(lOUFE(4*jPpiY)%Oe(Fgb0 zcf{2?Kz3R_|fuTJ5Ur)lS;}|C}hSs#eeasRmGgHbxC7?g4JRtRm zLa$QBs^#J8H{m*sr2R+T4A+a0XKnjSFC1`5SiLTOiWT~hbKe~K)8@iABHz=(fZ>4p zap@X5kTe|zZ7Css-G_@lOKxx(k}e5`0=VOymLx1(eIg}w3Y^N+uj)XZHt@ud9FLC_O4 zK5%3X0oEjrA~cz800qIB1Q1DJx$nCf#_}JEQl$OAkZpN`_g=K-v!2CiV?fy0`PbQ8 z5Y2Ho9r4|FnF+)J_h8Q`8rP&Hw}SkO0$6jdmxu@hQO@SLK&8?EWbz&-&C4I5+%lW4 z-*tn$<_n3$8<{Y#ODd3o5eO>T0)`7=M%JfccfRD|KpdM}i3EQI_6On%6C?yZvSEf2 zaP)~&tb??))O`VAIkpjAknHzOQeY=o*bf~@QLGWmpKZaJV*R8@uZN*?=s9fLhQi^S zld9N>Lfqxhs2O%w!OU^D!1v=g=R5q7;ijv&(l}7x^i8T~!b)tPkD&(fvOY3~PehNV zNfp6G_*>V6y#&r9#AQw~KVDmF;lfG04|rpDO<9|E(ko0HhAGWXiX|_UG1TTgY=%1= zCBYMA@W7XfInthi5<3aFMg@uNr;T5wCW5$>06EH=vC=2qU*IWpT#^85oHWF0Drh9> z#c^4Pgk3;^QLdgP+19+gi#4wKyj`L2cv%V^ZbICxuE_mB3+m@~g2AF6ik1Rk1UnXS zQjMqiB3J7L2W_lI00<#EUj9_`>vS%$z9bX{dso-UdGn^$gQj0f0ihWO)Lc-7Y7 z%gl_`gLnKL?UNY(f#wXJC_)p=Qy><@XLb0?RZ7VL*@LwoJT=aewYt|Nf9W zxL<#VY-P@ckJC@O6q7%@biAm#*Z)R!$2`tLpt0ll%i)XR&+`x0`Q)}qYk$o^vcFpp zmn!|)^IjLxx>BiZm(k`>ZP{NV9BeZA+do5Q7=(l4P4yP<9mxhKD?jlcLdiq@VpZ~v z97L-&@%?9YwqYidM?H4H<;_f(`%M*`hro%@h{r`II*-_rr012ui440%oH-Tjlhv1B z?g2KIhDH>H;u9y;KG~^GkNeZNRp#0k&Z<4eE6grN(q!aiNCVA#G33%r{9FmyR-&Mh z2_YhY=fEN&_(6I%Jo7}a;-Hjjp2FW)qp`3xn*u&H_A*#}Zo=!lA&<1m##}ygCjBX# z>Bf=}_gDb7QEAR$mCXlQe7 z*x~*v1D>bIb>k+IO=QFf>HWR=$RsobT1klMyL?^bZ3=K%P+mX72_Cgu;W>m zl*)>v1Qdx+ZOa}>p9E;#W1%Nf4th{Pw|8mQtV(||DE?P0rRC_|3#2h`-lNtP^%gaS zE-r$~L5QEGZwOTmg$06qEVRa)U!h;^mF#ciJv3nho7AzCF5Rx;>I9eP@pr1lzx;tO zE2}I*2GvV%uTCxgItBY=H#h8@*!JCS7t5jEb-x8W@J#i0p{#aJkPex76|?3$#5Oy@xKZA+mO3`Hwfr>Vbi6BOCubV z*&UEOl%_z(yniPS&faFn9>>z-RCT3F7ox=9DA?NA9)Q41?ki?Y*qU3im$ z>Ac?=$_)isC;Hsz`_-QCMa~3Ug;U5EFy7k;_=SV~C=}@C9^z;~U-c9wgz}X4aDQmX ze~*wvP%G4Lp8Q;fZXh9)?VMr4!WA+UviKozBNc)@R}YKyfInfsuOxi`Tm3`-^a#Wd zW&bfH>Nq0L@UB<)-F(AHeh^DDFukggUmr%rt#l4@m?`qDGihC21xRf_Gm zREMk7mu;zzB5AG>sm?}e9vNv6$26~RX%53_ei^BxQyQt#X(;OSaOKo6ku(9vMDxT% zOJ^qFYqH-Q{t+5>h^_LNgRi9FU!;i%^LaJuz%E*uA3QTlGcwEDGAqAjR$pb-QfJkR zWHlOPHG5{YW@NRuWp!p`Wz}j0PG$9oWVf|}W7}BcIqtVLswR87k)lD?yu^D*yzJeK zJkJ!Pwv?!h^oX{crHJ&Es~lepb?!!4+IOQ|H_zONZ>XjzAapln=PGBSGKRc4WSxH`NNk(;xNr^TfK1px6Idfj zsjl(~+e2tM0%bUhuG6T!zrNxWEfUE{z8_@IPyDtL4!w$pj>i{nl@cGoVS|9Iv`PW% zND=4#57K;Lj*UeuqJDGpVuzH){x*!}#8Sw}@QCye3De;)rI>e|0UE~qarh(&TOX{! zC03%Zoa~-?M^X_3QCyhIypQuGtPRG2qNRt1rBNQGUi>BKEh<$Z64`mt%=R*$OgIk! z+2@6Q(;|r5EogH#1qqa?E0snVmne!>&?!^9DEf2#dBz2YRyh)gtP$jeW>-dXeIO*+ z!mkiuuV`ARY}~7?*r8(D^^9q+I2R$F&hsJv^KiVRa@4r2*{fomvtVjZrB>eIi(MJ7 z_4`Ff;(>VR92)$vy=tZ2qHD@xB{N`*#%FIYA$^1`r(c6Ut$NcgQRavm{!hJv6-X0A z^TNVw%TE^`VoEHpXi(RGDsPOdH%98FTD2||Y8mVkHI9k!^I=lNKpE;ypJ*LLWWe1H zKWf@4{KcSHj8|DKlSQgQkphP`;XXByDtrS?44MXSA?xt*g2E{qri2>k#p(sGYutZO zF{1TcYa4{PB3AD}zH!1!;_GD-v!e@w)hhfnRI9b@OLe^UvK|wu54dj_G{i;1U)I8M z(4bH_EELs#b4nrc1{|Se*kkPukQJQtD-tdOhkbzK#iC)~!{PfK?1V(0 zjw{+PRU0ZgdN@h2IF_MtcxP}$(`XhY{Tk^TzzVdkj9rFf?a2D<2v#TvzFuQ=UW1Xz z5HIk;>uO1e`Feuu6WgZ}?~}YeF=?&rXnVBOt~`zBP=rUd{b}%+xC8)1AHbvXpt$Qe zdq>y}m`h`_Lg=5~vLgGnrod+Hup;;_&xg*lQQ?Mm1QQUlj9W)GsB+c0%&E$nU9>Hvc;fA}^ zBurfY0{Be1g$h_jXA+T zIxLTodyTYMn!pwy9Y-O`$4076;RW9)8gCwsdXBcIj+%Cky8USHrlruU)w&ez_(&3< zL_`;G1iP7<#H_(?j_4SWq~nhFqfpS>Y2a8(AYY3V)D0IN9t0f^&U1_gEDL}77eec4n9sa;K>rCBcQ&3>%={7e z5uG#&Ru0FL1t5o7RBzT`xlqh40KD(sq}y3t9#x833v*)U zbG_a(7JCywloidChQ8vM*54@(`g>Yq>~HKA7(y2+Bo@m)HdoxAEa;z$uUr^ds`olA z2`FF08CX24SePVTTBW4Gnu#s&rGC>zY3Idg=CU!&@)G+}568{)CjE?r6Nt{eX*TD} zpSpZk zh4OJj^od@3PZD@pc(y7od#!=1lP+^s>CINR4iWlmPvm*m2db8(dX}RD@pekqs})u| zNtTfe8zg?@Ga`Ye4HT_ zYap|-z|XKLXSO6_0r=Kxja{v(#coIzY(y6{>gF2gJA7BD-n8%fF5mF9 z9;Cr<<^97X<%i4dy6nmib4l!L!B;!Od)l>Gh?!IMtJpT~-*)I)GbGuKP$TD@+Uf*a ze7Sc8)Y=K<+oE&zV;OcbS0+e*u0P_#KNJ|V)7Z}TlTN$b^-5X${&0m@V>96=f@W&# zOnNE9VgI+@_U}E_4#+<3ojrN8y+<1R4HF10EkjF>9bjdT;2us>J$|3rLA}GuQ0x}U z?|{bw@IX6--fma=t$)<(nakB4sNPzh__?U@lg9~^8oOKJu&U0`tf|3|b6URJrMb_& z=m$Og#eKw020R58ht2lCDw(>Q@yqok|E<=32nnz}^lf{Q8thx)YS zhB^-CXw1GroILf!U&DHm2qfN%JdzE#2!I37aNWh10i@Hlm;fq_`GfQZ^L6?E#J=DK zebMw1etNBB-<1+66jJ4lPOMZ?=?#pdXG(G(*4HDVR4nGy}{%R%P#4wBNfhtLrFtu83 zR`-}I(CmB_L32o(ZjJK{-2;A-ZFu}*fYS4Zwq8F+^i83#Rxlvz67Me{JhomdeQGmP ztp5H{g0GelJ$4t*{VbCORKaMj^8 zK^?QGaMkqjm*@=*=NCY4JvR$#=Ib?hI>+=N;{wCk6Ay5zZQ>coCv=iD1eG_qMq~3n zCp}O?B@}DQ5YoG%^e`j4-OK{FWO8a@dnAws`53A%6vN z#(~U>af=9vuZ7~43Sj-$35obrO3nB}OXwAE9c0>}QluuJVW9$z|V^xse+XG^Bgz*(m2 z`fG>LkkAyH0k#FaboD2S5^gO4%{M0_Y$bF*Y+>e8xn3{UI^C?LU}C3rx-COd4b(uF zN3%g3%{%PZD9ba%aq4Dv-ddCB)IfnJ7uD0n+vWWs0b}f5COR2$bJE{(p#eJZ5L{SF zDWPWF*X{4}P*J;(#H4n|(cYFZIxqm_xJ7MK1r9r^?=ckoQo3JY9zC=8xTiwhA;-T^ z#MxQD@suPm!EivMua@vaGE`<*zs7y;njW7_i;72UDrCKW4GbFUCY5}H5-n5(xP|4! zbK?Ctip+P}k7bz$I75GJt}iAIiN@lgiGAS%PJdeDYc6X8q_fxVPNX(7zjM-3%+4jX zXMY0S8)XpBDj@J?7p^072qa-wqwEw`ln8M0w9{i|$OwnOvaN!yvsmb(2cE39IR(lV zSu$5y4PM4L#d)bQ0D@ogo(r?a#8xshY1=6M%}~D!(z0Tg>l?yYAma7Jw$wetuiKM`_N*lFdXYJ>l6cM}Px_6#NjJu}_BvD@VJ;uAE zy_Q2l)tY3hQ!G2X>?RN(OuG3(0IuT=@70%JwS)!bQNyLpncjzoiJ-}%s2e|Lkso|* zNpAmI#M|^<x|1h(P5AOmL3Bj|mJX2GXy z7>6@P1C?K9HX6aDdNm1AiuD~EdgIYGmVaLa5_dFp$9x4)C!=|--P^(GdIUBZv)jDG7_kDU*N-~fk| zV%vsOYy3{fW0VtecbMpe$7?~ju_N}s;7kceBbm8W(8Jk($A z+#emLu`U}{Mmbtuyky7uX<^)^7*Qqh#-8fe(bo+H5~l+T7^{u^e1OL9t8j@Oty^2M zk(Y-hP4s))f*qVr)0wBJXQ}pQ|=TM(Eg@U}5J3bY%37H2E06rW&xI2QiFz3AI*8h7b8%)PBSSTE+miu7rp@* z5ZjW0X_&qL4jVT##g%=oF}q3d@n!2}^E1zz+RqKa!?2V{xr=pukO@Pnb_4@Bc3K3n z^MIWP{v%aJOBvsRSGA)49m0p z80;ZIxn6!Y%KDZ|hWuV;i7D$sElfs42_!1oj%Cj%JK{H zE+s1=^`$;{mZ-+4-q-UuCJ9I+nou9B$D=~tdEfx-fPFXtKYI}Nx#mZO=>UOGq}%65 zi$9Q8Kj|w`^bvn_T1_KQ%*h-3G*RZog8>|ps74bI{D36b5oCKL^h!7=*dxHwBh1AH z|BD>>mq}}=ocwuKo-Am<2k~Sxt54j1Fm(#0v5v25JmBubrPmPqhX^UHd``$W+RR|$jDI5^inl&FML)fRj+I`mS$)<ZPIXN`zLeV!`2nz9FH9Fu^4;UDlYqWpH!xX*jTx zY`Pw1xA@3 zwGC6Sf%gVSt+EEgqbZmIg5iW}$gy65G0e>O+S%6;Kr6mCn1D21eqCTZw6ps`g6gIP zU{WyNLl)O95bUEBZimF@awVGtNbi*;{KA|3u9bM)M|vzUNiQ>bS_v8}2%Kl1JQa_* zOxD~s)Lb-2IJkUB%+_ee#@gE^4wfch_tGx&;z0^ic=}WL)>8y2a2X)q7>-9+JVo3z zbzKYp{;0xfWBB%7*27&yFj{^2`*?_w)Wng-T&d<_-sBzYm}^&UmVjxhXEBspF$8G* z&0ySbSd{fpn=xm4en>Ncj_pAf0MnUvSSB8NH(LByaTZL``S(7Y}$#bbfjL>@Ny zRXb3b#|#Txdc=Q*zw2qJWPc7eSM%Blq6H6$(2usfo`?eD{SU70!mX+J{~!Kg8!$$V z7#*X#Lz>YcDJjw=-3Ul+Fko~eB@F_C0wRhE4naggNfi*0R7z4(WcNOw-|zn3-|PMl zcAf1y=Y3v#J)aNH3GxGfy=~;@6$%pD-d3yQDr>KgDvdKX|De3mPaQhI;L^{woX?uN z)0yztfY~%p7Hp44mWu?JgQ24PM{bYby1w^SmM)>!pOQN-fp2EpdYan)oUzCafyC{n zMF6BKCRD+sRfZiVp})Dpyo|ge4U#@Wja?sTJWqPMb|acp!7nhKX#`6M#F5*(ChJV3 zI#^RBm~slv@}j9{CC8rT>!}rdq!5sPs<8w{u;?fE8Q}ENwG7GPpOYDkm||y1;_az& z^zLs!Qg4CgR_N?|biXpMT9sI!&00t`nn9fI@9KYB$9$xSvL}@*#Zm8L@5g_TTp6z+ zt*W&#PHTTr_ZEt!CM!me7|MSQPnj#2_-grmo_EXQu^wlKp2@wphOh2J1xhKdFC~kh zw3@vPHJ_#@0N1gun1oWADm_lVMq-xf=EBsirht#IS<={2QjLk^Zkt=3oZor`C=!(% zfoM#O{laqrUYYoX$68u(-hYDY6p$3MmtApm(I3;8Z-T99k%#E$KZ0I!wJ z;(GQ%L9ydbq*0MH#)XBRh)W5(ew)oUG51Qp4H!IcG~tEWy5_zA6Cu?6qb@@7LD%&0p5sLOS{sJDTWJ;4nH&$=A>u7%`B9U-LyyKxW46gEQ(HDh)Wep zT@iY;T&n$pqlaeF2Fe{x&fTvLF1yJJBWdddJxE#7r17vX|604@0@#zV=VYv!a#AL& zzV%75-A}WBzGiDrYU2uN#8t#`a&~vyAGfPhL#k^-k_3xHL%%oMc{_UsJQ<@XxnCWH$v# zB9Lh@d0rNatIc|znlvj}xW(*)nv1}na3(k6QY^vR0%`*=tt$MGtXqp?qKbrr0DDM) zFrXbRjM;ThyIM(7^vRVbX=mj{wk)Q4|BR0RRfI~8!I7EoV|_}~XudcY_Ae)X-oWRj zb;+i-rC{y~`iA7pxa#}bT|q&vu8tPK{4!WQW%G{Ytetnd3@#FdL;k(R2T?L3!ICOqWXSfg zbHLjK|L0`s?k9|#HyWF~mP@^Fx9d|7xHeLwiSQVXJSe*3@OZQOljPJelS@$GmxMsW zGAHM=yvk+pr}mwb&;HNHpk5YaA)X|^$$rQ2`ma@GBsZ@fI_C~~?+&L1wk6Ev?t{Oj zYYBBZeel|ooB3UUyPX0DN1p}7$%^8c_T(XGQ^9>(``^z?{I`1oQgE0@I#A^MTltW-y~K z^4NpW*0bM|r(ym|A%#IVVdO@HtfgBbNtBFt>;#y@cwbA^Y>+7DCHEeE&OE6jEQYn< zH!VZbd~t5RA!&=+!H{741#hoRVGII@S7c<^gzWM z$xrixy%HiUey!RNaKg5CL{cMrV0$-dGs2MufFUFTdgP?(X=t~Sg5Ft54xuoJ3^ZS( zyR{}f5az1K3Z&hsnZU*vrsybPt#N4w(~+{b!>_&G!Q#=QP7#0-aPiddFVkt)+IB|X zvo8;!T+v|1vX50kZ3JVN(*`8O*OmMZF=6JzhP-{~aqT3I91Y~9gqz{UI>DqC$2qiN zVdKyuE9FdAlH2=f2@@ESYbl)X9&qJGi?fC@NQKh*kKb)p#0sw}Fh>{tIKvM>pXjJ! zU2t~xWGvBXWr@jw9p|BUPb$gt?+e{>c`d;U)HbvQ>PX&=Gd~|bXnRx#{ovo9p+rnt z-32B{u7d9LT==)S@Mq`#!9;E47Y91nk47{FJ^K2$FHPWeIdt8lAKZY8GAw!~1@^0o zHNHmmGMBzxD8gpFZSG$RiSx#{@7vDYf9X_XCyb#i!uWRAyD1i_CW&br!hlC!?}&?7 z<%2l7&Ny@P5W;p7_$+~I>!~w~(BJx8wak$L&b2hIORWqRP=rNloOEiSQrhyJv*8yP z^HLP-k2Ai#J4p+2c`PM`#bq)IURuy5u&aqEc~*~r0R^E6)Yy~{%`DylzEKEfbjem`{H16zo+g1f$A@Zd({u+(TZe<`yL|S7mAuU zsZp$QQ>9N>w72;lA#sVwpu?TbqX(uA_)FmbU|+`fXoeVbi#U`USKJ&f==HBR2|n?Y zc>na_&|_C2MGixBiMq1@G-G1W;H^F2zA9LGow?QtXXiDgd-mHZ_oYBMVV5!BtV7or zugDX$b0)KfTcV-Ug?thndxcX7mSitO{u-1Jn5%z)bw!KDHBC@U%pUuXOS&BnS$}j< zFp<aOQ6)v&xTC= zi#?c<)x>Gt(=wo^tllFC^cD{B`A4s#71)PhFPt7={Z&nivA2rdlLFPt3spWoc2fme+np&*WrdJlpMwBBG#v&P{8z3r% z?yVPMy2!JOhvd{t&qb2&SHT=xH6%LH)lVke;L$5Fe&R7hO#bb<$&VQAvqD4wtgx)H_CNLM)IHQ50zftq7%U;uQ!{aTao?=L|U05@y? zT{cIPsUblG;;B%!14H6i1LhmSQ`YFQ7@%FRG(vbd3_Fs6p&D|XGyLE54lJLzE5sMx zSi!-|eug(tT$8I7_u7+T8lkQ7Yt|WBb7g#|G%V}`FZfEQOHS}f*3#hV%9C)XF^l76 ztQUSOa-%cD_7yMFljgS)VV#-Im%J>4_HR+Mb@E9yb$+`5RHmylJ1CBiV^w%qudPGS z43lBqoYeSc2QDMZYs?My<>sZ=<;+4?Uv7|VGsuRKWCk=)a8ta88;2E8L2T5k@-(Sh z(X_#x4G=L3WAco!B5LtQz-C0W!lX&|9-)kfn>6O0WV}&HkE1c0D^E7Fumm+dPs80y zo_;J#j{m6D+%ne@&RhLDQbY!iID?bY9PAo>?*1wB+3H>Ke_9tX>k@nJSOY!L%Ac3- zk!u66xD5cvu^84-`H#^AX7DK0A~y~tW9uGZTSTL^Gg^8Ay0U9B4cECWTp8u@z`WU zC#?Csa5>}mIqUU|m~Yk;S)RIl>^!;*gqruT8yEmAGofS{T)OwICUnP-}B)BKH|_46qO{zEvgF-c8wu%KQ|!qleO z<8wj$ye`EMdQO{-9xbw83u7!7wj$q}v6;u3cxy9gj{!6R6Q0m_d4n|bOVl3F2Jp7e zTUxAZR=Bh;$!80F2ht?61W#UQ?Zi7cSevA=(;0ap$$&)Wmw^km6ovu!p? zQU?`aWFgT%{?Y3)d{Y`!opQxRC~5ba21z!h!VJLk(LZFlZ3_akfBW{2K~a6z{uBPL$Bn zGHv1*AEVy~kt7E3n*&AoQ2)>ngPj_HLaOYIKxc^Ir$)($&QYh0QGJNo!aYm}ildHY z1m2I43>rfr#aYs%+{EGWEbho`6ghAFF+IoMGeL?%z3TIC08b^4rNJkMf=K>ZWeF92 z1e8lE3`eiE<7RH%FW;n>D3I5QsWGGfQg)tBVy6XQW`IST*b^NjT0** zJ7Z*@y&!$Hq^@=Hw7oK<1CC;5F@>z%ht*fKi&QrZ8H8sK69jigyn+pjS} zrqN{N&=qL7t`y0Bb2wakF+GZE*>9f{C%;jV_nl3Rr@-E1JXvFIC#Z3&jQZmWBC#yw9?mFN$_pZ?ntm~%euXYM~JCOk$i z1-4vIAvQf5>a=}QO4bUZ2DBsixaWQRzn^o_gBC>XS`+{M%o9Jxk6#JHp1$Klg1FRC zL31Nkianez1zcCsxQs5T9d6#QYjQ3XxJU8p&7XWW#dMo5lAzf9PYjKj*uUSOsd&Y_ z4WIq{h3Vt%{vW=y|GFjKcHrWn1(G%YzFWH7JbFOzj4c>-Itk1DWoMW`lHBm`$6_OQ z-x=3mfw$q4+7SY}Lh)1oK4VW)^dQE_vjbg~b}QAsLINF9yBR736p#~3r}Vk^MXD^t zStR9Wbx?)!@AXLi?5MhisHT?mC|nFn8G*H8sW-L9RaXF}t;t<@*6THK_TDD{f0fev_42IYt&T$cqTIrw50k~x&pe&EBEPrx^ z9!Abyjy8tg8d(^WbX<`tFq4*iPeD^}nx`*lG&C(>W2s!P{Dx4kdDOPPdL<=7y)%1YfBu|9K~mG_FB6T6+ZY)zI7B zNSn{3s=-`%KzbG|q{gJ%?UBmQL@X3Dku~2p;%lE>+crfdTvGAJVGL7-fc-(ujyLAJ z7Rt7x$}jBa{j#!*AN)xgf(jN=ba9uftUsvIq%-5)=lE~Y`mun8qgX7uvC6cg8n@# zH+k2Lr8Apx5RaQ$;Qj`qAYOO+LcI*5;CW6kN}GR-+U270o;pPM66`A=WWn__(*1#Z zD^`16M^n4$`n%{=)Q5*Fy_Yz5=o_zq6c>i_+$HjX(=`v*>mfp zK(HdZ32eG4Dqi8lD(6(AsQK@~R~+nNpipgy!euf}K=`Dn(R%T=7Utuq2`=IjRf^=V zEZZik`HgIE!QP1GiTK;mU2ZPgN#<-rG*|)^Ta8Z!S!1}$2FW9A9y~oCI~4KxLBdb( zOoz?pKp)c}Z?+2(bXTnul}`W>m+Jx-2yP}xwp=_F(vDk^3aQ6B8wP$6F5$9H_0B9g z6uc+tMyH$P-mxsG`-Yhx3&&9ZjS6~x%mju%&`tavxhw-~FD$Q2KP>!=&Of62ABIIp#o1hh`X5dWm`<;VMK z)o6`eqFMw+vp=jiCe;?tqorq)H-pL%Wu~ZL(V#AN+PK1sa$99vzAepNML8ple~`y`mz8iXuZGw6=Du z;g}%zm`JyA0I^QC?*;BH*>^fm@z-}6QHFz>8_Dky0?JbZOtjnR*RJoTW0wWq4}9=< zW!(|wUCCM8rgaCRr`n(|v__DVpB7DfokgZjatw>mv-oC1`5hk7-yd?sTWw3*-?U9% z)!dtE8&*VVTqa+0{Qb+by>YQ+L}TbCe%V7GV#T}t#hqdCi|AW3<1sQ$`sWh-OGds| z$-gJszt6U}k_CPCrSXL)3)2(Y{hkXfbp;HSw;wI9&*va#PPUm#QK6+;BV#OU!`W-b zVsj-D$!tS+;9P?}{7pA@U8yC%;DQp}>$uM_%x9v2E}HlWwz`AXl6K0IcE4-uQs_br zQip#0eDtfT{ir`6lOt$C&sU2@dqnNgA;E>-^j}=W^Pi z;hpx|+Q{Lfz?#rx?H!&39DUjy=hc1Bi!l%H^8Ea(T^sM`&3zzq=_&{vV2LrF8lqlOTvA6j_TOC1&K4$|AwsRbS9To6(!3JKvx zT^5wcR>&`vy*1~@K~03;C))e;G=L&;p$9KLUKBi4-Vw_*By*Kyrago(~a}vRhA*DOFWrG)CA@1~$hx0nqy{$q6TTr4n4}nBMVIJ&QX?`d}#Q{(+ z!v)j*Zc70a+e`>rMTLosHo_N30wR0(cfZ_z247qHIW-P_Ywl7d(D8jjRr zl-Xi-l8l-jRO0^F3|-aM0Q2|zbp>H;{=#n+wH03ts+tV4Z-_`ga1;OIDO32E+wRG@ zAd;krP7)B*g%j{UyTUn+4v${6t-dGW_=Bd!C22r0eF;ZUMd0~WvSjX&kq_0o%5eal zq&%i0Cw?&G+#zRlBv1G*OFdZ13juxmfx6YKYw$-uyjw~WqAISfN$>=tbw;FRwb;|9 zQ6JAewN=M3EJ(0YGrKm&(e4{rSz0Xh8l_G`$1Plk{&s}fv>YEFif0Y1`LJD+@B`$N z%<{Oq1o{am)e(e3pi4The1(8&8HHe85{Nm?y&)3aX~we<;l$&%swa2I1|9>}MCM3s zUq`iu%Zhf*NG{*n{OLQENfs(y`JGPGQ10U~^M84HB9`>-LOtZQ^d6LOviwx(Av9QT zj@*P$;Gua!F45y%O@BK|5$ttBXr7>tPtuYHXp07fn+I<&hg!*TlSBU4?nP!oX*#+% z0hYny{qpMy`5gZgiGEiI#P{6QQKV2nu}*4(x@+9Mm@nTohi6do|u$`BcB|%2sh~6gNPiGL=K1XehoQMSrl#{ zp^g|3K1*hYpV3d@53UA9g_JTZp4xakwXK%cy~by0?n1?}Zk{%Tkn^w%K4W5!)b1c? zE3N6M$m^t6oIyd`m@cKv5eD@+s|qiWYBR0rw?8^j^4X)IqKbe++Y|Pe9)f?POQW6} zhd1+)bMj(MG~jZD)zF{mV`!m2%1b(OXZYW)=UKOVtA!b5P!&(O4oe>%>wb80a`&K& zc>(Cq9_dIX?^afhI_9Rl>koZ1Dlc~{K{oCB#jlJ*(V1VOVtRSEJCL*_*2RSE~BQC6=nfPPNsApjxsW z<7s#YA%tD_T2{-9eO{<~)!);JK-UolWtwBD694GR{k5OPy9Flg?Qn5O{cXMWYLG$l z(I6KTt24q+jlUP#YH&74nR?-^i}ay^8aVZZ-+fXTr&n@bvK3oXjM2nW4LiPix*GFR zOtktN>cOAUo2OkJw8y*#my6VBo0Ks&d>npHZCr`BwImRBSZDcg`s)i`@c9$+@30Y_5f*S#*uNK}YO}Es zo`2-oU;fqFNbh>k*LSMaf9v4~+OIJCd1#1W0BJMqJ1XJaCxIcRDI3D847qz#*R89fKTJTF;`HAB#&^k{*vpTx4UvPM9+@d zI1gR4`AckbtJlU}q@(YiP@(y7S+e#qzoYsl#}7R6$fUX-JE_%JJnnxV{9=Yy=0j{a zJ~Zl6lJn75iH*m{!%=!v9JX@H|FpXKYVN(-@CZIJS3e-69TetZQcc7c{++!e?Rci~ zzp*djkbz3l|6pIjqgCwygk3|v84u$YBjZnHd_S>lSSTb@qT74JQ@=z?;DzpgMyI9M zLX9B@w7O>1nwauSt=%7*VO&XqHZT4U_9fatp+oSVDG_aV{#^RBh9UMC$JnMKjbhY@ zmJdN>+Wdag8OYF|l4%h%(h~k;cPIT`@D!vY zt=?;A8Uw*9R{s5+%DvvE9_E<#l8;!x+2)&u^|G-is~!4GKBv*#=5 zcSGRc1HHS+qC@}aO-5eRfAiz-(6b1be9Qd1l^~+~z`NmKu+fBNm`i2j%?EKc-I3q= z>!}fsbZB$2j|5q0Rr23AfhYos`u>A`(KE}p4>$FArZdEb`V# z4CkS*jyU{KZM!5WE&6NBYJ989q;0hEN-Z6CcgK?VQ2|aa=oRm%hx|iSAzSGCX8Ch+ z1Ym2}SP?U9lwvGb>6^ysJp}im_8d$9#ij%0#j?kBVLW)0PveZ<)|GG8d~u2~Z8sl6 zQj6N>`*a#GrN~YJv}Z$W9UpJks#APw90SNJuBR#K=Wx#N53^uY>>m_!W2Jvqrm0Yn zW^+n!8qi=SmV^qC+LO1TDL%h#8kl!332D{W{!rVyzDjVK`S_jV<0eJyMmouyGS~Ar z_0-fkOtaYbf|;fVD*H{;K9Ul+yf}KGCd=sMSsHnAk*{8jeF3Xaxy}B%uWO;1q;VNE zXm{>5sn?LbZf%-|QZpde1}1ObX;tJLqy^)GU4#k}0CR zDhenIh8Z!#1D;5W4jCv2zR^T6Ud?c$NjPo<|84JexG0O!L!x82?3Scc0@FBDlJm$HVW|>FW5r>xP^eU;zX6x z>G$G>))2`=@~W*$s*$%`#z;}Z5!w4m&;Ii=K`$6tgzDXh8&gk*7`tE}rmQo&6I3C87t~j3H`6g|%e-A!z}J)gTJ(-s)&qs40iGf@`Q0+yuV|sZC0C5-fU>GBFIB1evVb-*w(ST<@^~p{LO-P! zM!)f_l4^ONo-Sy@xPIM*AFc12$7+UI39LjOHmcD&qY-pGKM))|o(q-cDgKQ}VTOfyFM z?;?#|pN%k6RUF|L7Vts)_oM~38IOkY8z~1uY?>zId9B+;&5mX!)u;gm%v_npfT(nx zZ97iG()S6JH_6KsbKhKHYc=QWOa8_aU5EP&iWzmZw^NHB_p$lcH>lWDfbftZLs9J{ zAJUB8r)^}^0bp`f%eGJNAKAdPUEL36`-4hU6P;?j|3T-mmB+~FS8u>ycpYl&KTG7d zH~YI#n!FHf?vjSRQOe-WF%2tuMkH&vZ7N2Wm>N3L6bvP*6$N`~Bp+p)js(zIe`AsW zRP|b%gF9mzf2`bo{yN};ARcQAz-xR_trk&q8H*LI%+))Ad&V`f$juTc^*IZCv#a8V zC?W8f&*(oRDyqMv$qBnq&1cf zQVRNqH$I(Y+UquUl7L+VaCk8;+efSPryFC$-S2T_j0k@ZF?rpF5PNO(KGa<{YfXCD z(zxv7_u4MkmsCG@d2L$2A`FbkH}hYHW18G{<*Er(KV;?JzrFw2z%t^qw;ub(NAzKM zO`*1fDzgx5#pY2yN#>@>W2J|;6D);HwEFdOFI2Nr#cTXk9I2p#&p}4kjF1o;>rn^7 zG@kQ`H5qlic47I~K7~l1;OqiudpOc0#r)RM<%adw@|OephH=#0+s@_{k6$x2JTc(K zxQtDGCaVM)mVDf~;$?lCay%aDT5Fj*s3JiOCOlUN4rr_WqY(_XCfr zi0|<$Y%*`oC;p}}XwK@OuLs9)S6{qv!EW5ry*nMut0IPYgr`kB-X8SN`80&Gw}Z0Jg7V=$<=cJOKeWXKdg$){_kxd* z>r~L>ylLT4XnqLIb$+HX9_|l3On1<$ar;Q03CeCHoHP_p(FvzMfYZs)k>^tqOA;9m z=)jW{ewZ!1E9jNj#u62S932g(3C-p{!x45VE{Uuc4>dVpw3I>Egd%QsBAnZE>ZShc9gmH0CF{cCx+zfl<5X4Ha1sy`M4)IJ1OA=RA#e8-6+*X8= zr})ykm~!!)_nRoP(7XWyj8+9)y`j@JUEA_-L5ez3!W9p7UA9s+3b5;W@z(Zf*JGSr=Wnq1lVGO^ziW{aR$&<*hmYuJ%rT!htQG>-@w57=lIVqnY zDwb$ulVLe{#%W(>hj0$1I*Oibdb0zGiY~?P)Vxx^6$?j7HAr}Dc{rpC6}xklK8A~Ag$v}#Dc6T8 zTgp(tr(sM-jGKlmB{eF1M|~YnmYz?4sWG^=nR<&=XdWu7M1p89RQ!7cath;>lH(zeArT*H$$cob5b}DBLQ$(!E zghwd$cFQIoTu+oSIhHXcjnpcek)EG1y%{Q;kAjux(Kh3aZ_3<{9?<5oGLMSTjIX18 zR%l*7!ApK@b`p*{_?jb$`U-`5@Qc33{1gFTh*vbi-Lc9TBb#^r$W?ij7DjP3Ym zgG6hmgU;(hyQ&}LoVAV}^y-|iBdDyWeK)LG2gI1|>0E8HTrs8|*O)Bs?KmM6J<}|# zD~hb2K4nU=8QNc>t+8Znv{IM6b5pLw>Ls1S=Ao@Bou{6nGpiy$$B9-U{+65vtN>|T zY`M52=lwC#JMe_sx5qnF(IV=O-#OfgVdeJqBWJxa*o>^U-6T_1BSJ=TyNc;r^;6&A zAcvMafiDX^sXu#~+afAZ?)-|1gg!;YAljk|72s78Fj+DHxq~c^bX8~iK6?`K?M?_e z$R8tXHl75_1DLW)mhl<&Wj0IfeU zwa=nvN}{5^MDc*4$2%$X!^}hw_D;_b?~V~N&pgdz537wG zwLwpQm6c*i77L4_wD+Vv^CK*uXrUjoSO{Zwa@ ze-%s9vnUu8*o&N*zP3X=$l)p|PLY_km3wYZZ5yBbB=zBG>R;Y88%zDy#V~tj{X`{1 zXE)Qk)5WWMnjU9Qh;1KbN}if5JT+&GPZeE?k21_dDebAv(^({6Kc9Oso4Fl!_np1n z=q#-ci!hJv&@LYPtuWhEMmwQ4P0T(g)Gn1+cc@yNd{pXiI*Y7P@*1zRH!aM|M*0?o zW|{}(4?NG2dph8wR3I>ye$IGQ}F;o7phr(3LN;FyT5rV(uYhL5lEV=hEvVam4J%A4Cy(Y}}$II)q^ww-*AghU% zauMa}#w>HWrd2sbQs{kG`$lBgJ6Y{~rW?0=EBuu!H_s{tl>MsbD#H=?nV;p}ql>h; z=Tj)BJs8ERuDqaoGrvqZ>Y9Dl`MK4RPdP6$M#7TGPTQrwQkW3!7-_)=MAI^jkKRbx9zI9XVh(?n>1fE z>6F_R$CPouD2icgjE|A5WTa?DV{R$eCo17yyICv8l->x(-N!Fy8K4V zK*=Wa)aagEX73B!;N3@rGL?JNQEHhTl^-v7+VqcROC+%SjlxUq;tC{kciGsFTp$P+NCHQou^F(Mm(W zT7Uh;5Rz>l!y#L1<1Aq7O{&Mk&iD5Pqm@kd!a^3 zcti?xdEI)kehWZ44mUb}A_Y)O9IjeWm=>3|sPoT8XC($6`a92lbv$d#HwG&Q^)aWs zMg@=4b!(dSo)-1q|I%Gi=b`cQZd1Ca37MBQ8Ni0&OoamaZmR$)3*zqGWz=U?)Mq+b z5W~{Hs)`U}=KTGaoS>)r`mICdd4)*V@ZA?b{bdaUMur27emNOYPI;u{zI>=v-d(IR^e?

{pnHW4O}0aFjvB{zKLePyoBc zodf_gw<8^X9cLLmj#S&>;NjTEu$>q?3$UlL=Ue8QKbLXj%(Yug#ZV}5^y;X#d_5l2 zdeu_wez#R9yu%>&`MX%WLEOl@59GX~&t8pEUyf2}|6UY&_fBmG#>3611+~X;*6btW z9N@fn%vN6^MyL3vI|o&n-=8{;+rx2S%i|H!0^L22I`jCC;DE!{Rfx*=W4D8FURl4ij(i2K6o>}^O!x|sZWH)myKSekZm)c*SA2l<)sVBt5vsG zs+)z{>9d=hj4n&u6Rt>O4BMOF-&eK27jp=r=8(nY&s@?QDG3|t{Tta=8~GZWDg89h zYc}s+ZPsdR_2Mb}k>C&Ggy_Y+4vp=DpzYqp-B(xJ>cPMGXn`k5rNfM6Md@WzYCQ+F z9DcFogx1aSuv=p;8cXg8KS}F;4shIIs=a8Sh3^Bjo<^J0gnc@~ek930>+1tf!U2!w zp+Mqc=-$Qtywlzl!*9+Xq}o5owWr?Y?!2wq*L8)s+!h;`!e&DY0Hgkv|&6R#h~ zR@KLHODCb4r;&-L;RMix)Q&;op04KE-{7-!?tOIiSz#i{*kXg+YamyB?q1)V^64wa zZ;H?E`xaL=9G`bqb5l@~aKm|^wwUP_mvEQX3u3bW>5oSh6^{_fZK~6|udC-dv^Wk) zJ~CMRqc~mZ{6QcAq45|9C7arRC#Fy$_64P@)lQ`ob9kk6;I2gs?E73oWgGP11Of`D z_J6Uj7jYDFO+@U=pKA@uSN}0jB`RrWlVSBujb<7>!uY^Puf~{1wh#BD#kxSS(V;Ix z;o+Bd$CnvH=SBYZox~b6aepSfeY^jYp2$pFkC|?nmZ`qXYmXQE;);{9za2~14%kvK zlbI;C+#I~Y%3k@6x$*nRf3dH!U6;4coMOi&j1fLVxAgwX$CpRwj+7ac1W>E??96r7 z-q8(Yhzj}~q8#;8o#o8tyMpDDNAV%DhwEb%s^%}xB}2=ny=4~cD3%zXGbGmzK?|gaw@AB`dd9`i41jTcD3@PE$DQl7eYx7k6 z&&^*hSb8%hc627u{z}!7DWy*niV>#A@%RZ(gpTJ!z);agBkq}!{ZNlA*-wTZ*@}z* z#lA*7ay71?o_X3dMr&ENH_yJ^S!gkE_cQMLycT4xt-P)ysPb-7(;?`+*FEP13hz?) z93$^C@2Yg~a=%CKy(@zHDQ;JWeKHa%GgxHu3XR#ixgHXG<5cKQyx&)+LOVq}REFLc z+;m+IXl|pv;E-jrp=92Ev$1@*bTd2ZC!=s|ZH7v7Tw}TD_vZck#?`eyEDag3BkxtV z{e|YYINHmX-}|NZU6gM`0-f#MgFoHEaibRLS%YA14ee2HF{tHEp#H2eG^M zfbag5==vb}@W#{jve=;RvD!@5mp7eW@)wR6$A~{;{&YRqaJ3+l9#V}0s$K)c&Cvm{ zs!)ih+@%K@b>;-1GemE068azPD|DD%m8x@?E0OB(Ek~M3*n8I8fUpmugXqH#l8Fn4 zqq3Qo`(ujJ3!xvpFXh0mH3(D@6Y{?uZ%^uTXGcsKOMQ%(Hq)ejTH*~gjr?ru^4kLB zJq91r)LNkG8FEVGyff=@kNRZJ=SSPgyzH~zJ)&ygo4wBYu`k7`>;u&$PP(Ge{LxZTZE z;|G73&F;(7D^*~C*5&fxz0{9ORJv!fxk@V)zrOrgULl3;{L!xJ{u_qiSEv!O@k^Aq z(lpH-X&tJaaPG^l2dWp5d$DI?BS6tXE{e*N>_eV`igE2VjK%of*(V<^pWoKpUk^so zX4RmE;FMuw$?T=b5wgb*im{V=sdD1>)U+i`Y~^}s&dYAJfzdD1BD6U}YX*>u%TR#I zm2Fabkk*zbhX#tJ^Q|FaEs&vsz#**gA})ZK(Ixyhq#K=VlWIT2Cm5P;8t2aV!2Ye6 zw0<H|2JXn))W1gbZe(zo1qH;(mfwLuUZMY%HR3|hUx6G}|V#rrBnYuxNWt?X*6fbcr z_STRqpKcQb9+iDe3V2c>mS@0DH3hvRk3!Zj4cp9!z}$scdU?WA$nRWA+Qi#Yv|9?0k$Cuv`>vY zG9%<2YnsDMy&$62BvMqXM$`s?gSgX{^p&$P)pke^WWd=wSiiA#{ePx=zFSuHFU@WwgZ)xG^fmA*tXYG1n<9zpNXADBjWmGipgY!u} zDJDe*QfKohhpD-{y*==@725L5gZpYiS9{1U3n7nWAh@PpTRxx-5=Ve$l_0>QExq6~ zTO=Xm>>XJ{!ME=xC(i~rgFF+~gk)&; z^&4xVQAnLLea(x3>?#u1zTfe|Rx2-^p3Z!IdFG_2r}+VPdE07X?4Jgd;>f< z?0Vm6E_#$?QlbB6H8j*o28ewY{zKVXLLEIQPZ zi1m)ylaEI~U`2T9eB>WR}d>@}*X!lBs`D&gm6b1+rZ3D&DR)X+}?Fm zMR570LJl-uzTGM*y| zxkLP-NsY`eG&%CYc^MHIyFlr5RO?jJg8Ck$MFlupJbg``FuozIr$s{xRQat_w}&Lt ztf6VF0vh4x7Ff9bKu&&`7i&5^iKXaZxVw~uV|G@_&K90yTggKngcG+@^Brk>rNxMG z4HTT0A(ugdIrMuz>}LiW!{w9Vno3}WwgW4>qIw+0f?NcmjZ@fgrCC-=MMc!4%Z>rm z@9opJ9;Dewmw=$zN=???Gj+K-SlP<~qMY#QhwjmT}ML9wZeEV>;Emav&TCel2rsXQiP3!lDV zjx&b#3<>kZLyx4roG`97&k@`yWQ4qMkQAj`5{LQ_bQ*w|q;}dap?>QFkKmSqP`>>83cz04)|YQeP2V6Hz)A)EyJq zPIQ#+!te(nMNXa3R`2eCFsXh}Pynz6et8wF`pk55i2qwDx$oyanJj@ra7vST?9-M?lc^U{5V<&~j<}CPh#6m^-~~=H zqH)iwcwtzv{l02FAL{%Dk%Oc;-w$zK7T}Di)Gb4Vp*0rZguGjBnYpD1ySD;njbXpg zv>#E{c3L&JR$%f=0{#>W!#|W*C2jQQK0~rMC%xA zHJHO1dx{$@jT>$J8rNK9xCPDj)F?dx4wz%(tO6MX7k6SP%J;B?mr z(oT}58ft@Rr@(T@U^ryjm3kaa=D9?@Lkgt25@?e1z{wLun61{wu!pK7BnRk1qDp6^ z2%D3J*CEY1C#cAJsmWv-!2>M^)=)x6WI5XJ$3#w(VtFU5eNwcYciDO0wSB*a7Mf1g zzSOwlNnIrk53ixk7J(0n61N0vt&Rc-HFq=cG{j^h0ZIEcgLXr@{WRn8c?SIUKCK@f zO!xri>TLfms{VuR(W(RdXU5Hqt$X7sHt7>Ii$}DnK!@5y$wfvdEBiw(ye(P&Logkz z@8Y3yixp&&;)QV=l~^v#wjNvzz79NM6MG^@`LM2r2G;@hT!LOJ0bihC8Yt-6KAR`J zMFR~jc7Ue>v>td6FxVm%ivyONy1odSXiSi1OlZqLe0poU0gR?tsG;5Lpt@=3vj{Y0 z@6&!XXo|%(fk;S(@kD^8N%Wzo1bZjQ4VpeeGwE93xcw|~yWu{H27Uc`%B|MI_K2_M`xkqAS9@Rf_xJbq_6Wb1 zuYUa`Y`rC{KO&sCL#@PFc=_63DVu50s>MhEg%9SA|>4=EmFJt-0!`=$LDeH z@A2DTaCXjicJ_|f6F>7B|1V94`0s^3#>WXj%-Gl%!HB^R_D_8K zdh@9j-}Dau%^yGDjPEfckdXKeB>saezEKF@z)L`6zJC4szZ{vauCC6`&d;AefBg8d zy}iAyt*xb{<$pOc_&P%ZC4;Xh$JdJCYiaS-l=wPg3-WV9a4UMfkW_Uu5dR7%Q=zCr5T+cc$KZE{uF^52SFE3Bq&ef9eR{Wf|b5 zln?U`{oBX(PMSTv%^w4`NjM;U5Ab*Zlz$NorgvM!!1yW`Bgv#T7o!Lf?Mql%Q@5pP zikAnGM1>;KV*pVw*K#axhTC!+e>o!-VG1i+ej(NmD?w0@qozX%2?vg0X@^rQVOrCH zwx)Pm_tg{)zN*z!9jUF=Gy`>kwO7Wb?rZ7hE>&w8RsmaUukAeC8EopKE0rM|Wm)AA zA@joZ9F$*$5}9%fsw63Fi!meL>~Q*a{zDRh-!Kb%x6PthzUu#oGuxXb$u^lkVQep} zkO;w5X8;MSa`P5ki64+vV3J}XSXf<@EtsrH!kkBp55l7sY8xj#YE0^evd!FRz=oLe zT$|=9sFIFYb@khNLFR_QEUonSpjNo`+YhFmdrebZ?T130Ls0!Tg!hjm$y~@V!!QxV)D(KljWU*9)#~C z%Blk%_N&~6!0DKz=0^p))&}Ds z$={7bZi;JuPaoUvoz0?nCZxMdS)~=5=4B_mjB=0n}*a5&1EH z%oz7ZZ&dtkb`Yl&+s}!fm!iz7ex)ntDRw?1CxoDaLAO@Y^mb24>A<6k$xo8lfJMv0^m6HiyY}20)te01eYA z1TwgFg8555c?YKYfrm+KuwL5ZDKrvg4+jh&IRdC-MfvR!uCE+8M>%Z=YCF>+V-q<~ zfWDzVZp1;N!~QzC1WUd8&g6avCFS#h zFAtVok_=diJAF3Vm6?wMwR;(l=EV_pk42pV#=cMnAvM_>0f2NXB0#rHzXZ?@V37>I zH=Yvpkb5t&G%bmBC010AzlT!BcqEgNUR81CDC4+#&3b#C-a1)1g~q8A$r^l@qb>SCau9vI4^2D~}wXZ1_QL(~(BLQfG`N?!2?Qb119#Fj|1Z4{+Appa_u90L!b z>ACzSp8K*@RWZi?8*4H5 z`xST5G}nv07Hb|NAD2(-lTYIu5BUd-i~HUIK)Y&>vnJcINT%z>9tVNhsW$bq#!7`D zCm~7GuNjc{nBeUsb)l)R`12x;ek8zK;l9~TmQ+(G`P=4*nx@GMZS(B4U6*v0OuLgF zY9Uf5_h+}}wk>{f)~tzWS+mej0o9wE_PpLV2Gg;elyIoUiW)bD1Jp>AH7KP zU=#mS+}vwh-i!__``-_3)vQ?Mm|ovMBZ>M7R4O1MA2_!bHGafOPZRWmMB^qcfl_&8 zTJ_(c+oxYyG!kod$OF8s`GY4x$1F>oGQ}Ljoyg2L#jEqcls0#YMv-6gj_f6CKI$P` z^A~3y2&V>x)1F&qc136*qc|tfU?Wap6A|C(J4B5A(SO6L#aT*+8@L(^&GsyjkA}yb zsn`z_aPn*7qrqco?56-bgR#L)p7bH+Ee94;4c-Uldc2VjoxUo9b$T6)@;*p<{x9X#P$T5!}i}7;P1k?28v$FUs_f0WYSitGqAEP0{a{C_^w!=wE z^TM0{;B9k0?;hnSibDANpEA*0{_M-2$d)bs;Uuy2?Z2%5F}TjH`HpQo4<Fd`Kp&&nCTHIr>YV$_0+oc?0n&T+4cV!mMoZk?GG`pI0I;Vd=iZu&?d zcmsrl8~t536xuv4mn#-z&*w&cJ2#WfYnd;PF@8h*_A_pK;mlb3LqBm>L`o)o+7vE> z@kJIU4oJi;;rF7Yg|869@p~*#za5I z7?2@s0zi3iKt{19Qr1avgdi2JbNuMcRy-BA$i=>v`SN!PyZvUw-atYqBSUN;;>`g4 zyUm~p{=^FnIxaP+!x-oRlH^sBwG%Oh?hygd`JKjry#$FTpxtg@~1@q zN^s(jjA%(>AEZnBNf9LmJVz4$2bW2P7&WJeyTn(RV`@Io2TFyX#HJ(!Cb8qsQ|>>O z{HK9{qlo`jHh@}(gnE=i7XTh(@#X!QEdJ3&+Xm?sZ zXYf%W<)1}^AQUB-io5`Y$bZTkWd}_q&?=9!GJ>-*v$C>VvvQ}i^8aNOGG!ObW|uzx zf5e&cY11J9tePOsxMxR=y|(pN zr4LQ#>SpDR3}%cm<$22HO)#Z1o&)>`bAJWDo@~tsdmN>McgbmaoFDn`HMoehLhKd5 z;FXX-KGr!+^8Dq&fb-Qe2GJ?XIxON;gI0Gce4VLKPyBI5A)Hs1z-)m8{^gTtV#Kxz z$t~zUIFo4(6dcJGIO3941qxa3Td{Z`^6Ma5DYs98TcnY?pqIg0AVkODy9Sg$QIMv86&YFx%tf*7 zc3IR=slIqpe09ZHWy-xw;6gI|aWcrxPHC^H{PlK9mPO@Rmi;s4f~Q&tTBb6R`bxj= zm7pb(PiXYJkgEEN)copb3V|9ou5jQ1O$VITL=Z8>39n107)Qb){uT9vS4@yG{!LcTguIi>dbfDLMlSMgiASXg2J_LQoa68{*oB z0^DVJtLcF-Po_-l1OM@LKz>F@ zYYb^Hn=MkZtk)6xpeE$v+y%a_Ba`Z^bPg?XC4J#rQ}RT+abc(lyWM13R3B#f-a4+%BaZuKy{7#xrcEG;BIMNpI?1%Mbx`vJv%GO30b z!v28lu#lo&3o^fCofK6EAQe1-bR9r13wS4I2l+%0t5QJ62)Ggoc7cGhGj}BCH095} zyNdrDJKIEPF~*jWxXiYKCd)PIiDnNVa*hbHCIA2h!6QIGdobS4%RiYiPZ@dzpf9i^ z2Q9%{#6F*}6!z?tr)f6>J3ixTXw?>VwGf@(v|Yeqv^AWB_tptff^BmmSnDWK4ghpw z@TtyDSrj2q8^Ch_Z{tLK;%ozQ!43f3Tvqu!ULCeI?*z!2jqOSBKkNInLr1^T1{#p} zJM@5xfQv|Fpb~hlj`A{@T!9N=g`&7Ppd2x{JKG5ZaY6B&F(AyVs}#CUmcHjQeWMa} zFD|={t@_mQ7$W-Sg5lXdkH39dRGJG10V;&(b=MA%R!J7`5RD?q#v!rfAZI1EJkZ5~LmMkhG65lgqI8k|q4>!|)O6s=i*%^7h>CV#0%ZDV^5Iye*^v zyG61;V-)R$slX@1hq)xKfdytARMbkcyQlCx608r)_pyKCmUWT9?1~CM=W97(D^TJ|kgmne9-BX|lE}$(tkoFz1IKnn@QK zA0Q=MI^9sqx#f@cVQ-=$zWr|5`2F+EjM2<2&FmZ#n&cWlwy-y~!}ff3Z@w0~u$ef0 znm3QVq}8*t&tX|OA*U^R!$eEI_>-`_@4d);J-76m7Ir{ym*!OTVZydIwF9U zVzfVTf-z#o&=3@xPBN@8OZngh-g?!03y){mf-Ian6PvoDA5Z*ajj zUkPozCSUv5K}(zr75fE_d%6B%WRrAr6MMZjLcTrrjrN|{nu+LYa>N|^>z2&s)-RE5 zrnf6Adn?8U>-C~L+j;9Q<*T(fHgEGsgz`5Q^R~2}00Ty*dh@qaI<`KJgn#}t)Ae$@ zC1O#N3KH8yQgX85JgbcL7U(1NA540i_Uo7{E?#89>IaAEQN%@K$S@Cd!ojRe?@oU}eTQ5{{o`)(U6 zNPHUJDYGluI5-XS{Sq z351P`WQz9(g!?w>!*L~(=YOp@P6YMpnZ}?$exJ|e|Gmq880Kru6-|l}18W$NE*28K z4ucEs;W%uUjP>`d|C}P1z|ZaGQ~w;k8r{oy{;zw@TnMG}dbpRu_n2(-{9VBXYd9@c zA(SxE8Xs}ixbXY!5C~s4dassZ$BsPzV03AhNNe!b@9B)Wtm~in*6X>XjD>&K7ECwG zw&|;i=`x73YZUZX@XeZU`uw}sOYWzG9Bv`bfTlvia}ZQLnRvxOjj$B4*r`ECD`9m~ zUs8@CXM2EUG+h24aVFDng|PFf5CI-Ee95eH9si9a%V{R&7rg`rqW3-TB=fdVQlX%W$yxG4k&`O0w4WR(HUXRLm};uhV-; z8?C;uR~{}Sc?!>=Y!?3!XD~hww6v^VW;5SJxBgphz`JLW58o|J{2{eJCmr~=`5#M= z?vfJ3;NOosStP@KxL=>HjRPh(vJB0> z;c{2oCr^q|Jyi>3!)LflX^*x)*=;`m5og4dAXLHzl}7VR#Sju9g3+Q;n~6#A3G34A z#IOFK=$uzAP3)ys0(-icVjR-qFN+xm0St+>=l2=7P$Jok_B^rvk(c0?P3Vn zU0P48_9}j&%D59stu?Qla3sq_e4p!cgw)cm)_BKU)gZg?#SQZNG!I zD=`%-(5Ww1_UfgA8jE$K@gseO^oe2i>jtAAd=PTeQK!70KQZ}1QJE1Jn+cOP-sJH= z@0zGJnL8%^Ofj#*(tZ2Ipx8t`^*uM7o}X+=Vk63SP^+Lm}m;Dt#m4ninW~ z*J)h+ZP0_PsPfcxQ!3HIc*P9&CoV6@Md@7g3B8;dtE$()Y|9|rq=j1vgL(^8q}4xU z=iRfRkS{egF711j;p`%N9v>sJecnIiM!Gv)*hj9l<)q4eY5L9AaUe8Z6K)qTov^i$5F<&P>#wXv ztPuFSsVA@Uo1tmmX0bcR4d0d2p8x4Ykxk>@-vzi&cQ?eLX0`)se{zAd5_{_p(5JAtpMu|;-QyX|kUuT^GkZ2=HM$X3i?z{3^x z>s9H`nX8)O9peiNnMdtoUEXMh-a(X>OJBi1`C+fnnojy;$Yj zaE~}gt!1hv#*f0|PO-XASRZxss~@R3CurAGz72y_No3b20_{zdC{oGUpFMdI2+m`3 zK2noduM1NO;|58N#jLVM$s%iu|4=ZJcxqHa1S?A*hccR4L#jzvZN+EVZaok`KTf^P zrH@maUlh+q`BF0bmv|p*nl2xvf|hug7tUpjM13;sI&O*XVKMi3iJ5S!rMJ_$b2!m` zAnIgI-gTvyK8?!I6jfWHvfwXf-FWe|s~smP=_=ij=^b2I8s}u>Ns`8ZD%mp`WyV}0 z3W`ea^dDGPXblP4TyQNxv-S3arvhIs+EVnWHp~3bOgi3t(V6|KF1i|kB&8O~>_aR+ zbmOsp_}Q_*KUKJTV)6IHZrCeNtSvWAqQNbwyNF7yN`7IBDc;4u;4Dl)M?_1T1UT^; zbgL5BxAi&8tB@^L#$79#xiik@5sn*j+vp(^jluSI4i{ay5+w{SI*cT3Gx!3Jyl?zg z`CX;_w<;Ks`^T(tV@@hgO+_8Xfy!z`?OV<-3jIs*Z@rpo0>77cypJpJD zBo7o9#d3RAYZg!9&H9gaYw*ucJ?)4*%>ji?ynUJ6k12&r>L@(x6CrQDunSEO7zH%w z_jc_BsLhO9)V~+L@^W)#sr#PY+>~u12;>U*d^LU6%%dy(a$VMPnYpsr>!-UPS9{0A zzGhgh$y-a^dvnXCfx7k9rl@OK)4BYNS`v+@2<#K|nz~u+i~>WzoA&wjDh5Fj1^B}_ z?uCE-6J^dnZ&8@`R(NLz`oA+-Q<;`qbYT0?{#my=P#=pq@Y(WP+q>ghv10=?o3f>y zWDU9Fv2gC!(sRC6(Q`7JRIbL@JszHe7U@{V+fTh3QxH#ZzABKdR1z0EzT-zlYF8n= z%uz!4+o(~L7=n$W>zXXOYQF6fGst|W5e?u{fPjFC#&aV3-2@z5zU0)>aWSd5&a$Ykq) zjNsI$U@SKbH%9E`rED!`W+4cT@yL<%c3HF{4bWfn&oZ3LBKKM${Rn8#*+wNn0E=*Z zEC!iyK*bSew?DMT=O8|H&NonLIISUBP~Jk(wCDsB<;tf&&Ue z_^<{zq)gpQ4f#S~NvC=ZT@krj&nM~=&Zen}!bc&NN1srh;|vbif3Lm2p^jUP1Y zGY#M9CrQ_yAF7g3BLBk+-7rY%a$F{In~RjDL-z~TB}2^3qm(Po zag<<(=;x~;D{S~6i7$_j(#-M#`(B=9C6VuC2Rz;EW3+D+S^WPTGiO(k)zYPJp=V~d*Lt3xO||P~-`*XhWEX{pzuF zm1nNZH`kTzh*$u13rvu3)pBLAC@+D?wKs`XfM~v95;3x#+d5srCEb#Z6avPjcnNty zk=4$A9`ajuDcu*!)N_h*9X(mgUAyK=ckjwp*<;;easHXnRy46B{E&cToVgu_$)V>{ zWS8{n{c#xJ8U_U-VB#m_^0e@qsBX}fieiFvRaZ2U5y)E!L5%@0V$rAr;Ner~L+}I5 zTvZuba>Y%Y^Jb3Ds%qg_ukJ*T{$0^~v}%T`xpe0^5dfO1llVRY#(9nd8y7zmz9rnz ztuai-I7Oo!8)wV=(&j`>B3Fza9QN@ICk6w+shU%IG~S|V{IFJ|HU>l6 zZsP0_7$5M%yn}vUGWFn9R)@O}1zA}^mC@#4fP4!sGd4z_zoU+k6hBl*)>Ai-&^wUO zIFPuiF>o-DRQuuq!Cl}7HNrGgzzMI62S3{lcGZzZ>fG^@AIQ#)>uQa!MQOyo(x@U$ z#oEOc(he2z4i(=WDlv|enPSn21(o^_RbYp3D3YvN&g{m)8Zc!|DalVea*W->Kr$?NwBV?V3~2~;o;|CjVC(d-QaK8$=Sql$t3n_ zs30|0y8(CXu&}?%FIIAbhQ?Y*@(oK7Qu~nBINroq{tcNf-tnXXuqvVIMPM1C>66u% z5{4%``p0Adc2i&OBGEIeI=?IRc33sal5xgkz*mw33p(;bPTcEWdPh$2Lsx`!D~n_+{}PBq7KkYH!;DX%h%vwW!?ky>X=up8vg0LYW`GsE==<8=?;J&d{U2$ZjIQk>t17{1=OAerqTSu`!BX}zl;NMd z6Dob3s&CX~*M6u+!*AI!YokE?j6KwQy;QdhkHzD|$Eq;~nD9*{y*@4dyf0eL#+Lr^ zq=*=iCs9(H54Enp3to?xF5=ATU<{Qwizbtt-k*DdlLl))%UiG!2gkxT7Xr6$acO?A8z?L+^OL0X0Qb)V1~#K+OvcHnVD%aGSy>}ZXU5_&KwQ*o}&w?ip->$ zEoYl~ehY5n_RuDIwl#gWrf){F~mQ z+1BayrnldcA&;jBA0?~Dg%ICPh2e9HK4;7RTQen{eGX{MZB&%Nz>h@hIq7i8QbtTN zd4uj+LQ1q%&`g4{1|$LnnbVENKe7XB9L;u_OsJjyD(xJXL|~+njqAv*CQqkIS|BR1 zamsa&_BX#dIw&+2b;ma6P-K=4*1z?=;kJ7?9T=J)6~#Z$v(7f(PZu8mi_8Q71M22? zzIEIU`s^5lq*Jb@QS+U zADOOL>pDBr!;kLS5>gK3bbs>`Qg{_iOBac}Gl|`kV}b`_+K!fO_l;TK#_c;>=tL|% zDvtv`C=z}WWuLxgk?)XwX=&L4ff-{gDD(S8*PZi!IX!SIl8Lg~ z&6%8@q^Whm^L|<{K`&+^fx(L#5k8L!G@=8Re<$fhNBXRs@y=60;f!_;7(~v!O+c)= ztLNluu^Vom6(-__OPF-imVDg#Z1o`pAtmwgkuo6R=M-hyM$ogx5_5>>KqL_(TDTHw z(z%sO;pj*3OP;wKJhQ;Qjbn9w|2lEHR@6PM-?5C7$YK!}+JXzugz&c8>y>X`osjsH z@3gJEq+}?*6`k*Z#;+&{-9tqoAd9g+P9ZMw?3^Hp%6pfM+bu6|R}VO79Dsv@Vyd1& zgT$)tN^O2z-%0rtM|u9!6$FWVx7XbT+2L)s{GwDR*EV1cSf9kjgxT5$z(5L#0rxq zwD$qF?|}6nS2tV$3Mw~M!#(f2B8}4u-!X}%)>Cw(Xra8na2ouD4gcoax zq0&EEo^coca^S!2G2P*dLE6eU?bpw5e;44Z)8Nm_l*+3ic^V`kK@4E)bmP@O*0MZi z@O_#Y;|FK~Y|dfXA%H7{X~DX$c10_v!0jx?mdN+b*|EgOh!degTNTBVJK86tAD+UV zA7!Vra7|$w!LM^lgsfeEdgzPF*-+ zqbK_^Q4ahRe}w<|_Piw_KrZ11a?K?q+%h=J7Gm>G=u^Okvcg$)1b>B3+SbT7?RUqI zu}|+`?Z|#Qvq(A=Ns9Zn(=kf=F`E&i9t5#0#9rJz^B;X&@IA_-jySY11~2dSM1Ate zB=Big@`0{_<&QF;w#(D_cR}R8;%sg=J3Ty)ZF{LI_PO^48w}Il3V34j`aG^c5jf>- zk7{1Ew#j;qGW|S}j6cFG#%Q4ScewwhKHp6~get_wDI7qdAG}=xj|PW*1UL2tWK1mo z>^hIe-O<9jE#llXz^hKX#nKn5uXfY{pLBI-_Ps|~ehT>~ZvJX^9?8+cY}=E69ZuC4JKreQ()IWWo9AMz|-I2md| zch&V_EIA7l-We_2A01{s+~<4M9C#`B{3L=fmUh7_%{ew~8$S6f6kk3NX~>TYMnUcp zUl$1?gxnxLKGD3fLCmO=*LTJo zUY-@tBtwmz3NNZZU#xw;#!iNnE)u(GVAXdiW+3?PRtiT6K8hefb0Gfgzr>kHLd{WQ z^FQJYh(Stzpu+aEB-FFzahejh29{PORX7+`I{1puuv-3ndErF{D0HBfX}m{~QY!F2 z;>_)_LS-B^L7b^n&Aksfn%y|rdVoqLgM~BE2&iV5D|!4Dtgrcnvm@fyoP3ws1#_QU zl({ces}X~09XfS?CTdj{^!I3Q=kJ}x&PY=HHeKbzIbI1TzG$9_0c#$trANx;ZP&u; z=h^tBkf6VREI${i{bC~n)FwJyOHhez_UfjCe6%Uqe-kj~(Q*v^{NAPX!D2U#bnoL= z3MILA!0KR(0a=-BhWLVqy+X8WCi=GlUVR~LVe7iQbpbtS)pkQAW%ck__d!$9iru&#}tQHY@rY~CDzNAtu`h*&g>fgRlv zj>gE`P@nva;d}V)>K1}H)23nII~$~&e0zq_jg+P2f}sWfl$In42s#DQx${o)al2{E zn=(TfC_p_*tiiO!DN6#aPU*+)Uw+^LpsS4K7xwY8d|45v>ir56g^@#d&ytCdTt%Bf zS;)X-do1geY6)72I_SU^fgc_N6h$+K@E6Akwz(D4XWA2$q-fo*Dt)P}B~YHF=TTLj z7vjNRL9SD$sn|D_%n$WkIuNKSYPi@gPwKw!S=KP_u}Nk*S^Dta*_4VddpqVaUwt2Q zsF&{FwZ%B$h9C)$h8%TikD@Ij?Vw9GxdZgWZ^9CA%Tm0YXzN;bsA$_(b-QT$Ufbn< zi(hg!8Rv4w5|rRvx8M1EeQ|lG^MIn*Q#)?>IL@J9I4#z_hx<~jmr7+r&MO^FtywKQr}x}r{Ob+-JO&BTeyJwU94>#bK^%svx{f?2g@_D@=MxVyLq zEl41V=)YmYj4M6?h{VH7-5%-7lqQHF=-WG1^hA>l5bV7xY~U&tsa->Iae1smdnhNE zC$qMM1j{}KWC!@8q>D54l~(lA=TD)C?1jHc zj=5`*0>;{Pu}oxgP&p{Yum#z()FB3-Qz`KrWJL7qoQ9xcdr}ZwmGr_u6~Tw0~$txtr+cn6pR8!+Bs zMGVJ68f^RZXqIapC{Vmxag#4uzm6MW3`Prih$p*d7QdjS<>6Oh8k!edW`2yu(H|vK zs8)*mgyH9Sc4lB->pJZiuMz5m;s{!>rHiEgl?}%<>_b77lOxMYCy1;8ZV2d1hH_!= zgS#=$RF{e97$H*hB!D~qJ)jI$4H-s0gr-4HS}@J6`#)OS=gA7Gjuwd(x5Y_HzzyCF ztP6I+#`!YXKleKQob%l(GmqbQCp+3n-nNO3nmR zg)B`00iOgAVT<;hF*3ORo0HV1)$hwhbu9=_Kv-d~MSf_Rjo4oBXs1=DrWnF7Wb$|@ zZ+|@r)GDA%k(SwacU?Rsu1oeMC&HDY7c|zQrX~nTG_m6%t*cWfl-h(bv9ti*djfbZ z(#SVn^(SRM;X?HtQ(6ubO_j1gw`?hpf{zlT0jx&`))-j>28thiUo=PjvOxgZD;18H z*Tjk^UAHM@R2UF+1DqpWW5mNN6o4R{<7s_TKO6{HVui^*+Qy`JH#NPbOS6*Q970>T z*Hyn4F@&MwA~;n@Dze7N=L%ye(1;J+jWth-%xC~Vy^#7$2jh@WN6fmL0^0y8O(oR?wdCDXv2!+3hc9*-f-{|_>!(y=0$qKdX{vGdp01G<)&P3t5W*+JC-Ac{9fb38A-gz_09*6?^P!Z#bpeKc z{%W1_t59z-jqkjN%VsOvTx=fugY)C1!YiFQBa+oYZ2#x;KiR!A!&D4Uy9^_aQVr0? zy=WsVW@_UznXr)^Q7_#gw)I_+ej{T$Y?BMop1bjG6T*kDDW%9MU5zCwxZ`&+4&zFV#qBwSVIJrV`wD#ld$wU2++Sr$rRPJcj(mG|L zj*IoLe6stNPN6d(05qE_>J!b#RhfvQ^x*UQ!x#Fm_=HtLKNI(|E!AGiaByt>vNb%l zq$K$k7I+b+jo%qbdh|7?<3z=lk`XE(29V6(;sAwxv5ey38Mnxdsef4gRbspnti#S*>DV|0U(h}kW?S|m%fdl7C2 zJ5$xShiSAhHFVhlJUEW13SZPMj`npc9z??57J?ig;QM$sh#vd(PY!|;sMtZclUXnc z+e6@-|C(~j=#~)5y#Tj<`cDP)Gp|UiSt-`-3~F_JqrtQ-M05j0bf2uL)$Le^mZ;h7 zQRjvIn%#;W-3`s#A-s+)FIuMb~?F^vxz5_py|2P!%<9ooFtF z#HF=c#X1^`U{P*>n9|=jS*kMGG(irUg$^2(%YsJvY``xZ7A$wKdhVNZpV}{5_1QhS zx2)HR_OR-{(d=b5>LRM+wnjVXGOn1l6!UFA6gHZraOk`D@xyW~Ib+mcwIz#l>YRIPqVpxEZ+Kp?mKDVHD9$MxGM8yhzBV;t)~B%0 zwgLo`TtZS;oC-c=~|NEAw5 zfgV`#xg3=-W~^O3s(O;3mgEmC7!t*c){$it{MV| zKJRCscZ-pMYz9)eRe1A6K>0Lc9TX>=G{C=@V+(xs-1ZY~wT#{DtTsJ$0R$5y5mkwn za1~wOz?`{hgaM#7%9<$sa6UX(CuBaPdLz8Q;OQAIp^cvX>h{a^O`Fb5aY8~>Mz7sG zbt?u7fECap3Q{~a(i_}f__3w;^N_fyQ|P#77jK{hxifrnURZRxGy6TCRS~EUb_( zC_Ez6Br>9Cr*gR@l(kvYz3&ui?*ZFiQ*Xsuyh&p34IN4$jsX+N zY|a|(&9Ltb#M`}3!7vig5Ch-?GEDr52fqT^?51ZtDd#4yd-!ZEB5xr&X`}t?Pq<$XCjXj)TpQ)p1P*9YM4D~Ym8!aTx|L#6_ zM-&q)k%)hfvx(1)i%$bHmOL{$E)ol?!~Ctgy{_f?n}So7zmsh)3Q@T~J!uItk8zF~#B(Y0-N+Eaa6K6wU!yZWv4lo&Dc zn>})2Z_?iGXEeQaL3E#GztQD{HSH!N&$~auu?2wm!p($=Trx;tJjAxH+^Md}OO(t% zzPe0_I1EngDOUEXj^rU6ULjUei>g@FYF3R@k_S+lV{TXWoJ4w`8s$J}eg3hdK1m2i z!tl3nM4dt{-A#<6&0sPb>3SN)Lz*v`$Ns=}bOB2*5v^-Iy{|Y!V0}9o+09Md4L4Ra z7kH{?d)G|}!GqEzJ5(fO;?|gcsYBHskg*k@M&`uJUmbvwhxp{t<*@*Cos+_$QX9>KMCwzdEAq3;UOC9&U=Id2MiE7dUaPpPI zBVOJOeyUPAx4pW^7%{gGK#T?w%ioZRH=wT$euzI}%0YL|;aKA2KesLSRYmU{Q(%9* z)O!zS*nHc-Z~IoFX9rW%Ej_0~a0EnFj;2U%-MaAO%TZkx)>}bMaJTg24FmtMdJf>67g0^x zRpaN^l(A@AdVf9cb#ecX-^<^C!bq1E5HaFJCPz@B$Nm8!lQRPCf!tG>%KS34^&o9Y z2Sm+pSqbPd0c}RQoJ2~c_$#gSjcy;`ee@o=OE2bDs0wBX81gqP@mJ6Jqe+8XTpp2e zQx{YfHjvcSbKKM2@w!(aK;xC~rrvvKB*-&)_lLb;W44dM-y9;|Ma9y6)7On=WcRQ! z!ro2Q$uYg6)_GUOf7BgoZ9-3tX>N;^m>0VBBY&M*a%`LZ*puryM!KQx|-;y&>b%3Sf2W&Z$ zguke&D&WqyYFB-!JoTnO>&@ll$SXH>2B!}JwvPUe{!gDuC7(rcV8J@R&EC>?>}mdn zj1tmPBVAtgzz3u;qkJI+0*h}F#KKB8=Be~<{<^;KLYD}jJT2g3Q7)azw**@hbNr(& zg(9YrXLpJGYH*uxo@v#bgjby68l(%#kj(fV1+Uk!cY>Z~w5TV=KJmqOcLr$Kl~jiu zzej(TC=7Va-D=M$ZFH$R-i?k(+E%jMDq%@p5Ev)XAKEL3{$p(J)ba*k& z>k%W=(Nca}H0#l3wWN3H^H>fBS*6ZDiS^8>Aer=6g0{LxJ8wYVHBsMzb=@vvV(+Ef4Fcs1H!chb;!^ajjO7(2ED0^j9KZdO&8o3^6`G@a<`8ClP&wgIF z)6XjMGxx({@DRw9(d|y7YD8#iXYjDs$0cOa)@#zrR1Cq(;RFi}s~z58;5jxtu60OS0wjmm81%FS+&!U4QPcT`?) zLvCLz!zBp#izgg_Qy6sk_?i-Gq}Z7ber+J~e!AfAIOWIs7e;WW9+%{gQ^y`}EZL?llvD?C-jq4e(}SHslEh|j&X#!-Li4Zk9(JW=C;9l+^WFB zZ?u5++0QqB@gMDZ`Z($SFW&C@FUt4f7X1wjFf-K9-3`(q&Co5NfJnE9A_Jl#APn6N z64Ho(G$I{CmozF}f;7?%bLO+ZPo3wSy`S^b`6K2v_jO%st@i}ZqjWYAvR&mw4pLQt zPl52_R5&8>gW-Mn4Y~7kY#<1ql*_0g-c}`y1S8H!CD^G&QHwZDH6+;gg)rT{J4ie1 zX{TnFl@y)?9CZM`Crwi{fN8rno~4wbn?ww&ISsDlr1ACo_Sel(}LS+~Da z>O7r0sq8EaA*xi(JkV9N=R)wAgm)2rBo84GQcrtwtTT{B-lwW1wV&mJTf$|86+5BC zHh;D^#HEs#<)cEl+VyH|Ogbb1ghx%7;iZgQ80Z5r&wTf4V>Ak1P}fXsV>^eM8TNB@ zw4+O6zM&*w`s(%g_aUJN{s~RvG#jxry6?wuYRyIX;pQQn1oxg(!j9~i)nb_xe0UF1IzU650`n<}+2_zjw0 zJyHs!9qWHGaLDX;Vh8}lnd5~lL3q-AKoC>fMr=?+d>AbFyRuGssCajLCB7*{FcDI| zJ252GTvk&_=jdDgl{P2e29pDwCTu30Kw#((Q#lfOvEd+My@-C#2pl$mla0o*u-?7F$t8G4tks`lM(oi`5!MY7;}zH?bk+sa4{k%5_IHC{Ik&ymr6fTcb5N~O36%Kh~s-uXZFKDn!uE|762Ts{lS$L zH>kE>gOr7>qsV}dR+X|?E6_Yx=hcksuZ0grKcbA=0%J<8k`;J9Gb@mhp}zpU-d81$ zH}>_u*aU_3I9ugD++k~2b`k~?K3#nFH1!_g!}S$^Z|P!U*Zpes=&;rI=lReH(tdhM z-Ip`#sqB33DnhLFXv99QfBD301KoUF4P+ziiAZg_8+BzPWT$xwN%PY!({0~`2V1ek z&Tf}lhsp>Rg{U<-SDuS@r1@oliGaabIP0^5TRStZ`XwhHwhF@^bUQ&%$o@d{<^G&e zb5j1CRpWUeJ$qIFghl*dzM(^{YLuhJsUM$7>!5w;)I5)>3PMactVFV)jEZSuupN|D zl@}zBW%XfAF)%uO@WbtMtLp&w+W}8~t+01U)xc&)&G87K?1sgFS@e6JElIY?)xfVr6`RfcIjPLJMx2)!7d2Su?-#hX5+XQds8 zlS>eCe=)!!7B~=MbQp>6uI%NKI}jD_ksK0j&Vu_)JIItwC89PS_lz~(tqh*{t(NmW zPvaMrI_;Fy-9lB}_-J~rV9}UkLO!L7p+CGyJl|h%iBfkC5;P_%qsTRxUZxM5Jxr2s z{*)@V1s(}CGGx6ECLw0S(SzfOM1Lh```NI?AS&(wnyuyL`2B?RnZm0`pG)}8ffuZ| zoG0t{#m4MZ;{(8Z((>}&2*Cj>jA%Y7|Apt~Jk3?tO~k7t*&PR>+1z~o#2PjZ0bUKU zh>2vbsd$y>S+$5`umMnL{SEVT3AABVJg@T>+ z`{ty_vqvQlC}pHV!XI>%7+JeevejURo?>3(DU`6vaOHWF6ShY}nkbx13b)NyB1!9I zK&8QJ+jnVD017K$hD(H-u6qJsvreBsd!2(blku&%HwBX@{ciX4%t+|VYrz__P@Ard zd>)&hPv5Q=*%A<#Nom);jDNlR%#c86@?}gd1BHMALlvW+qhuAK$TNc@mxMWOhx(R1 zN6XTt*(u`G2C4{dL|{@(81S~RG9@BB+^}@owT`tlB>Z*dNApOVbJhoX_h>`REe>N- zS^K`J*O{vS`pGrwt&Dzq zGO4{3zp<55$nO|B7p~Z(I<8!;HLm6|(RgWH33B^#{o^qv#Ue_shj6T?V*q7kT93e+ ze;5d&o%NZjMjmNw>DPU!MCQFh()I#8vCc^kQEfHV}GL4Eb zEOQii`edq*>vf4`ON5^@o1DHEGFCsvg}=`X{qxc1*X3Eh&n;9M2MYhx1n8Zu>ypsF zmx>AHo+8+Fd)UyZU#+Bgb%>v^_^T0CTlI~UU{r_v;~YiE7T#s^i92Q-B5(!I z^X0F$Hpe$#hb;GA@-^qp?Vq)}(dru@Z1K#-LS&q0;t6-^7D!9j36n|p4l_>{3STsI ztqb&gbMcY7sPoeMy#@7{w`ZuB?(pDmZ3%oz-Oh+oRZPp13{=cq*^NH`wxM?zHOlb& z?85-cocL8tI15qvbMo%jezoBQ?^l<;N)IQrDcf>`Hg=sFC&L1r-0a6Z_Fg2nepCLI0~>f$|HV!DV!+MnD3e*Bik39S>ytf| zqLlFhW6ssM5>seoPT7WtM<5@V2zS&9k1$#EXn))9T)#+i>9SVG0%QlqgxjUKBH#9w zW?y!z$O9R7*Im{en2i$`%J4V)x<+1CJ|tHGOOOOg%-Bbox!>{l-+D|JX#w>VjP1o% zM0ocqEknb1r4@aPtr3imrb#Uv6}knDZDJb;PLD2oxphh@gFFg}5G>v;Uy^2t&jibk z_v3Z~QQaI!R>EAW%#{;UH$V-hi~d=;I1GOLU634GO2$!t}6CqH=Fzn-_((6yc#Oqbi09QaWfWaGO;VVpdi3vZ& zvkz9C&kJGQ#X`Nntl4_B2qC;E1RgJJjxCN=dxf!q#oQSRTnm$*9*`)GVi&>K3|Jl* zfjY^QuN4T0Sr17ai#Mt4?C)4%-}T8I4KF`;fl>$0XZ6{HS?<2%;!>{S^m66q8c=c) zQ$9BQ8y-&n)SdQH8H|>9C$@y)7Z(v_A}J`9RmnCeN)Bl1t7+IpX#3)6dq~AI56N>5 zSqyB>b~j+ufn3v|N(3p^Z$qZhgVTnWV0(9lQ;~+wYR?z$rI|XQ_$uy~xn)$!kSi=& zZB_b+gw5!2dUO3hXYOq21q^xPtmJIinJk~CQ4lX&Hqkt0LEH2{hOnIkFg@woK>`(T z4X11u+oMBl$TFU)2y}WpHdqUydBkB@LoXuA1{vcFArrAlr04#NN&Y=Hdcf8KWqCBg zG%CV{b;xY4MH_a+7c<1SCCnEkf`j*v=p|~K1G~)z!JQ+TqAl7=><*aC|KmdDMBhD{fLW#{07WL{Fz1W3xLakV6(BIz3RYw=`Kw9MO2BLcAMI21=R5UA^_ z461khW7ey{JTEiVMA>1dXD3mY9 zSS_rII{K1}$Fv-z?7Ql|1N3A1!Whe8OwM!dqg)J9ETFr$R&MA*&>=bb4aQNvX*D zT2J8gK~5)sz4*N?Qg)+qS;13m*B=b5#`_$i#-*OdLlhmmWI|asLiRt{Y;u`j>Ko`7 zE2D=`bPkhuxl$hcPd%2c8N+fB&@vu_1qZq_<_PnREJ>)>HNJ zo9eBxg1oX!$s?gxqhZRT$1SHO?mw&)PnZTyZTrORuqN3j9x<{ek@BwMc#!G5l29f8 z>8Nk4rzWYW^?_AP*;4B(-h)@z?D@QoKkaSL%=IX(Q(m3k)H?AVIV}mZ3+E~e)jIIz zbEVaqSbs2zFtMP2qn+~8>0IK%E7?{|S*@gx$n3Uu$X%puTNeAk4Vfu4B{y^pR6L#+VY;-|1ey{9**Ez4$*++1`5V0e@%j0{9q^Qkf z>I|UR9$=}mpd`N&rJYV7!%R{1;aD4kYVT9%pXIJF7c1QcAA-lT~HyQEVWi{}aju`;*} z1`u|$c-s#%eU2VZBVpWzwRJG%=K0dFS<6bWI@NG}Gk!(8Dj#Ee5buRpn2zmw%b&9< zpX?k=)T3~qqIl7z2z-hskxrnd1?U>P`=t^G9?7|?z=D@4=2@5X2O`uSv!de@#ifm7 zNjiPfy_`EzeQY16B(17@s4~C#q~XV*8Cs+n3jz`yv})6$T4?|j4bW{G_MTSo7(%Dn z!9s{+pjwIL6td|mxZgweoVN3fsybOLHKXTkuKhmm9ftv4Atn-SNL6S^xN7+3cZhu; zne%igk@6#0LsqqDHWQqA4d8R`$UYV_U0No}&IJjw6dHRMK4~hnyehOcD^x)eE3AhF+ zN}%#oW?;9evO2o5a`#tsAs>U2JsTdt_1RAFvsc_(hV2=9xVnR;x_9a9euYeFeN!nZ zc4J_{FvsxtA2`tjl6Li~)=>7_BYGO;=5LnQ-)v>;9DVAZeH`H-ic2L=6!HP2XA6{O zOI3)f;>!BymO(54NSUQE#iud7xiRayG4HzZnM_lvd4u_GW%*oBm27jRc~xU`MeB95 z?ThB5=&FL(_1s5Uzi9zNphnHRsNhM4A#HMLW324-t8sIN;{oDbTarLz+LPs0h*=T- zjr~?y(2CFeh-`bGdt%25li-sMa=DbfW)x9N8|i$;vkx8g^EGH=kG68E?uZK%q@`10 z-d5Uzd0c8kH@#CwuFF=g_ajYxf@F{Jd>7|@=Vf}g5JQ)bZ>QL0(JeurYs;Jo!*(K# zWzmydy_Nw1<)m9>_b7{&Sc@xf@9y_EeOWg>PZ`>aED|H+`k%EtOO@*m$ZQ+U93Y@G zZf~*fx=HJka~on9nwjID^8l%KtEa|KmyP56jyh zw(>t8w{m#D6%M`$`^qr3lR3gFU(|f#qTNXu@_ss^bvovD8l50Nlk$Ehy>%w*b|z1L zw($LIN$YI+?QFIDT$ubw&dtxs>G2<#L*H&jU(3I#?ggxDKn{#kAMF+vEPu@1F03z1 z{eHi=m$e{tyLj3(*)pO-F%g!}pf>k}d-=pFK?6mBGk)krZEQAH0!#I+^tP>3CZ|lR?E=35hh^rfW!zf7 zoyNAE*1Me!h23^PJUm;x?z`P_g}w3Y-C?V}g}c4U>^<~~-~Lwi&U)MaA=Ca}g};|~ zyXS3xvHW+36b>4h2<`&9DdZ1Dx(~j!{--#@+kPZ~KFVSwpzuEya=@yB+7<9(^r2OF2Hs{2#{jX)tfg?chA?Wy>f6NP}4S(wmd-V(cj~g0` z7e0!Yb37Lbit9ev7g6ZTkBS>b)|cfuA!#|xh1S<$Em!iL8|CU)Tpje=dGrheET(YE z{s1NfD+$pmMN=NrQ~(tcF44Qfthvn61gF~%ptm^`0+c&A+)kU6=l}p9FkahS*-n6= zN?x8$jboFM!dYC-CQ>53x>M!dBhjK6|A;f%DcBG?)#CU(m2e2RNed0>P{rGQ4^}MR z#I?aZ)hJB9{lKO(gortV0kM;l87}HFu7mHQ)Gau%?@r(#UN#-9X)TztCC+YC0!e5f zdrV@UA8pYZ$oMaD=2|@&rWLrN9Qw8wkjziY_coB4DWV51O&~gM+bfo4qP8GADuZ%1GNr>=iO14rImn+>jOiJB$ z=yR4ZskEGIY`oTHheavt+f7os2RE-a#|!m~tQP1{|7@MQ*`#jw!A$?q0sU>Q*KZHF zqvAAPE_!UKh0Pghpp7vLm3GA{120=|sTllkBi>rP8_Y{JWW(j+=;yK6jK`M`liH+5 zbZUj$MgCWD25c`-tV*H74_q9K!XUKqBYw1uhoi)#loL_ZjhrVD5~PiR1W}T!#q4nk z*qFZ|7D@;ldgAN;kabTkKAwA~R?1OXdVl(NoKm*xr-a8hdJ@|l2(Km~fKXzSr0Xfru17w@uKJwv68g?LA1}iQDx@ou4oeo#jc zmJYg~cYpo^LW&W;WzMnSK^)LzQZ>u+0jYv*E{_gk)sTMoMEt+B*Q zZ4z+r{nWHn05*!4<mM&iVy+wfpzrO-l z0%e#;Nhjn50xS9RAo}5*6klK_t2BnnOzvFEoa1*vvg)d%%;8Ry+XWB~ZAu(AOiyZIAEw|B-|Kg5Im!ifiJgY3wk5z-Ena^-K zhO1|?rfo`BjFnT|E7xBQrPlON-{nzNrKyfdIcDSm%MT?ggk*2i#*fz35x|JjX^Hjm?0Y2g-r568j?U$$UKm1V#c# z+-p~pxSnJmHBH1cmua@&?1lQ1W7}YnOR?gqR|V4gG8;7nG1h>o0cE>5cZd7!*L#2c zapab$}}ja6-_?P+@H z)hhzn4&&}Uy`jY2f zH1Yj7X1t8Wm%@Dmn3;gDc_cBLs{C{zf*0s8Dz+nt^QS@J8v^gkz5&ti)^zo=DtyjF zc(}K&zPj62x)_SW5Pz^3Yo%tkuQV75(Nxihs`ys!7PDi~RXiT&l=#WeG15&lL0v?u zkCd!ti*}`J0>auO<}9wXl{E`5v62AHZu8;ykzOG`zty)B?IWV*c9UNJwbfguj6-=T-mZN6nFXkx!-Z--6ObZ2sf@ebeQy1FVyW%Co#gJ|elHNs0+!f>CE&~kQTu5AWT(-ZaG}efcyD$XwzY+yHpsLEk=0)qPax?jQVsy3_T=ycMvXD z^)eznvZS~-60Z;IEZ&oL1u_LAP09_{mEyZ~4>k-Bdw&*@2L{%Fuu`7rF3sphb;wQ? zK4v8_93e|}0a38QUp*jUhs!f<;`p!x(gxrk#e?`*Xm~N_icPu`Bv`=)6evvHQyja~ zAIl>SM8p$a#1l7+S>kmQ?K}pfVa9*CZH_l|tCoq;2>)i9*a7TF(g1wRapE>%{JqV1 z5=a8q6nGVuK=~|zddoEwiOX_C92=a#3`t~_*3E|#pH&gX=TfqjB=Xbp|5w`L4TiQj z#rc1uEw28*(-wFCH`-$NztR@y|1E8?hu)v~mu_*l-hk09c6WFGL$~O+V9`L zF~G&ze*zaZ=-E;9Tn74A-2XwhK#z~1CqJUc{V{~a;#Bv)q>G7(33PuEy3YpP+>CC0 zg+}S2o8-}TBIp{f|KKl1Mn*8Y#edKiU0q%OpHPiiMk-8`?z!Z2?CcD5BNG6CJHxTwI);o&UvI z*xA|H*w|QGTU%LKVMGfvGqe9DS{N7@=PUCIX|O_-H)Pzfg-o4pw=2d0AOmX=!OGDJe-wNpW%U|Fdhs z!NGxXEm&Du|No~gNGC3eI77Ssown!+lOX)@4{f0l`7heS?jPEsSE{6DT?0c~m|$oN zC)Etz>YIXus-pibZE^Z6+F#;}pey2YfJvc6tDhd-n|l*API38qI-UY^c`xIvVh-yn z7XF>Kux@?)^-h51EyA|T5}*7*S=zE~dmO9S1DX2j^?#!+#2m}g*pDgYy*=zFd<-{? zTW4$M{XOOXowo4DBi^H{o*pXui$}e9{TI>PM`AMaZ?uK%f~CQK(iZ1?4E+f7#RCj& zu@7aSzTej7c2xg&vNv_fYSUv2Ow>)YlJ`H-7I=$lS#X>dmhLc?P@exqTd+lFS_E`Q z+^gHPix47Y8S`}-zetI>|1&isR`xD*>iq?+=MP0ys{etuC`_UYl#CDKH$p6?JG(r^ zBB1)T<&;5L#?nn7c2rCqYrK+Pl;yRhMHvgn(;5R;{Wsd;iu$t+z{AoF^{0ggVnq(5 zXXiW$pi3z(IMT|DD@xBW$PI+9btp2`qWN|(w8hnrP;#)L(&vwSCIK*V0M2LBC1YGx z{pIKD7mtvgPW(V+@6~SYl*w~fr3UOF{-U6Dy4@Px00NVm!Nj2t4ZrhUC`!xKefF9U zdigEuI<5+N>;2#Hmo;u2nHRL9zYJxgaD;j)a`y*I4>}27ssFY52ebgrl_es?v9rjc z46pKas8G^m_tN_d6D(>vMrJb*UH9sDMXgBYdWN{L<(C7aDHUH=W3pq>@x9>JgdY7Z z>GSsE=@Rtj<^1itCzA%|oLs=wpzbRrY1wbb`fz5B+VQuOA%y?(G%r1W`RAP|9N1EB^+p3KcUy7z>wIpm7M34+U%?a)~&%$_mj_xvFgRFRHW!+7u1O zHa-{8HEsUwx__1PtmwOVS@}j~`=ki>K`-X?l?&i&qR^bV++yUK-CQQ&{zfD~ep(+M z$d14eK;m8HCc!;yAwlBo6gckc=aNn#Srnh1(T;s}5C+KED5J^1NZeIdruqC}3B16_#{iNL9Un%qo)BjY*hEr!;xpsrN06HE zQ6D(>uo}fz$Gp=s7c?RujQFN5Ibp!BBGu8hNF$t__tNCcTprW;^p{@?`*Fx*%l%L< z3HCoR=H?&gdv|k5SWcD`jFc z%?G}8iQ#gi$qdiTL88R*IL;O_!D?SB0XIw=?+sV#3tC)pmn!UKk%LrhEr(x5D>2fW zECg{ZL8seF=x}BX9N-ATY(HVnpi?VMb^ySE!V0F$)eiY^>14nmGya?^g!~rhWl(ym z;l4VS$wE}(G?xB>St^JLT{R~gARS*Jfh1c*;Y(ZP1qZ>E84sm!xmtKY=AXKlW(BfNl7T$+hxCi^H&xwlSfazol$glhdtA(`NqL7>xDHi9%sj5^RRIC$XTS5##9YhGnL~1n zt7Yg|+)J+e4V`<=ugK{ajuhTDxs?c7Rru8IHoX<1!R=+4qZ>!W{%X1C5%8YLUu>?r z|DubC(kmw40)XYx7#iy%ac_Rks29~;##CvZfBbMayWZ|NDfs3*G0cx4sC>y1L9pke zc%*&NZC;2lj&@#YvT4xA2`vn_pH8(p`Ar^`UQOR)Zbxw~)zkFj!w;7?Vv(m`%nPR6 zdF=@waIy~#s7PbomngLvx$FP()pI|t-dBfGB_teU9hzJD)}2cl3zgx9!c<skc=6{x3KEM5Rmof>w2OEObD&E!fTph$t(^Vg#BeMXO3+N$ zpEIwKv_<=@k2TGUw}M_>{ELT)^(}v}mfwwkT*Sc-4E8^Ovy|@#D#I=%?y8mX-^KW`$Sxt{KSP*;=cx_ikK93JYK3ulv30*nprJHsy1$G(kyeEFGlLy&WGK6t$~0LLMAfYd{r(P z(#S`j@+qsqNOcR9q(#%SL44Mqx>#c;cD-fb z_D26r<55blSQ?z(N#uP^lx}!Fl`ic$;d?8mmW$P1aGvL^7U7G}&8>?{6^|{a1|GcK zZd}g;0rGnh`tRx1U~2~WOq~x7%}eXr;2PnCP3FPhxD{Ids>^h)-kc4#KcCbS;nhC& z?JupLiWZ95(tYj%Bb!zU3|?v+zaM?k(*1T=jayb(VLvn8{O+u#Q_i^iJ5}}h&S442 z@8D1wuzPXC;-aB2SNX+rUbfw&DF^y@a@FSwy!5NaU%MhMAyE6=jOWA4YxHp+x@=R& z@ye;hkCDj#q8?O7JrXN_9e4L<;C{}{MO^GBv$dO<;6OiAf%%H(W9 z3-)WJB24@lAaoJX-s{Vm7Brk7&}=89aYo&q?>%$wQ>sBZpF*fwWg)N`ct6eYyeP<^ zftKEmH*GcOVwE~u+4^Z+h=nuNp)sIs8U!cxlcEW6;-RO<1|00T+$KVos<~WOLp`P$ z-9@>pUI)ZVB3~$Bfw_!rO@rY|KEt*?Pff#-A`%&EtU@*6(Nb)@=o+>dnur7%_P51h zmd?+gv3hc$f>lgaPPqg1ox}6fD8hw_4givocmpGH=q?LM#Ta%|KsdH7<15psX;P-& zwoy$|Siz4XQp3%%(kLWD?K8u}0%!s~BmxT>qSX!Y?3ZyAZ6Fs&5R8J@27x<*BCOWr zZ4VDXI=lCRDWg)K*f#|G)4a<`i_Yth-ZiDzvjMXsNjzC#N(UrQVE1dnBkUYw#c85< zQmLNd`7CmW_INpNX_^mC$3h_#|8NvY&>L>p@|Z4$qqt)Q5l>+raT6G35|}O%SZEX3 z8WX4xcvQlPJn4yikVMXRiTsy|!n}zBv`OMml8A(pB+=w^$$iNj0Yg`&*88!Bm}=&THOx(^dQ9sLt99HaCq_$ZQ-2$ z!KLxTir6>LH!#`6Ts?bZX$Ttve#scP91KGqCoh4P+}h_=%W20yj06SkorO zv?PV{T>|ZsN z@U!pD7GSUB?@mV{LdxTb#}VM5{(^w39E4eM@RyR;bVZLyf!>X< z=r2Xxyr4T)EL>ZXGaHBr0(@Gf_QItkl`cEoyZEC^Y1UwgeuBw!H5y)EVvINehvEc)*WiUUgJmI4N-=Nl zlM%%mGL*QQv29;+P?52aJg6TZEW@U(Vf^#jcJd!+?Dlr08DEiJKo-7DIrejA)^OZQ z03wgXKNj{HY^n^Ht%OBZ971w19|OHT5Ft?IAb#MMDc+O~$uD@xYEv26P~}KQVSQ5t z+N}Cvg2?~^hmpQq8J%B{5?RCB98Y1Mg>_vM9a@c-@G{8wYfNO`QVFKv9V<^?i(gur z4XsrPzyhl~;_-iL45@vv0!G8d_+Zc(1Co_02)i)MG?(BnhGK%_VjP7L7|HfBGPe0WtssIPBpY{jJ%SdIh3ba)w!CG ztCk)8*tz8byvhj=Pad zf*vDOC?JXxhGG0)c_|px4D;i>T5wA%l<=EOOPAmdN}d!8{1c!2roOuPTe3UxBNkW} zhGZ}xurtIOMgD_Klp7E=uVT+4Aw69LjV$cZ6)gaKp>4euMHMd2u+;_Rr92zP5$&5Q}011S}*$sgO`E zm=FpEAR$x2urG*KNJ49JS&;Kh+^g?};pUFZ&vEdkLAfp8zt2B$OMo*i6HcOV+J0ki zk%G=xpvp*4$pNt^Hr@>j=DrZO?trM-qbUsria<5tS@ib2`2JzOE4^%>{<=(+w4)2= z|G0Vd_oTeO@hvw0Vb|+VHW~TSykvn__Nt;3*FgmB)Y*_~mL? zrg|MZ!;|La@s?Q?_U{MeqDM6XusMl-YPA+U&#FwC|9N@-^O3-h0LEXQt`z$4Hm|H7 z{CmHAuO|%|r@j%)kYrMDEReJT6E5ZX(XG+Q+g8??nZUgnZ9`BmXLm%_j9KeU=H9dd z|ID+SnW7j9u+7gt1MFO)$=Bb1ei4YwTIj9H`kA*krxk$H#6R(IK2LV|*GbD<{ja%R zy=genk2pOFEEsMY?r=TPLVxS8dZq8*(U$K>Mt`( zuAwW8bNjA~>jG2i9iX=hixuTl2aHPwQcEbyrHh3nrWgvw_{9MhjhpvN_lFkhRu+IZ zPwd#qcGs0Yy+viE+1rDG&a4$(=*l>ojN~U3J`DHw&Nfmbhfmp~VT77c8#Q7kQ zTdn+7jM^Fntw~Rt@q1O=r0c-NAZ|q9P!m@k<4wUInqQa&M(~6qkc5&>MS;bn5!msfK za@=@4#Nt-;gDub4osrb-ceC583p;HJFv$Zv;Rm~hR)6}57n>?Jq?tA{NA@5qYqtjk zyLx*`6~BJ^?Y%78Eg0NAY2Evp4cm0}{j9fNE4cnuX?;`BcH1w1w_1ODM6ssRvA2Z6esQvdDLh}ASLdWT*JM!Srcx4*~OzOd1DQ0GVx zgajE0|HDOS?>-ZRMP8$=@?2uqZ%4Kj4mZPFH+x?0r@TD6?7_x-7iix@{e5!mwRn6& z{3GY3MR))4kGo^Io0a?lNoh;lb`|jt1f-H-fC-tPfXGOFmSIzDuYi`UQKb|%c|M#*go=C6iYKq^?MJ)Ov zp7}CS@iJL4)dRra(j$CjaGAMu=?qCb6QsY`KdrRZj_B1+?+=u+U>ojUk6(jJFd)zvS)# z591g6P|L1X``u{Tt89_0-gXrn7<8@51+N+x9pAkGxgE`3WB+?MNdk)ENF}8vQL7l*g3@kk({QanoJA{} z;~CldU@RZ6^1Gn2CD;dc%b(p(MD2$|MLh06eB+qKHl_bcTSOi$8GQ+&IkJ1|M*lgV zf?gqd`_RcW%6`B^+{eVu?3;|r1Jy%3({_E^nL10adVBpA+psr#^rruc-t=Bm9`+HgCC_Q${aG2YFc{ALc&+(j(|Wv6FGoGg?AybhSXuhJGD%7F%uKDd5Cv((l6RZD=*f1UeyRCxe8lra;rS3Fg!qtU-MT;=!vg-RT;)rDftcX_(| zIaascXM3zNiZ5fqUsU501+Lj6Q#j!tT zAWEPD-4);kKzc{HkWYN91H{NttxB$M0qN|NQ;qDQIxNs_@0iwx6QL6m@>FQ-*CJZT zHB?13S;JHfd$!&r6Af@Ues_a!d5o1Oab`Ir7QpC1iJAiSYZG$pPmLbJAzddigW*uk z-!TqO86MyH?l&cN+-v^y^?@wu^+RFmnAs$K(Mq2rjc~-+a8e!miV&*Gte1KGK!Z8t zq(ttcr@)vBIv8r0`<)FQc|Uf1_o2?5uKPF{eT=xV@nZqXvW|WTJ)OzSXnCs1EA=0wO+Y@XEJqHMlEP_4d17qpS|5^Z>hk;1nUuhpyskvBSbpo z@uCZ9q)wb)XdcQsbg1^HB`HJ!LtE(SHazh?e%-J(6ucEX5jID8VHv9!D*fk7`K6bw zrPiD2;QKf1pFt@)3R|-{D=Cf61!@Jf_POp(8EZp-Ru7(jM2o$AXOD{QmD!m{#PeLE zL_0#CWEu?)x7+!CXxcjb(tG4sz7%RMTp@-_-xbwt_0DB47w`CG)2+$otXAPK> zSXuX;m<;pzmLL0b-wEdrM$^dI&doSFFpE{kl*Dg++{ZN(zqliJ?qH`=SVab>pL9j- zy4at%WxWX%H*qF=Hmj29x#W*OocI0I^Hy!{agivtBwstjabF)fW-6T1)H(58|CTx> z9lV{+>u-D5ql=9!YwtIF_8W6IE9Y!CIa*X?1+l!{&Ug&O-**^&Z?*2Xo}Esb&pw=jo&m6;{x{w!x0*SE%FU zAh#?IphDykQ(eHqA2VdZtiw7~-K(SM#I2qQ!%^A1KBz2eA!5VsnK9zh_6sc%#^*;M>Bc0YN$!y%*?UybszOAy9u6k2ADJuZ*b6-Z>$*VEI%z!|PBk>NI!4(&A8uj2AmtKa z=OYj2wlXIf_Sbr@v5y=^I0%v**uq`yzG9|75~LTB6kneuS*`AHNxMo7)%hNido*lJ z*UUUH7KLWr1@oj%my8AfR88k@EY_onBqKUi5u=yq(o}JgRjvukAywmz;Bqlc;KIzb zm2YYikqH*VSztth{$%de-0)Ld(@TF#gu5W zRfT>>6n}NRyytv;nM~x2L)ZdrEB_n95cRNA(Hj6**KokF4pj-V8mPI!n~YSoiXc&f zM{j?=$aUcDv>5a|Vffgf?n<8!qmDrsJ{e#s ze;_pnVAxE(dN2Ky@Wu?O#>>#g1paUd0l*-Y4Nu{~Jj(;$C490O`UFerUP3&_KL!J; z_Y7cx`bc36h99`fwTI!s7>=6KG#vD4BOsLFal4S!sK)}G*&j)2w?L6j3%@);P-Rb( zouTj}J47rm%UTEc5RDRZAx(tJ;ZU0PEAxK|ST(%)jSsHwRP>WwCCh2>-g_ky-P6KA zTeQ}fUFaTzGn)*);5LfZ`kMax-o_76HDdIbMmD;GA;T`Q~hOgukKlVG&JQ#eo0rsA~nm?z=o{M7f-eQh?QGk~L31~R6p zMuu_qo*r~!L!YQh<00d5`*BDBaF^mT7~nId1=4cWm5mJNBfMTuj&kXy8|(ahTk(#U zF+NSi!(m&@ZEdRfC67^y&d#%g+*g7JuVA~ZP*xUJ%D-M%03nRX%5()fg2J`m2#8?e zP_DTMd4od7vG487Ui97)5s>Sqr@kzBGcvj8Xxg$9a)x=m`|hP7>zNP|+=8M!6b|EE zje?cAq?8UyI>;)J{=>w(<(HP5%SytCs@=WXsv!pG``41~mabHLADm^I$NY_B9$?QU zjq~hYtp}&Wd8S!O9@nyXRRlH*?)e>5fdEUC0re{W=qZYtr#WOwcFmClFek)@7^UG# ziDRby41;k9&z*WV%>6rleDynlV{nGVYETdNVqcHG@S7EviR976t9uvt)POLy?-&-V z(gl7WcjudO74)Se^?M@+n`l1}+f^60Ulu-<&(3HYK0024=1wUv7#T!rbts$8UW|1k zUIa$!Z{pj)0?uE_PN)=YB{glAw)cr4pMVuGoqrz#FotW_F&AOIz-M+wl5%vAiFc5z zc2F2~P;w{{NZ}CJbkHPs(CR8t2P@HacQ9Be(NA?Sopj(WcQ8|QuBn7_W2!C`og8wV z)JC0L^GaO0opfIE+Xd~AHCe-p(4&47(Jo4eok2w^NSLBagriGTyh}{AOWddnE#c55 z>DhHZxJxRzOZronOl_A$G>*X*u1rIh!bz7Rs2fhGqLS7LE>q^$Z8m`6GiriwF)LyR ziX_QQFbXB^+HNw{PMz9r-6>V>weAPHo%$d(a$f)h!eb9tGGypsGU_p&>M;4F#2XAh zO_Na#uEPT3dK_SdEGzuQ!4NKr07%||zqFklUcjO(9}a{CDN?(%)JdzFTSyyvg$YXC zr9XN^X^HNnkvhNK%VUD1PK(EP$-bV%0?Pvr! z^ku{cnWFGr5y4*O(V?FGkYG&=JaZx|^O*))J~WfT0YKkP|b(5xt7 zlAP9#juzg0f5g4PSSh5nCOo=Z=Jh<=mRO`(6~3P)zIKB|Coq_s+?w}7;kdN9z(S)C z2yXNV;?Zmk2MtyEqH>%A)Eh$I8H5Ne2f6g$FH44(dumq5DMtQZtlf1~l<)pN`e$Zf z7<%ZAp;NlMOFBfPOF*Pc${85C8x^EeT0lUQQbOqx>68!zlvH8PeD+>vuYKb8J?E@- zo;7RM{Q1n9XX<_5*Yye*Y^{q&q~j}uKp56#dRoh(ofG~6B+{W8A?nyqiEy6ex(|Bq zXFfM_3_9Y-R}=#khcQw}u(iAHdo#UmC;SjvTmfV}K{|S*`}3#PkDtvHs^srJcTQ+# zj4f0_MX`@nW%pomI&@>h^%q)IzdFkgSaU2U$0IDWltZGqk6~#J<@<}#Ze)A~@ zHq4q}Ln|}0K2B%eNgpGIm@`HY1BQEXcF0Vu$iONwxs5i|FE!%a;ka|6V>_exYH7l$ zz(8zn5>qf74WwW7q)wt&X3%mUXXFZvgxUnYqlJ$+W(XxTb3aU~)+d~Q zCn3&=0vo-?2u!u9C)lj_*c8v|uEfCQk~wxvZ!!#Hu26pn%(z{u1(>Fv1KM4~$Q{I} zCZ{o;xPH;nY~y0w{g4=|99(aE$$1`ARVroicW-lO^&HbdM=<>{KgChcIS1YkiL@wo z;@Ued1o|oF#~X3x!ZDASVzjObj5y6@jx54|^*GVCku*a<;7tWI$269#JF__;=itkFy$Ky1DaTepnr&tE|gn%$P${L^3}r%j{`ue>>1dbgxR_Bhx)dvd(zqjsnE7N>-pYNg z8-^nNnG9Bd_Xd}sIzvi%=;hJ9@|fA@)nM}`s2fj=4SKQbro!D4%P!yvHVOJKEPgz) znv{5usjcYL0RrL+HC&cecFe0E%uBZ{dz3=L7vj3Y(N2bKO_A*`bl-Oyr zq*>~bC21;*?t~p(O(nU9BnjFm()jwNFg|E~8NCn{B)maUDf@fn9wYHOJ~cjAxz{#b z2j^<)Qo#0ap=p|OjK{yJh2mIKT1PghEc>0WTov}x=kb_kf!N2drujcQ+}_<>a`*zx z#EtBT3tPamRIcqzu@mMhJU@3*a&@33u~xY?Pjmx6V{Mvp)a8xbdVi>0aDo!$iC*E; z>Dt+v>ck20iIsZ{4UsN+pJT7(<-B$lPp(X70M|c?2ZJW3c^mA1#SH3ca+p-(#1x}V zVB3s$oTa=R65^+MiQ&NHGb!PFnj|j9Ue=kzGcNO{3b{LKQFxy;U@U;S&6uSv*S3w< zN_>;{a{wTYgpeps+75o(Qoz^K*wwq)d^peIFD(PmqWy<={3>@tSHHzvtqibJO45Gy z9si~k<08}S9F)qSRUM~~tqO$2Jn=z4xiClG?qYgY;z^|q4dG)r+7zsuF83t2K&h~z zQlW%Bkce`#&4Y(gx6E?(u|aNlu1(RE@Ga3FZhi*wz#e){y` zO0Wdktj9$xfB>GDyVCC2vCa9^Hd}2E(UzvpC$0c&wNL$9eC{4PC4N4%KHU~())Ye< zA6HHddF19%H7`{CZ4azbfw1oxfFM8f%umm{JSHi^{RteP;*SpQG+V&@Luy|`kxV=e z4_&|K_&+MT*tI>kHPlw{_l?G^9CXLJec>#)ybpu=3-=kshb(Ad0jfCj!;jP*gNm-* z?YjU|EQAjU+F6~ubr;`!)N=>UCMJrR)Pz}8?}SW(AXwX4_VH}2I&C>{jRAI}sO+iid>MxDHIdLrBvf;FNcYY$ z3x+nVc-y@lkG;|N9rG`Y*5fD%L=$>pH!{+X*xR4vVFF7r4wh1|hWlOZ{5-CKzQR5w z?RLsw|KAPAh#b%lWtW(Eq`1y9-P65M=tj|SlpA0sKjFV#0*Ppf*=dUj&xeR;{ba|S zd7rNK+r-c2j5IKxNk*PMACA(;8VZ&%Z4Ci+onUiIJM*R}XwNrIt#dOiOB$Bg$9nO! zPopV)0*umro^ClLr2EVE;3_Tvf<@<5K_|{iLC)U!&Em1IG~>Cr{U7yQFr_*rtj9gH z$C=EkG#W*CoNoHIE-X$Bi4(l;AHN=T zpEd4jdNf)Zw|~SuLHUO=O@J~zI5NXCUidso=$8-a%M?SBz{@M`shB(im>f(*QMe!; z4$;ep=LnOJw-x>PxV(`y?oTeK7wdak-UVtXp zrlO`ej3@x8uir_`|0~A>;Y^QygoN&z$Lsw9bOSUv(I0p6`o0Cf;f zDL){SDJ7phEXVW4OKNEr? zv-$3|cy?w^$=`MPWdD30w!N%ZM2nK4<6vI(>C zcc)6y1T)kf^%VWrw}+Kp0L7|2UuP-Cx!9}GF?WtT{0XT9&fybs{Bx)jh1uk(8AB1i zE}pU!Sr1BucXO~_lHHUb=V-f@FBO3WrIKio8y{65#{h~Av>D+PyHq~#tEn+|5Dkps zn^G@Jq>^^n7!&v6+R&wwN0#XG^FHoPs_TH>*DDk{PI&xGS+DU@uZV)96lyCyhk8B(pGdL7r?kYjW{U(&?lQEZ`8;2 zMVJVnT?z4N*4(q{iSp_udFJ*jjyZTd9R>|Iuge!hAjm6MONPk(1&GJTq01G{(f zEAK{hoNhwF>zwJg%}i3q@BZBGLA0HlQSM=HAGUf7bCY(u(`a)f6A3sxjADp;{HfdT zQ&pvcUM9=OIO&{GGaczT<;~OtkpeLdUDH?FePV62_xdnm)%F=0{BveNFMnP+r5xaT z@9k2vGr9cY)Q`xjUR=>86t9Tw7$aWO7Gp2P4eKD>Dw7d>cNd>*dui*Ix-(8tgC@u_ zfhmBD!4pu%PJ{4>{%abfm`AQw;N%a4{4)(g2KO4V{0VVD0QQnO<;1}@Q-zQ+o{zkl zL{VQT9IBe~6a+(Kfr7m_5z%Uuz4dkCM|-_^X+s}3e7reV#dHh8re<&?|r1a8#j)EDwtWvNM%qmH`6slfP1-=jZ3U%g!+E7FKa=u z_ia=%R{*y(o#g<7U$LfuS4K`fhKLqFr<52|vrYchjaJ4=v`xt%8t=}P3vskPsWA+M zUlTG!XbDyp+%6+i$yaZmZy#|tdHwv;KF2yowf>y&kj$dY0K^Cv*QBDk;9Ih}K$b~t z*xhK#^7L2*zv%etW@issS=Q11-sIp`HJbZw_yEW#&U3kpJ}$FTf}(aZMi=)5=J&Rw zv06#wnF@FBNFKvoV9Goep1a|YNOI>i@fI4BzK{X``9B#F@~(D zyVbTg9uf)9HOjcCYF-&1V2rmlgu;$EaAQ?K=628Z$?l)?{HmFV_*quk5Y^TgnNn(L z$2(W^{F|%H(pLjGEAGLecon+-Kr2VI%edEZ}4dVZT2+b@gX zYnMD_|I*%#m~KJnsS4)Mjx5cxe+A-W{LSLc+nupq60Szkpjpzh_m=PA?F|X~P7bw) zwA@d124jQ$bOp{W`7~lbWn>6A{vhWJ8AwX=ek9LmSiHru$J)SM9=^;VBs7G$_?f3A zHYE?+F{>e0&MeCOR$2FKOi$Byq_oauZrEPS@ucq2Zo&OK1HnzBDY_JyBBmwTzIGMh z*Fidm&m_fmdNNX86r6`Y*FGFh&%6~Z;;wUJ_I^GSKaO9m-d0;2piErT{iTY3*`2-d z`CPnf%P?ES{uGfi3x@S$oydyG&d;tdh8car^H#2A8YMt=>akNq%DC2m{(NWUC)yzO zsE2WqGr#rQsxnrxF@!`vXjo`<-!B$VIeod97-<(Q(D~-+q4kjpvw-{dvingdwfT}> zjlEKAhV4uB-dSnRH$^O6%TtwM&fimmO`%QfXw2NAtXErRbKz07vt_a>qP_VE^fW$i zX;}jmI7~9`Q(?5pQb+s5j*0mjlCYb1g+r`kE!}wkvGtfl@aqp%n|o^sj60gweW~Gl z{w1~YQ!;4;WqB=I%BI;oWF7moX{l!~q@Ev`KMm}28v9bBv_prn#QXBj>Wn-%yy0#} zU$?Y~M~SeCuct!6Tn_VPIfo6e+@;OLz&Hi-p*CSC>A`}zVBibVmnQ}rK}w-2pi+Cv z2IDuupZ5hR)8jDw$4@5`zAX7ZDTYQ)`D^K}>>D_OEq!RYeSS|Q8-41R<2=*yz4^X2 zdidsk|W0Y8)p0bWzU=5 zjqu|Xvdkr{z#l_h8!i8a4zXi?6-)K}oGOZ}n^=9^mUl}XgoFO>)N^>={?sVeC|QMc zXW!fCMyi>4d}Gb>3FTP=&CNaFejv8qCd1u~=wG6;Gs9)wUSYY!#oa-D z{_~Z2?Is$cXn%aejHkP9fTPTP7A;)ByfwmjUB3#YW(EEHfETF;vt1?Fw#C0giE~i! zTc!xGwJ{OK4DnED^ni#B#n-%vHYlh|mYdf=x9bMN*pYiQ6`vWrYmqoNH-WfMM4ZVu z|30NPD{-U)dafAH)n-^@jk;2u_7K+j!NIbS_2inF;F~(W{ntgZ=kJpl^i>=vYd7eB zW;0kYGkR@6mIstPqnWHsX$%S}6Ky%IN{!Q3lOq_6osm6cc!;P?&cRil%u>+i3Y*mi z|KTu!IyNy~#B8w6+=b(hHa5<87?g0}VH>(b;>g>u#(ObN;>SdNIQ+F^Q(T{IC~*BE zu&5ZdW|U3FaFWE+f}pix*J~>>tSE&TU|oX&K?J)5Z`p>(mIR3g{yGsi?Z@;Q69m0u zo&#np%FU_3*9p7{;!oU?-YgNgC{t=t2P`LrSm%vk0A&Fk*(df?UJirp;x|O>pE7z= z_mGM|*agNnWuCJGM#Cp`8gVYl#?lTF9@~g%Duvn?3c4(Whw&U{WQ5jE!Q|Q*wKzB!ux#BSg z8?18s8*#7rVLT(%4p)ZL_x*C{>bhP2OJk1I*nBoaTLv}T9Ub}t3tL;RLl_g%Mf9f= zfrp*gCi+q&-#EUAxPZmnqN2sYS@L$9bg?fLO=9bsX-QISeo?MhpxmUNKz@5S5RUow zzyrG~R<6TW3Hd#wWF1|hz~y{UL0r4;(WS0TKE6q%v81B{ws(A>xcpGlMffL)y5fue z8;G1Vv4@9=GyR5hXr+M<$0?|kVU$&P_1h<=Dh7uNl5x&2ZEDo2(>~-?9v3bG7wn4} z4&0HYD;X~LTPlO^JTPGG7sn1Fq@!t_Il*45d}fP5u`a=`+Ya9xbm2(#aIg$9E{KtX za+~d;YSmQWw*+@5x?~jTUnJ)`gxqX5{9pwlu&%WIEkYNUW)v(ltEo!_aAvD1Z1>+| z){pGMR`Br%UZ{y2zAy?e_tkwEQ2Njjsv$=Uj+tJAgbbv9*ooy!q_ym4L}GXV>3+F_ zKFVQLsXZgLN;jP!yEus@QdBYct)N_Ou9TL&TriNuiv}mY0D*T23oq^veyEqEYQ=IJk2i2_e?gbE_rg>m`Jpa-P7%87wR8O4m zr7}i6Z`e0C`lMur((Rbg^@+KMjB!SL+*gjRj^(S#t#vN&fC%G>3@h8V+Rz6m*P1|U z6KiYdJsg+$8ZKfQR%2WkCplU_K+bxptfOR;-QS#5X5R;5$K5MZiQ+x_lsHUvoBH`$ z(IBRDL^{r!pjU4q`8!h88Iwy`1JoI5H8s$$x*GW3w!eD&9`j0v*5e*4pTTxN&tdhE zirRBU{t@->t+nVj*$ljJ4a>t?r?c9=aom2cI_vZUh&GyA9n;8ERx(Btb_)AinSpQ-%^4-{H*%DqJ94b7>PH$A2qwLR9VG6(tA6_ zVceS=XUtYIzc<-lBAMI&4_mMeo{>D7)Oj?iUq5^j_Y@dDkdBheMv;F|&GI@L3w;^; zg9GU1LQ-oubobdmKU&wcpDg7W;bSW|VPH8NR&c{qt;Bv-I2|5Itd?0&yYmapkw;b}l>HEt(rJy`Lqks@LMd!>iS5;l+mRl!4Ujes>EY zt~t*qrC#)d$(Ni1ewsA7U0eGv1@riXtP@?k>5%m|(Wxzs$Ab-94TLZv5?2xp@D*>d z2QP+gH*xw$8P6lPh>xjmcR&vsK|)(y1)SWubah^^jRT=^(c|q;-2HUQ*t6yLY%P*jAK(t`A-w zJAqSkb`79#sLc;!V)uVYp47-rIz+6Vz?x1)U`Bdd>dR{CDlp^8aIfk5HiuyEyV7zr zYl_GgjE;<%`2 z<0)iL6u$QJUT3ew$?$je*W%n_SAG~gTsRGD2!Ut93xT4RM1v-2DP1`KEFb_*n~ch; z6(ctk!zt6^umh^%SqyZA<#vS>tD2T;^X_a7DB-tqsPZzCink1aFmy7K-!tDQkN%cMXh#%%6upBmGlxcj;*YJ0^H$9@T29mZ6AVV ze>HAz9Ybz)xkg_H6$K7I-mo@Ggv0~Bb5kRjNXL9!aqrFZ7R$JEdkVj6`W9UsfbCeD zv#!ym@wM%nUq05rIHh+SE#?;_*xx}c;4Y>~G3&L24l?RyK)R#X>4m)wo|s|PpdF5y zr);3^+2N_8pJAiqMd{Lmx4v#Nzsg?*-PE6h_=oTh*ND}$H|szW1Q*&A7k&(q-cc7^ zos+57V8=ffHqqw>U)nvwjfI3OqO-}iJTA#!1wPyrD?1c})Butv+JO%)1FIy>r7q2g zP{p{`U}w-M-V#I7__5(12REdqMj zu>glz6!i(feyHXJV1PDD!gjYLPL(&5?|MUfjKcjwbT_6d%)Ai z4s#)YcX)E&Xq~d)-2wT#AMTFoj;ivOqX&KNa+*tL%B2q+!j$DYbycp-$ODXUkU}Rc zWB75BJu38f&qK0;&4W7)pF?MnBy*N2#4cm=0mSFEIAYGKx&ma2)x>%swRp;8MsxkC z3u+Au*M&|}iQbZCA$B6Y>sw>LIDbjiG5jux^Y>!W*bOJCY9ZOrCpkEbK4?WV#n&7v zO9Kle?VF}ydKut&a9Vg@d6ull_s%hrAyD@D!H!;T>2IkCS%E*76?KMxq`CeM8|qG` z-K?kG)_tHE#YDRjVJj=@s>Eg~N6)e5nUh*rE94DcBQ%Cc4VFemV2uxW$d&rbv4*{M z>o6i4ffIj)lgRLrUc=!sk7$M=6}e*~l2aMnau9`Hi{oLAWx4l|k{WNhJ|SFOvv!S- zeG~F3NWUk2Md5Fr7Ca%uW!@)axh7*h_tS-ERv^gHVJLYXuwLsm$Gc8F%d25Gl)~Y# z^z859o;R&M$3DVw!rkq9_5fqI3MFe}A8GCTW4ZjA!_`$3hO!HqXXS0e?JO!%PY4RavCbk2`Ne( zbCrL5GLjAmooKJWP~`m_X;P+%e^?ap8Yi{`6bO2H^7Nf3_iqP7idehuV+y8&S6Ayw zAMLLCAx>c=`46v~&*H|8jA{F@@b={b{0NEfxFL7=TA8T?BIhh{75x2 zk5zfZI=QR%O9ho%oJHe3qf`xv)MSTjUQJSrym-!mFNR(v{C=hDTvyJcdyRHNsRH=a zY$h#)WAq9Rb#@eSbkp6aC_s7fHSB1${*{UMKzA_4#BA}+{!BHxlK^pLIH&g^4WX4Q zFC(Bcg6eZr%4^CfA@w*qn-fQyM2)^7b41e-#mjSAj@~$y3 zr9gq7<79h`o`PUSYOJy7-RjL<%nXS_LKj05o8S+G8zViD=VTuqzA0%7Cbl%abZgm) z2jE(DgW$IQh6t#WF|m7ncn$vhkQc_pm#z`Z=Z0|+(Se3c4KnyT>!?!bCI3**T6Y?b zms)K?Aqc}%MMqdnomxhiUz>^yp{+kmMMc1V$Hwq>9!~2e1f7w6x+oC;LAy=O7p2Yk zmoJN-(;@0Lr_@@xm;!HS-Si*|*1z>x33MZNw|`r_W-?aVi3g9(-)C>K_;B`MDvhf` zd^!f_gRvp(bG|P&pGSN?s4~Jh)1xQEhpH!{=tm8+G1q4Em{nw+^H^Pr&6VEuUY_lv zJwa$gj1vUgRZI-$s5Gp3GxzhZfTq3_sbnOzy30t*xrL{g(|k4My@Kg`c&ku@QS1{FU$+x)q_iZ0D-dl+#GYH`c%8U5IfB(<*%1H0gw0(@uov+)U2A}(^amtOyM>+f+Dcejcl2$H73iZqE z=4@?u?&cm7NeyKf-dWr$qZ^;!l|jAd*|hhB_HGuGrfTmdHVlTktG)Tw<$m{+lBTw7 zG6`dZhzP6hkwH-s7yxuCXU1^k#ky!iSao;~=@nlo|Gm?h- zR957G-EM~4**5-X>0Qr2_=9vjlCZsIJW`tg7&zO(dSgZN>G;@X?C~Q`;BY2e>UE%6A_*quVFCXtCVg*=}6K&4J7~- z?XCa<nXn zbZ>e;-8lSV(+06`z8cey^f-mH4N?@XI)Wr4UPFF><+m@93VejfPk57}gjR#sAS2Pd zb(5+&UxS4{3jOYg5=W{CY`xbCl5w@^WkGnwW4+XD49;z77P)B;AAZ_CMMr zm7I-Vc`1v~wY(awH5d`Q7RvlPDf`BPe3Rj_0qnTzlMH_+Nx#*!R#nt`w8ZkYM6%_) zsx8UG-OCqKLHjioj;hP?Gq2O}Y2Iva|jr|MEm ziw(1q08uV|~2O-DcFP-%Zq zf8_r(_`y4}%jdLYDsIc^kO}p}`_(pwCQRQ=O$b0KgRs)7I^trcq% zj#e5yY|)D!(jL=0_IAVNd+^8adIS3Xh|(*lb(q+L%R96VC%7(NROF!F!xaz$_x>%m zFLo!t@3r;g&L|DPRs1E&LAg2Ehol^}r(*cr_xE?rIioA2pcR34Z4xg(^L&ivk>UGa zJ3et~Zzn+LC`LtLqr`g!&PHvP+5P&xre!`wF|^cl33I+_&2OBT)ubQSKaS^For;<1 zT({15Y0R7|xWlF8-zFJP*jD-mJ|juji@6bbwDuc5K;{e|lkj*Bs&}n`cGQz|Wm4{a zO(&&2uK^v5wO* zHebAZ!8pAj13$JX!a{f04^4@eq$K+~Nk^;KK^>?IK?{lsR`F6DaSgWlq$^GORmQ6F zCbGMSu}THoI|(7a?CfAMxDK%l4^jixWcQ42`Ac8JlOYGN;ZE7sE#{Fw%zHQHOCIdbvuG1bk^)ruU^>-EJrH)m;NG}?r&(9LgZjS%-hlYlI#BtG&Ca&XTvig>P`h@#t%a_D&1XA?dj_h_E#)7J9 zDS?$l8hnm?;Iph|cl?^GM=gDc)%#x2jfz)QdrJSl1UvzM9OU`AtBP5pgNdfOKtJfO?q{^erF;^Yg6$@C^cd;`S(yL}MSYF`@YT~3 zjN$EXN-n`+ga5MkJd7l{4T@QsHH66cKo!;|_3-i|RJOvA+cz)-@&S9hRgB=~(kY}rNxaZ#IIN1M4u zY>as2?UT5sN6;1F;x1uGk1){@{3iUztN|N@>n^d+`cAAjn~wlta})8#37p@F#P}}s z_=IH02iK5oFLoT3*l^CF3MKjc$z&4pLWqRQ;5Sb_34<@C3m@rPI(yTPv6ss0vp*2u zlHm$drv$zfNlg{nr_^>M&<8&33qK}Jlrc@-Y_RpmuH*3FQ(8kZx+Fa4KAZ+qn1NvS z{VdN0AtF7!B4$gyv+rh1_{Nu-A5Ka414~;VN_}6*s{WEr!{;;JWGPgi({|czsSk#} zzbO@ji$_joI?bJRic97D&X$}D*N7|agAV*;o;Lj(JSLSOlhs(1r^bY&YJ!Jpic;t& zf;m&h#~w$l1;Gfo*1@S!e*6SL~UAYya8 zS^RmtO0J|@4#*zid;er$DE(e4D(EsL6yqaU1t#ovpeGQ+w=N+H0f<^lsNjx}g+59o zfN#~uXweVBR)(gplk9E4;i`mZC1mJg@)J}iv#Pk(%%SeDKa8dG`F?zc_CF4ONL-6b zI%F|}{P`r68G4a41pbHvY={H^8UVxWbrx(60gmnB2M~8azJNWID*{n~{kNnl_r~;~ zE9-(5jI-8DTJl(kjLlIIq%dKs@KjX6j#pR)OeGEiFzZxh0CN*<6}h0ynYNTTS;Zzv z^#-e^8Nvc!6hI&{kqj3OEKQ&Y9|uZuFupPoaMEW8XCoU|iM<%rdP=!QxxsL_LDy9J ztkq=WuRhg%GBwb8f8xf4cq`wZ7M;QXIt6jLaR+&IaYeFz$jcIH+fwjL5LFW^p;Za} zIOpA=*1Hqph}i%wg<`F>?4O70%-Drm%|535eS-k9SD{mzFJ~nnIXYqiI_~B?FH}ix zRaipKS*}!AC;>pan9gs572XdY?*rhQAk4Q75&+P2$<_q*YWkXKz0M-jnp=2@poI4W z!+m6jt>zjyst-uuhEq-OM@En4EUwRVd~t`JW*LC>jA}1a%3c2M$23 z%>1`p$*!LqCtI1Kln#DowIcq&<_L7ALP8Fvaz*PBB)8en}?7rVRJ7|^Tel$t~cBn#$2JlTbm~64<+RJDJ!auZU zE~WrlSy|{2Fs=<*3d#pe^V7ELEUl~v;SD-!)rf^%mgTr~aqXs6N zpvPa^ACI-;_fli&Kd(Ozy)gT^(M0=Rzj(aQEus#opTgZ;31UuK0zaGLJim8931a+#GVsr!C=^AJ zW*YI%y3~_LFy#M^I%~wZX5vb8xY$vP}s566y z`Dlj@BPWZvuq*U&u-wltv7nR~b0hk-Jfui|q>E)>)Rk0he*DyEJa0$T_h3oEtEiIJ z*b3T{YUzZWjs&NWxF@vnUt5wUek9>ZCy&r3<>e>1OCzQhl6)7?M^~v|CF0IQ(h9GV zck@-gha^AEPy0oi_BlWO=qw?^3C9d4h4DHAA@fgt32$en;B}^mOqRrxESb(Mh3hO8 znQVf_#-`}jK7S0*p;N#2vryol>OluUli zll+9v{FLkb44G$`44E8AXL{lFvz4n9GRx;wmKk9KfTKN*!F6ViRa$s`S!l+{a@P=!XD?v?hbmTQHUx<{A4 z17pR^ml3oXgk3L>zE&tLCiiKBxg0)teyH@7t@5VV3RtWPdoJnL>)}*fo$|XnL$)R- zwB}h?O-dJ(s03ONT3gdqn@3+;u~^#{`sxM!tIprA`edQqvUMYiwL@KXQ_pKAWb41u z*L$Sp*I;;%q4iFwtG#iJpn=P_gyk)amYSRzp zv3}vyoGFXRyGxim5ahRQxCSW3y*}z>B7`Q2;XsAS83Chq#QmqypB2%~ z`cI?(??e8sKW_)Zxf{GE8WIVVv# zgCV||d2};RRtlFaAq)aY_f*JEtS7FQC-UT$@SLf25eRD)DqtOt`t5_6k~#igEc5sX zIEtoseH;W()FKcTebn!xmfkTfe`LZRURh>hTp`Y4?nNSg|55_6D);rTl5H*xL@a}P zflq~q%HFkOe~q91N_fo5xUKwfW`I(0?NR|zYtLw{JPcAMxLm=?76%7C2U9j+%jG3z&DSdl{>1 zWKoAyo7g@9OVa?22WJ{iXGaxtbGyukA8&uWUBj*;`z3ii-UOzPpvm@or|pk~ zmp=wpf8;5i()66_L?X;U()>z@cIG`}j12=QP^_ks$+jI9V+uxj?JD+;4i=I+ygAm%0lrQa0F&h&g z)g^WSXXx)MW#N+k7$OGQa9D3IXXN!2G0r5w$WKMec=J}nhmto6gV`3I%@iV1LE#gt zhU1G>jy@BAwAh^>RyAHIANKn%zIgQ{mbRc*usTcakkh?t+EP17Y<>FMbE-DS2TgjX zrBoj%cBfJi!f4lZ!+Kd&%Sm!X0|}^*X0;a0AmOwApVh&C&nQZB+Ht54LlVk0=1kL0EC4+S)`<40x2$?Cz(p#N6 z)4zkY-_a|N#OTaw=vvAhDJ_q_kb6p^&~>&y`|3eYs%b$fI-`k~u@Bt)+K7l{bO55f zs2K74!ngv*{%a)~y{_?Pd?jrDWb1Pgp7OAg2uHv;0>BiL>#5rPE$fe1BAZm2y-RakclkZxVriY(>#j_!<2r(s<%9gh;WLsPKb(ea9>*L)}%MdHo(xvWJ&PRRFBh1`wS4 zj+_3~el@kKb)si{KvK3EH$XTX&D_uh?)_eqjsfe{)ZYm?*jGy01CX?T(0ILw6K$Zk z8YhSEaqV1ffMENgA0aX$U%>eeu&2r$%jcz%TOvuCnDtSjPfL zoq9rf#%)5TP?TiYzgkQP2n=Z+pj+!uog_)KR*9x=Y4Sg@bRjDrkk7}-h*ykK!E2pV zrw9m`)|0vkm^F=N(37y@5J{5gO0_59(_RosLrull3`}a|)r-#n(!_1EW)L`9p%jKv z=Q|eAeX|ns{f2QZGAkuuop`4Pka&YJLTJirgVWFFZJydZnT$w#9PsU-SoTBm{qjxK zqxIbJwlDJ%)B1ro8tSR+3a?K{X_CE)iD|oyJXbhBU&-t7;&+yQ%6&p&WWXN$bp{d0 z%a8u3Bz|>QQJ>KhY>=I6J7!Kk+jH*0XtQBBZAy7GlQo2Y&Vbip)9k{H@(B0EfDEmoars zX5xxetB{mVMC08phB8Tv~@FCvputU-W#hNepqKTWsT=>_{_2N#NW2NYAgBAndl84c8uzak!gGrd^#4 zP#;dM?<-@jACcb+$25YP@&^ev@u$-h1IjrRIEY%C31X~vgQ4+=ASj%`4@fj-?6n{- z&PWt?)S{YTkLPMlD6|79o6J8VzG%e*NPQ*>WVYQTYAvR#bpvb7>T3<{n^LTMi-Ya} z`3hI8=%_Y(z0wdZnvSkqO`926%V9i@P-Gm&e#oz`Y#dr^6!TQLlwivrE%&JyZP|NQ zHhAp2t@|W!KR%kk+Pu`9h4AaJZfUBg zu&jlwGyXSTpo!amft|+Jxn9`N81gyPp{4t%-uo%x@;X6q#|J@dy?@g3HeYb(=;H?e zBEpqD-QX_FY<)vuW75i@NATO_qlVxf!qt<+;O=d~#wQa=t7o;r?+za~hOH5%bA-y=c#~iNNaGLa2y+mG3(Jad=5Veqg%7&&G4G*N2 zvO9f%wzkJ%Gohk2F%Zx+sPG!>L?RCx=}5*aJ+;oGEUJ;1!6{UPQl z(KajLSDy5aSlS?ASXclm;A$8L{zEwRm5l>S##JAycw0Jwb18kBT6_}5!5JY9p?|v& zMb(ZVh+0Q6`cL*T28nG;e||C^U>lF~t@$pHUK*N*4bBVrN|>)ZX3pEkqcM*%m+7Ne zgVQloDvTv8UbDuf%Jr`+utl4AESk&(xp<0v_=NjpMxMK{&hAPHP(!96L^j6;Yw zJs4u2V=G6d@O2awHHeC79YUeh6fJ!#0tPHmpOn@ixinFDPs|)}w}1cCI3)%m;*yw? zu2AH#zIY^7OcuEJ1E56_hnEjf5B?dGR8Ee6`l0T_v7Sh!)kf;m*8D{lmgZq;5E2j5 z7ER;t);Uu|a=xXi%4po!HP=Y8s&4Oq7alUS*MwCBl2$sOv&Jd3lHs$aMjUxQe5j1A zez?W~u&Ypjz(1J4FUTb*4ud^zZ!xzwx7hoe8_doB5)-(&{^z*8I>%fcUR_;XUS9q; zCV)BL$NXBoKKpTYcJ}Mnub)4EVosM%Pfsx?C%=!6F(>mUCnv|)2S-PkquJZt9nAOP z+r2)_&YORG0^h%X|Gy;#zWs+3SnI`nUBIlAU=}j}M^a!4GyM!R8IBqAUzz>*U!*_@ zX2=QC-HmyhhUqiHbgN?8#jvEnjq%5GBN35JDG8quux2h(pI?r%aB+@Uk!nfkdXf~Bk=Gc##s7Z*pz{|8Cn{}m%3Cxj8_#|W}xxEU~PG#F-j3>^iAk^}=M#1O(TFz7#w00fKy zfo_@UN(A`-8xxR{lKTJA6QH7^qNJoGCnqN(BZI@?q@<)IBqT&cM1+Kd1Ox>5`1mjw z3=a=`!-GPhxVX4DI5-dp1Plg)Kp+eNRAS!;006@PAQ+=|Q*mE3jBN4hjmv*w0`XF? zm49IZN&mtGe*Oy+P?X1F0@_$i;Q1`iYgdhY>eqi?|4*1e+kWy>sana$NGv8$iNyrW zv6#Tu2G^`y{V*&hQ0f(CTljy#1iG=9fC6psNpF8Fh*h#X#AmA~?M9PXTIxTTz^|#^ z=iI-j-sQF0&O9;RGLOg$aG7Xw`WGhfxYJUtY;1JV>$t0D4f;?{zW)2u0B?S~@$OEn zNrLrwg-g25|FPrN#v{VwM47shFf4}5Z^7t~W0fp#Zy$x#AHQNYBw;E+(XlJ;txfdw zU@!obXB~+{?Y54BaaFHJ5lQZ?N5eIFHqeyNkh}meF&sk17__(XZ%lxl4;4esQCYp2 z$T}#DR5>-K+AtW1R+&6_qY7T`|DA- z&Xv5bxB_r8Nb*~U+$~doS@T^BU)y%}G`tj~bqo^9w^xj&_Sh?l=c?VqvnGHd!Rk%+ z`5+G3lY1|A$pW}7pIEi;n-sm|%q=KnJEJecjW{7Kt8PCyc-3TriP^wWHxqWRcxtZv z0S7mx)}kgE^gX{Ros9okb2fs8AE<5VI($8;$zQMh`bX%iipZ%?uPTRA=O4STy`=W? z*lM^qs%eyzJL)=Y|8Cv3bgRMJ9^t<9sIz|K`-}Izr~Cyy9|~W2)*W;`I_ZNwf*#x2 z{Z;E%{w0e$A`X7`Gtv0MPpCTae65Df=p0s$VsOQ+D@!$!F*$YtH)_IR^^~q&H5^)dwR+%1?a=GLS2F=Ii6! z8HS9}zyza6~LWU0jTSNEn?V#d5VU{gLKiwltC4b@_iI>%QZu{Nsm@U!37s$1#(= zLRLq%jAM4lI95hTl98E^5gq&3Gm+6TlMp3I$R3$l*?Wa_jBL(*zW49`JwPBHJSAVkbZmYQ7U1I7C{5)JccrN?JFq9!Dz~MOh#DIS3N$q4>5` zNKnyepU&(%Ca7}faO?c&&BrlH|M34X0dh71mRt{ISOvvKDbskOO4Ef`TF63&)R};) zP?b4>IpJpHf^RNk&KVEsS{vin+X=E`@w&t4Wc#O~50$+R`C{B;=Edjo$aEDrDy zqEQ@paw20ZiegirYd^MK2I@^^4&Z5sxM-&36uSQ~0amwYE@)T`gUABQUpp<{yO`>@ z;C?H%5q;Xm&)Qy}pNQyt0hpaD>Fo8fzDj+CTt>{_W=?jKYNk2qoyMCNzdp3RCCU$M z;^}zL7gAKQBuwBp`G1(eH4-LJhoF316ixwP9-IyNXC8(ANG~v6wlT1af55aTD;QfW6DQkyYv*sqhMtp~cTa|q<}y?qF$bcve5Xle!t?I9lfxfRglMOe z1s$+zBKQ`SwI1iwTU3#8?npubX+92hXR=L;Qr)@uedigUA2&|vVU~_H_uVyLDLgG5 zNPRteb6f8YB1bam#e#cYGY9S$8zRPYp^&4}u2qdKAMT&o%5Y79TzvQeojZp*k3GJ2-P|Ron_l3DBNOr79DWAKmJM^~bCSyu1Rgw_xdyD*Df21=0I?x@C0|{Z;xJZWswne8@seWvuu;G)0MO z>gm6anZZV9R%J-Z{WT*0g0`4|Dz~O5wds>3@r>cZM#$z4s zVOuR`i&uB%_J$87hC1SWY`Ujrnn>&dA(H0{l^MY}BV)DSGi1>9)xq4OMx@(cpT;`~ z3PfA=uWMc+>wfdUHji3Y`D8zUU;0ut5jFm2C+$r^OvrfwU{HA@ys(d-!Tf~SAJnjC!s?tX z@oBZ!jpGx0zc==QS9)C_%aiQ4H0$d7m;wE2_GH^Kxuz3ZuQ2|cMa0{>61W4y5Xm9q z%4bsgYuO(ubBFEJh=vhh8?6Xt%ct#se98OzdgGZ5AW zArytZ2sd~uld+_9)AnWX=7(+d&VFb`f?2}M-Fx4BtG{7uzx4m{2s)dd%KNJpE8p-! za|mE8=K&-#TWI0!;n1uoe(=p0C$Wx^C40Zu8W+rLJcZmC3qL&j^BGt6nX!JYWyom@ zA?nuoA|gq??M4+!{gff*r7<64F0A9a@y}QbFqW?>zsHkjX|9V1-+yfMXYND#$rXBp ze6PNi7l--Tg1l4K7>mSi-r4gd=D)?f56jTniVUf#MFN0hbCReRNgI$pOdcy+e{QaP z9gOIF^Jw62<+$|^xxud!^cn76*%#Z3J3SJS@R2|$qjS4-iJ|wC7))Q-_2YrHu`eet z-?M2z(0M0nU>k0^qzl5IKpB%6O2Yuz*BeJ*l*-ZM;0v}Q#44tX#Yn~1;jDdMnJidc zc9pW8iicoh=sVq-cszdl&h8ycmpfN4?tJMTjhFs>-N5%hZ6G|%-|%abs@O4Lz6$O_ zAvcQ~9Up(YJlP3THrvk0XxMK&zESeSB{GGKpDw3A^1cl5pzE*5Z^Ot_$Lf%#s2h&k zQrCbM?BU+M9bbY*7hz@aMR4B@=7S`yi?h}c(N}>+i_a7>4|gaY4ZM9pV-Z3r=R3&k z5Pt1>(3cQqG}F^nYUj0JO0@WWIp^|USUzX=^DE4kN6Y}s_)2M*i4l1x{y7I4EA8}R zF!Tk#fA~kEFwB!MtCTR~&ta6NjE(FD3mm)Azv4fVINU$Ax@EeJ)CSsT zMsKa$1PIq26bNGFxg5g;LoINVErK58LcYfVX3o)^M1Lm2Dm4WvdY&RG&_57%_y{&txQLIX5ufW4)E__{0I(X8 z@)!>W5L8PDsKo+JA2PnI`|h8OyMO%=-#a2d_(wwM<7DLHNX2}u7I*}b{1`<+E(s>$ zA-1>U500WhEJ-?ymXp__8+{X`H#lUwlURN;QrS@);lYVQh(*GGyug_nc#U)-8IbxP zCh#>?Y%*0ME0uJQ%0fsbVFI$hQzeNCX>woFlul9=Ceu(?(}hmb)GgC*>7;9CrKXgU z>A0k#C(|+SQVl0l<**4Sr3qKEUV>V{yLh@C6civ?1}MZ&yZ?9rHFcPC)&GYH1ibRk zdKLKfKTIIx>h1WWkuS+b`OS4|9eSNK_kRXhBS=sYiNg-R%@+IRW2lLgeh5+h< zp%j3SLeY~Pt(6n=C*_V4SanZwBc_1}P8f{o2Fv z?Oon9nrgv|?zb29?quA5!UT`b^i}*D?ffCzjWACe<7S)9&%f2qOKo?KGWx633Q#4itIQcel zGe@SZB>YE-c3FYWu3PU(fp;Kc0!vw*3?Ih8dRyKm{m6bH@(%mDthByNbJ6ooZ0RpF z`0Rgp0VJh426j+I;c%K+T$cA%q_j+=yj-_bd)Ipr{GMr(A4N_H38g!_j=(R_G_vJ> zXUl4NT;8Gk&h<1`H^tZMM^Uxndk8(e2#JWoz{dhBf?rq6D88GUD&hKcx6qMBQ(l%U zmWwCWFkS?aiKwVmE87lC**@u@#|9X1L&9?-2_h=Yj(9-eKqq`1xI$({%fXCqMhTCU}f)AX8rH? z64@`2LHRe?KM@o^X^~ZO1m@7)Vu>TrNqr*6<7p3g;CLiCCGep(|!bx`n^5l`oQPIr!{TmMPcPx@l2!#1$ubUbu^0Fa8H?XgcL+(PX4 zW(l}`H;<1waeX&1-C?a%k0R0ogC+G(dh3mUlHEb}+(FQmR)PDLXzK0Az@e};FDYsS z-7^4qmFz-J527IhGDsvt3ROooqU%=o9gA*Qc6V=3ckDT%JR!`m`Mb1Ur$ML;H-Tn! z0n`ivtxJLr5mcIZaOncvlL2~8fT6q~H2}QU`)dXgoIU-Og1-0T^YEJTs*AJkRlP=a zvSxDYkICiC79&V?K34l?nw@5Non12d1Bzh;-EV+e1BrMPRO@o@`(2I!J^29{>MtAd zyd zRmJ4{{>eGwpK&lR1f@SS?mkl!Iy0I3w6}ktzkhB}`4u5+=v=5e9hQ;N;0q3G-dSW2Y4}=k5#hv%lz?Cg};#B9>0FkcBm6_Kn7cU$t|f z?RhwSZmtpZy_k|1JbzV!oqb@jVr^0JY|f;ARtOG2s-Qhby1ej3DqNmeVz>m?+dmhJ zfWaJjKFF}2dRBbt7FVJ2&N6MtB7NS9;=ni=5)zUDHJ+Oy*PYNe2vMzkr*^p{>Q36v z8*N3AS>~K5k|nYRo=R5$Q;$qn&;(;=D?JT%CfLKIa4By z6;WnGp~(j}u&aZdu@cip1{=D0qpSqza>WLw zX~p35w=LJ^q4-8o49cfg3sW-^`C<=Wdhb!Ah+6DI&TKbr?d)77aQzL^q<)SEn<1zd ztH{XnsXszN<#IbP;dMLPKYccB?xpjnB7}S`CNbJR&CcUh?(S` z$Z-(Inf#AqabM|2Qh?ReTm9x0>Mm=5{^+mlIS9)J5>;9OPX;{H$}B`6BJX z_Y;G6CwZ#>@Z6_&KcpEDMthKCMc-3%|DG6m9xBZp_d=+aNnAiR8F8VX7rHehzFa@B zefJfaNAh+D*A`#!;m3J%5J0u+r3`B!IRS0bUuM_22mzIw=P_VIWf~qL=DhJmk^pf> z@XdMRU%0JTU+oeo5et#CgU;fqCAjxr!U>@U8m!IGt(~*+5Bt{!_gB7a0K0|@C>6kQ z!^$ZsyO<8(P>FCR%qQTO#ckU&jriN4&TMYrtHur;iKHsOW?gnAk z;ve?xj5e>CtLi(w*zsfX%c~I6N_{^OTD;3;ArK^_^HGESX6~rA#-7@A643&{$y-s{^;MZk(M~~_y{`JY`mgCSTak& z%_d=dR4@3T8*O>5cEZdi!PkT~z`fu6y%J}Xfm8OQaap@R3{Nc{epx-#b8t1Q?R2TA z@Ds5Xa7#$@AbWMe|2iseEzMTKmU}9|3S<`o<|#tapT6L zy2YzPRImDRvjy#qG})}{ zNYd(5a2i6F_}Q!fUFnTs2+aquSw@Pl-#>G=wQzd-1{&|=O$;7q+W4mAKZy*N>A<*Y|`^OppMdTu+8Aw`eU)QsO-u{_mKXv;m}v$Yz! z+ty{D_lr-*I^X|T=u+Gd;jq5Vmg5Qap#UF%e)8i-%!y+d9`2Z@W z#TMhz>R&byply^UL{h%(uM5(j<9vZip`)o(s+e1auk2weXYSOTzo>E zQzDs{witJd9qx%W5yhM5RAo%k&__e0`1+GK5N7GiTq~GJIyX5j*}%%!-ZRqWd3USA zPF136d5omsa);Zfv2pwXbw=Ll zZL~pHU-Ir2|MEv?X1a77t9&&K*4x_M^nl^%>l!-!22X3SnvOh8_K)&rMPJLN^ zR=j2XyV_!4ICHw}5rz2I?nknF8H(47XJci1oMMT8ld?3&1e3n@->P#UwTQv6}(1 zA+{mj@3y)O=y0ofkL1qnIm&lL8rTh+WImv8vGRM;`t+^|_7(ryEyxt9;b3Ave?EDa zw1DLRd-C$o!4AoQeT9B^m2@$qZPkF{aqcsP z90~s2SBjn_c`ym^|8aA%*kT^kzRHyIsDcX40LI1a97HKs=(04a(dJ9!GdmL0SZiCT zqP^@mixFWA7Ej=5SUz^g1u~ZQ1q4_3G6PXlK0>9FF!nNb>?2d)JC51M9a%R!7%z?? zuY9H~d-F%%>Mu6Sw&JPtwIkq1764Gy%qK|d?E^gODiIj^I~L2lWq8P=xB$zgO`%Ud zGh!TR>_D4Z(h9*pisI$i&L*>!ca-051a(pQ0u(oPLydh2*B^KchDzDV?{-J_e+d@dVZl7t04 z={V!AyFEJ;d1|!WFgWxnSD3Q88u%K%l~WSHk`?90iP|k*t+gvx5|fM|@vRdU+I~%t z!tFbX>?M~`Xi6gA*BBUveN?*9&+Ow_q-c-{O`jLVEwB8@=yp6aLH_pji7iBh_t^U* z?dm42%PS#Lj0@crvbxeg=^k*jtX%)gX)UVg{rYLi3iP(EW2)KD8`i9@o-&~^9qLyml_?h>67j@0L2jH zGs}LJfWjP})F!+-*=RYNlOjhL@vgMp1O61YHdZ zAwa?e)F`A|m`I;lfG`GtuKNQl)@m#@YVh(Fk|aRcr$*HfS_7hcxb?k|8sb$IM<&(` zs<~Os3zqh36^dvTPH(+lL@MgEinh0kjkb!fv`QSb-T=4#hY94U8*D^B@DG>6frvN% z4#8;4(H`ie+`O!vJe_A{C)o^?mz>zVT6Ltw5Z27b4jb?7Pexd0wBWH?x~)SG#&L; z=lLs6`h(;M*vUdIvCSqo@+RZ*uNW_i8w6Q;>PRmDBt}95aE*T$t8Dc?<-xEo_amkJ zK|&}6ml|24-k8xXnp;er4_)Oy=qmXoQEFU>0IBUrYOk=Z<+p|DeP4`q)BP!oy2D~ivA6B|zWDTA zhU;Z*_BEdM#+NqP3zO4%h0CGIQr!BdsQXfIKd_qp#8L3~vFFt@IVzbZXhkxta8sJwDBICkxNNgc)5oa(mHbXMLG6G5qoiU@WFlWRq2`a@iBgLXNCx#ff9 zKB~aKjx=m7SP>C)KDeLWeX!D%a2(~iK=B0j({m`w%1b3DeUKu!52iIpxr&Kkr)0wk z)GA`5o}>3ie|)!oo6;Sb&>O$yVDx%q0Lec9ftNy(TKl1BFj&dWJW zy&0BWB(uy2zw!sesy~dJ#a(5GvH@7w!X08mxG`03XSE)s9$Hy1c|_sm2(;0-I@SP( zA1De`@NC3BS)<#s=ikZ-@4#BjKJ|Ee~@^j zD*1Vk6{43cA8MB@03brA8uVu!Mm(5?=0A;QOhsFGMOsEidh*o1-59y^spjZpJ{WI2<1>=MO2)$}LQxT`8*DbaNMR-%`Is4^&BI~vXRH!rRx$#+Ia?_I z1VoPx&zYY{(Ug=X5|OIFffm9;r4{)OH6Wqj5Pqk!6F~YTc*zn z`eMidVen%lpx7LR`(ui~n80^TMQ2LdPw)c-T`=NKY{k&sNJ+ZND30Ih3d zRDAI!pfuME*?$#jnWa4bCdV?P92OjmYuxVbDYuMxZje$HW?C2J%mXpgv#QIz_81j$ z)jwK1x#B5)%3Y?rg?1W;Co^`Bi|+2bKGFB)!Zaxu$5qkx#n<|8{(pu*twV%m-ArT0 z?P~WCoEJ8A)H0foPLxBDWsh06T)US^Vg$Uvw==^PTxZ7q2(Z?XtAGG;*09O`d*5qp z?ndHXGD4+%ahIdo3ypJ6Ic+nJ$=s7ET#}&y-BC6sMoy3Bp7)yB7SGQ07E{XzMRyMc z3Ct{9o5i7KlanJYC*)Z&BP}fEj@%0^&Fmm0wwJ#B1jzkpd4t+O9GK?^$LxLBfE^v} zWJ)kj1Q!j`UbtR1&LFV}9bf4GJOyvW+9Gv6?oY|#$*Y*}k9;oCAD?@Y4VkZ=6@ z`^Z7P^Vcq<^A4AQaWWW(0~^B}?!qUG4*NjOjkZ82PCi*?VZuzpM(%Px9zWtxX`&pp zDjP`A=?mkTFtvVZal3OhHleA)w=^1u&Ff#)_E^2G9fQ8+q_eu@xRdwvSRPma`P8l2 zN3EBSF`ZSA{wM3YC9c1Z#64VtJ8L;5TY>`ti1H8!L%JREcM3>cdfu7NXVD!iKSn&I zUU%iX_oNAi*F};hF(ob1EpM&A7|2z$gZkM~IF^FGytj(7b&iyH$>6nUfPDbKfa?|m zF?WBfu}sA$i`KWoSehXr6VY4%U|biG1pUo)W^ZQSkMZDAKx)`^zrztyWGA$;9bH@p zT&@^bY}eyV@R3)s6!~1?uE@>8k`G1ji zl*$#@2t_zLeqvFmnH%G+oXf+n#~x389bdnpbqjV1{Eoqq-$GW_!u&BEO`YTsv~Dd? z^N%ZCyGmR?cx}W-!swhqF^+COJ=_RiKb}oGaXp3gR>CYZANenkfh-`zrcJj&71`EK z>tt{|BUaJ2`4bNFP_}dZr>)1gD7T&vnCw%jV62qFC)_nuv}GN|-R7vLcJm`M59gy^ zi{;&U5>nzmM{pvO%g{`g)2RgqU{o>Vs}#`n zG8p!%R1|3o;LD&+8Gt$TfRcLe3D#Ep_}L!gxtHDLr< zZPIut-R4jnqOg*;wd#&mV0|j=mM)P7nc_>T|NkKw`K9>08 zw1k{`#Q3Qz9)V@@wk134-n-AtT<^i5&Fkd`=8KU zEFaI9O&y@>>n&sBBk*d^Y!F5w5;VOUS_!+(uhJPrtKt4wgBwr1h(7PS$&6Pc?^o6U z7Wa{bjuJNX_7I z9{nurFQYOmg-)`A4kB9JIl^yZKXxO`Lij&SAQ}m&{yKJ`=koB2U-nT92RbU|gFn+S zmU_q60Wy|wl#qCIEY%X37J^fpKq~XF$FYX%{BKXdk|65{Nqep8{g`-oEV`3-n>VQB z0m^efTkv!ad0Kdbk%S5GAT7D-?#1H+qmhy3&B-owKA82uK;r2~T=1?htfRgd%|?2_PZQ&=l@42#Z}8{?~N$7Z@A1-WIbI=MTu2y7YgsO}Ozq zf#)w5_i>v!vs4|$V;+ccCNu~M0+12Jtsl7VFCZy9a)st7XUrV^oo2|krdD6`@_dV- zX$XhjQeEXmE5W|BIZoP{*9xu>sFXv~$rHi4unP$2} zr#Rem+(zgNSors^9|hyv&VLav)`^#YiShu>?jp5A?ID3jJ^aZ;LrWTgw;jhIWL)mN z%hwstM#2P~lZU=v1+-JeT=pD#H21`^Bp>S7@}=K&8ZNioZ~IOs`)qIf_rB23|BDI4 z?!Dp2+N8-%CoGDjyg;#e{n`8{I#ET!1TG$vmVQ4z{zcjVm35!4^X_fRb^Rqud;cQv zr^VI^EeHG=1#!CK&N1>{8}3Syncksxcj5d&`pka+JEI&$$)`KpCsG?jBus#%|C*W9 zRp7vDk&=0pCdAQs;P_eL!650Fcj53IDUFr)UF*%zR$M2k&o|dj#x=7>SRZPt#3W_o0f@$1mJ`*%Zh$f80jTrd<_B=(nP#K4El1EgiKgLs{;Xwnd?ZX@ zB3nAWWq*!&ee|G1RbkCp7xK9%oKC*50b}A0=JQ`n`IW!UYeK8Sny-Jmp*jkR7I9up zweTptMs%BG){0iCkzay|pY-vL@DUxzo2l^58cFi_c$6_qUEPR*xLM`_NNFcs^S11v zsYa*1LZiQMK@15K(BGetyg=l!q@; zOJo?G_JjH6qg`4VSBamoS5+daX+`;;R2f`X7jF5XFd&0S5DQ7HiByS2@KUPW8A|6X z9J2}%uN@9xgaXN%p$See?foBnt}HovU~<(hO#tHtUM*lFRq(I#L2O3ZtGp*w`mFWk zE)1MUVgSH0DY;AcjNdYhiu(sSURO*&ng2&klw*)&=T%oXCjMW}yYMRkMd9eWTFW1g zhyjODC3~d!+@2j=`8PqEoy!4tGeGP`$tS1dD2q`uwHHGzAfenaO5ifj6i4DU@o)h; z(_~6n5C{<^$1SawDleHpLLHbrYb7TiW!oGA3GHokst4%3tU8^%@|6r9(bYYaZrPWT5^r1T&&Z>HnbRS1OnVk ziWuY+;0!Y`Q~M=*I9c7R5>!AZoDZSEcLW#DUcX|n`B#0BGk#9#!dIINdzAN-P%3+W z=WiKXahH5*jX;cir1UU6Mhai(w0bQV=of1?1NyI9I=95ikoIGBukmNW0pe!aCl3Yz z#WmQiKNn|2Rp8mH;#JB-Y=qPThBUpFTWY5u%tJY-$f!1;hmeYvqLSFeq$)1h%S-}T zj?4Tc`paEibO6CFp3{Py?G=L76uku+ z7>b1GhQXfF*a=YMZg1j}JGDt#oT$G=yY?_mY=4B+Z6yId#-0KJzm0%(ZwHr}4NYO) zpF(JV5Ho|97J48q?cd%?W5KHr`EL9n0`DSZVRsYLg#UmBiTEfwJDxjC@D{Foo-hW? zVj^p%L&&}EXuc>Q#yLhmrBg}p=KD7EJTJn(Uz%C?(M_EPrXPibz1rAK?HD8^BC~aO z9gQ2%Oj0x9Y(+dB(%X{k8a(|1x@{?!dQd*UXv_RGbtN> zxdYCJI26nzdy^R+XcVYUwxlDmKb^x$3bl5x8>u{&P5)R^s%`V`4js&7jyIA#ccTkg zHpz%-RHG0k+r(6fFjYXcO4SwgAKx8$y^r`;>ZtslD4F(HK5r+!Liy=?ko-?NdnGdA zKY`{z<>p<=otI(3pYg&kwA269tSj%TrF0CHO>}S>RSZ~f0tw#0SC+y`RF-AGL#r9y zO;+wjzr9@&L!rmdZfysBv483qjSQN@UZq{V~`-ml(iOuDPaKd{7WF4A^0 z?mYRPHRn}nUf3i4qc-zQynXM+xAmSos(V2kXM4W{YHWlZUJ9oJghN&rgf3{7fI66} zO{2YB3D=m^`^{YZ@W0)(jp=!EWnOOLMwh=Fv2UIzE8UzBkL1}4T9`lVkCndaVQ43o zbLf50sHrnOHFYRU8#kdOjnPg#t)Azae$}27Px#@yZDe@J`#qTT$Nf?)_I0muC%T`p;gD%F7&Q1;8qDbLTc_k|i(i60^L6S?#niI*FHM!D{__S_XQ)Lr1QwYC$6 z;gcEdw_OJ9r$79Ime&SwZk{GiOT9mimN?b-F#BTlt8ax8;!G9Kh*(W^#bF!%(ptr= zXDoI0%l)YrClu50+-7%j`Ukq+bWDg=!W8o1TDQdgRXsySa(_L)^F?3w^NkQ8_h%Nr z&8CjsR4==wjGn3b?Yb32a4rRVUc7#lcxbzS>z``R57nlHprRia?R8Glx^Tj1hLyQPp5EcUb-Gr&`0ak0 z_zDiTcNDTqH+LEKs%YyzcWm1v*T$duncaE4?YXAedBcb{)rl~2meHfd>C>1Q9hB7^ zvsR7rJYewV;}aeo9-i}mbD%sho&O9BZVEP-0bl0mAn%o%^5aH;T` z(R&e1$UurEV;mOdX?eGNALyX-{~0a9qSO*`YAk#v2-}>iVe{xBwU9^)n%3!|v3zjB zBE{V|oz~okGR?~88glLV93BrS#&faEYLeD=Mw(d_kUZ`(9v#uXJ+gismho3;Sfb>`C{nj!Wd^bJ#I(_Va&#EQX zprlL2Bsyp0%6`oT%o_C(9&P3 z+@O(VxuP}Bzru`8d$4S@z{Ea5BY$&6FVBH3cDWFtlG) zCVx~5yEZtcmS|yM!8I)1dd&oS8_+XtuYfeKzIa$~bO@R9{|MACp>&Mr` zCDxWcw~<2Lby;gJ_6|e2U1UlrLI~^+OabSBAVjc4kCj}eq3xD@8>@Ak4b_a$CCK5_ z@u9w>Mqr6g(FBqwx>3MF^oO96v7l2~{?%kM1h_?DA)LYDj&I;JC|)DcBEiq<&Xsm` zg@#Tv4N4#rq&%a}N(=L<=L=vWo2y`LbU@7uJ9y_gJxeXlm~_;s0`Yb`IeW~2oVjh* z)??#a1o}c>kT>(yf!IvR#QZg=do=Gu*UbVuA@VRG%4jx&7d{} z!|5Q^ls3X|ftgY~HtKwx6A449H(g9Mf2dlJ=?Ew2SU~PNLmr;HSja>1G-BB+t z!=e4xb0vCJ3B%~}Fp(V1%MChS|A@*Rkq?JuA1=!@+e4AGRzl9JX zo+s+C%#M;;t#p^>Z{CsL)`%NcVdatzZ7zL5)Lra+S|Il^dvOV;cfp- zs^AHV5bOY7P54!0i)fYeAfI?9l)}?j;O8D#tFad?AvCF7+6gUaffm;mO!BPYln>U% z?ouoLhEH#?qYRrbg( z{r<5OZR|7~J5iPzHul4V{)vZVlRJh-1lKsR;P$YB(}PgpL|EdVt(16uy}9oa#4Y^6 zg3Eb7H3}r(J*4}AY|)fG6V+2v@@Kf@%xI_odT8QC#qof|i4~tmkp=0wbA-UD^d6Zt zd3Ih(+!(l_>HPtB6?=UJU9tA}_;mYcqBdM}iU=X>5i0K)2%p=2pfDG{IGl#zG!o_U zV8g0?4@YN2GvnAsMHcv<1n(gqa?@akoH~bPqnoeDORuuZEKxg+p4e8uA)#CKH!RZY zPgoV%8#j2+G$0?AD4a*C@khHQ86qn%1^h$i z_f@P%rOw@B5~cQ6K-gkmFDJ(*v@fdS;2)xHdihkNlu?9tpR1WiBnX>NjCnRC9SZ5w z+G(Wn8H8?fn}39OC%O}V$*fyN|lJHH>1hkweKJC9e~^lOcnD)T!>+R?*?KJ?ArS9 zMjDvn`zjZ=mnh>W(f1yiv?#s}n3$=n)VE#nGYQA;mqK<=OUQ^6X!}%w^<7zteI-}> zs}HHm%0>nM3bLesV&S`~?E2IM`H}z2K3cl+jOu`aT1xcFC%L%Hi#3=?d!=f&l*aN+ z$7JtQk=)#umFiEW&=fv$`*TtBEoFfkYj+R$$bDGfNMVj|+&Ib&Kis(;=Y#&@!#yvx z+xk&g2F13Ht0|SHvX#`nFOAWA3hiYFn~pN+Wf_@Q-Rbpwxp}}n{fcEGoGm;NLnm{m z_o+TN#Is_*gT1{A+0aOgXiM&sQB#(pHAWiNd0nUOxT4`~6}M+{hv;iScWB?^owyxpzkJ`^ zXxL=^Z<&FIJ!YCaG$ji+Wzy^kld9N~%s%{zgzD!3@?}YC`_5H|n?QpMyDiNV;tc6`8+2?P@S;uLk@1Tm7|?e=(ELhGyH$6(cKG70gcBOR zy77C}VPMT?K;`*>&S+?Ip222(`{u-BrLiNTFjiRa$r$A+-suGCd9r_am;R{zTD6+` zty6xG-!mu4@GFr=*rZ}m^KtqhI>+#o1O=pnS-U}xu=N+|TZng~%pCThA2RQs$`r{x zFh(@@4q0OQXy(NwlK$4`f3H`5p$%KaQ05XbR27)GCJaqK;w3ruO1lPcdV4MiKrl1B zd6NKc_{?u{_L=y!)|1D0As-1;$>?8uv|JCpqI9t6<&EX^$SnEv?7(dd>17nw{7tEa)Fo!rN;8wg2mmJL z1$D2!-uFKGbxYd0!9=NtQF)S4C7~U(W!Rjcsd~Yfo#+4EwGWy+sp|js{hH=v_(nAp%KUg} zB_aR14%eSdX$QE&MXZ}9a+OHSOvAt^Lfd1yrB!L8>rHn;UPGIG^r&Wmyx(Xrjmc zpRNz)f6(hc`7*u

&<9TkdD)wCymadvkL7b5A2&DygaZI53gLHq=(SIXL+2=#8O} z>gAJ@UtQkK=*S(v<_)EMIE{!Jp5^?y^10Y!y4Gm?AJRf< zzQG`}b6$J^NNwi5+8f(#;&tsju9ak7N_Vgw{m^#z&o1uJ^d0U(Q&*!8TX`E@tZWht z4-(`Ggt21$phAWZSD&>Szhw(;f6}IadRP?B(<3(07p+9|Q@3Y4!nvJ6^v6Qab%q6W zZ_ZBo^})=;h?rjP#y+p8mCJVveH!%QQuYs!B{rCJXcz)DL+!iu@v-w(c&HG5}L z#MU9!jgoRJN~L7bH#37@QNC$1YbzssD~x zc*U3q=ky25_)BVJ0jLNQUu_-wS>j%?f5#!|8FELDO2p}p&piFf={hO;MTTy|l3#tB zRu(hy+2&wJ3wa-M^oWSD`1f2uW;T>k!lKA`lIE9LByS+?RTplm=9no{;N=6q8wQy* z9+Lf;_$OrIzZOz-B)%5$%I*A8yH6=aQvf*c5171sP-Ll{?b5E$`=WE9stlL7vGXk}Yut2Q{6nXdt8#!~Mg_hFes&vO9@^qY!>gY8vEn4& zEUgtUIAmD6UdeX%TR>s%yMoN@Y^e+3BQeJmIH-l^?7v?Rl57qqU0%$RON*7-9L)y2y*Qi+ zdhv~Mic_`V+3X8dqV375lVRS;`kQB5r@w<<<(+N?cLg7@NB#M>|F`9aJB?x)YhjjG zr?s<->1UYsPUCUy`p-&K7m=)5=P$>=jt5Q*eaTAu|FFRK~_1E~$U zfA1KX+0u}_z!_nO`;B?4xSdcHFvY(}Y2(y5)!5JYNlN`$G6Bn2hKS@ZdO-W(nFfb} zVf3x|JWAItW$bFV6PxrBeKZ5DZV~OH^lWP_T~vICQVVaQMr&-%-LG~oM)#~&GUiGh z>HFx7o}#6fufAv{^WzDNK|dX5+1TJ7Lb! zE4)MvZ^|1pcGR_)XzD3g7v1#)@|KO;Y;4|LIb_54bF8z3T%kX*DZO#BB7A%#Odztf zfa8cKTI9Kxv`$zrU+@M665fo^_wde$XSjAF*CIvo^~d-!=`~3;d--wfPkUxw)Q!`h z(UD-D$DZ=!T-ArYxh_)Kjn$OgGzO0P9WAV|;TzW;Nc^Q@UOb7oCm*fG;s!qwDA9@z>;rFwbjk-j&v}o~cS4=BY8JvZ6r=N`W zt-ecRmJ-%?D>Ht&X7>8=7q(UakM^lAaF3L~jf!j`T4WqU6y*tzQ4$>liyr0{FBR+k1Q*%M>30k94#F*mfi-@H zqNH8Z^3lVVZEm}V;h{6wLl4G#{^TpIq#q73V&Y}sLzrk!d(>(5L>uHPOBiS9j3Bp; zoH}z^#K%uJ!d{xzk^_3mXf!VwXJ%)aw!cxbD*p}9Lw|+{?_gEV@3GMx+%B@5)YPjl zX&z&ipxc}-&x|lY*DLQ4(IiC^bji9>?w%$peSBQi1<_ZUW8@O z$fDnolJTIyqJd>u8BpAJ;k#KT@^9Ju z&bJ?EO;r?J>CGBGgkP3Ty+u~m3WAeH+j&1*=QSNezPL#IdCjcgrIBhttBTy_u-@hH z$VK+0^6V8`46uf`)P2beQiz~!GaC&Ch_thD9X4|mCF-0L<94_9%VxP|uhUJd*X-Q7 zMV22WQsV}d5SL^&;rqG35`dfK9A-qw(wQ%MCMtwv2)0`(%)qbDY2FTnQOhCLqh1n z1dTd_e-MVGb_2bfzC!Yb+ZlQ8KfIm2>?haWIFTR491bqwd@fITbbcTEz9# z@aR*XphDU6<*TtL-|MjtavFrbBZzq&)~uK4$<7Y@t**CBdPMxKc}&tO3{K~779I{^ zA&`V(EN$7@^JqaMHrn0Lx!+fBXGSJ&gXa#CqVrVL1m4y?CJ5tj_E zPZpS}Qk}ahq%HBK;tqKn)v5RJk-sclM*A#OFOBl8s-^UAZGIsC(>%_+HS-tnbeKHV z6yCO*8)#0HpDLG4;`c-isMCex4~gGa2xtwJ9@?|zY$MIs8Rxqx7Gl2gt2wC$Y{LBvl@ms z^lVi0WXa~VjlZehr|4z&EY8sGgks5}-QxR4ILk*qji->mt6`g$gD=yorBOi4uR>u+ z(MdQP%$0YwhPQi*Hv!Kk<&8|QM!uHu=&M%k_ZO8$6d*^DLJT7?dZd)4XpkT&DGxzu zajt7|q1?cf{8aw!+*1WCW%~Gz@EYQ5@gUSzIR+rmG5ZZZ&`C3%`Vwo8= z?0NK(#&nl<7@7917~df%tStA3-9(zb2~U3O9TRF9b3BY?9|{u}Ttn*Oo6J9ooAfS`?3Yi)<3L2g!ETx3eir(NNb z0l8A`Y0*Cc7=V3qRVKSONs0?MD#{Lqd^bMSI=Q9S!!X!m_u@CA4enBh?sAGA3PB!5 zx=$QRV)<=DP>P=AP@Ex4sQ#g6O0TC)P>5v%D7sW4bDt`)BCZR~K7-*Vg|Fd-BHI`) zWIb{n#kteYk!0x#S6rcHaf55SeeLa=GQbLYqscHHm4`kx8Sbfk=%R)@ZHIT-6@9yd zd_URxh#5NFq_#*6`V^gR2k)?BKdk3zxS96@M6@J{{>Xa=LHCXu?wudr1O2_H{w>HZ zv!CAO~xOz*#wD<1s|ja zKD?rGweitMUv-1GdP6miKb{7cPcSQwgn;NmISVzuKd>tKtLOOJYC_Ih=KABW4_Nq; zS-w9CpKT1XdCToaA5Khq%uE+{Y!OzI5@ul;^6q&=!C=Jl)zJNkQ1+{l5)U+=v#MmX zqE$`N&CHmmsgXLYk78>ih9)q2wAk*nP`XJp@d0g!8&ed-GU~Zy_+n$Y)lvAnYt&i~ zf3h4Yb4*6hCPW!v(E^s(0qf}AiO48V@YSXI=wMu26Yl8|E``(;Kr&OB;$9rZ6)45O z4vv4*6kmB1U!#;zZx?4EO>NT@^YI8PbriJvHt zo03Rn0>71#No4}ZP08oM$?qqlbTYAC6G1nWA_mx0s9h=aT@#)kNpdMat7Lm7)covq z<})dh=FgU@(43l_nfhD_|B%frBsfyDTZRchl4l z(!Mk%dSrTfA4^BDXWl%P$2LpH+Y9+BtrPt-1q0ZfOq4OvESv(?4_#g zMW20t{E9X50bBGv`&{TRrA`AfWP7VG_{GO9+LCdiY z-XR=dDS|l_i5jivd*5_ZwfRmClERhcqTLTfpm2BN8C_(kXQY|riw%5V2(3M37+ydf{8}-yuyFgfn#97DX zu+C#jK#i+QFSm=afNO^UEhA9hPb1CiWM;K{gmODTgbq2UPGzTFO|>oqF5p|O)chrB zkgN3Op7g;($+X;_oSB{iwO%+s{nZ&i=6nv{cFG1$4fg9*)XJTkRL2r|>?kdk!*y zE^@o8&HZSb`=$O3?mmBdK5u39@BrZKb7LMRGlyeU+x7?9U(RiF&r@kH(R9p%BCftp zRjFiDt$()+VeZ$NTQt&GI_3r>0nT9ns8DBsiF6YeDS?FrD*i=QmpQ$Q#r@fp2N6F; zW|5YBQn5S+^KBcOoq#xocMrqM<|f$T#%#L)3MyiemgkAr9}_}z`~liD!#P`CBKz{q ziKAqj^)ENu{^_Ji8<>Ry*Gvs43`k}Gec(Kj7u-O^0_2puV zhDnP#O^cov;1AU9#qMwtcLZ+yQl1_One#Jn`xS7(>pHVd#lPc0EvYuY6GgkXAMr~M z^C!@rTj;CFL$JyJSuc<4VBnCP+gx-j9aG!DINImXGThJc!X{F-<^FQ^7jyeg1rF6 zhHZz@Zu^slsmvDS=2BVpbEaqD&C|wftZ2hA;k~0rtN!k>2_cSuXl52yzI8nnxPF0{ z6^zGKdbDb7aJJn|;mL%C!gAHU9p|tAb#-soTs5LK+==jwD*&dBYAoD&|1^`v0qd)j& zB~xjm*()!SEFY|rVV$;)^+@B_r@NK^AT9wI4;VrkCyoy07m}f@?9B+ypzENZw#@=98T!mI38hCy`vg-LRsxY)?5ajM=#Yf!=!M$^8EcY;Z-Cfp?Q z(M-N0DIr~Kg-tb9F?|%J&9Lvl%)Tn;F#n;C}up)m+VC@9H!Hh86~aq6Tr16s%|Y< z-q`JAjXYcV^yTW~eY;c`nx?k@)u0fS=^wp~@<+tbt<1}jA$n}ud)F?GqdGsFN?+x# zVo^u&uBbvJ{~Sg|N@Dy<2w-4CQQFrP%ls2hG35Of<_`t|HYfugGJ`^%vrbAzjO$XL zL5l3|GCBTE0o4syC);QLCxs{Ns?tsQY-b)+j5T2S$y;bU*(krD(w=%#Ly5a(x+GEXH15Pv@m=f^!c z#!!ffhm49dhdh7@Bg7u>&06aI6{Q{geaTcuCb zt1&tjd~`vm7v>-5yeR?ib*{svZi+Ta1FIR}%?;5q$9c+$rq2(n0xQd%f5lI;~0EBq?&NOAT|d=6@;tK7cLH!9Xje`=n@O>xz(&vrq$jJ%Fj`n`k}U?EBs*u_S! zUR{I@H_v`{sJ16?f~) zg;e1Wx7wlCQPGCMq`!S|0qycpFAVU9kU>dT^5Q=3CASzBu8sEB!t!Ns1v*_Y1|DVD zRsQzrw(sdf0M|#MF{(w?R2j`VqR^#T)m?SRTl)PqcRkgM5ob%flfWSg0=H!^t#iND z^x011$G=m!fV0O7U>T*GbSW`B>+Reomzz3yX@}AO&GLUhvi$#&AN@aC{-?y#Q{vfQ z;_08Wv$Ipu`;&u{lav2&{^v*g|Hb(e4-O6w4-XCwh=2YN57sXBc1fcDe{ud7zgPYz z=l^T`Kb-%?_V&g0_lqBE#LZ8{b;5sf{{P+bUtL{YUS1|HE-wF<<-gEyF*QP*c|n{= z`QKUo8N}ho#D4#|@h|_=^6$+ic02xK`L_lV+w_S|O2m3;Vy)1~$jJXc&cCLnhFGot zkLX`kMyygKR^cOor%ayM`WZW(!q&T6htVL2qq_zfzH@itW{K0RaKRhm6eo~{sZ}6x^ziS zPEJNfMp{~0N=iynQc^-fLQG6dL_|bbSXf9%NKjCapP!$Pj}M7N^78WX@bGYRb8~TV zadL8UaB#4(v9YqUvaqoHf3y7mf&8H)$^ZXm`IiI#y#Bl8&q!JKJNZjuEJDCI*RZCr zJAvUIR|}@*Rc|tz!hNt&t*1eXuvJ+i?*40&XHqvlt2GA{4qct-Jmz` za(;!pYW98b{>JQ=#<%kyJ!*U)B%OK@^MsDvFf3EfwKut2TzH-B&g`em%XjAbo8SEy zdI0r!a`wFL##p$;FPk=p`)i*Awf?pIx2GE+cWzaZMo;s>m}zE>nFH@-u+*~4zn1@S z`i6898vB1*{%xv{=x(V6lPv!aVTTZST&K-^#<~69Unvq#!j(_7$S)hBC;vB=zpYZf z%NSf9MXek7KP-R2XQjF<#%UzWU-AiCCjf1~l9A{-;+_8V%IAs9BtX<_Ud!%W;Q!U~ zf3uq5Bpv5w3l5mXLe|o6uLZF-`L}2JX57}I((OVBB&TE@aJ(p4%qn@&`#a0YSCd1R z%$enXSpJ2HiW}>%PQ%5f$aL#anIIvyUDn)n=4cO_JWJ*>>sQapynNJ7*hICEXXG7a z)jdS<%?j(Ah9G(tr|h3MSP)uTZY6s*KGvNYHWfAP4QoG8Wj#|H<#qZJq~dHccrmK+ zf|9K``y^ee`pXWRv|F#DO;z)!!wm8KS`EkT_q#oJ@+v=UO!?iI56#}WcSYC~wuu)sRu0i`et`S1bvx8ZlR(p=`+MN8oDw#muMSeIAp${Bu# zcZFH|6=y0M=R&`NM3JZevHWYHcm#YPjf|YyedZjh(G(1NqS9Dh*u{Rhz=s#>4_u5A zH~`!bJO^C-T|&QfFCI`I%ikwwOb8qXNz|XwYH7WUtxP-hP9bg1_H(MF$F>ToD@m3= z-NUbx`2T77TcfqBDA2Kb{dZA)Okyh|Aj~B8U(4T97UASXvi#Y)QMrq4iEbDX$j@x8 zDFaQ5dVlfV2VbbnZfZs>Uh^vt%_au*bq0eF7!>sqKxEEDP^cj8?Jd{}Rm;Lu{*tgR@LQ}771zy+9QZNtRS@`x%@VT7Yx(-Yew?gL%07fkU;JCHK3X(-j zTNiTtTmT7RiuIG4M?6YZSNq1XQ4!QSl&px8AT1?NV?N7nP$yy zj;D@e-ry+U@yCO1E^Xb(pG{OfWB(O$pkH~20qoVk%p3HeL>4-#0JUD?JQD4d$n?h> zmXh<7_I0twxh4dT>u@F@a8&-F1!z!HFmi0#V^YUgDuS?My33zs#ycSCmYL7r*R=n(4t}k44t~r!zxS}> zW4e^~*;KM{^z{$2)FKZ?zRdq9W0l^jPk8)E$mLc0b@B9bJ=Hz58X$3U0l>Qxf?tuxSXl#GyT0=&S7q>z7Q5p+%Ki&afh2U7ToQz zoUKk3*?+rG6u09GI#Ai)sR5R|R8LH7Jvi?uiO)fPCDEBq@^BvZY7O3(jy+?d;1K-e zW54&ZPW4vV@WNa3;2ViwP3Iik?TKIf=LDYTXgBh`X1W);oHGxID0Q&Y1{iSn3BA-p z_?T*ox!ZE2Uruzr%aGEZz!MN?%=N?g^xmN9;)`Es5w#_Dx{%KvFZTgJ{inrHDA=My zGYpBaAp#>Z7fz{B@7Kf(6verPqZ32=N1%_sjS_;mw`5UU?wqHSeODE0WF8{~D1Y(N z%M-v7Ff`RI|0wP=SFK_`IL4`i-NdM_+K1++qYk9E$Gp8t!0+abkIIv~cOAdV?oNbG zpUxc(K5CPzM(L1Uj>~dzXUt>M6Sw^xZx2QbWGbQW$@0(Cu<_6l9&(i8VlaDYl((B95s*8maz0_SUNvMc> z?HFWF3p$<$gQRQDQ*0;?u5$F2bpM9u;_w>&0>8jhf zy-n+qnfsLVBVq^>xOW}>MJv+WEz%YfSt=NGbB(DIiawhN=J^MZKm;ctidQMXPxz{Ka7=9qAAl7092Isk9Ke_=6LgeRerSjn8H6Qf7LFTWnH-k#8?O5=F2ydvJb>aRiRAbHm*huLE+HxGNhJSn-002l3h&^)rYAZiO5ERq zPch-{t%Pw=<}H7iAe!zG5}~t8=eWR_f8-KZnpoABs11r4VMB}BJ>9}FQQ@J7`QX6+ zVEl5RGcEA&8gMq5d~uWvu;a;;@!;cR)_e+9b3A1;p4uJ{&BD{Lr!c(1(9 zrLZ-p(7#FHG6LN*gmEe3d6b_C8$E-G;jf^>$xFkxkDkH)WAU3)0Qt~EA__5#heHdL zb??J`5NX=VX}b1l`XOnCS!u@2X{O)Pt{$hEv!`1sr(4^n+lHjuv8Tr%Yy$D=F30Ki zAu!3?vC{C=TgnK;F1bDWABH-; z-bOT|DM@QU012MMWflI;s(X`FZ{&LGVZ_hpH;PF2;zkK?*mE-%Aj?tkGg*p{Y_x88 z$iOglk5Wzp`-`QftdUrzyRg{SpSUr$-1ZR41y{PCXsSM9RvZcAe~U7z%}UG-!5vTJ zoIYZrSIVBc9W!H}SCF1H7LwES=_L=$qT0}4PweTR+j(GPrp2bbjpN5B&7lVL+2hY& zkhR=^s1#@i=dQyaf9^JZ$XSJ@XUVB#pGbSq$wFQ^oK!K%UpMLf$^h*3C-x-MLJ zDKvaID^E1LP%%DVpFZ#1>m)cIc{z#accrmMbK;d>9U2viWWQ1=E5La(vGr1Q{wSa~ zMo0p*C8SOqS&E7vPJ{TOnKwl%eML%BMOQW$X{T&?jS-pViJtICSB~PN+r?fjMS-Cu zs1#SLuZ26uFC&)%Cad9pRZXP4bhf3Ly%4;X3_^Hxu4koxQwr}GVv;cC9fNSPM_wu1*WmSBitA4dq z&Xkn}Wh0;q4%N&SHpU1qSDFJf&6AV2fNBBRG2@8y#; zH`oa}4klNpdnZAEvyMHd4xCV_kwQLnR7rhWXFCF#MpC#aA}G2601qLWlasZBiMu|J z@N~2HN!~kimOl-7J7q&YBG9ohCAblpP#65ZCafG0?P~uzp-}%X)0=8I;NL`sfo&iW zJo&U~0EmSEpUiJkbES)|1_TL|O-O{xE!Z#Q^HU7-IAzPYXbUE%vD~B>dI!PXQ2lDU z+A;@igjuh#P3ylU=%j;mgwioZNzfxPT>JOw}1}9dt|> zrm8Z2UsufemeRthTD~oKs>RfTeBB(6ecWR4TfBs=rE9P+)9(v)iz$%nx_zPO3YJ1iBM656>`l z)39tTns$~9w1Rts9i)gmfi4vQ+qqIL;3a%>;5tC# z{l^F^wLWpXKI@jo5~|LrG6chd1F5IkZ7VY+%uw$Vo5#NffAj8BvXp-fe&jy}zxwGr zt<7dE^%t9&4we&8EdbnVP5ht}>*-#$t$!27lB(ple! zu+p`#L9xt1kntC?+`ic`gxPMQ-tf?$uAYjM4C^+Pe->) zM{Ao#l4eG@Ob`rc+ZVfI5Sm;izef1L0L}K8?u!8cfJCN~o0*L&n$;LQ9ar%AVzNC> zIXezP+qN!@SUV5dhJP){8F!rhYE}77zLK1!p2FR)M9BHuEwesv?g`_k6SrrFLHL#~ zG-+pC{h+N}#Cc-6WGuk2#h#0>pG)Rl{{>?<9`&^9ukU0->?A|qB-g-Knimx3cxw6T z2^#h9^==~>+d-Lr*w~6j>9!$o4agfp86x%F#%!|0Z^C|HTwvgvd|Q#BtHlk;DXjB! zn)76%ddM5IFtvfH?134QMu*_0hRROYn@-iaP4!CM|1=Om&Hep7@qEZ&_X)q*EZA@M z9cK1B_r2-LCj;9vvrjAG0QB6ST9`1s?>kqEnfuA@yQv;q?nh{$A*dk7bJeH1oTt*; z=BL6Z?wHNx_{~>v0}qhH5RDm6ziG;sL(~_u9kUDEb5#8tb7kMN}{cW*22}a`jLKXHDYRcE_`j1*i6oUF&Ck+icOjdoEy_l zTIZd62^ps7Tj+jru|^UOj1AUn;#buM*SD1y&KIbFsUNFmE608-FL^BSz(3G_4GG$> zq0+@_32^*;r1A5i%g=5Q$a=wH*=$4b;)gKL`r8jS4ZBcdSI9dAEthL+4h4A%bc6qN z{#DgRH-_9AR-({G<{CV>>?bfrTwOu zlC$r_^`7MHPoUxVDq4~G$*BCy@T_N)kx&7qKNPe`5XI+k^4${`zjyzEtH`(1N$i6 zKjvZ?eJ(4XUH16&C>ID8?PIUOm=5T*=e(LJ%$f&e_6N3+&w26=sN)WthLXjHSI^DC zH|7r3Q{g3jiK!z;_&B@^yv>gzk)7yLVvH^e!Xov7jd$4_&@uO{tXX|nvccRp+f-#rV7WMM}@ zvq<0A&|vPz7cFn+x__PY-aG%K$>KXl_nBC&F_ioZJAXW;x&D>zJZEq*wu*&vmx9Fx zmJ%5yO-ZzY6)w~HCd&|0?_Jc>vBb~O5nQ3bB0xZ4Av8R?ndXZfQMBVQPd1CCt{7TA zp4{K}DD;xJ)gvTfOS~|=kl9P!EX!4rxiFbOVsIC)1}eP^+yl1QH)5? zb?-kJGu5P&i`~Z#Lwfrh zOJRoT$JY!AxUf%#yLit_rgFVqpNz;0)U1r32=I#rwS_#o?M^ z`iGsHFJ9d8UWy>1wU7n5RxQ~jK_cq7XScBe-@R*kX(?}e39S9LE!J|6T2o;9d?Hd> z|DnNybXw{bGiUUZ=e{3_(x-VjnR=?m_4UuDo|7-Ublj;wn9YVEg!2f8iNvqU}&s+9;+pqb?A1+p-*P!zb<8j%q@;u|cHI9qN|9X2x zskp|bY`rh}7!i%V-nc8@``2jWD*t^RL$an1m2Tz8?4u5vCN$Nj4 z8CC`k@SV6(6PW;fI5)fNsZs{QHm#Fq#WjZRh((L#{ynVHDbm{AFa?1%4_Crx==zB2 ztov1)IVd?LNTiKHJ{(3{Cpw)@)3%9 z+PfR2Qk`T4(}GtjL3MRgXykX1R3263|gZK8@&<9=wewO=v+tUx%iTEaJaJeSf^EQxvkITJNgGC##0feI?Fa z#R3>(t!%(O%7CrdQu&j0UXeQ^35C-_6eMASQQT>0G(-vWv|L4-lbA#z^-bHc7;q5s zNpP&gbjx?4wu9RNvjW~9l_qe*=v#TBC>OeB{(v1px^MY_Yl$(QC3=|wY_EOguqN4e ziv}nvjlJBmJLE*|$%#iAvR}A?qD);w+3h8~UccuZdTCL2dt5@yqgMCT1~Ow}+oNkn zD3v4s6=nL1ZJU=CR5-f@_BX>FEDixQYZ*(tT5K?u3%PI0!jGCMezR>CsydTJmb5%@ zlIp5GO;O0aNBhR6l21sI+4(~eEpgc339+3noaEQ>cvDEbtKxO?I{|VGDJ}q@jaQi+N>MrJCe;zq8puO94*Vq)9xMRH6J5fPgH&Lqw3(J5w%IrF9a%&Q( zn4;;|*a#>#1f4qIN=-E911kJ)0G=HjV0%3WX3JsjMrC>RCxW-127AT_7OGnz&?!;5 ziXRw+s*(Qs3SqmK*@A;%2W$}fw0z1(T>wCV>yfU;L%bIFi}(7v5Wewa3Y+5tc{?<@ z2WoELcG!hzc4E0~5nd{JmGu!CB5dA&YucY;*mqnFq#IBO_9il(A4-s$(7hovt@XQn zeMNuWb7y6*n(q{Hm`jP`F+layc$0iza6y*u-OXFy>GfCYJAX2$vg*)^@76Rar?2c( zH&6ef{nD6Pw)6U#iV)4!CtQVS*T)mTzha^v5r}YsU-w2Izdctps(UIPOTVi+bN=m6 z8Y<}@pIVHk>kWQGPx}n;eZY3#ANw$`@>8T$?UG0=Tri(R>UX(UkQWe0q(0sCRx}@Y zXsxH_#qZR~1Gf9$EKc;oqJIx zMX=uWUXc}a^iWc3y8iRv(XWFHtY@86r2BP^9a%izna2cWd$Us<&v@14BC-$bP??oo zihHzezfglgG1J>W>#w}z*E}*v>)uUfKnQX@wKJU4xpU~M_!x0ND~fB^;jnG2eh7FJ zwxR5fws#^0R;vxP@>AfP*OEz_Uo3gxN8;nTzjJ>-LL+u#=1-|g7s)yeBKFcX&z5*2 zkB4G4_HuZ`H?HUX9c$G1WzhyzuG1p>F7n}byJp0yN8Z^F=!fISk>uSEdS}ZXsfiJ^ zm?yuyJOo}I@QqhTUi_UW5}^cui2xELkjWFsbqQc=0>qO*@vr57u}tm`Q@w&GSHTge z$N#nbsR=sXAGd-vkE~QJ*q}T}+^6zZOjGMrPVV#<^*^cYn~WdX>$ITeA34=Na*enD zUT$BH0?gN;HhpdyFxc{K=ox;7)WHeanPe%$-ObD^dGa{ zFBr_eK;=-^?LFQ)BCh|8QSZI>6MjRGGCqn4sc#|KGNuD(^^W%Gi?y$gDrcbbPV8~W z)!!mB_%Piab<|P>LyH2OLivyf$6(O6T@-f zdCzElG~~A3K-?X(+e|uDV*>_7jdk+rep@}}zJnIICaM4N_4@`%zP@AA`-h$bE2e#` zEElbG>WMSMwV0tsnDj=L z6V1sU^kcm-eXZvEU40wW1~0x~xHxbV{!yh|W;8Sa5i1v5ZSxGRD$f?5_`mP0P50{kS!c5V0-W;k8RyNQ#= zYP)4H6%Q2_g$ZXu-KD-ob&#|+Gy^I&ARij|Vq9fl!0)C})OypK+e~Dc*qR4dO;!z1 z3UFsc43-Tt!8oKXb^VGZR0sfc^C`%i$bDUH?Pk9c<6>+jy7m9?!FZ(9{MszNAZVA@ zIFhpOoEdF22?@n_3&jjaaTkV6a@wwc=3tw6v^v2XbG=CrCt}Bq5{1cxe+f^Y$gUX5 zDZ)wEL40vftcJDk-?YC`MxkGdd9*-Qp%ROGZ5_L5r&R>v-;8$pY9+8@he$vp*C zm@MWlR3*fQvl$tdLdx6h-}F0ZgV9ig>5XbO?E1LP^gwpK75+62(nM~A2dnPN7VA0M zU_p{fa=;{(5AFEz=|r=0*?^ik7SSWR>##{Z_2FRR*?&X!WhExNq^`wrJ0|z{0*xOr<;J zZri3FeZy8`gJCXQaAR}=Y}BgpiBqsI$6-9 z%Z^!#(l+z{svVF8@PYNCaOj4!?|&cODCl-BOvjNb3I6f*C&})hVotl~FMPlKQF9&Q zP99RFNR-0q%A3j!EUcO>q=|y;7od-;W5dxgk1W5xt6bRTn`JL{8|9w&5_06am8k7n zG$o0n$C2AGxpDU_FxbM8N>P`O#NR88vk7NEdjU2LhI*k!ZUsZP3hXbKr@2_De!RXO zHgn}f(7mN{?$v`OqT(fpi73t(F)zvEHW==ahnmM#a75)B7BG6mueuYQVax~1%;Afd zS&AOnO<@2sv6wL`VGpUD>oq8VFYHs4Hz1Dxq?hF3yy_8y8a2CWNy*}Qstonu#A%{p zIlp;KtS-GhQuD|sXBO*FM2Va5EUOKA&U-IiQ_M2Rhgz&hX&@jW!C*$Yi`A>GcRzwNbevtEnBJexagnMEmhS;qp%_@g?WgTfaHC9Es=ptOfh{OezKql?wYQ$@VR) z_$T_^?Z_tsxy3Nrxp6!Nn%b~aLH=j-lW&Rn+|zQniTFx(RhWah$3M8fYYhI`#+!)7 zvZMjz0pbHg{okzTbbX}UQzm!VIPmq$gB`YHP# zc&uLiG13#qpO3m$x@;9<= zZ-rU;_Z{#rt2LK6WNEZtAJmEPYrNinr};?)Kg>w!-44aC)eHYj6o^3nM2&_`CDZwy z{O?aUe?flWr0^8%F~8Y}FI0!2jz}lRKB($~f6dOXgA5M>)sruJI2cU*ne_dQ*%qQh z22N@L`~VNN&GZwwk}YW$`=6mb?1FS4a`tQ$};F|>>R`fOY(#!)`KE`OQ z1C%AcSDqL5H#nzL$E*K>-dukWvu<6@^PrhKFl`~$%N3k+`hO617hX}deZ27Z48zbc zbi>e{(m6wSw={^9fHWx5-AI>!v`DvzLn$CBh=sIDw=~Q<_j8}~oHy1v?_RU^AF$V& zz4rCHzSrlQyyfDrQ&75f1mJf2eliOniBE*VbQ}&>Vj`xc5r5V5K8gmp#AO^9G#wh| z#IDes%_GgO%jn?e4)Y=aq_e4Nk^CL_@ud4d>yH${ml(A02MU=%=6b9LcMK_Kq zl2qP)@4Ef*;THY<50;xTR6zyWx9=~zmwXa3uHSu?b=n`1i<$LtQ~jEK$Bu<2 zpb8cBAbucfn4*JFCC-Y8A@DBNv3&XKBh5W7qEG=NCCvq~hn4O*V%zie=51bk-^<$- zfR*wQUoW=&@ZNxztv-B=3O-e~p1app$E)i&_u5>R+7g;a*waVdUILd>>rmC^dZ)G(SQ=+*C>&KPXcG$%Rjkgg| zNKM*4mJh^ylplW%!MOM~n?IfnPb<)R^yy3G(D)cIEf^R)s=)1lO`$n(1!i^MfBWiV zK(H1JLiOORzQj>VE?b|0OqrbuzC{wqi_Ov?%Z8~KpZ*dmCVlefG|nLTbXWvx9+5@v ztAUIdBBv*4o-ZWAH(_44@O@94oA6wNeJ{ccOU9JJSwIOcXRNJFCHFju>VCU#DmKs; zHHH+&^6{IJIK<|ZDeXINE_%F@BaPL8uxaV&h&|IfTq+a=?C1RN48&4HdRxf zzsmoLQdbJzP%@AJ=8w`9deB4Z3IxCk@?Lk!(;1e{r-T6Hcmot6+q2U~vL6Rz?Dy{R z&il0~8u!be|9sNq*+5&Gc6AX&)CU#44L%06@Y`8FkgDbA@1So^o%*eI@08vrA62WaOuLO)SXBi)8)yY^+8KpYDq6tnI#M0?=^m+D}C{KZB z!hx)fyF8nQUnO%P*qCkr&v?m7&sK4SF!;-$>2@ z88xP$3ssJB^ed)0D%T!$q-wAICBDect)a}T7G2#^f#$_iwprtogz%M~Ij?Fv6dGLH zm=wt;rWOG9^yyHON)pjXE>|Ti{fyBXwO@FevJ}R0f~M&;+I3nI&BDQfF{P?4+onaK zIr8=FO46@k`piKl*dZ0ns9-Q!cwTa$BbU9dtGMoUyOq9sV|nVfza~%tk58b3HddeR z*y-Z;KkbdtkybUf_%;rws}#>cl_ff|(NEcxo~A@iYSJxYne&wcYjd4If_~MBvF+8sL<6T#L~K|iM+uiagauWW+pecdt`D?{)ww` z=~n`~t2Js5kB@Y8+{%(Ju?_xiI}0B(B)ETKC&ktNRx8~w^?3KX{_#MO?O#^&*bDyg z*{tf~beBA_QkoBn` zy>7z>$yyF0Ugw42&IUDKG>p+8Vv2(-*zQK_*rv20e`IGb(JfYDl?aVZ()*1dmE*^% z@BTsxxkH0a@W}H9T}&TxNQ<^ru`|1nWlv0wkG>y&e!z`Wpi$ax+VqxvjaSI45z$B? z=L(0s1VLhHY2Un;70x*g(i|eh-&2|vDfu^{M!qf{xs>0X3`1Xo%P@r&%^qv#s_!Rt zB>W3MKXq04ayq7*d{WZkn;7oN_9^&I$m={sCmvSTFwCuF(5e;-X%3m?mH1mn&iGwT zpZHU5f0EbJ^X-?v3#yrkeU!k$3D4k8od}+j0$QRqhjl9!(r5nJ4@)TJZ`kO@tHrB@ zYPO;|V+uTQ#}iloIHFCTP=6+fJM>Ndz5Vc<9ooAJ^n_XMbo;*fvFFmHw2+~NfT_+` zdL6$8H5?3d%6!}6Oya*YB*DF-uiWAM^~Pa$Z`wt@FX;B~W|Yl#%)0DyLFs7AgWZFu z69}}|kmLhi=po9=`a4cJ(qHcJ64K-TD#eS7cI~7iA7#r1mY^|yh~8mQwBN={n_#;f z+9=@@utRz75XJu6y{wn8&CLMccaNq{vc9gY8&lU#2YftjVp*9Uu-7q&*xP@7Lc5r@ z&^_NInB{)6&M0gCM5L{BF`rMI{fz{)wk36KJu7T(xEgmdvm~(FV;H|TlYR9KPtbWk z!*AS1Q*^!|Uj>utoKQ^)P}Y5|-^4m5{7GimtokCdp^J_w<_{&y_-Y4YBqUdx8r-+1z6_ zAQU1b%m!fJMqkCrZ%s1&-SnuW>SaL-*PvI%pK}5aOrc++2Q8&Ep6;$J-yVr5K0B4I zBryB)j;oG2&y@K=nNbsEtVu_4MUHJfDW>=D`SB#d2?rC_=#U}}DF7|o&tbf_c~9PM z$g+_OZ01k|FM|VD?k6rwJYw3fi}JECga&2-p|n^ME01ST2cMB%m*e!sC}4>hC(7=< z+tNyG>FOF{K$-WY@xLLxf z9IPl+z+Xub7mEm@145V_hAmUB*^$!~?UG{Xhe$8j2O3`^+EO@v5;iZ#kS8`_Kr_W( z>GEGkOn_@S#Fu4NdRY+{$&67Yu6{Dus*##Z!udaNkIc%7*uoW7C}k@8Fuj>Q5nh!# z99OFxf{u6PanP7=T+K$W#ZXSWiQK#u6L_nPUJj)7KOucXitWmLR;=WXEJAUrbl}3c z&*OxubBh8__%5qL3XZ~hKLLYiFUWvMucPRva?$EI&{ZMVRJQKu0E4a*rz0y{p<`be z+Huq^%4=~zGHRXsIN#mVQL(mEuU4g#l1^5%LMn+(ZZKJnilOZ`nsbp&!H6wL`X|yJ z^$gqYg%2~4P5eR!8~;N2-D`V^xZ;;L(c%f^%2_ka<1Fe?v2@^}{1PWEpWK4XMXiMr zd^J6#tRm2+n#}x)Ca<~{m7Q*2Y#*uPmogPF*|Hj$Gc0#ayp)wat{8hNI_zdcXz3Rm}K3~+2ZC^HPRbw|^gMDhm@ z9nPCbNpKj4j^LaPb?9bma3ci0s?D<2WGgs;<{=hTwG}Ttc5t*8MfIak+L(qYAU~Ro z0fIL_bnFbV9=z`cRmH6|<8vDAVJa_b68c?zrR3LANfI_rx1d5YiH z6;JV$)FW9=l|^xtN*cEq`E}@adCH&|$e$M@k(D#?R@4u$+zdUF&<1_#DfRwYJzMIdWJw~=C-(Nnr(6V{J=Us?vn z(p@Pf&SnxHm62>a`DeW{R)Z^TfO+}(rUfFsHqk>zDm#5Ke}Z%Wn3O$q8L#SzitS@j zUh1JBPIOVZa-Qkna+|XL?GQ!12$0)@6@A>ZMR#(_BfT!t`^L5J_o-Uz4XC%;@%4t5q!j4%&#K7gg9%e5#QE|0ByduV=^f8d>z%yKzBk z`=%~@&!{#`Px-#rdn&0og&FO4($!cpRo2`ZIiq+<`*7hL~D1zC*pf@B_Q3GPJgpJ=IeJ$v<=a~Rqk3HEK;k!U(8tyVwO*nti(8r)mqdyK$Zq2g+vq1751wm8RpI z2P~lrXlV1L(!mv(&vol(aPgp*MLn2AXu|f9*)E;1D`EtMkf~0o&B~-{bjFW+GLYOs^GK*Xh9}@ntfbBy0em4^@3to|7gXSMR z6|_O?Em3%jP!sr^y8EPE0?v0>62p8H9^SY6j%H;>BE!rRlNs~|!a&dwws|wz4u32y zihEZrt@wzn`Z22`_R5vha{(cOAnzU47V3|}Okci`p`yK-v8*nRnA3&V)Kt4%_OnV* zgA_*$T%wFWFeT>BAd+mX-4-wBC|YAty8Fi;ZL#k-m3LbU82hr&`_2AZN30J89tlLq z9B!Pow&ET=!hd(D0!QTAhy+(51KKGB4_*lt9WdIt^MsRQ9vu6|YvJds8^=CkFCn~m zL)yKNhaydULx=a2{f>`X9b?f0a+^?om5&kx#6I3aSdNw6@x97Fodxp^yd1@in15sp~Df4dJJ=YAS8fN7`zG``p zyDJX^duRHupn-8OgrwMFYny%tf@nuADz04vrwtMAs|oirhsHLcBJnjUpW2G4)f|W= z;~k`B_H04#L4@??PBdQK(|-=(B^r{diNP-(C2qHb(RbYb-lrC7(a#w?xHC2pYS$YQ zvnWC&z*@DRqOLJ@PQicg`o%Qa{#r=p|38S1kmO4%8K zuYbEDJLsGqSv1E#L80TH&ZwJ$foGdI;S3lH{y(_>3ZW9AMkInqjsGw1WyE^v5HCrm zNmGDrm$3SUk0Q{b<*dsvs1#RYCOG6*#@0aPaYSe6(bpc2L56G)Mr+X;rq)XT?%@)&6cJ&T! z^bQFh9x>=2S8@SQk#g)xN(Lk;_tSG9lH}=6?QKH+RYRw9dVI_~)Zm?*H8D-Y$fw@D zH9=REl0GFtu>ffXh$RCo0#lNL4QOV#MI+_-qm&qeaX2ningeIEBgA&!>z>FIyzDAi zM|UXAAU5;(s0k{@O~#cKtTIn^pV7*0^nme3Ec8+6z~I zDtU3rSmq5gU;TF2#K z+mZjb9MAD~p>~mlYbq(rxbqrX~0S)v9xbse#}Hr+u~H|mMB&CLgQw6s4hu>$X-*)e3Qe6+{xgU zt!Zz?m%`AqN_;8b40|GhtHAGT@8j=rruud2%um`JU%c4?`|o^dc^Gb46ns4VLgX0V z-ZzF`+7K7F$@Rze>bljkoy{}zHzR-kvQ^6@r4u|uqe1OyvcJCjH6fy1rK(?W>0Ff& zNmpt_RACV$>+=!_RUWp0wFzd*ujLp<0ku0BtSFeFj-hHN^hR%JKxPPyOYxjNUx}EP z-2xBO?eMf-o!M?91=GaBj;liPsO--R4=DGiF|P8(I@RH4{_brMYJQ$b?hRKbth{

im!l(LFKlQ3HbvWHK0`L@Z^JF=kY%_PNf)m~`Zk##OPu$tQD%R7wdg zKAjwa(X$O#erf;wEfc#(u|gIOlvTc_;^A4Q-yRf*rz{X9cbt^#w6%|lP8g(iesZX} zGBxpfBTuDeUL^2k(JwlbO3mlq{8`1b;kL6@w!mWvgTV4uYMrMil<2Nm=UF0)l}JoX zv?;tbM8k&VXY2xtyJV_stW?B0`PaBFBQ(0tBIkqGU1=Xt+DB;$T3Tu~Mk0SzGFV-# ze_6wyUW+#gRwm|xz;m4Vf?Txh7@wSdv&%de{kHk?Po*jTtZVv?u<^3=N$gP-TiktDVktBFGW!EzM*Xy;&=iJ~Fm_40JvtF5}GrK_Em zY1`|)XvK|F)-fBKnK*Pq^E3U0*Tqh*=TX0Yuul@nMpMzaDu^e1*UvKbN>Unv`l7UTR_iLpVb~@XEndQFuFfg>ba=@G3t2*Fl{38Hu`2 zlQ{c*umo3>7zLXh+@DFXsLI1>Zh>KC(L-fkh+%@7|19j6@nCtSo3*z88vSZF`TtC{ zQUoIT>yHeQzL$&gu4D*(d*?1E=m z=wa(PGA?RPBCU3ngdAj<91>cMSvf|n8>B+g8RDnWG;|sXT;8Wu#_zKb)%=y**kqzO z^{qK0VlJA63*tI~G1Rv-DoV%dqefuA`~4KpSp$BLnlL>t`kA63D(N~YO1y!0D;0+a z`y?f;6PYq+%_;OmQ`dnvGk>YQMsgsL;jv39ywrzN$;iHxC#5-azTvZiF1J3F(x=pO z|5}j~&0!0SzCSiPfOLnlL{XiVG@rW4879Is5Ey+wAr^K>J{I42no6q6ru2oTQ15hz z9A{v_yRr;O#EitC^4v^fopEf!N(ur93%4n=ZQOd!5d z=~??r3CmifH3mrH?kLw4=OcgdU669Tfla+Tg}k9!|AmWZqrVLc=@K*wk9`9NZ2`92 z2{9Yc5`N7f;D{Y_gp9;R8T(2NPS{#~$qO)jWh+m^0mJ0+gxRVdFz!AaF}Db!dK{11 zEJu(Xl6p#~wpz#jp^dyE>Fa;ggu{X@#e`Q<6_wk?Nxmm|RH>p5yF*)0Vnop|Je}tE-Pu z&=UzoMh~@jWazo4nJ9JE$z&ec!jJxqf2;6X-Bi{s7DgKNYuj@2DdjYX-;fSBsuJxv zPfPcRQFX?@_w;;J1pP)Ws{=97#vYqTeqY)T=m`JmKEgovqh#sqjnmwocTN%8$9_UG zx@Jv8O6d1_Tk%(KtRKz~6s>&8Jb$~%n0enW4!@lDp@<5~+wWSoxW4fs9>>-v_2ciA zYprf&a2b{h8))XuFU#ed0t|+fJO(iDx$}QUE#p* zWznyu{+5YMLApYZBLOl5cx0(Lx*Oj)z7If6Pm}q_kd&YVNc`R;miV{SJlNv-q6H4L zFFo1xg<}rqoPX}vf1IP9yMrd~{0M@av>d$6lGHgjP`VomC>(*4d;k_7O`Z0B3^+=W zJpE#~@71qg%JTrHchVHTA+ZUU$0^vlN2(aqi?#Sgm4tI?l`mwxssA9=ZVb=lI*v^Y z&ccmQn^q@3FHE+5-N^hF6+afbsyuRRDbzK`LxscMPR?S=jJx2F72Ni`bhA-Ge&eL^ zYSr70V1c-Aie@FR~uk^}B^0v3-#Z|N4i#x8P{;L{>i;p^yhcF&4 z5irkr<-u|Abo2M={gkPxZEw)SwL90SbkPG*%zB%3@C8C2AeaG`n`Rn_{?=+=(+ES% zM-R{vJ{%J8vov6aeelfZ;BvwHig@P8(ExfNc&FfVry`6)lnQz6%~8BBxrV~a*JmA6 zX0gox!kW&x_t%(67W@zKwqh2vGS~(WMBg8<6R+G1R*0m{T!_ND?;1}Vr}4_03Dt%1 ze(2#q($QvXXz&a+&J4k3_yOfgy^6n z76mrI$DZigo6|*;Mj{Gh`S-gV(Y#F~Ei%M;LCP_;LBb&n3vq!ok+>PwUGZjVqBi4ie4kVizEjkuvL)%*!(Jy5U3J? zFUICyrE0K;*GJH9J1{Ur!uR3y+XHmtWn731CUb9wA5lt1M=o(bTvnulP$Q~0hJ)KP z@L#h$?f=01EO{u(DHP7IJ-rnYE@RKAhk^OaD5uI<5GxF3NW5cvCNd1^`-D znB5WZe|dh2NJc#fAk5+bL{Pdoz>6a(6xcaNvJOVc;6zGvbuBzDnzVY__f|zme97v; z4T29@DJ4L_=_fc0$p{(5nvW!dqrg%i`a4ldM+f-e3bO?O440EaE68eD!j88&eU3zV zgzhc-!Y5j^XEJ$?cfhJ`aNRbsoMx;?haAT!I_?PZbKie#enE%-+We0IfLhA|o{i`P z0OnJBI2DM|m1{W5Si0j8DXN^Q)PbOpJNGz~>_rrmH-!N!i<+8(&La!iB_gQ$n8zJp ztVh7D{NRWcTK95R{uNpyBmug!jIuFuV3Azm*K>tEazz5AFa#id>9>1`Vj@K1X_YfJ zaCcr9plp39%LiY$Ya!XP#a2l{9FjgUmy5AU1jDh(Pa5#eL z7y$gAONNn4#TvsC+ClEv`Hu=y@`gp@pxSO zhr$^iIeR?Z0K76JNQNbU_&$Puca=_$%z7wb{e6cuXvLbKBJgf4 zu$#-}8$hhUV)y9G<*@{9HkV6C=fkkGhmjJlv4O793r{+q59@WVC1MKn ztvENzqh4aU{dF93D zA;|)vBF&+%sY9AhLY?wL@baE~$O=~N3Qji{TsI8)Jo!}Mi}CFFT%Y7ADrjvqkN(7b zQ&{j~+kAKboD$n8=#^hMN4EbTqi1dFzF7Ga&dw3Ud;9El(fa@3|n_fht zky0_L!7-ZMF}fEqhElPn!LgRzu{Ia64pMOsg5%t}<8&EU9;844~c+lr8p%79B z?kw`?=OjbViLkN>l(XXG&VbiPGhn&%~& zJpEw)+|CuuUEXP?lAkE8n$n|z&g#jJ50UVUuzm%oxrg)P!Wb(c`$RcQNV z(SUSuM?ukB%i_t);&%nbvmqtlLJB|kl&pR$UY0K1k}i4EgR%UJ{uC5;tT2B)i3An$ z^dge+{$u%*%9K-v{$u$wUX`Pj2*9BgIZ@bmn0K}G%Q|VV1jI{unL_C+%)L@o=A~wD z<<4cLVPPqT^Iz?$s`>_PUlHQztqxktH3irB6+SzOs;N?{(FNB=f3JC|RQss+S?YI% z1UlX0f>Kwq=d9J=iLnf+s|bcWq%Z_bSUJGd>oB|le*L-d^-sFSUxkez zRO69V6W$sLWhT&^ zMfFF^mseDGk!~1|-v#6GBgtLq07y|YQIUZC{T5_Vi#i7EM|Bn~;9EE_Y=Y?BUExu0 zntwSKsA9codsASn{DyYu4JlUNP|+J*<-T-IviSi*uNC4I%(ke#VFvMcw}>Jw7Vs?|)@2xBv4%gp>BJs{Nv#rumXZ8+AO$}~ z5m+-fhfb6@Q|URttsN)Mn;m?#S5Imm(*)tfFW6FQX`y51aPz;_3N06*C2nAbW8F(T8y@nB} z4}&+`{OGw=A?_k+9!P`EX$Kj@Lr)}?<$hL`e3!I=FO|SM-~Iq0B;4jC9+NK*WG{CN zek;FS{wBZDB>w}n0&YeU0jSS>4sPHZ=4L<+XK?ZH;_{cbKe3nAL~Pe>-onjRxmEAR z3&MV54Fkgef%)MMVuO*C766#ym}>VP6D)3uD}wF{=stN$A7~37#}s0u2zWC62`K#& z#Zelx`yBqFxG75)@0fkN;8prfB{CNIg&8e_^( z_dtlfZ>8JI3i~a#JK6&jkipN|$Q_|OW?1nS&f3;XTfXY0z1Oz;ZT*dS;p>Tvd?yZs zkf@`Q(%(pC#bbMh;|RPfd&V0Cyfs4nbb!jWoC+ERi9iuJv(WYXkz24d=k;%aP)Ey- zr`qUKV`gE?<-ZPgaOW3ik1(|WtISgW;rU_K2bT&05zD8Bc7K!6f1Se5JkYX=Vk+wG zDnCx-=WG>Tzc_6Pzc3HiOl1aUBIsqx4hzl>an`^T%z)gx^YT)GM!O3T7>MAXyW470 zeMJR`Ez02Dn5&l!b8NF~EA5UC1 z4nv>qfeqXWRhZDt1|7UG566sTdIHER$>WXjJZxTMP@>c4S1(nUr2eMbc4@)fi>x7y zOKk%EhDuRTAsc>{5p#troZb*k+E)v+ZMmwUW7xUALC?i7QC^|8ab&hsS(bEYcSOP; zjisk50I{g$b92F*l=B;>Mq|up`;TDAu!0jhSZqKp99S75BQ6}lHayd8PZBt|rCy0( zqztxK#}lL(R&>N2j*0}h2h*^?HfuTlH2CcBNY2n&IFOQ0&IAw+w^1bVf>9O0LSWc> z9OvLlSu|RB5DReLRi*$E`|g1Na(t8W3}CR9MV$d0;hd!{frs)a@b~8cUY)AH=W#lX zfXWn}ejsH!qp48g*;CQvQt!MekD+Xf8A85*|C42%rPX4Us_`5cqEQeYH)P+=e>}u^ zC_KnboA>o`DI&f5r5a^xurjFVMVuB`Fc`OGFO(=ZrhL%xY`Um`9d|HP2zt(CD zO4o5m#>;uQ)$9@V9&bNt9s(Qewu}i9pkRMflw!#0yUDSDy?*+GzE7W@cz3`1RrQwsIZYlJHduH<;F7imk(U zV^Godh7f@X*NWVKoiD5`rruV}n#t$!iEbPCE#+$^AN`lsUES)&NqNrk2})C{*XC1E z>iP;fW`Xk&K_GLH(uVKHC{6IF?bFw}$*6AH8EdUkuQO4D#$XoM;h| znGWd4Z(Q&*tvsx;k^13c89xEpV+owp zzQn^Ki);y64$pflz1m*$)37%CW=QU2<%X$mInGwp;{|Nf?+I^f!tIcvHmqcv^Tln- zB_pSUja1T1HkRP?P+nt#Jf#)Aa)^lp3Hr@L&- z%blqvz!ed`_!IbSYE$;+t|&0w>u4L zE>j~oP8c_-_swZwFC^?7z}Gb5eJK0J`ZW}uFMrQ#G46{^kIq48;CFru8n6-D665Kcc<9Dh>{Wj z5d3sn1eXcJB&Vo6E98W8*fxr?@i1M@n#D8S6^AY#Mqu*y!wZ12mS{&P;Z!?G+)UZP^a^#-uMOn=UT0RdXv}nrcFto8{7jhZfU*wJN$*_ zq<{uzfmfE(Nek`u0k1tDz4|{}{&JNp|62Z3&Dk?4D)t6dBmc4dcdh6>{Hb?!JESdFNYzf6_k~_#P>ezl0P-U_E7mUQiy;G8&k&$Icu|Fy5~h@+ps|6 zZt2BlkBro3-I)jhxSpl6EP8|zn);x_pULO$BGZ@lF#&W;{$-*H` z9OwI)!R(Y#w@l~}JTz=NsJI4N3tmxqDg<4hE&^*sP4LZXI2 z`Quz;%I%1DEbIb+lz&iuhvagB82W0{VMU|Qe4fpd9Zc>Rl%M6k{KKBCnvWjCl|-Z=;PlfCnv|p#~7Ob`0()H;NW_9_j+r2e}8{>clW;v z|Lw2uo4nVHLfe$$uJ)2GwZmot-> z(_@!YW2aLSmlG3LV`CR%W0xO3T)lsP`r*Ur$jIf#feX~YWq<#9fB)q~&*gaQ)oAV2 zaLv_7;q8a;YgF|4n>QC7otN#E*KZ!(bX(nYXx_Fe-8PGEOidjR3`|c?PfSdVkB^Uy zjlF;Wet39zU|`_gyLWwkecj#N9UUEQZEYH6G;hKBR9^2@@)>-4m{T+QR>*+(glosUc4wNDZwEA`T6-6!9OD-BRM%aK0ZD! zE-oe}CNeTIJUl!sEG#rM^k29?ARxfk*Vo6#$J^WczgWMMlasx@{ePu?OH0dB6VppW z*+VVuD|OK$1oB#*`%aQ=Q&Q?$i0ikY@GTefFD{-9PVPH6?HvR42Ap++f$4^hZi9~D zjv97HN_jEu~G$^QR( z{TQtO|1R}on11;G$LOb}rTs6^Pew*YN=gcY!AM9*h>3{_2?+@Z2=MXo(GUQ__!^OqL!TAU4|9?sSn190m)9Cj+noddjUq(NLjfU@kjDDtnjsDS8jL~1r z?OXLR8)NiCX#J`ulbr853`W~({`W?IO;WgEy`br#TI9lOn|GYQwoUnsT3ymBbUpk9 z?w6aJ_LXRN{nzLhnt5e;OXts*4__Swh}q2e^B=D_Ct$x%)#+*d_3V4L$G`CPOS0Pl zPj0baZ_k(1gMh>IrzB@ve_ljDc{j^q{xSNAY(EdgSP=Q6h}dw|P&j03Rn@_GvvoPu zMc)ewYhFxQ(3F1M>fuhSt*+m$S1A~GwFjioK3LdUMupVal2T=`8k3{%e6>9w`i9!5 z%=+S24Vya~`z*kMVHzI%e6gGp+5|;Z(IPQk?+v5tG zj(2rN0)Kz_4DAJ)nzdDFrDsYJBG`A^(F3XSqn-es)J}Gk8&*X&7KykUJZ4OKzw8+A zi|t9~r2Ljt8;DC@LJ#&euI@JHt5cCp;Z{xhghajHhrO#ENSA`?PY{j$^0`xWW7;ie~Z>7lkd%v`d&03rO<9d%AGEkJ^+QwF9UML}6- z0Q>H6$jB>u4w2w7Df}49<&`0V@r*T6C_({O z6@{+=pd0fN$_D#PNRBlfR&q~@BLKgNf`!B?-#Eb1y@>QcbFPriuX7QCHQH`@ zzL4CY`eqq>jfKRvf39IS>tU&n`&{pL$`}5rd<|+=)UPeI8_J`1W@ZY_269t*;xgie z$qtRi0Y8b$zE{p%ve~1o4_-Vu^5_Hj6bCsco8#Z=-h!J6Lf~t;!W`zdJRiR=h>oZ_{-OtNJU$yF%>E8F+X}=$7k7PRXdFb?m?TgXtg^p3({rR*Xq9w;Ug6&nwkK|>k zw#~Y_N(R07tz>e3aBj4;M!xp_;9-75rP>*ixNlvZY;$AT<-fHnfcv#KcEA6;Z$zHT zZ|vjpU11*g=16kr^5D{i?fW+YCgUs{q$xOGyWX~a^d39=v5e1k{!SV1&;~k@3r?mQ zlo1m)!iN#g#eHod^P-Ctm~b3-q!FC@wHxPs_9ZWqe7KfUBsH)IX9ZvK!*D9kj@jZG z>zBVH3MnnA_q5k11w$I7nD)~GJhLrFov1P(qK+tfdUpEDk47iQ`eOXKnq)CUZbygN zb$v{g4H4)Pb06>Qb)Jn7GTMn?rt17KrQdZL87_P>e$PGloU*3ARpRt}8?I#IhU^Xw za1pnM&0BW)+q$H3ag4Y0@41q?w1~fL4&Oq>LC&{!#HPq6kN>2j8a9 z3St$Cp4n``7yL70X;EYA;V9;t-`?66L2n*`0m?as-_Z=wUa)92IBEZm)fHPCVEuYoUD)N+<@aq`@AB)IOvX>* zh+)a;%Q)jc_(!=b13Wt27lw0%av^ctIxU1%W!BC%ibeJW11oOop&!L?)_(C#UprUb z!oza46w$N>T4bNg07R`4?Y2R*P6fkeaLmrm>jQbS<*Q^gzabPw5W>B7V#Q>N-pA>= zUMhOAt8QZPx@yh1?Dthcr4TPsX1z%@(+1YX*Ok+@rEj}-=0`0xFv~+<7YA?Xz=P(a zCx5ykV#_12NuTb*a$xqr)UBKv0Wn@$~#0Loy-WR2s^nRO43Bh zT*Pd03AVqF3i}(qLm4AT!)s{)BY+bwNdgkwKC-y6&QcDn8j?R3sL3uUDY%~ixY3AN zry;=4f!po1SzK`KlZP6VunQ`WTFOTkQ9d;8Tn`?!!vX^mp1^DEp5(`;p)F{MHDG&6 zd~=Sm-jRI#t}zB@aUN&n@+duV8mmCpN9h(x+eXihAbja$JUO*d{*QU$yJCk}lfkpD zZ<=FXamEF?CiUghW=g^CgL!OyIfrqXoQya}@>4!#a(YDFZ%@#R9wn!aaQ6eA>C`4y zeog+4n^;?`A!Euy9mTpPl?E4O<-o|e`K*z-_Oqj&C11&BBnV9bQQgsmAHnI8pA&G9 zcwbkD_l1cVDEX>0hz|@1IWpXu*SN>KGZxAj7Y8!N6L_Y+rdg|J;*bKJJ`XZDlai$3 zE-o^kJl1)Hg5E=5m6nl60YD9$*j*Sp2PeY4OyTB;xf)80xggg<1J>3E>O$Oz36b{${i)i2x-d5THZjPi|CiEzv-3KhE86(@3;3Ac6Ye}6M0HkG* zNEti@lM?6pz=#mcl7}Ss$^akQJYVTNf6KhUki1~aJjz2TWkwzb=#RL}d-5$W(lS4e zC;w?keo{}qzjS`eWq#6D{xe#zXBAEcUO`q!L1AK^;NkO({|lHvXTKGcUm2Q5K~FmH z4*b9l9Q6qKKoHdc3J1YCJt7HjFq^blo3?qIxS5-}xtqM%o4)y*z!{vvIh@25Z5DG8n#UZ5$O*tuN#cn}OA17q+B=zs&N|H+!JX%K5UA8q-T zo4KBLnVIbQo^k1(@X4O?IiKrUpZ0l~_&JvhP+E$R0r`oTgc+ck*_m9aV%wRW3R+p$ zNf6F(3T6oaXz7$Pc~&$zY8Q&3SvY|4P+t~Wk6pQ-BI*>d^$eHrVMz$Qx?l}_r06-ti^k%YLIh~jskHJ7Dy z%Ag6FifhWIXj+kbIuKpxeFadZ9l48jTBtqoi<04@eA=gK|H`C1WG8Y+hd7FjS8Ax1 zdJu@3BZ~T@P}-@Ux~K+Wh=@3;Rw{Xyda4GIsT7i?jryse`lbwuqH?B&@(!on6+TxjK})`joKBsnOc2T{n%UWsMverykj? zminxDI#|HEZ^(LY;fj3-5sy>wsO8FMDV74PkPi2d4P>yacgn4y>8*~cuHTxiuo?jU zHVceZtEEa1A^;AlPzEos2JrS8nQE`*hp&vn5T6hYdg!p-%B+{g zs}ei0`nsmB4U=G<_3E)g{|T|KDy=%Zvm@(xs)n(|bp!O# z00n^$_}~d*KneG7MhOVAHrtChOR_7Qv((y-w5Nm=>lZr0Bb-nW`kvs)V0(%++qc{Jw}MNxh`Y8DyIr&ZL6@r+Btr)Kpb0YY2=E|%Nr4IfATuIR z3fyoH;!p|!Lk7;k4(q@SJTMSzKn?DI4#fZ~X z^01T2%RedB2HAiQ+c2|9K?dJ|4KkAh#n1*Z|DXolPz(aG0qKwmHGl)fU=CjK0!JGI zV-OA2AP_GA52A1bmB0^cpb*7tyatE7ox8kf8^8h!0F4$5HyXXGp{z%-0o|Ym5=0Oh zg#ZAM6FUI_I`9wk#s~XQDQ(~nUI7Z(Fc7W44E*b~{)>kIEWiUiwamM+e|lP#TPzH0 z6ss@_01&|gF$w4(5FC&WoWKASKnmJG!7q>xl5hYWPz=o=5YfPClF$z3Ngs-m!XvuE zE-bajx~>392LC{b0|A>n61i6Vh*(^}FO0}q|6HZCaAk1&p&1JmEpQIEo5P%@tJJUzWkCVd zunJ^g2E~vKv|<9?5DH>|2GHOPE3(IZ{Ko}xo*hudg{+{5yu~)T$YNZPvKnWAE4^~M z6mjqm{4mV_;1B#D9vmPI&hRpla1NEi0Px@l0MH55;FD$m08cy+QGCLLJj*JK!uSQP zy`074tjMs(QnV1TGpw~WJQN&|1Mr*!)xZilpsUjW4HZBTl~4|Wh5+v%eWGA&0$~D8 zDZ(Ud!oLH~-b{kEoXah2&gG0w7cdWx_t1BNfJuQh9Y77(5Cg+w0^(r<_+Sbm!V2ub zCTidhn=k`ozzpC(EA<-+Hjuyj|C`X=ywFhC(4;!JFzrsnd|0ueNNmyhU2xm&h00&WNPY zUVVOGot0cX9^-n1x14fR;A3dbC`ApFH{I3@&DJm`&g(qXa9!6jqPaZ1z#ml%%)Z6OV_z2nHYS@Dv+NFUA3U7Kn}B ze5lr((ZB6YUhfU3^X=d9O&69e4_W})iHqNxq2K$hT>X8r20q*l-4~=C4DVy#5vJY@ z``im|X$=l}79Mb7T^AC7YK#!qML5@zh~S!`;2Z8*9WHhs9)AD*6@YNujbP#v$+Gs? z;-&cFxftT|9pG${0RD;Mn;6ME&f|{gpm*X#UOY4PepT({9e^vi%k; zwF?0-=QLF1nu_7u|9$6auHiB15tY)6+sjh>o{#Fkz-F-e6H69NjK2q%I`K|B>-&*>fc;mkAwa$)uQ3a^h2S?uR%~kFhf9@O4 zUmeeQ{4U;*|K1b>z*4~wr~^Oq>22*Tf4rcX3DvN>$4~2%HX`lRB%sPR27S;xc-k$?j{pbX)#anJy6CLn^~{p!u$@P(Zh0l-qi5O+EM@JmDW zn8D&#Ur3fk0@WlCXq@yY58%Jv?`FXQC1waW7V~<|^L3AHmL&uKP|rDx4(X5$pODW} zjGk^up!b=Wn7^6(x%r0K`JP{xpdb2hN!s%O0(z`it56;@_UCU;cqf{^&oK>W}%sz5?bypz9Bq?Z5u8fA80SaQRdU zu>k<_Zw&x~1r4hB=fdDZh7BD)gcy;af;S2zUc{L3Aw`QCJ${795#&gc1x1!b zS@6Uzd9F5AOc@j7NtrbnB2-~h=T3qh{&nCPROnEmMU5UsnpEjhk3NBp6i}+%jE86b z@qma>A=8gExoY(K^oi>URl!LxlU@4bvUuGkPPUxnN}89-*dbVb_?d|LHt)~#K?UYPph z|3BKbBLQd;EgimYp`JdJe42FL;dP4}56v~LydI$4iauV}G;ENvsb9yQUHkTu)|Uo{ zp8Rk0vgFH)SE_-QywA>8o98;6dqnT^?cc|re{%h#;3vcX3P7d=91y*vxKOJ(_f#XW zzkhPluOa>-q_9E@F9hr-=@MelK)xDG3d9gSG)g`8%py@Q5si}1!U-{iF-93@1mHy$ zITS8M;&eprx&L?+3PI*j^l>~OH-r#F8);;+Nhhyck|_U-EYhzPjk*%cBX^Quy;#QD z^1LedYO%s7pF}fFHS;=Cs41-sQ>-kBnv>2rYZCGZFvtAx&hH+KvCTCHCA83?{{-df zP0Rc&kWUpEU8>HEx|HY3J>P>AsWK@<)KE`91y!R?byBoXM;|>EFG+=3^`b4}kw*!* zQdKq6qc)9j)a^nDB#%&k1vV&MYbsSUT6^s9Sh-q_=m9S?Vs@u!i3JqKVYABv7+C}e zwp(wz(@?BpQN>hQG0SCY3$^r|6y<+Syq z2UxPS-DFRLH$Q%_TLc(G^rg6BgB~u)-&zL_uwX4Y=4#r8)EyF9k3VL(S|!7!5er~$ zDZpZx^Tn7XjgehgV0V!+z%!3Tt_kRVRlcz1*A}=17$;_Cx?7_`x_Q}?|BDhjrK+u- z`XU75VGFFRhq~HkqFrQ}MniyEq-nK7efp!Q-wL~=xJR0s?yn(wAQ*WR>FVyF>h`E% z{Mv5K2w-%HU~R<ZJ3H0V0^PT?^{Jzsy8w40eN(bJ_-7iYL$QvTK zJI@|diWjo_#bkOWo1dK$_z>p_0|N59onLZipW&&d55R!M|1_AZ|NJ?Kd_P(ss|tvc z10v8UCxF$&AeghsOmIFGJPinZ0gSF~(1zTBVODTdz6io8gnv_?BIFT_n5}Sf5*!=; z0>~sr0Amn0gratG2%H^)u!oEKAx}g$1Xx``ZX+Zi7)JsxPSoZf+t|(&CzGvOa4U*$ ze2p3#GC<9-(28~p$}HqTivWBvi?G|=LpYHQ!4gpD4ibj$Pp(E=&X%kQq36n7?083`k zM?c=OH2=6k2ZY&xg>V8MN!!d+>;>rMBX-~7EYNkD-lCvfdR!xl6_L~eh#U|Cmgz_ z9RQ;j7@%lOmts)>U=%4OT@VioDw7_-3K0V(Xg~Qf!40Ux5-U}c0AwLLnKtz(G_~pZ zI4aVqc2c7r2|z65v5SyW^{V0$B|$`i1{avY8R#GZQq>d)V7SDoZxsquuZhL4s;;gW z$%EzOAkLkVDXai!MLF_8j#k8gnS%-e_d)OkX$xyRxZB1E1ogTXZ>5_N-zL|(k-aWT2B6hlz&5s3wd%W;Ys!Z@DPo0~ zZh9qB-8%+Xo2vDQA1rqV4SZ6z(z~zY#!JEG#wZIf8-RKRETR4eC8{WcFV5VX5fBJN z9<$g2AQSwS&K{Of3&;g9WHn$8_oTpyn(Jg2ywSTp0JkY@aK;-mnkvQ$0I3gPkxVF0qGJgIK1{MFH0YS#_4_liY89GUWVHw4*%ds;Q!$dejES* z9FT@HAWjfToPz)aVE{ZF0f0{IqaYOcN1xkW5P0|c-|XKd+(d;0CCULuyR6dt|+)D?68mwgWkwwI2L7!=a*Ho%7|Zh!+;u)_oZ zAb>TZA%-zfqZxjNhfuJAK`S(eIJCbAt2SC7sE+D`1^S<*7pBZctda;)qgsTR8uVk|;3?zsUaIi$c13btq9;8A6nmx7h zl!#FwCu}MxR50_4LNsKE{{esnd9Z~pzyt5%LMe=oFU*bu{EPpB88R%x9E^z_1e*xF z6go7XkLad(r~*8&gZgT_9xMtC#11_43k*{lK9nglB(W~6BPmn@dXNV{_yRnLFa#q+ zX-mRifig>ssbR^4YH$a1I0joI2nR5Qba;niD1pd0w(hGkNJ};l_=T330z61DAJoL5 zv%^UA!wW%z!+9W8tfygNhDg8x9#DpG*Z_h!1#wV=F_;Ev&_&4dMK#Ps7Gpzszy%P{ z180Lky`!{1vX*7E5MToaVS`3`dKeP;2Q;V=ec%Ivuz`OtK`IhQe=9{(gP+SN zl9WA(`Y1EOX`rs$zUtD z3d~26mr@vq{}(8Tj{Hc12uY$8CZj~kyj0GoyvyZuPNi(l=UmR{luqTO&Za!XBTxV? z5I+W}PN=-j@1)D{6wk5TOPPEjzqF9*1BT<;%{LmBsF;e2@kfHF0fE$^g3P&IG)VJH z$xj4;6UagfY)40wlG=og+nkI9d`~zUmcb~D!_dZXNP{tuhMpWrlYB{XEXRfb#+C?x z0Dwa|+)xe$EA)(rY*Y;e{fi3{y#|G%Ve!C!U@}@%2Y4`s`^!(5EK&aK&xI%eS#ZM( z000(HL`FPGcQhfsi-~tgg)=w}7WIqgq9GWKQS}Tn{X{(<-O_Pf2t#nK<|u$re72I* z&>KNf|A>f#W6+0gz=Ra|3n}%BCVC<(wINKDG$ob5BXq!q(6Z4?noBnXytNdnT-K~%0Z#fVD42Y*0^ zPWU}G!BPuhLLjJA4Z2i<$$$vJ)m+upUFFqY_0?YmR$tA4H@MYcHP&NA)?gjhVola& zb=G5DR$c`GTW~`Rz}2?YgCZhSK9vhdbchnT1Z{u^R!9R#$cF!ORhm>2F`QLPeO0&F z#k?3+D4^GRwby&a*L>C2edSkveS>}l*nkySf&JHkHQ0kS*n+*+HWY?DpjRzW%`0HE z|831wBuoiDNCthlhDsRD#Lx%5h}6DtnLTXR@2Seh1r;u*_n;m zC3u4+pxK<&*`3WNCoThArl<2763Mc(DrTqDq`UvPr5O+-700@iI>irv(qid_Kk2ihfw6u1Z6 zjob){r+V~V(gEJ35Z>iwU*%=r;dS5l1zpYksCmePvK4|k5XBv^Uc)_8*fmv#umnr! z2Td5@0XBwGqNeeUkcc|p#YtbKSYP=i-uR_p%(dVPzTCd;CVBV+v)zJ%BLezvC+q?bSz%AP* zr~^E>0^8WNe1zfG%UaW$A5p>6boR(v^o>D1x&MVLBM$ zbH3hTuGqSWT7y`IN-zjYP=;o9X3^?seMyZ?P*D$3>9Lh*n4aoK=H{se0!eO!m{wvY zM%#z((VyC!%9=Jw$uPH4^bl{XxM~Jh=zL@WJty62&q9z z?QOPU8GBf!V!+xKcx>dJ4CQ8N=MH20reG{6-P6_FD^SEJsP4jc?I?zAnGl0k(1vPA z1*(8-d||@qN^kZ44Q#N47H9_(90PN>X3)m#yvF6do@)Gl-y@(_Tu=hC?c0Uk-vIAv zh$irL*6!BG-P1U)2>+GT-~)Z=2XxJZW!UiK?r;y^0TK6MB1c{ya0Ph~hAjB-xXtMy zSX=8RMeH`km^c7F&;(701H)@@eEF|h2rwJ}6xlEV|1o$x04M_+`0@D;at}B13x0Fr zZ7q86gXD$VD2Q0LmGVY>Z5WRU8Q=zZum)>@hiyarC+KmnZ<7z>B)4C+je;d^VuyEkK7Vlo+ujdA27kzheCP*R?|5%%MqPMD zkVg}zxQ0PD`lGjoZtn|{kL7}|V3ZGHF!kWIg+o0UY?yCx!#-h7u8A3FgEo*gznF2= zphtTY`X_OU@7{z@XoqP4Woc*!m6C5Dg-$StPT=;r_x8Hy>%13u%$MI^hlOBATOn9SIf&^`&-wvR_J}MA zQC9s?UUjBvsh48>#{Z3WU~qz%fq0|*|E0J55ZC;s@BQU{f?z!Nwe{~h;DgbR@|Z_< zcsJCT?U+pgY%ychhS z>vNhn{M8uy)er=Iv;OO68BDl`Qh0<%CXqo>HolSrUMkm&O#K?QFV z04-`XqEMnomoiefdFgvEZVec*RpNv7Jyc+ z1RF_Hr%qZUw+kD-y-Lwy%fNy||K=QQc(BUDhkdw`H_y+zA>4+el#qCoqM%ldU+Sit(gu5J4^?%bVS*WRle;$OwWSy~=$++*?MClkq| z_vhn}FL=7_Nd6Hs?9aa)YTs^9bVN-5NI7K1OocntYqWVE$h$p!iGhH*if{iu{`_d) zzxJI!xN-q%WSxM=5m?|xhR7q&As}6WM;%dAS6E5dz1H1*7{UkMLu7n|4S5Nf!vg^6 z0RY20@bRY~ej)e*Ob9H>I3tZUt_Yfc_yLGufCut;n2$gHL61C%fYbyXcx-V|kQ!OY znuhU3=^cj&ZP1Mx(1eJP|2s33h#DE`sJK;)__+d1AZ4n#CY!e1*jbME?f9c{P14zt zodW(bk36pU08&kQ2*D(UAUz4%lG9+Y7e>!F=3y4|n2Ep$T%#Wrw|BiT3* z>6QoOaLzLM6r+tfF>G3DZXomm%nI0g`z^Q!-6()nZ>1XFs;?qesJep1I^3-C)C!Ui zdQ6uQuRLWp6pO*)w$MKT|HFwvEu2Flvk!HkNioWJVnTeUhWi#Hzz8xi#u>NCA0*k} zgAX>4=*5tJ>9&g}|GOs>mokF!&I{5O5H^7?%N+HpnZLQ^Y}>HKc5rM#as0y%(f|0v z&jD;otg%{o08>l3OiMj=#AFV12|S><;YKL%Skl(H@R_XgN$-+P^GbBOY%54n)Pctp z1J=CJ&3)~B+ug7=S`Y_0_?<&FtmKf8H=KBh-_lfrg~7HvDE>I)Zdwh%HzE@R$v0q= z{9i?9yF0h%gr&{np7I`HQWto9@q^r>U#IVd{OXr?fB!rsk)#P(QjI^=SORg?oJOA3 zBES?fJo3r2^&UPl6f^@qn)9V&=b^9cy7eEKEm$E$z6??oc-%3?M)_t2rR@39&f4Ay zpvW%2X?`TPGrRNj*fO%y~E*^pkzs+T=jfo_4jYM^2aK_pnP z4J1RD10J}*5%cX!De6m~ecE>wGhCw|*8-qd7LW^IAOVFge4)Z7#|M5eV-uTT#y;YJ zK+XZifgstQ=YWWkLoCP@KsZUv=s<)GLhvGWd&~M_=fM!#4lHFLMLFQniW9;RDu)2Z zA-X8WF7js#tgwbPSRsayO;1h=^dWMZxIiJAgou6mlS!mt2e^q&C$K}`6f*?E_=vD5 z@tYqrAhChqjgcu%0LCo}(8x*p4}WY4TYJU^#|L6>lbjTg513OVJeI@K-}ag`I7?N0vJ%xB`_oR9-sM)0}R+9^?K;Z^2srKbo7W3 z8dD^eJjf1Gh+`*h_QzHR@|CV^Pa%PFxcpc$m;^BdFcx9XbxQ3$rs)Sf;~9=l5I`-M z^o}My`OK5;b0bNB2|WzK5+o@}dvbiDTVTn}{Djk6wXmal&ppNofEm~W z0553lLr_W(RUG3dF#U~8;b>D<*)$KqkjF3b(2{!H>#jj{QeN%WS75DHSbx=6V1u~> zVDth5hP~~Y-qVdw6yy`!000@v0TIcnlpW~c#wkW{);6l@jcg^{o05^;)cu>prmsrT}CCj6C4By)=4{8}fk-RG{J-_-F$FD6yKzg4Gdj z&_NuuQH`V-qyav=!9Ql8fCV$S!47^fgd;5B2}9TeZ(u?YGOXbZbGXAE{xFC`|NLQ` z6hXu$J~4_-OyU%OxDb4@MHpC|VLig_#4A4W5}=R)3iG(f60X1-D&XTG6S>F=0J4yc ztmGv#*ahQdO20oKEYi6A_NBiP{Tnu!P0+7;tg(o zGo0fr=Q-24&UU^tp7X5dJ@dKGe*QC{>CA`))dCKFhJ(HIVCXlXYfg>3!(ylxZxp})lFu7xY;`i(Fm|u&>>QZ5`r$NY1?Woltb;J>82aAr_7)gke%AD3oweir^JEl`L(P0T%Fp3m2Z2LGYp&MZD>|ncOu* zW+E||10rcyvnnXS40PxN9H_XZyII~`mp^yjblM(H+{(WoM%EW z$_#6G!yG0=Jme8UDY$VDag>5nWN-#M*1-&f5kv;=U`Ih3u?>7=|AP$>8FetvlqRQh z-YxI3M?*{m1BI{U-MNXk1I_*;vt{8IaW%{ZGl;U7J2ACTtUKOtueZAw#f)fFV?sOx zA^_x|7;T7w8oHq=0Bj%~si*-CieU~9Dxez5fc!wrz>iDZpcDESoI@}V%uj`?^X6B} zd%S^W6G4JKmlQj?oLlyp2eFxX5C&*xVwjpJarSZtX&3_{mQRF^#1!V?^ZWax_jU54!?l=AgFoCu zrM%$S%^(fVpsTo;Jj8+$9EK1`hZlSf?dzzB!~8UR2S4un2D0zp*5Ii%T|one(Z4b-q9EiT21FaQpe z!6LCy0+AhCsUDByi5*dpV#G{@5aRzW6x}VNUsW4aWYk7=)JKIB0T~R!Tw(`M!!jrZ z1yI8(kbxN#LpD%Fm<_}!0zfLRVk;I{88Y0KF%B>||4uE=<4=fRSC}4dpxzwO-`O+? z5QtJD9MNIWSll3^4+5NCF(Yd!q-!}NQ&d&tVU<<^fY1;PKNtiJz!wsP7G(bZI6htMIL%ATpJE-Cf{Ea5KLk^f# z1`>ocbYS@1q?YYZE%Z-K#-+HhB~rnkPWqx+0V9I=$Uij)&I!k`8Ai_mpi<&TBSOS( z_113%*Fi{1Hey2zkd+A}jSb*~Dck@KumU>({|`Z&qZ#bOCD;Hbd>>3goC>j!T&5;L z*dtcp<8A1pGxem(9EcO-)I98zVz^B~2_{m`-3KwGcroQs#MgY)*L~&JeiekIT-}=S zg&If$JE(&*n887uBLFl4H{?U*T^?Ol*%yV8YNjS@UWIGg25ef7UKR*}U;!?uom>g! zDSg49@Ma+%B3mTl?Ez=O6`@af8JLL~l|kGiMN)Xm<#<9xdDg~xhE944h;_7{JOqPi z4M#PR50LaGVgBY)PR)T*5-<5ufyQNrE=7XE#)8&gA;#wDKXnp=5A_ien-p64+ z1jSh##%bKqIbB3e)QNZjD|E{WxI$TkDe?rVQIzOwoM=BDX}cswA6Sacz)P@G^2u3!r$|0}4e7kj}5G5kY4$b%A0>#L5b9mXGCE>nZ{2q9Qk zES%19#9pS>39u$4x>Aw4{=^%`;T+asmvY{Gv?^;kpk?t zvP!Pn0=OziPjQ#RmTQ&HDV5>~u|@Y{ywtQdvBSTG%E+(N)O0jqxO!k+8Z5>m}}iqUov`LTwRMc~*9lh&5r$i`I3sx8x!jgr~|A0%!` z^wbjdNZsaV!{Y73D%Ie+|ChFK3uq|AKU`qoD$d?6S1+1rzzRned=`wY?G8w-dQL77 z>L+f{DdApjsf;cRrD11?K)|$H=oW3}rUlY!hSEkV>jnrGxE?Mz!Mw$-?7c3``ligv zZg1r6#sqJBxnMsJ2r?}m!+0DIea z_Jx`KLjVh~-4(Fm9FSdCIpN}@~{Pe zaOt8c5gP_$I0oB&l43yc5=*e03ex=6j_r~P?sgG6o$6XN!2f~*7lSMndj$}?g%ERA z7!L*!IR`V5Fh;O2y)m&`IPoGwab3RgVeN5Y0Re5<)>>?W7UwYyS1$--*5M+sAqz+$ z1Z5#Bh7zxyBBuo-tFj{#AtZ}R9K%pkt=C#`K)`IGCU-F>f3Y40a!bUEkuXsxqcJM0 zaj?>8x^D6a&PVyBMJoi%G37E~Npfozt|yDI%!TrCIIX-0WGN2@rVg<&TP-qUtuBw? z=E~z)m_WeT|Bp0hOe`ZrAGgIHC$csVNAljF!3uNE;ek(yb21(?1$(M8kDyGZg(&<3 zI)Lvxhf6#k#5}V_J)fN~o5ZSKm!)FUU_8k9pl?8v^FSx_IgcO|07EWNlvy}Hzz|qN z!!tFLr!~XdCy#LG7;yu4S77L7zX9|?#w;6G@HAgA#Q7;LgGB?l!#@Z_OT*SnBWO&Y z-b`n6=rG4TyeCivhAG*^lLGQM+if||@JNr~m0_$`oI=1Xbx?b8nS${>8-{|&!(ZYw zHQ|9ZE$v5pbx50YTC<^xaIRO>K)_rAS~Im!zh5WIG&ZMRMSDaa@JTSI#LP*-+w8PQ z_q6o>|1?2|^$1qXOm>9;oYXro^k7d_VH56QLv>>BV_OGC7T}*Oc(YuaL?EgT>)5qr z%dj`KG5bidnmlwDVF4s9Kv#r9z$n&egNtvg+f(ObR4evsv&2QK>`^kUF-nNGb~WYR z?S}AnnI!iM6@XLCD^$!tz@Wl$yL4&W?`bo4YOCnU*ff*+TZ&G>9u?$u-*t9>^>)9q z-Zr&ijrCO^08*#JB%ZfJ`!|U$_iHw{YM%^Mr?7mV#1Pnv7Z@c^SBR9tux?-Wei!r_ z_O-_v#To=mC>r>Ir?>DbxOpNq&Hb!u>D;OmBOon~eDt5d70xY03P>?{tBqxz0 zw~;TZiYq9KFZpwWgc87&EmTn4frRr?2ZN?ETCDP&xAMsF_w}NDuw81XN#X<+0@>dZlnQ#pQHxpspSciTvrM^(iD!_x@2PY6IZ z1WXMidXf7%`JTCnrg@#Oxkpg7RabfgarD&A`lie8m3um$ssI_whee;oX z_qvAvy0?2cE$)x818PD9j5_S1$$!hD13;sz#iOS&kNClY;AXvV#DwEPg-f-*gEYVE z^^Viz0H_zK!-8lF05=Rx&>#HnA^D0cIjyNSP4KUl*2tZgKwjG)mIS&Ca}XB@BlJ+!xqbP;?L^h zYkPsPyvxI>>x45X)BNSzJR{y+8?eC)(10iC0}hD3Tz-nNx6nX{z&ZpB8MMCZUj=b} zwqU~rK9r_VnvG=F=o`bkz>b*9sYIj2;g5FgfRYzNf?b3!v-B- z-uO2|K~0-Capu&ylV?wz9^NnsGL&dhqeqb@Rk}23kvBz{Mm-AU|Cc;hQn3zo3YF*; zJa(pJ6+0H`R;){)WbnC`Ezb&XDzue5m#%`haqH&QYtzNQ8!$UGaCpE`J{%(va|9_e zabw4iAw%o~j507EE&3Hy8JTlu&!0hu7M*bM$dU-n{4{&7J`g)(?!i5DifFgqV6nH~{D-|mAP(-Ozfg)#4 zL3AP}C9Tvk40Nf7vU)7-)YDJT3&}K-01%*@OAzV+A4jIFveGQK>{HfRzx+jm)lW2c@CuJAd@Z(2Th$D7(Df9xv{^>~ade_*Q~{MCO0CVdB4YgU1{hyf&{o`W z$z2HBiZ&2KjDIWj`7BUR;`p2R%7{9{}WkX6Ol(4Ec&e#%_!=4uHc2a z{Fh8+2{qJNiJ_IYp-<3oL5ENLQG?ub%Psc+WD4>Ym_tHNS!GK>o+yp({;5`gPRzl_ z85$y@GG9dZW!UE(9G=w=dF1)yXP}?@0uMceIGW#}#e|qyiY0ya%0?eT1)O})amM41 zMO``N4azA9n#y_!LF~2J#;;}2bbeJ!rx%8rPbI2y#pyG*z@rW+=r-1FFr`+{YD5oD z66?0F4V&?7RUqh}Ns+GiDbKQ%#Po{tNc_Eq-Qr`7o~oe0J%x_#gUJj{Uz z`O}~F$|O7U*bYey^pW^7M?d+Eh5@1|NHPwvkV8~P7s8w12jeF}$k|Dup{x;Ak9Zq#Wu9f{zm+2s>kfa};C^4Ov0^C?g0UE^&B2bPNfT zWWpKBsfJ(rsh4wflqPKYU1(k7#aec zq9FXR0Yr8Xq(Eenlqt(2V)l5XJ~r}KjNFqf#P5mR}7M-&Nq`6X{ z+aze1#u%D2;%B1uNh2QnxzCPVq9FD-NJSV?nOZDBqa{UBH9PXp9tE_a3+dB@zbtprlw$lZ!Q-@^bVLQi{QKwGC1mY;jJs6-7SBSI#YqjfqpsEq6;)kjN z4;jVq~xP>8m!m8L(fV z?r2=ZgF*?L)0Q4Kl8KcRW5u>vQo;Zo1;GcDG$H_4R7Ms9$n0-FBU_7f);^!rWfk*4 zkD@uP35fK94+aWWud>#cicQi_=L6f73D=G|h)pUGFp?|;DGR_gZ)CVj5#rXzxU8&U zuH*p=S_*IuTurTXZ%SRB|GKtfmt^L76Cwa+6oef&NX!6aaXA1l7%}Oc$a?A1-bU8& z5CVIG)4XB_85#_~t5vO+A_^Mp(r3i#(XPrIJV6C;vLI=AOdh@k3@0#{#>V@viCqP{ zSb3GhYs!L~3gI*=Bs5HgouYonYF%|InVl9(>y3d+27MI78j&f$3V;U--`1GR7D;i= za;&@^^Z34Nf~75>`!nh#GR-|Eb98xm&Ls2qYG{q1TGvVeXT-)5_2di)bODUZcA3x; z`7*xbHs&|)?}`*Unh=ymK%92CsvquBh(A-}*7lc}cy6j2Vv`LLfJP9&7-^wV?T|x1 z1j6%?a5+B=*n=MJ|4x6~<(tdACQN%q)75>goqg!(l2YQ0qG=B>@|kL7lSbH{Y4v(u zZP*WsHVH?o0v=dLCL_-f$v8Bt8NZE2V5_m&@B~Rgt^sAwOy(AKT(+`T?T}}yC)!6= zZJU<+GbtpD3&*lFX#Z_Pv3i@yWi9wwoqT6?mvjW!D2O{Ypq>KM0vLmMH@wSTzcAl# zdAJ^&4{RY1SsZN$8u~)hv>kBw27K3@>Ggg&EgDSxqa`9J1vl;?j#4m_49;N3I+(!& zgror(<$%XE9-)v%Yy%(JD9`*do=E{zA~uzv&v-j{aa6~b! z$(i7E4j#L*KV-lVWuyWjtw=^fs1d3BM4gEQ2*r0N zTc0F+D_o-IGU*p$`q7}?fOZqD3w<`^)5dArsc$>&-+pj#%U|3H@60Mj0f62!WD@8= z2nW)E6BvL3NI@IIYaygT6c9ojEFmE}0UHDaCa5IyN=X2o;o-)hM?z{5yzl#{?=i$r zG{`T1|Dfi_@{M7lpnAHX&HQcc0L}#k4*n!c?(E~`MB~Ip!V$9JUiMERMj#wKAt7?W z8~ULiwxRfx&M*){ACe9sD&ZVn17;{Nlg1!6P$7eQWCz*@2s)6)z)vAUFf>LGd!PoE zVu1zwWeAi;4+@C=RBpoF53wr6215e}JE8^7LFn|)_fmx#mSIsSfEreT49uVyvVj5= zA`RdH5)y(56XFRYumdJ=pTxi&3L+Z(%t$uK6*934&Fc#jA`C%e44EfrhUS}m#s_K* zaH!}FVGRabjx*>m{(jB=AR`X`fgg17AN+wIGKd4D!5QuaAtd1(2mm1%03KKcA<*C* z|0qEr7|;PBaQdcji5$QfVk7yIBm^u63p^3PKoKEC@iR!#bsPr1^u}jgk5AgK{Nixa zzK8zo!wxxu19IRVbD$bn;qp3Q8la&96rvK!!Osxj9hxu=-ofe=!ub+H8l+FvKCpb$ z;Hdrq9R5Q|3IP~op{~9WxWW+t#?dp%QFI)p!i2#Ie5MLk2erb;6{QUp-EIcu@jhnJ zb8wF{_OAn|0UKh#1bi}sYyclj;RbMk71&`l6wwoW(gZ{RHTK~WY=9Fi5A%#^1EQhW zBn1R=LC`wVBO|ggLb5YPGI0Lo35G!)48dno(0b6&kzCT=U{VG}j0WqYCY|jj|084n zUIu3JMGd5Z9n`@YK1vl}1{xBg5x5~AobDsOa&tByHmqR;It55htt&C>Bg2w2#*%LS z#dK_;R~Dw^mSzZKr5#D|9er&M=@NPHa=RKcbEvK$7|~N8fZ|5UGVcmAH?D*_Zqc+S zxuS<*&Mxgr^DV^0Y>t=?)Ft)&1G?0u}$sjxHAVy|IHXK3c3>=s5P*YAMJ z6AsTaHI*~wo@|LAs~}oIMzjSBfFW(}v#Ih^$M(~ufFR`3v0(O%EpNp%|H%+FVJ<=I z%oZ`K8aGD<(xD*o0k^b80Oks1Dzv07RLnB;PsVN-F05dhYeP_uKy!@U^f{ z!GJNg5z-w>2!bHeDbflmNb2ZrB&55$ySuvt327vhE=QN*KtOtDug~jq-rvvnoXfeK z@BV}R@~r#)al0lx+f{usE6};{J!wV2B&L?>#X4YYfS|4R`ICd^&CZH}(sQUHf-y}KWA}8+*=^e~Wx57xuTym?Dp0*|q?QPvao>$uZQXx9MxA{L-);6|G?Y_FZc zGOQvAI=_c?GzoP}4~30-6-f5CAkUwv#4B3Y>ft?E=xNp$Ru&4y2d%I!&dkOv+{;`! zEAb=Cx{wz{^}xHw>m-|Bm%s@PW{K?v?~zp%zskB}D-3JUP>tIS$7JTrnjYMv+I_l79t=q-xQA zbIdISH4?kW>-|Ah?o3ffz}(=warFT1Tra}~GGIZCH?qY&#D^vQ#R*8^mU*iX_ z!FOLt-nXBbVJNwkCc8xYtdp4z9wjV~M81rpEKht*AwDQ!PH*(^w zr@&5ywejXzkX5U^ZUF?Twb0i1xw(60uJ{#sk#!$j$ln@OVlQ^HMm%oL4>s&Ul&)W0 z%|(bzmo-hB_aj1ZAZA*SiXox^K|6)N@2p$w^je+1Cb@D4h^|I^yr&#$NPO`Fdt+xO zSvpoY^Ar4A;=X(CZu;#!>91b?Q&%$8@KHC9dFPMjXI}?jP$lKvhDpmYqzH7Svh53b zojuW>ed^6@^vS6=@Fw*=BS^@|n6@X%`*q5A6p|8VwcJ5&cKq~%rRxVc@yT5h!a-Wo&0`g8UrC{ISWa}LV1`%fkINNj}No$Fut z$xs=)QLzZG({Ql}uo?>xmH3-i*X7K?gl2s>-JkWobsBgYSok;e9`N)hS>y+yFvb8f zR6gCO{Cjcg%Et*zL3 z;W#`I`77DLjhU3NC~meb`s_k(!#!3Gm%9eZ?wihe zagl~u6;4m=i}h%KKyaC^!j@62^9XhsVMz_hL&|y!XATVXR;-gDh~@N@!&{T2#u{C6 zH(ffPMnumC#Q(MG`XJLK66r?deBhz~%^Eb5kMmO7-}!IJTI-TYt?EoWQOMuy<|n@8 z?!E@CzJI6zT$Pj^A_Wqrjn9~k$9t%!3}^0iq-Y@obQjq4zgpFkcv9VbV|%@`dAs2K zXv7>+QWyY9 z&0SyG;>Fq}?ApJI)>XUKQL~U$^wLkQW19peN}b531TRYUlq$sfYBKGRO5OL>8c6or z7ALYzshrA}wkJA1*)B7uF_Sv@;U_WEvAoFrp=WTf`FiJC@nCuO=-T4M&(c0x1@o!% z8^9~TyffcmN%2J#?i~)Xi+jg**mLd`MP9n4$2aDxyJCNr`>(G%zy4|Hx9Tyi@6l;Z zK(g^M$b#?IPnbTnTE120yc#eR?_(TqBBE>t;S;UkR@&WE-Y)mcW<4Cp>=_Xo{@o(h zUC2zpL|xR|m7L}3W*wQmVwz9WtYPGfM~O!sEw^q*2zInU`S_>S6T#?EpUrX-R{1^H{$7m-NmrnGac%4e4eS zzV3PgLWI7pdwqR*-n!cn&t*gDaIdt2$*|k6wmoZzxuU8!Yf6poFK!X{`6BwP7?kRZaUx!Yg6Xx zBJFKyEqT-$*(F9}R#I{ML zxvi=fGKoaDU8XBr-g_!@`BScE>jS!VGM^)p+os-Oso%P)L8up1yBogG?c}|F@y;o>G$62lbwH&i;tkY z&yCmGTOs|mHq zY46N&xcQ@wiwX>PN znSD3#7O7158GY~0Rl#S}d~c$DcI`8u<{{pkIIibTaO?LoT4U;4rWdGvv~eA#}sN|?0Y z3nJq9T*JQiH}60Hyfrv~l6%hTjkAz*H9dyzgdNxG9uwW)V#-u0l9v0F)0X_haUiD( zhXv^8k4r>@J&Tnui`^FG@FL(Z_!0!AfAJ~oxFEup>oK;`e_|BsOOKKLzZ?Bz6u`l< z;{R^+JDDhD!Jl@Z(jWI{vWrE~NJI#he=An{Gn^T^ZILYMzNe}~v!#Y8(eM0tTOoL; zRcA7magT_CklbGyu4NN>!lNHYD>l((t^Q!G%j>#AA7}h6!RH_%T1jzr`}etFj1YD! zA*WYwPmt928t~vbk2KN>lA)rfF_Q%&CJ3{EPAUzUMQx>lWuRQB;ty=tCv9rA7cCp+TSlVPO+4V8V z!*7+VPO|%^bMKhqueX=y{Ie6A%LNTQdiMp#;J34weYaJA0^QQQS3iC|VXz|^)LQeR zo;5cNY2|Ss;?uSuFbWePZe5U)qJBCPph8U&B_51)#bD&Lp*Ia+dI%aL8)X<0Z(Or6Y67_tK(7+bGBC2hp{|jbrrRFd|n6RW-V_hlNV3kolSr4;4Cv%=?}; z?I3>?5g&Kjn4RI)wnf=)GxSi$C*8LBZf@^*sL3jlyw%oUg=*C6?8@W|+xK ztSrVl=WHowV>smJCw_)It@yy(W!T|CvrCVZ?la5Yruv^I3-4LOar)~BSi%^685t6O za724+FXr7k4A5nGGvk>yBxyAbr(55(RJ&p-%m3P{{}^yfj9|56Ch#C=AmHnQ%3dJL zCV8j#@AKQGZJJ%G2Qy?$I|jp*pscZsX>N9>JB;&PG<)u3H=lZ4)znyi#jCv4dh6A|_v6|26ALvO!sCdb-iHqB{+J3@J58j3u zevsHRBt)j|Lpj=$b9@+dODa<$=uc#M_^L8yBgvyFI*|U$#7#t)l>h!qmmBMG!uU7+ z)E!`85ZSX(Dw(#2iqju8X2Qb#68kYlS$?uK&*tOQmG25) zQ?|ON;XJOQz}E*bXt*hauhcy<`~)4;(hM$!*1B8Xpiby6hgnm8Mz2N~8}BTnJfPr= z^F1Ad5VW!(sRA6t_O{lA3FBo>isL^0$&RW)gG$=$DUSt+Y0W>V=y%k6IOwz3@-3E% z8dZEOdH4zkDAT6f6Xf8*u`{o}nE0rG;4v~^_G)hao(#Q_LPC}vuVL~RQt(JZ$aGN{ zc5ATR#NPqhDSyu+{Y7xT0CUBP3a+nKFVRQ#Fu5jnw#&1x&x5~v^y1uqIo?jHdJ{+v zK>YVAoY4aSQ=q^?J~f-4vnsR*&MBtny%7zi}?DdhC{`xq;FHwVR?a&S%n@W}lFQ zH5~r#gR~VI$>%Tqjvo8s8E_dQA`*yQk*LGhuUk9$7^4=rsV}6=A+%SG372|EA0jwzVKW}Kj zbh~W4wrq&d0OU2|r{ju(`}|!T0&vKgf`y)qMHnO4h%pEpz!yWp02d%_>#c2wbk8!^ z{od|vh@DJ`SgM(Us#C3rola9Z{a%DpFHuevX}NXZ;pi8VMTZ_&36(gKpnmLPxBt_t z=~&w&3c%O8U(ycfSXzKIV=R**`-Ed0*abOA+sorS|2^~uvhn&UEX9`)h-}NMaQocZ z=fXnv>;ao_!<xAhW*=})rqynn?c|Gp5sAYg*%Ny0R-*}k#DU@UiMG`8rZ`GXXv_( z;IvOg=B%0Om^%HJHBk5SpL2p`{hW{mi~hymX!CmHzPhZ37C18ULRa*6?L1{x?R492 zzs+PKwb)mFJr*)T2Bak}fiL(5h#h($u4#V$W&<*;sCq3xnjvFq9nJ&HmhSst{2>DT z@ji%E$!YL1H9HigKu6F3F;TynYRAE$9KHzVVl(_{@~9JACOv;ZzCn4iU{;h~HD+VI z{0*0Wx7DNBGQ%OY%O&Se_zV-VYgs?F8LCWSgx@hhFo5=wk5ieN;lr0_OmH!@@mBfM zv&144V=$v4N0}jldh!B{N%IH3h`pMr^f{}t?>c<{`HD=@j`F0e>z94(^~&Med0$T- zsSo@HMdW+&1tUSW))TbB?Rz3dt|CbO1La5*;iqnmTZYZnK7Dg5`AF~L0$gMnlGa5(%xihg(&en0|z zmpJ~;AwObm&(A#su?~J@ivIU3{3*lysmuInhyCgI{22)Xm^lJiIs6jPKAGgce@X)c zl4UjBK7isssSP7rUgHB58T@gHr(?@a)g);e>{3>*PrCUJsk2dEr4O& z0TJr1XYPgwv2-Pna1W#9PGy#w3-R4EwofC8_JhYcfJ*CN?9!ob+M!W&oog9n*eL|=qmJG=dGa!O*4@N~xn?6QTW??vd(L(rG`fD#{{6g?%&z1xn%@Y`V9v1hRidR21s&F_4cBukXio`9CBgBsCjidLe;sMlg zbR&_7%h*GL7`(-&_#W{OEJg3P3)4_1+_@`}hDS4$M=x_EIy1+f$i#A#Cmt0fJjjoI z8XqZ0lJuBA=^0_7v`3PnPNK`R1kQ3`CpcMyGx@a=CRx)m`E7WzPIEM#+*)K0Vg8Tw26~Y*2?* zVxM+chirUN%C0@0Wif%tBmJADK~lRs_W5y%lWb*?bZvwb749}AlAWQGldY6JOC9@# zT6&|L^vHu@G@TYL!qTJ7D@C2vQy%$AB);1c6LGVc+wPdy^c|2j1#o$lhcEhoFd`4U zln41Jz|-TwC7plIDjyp)rLM@Q9nGgc04AV-^jrn3$_1=f`OLZnoD~K4AqCtA1&<=~ zA3zEP4hkMC7e3W35Q-=itH?Kz))gZxk~yF;XG)j1DpH6jQmQCY87)#fD0=xZ&4j7w zwQ{i+GZ2F?p)mOa+#JCQQ1T%B3GZ zW}SGHo_kQ8D&<0hN=M2|L#9hzmCJ%@a(tJv!ZOPIm8rZ(OCur#;;hONmCFOT%71v2 zr;V2Rte2%jgmSLRGY=y0rwD&Iz}M<9gnzVv73#3_9;kpcq7+5^*AF&~?MUzgx6p9L zx_5JN@HGUXk4y!&bXqZ5Q3I(2F;_NORpOBlF8E;;Qb@>O4dz+O{*M*qqKL|+idve= zM%~I*Q3OS>2910*6MI#0M)lxQ^@uV8SO>+R0{~ONQ7m7IfH*?{mZ-{}jG8YM)qtMr zVJifhs}|G?s^)|Jts`y~Lfl+c_EvC0uV~5j>R})25eKvsnY47v^;Dh-8F4UM6wnI= zJ7x!bM-ZE+gGv!FT0TUQADEX9Ji-JkdX5;%gLaDkkAmkEC5uYK{m2Hcu?AkE#)>D6 zPdpnzju^siGy#7P$S#gbB2`PKmGZe>!vi7!XJ-S?bp!u(laPv)!I`Gv6D@H!Ej_&^ z*6U^^G3@3ABBieJkvm`!1vTmc@AVi0P>s^uP0z+C-$gbVRyLU|H-Y?H@reKl(hv&( zC>9A%o@$h$ZIaU~&pvEtPJot4BL;dP0BMjm#Bq<05Wg3ML4a^&2&eME;zWSFIAYvs z$oLdxzF0@GXNPcHN2N8Q`nrP!3Ab`URL<%G(7K)69Uz&GlE@B#G@xRvqee`Z)m68= z_)|@@y=QOd)M4j$y{eCR()?uUNr=UnLr^z;GLahA|v0H8hFff)A~h+zUVJ?vxiY7>p>TTbzn0Tba_gb{W%65|Vki-=C zA=M83jN@McQ{!Iz6Wd-B`%u8)%EWKF$v^s&fILDBvW;yD{w#CMx@FAscycFd;$VE@ z1~q}sqB>EXq@XY})-p3sF)J0HcGsB3iJrzIp0t}HR?{0F${GjMP2Q?bZ`n)()uw1{ zr+A6KFJyuC@(6J?zOT_uC`8YQ^TX1_5Ei?Ym~8ms^h zde+b2uFvRG%)T~2XwtX8a)wn}_g_c!yOYeR-OkXf&*A&eRfc5NQdrx5eWwhaSFN6M zHkdDBvdY7D761V4ssa6#+4$>OU!J)DV!$h6K+vrvwnQ81J-Ul%1CjLE-7I))0L!GS zvgvANY(V4ocu|yNYKX75E7SBJzw>krFRM>S+k^7$z1LSk zIBQ^>)et>wseA2M$o|aL{vZxx|I(ZC7ct-6`4Y^EZgCfips!i*G+4q2kQN-nDu@%xVHd_2W00cBmU=FA)N2`piF&svaBDbqKNBBLT9)gKg(e6PvGu+oh;4e z`eVXrB*QsvR})S}lu2~PzF8$EW48rieZI3t53!z=&gADk==8@g4`8}#peWP~)d_4;}5?S&sahY6hI00&A8bAT@KH~QHZX1F{*n-ZpKSN^e!@O1mESH%T4VPBQQBO&b?^ zYEX5WTzlR5``79eL^$#guFwT%qy?%&w&PY>HSBg%?4G`)tw#O?@k7FVY43<6Yj1NN?=>mG1CZc1E*XRJqg{gJ9FcS6`McUIF@=?@J?6wxBHx=TTEPgX7^5r+}IMwFVm$Wjq@WJM=zD>kWDdOBN+^6lfO$__ECC#-WVV^_wuq&-( zS4tCr>+(2slA5@}a3F?VZ|GIq!y*9_~iDJF^BZE&KXV^6E{O|WY{&?{F z`U_~oFX8tdnXN1w8xO~`zbw&TJTV12t)^11Cw`-k52H^f(*lD6a=`-aa1Z7M@pDqD%%vNhsaKY z3yx?GeoHA)Ic+gMq3ScC4f*6z#H?0i>GVSMu<6eex;qc^Nw?E{Fu?egPVF;mAwI*2`dVGCxhl$cDsKG^iW&@YQNM&p2u{lv zlYJlb{Swyn48UTD??-y)fvZXV4)H!cdWf>Vyy9q}UH{-XWrRSE- z_W+e!V;|lEM)^;*oyMO0U1<^*c^tyeC37ODZed}Pq&Vxm5aPiVSFOVXmNO{-~htyS^`lDq@rYnt~#%OP8rW(Ti z%BrfK2)pa@ztBGgEc$na6NcNa_l-R?~7 z@9*#K?*5DZp|RfIe~EuLD=XLY^LI-X|0nbxW_lW{|6!&>|K9*0W@6%UYW#BID;5B} z8XLpXe^~eL@@o$k`a2!(x%~3wYN+J0r{@x@{I#}T)Ysn*2VVCDUw`(y=`y`(H@j(h zb=xF)TQ7tj9sSeQh2{PxCMK}r-`wCJ7X2F@9v&DN=FL3uf8E{PSog2Jy}h-y zwW+D8{=eYAyK2?DDyF+~(z{Z~-^!x?svs-_SY2IRQBm=)-G?bu!Ww{>BEU_N%3U#N zxiIrTnqN*%&P8VCc}mLP`1rd-nd6w)e>}i=`svuX+W?E-fkC&<`nP6p4xL?onVQ|{ zNZ-AbJk-%WP2xWH{h{h{XV}m}s{c znC@t)wrJ`9VF1ZtcQD8ugy0Sz&p=uli~c=-{`}dqXR@-g|GIyYl9J-$;v!i1Pgqz; zNJvmn@PE>O+}zy%Q~zUSW&JG@(!+xjHg`+VS~f>jr6n}ckOatxe{1@9=_vFP7;d*kk8o}Bf&3RxUFynMC7 z7v8$qtV^{{?cI&8tLnD`=fkzHovpur^n6IDQ45L*37z-e+4z5)9e{cE(Y z6`TZkP41+KAPJDMSbGr0_y~EY{U-af!?n_2Xw?7%PyXK!6Fg}>{{m@iD(1}8v z=NWq$DgY{!w(1R{M`J5_S{CcU|Aqe1w@vqkFokfi1mkl&Lm50+N;Wd!p1`7iU|3LI zpx_*KHYVJFmk;3FLT&yB{WF1yhUNFis|xL#K!8lA1^TZCHQDvwb|e?4@IwTRy>ZI` z0r(~N!^dn0+fQAjzO0tvn*LVSzIWKtaU?c>k@HT=&1wzp9plgUY%=43~8U7x~po z%ToF{Il>$g1Tf!CQ@21yuSN5r-cU{Q!&hUEGcC*i_&adt&1hNwYF;p_{MEAJdiX0> z#UIIC0}+o41b5v2YdaaW_$xn+Vb^Vp}v<_sr*_4R^;6HS*zr9nL_ulDP zPOt4*N=A3)28^zJ8Io5m?rwgpjqagy`+00Y%ji{U1%Fg^WWY`tRIAR7Kl@ny(KUJF zIMtuS-$TN?RgD_Vlfe$1uEobM3Gn!TCUPtikdN^Q7pqQOd z%fhM_2*oXn!9yW4tu?YvJh}ZpOCL(|w zUrDagWzVIqFD;zSzvsZYc6XN|C2MmBI8>;+YxK|~%*_#g9D-oxQveWR-SZ+$a)LmP zCQpHgzO9$xBVw4l%rS)8rGViHUl_xIe>iO%kYTh^4{|;oPJu>}(V+l5Y4uWI@~w}H zDvA*PGYK@$122ewiq}kNH_Z~Cq@e!T0dy*q;R+op4J|-mJS_mh!Z3g=>(ZfF9YT8; zdjQ`sgd5NU^wC#ln&1eQDVvV)f5RH6O4cvMCx;lN#tqKve?{}7K{l+J&&57y({@ln zxMmd{nmme|nGe03Zv`Oru4an3y~h6hZqwU%C=dL)gq7yuWg2y zzy%OKAPO+yr@-@=8Cc9;?Ig`QN7GKO@T4Unx^hK{Ofjxqn?=QiaLJg#ZDed}?}X!L zVJ=_jrQ|g+sjcE^t{5WylmCnw{H6_uxI_s=4)Du(0PwpnvabXn=z$ha4T>7oeR`e4 zpUl-*+%S`#Bvf&dEWS7(L02#0Dr)`a@t1sh&k@X|&y`cIqYk}(RxiY#{FUqYn|C7r zJRoJ^+}A%fddlh&^8$dn*H%X>nrk-c{=wxPWA$4_Q=#Isn$;$G&~$Kn54GxV8QQ6!1Q2YG$Qb^S06EHkpi;~9|Q_)hUOtaL?_5tApn4U zt4)S5Bk+0h+PBI>Tx&4}8Zt#xAXPK@p~P-ly=cm#5{KwRJu~H`jE({DY}%02yP@wv zqJNSgRKdch{xCf>iYZSUU);zM@^Z(I`mk*1sStANVi|Zqub{B9`SEWjpAxS+wivWCvEAOLR_n6-7?}8O zy`v|2!qs`v0KN3L8-V!za@d;k&nRBkVQ`J#{04y+9V-qxy2fjHbhUNkZ!c=L_T_~h zC1wz>XFL42$8ba(AWDejiKDq_^BD3LtniyJ*1K<5U_Ml_>8?F<=WC@J?f|6 zJooPrx)zO3msDovcS_M;y*2}zC^3w>XuS-}=SG>??qlvprm4;WChZ)HJgRrGiFjQp z3RDZN5_W%L4^_Lx#WKcp=B87}GVrk?v{P{Xq8)|TMCkfdZ`E4=g*CV z2X$skNL|f>oX^y*RFhaMqHRH!&U!%lyf@}*(-z=!>7qR2q*0v(7qiN2!>>PSN0;t5 zF^rOs6j-;Qb>9RYJ!!y^4nKfAo?blvmK;d8Zi$p{CS0O|Kwmx*06V5srsrwb&KN)4EcoqN7KtH}ppkI|>QnXie5zfuClP!0aPR01UP&x(f8_PD>)`s%Es*Pbt#ojS zV7aB5O~NRn5g$mZq5Y&`apAt2g-{toJZ-hQR1IO##%BgxA~2FZT+fq^U0e{JV>fSSJtvOiWE;8syEc z)M~d&M4De8gFT7x0J8FLo(I1H#}n?=!7|xAx`)hqc4ZIP$pzh@d`!;#Pks4Ke5FEt zuP6hw!2t<#z9b72?!|A>A?iQ=zD;G-4l>ooCjp-EeL(CzCv)egO>>nube(+ypjq%> z7Ybm}4vHT1b#@CFPqv(R;vtsi1)@O8)#Hk$;Nd?Ax;78eZFA1USDi`aB`&m7=I}C6 z^gwBm5Bwz(8p00fOyv~q*xG`f6zRWF>c6*mY`73)Y!O085lsD@oD$$0rS72Z9^~vE z<}e@pT*J{$!`2#;@6$UJ`er9o%8>w^;{R6BcjG)npDHx$BD`HAlqe+#8AchW=>IA$ zLTWv*6K!i#7GakboF^QKTNozzAv9|}Ovy1qG%e6cko8) zJ7KrIfY8H@pzb~8?^I-#*dk(CxX4g=?r!+#MYL;g)YwzYjy~=ws)r(c4_URMtG>h# zI^vA@!K0>JYA-_Rhok@E$6W1EZ@4ohf&rlk90`x(ST{K0Wa9{Qn3Ie+A8y6G-;TpK zBmkd-MoOZ`Q^VHUVre*Ew`jk`470u%WA7X<)n)M3_4;8|&6r`=>ejgSHN z5bbbV8AGkle&JuV!{AR-f=1%0smXr%5i;e$J(v)}Xt=5RN1o7Bgou{MVyL7B&hapT zw068_d-Sk&T7eQdw=2LC2^VGZ1IoZCOc5~k``GW2Jasq@bvO`*{|)_XSITT5{4exx zKeNvxYqUMISZS`BWMCBoTx=i&m!PIZPRds{w!@6S%kzCd!n1YMEO@nAsqb zvrd@9M^m^eQYfgKE%dQ)I=xWzDoeZ~OF7Tj08uElR5*HBxNVuZOI@J4MD~0KT9cOn z=*dX1OkH}NZf%+zzo+9vn3l5`vRPKd5P{u+D8V%}nL-dnhT{VrL2)|8sh7#QiwVdj zA8~%1VWwCD3Y&mMq}f%e;h%g1H!#B+$XyTEP6=kk1fIc2r#e&=ms!MqsIZmF&(3VM z@U}AY>nP`Eepkx}JFkOH_?5{mLVhv9Taaq8qNQ&|%DqM^_c^EJli?Wo1-? zr(@3)c;l8LKVL=GRUjmoiY`e@okYEjMqL9cDuYKVGlkQeD`dYf#q}yjOH3CJWt2bL zt6Ix=|5elwBV5&^T+??@@fZikW0b%%qMTwee_Xlb2Uo^aNA$Ods_fU*nwHqEF4>Z0 z@bXp7*pk<}Xf3TyEuycsE~wV6y!JP4d_xD(!f+{&HUn&3LLgSNr(9ZhVFD3DJVI6p z?$mL6#8PqWjs$rPjQjX4YF3(!+D;)`uH@5iESLI(0CA5BR}bdL^+| zlDDmVv|1XT&8~V#-~HC-haM$-#3~hSoZPJnCH00XSobOV4l zOU* z@fui#CO%b%RWb1bWx$gt*sm!lk`G~vQ71;%!CIz(pm^{C622}?us+b<>=_od+!@bh z97|hgELK_C*(p-mVba%un-7nH0IJX*#AU!6dBhftpcXV(pbm^uCj$23`~(m^%>y;Z z!OBQL!(t#KCgKGq1V0nJJPwrE1D6d)gkN`$Q+&P}tM9n(JM|>vMY?$*)3rM@YWWZu zelYP~98?|nyAa~d8L3eczc?Dsm5P52cxaD;mpMXK_z9wyYg0BG(K_-F|CIYc~{ACoc ztv+xoPaaqgTE}{VC}I;_fJNRvp5P4MQxuvIgrhVmjJQ}NkN7m4yD+S~(ud3(Fybcb zOooyZj-*u~?COZmridH4=?(z6K$0&ENaFE28X6>VgEZJwooL06mjeJRLx9Z@#1jbi z)~qp1-5BsVBkX5)kA6^}*Lcjz!0pn23HQj?EONJhP{FBxP(gJTtn4?TE|iuB!wwHm z>hJ-4ka>0Ac+O#v#_$`}$uqiuztE1@tYYTu&;0!T7YO`<$PV-<8GRjyw+l4SL?jmX zeinlurjsFUJQXAxG1SNpLwpkS#D;5!852@`mn54K0zSLO#|_v*vf7*JI+ zc_HC&X5Hd#(DYaXP;5P7cr$6YE-d?pe1`~N!$-Vw4UOkSc={0^*TLHSK)adUhs)ic zv*vZ%=6SOw)g?anL&-G#;GaN&Y`dQZK z+0OB}*aEjh)r;U201g`b%xURtPj^O}W2uNz^rEu8elgOr>;AuCA)^IyRSg$t<7<^s*S;3m#-Fxjkd2P32?Rs_1i-&BcnJCD6 zdCDO1LFA9#s?~#*hAY*zUhffF>u=h1lc!zZ=A%)gWk1M|e&idVP|*mp56~8gA9n^n z!YWZz-F+OAWQ5Bow`gRq| z>K<*x{JP3HzzcyA)g5i+w7mAAPeDQ>rGEp-j(Vbh6V)Cj!T=x#*La76>zut|9!5E>ZLx2~IB(s)Ct1-v4tvI@>6ZO=5x*;$$xBYRI z0b?u@nuz!-cyh+ia8CSk|DYOA^tpjJ-W)Q6|Jwm zc7tENU-JP;W6x8gavxpF+W&a_o{~)+dcu3-?@N~JK)i|ZBznq+m`0Jm#yw&E-Nbh^ zFY>aTFRpad?xuR;x>@+|Ck=Fj-|db!*|;=zgb!|)hN*uU1RO&Kq~QQ4!!rWu0jYZs z6o(>}#>TUVdpry-1jifCW9Z4uPN`n8$;Yv(WjyqFWjd6AL$xjkHryVMgr|(&k_LEMR%F-1~uE%&u5S z(FG;r9OKI))U%i;eQNQoSS|N?w(gVt$^5sUL+HgmV5}FLZ9kWI>;1KxZuh{XWM{%9 zy?Ff?pZ=n~JlV>7-->KYvozk9en9Q{#^BoZXtnFLloHc?Q((pt8sRdL@=OD>(m8~y zaOZV(_7D2^9^-R&dyB#6lg7bktCI%7pQ%fWx%LjF;xY#D_2Kh}Pl#poG@{u!qi{<6 zpi;Q}&qy5m9N69t?sFDAxl3m*7#BKJ71=RMa(upH)kGpf=ZtHoz~E8H6X}W0-x&Jg zC3qslCLhQU(%HB*qYSkFw-Z0Sa7suO2HB17x)AM)P2s?$~^J{ zUsdmQl2=DnNrM^XgjY`|UXd;RnaT@!rOCn=MZFWCWnSDo7f;$;cF%2!iU5xokj6~T zuj|fAXX#pSI`bsiK&$XTl!r*So~{p7Y;5v)R%idTs!mIv@SZfK@j+cPwo@Xprx&s2 z8H)%mGAzw;P;a*?5NKw<_rt3-F{Q$%)M*dDy}=BgA4{~)OgW5|ViaC*l) z(ro$D#n-6K72!#-cdyKF)y}@27rY@eo7E?c;tvT5dmo}R8XjG7u^6*@^|m6baEY1= z@8<BsFH+m-M}5zq%_yAN%BP6_lnu93CJ|>DRde zm~tl0gyGGBj9@;xiqHz^~faT*WV@+`P42TTZT6-Z&U50 zOaVM9Y{N zL3XH!a+=3uwun!L_;`E0{WnY&a^JUd05rIp_mj3qJ1u#>9|D;u4& z;}{YF0cIWvrjHv_TCPk(GFrmkX<^7RT7#7NiiO8DUCAERd{Ow36h0!7(3ti9)EI)J zQ^UnpY&#cZPE~(NZu=@eQ-lur9^4bgEYr*Mm5xvvbfs$l)me*#DvETYU0qf_k@f5} zRm7V`JziaqjiPvXtuLG;{A4;_`lr6=cKd|WBHR}$Z<#{ZK@ui(lJn)TOaU$c5P>Rr zVxsm{`9vvPmJ*6umelzu;$9WRSQIm_TIxDgd@ufXQYdN7r64#;6vTGMqSeJElT6Ww z^G3;89?v=?hDNGNtEkE>xL<=Xo$rw+_LYZIofGSK%# zXgCzUWlyU%u^r$G-Ja`+%I6vQc({N9Qu=-1=ZQZlSgK;6Y#)0P#?f$Gx@u=`I^eMQ zVOuZd{CQDvtYEEb`?WzU`Fz{;D)NSd1>%t>N7smyaVfq(T>5psS965-YfGiF7e!;A zDWNo_O~uO1dGYf1CDQp6(cT(cYuN zRmk zT5A)%?uqwaCS?n&Hge1Kt)h6B?Yy#TWlzS#7dJLlmTl=|PqS>tDoxZS@msT5r*nk2 zRpJl5hAHhA_6x-jY79S*wVL%@sl#{fu6r;)H zyLhJh7oTW(kBCw~p+0aPwgg!);iUqTme#E;>%Nq+Z!pakQHA1AF)OcZNY(=D(9=Os)d!wPJn(3bLf~TG&kxQ9VXDl5 z!cFVR^a~rr0@@&9D?fY_ua(ii zpOc6(-t~yrcnZ0BMo27#;I~Qs6$>L}3Vk9FMo$om-9fWg002dw`bK0YKI6>PV4Nb({}zN#JJ$aO@7} z6ajJF|Haf@ct!Pw@4}y97-s09yKCs7ySp1{h7^zn5tJAhV(5|-6(mGTR9cV@0i_$1 zR9d=3=J0*b`#b0S0ekJW_ImbOdtc9U-5)$_Ru!4>456Po*^K*p&;p^u?C z2Hdz5@lfE>a#xVZjNYgtNTf6Xunq9?$HNnc z>Kj9F5Kz2~1O))fWIh2sj*5b{U&ukP_Bw9l@}xj&(iFX-W#W?Ijg|hm0`!V$`SNK= zDs<{y727B#L_bpto;8Muv@+hKB?Y~T8|=Y=i-D*B0Fp>DGyo09MVZaxt!#Akn{``G zFgdQi)G7L)yWCy(sn04Xi3}juX4UK7&}5QAFzuq@lOOHSs>WEEU^xV2$^bvn1_D?C z-Wl--7~0D}zB?OY-UaM4YfnVV@3g$ySJC7((;VMWiF6%!Ta0^=nd50U0NPi1r`#c~ z-TfT_mCVO0eikn(jiIauV?(teR#r*?r0iR?tW#`X5M5LF^A8cXosj}xqr3??SV;t} znv5Cc^1^kb!ledGaPZ%-W(Fg&>=Xg9GErrTKxm;O0+rj>myrE6=0-cniOnTcvFN$* zOQNpI{jb?&`05#w0$mbb;!=-_UQdd=*$o`tiy3~mtdlLES4bOeyby;wG#n$YR(D%E z$yVwFYpL(6{jmA9U0m;7U!pdWg|?nQUtKYZQ6Y^%(}t|9>XY6`&qxQS-k0Ff7x_5r zNZc_F-P&oX7IU5{AeV{F=;yNzqZYhSs|4G61#~FN5}6QMA7=up*&zHxU!&P9jt_+v z+5<+r1a$jkhimy>V#%Oi3~%+n+%UVd;xYlycB~K*1oQzsLBdMQi{DdDpC@aCS55zrL@=IK?hc z8;ou?|LEhN@_b7zFjk*cGKfi`!jDF?CK!eq{H-y(Arge98W+P+4qXY3t1*XXhOfg% z&_v^t9{_#VJvd-~B68A``#`5265A4QmZ3y@O!QkjYr`swJ~fr0-(p{ zj;Dl(W(JzFG!ipum`=A$aFZELWvWwf@e#>pQaYK?#7)GaYA-RQ_{WpN;3)*vln9p@ zt|xB2ODt9hJ|*EcB{@S%u+S1OJ8B~%?pUwS>sAT5$wG)g!EVNoZ#`riDRhrhxeO*b zB&HcPrq#D5RNc%q9#3y&033#l*&8P`BFwq_r}Y(5xxpO0`ojq#5-!RT_Y>ZK+CJA* zfu8q)&@IuI;l}trf&^Tm){VoiM`*!$&fOY|Pk+s2h-VV;bf1lo+Le0WLNXw> z%F#QUmc|X=M{f<2tpG&-z)C|n|JoirBOWWjK&=QC0~ip&Grkiw9Q273zy7ri+-zixmobX-9fa`Dn$f=*0CI?C{4PqC|?L zSl^5UYh$#^YJ5lvLyq7Z4q01M-6g#;OVQgoOl3^YK1c>RQaCfeHaVKn1+p7Y@Scwa zOJL~6AuH^5HU%SX^2=hnc1>~m`SvTxv_R)Bh!)27u3@pU-{$Y+VrnSl0V^7d8Aow2 zEF)8CtK{s}bXS&q>>GWSlAtKvt^|jn7{yh?k&eYZqWK)CEt<*RCP02nz+rmD0qMMu zXK%CA=#W{j>*kN6ybW5cUD>j*gGnSt`Wv9((UDduAGSzV9~JxoJFb=ECv1EhF1LNr zv5>h9tXGTO-iop2LJq%F%sEQ90i!636K;urT00@I25&YL9Iq_w^BOVuUE{ilXvJ+1 zh5u^5PcQU`jo~)Lcr}*pFxIvUj|dNmNfaT8XCuY4I{oJaGlXh)L7ZuULfhy_`?Z0W zme<7i0We4u90I3K@bkdCqFf~M&9Ng_WR7HGxf_E-I&Yjg-eu z*(f|R*aJb|9M2PHLYximx*x2DKVtoXt^TpV?HJCwF-g1+QfVW%bmLFjHV#YD#Gp24 zWmJq00Z_Tu<*n;lufm?OWND{q-=x-rhaCX%bjmVnf5106pyQSsoocsKW7ZtiaX5+|+F*s2PUvGu^v zmaQ88U)1hv`kPQVZI;P(^w3K?$wT*2_04b7uVumNp09qz)Prre6YMY#ZM(n$&;i|n zEqiXqtpgVTYSCr{AnV~6{KMT(@mDq=It3R+KIBw7?uh+EJHzGw`w1Sv3I&cT2B*Y> zA6((a=OTQ5Y#>lb^O)q-gU-fVt7XSr5 zMnIm@db2G5KJoF&5*i98eygsxA(8gT!QHzo+AA4_XQ_;_G@cNM+|H9(==5dWMM9VW zDE)CfoFTL??Oxk~r9QRje40;ku~i<~W`V>n?7-|s&A0s|1n6l#o(U|@vlyaFy)vGb z4<(3)vK~xU6ozRdY@|i0#vk=ld$NY?XC5A4igDIMzZlgm4j=x$%JIwwfNZwoAECfn z3wwvWOTXP2cgOJzjia9+(6f38bCI5l6%Q72#gkZp^EsLz%u?%$PwO3WG;;DEozHa$ z!|u?3c3=0u*zhk>A20so&mJBsVu1cX9J;9aG0QHTe)eCy+bR<8O$lQtSiYtA^6*u9 zwE#5zs7ECl;qhCv3wVcjbjP_{l8doT6$Q|4$1uAc8lId|~V1XF&V_lH>7g z0cRMaHT z15scD9i^Tu|MN+%jK)fZf)+Tex6%qKRB)gDJS$=KHG#)Hsl+p{h<}oy9P!=vhhb>k zlYu2g3=z`tQsFw#C`ijTNU$Ubw&0Y~`J^f=&O{kw0)4zcd-Um7NQoAOn53=f&zRi9 z$N8@xN%&pG8gErPZiT)L%@6y?K6uR&0lAdK&|{Q}=PrC%o|3Qwl{GP69nQd7rxkhE zZ?!P)@y{Ms+=#W2cn#n17$l_O0#uC?A}>$MA3hD@2N=%oS~!M2fB4Mx(GiW!y}GAk zR1C4Cja5N{!;Ww}rNX+NoY$SYtua0{PP=xAIxpyi(tDsCoi;ZWIl5Vi2DNl!$3b2m z2_eOJ3PTnBcjwqHo=f6F{qUhcH0%j3>A&Tlx2~NS@=&~}Z3tboq{s*l}rOvmJJCNBn*sk*BCB+~u z9`ra@4oZRi*}xLH2Y~``Apbx5hey?AQfyp&KYoRo;OxxLq9+&$=*qr-7V=5#T3M9a zYp)Zs_#S-p-ubv0gB&Psukk$P{$3>ed^OiTItU7nOt-YLJsX&DLTV@m%^)E zG5@eX{@G6NuSR1i2<=Aa1DwIBhihWyFijR&I$X71%NZg)-vQ%%n*d*fh9*c*>N+hN zP-{~Rp?>9K%SGwZO}%`0@K@^Sb>k`X-M(!waubz<?M*-UBO-v5Bvu;Q$@KKDB zFeRm{21_6(%Kk|+8*Q!!+14sBfrPeUP?9v|?V<`RN>xv&tZbYi>SpBvBa+?nANofg zPp*RYHZxLKBswuib=q&wWSCNYea>NdZETE(Is>Y?QZ0sXn$g__ZRNb7EQ`U)Dnr#@ zr3x-e(~`GYBe)Aat31toUJeBfGx!y=8}aCa!-}4p{gPqGQL>08Rm_4yQI>W(T5H8m zxvStB^nu&a3AiiAq)It=8>C7QM#?m}Kal5FVHm!$BUMS^Q@$$P8Sd}tAY%5km*nTy zQ#B2T_%^k29Vq=`DrdYQcN3wcz1nmtx$!4>kLy97EW-Zv6r|=PZ=5TvsqPRdXeE z59Q9#;bf04ibVAzH80_}8jh}EzK<0e?<`MfWSObOpjK1 zST`g(mc}>aD<<0wTCDcWXPG*}Kft5?j_)onM{>>;(esU{r@KF3qk{r}fKshz`(5=9 z(_T|Y2T6bH4bH#1rp6Z-=hy$da7sl7@B9`8uU&|Fc*3hLcctx}Q{2AFVQ*C$6>dBr zL@mD8f8O`LnkO97$oq_gZ$9Yv2SgvqdW5sI>FHmqrj*4tV0WU3{WmuE%Sh>Z?=dvUN>P8PFQ>gt8zxEvNj2V|8?AVt=v(I(TH=iA!w2l5sh6vI<)#5>!?VQ zbm|+%LV$*xWJreCeH$9v(yQzoT^@x1`JfqAak(&TOyr3PvaQO(N5{#Df-n+pfAZ(- zm|iBK%tVQ5))RRvay?o#GShbU39nNk1(-VN7@&)_Jvu`&1BX;Ng-y)3Sd(nt-`+qx zi}basTzTIyH{6U4Lih$H=j}%LoMDM!%WAO9IK!E`k6mRKNo3FZF>}3&SYaN5q8|kT zL@LWvzr!=EmSZ@9=FY$mkbHo8%p-^iib<40!1%`S`46ng>t2$bAwr^FT48@qArlJ* z|NI!%imQPit3fF{lNibG$6Vinf3YTxSV6xyR9Pqqgn#4TVDc|Hi% zqZ@Cv9tcJ>l#oQg)j9Yk5>2N|@WDVl(W;5mz=l%he{gNJVG~#vu#{baSJ#ZdG^^0O zT*!cz9S{f2aA#8`uY?;0RZS&w2bakG<2B}8oGQNGkRWFA(y#@L6mDa*6bV*jc}>AC zSL;e99lI&<6d<$t9_n%rpbka{MtAE%j7QdwCBjDIOV>Bn`bO~EZSc*tPBzwsbnrWz zR?T&sG`^4g$8X04gzJq;LP>;GYM99RL$F_JA~9~`Ay2>r?_f{$!feQ7BvscgW+w| zNP)VoZjh_O5Y(dR1Yz~!7qByT)fntxR^Us1`}NfIuyQ03k`mA%q$o0Zgh+od-OKS} zs9#MQfQPs(r9dKq5Mz^g>KY)!Duz;3(euTvC|i$Vcp3At$s2 z->DaeQF`A=Ii9>oYJzr9J_MGGEW@q2!c!RTCV&ye5{>z5$rXMeix~$nAF^sQx0|H< zOq;Q7Xt)AVPAR`wRxJ5!b^Nmi0MC zwO)X?PiOG!)I^U;2)T%)Nyv0n^W|<0V5c_%Sw4xA`M<;~nbZZnfn6lt$MJMEK*oQs8vFW!o)=Px9^dP-KUA}_&;y)TG07;5}f4!rH!bL zcj*u;B2U?njZoE}0RX4hmaud3pnTn|-z`1W=3f@$WbnKoD%7r_Kp@aMt8679Z9!wiD&qjdffuvfQmj=wTl8|PEvu;&p zD{GddPAT%SzX>|7OflgrnEJ=tc&#oq3`iG)Ix`gwh53cto$^B>jtqrvzr0f>!c&Rv zvf1us^!Rr6_5n8S1UIZjw_>nlmkL*%y@w8(^qj-VH zFsR(9@r?MK{Q11L?NrfEn*sn|Un7kgFO@)brmhl`y7lo#b&ozdr=-Rb^1`GE4BJ${ z1o?y&`mnHfy5rwnKeO|!nBVe9;fcsfwg$snJ>aGb$InH4Pi8thPl>&`Z&qS65aQE^(uPpD9!iZ3#e zTP15-1;x7FCNvQyv=hir(u55F6vSLj+#8_ck0WbEh0}*-1t^n<6T-WCN$SZ2S9_F= z(Ze|mfL9N0M@cCS+4tm~K|khntxBlL=W%_VqXX8y2&%xC)TlV~DZ;Iz;)%I94MW=4L{kCkyTw-*#GXg1Y_b40yQStqQj~=pLM6#2nN&KZYKpiLi?I^ic#?q| zJWoqCELk;wydW3Q7M+fcv5)SS>E_|HlS^CG$wfYCjFs!omY>L0Sfg-J=cMK}wNT(R z)J*4M{+YG&Kr@gXe&_leTwcW%Eo2qP2DhT{&ZZ_R*SWA6t$%Y_>#FB%@gRcA{A&?- zIt#X0_F!_rkh}l>71bcvy1%uxDlHjfxhP{#j7AzGW3-thlX-=cuJ2d5LIMNl37PV# z2fsEQ+WM>rG_CJkZJw?>@#VvwPb#qX#8BC>r~|9tx!5;3U#4n0Wc595#M01q)1=I- zP#Rk#|Kl>mbJrtsM^d_La#v7){Dl(aE|%|!VPksW!Qm!ZWN*p+(X~Q*h&FYBHZ6jC zh07))!`(A}t9@l0bW>)$_)Amrp{(NX90OHv(fN&UDs+aw%+@R1bh+G3w{+EQ?2HS` z@p)FdhYso9iWhS06>}piD>T};!NWW#e9K}){`ooZV&PZF8_p*o4>8Bw8ZArrW53*I zUIJbjI-~%&{4)rRae!5CSL%Q3w)}SN;;|v;3Kn`9uV^i?*2{^Y^$F~bJLa*!`@Im# z^D8G-db&t!c{zHPN$nSy3z|u@4&u_@hOqGfc;9{(`5mwMFoUE#SP^S&p{$k2H@}hT z1ipA^zRP`CP++k7^2hPZpZ)L^gB)QZfJ2M2$Y`%9luUfLa>BS$*Q(MH=^;7!@btq@ zBpZ&Kx@uP8`Z=&X`&UKOo9!n_W=F)1$8K&bDkyyfy@Non(mY6U9Jjy_o_>Q{_$#iE z-916_?F;vU8Zsc7ScOLWdy&`g#9uqvsynaN)p3N7P2yD#OKkHTbQCc=Z-!F~a{Efx zHOhS7yr5@((NkCxK!;9c(^=ek8_!osP_3()sVYm~M+Dlupees&;tKzx# zSOxB61bSqu@S&Zsd^}Aq!y3um%l{|0=m$el@0X# z$Wbr*X|G3yRn|9qC|+hXEfX5QyW*8g>krP@9b4$G>37W;hq5Iz==~gzu5au69~{;z&tnI_ z^K{j@&)?+1tMqAAtzTHesv+R2S-G08?-cN1^4Vty;hu%h#)=hA8Vhq`LN<=EmS_LG_Ix;9AneQ_U9mqf4GzVoW&iC@1N6L z9XqkJ>8TLqbc+?-n($>CuBaSV6&g{T{9To8U^8Q^4c*$z+&d$;uCu&6 zLe@RD+{do1Zc=i8Qu4r8@!*|R9mE=?58pMK@5%vi{&`yWhx;w)4!(+4*OcWaB|4v= z+mkI==PK&AwBE0nPKOBvbSo|p+^t~O{n7rH0TjfZ+G<&n@1_|s;l;ow$STVRpI>#{(o=2 zVnd95we^kiCzQ5PB!B%52;51{Hc2TCVGI?Wd@3+}(78;(gy_+lpa{|18VV!-E#D8a z_^8kEql&j`{_Y=${%UML?FaBX;%_jV;&+>H*AcJ?5WYX&tE&Mi9qq^KQ9cO{zV$ouRiUm_ zuuZju?b5m0B*HE^7SIAyS`M~H6G~NY8s=eR9cY9dvwf+_#f52uV^clezIuErdTzu2 zn25hg?U$wqk(!HA9~ZXwm4T$?qccN)aWmH@d_PH`5-qs^RHR76TFoKkg3(4UkfZtJ zR`#*{Qb;L&mkb@qv9b?jmuNi^VtDGWgsr{KeSd93_c(I%xymmj!xPWaCePQB@_rwK zr07$$rSP(2?XbQ4$V5!oR&+ocC(1US2b9d zl-*ZitI&{*%Mi#PrN7<@pieZo6T&EL^*X)X-`uM(7HR(1q0{f0)ErRgxo>JiJvq~P zsdE?hYDdQ2q0v!~<8!mv`2FWAKPWR?If(@oD2Zpwajvvnk;8G}c3*kSuTv?sB0GOa zq9yX)dvXj-KQ9qW3~EXABaPu`l@pbE_N*K{o)GMab4ZQLW~U=IbY0{U`qFXxXQa(Jl=ub}`srhJ!FDc$ursnf(&pR#oD2>!F9m_}# zXwA@~75y7rSxTC_G+a;dm%~i5N^1rOe#72<1GGz&qI^~Z;(IyQM*340|F`T|oRoO<+xxd=Wa^s$I zUsSr+cY2Jnr4Xdyq&c5wR?qjlL{&XvB)dTJ=4uQ@H#P5<%v-Ock&umaZ;GS+e;1wk@tAnG{>15KF(}m%Oq^Vg0R1+>Q}YoC~SU4RN9g&ZMNEjNW~( zxYzt;uTyb<@XLPl7n-hUno-5W-(L=!?<&w9WYc#Cf4=Odv-RM29)F5FkjmR}d9WiK z^+=-gl!59@j`E2~A8o9J#ZRLM-&k9 ziXY$cBVWMv4b`o>A&XE9+s4*kFvxZ!Pox^mFL{stJ(7x|Rw(rLXcD|DHxwM^1kpR| z)=qtRE;(G$c#r=1nCUCJjHG}+*S`o2*ci;@f%yORGzW;@Meo3Ua&)P%=5SQ0a;rX( zUqmd8(yQ>W)8F^?d`DbEvhzP{gEWpBbYHaA7e428mX8&2p8(aG1fofG!-1Q8Eqw_sePJd*&JV zg;wT8iT#MLHQzviru;5hWN5mQQK_{Qvu2S;>i{Ce-3~4hHQ=c1rBrB(MiIn!)KHJ= zNs6h-RgB&AgwBzQd(ts|#QQ{FVa!x=uB~f_ z*9^m(WW`PCp2bVq+LHwewJn5wR*U{lPQbqPAf08D{o%~hV+GIo>Dg_pb{1Iz8{5xl zd`pq}^%lF!9*@D5hROIXesUIj)TX3@;7xHaK4ywvN+XT|S7tNF$g3HdL!wAGYizpl zb|lS?)?Ho4yl%mL)AWa+Q0D2kfag8zMn3(M{*lY8nesyW zeP2o5-!;9{9F6|ch#g0=gn;P1PZN?}d&?oY^fpID%%a;ZBh?$s;V=&xFoN6Xu*bp~7wi9b5@Z24q@JU{;}4JrwRG39l>THXP^C1vp` zH)?B#112B>^J9?re}7yI#Y!(Fj`9B4O9K^W(g$H!xs!&d$QkohUaX}_o<3tphlVO) zQ%UeU@~yINp1k_v1B{y!L(Yu9W$UHWj$V^vfJk5{S?4()jL)La}cd*tVhBDLVKbPgPfOTAsstXnZ~5hj-r4xIj>SD~L$VvQ&U&Num7oCag6k zhHh<$pOaf7k=xmsqWN6C&4i8a!es16{WwHfStog+baEQ&Y}JBb7D{p1Tx8s^q5#@) zNbE^R8?de>li8~RGS4<&u!cRCy{L%{Ri{6V?IH|6i-AU|GXcPuLBV1F%#~~BK(C<| z<4993NEg~mdE)B}TJ{HKt6L%_4I^(-0@a>~b6uQmH)yS@(OJOQej@tgsLB0vll05> z$>)c_Ss$W@C<$m+GwE#+tZ>5dGEDHXTG00?icccbOJgP29L;ifznbu;vJQ6VC84uNbjglS=k&1aE^-QU35VhLp(rI*VgOfHQ zYX`TAg=f6mk3*2vvaxWcD=Vquk-=Ad^Xyb|P7Oeo6$KA5!@`?z3AnaJhTV&yv3N2( zI<4&8thDibq58wBMFxQb*F^ya#gDaW#J~~L(uBpzFZ5@gloj_Q2+{MsLvj6Xkh_tjTXM zqgpl8JO%iRmu~k+xszZw^nq%7PpD>m}@$8OFXqLlF6c0=>zZ7YhZUyv3ScZJFpp*y`KQZ%$EkJ{0miT4NVWCvQeahM7%f zs+8~olj4dNe|>N6Z8`2!sxrf|3`b*`w~%0{tZMwjmQto~86<#76k+fX2LtuN|ITGo zaNPvsOL1&U=*7jg2?n6^<=~>7LT`GRmmzGgX|~M6<)xL$4|`cqFRaDx!`OJk#5bO5 zcmW=zvU2tP4DR)K{?joWj7W%pZ!y}Y3@uko8%O8fl^BUw`k&O5N&NG0J0+<0PK1OQ zzl(gJn69b0+NaR}uk;W1A8!*laVgd<6b)bpOq2FQs->+f;!(c7(ttDx^-@``uV@7r z03b4-2Ei6b>jVM`)5h6pnBK+5p|bNeHYN4!ywL=e812^*9AH!)T z*$Kont{GKEjj({`QIiATkhxp0T8AV7b0FZ=i~Fo~_5WtA(5E^T(FAGFOWOdnagrZD z=Ioivr+IE`d5w2FlGG+*96AN(-PkYIGa`cBFDJ+`z;We=qxcm{*KJ$O&lY$JzceiL zN|M@5`<{b2eLeIYE}T~)luut%*}Y5|B;|jzy*;crG+m7EJW8koDD!)|PuMZuBT4i< ztrwKakr!AB3SlLAvP$pjv@Tyv|HcWV9YZm$k`H5LP7x$tccRdZq4qD~s08lX#hox} z14LCM+}R9KJfIKb71G9y^N3qz|99#L<-XMAb&iIvxY5}$LL-A2yNq1q_@S4}pF?8? zcL3Pc1QJlpY{Lc#R;FGq;e*vvx{`sZ2?3)>7Fi%fU1hxpk!FfyG<9LYepfd17|G|G zAa8{6cKJ#5k@}k-DVTaX16-kX(ALUw3dga3=44c6nH;ONRMjqym~yam3~@#D+^dqW z09NWUVfwTKhW%)Ue8FAX523h#rn_ir$u|}#Et+~?`rkX`gj^IK0w{ia*^xvSRsxg} z?inXTloR7a+lP!6dnGtop>K>?B8e?MMw)0v-!Pu6wD>1-nyw6yDemtM0Aj1~JUGTO zz>YAc-`}~cP26lu4a0RLOxKP=x7yY{xpq9^*2L_OIT&`_8KztcGuB4dLAh{!9)ntr zM1A5V*xfHbDh<&D6zj{oHR}1D2Qfpm;z_*UzVaHZ)0c{JM?JE^8k4ecswft*z6jrc z9x}<;@s;P{`@`YMXl`8zSAItUZ5lj)P^ONM=a_L<;MsoQn7gUMDCxh+-mQ9g9FEwb z%@NO(Ns6;Sy6S`bcO(nKkKnjm@F%&bl8)#e315&J-$p#&H#LGAOwZiA6rP&;VW^1Fy!X77wvppS7>?v1gwmwE zU)`6Xx47i|v_=Cscl=!yVp$%aIO-^*{HHvFv*op6RqGradc@+1W(cQUX~HQ*qfhR; zr>e>Ts%iM6MQz#N6lv7c;=E$*A8UG=C=`1TinIJYa_(x_&Q#@s5oIkg8AARi1Wq;I z@f3mHs=N)dc{^MOaJf!Fv2UdWhj^4Z+^8l|^#F5*kx$BcpVXsGW$1XoPh;>_vLCSr z1Ci4hzB9!~97=KSO8up3KYN$gkuNIY+HV83Qz>Og&6z07;cnuVxT`a!XgXaYA9m&J zO)*^w4_(ja&qW(L>Zc)!#|k$eNj3LAb%{&$pY`x%OM8n+EyKQ!bK}jkNt~$=iT>_u zNH!E3G8Crl9ttwcmtQ&qO(~X5xEmx z1e6d)gL>*?y=F5Y>EszJH8bmpDRtsc);{jU>ueH+S)o1s?(Yl_!x^dL5{VoryXLTaaTyz?Ju$kxPW7*mUAr^!c7AlA2!CT%F7oSC` zMuaZ3%ynG8p{p9Y^w>sy28~=hKYE;Bc=THOdpZ-uxJV-&D127)$&2y%L>;&m5&*)) zq3{CZ&V03+w6k-pGn;~}V*UM;_z1J+ss~5$L>0J+*U# zq`)5wDP$OL7j>lBHRo*KWRi6n*0O+8x|m6Njjf|u2%Sd(EF*ZuXVtrryTO|G*!ppA za75w-ip_wvC^6M|G5B8X6TmNwqLX_Y#@>3WJ>b&O)an$n@S01i zNT(^#VkV7-HoZCzuo?W)iEGLO$h5!4=;4GH-u&v=EH};^_ieG_8$S8)+3>K17x+{~ z&9iShB@3eq?x=H1fL+nT(dAp4p2SjKr>!(SYS8ee04=EqwZgK9u&{!>B4L^eAghB* zZe_1}#pjHQH4woK+%F!bBwB7BMqeD!_Q-@@D#n^Op6*Fz8%Nr8^+H&ImT#2W?khJ@ zMd$_%W)+GfnOnJtg2+~4^`^r9Sk(Xl_dLLRD)o0xD-)=2F zwr#GXqD>-`jikEKxV}-pZPNrYh^@I4V!H9^IpljAss_vRJ}j1bx>RSssisM-*_nxP zX!~fe`SF-Cd;)~;O+=1xvpY8{d-Au6OrqLovBAi;+-RMm4#+&aM(qo5ylo;kx~_Ek ztm69DUCdT)ikOU@3#BemO7lXWG^BVglMbo^>0+fBV)KqHZ{-)MDYaFrco9|oSM#S@ zP6*IgN2KBNXZ@82od@&)*dE=~i^d(Qmu$ry!kZmqg-zc!9{fWRwuCinEZJ!PZH{|U z9WB=~Bf#ac%EB$wh2{7h2|<<+x4#G9{vDNlhoJAAD8&x}vP7!94U+6MJO9jNt17?B zY7hembfVAy-1mN_QLCs=X<63j_M>T$u^t}*?V7KC{R6k6f%9jbp6OOr8=Q7dj6`kv z(@U*xcx~uqX&7Vw#?n`sJQADbirT+lDP}*H*je~64(h~Ejk4jLxQ)!o`FG08^ehhz z$`5?qfL`^I>KcCN{y`ZwaClOa^h{t{S*?OlgE+1-1YNs=%9BHABv zkHeOT?TdxK{Is~<*q8%1rQzBY6STK)@Qkc}Ztlre4Q6nM)}!8UuM*gJlnx4R{du`0 z_+?thx(2-ZR=|mjIyy4I!6*1jvB_U}_z#=amy2;z5KKHxWx@KT!q4-L;uo(fwUh}+ zN;bk(cB!I+u+=|yoxXfbDw0V=x^JLF}r zb_JE1>mo&|Uc;LlOo~>M0y`-C(NJ%1;X#Kjt&XK@hK+w69dDI)=QwH0BFUCrFGR{N z9tExBuwTZN;a@Ssnoy(6zZO45TxCaY>B)XWHXk1s;<7rrb4QW=vbgc=Jbbcu__`x8 z4M2zh8^@hG0jxs5-kkw)P+k9n{^3Xykjvhqf6m=;#4J@;Z&lw6q%z8JpB;^%2QxXb zdjB8#r=ylky(1d(uAD7L{Lx~2qS!;j4ED#W?UgZa#WFwNyhp1#C zZiW(j8lXk&I(w_1rNCA5A6#E}ZP`fHE`GG>RHyYah1+EX{!XiT0jpf;APGD9M=0%Y z2p8m{W0(yj!|zUEkc$i-7j`KQWup;z8eHpMY1n4|61|04sMUGAHq|Kec=1z}?R%fU zvnSodAHkD##H%4H9W9S_4~gYNzmp}R>0V3+CLL{!zM!~e$`|e3%D1of{RlQ@QMM_R zcRN52D}+C;dErQK*Z%a(e_3eGhc5DVhgwAT0sg-)cmJT)LT#=oLV`@HfG9jHbIXIs zD4ho;{xh{&vt%~oCR8+r7_bB9)e+8G*v{ihX74`}G)3VV1yFz=G^A`bNeJ()y3-fd zxhz8A9~c)M!NY#m$C}Ys&&|!P<7TXCbV`U6;{iL13Hp)?4&Gc@P{yRRl1k?^(t}F3 zJd}O0wzIS8np=UpB8{nw0>R~KwvNV{HA|442(E3J!Tp(6)s}+7>~LT1H~yBQlJF99 z_UBs#9v5XEr9m@n?#>v>RgZF^K$*EhlDi?E5Q~YDIFD+dMqJS=))SuMvhpgMVlzpr zt&$EW&)4NRPF|1dIPl3lorSjvyn|Xu%6a{LaCq6`BD~jD9@*-|q$AX^^}7N#(_X*4 zYU;o9@%uKoKi{kGPTPawI$hX+TX$!<>kRuZLIh&f>_oII>?sp#P5M?(hZ?=Eciv~3 zq_xyGugqT5)*aN1AOIF;Z5Vc#xPAbVaN|tK_qd9tKO@lY!^7A9@-d_$y13qN8{yeG zg3Vx#@Op3jgct7pk_=}!eaTn;L1Sw6;bsGkKHe`W?8522vO}ThbWZ+H?YmPrpLsk+ zd2AxiM?TMZ@sBIo+H|!h@|q^3I=;5go|C{AWSE%qEMa0DEqs96FeJbx5pVMQ-%6Lo zBL$Y#Xl!3&xmRf|oGNjqqz{ZydNsMm_ra%NsgNmJqaz|Xpd_IiyDEnN(-k&VJMVd^_FeYVNHzOb^ZjhJLff7>SxbKcw6ldQB3v`@p$Y z_AF7h@b7^X0W#u(!y;<(F#X&xcj9#%UJ0yYl>-0d>z~>$JCU8bh@e`AyS9sqpIC`Y z?yx_!SH?~>&4;LM*p=}B&0-$a1zSd#DB8irk|zJ!LO1HFx)|)Iu99{1UgYkP?nl1q zR+0izmONuRoQUG~NfCelsO;Bg1XA5M_WtqWDQu;0&}7iNaaT zW@t`H`4&1Tjq@v&X#q(sBSCF+4m9Tp%7*2rfJKCiGWfz@H|0Y+Z%`wTrJk2^u<$a< z2KJ@J9RGy;g(big@l#wkZFx@J2Y#0Xqzbum5GAZ9M%CZ|xRCu)+a@HIC?u;Ev+-;=RrUKOszKbh?E|n zOmTojDeJEhN8e{lpm*{7G!swx>{&B{G7`wM-zB z=}EytAC18PL$3_|8Z}lXWCEPFINBl@UH-A9UwQh7lnhYJ_>y)A-rxj-gd*S5;PaVa z3FZ%Yr-ih)^x6vn%?G0gHriLK7WLaBD5>6+DW?Kabp&dGB7Yr zb{#_DxK>vgYzLlJVZZfyKW^TopsEBxae#Zu@>ga4Qk3LwhR@>#l>ZTa39dRT%%^wN>MJ~N4bQFDBv={zc{!i;z6iM*7h|{+E!x$56 zQrcM=f5eWyU)xmb-C3nx#IBwnDV}@UdCepHJ@|v`*-ny>y0`N8=-=Ow&#%s@ize5< zd}~>H)N-5_CBKO~;nOGrOlaSW_!Iu;^G__vRo9 zy~va2@7uS8)2~M#MV=P@Y2Og}5F+Jpdr;Qt`1vQ(pD@z0FPu^`i{D88);{dQ<+K7a zTPnva??qm=|LOP>MH>Fo1$ouSq6l3D#Qbmc@5||H(tjH~EH~5dzns5}3McK0{OcH{ zaM{Tc^amYvD@YSHI^z&9(cE#iKgV3_Lkz%)eX&mZL+{^#pWm0|pF)3M>tPd4uu*_3 z)tx8Y{QMXdjl=H}OOIIO|8l$M@vWX;> zzVHB6Qo!?LsJ5d7pfr5>6o^m?QE4=2J9>{MMrK|NFEmDIn?l@!LfMK!RhvS+l3Wu* zuALt%sVyd5i8h)?$it&)Dx(yy(3UMR=2mewm?*pX7>BDk!w|HwcKr2ew9JGf^*uIN zY2h7e@7p4Q>%nbm75^A6@DL-?J`nwEKAvna!EZYOQeqv1NeJ=4#BRqflqW=7C7|Xp z26zb>R~{~*m>gPxU^pfjW1&Cb5#5sbY8z7kPjHJ#%=JhbHOEM1V&k2L5_PAO9-bw= z;fyy3O=`?XC2k89(k8uzCS}bh*U=_|L@;hRIJ6>x_x0_sl_?`bDc`nJ#-OPa@YE^o z)ESS|IZWz8W$MyU>dJQNPiWd=DA^}*y0-1)^!dbXXv!`$dESke#>D3so_?yGe(sTe ziAle%O#eHS{%<=S3(WxXW`J}uz@8b9#0>m`j8biZU-@Y%(9HIsv>y%eO!@q{|BJP| z{%i96AHRQYgE2PPMoGg^Ns&;bQBYFCA&QhRx&-M^!O@MBfaFMN=~f3KDJ6}7ARXc` zklwY|`~CfX@^)Q6UFQ$`2X^eZ-F7_B<8dc|G3fYF7>);>>g+uW-^hThax`q+z2Z z!P2Du^rTC)aTo&lf&g3jL9h{9h;$UwZ9hhNc2-&T(CdfEqs2N!vKplh7}Y~o%|6!K zGh9-_c$`r(_ArG-j+~gv5(}1$)$dC2sd?!+`VwiIam{jF zi7(w)Q;#K6uS=%AV@NyFPixjsHBL`uoJmEsq&|9OoJXU9#K4hQ;qa*R`26%J|Md8l zbc?z)8UNI0>@m##ueA50A3MfmZ@%JD0c=Ppn-OsO2v`K4QCgZ&-j`9inem1;v&=Z- zHG5`*V`kG~MqN~9TVG~FY35tntd6LR_rh5pqcXc3v-)0T7MErXwq(`QX6Cn;mj$8wO5+)Lpb+ODVP!> z-HXaSoXI-wBj@&Q=8}c8Kq7<=EkZ?Kj_AuAL_guNPZ};NCN?oGagTuR=VCHJQ@W-s zvjlFFY>uOcT({HCJEbv*uwgjz1x!*zTJz(*fC3EiHyW8ovK2%lHY8A=un@=+d`TI# zjYr60(fn>mGWtIwlW}|blJW)Do)pNn7Jx?!Zg3P*slaBjsO=GW+qm}ol|l)T0x1zR zMGlnjFSrgbyeWci@X~IfDt>p-HE6HUR;0+$qzJ+Xd?KMp0%*|$#II^(34s746l%{F z#=5`Oe^P8vR!lYe`nd=ir;J!rM$HpxsS-7pSCJSL@I+Bswa=CrbXU- zfmgv0R^@o;6$#j{YTAL>ieZjQ;^*|vnp)B0^nuaZ4u(3SWL>jVP|k3g~y*t@Jy@com>{5p}$X z%EfW6C?hDmUgx!OF4p@ZW4v1WB}o}joz(V3(U zK2dZI0ktp!wOyoJz!`l1V^YJOLLw0pf1TQP92>O(mQaAiWW$o(<2PpuA)=)g!uGRk7o_d zS~U$N!m)$xy!?`$xtp#9-HO3N?D2@{MdMP+*-K)ZZ&oLO?+)JU2~zA06NN^6LPfRr z#+~%$P?O+*fK?XLq*ZKvAxlX=va#2M+dCfnr{@D@7R7+=NiB( z4&>1F=hFd?(a10GZmV{X4ISVY+xNumQ1gnp_e;MWMb@T!C@ z!Ug)&2mXcB9BVla2^zmWIPOn9;iAx3@q0qb*6zm%tLbI*!-r_?`SEhr$%p&4meO{1 zm(ljc6B^m$E~gVh61EB?R2CW%k=gwI2pQ==VSJg*i5_^Qi*}_40+nool&0TQAWN|5 zDEijr&)_#eQ30+oRo_}>(xrKib_zgkyCGzVT%}Yd&57VTBJy`Ny%oR}=Tw}!)VqNr zf+gS^%BZ30*ReHU!pngNmr)xS1mT=ojT^Eynr7P#zMKlZ0?;hu5MVw?E(R)!gEkY9 z(J_U01}Z2CR^|b=A^Q2xy7QB9^Rt8V3-k-oPZ4uCr~)1_KSD<5t2-6%zrp7%Tt?52 z(F6Y2`Kj!Apn87(bbg5*c-82bz3-SO?NsFBw0SxQ9$KIdT>RmJ4ll26S*b>wF05zQ z1~V)|78YQE=y1-VTAZU0p_xB^q2n{Onh3o@f~H;O^!Bm$7g(t6pbI5HaFo58gKI5R zkH`mJ1`xJr$RmK*;9j%q#O|UD_rno$7LjfMRWk<3+s$TFwTg#>hX^z>Sm>l1{oQd; zxia#~ZMfY4?HU2K0?blkwJnqaHx5}xoTb+9OQ|T#>1TV)v%Vy;4%T1y%~=Pk*8|Sh zgRWcqcOx6CHNQ$fk3g<_=&k$2uiJ5M1|rEDkVKa+hO-&wukk?}IYS$SvkhuXV({&f z@aV#@cO}82ThV8m@jSCsmd!prrps>I(YGaYFvwbc=cZKW0e3Lj4ceh{SK!ZVttEVH zgez&FvDva2OxeJo;6GT?1WO_nU$$!8ZmK5S1ceJz)E_L|l0f?#+uK~zoo2=v?hGXp=NzT`R?Y?~HTP*!9pmsXHhcK*jp76zq!WUj z?S^mX5`3AMFk16)zKBdp$fHz@(G^&F%;QhlbDR?5zYI)&z33ppNxkT=zpUS51@RF3 z7yI_&TZ|K7ukN7=yB& zwblCgX`+-#P);g|G&|{G4d|q|Db<;(fx+#Fv!gRLH~4S-&4>(^SJ{{ zaBkP=SZc&#rrRF^{Sm7bCWq|0-|a20>A=qil!2PZuf{E0D|Y?U?jmpg z^(^4zFfn**QXQK2gt8Gs1F$WYFFea2%CUhrYl0H|iI+4X_nK8e)byREgGFZ^C2JfG zpI{fb9zYqXxD~C4A=xUwJ@?eutWy#(G%J!Jga-~FVu}mwyjq8G79Z@TD-s@$*)!|3 zAt;?0TVw9DvkPS@!Qf#T>~-TF+F}-COSyiXu^PM-r;|E$ow-Y$Ie2ko9SDi%66$;2 z%cdFkd=5fL@BtPVbN#z2G_u7I*M4JF1urf0N;$ZtKv_PidJ<&DZ9FkDOQM>3^gYKk zv9Zilc(gAdyTse6!c)W-u4?N2=f2UOEke#Y`YURj!Rny9y+I<1uoRxeIno%mlC$9+ zFha|3XqV}|KU1e^=?;~Ybxb50JR13s^<3GgT7?rDMZ&0j0~JusZBSj~*Vp0}O7@qn z35vMc9I|iz?AHXVFi3V!J=Z&3F68qDVRR*zrfOTA*JI~eZ;;9CA&sJU40rECrka}9 z+>WH_zt#!2&b0_)Kd~R$q!<{sl`U4@%yj7-@kCb zwLgFU{HN@<`{QhP{@=LY>DJcS`uf58`pN3**+$p*@87q#x3{*oHa0f?Q~CS$?cd7Z zF-7^Cm>|#Q{%_@PYHDh7a&mlpd~9s&^XJe1m-u`BpTytrFh%zJP5J!vX@B6;;c)L^ zU*ADr-(hbrMfp4U7xZ_~-F-ONaX8R?^s$qo{GGmg`}f_ugSPg=hQ_1b*GC^x&bmEM z-g_N4MW3`-oHnYT)=K}I_}lC0p(ua<-^5=-LqlzCZFO}uxm1xN_??w;oV}($E2287 za6GNJ_@|ukp*-w=Sbr4R?{8lIes=cBD~Hjnto;0Z0)dd5o12}TeVCB&Z{P1Y)@U`( z>I9EJ^S@2PKi~B6%E-t_O-+6I@?}y|(u)@_Vq#(TiR4$9H6YXlk9_5~wpWe*E~ci;IhslarmDowcGbDlxqb5^mjI>?bBBDk}OPtRFu=|Nl1qI5;?1Sy|7WJIBJp z!owN)LgUNlW;*hN2jHBbs+t!sn4&xI;v2*aqlhd*80t{5(A6aJycw*+LgJ+0B+NL zli9|{ABHN=$^58)_dJtcEKAhA>NzOnCYw+$Vq&B~J6G>?Bj&j{^N2qFp2FXPg|^3J zRx=n}@aKMSHP%tNDDbcQZ{M9BAN;at&pB-${X;%{or6~bvEiOjGxjD2(d{*1 z=}t%TzW$5#^E#1iCIl-uPV+^``ycQHb0*22S4E0Y^~-rY-1rtF(QR}u9J6*YKknK$ zuY!2FpAJ@$O0)F^D#GVgiL!;gB`Zlf(*BHbtK7;RDfbK=S6>?0m9D1p^e%Oz;=+Xm zUea8YDojwB^b*Lp@ol>Jg^<;2G#7biapfP@Pw*xdjKL$6s6;jhq34`7@*)LhLs0ey zgpGm(^{wEC&`Pc3qN|n}ju~klt(%#u{ZYIi@kr7_>3?VawkzrrSI{RrR#LuQE!QS&ayzTD<7;irVow>Ae_;OQK1F_ES=^+N>bhhbX;6`heCD z-Rok0@M!PjkB%?7VCLW0ptlF#?x~=d?`>CRP?0lh`vrX|>E^|?za2MtcN~8W%4$>D z_VEApdi+ji@6i>1Rn`E)C_TT~*H72hcYcpyA=Ov=Fc6pIk<+TVq>fAO^9_?UA*X)^ z?#4Xf9n*hZDV<~RSI2;p9E%+pW)I4bQ*Qcwg<+D)pPZfaRS3k>JS{?tWbCy260tuU zD|2S`&+Cjx_*ceC%UvmRZ0 zfCiVUU7N&1bjNSeKxtK#&UHZa+pPl$o}laGD|`@)Sw4h&*(iNEV*jcHz_23ANYziCFEgAr=LwN%6Bq7~+~#6H*-783=erOV+VG(xT6sR+oQ7_%w2@?(wLZ`AwQ;Z20xM3q9%K ze4oa#F>anQx`@~6GDn4eE;M*i+Hg^-r2g+Mo`KZ!9XBSc(JIKo1V7U?Wh4%%3*gWF zwk-al{$NySzdjme%dT5ejS7$m%2%1^fLxqnu(687f+Vvb+3=cQWYI+&BF%Jus1Wpdx<@rJx*jSy5fmFx;gP0*-ukZU zdu`L%UHjtn0z8!AH~~t9Z2K}{Tk9V)DCF5wZnnNf)hd-J_M}+*;VWiq-b$lLY0iA3 zkNj!v2dgFip1}*RO8z=*+y1z1M|ct7rSfhvKr=u_c;Q6esNndc)^ppRUqRkY-V<-D zRqxikpd6BPaOf@iw#_WkWKJhDyz2|KzPm&f<`*O$?ydtz#|3Bx^Zoj`celg&D`W0K z52H?vt|49Wxh7U3D3F%7HU`Yy!aLthsPbBIE2Md52xsPkBgorN*nHa zRL~iZxN;Je6gWn+UHi_}nnLa_w_@lOe+Asv-BGNWz2G91RPjcAn=9mC>Z^y=CE}yo zg16dQ>{5{#F@r9G+?f|9FVNaG^eFuZy7O%1DrJ1L{yr%78wb^Bx1d<(W~S`ZPg9ec zw8b?jNulYBUoaPbJEGX3)5dh;i7)egk;$(rnN%aE_Drz9`c%Zob)T-$yc zz>52e0Onp^`h5C3FdODcqUPIz`PDmhHb6iA&9JulpRo3l^*$u7cE832WMOwF*>`bD7QH zb;*z(J^u`i##eTa+ty@$_%tV{WM@#9D{ed9dG^^LSDe(tKAwOIKn6Noe&HEzdUN`L z)X~@Q8;hm<4-XfTPk$;QfZ>QcCz+4mV$PpFvwItTcce6>2*KVhY_}H^tHW*E(j?T^ zlEcVIYD13CT_>+_|McEqp8LBIq1P$nF;O8uSNQ4cBcmRZ$vU1w#x+fv^A$IK?i^G6 zuWL^)1wHH=agG-Zgw^15SFJav@Fg{Y94f}C*IY>&fW>_*XvLVoZ$cvp{)5vv(eP`4 z;-kXwG<$x_5saV&y76;?7dK231#OYCA!VSTOL>l$+ylfy{H8u*V`S(pfslvm9uWIL zON|gsKUV1yM%fZZ`EbeM;%3h}`;S;=r?=BKr3j8xNpHyylJ9)y;;2YMPsD(-~|F@y^R zMU31FZzlVOV;F!Qz>W_a9N+5^1dHhXh!3BRk_(Cy%!?H4h`d=85#_^ZSdAK!fPx&N z^YWuQyQ6YsW27Xn@h)E-Fl4%LAy~*SSOE64Dw3gW#1eWCA;=n1q8`)l$ArBi-q*#H z4`VzA$Ks9RCZ`!NXfuDTi!oa)m40A|U+92ryojXeZ!6K^qu`hs2IOO)LRCof}53y0Z@>^a}aaycu;Icxqo z8?SP>t90Qkw0stdBahi6lgT6xeLIWoNhU{YUj0m7Gi}P48x0*PlXWXkz$v5DF^ikl zhxafSEKFBFk`9p4y|og8wZeT%@A;Reaq*=FYNnp{=7w$NO0>p)a6`Br(zwf|$;`%# z`^7%h@-`4*V8dGbxIMj@Q4s3L5$<1@tqFI=sunJy+$3HuFGB6H^u~vUrcqd>4E$q` zM1}qW9(~v`n*Pkk&+K-gxlrNyx`t5 ze}j!Rl`jq1d|k9x6m(Q-8&Z%_R**QG?EM6-LWuTD0E(pxFFS>b!^;S>f<;>|)o4?j zZZnjOSRPN81ss(vv6a_yl+??YC1sTFOTYGNWjKc~dbv?vFk6%jFZpnk`!TxWo=DMj zMkT8X%)dW6VZTKGNr8iLYK-6)W6N5kIt zdbGc^aH*83JcZ>_7>9OQ_mhfqOO>C2D$sHHZRbJ4pRMn2Bh@A?~Wm@I+tfSQ^&N{v?`Cs6c?xY|%WPt_Ql(ZU#HV**qfpyBal$RweXlfku% z^uLsmwHPoY2--P<+yUrpB+%|S`X33%HVgzZ3Z22B76~wfO0Ba(yh~<{+d$>xr>%4~ zHsY78uf(7WM~XRvpi2b$YCHaFy)CFG9;T-FWRl|T=+ zgzUM&mGHEO_#_x#Ye9Kz5oeS3_QUz@x2)vRx;=PJz!p!AK6>5_-j;xz!P2sgg1(ZV zebQ(ze%8owManFYj|O%CNO>-z=Jfv&_F4ftc+lG!g_tiftwvAlT{BzJqxDBXwcnT5 zln~#agmzmj?Jtt{xgf-A%EaXo`egzVyad_;;B;6}%?Q1RC1k%EMuP#jq3OVhk75>) zG&&8mJ5dOoQq%Hk+Dlz5i5?cF_N&J{dy?qCn6_H9Hwz!^3--!|3d$%z6TAmm{Fkm5 zeG&Z#k31xyCKlzs5@{hS+D)=(#1UvJuTe=S=0c#%p2-~Uyr2ix3lwmtY&l%Wc+TSheMXSz7xQP~NQ z5Hu0aTa1Kq0)V1wdPpJynuUfv zVvZxxl@SJWy9PxNL#h>{oZJjljVR`w*5_Gh&wsgsyX6ec$-`gp5am&@Z6{@cAY#bD zi0>pW3Z0lsfY<|c-$;@p&TvIH+KILguVb07lIRBUy5~;S*amAW=LV4{M0(3Ew*6MI zAO$xjwhRQ|hNb_WaKlR&9h^Ws9s}48HZHd$&{8 zlj1jVL8-n_A2z%Q_j+jS!#%+sFhw^Jr*%pL z?j;;0B)Sy*{7At(EOV}{aylj(9bY*|igS5ApIe&E{D4G9QS7(g+GPz+FVJ_@DlITb z&hlOwFw&hV(+7G<&D`d#eCBhBP&k7R(_l=f2mx(EH)dEy{dK=Zf4FQ z=r$t=td*-T<-T3>HeWiYhhAtxElw?5K~9%+z=ua*9>{A}Vyiaf-F1V7c?!j5>$?7C zdabB~hIn}{tV%FqckXNXroYk}tcG&HPx1YhG=^BuS243==VzX6$|i5Zc~-NK+coB^ zWqw`QvvoQ#?sX;FiiIt&z@@0FH9x&YxQbB^kY3=rhH>4}ddF-`{F=Y8oqo3MueZ~o zw~`=+e!8&!;`)y1^=10AMH9^Tr{A_D-)(eff1k+lpbgv>eYf+}eM?*ATZ!`Sm}~vi z?(X64<^uiJ9`#DU`PSaTjy4~abUbK(NP67$yWP;nLf{(pUWmld4;1Rh6TTm}`G9T` z-LnLeuhnj#*<$1Z33&spbZiN{+1o@sR#L zEIbTg6(o$iBY$b1|D`Fqz5eb8vp6~iO5dBa%OXx5%PCDk~>slIyL?eOa7mgnBRQEe;&Sf9vj*1-2Ib?+#LmhCv+iBycZs!8r&@Y z660$u_Tkrueu=)|C?DJoAj=}2A6Sd;qr?w6koA|T4PU-16;(u=>JRcME? zKN@+Dnt2cTZybCY-oO!}14Iuy@9ejj^XlQ2*%MCu$Q`uPZY_>V=q`ZmiE8M;4kp|87=})DL3GiJ5E~L=8SB+WbOT1eL4aUtda&Q#k1()29C3^M5}!t@YRg_>hsfCeeJyq-;_X-06r@+uNnyG?jeEw5$EyB5kSr;t=UUOc}dJF-Mj{$)3m zt@IqqZ6dWk@JfTi`f+$UPEPkuyQsq{f zk3r^~Y2kM@HhWHFu+6@fZTFPTc+E8)1?{R2bT^*3^}bMcSYzjiwW-w-gk%{QiBNe&G(w|gNzNiTd1t`)aAs>_cZN7%FY3| zbMh`)JSP_!nyrt2kHY29HPSAHuHWR#2slrxWBDqjA#L1FJNp~E4HwXC{o)t1(Ss)! zc;pt`wWVKSw4hyh8-LmYzu6cqeqy?P?5V7M_EkFng|uX~mI1Y!oIdxPNTPH=%^7D4=buHEX+ zjKKYya8?TISIF`H%Q{iceipCwf)?l5uJD}0%t=eL_R*N{Iye9LAH(cFGp~5^WxBZE zaEcfL5xi-3Gb%=T{Bbuwm+);G`u8^?fu za=8BB>(TF?_UGF_B+nG%GV$5X*UM+v7*Tk zTIkh{2(rSCH3vUzfkbE27N7TxJsFRKKNVE@%_0#hK6jVbwF}PBNiqyMHd{J*Ngctd ziGNnB1I9DDu3|0Kqz&m~j_L?MzeT>4b9xi6UwUgTcDgGzg&|1(cN#jUBQ~{RG=b-- zHFZN|yTWy~5H8w|!e|Bs$ty`dcc^UMQQ@v$=lYyXzP&poaCEj7pN_EAM@Z7G|`kTTU55O;8ghZ`eCrAdF>yeV22W;NyjifQHe126p%g-G% z)2Rd}cO%~BsfuXH4IXj3-N8z+T+08Y?&$?~Zf4DC3vxk@Sj3f=EelcvZw}nQ^LUFks|XB&q>bN+MsDWD-`i-p(pu#w zR$rhLgg+>>430ap$>E4%7qB<3l+UZq7jGC*)0M;O2c{H+v3JH{-9J~Q)Z^&*Er%9l zMAFYq$X`+8*Y$51YGzX|@`B;6)n(KonxfZF@7HCjOg1^wYioBy74sc3UD<0_Z`#F;|SruU(RkriHsdkVI8vtr)-SYpbgnQ z$>7_!fljsp*)@rjOTkMUTe2aBXPUQ#KL>f^ta=TZ>@TD!+9gTI)m<^Pf7WtydCt(d zU!l14J_rYw?p3Dm)a-%3GrM*@R3y*_S`Yg3)LL+uc~G}T?D5xUt7`Vf^)#blayypD zhoKI`_dWoSFtmf-S2sSRwO)c6z0(uvBfdvD;k&h_8-;e%&Hi^ur6#kECbzmi4f9{S z?Ky8?kTxq8WhhnN(LZ1E=o_z*R*-1BB+8@rCKa_xh{S9M5|@yN0grUa2+T(X*Yk1i z0~(D2jLrs*c@YijzOy@mJMCpN>8|X6Yf+GmOx@Gko=0$w&OG{x6CA52v4fNRt_Bh8 zHgisq)FCz$#9%wz0ky|NR34#U82kp94x5uyd%uf1Jmj0-cz4b6Y2|j}uh|8mnH`QB zrXHoct*c!=w`tz(g_kQ*q4$*mV2FspoLry*HbB??NC|h{3NWoeck`XO8mY3AAhvS!%#3FyVG#2!;nsBgBRcGV;2xoyTmvwypdx|!oVdfiE* zBY@zYYn^KFa$8&sQS)rfFs+SD@>q-FJxfHLkw5SrQjk0n-U$uuA5ieZh(P~g?eJJ) zL~sfId1P}91bEBDK+aHVap$bmzQJ$$Ug+t2fn}vk;GGRAugU4gk+ur+Z~1%@o)_Q2 zON5$f#-ggBR(`R;#8A(Jt5o<13X&%aFa%>lzC-YLr^ADL!wScmi+-hl*d$6GE2B(R zI?6hime0T50HR~$|X?=tOPwt4utD+H6I-I$sLq~1U4$hOB`Q!#rZ99qW^TciG)Rzmaqpk>#sXH60| zydO)MBt1XUgs7<>-!yCM#4SgIn-g#Qw^%W^oJ-;VxOw$}R-F=I)lleulKfHd7=DXH z;CJeFk&-f(y71AMU@sf&^i1vMxY~hJ&$p0hgha`GjGTQ+t48dlkCJ?8cY9V^yRqdr z#F={xL*Nz5M6(nAcODtfbhvnKhBNJGOdV-haQ2cd>v}?DgBJX#q6^i!K4{q7R(qb9 zZ{Hgn`K&Ukq9^)MlkZNHk5)Lsz+@1M@RW&n+tlxa9_;`b2j;40^Zn&#&4SX z9I0M^pnJ1bb3X(wqIq5k=q)sBIDUFfai-bnP{9tSm_>CSho$1hgjldeATg1~mZt_mkx&@oA_JLn1kD4A=Vcfg!wh|6j$2k8nt%;`yGLzV z7R2p1w3?zfMi|;sjW4?>COF3qEg$5aO+fYy&hHHFWvc$xO!$3o_>ax-zSr{YwZa#pzNIMhfE>pPd9`mL;K4M=56SnD5Zy}a-EvX+ZRMmEF=JJ4mL(H1(`rmCBePWghV znSsxj8mjqDVYT(~<-b`2II=Ii%pq%?(6}S|y(4MN9fArj>Ru}RWc2%U92<~E2We_I zaP1mM!qb?Rz_&1C&!U73RSg2~esbFxb5GGq!hdqC4nZ%DY5dWYScTo#2zz=Eu8aS$ zDm4BqC`a}3Yc;jrDb+5K$|xoyU2$ALhDAl^G?HZ`)P+c6aS)Ql8H=q<{d;)z?jXMb zORqY=ruJ$i;6~lp8$$1Q->RYa#!Ffq3WKLfqu;AST)gij*W*PsiOarwZ(hy%``a80 z6{;5Uz{Sx0^z-%4Lvc8e?nby@FSU#^l`HWBvDeUPrpNWq76omtry$Vw~mbD>5Z&cT6r2m6eRE|_os|)rosm!o%zQz ziZWXIjk8Y;FI_gdao;$Y0J_`|!r|AQGjEbQ7#TQH7pxf+C=?r;ohmfK*7L;V(yXy) z;pcl{UlJVfRs?2+X-K5bR1^J!@RzjDVWz=uLH*<3@`%*_(fPaZnTJ}NlX0rBUAOY z$QoNXIlKR-F3xQN795Z+Df{5p{l!;`CMj&;!(8F4;Y+N=xUD@sx*VqW*CM(7B9M9u zZ&{XBbuFWM#{z`HIjSLwxJh*CEXIeaFd*r$C>3b16kMV<--xg%u`=HXbHjC>eP5b5 zU7|)VN8vv?5Q4}`vNPKOUtd04N=FBMrwD@^=EeALj>g4yMx(+*Xwz!y=OfhD8>vke zsm4v;AKgxy!+Myf$h?IQ5MZqA=RN4>6Tjzua`%yFC0=yhQV(Q>7&mX zX-Y@7#F@jIL;3<%B&FLAvLn4WKp~4k-n}cEl4E+VN$}ndw%*XlWy|MkD}7Xp?W?eR z=we1Ta9fc!v(KvbOPiEP8jJ)ClMrE=nsfh=+QY^KTs0NI2J#Y$@IP3)d1i$PT+@`c z4R)Ikm=2~-H!r)icH4F_i4AHj5osKGHzRvF`%ul5htZn^0!pY{DBi+GI1Xxbx60g` z8nmGnO_soYow@&Q{LfOD4(+vc8moiQJD70)MT@}VT*s69_$stN+na~!Gpx;ap6Ay5 zcRycCU4MZK3y_7nbR62kik zhl7OxDRtw6qDS`K4k^8$$B_|_dc*xlP;I7#zyA0OH9q6f_&Ep7WOW`B z@^G=sm$#n%5jN#Xra|9}UDsUY2DtGyA&##|7TB8_ebw#};J%Z`N)j%-(>s z^paC>ge~6Ey+h)=V1&n5>JQ8K+akV$5tt=Vr}Nu2(!%afQamkpdWhVC92u+jvsrRZ zfHgM$jOwl%jWd4H$&H3DX7{ks^U@tHKD|jRp3k)ef=7bhKJ`j( z97E>rL>R3cLV)|byUJhp9tdo|h+HyHTf#ob`*H0LQ8vPW3Q$vy5cd6}n(AdO2BRT- zITeUJTL>Yad2qjX5cak@RPt;oQ;^mS2xs++ zp!~rOC5kh70UF6E$DjAkH4-Q4X78u)y22TUK zlP2Dc2hLM}qa~yVo<>?2{r0T}fv2g1KO8al+qR0cwAuenUn@Y2{FqE}n9)5ZKKILb z4hvY8i8=sz9Z)}=4s(^InSdVf-egpLdGZFcx5{`lly<0cC!35|CuUXs&HHviXC2me=HHZwA8`(O|!;_sttd65uWMND3 z*?i{gJ`c-lD!;_DUk={cTdE2T6(3=cEUC2=cyv}xwsm6gy`Y;J!OE-tCzf%!H%ZW- zijH8843*!y{}Mh`+c8W~GZlFFN~A1cL=W@Z%KpwwZ?W)jju~g(czEF1>h|fd#XAVS zZ|G6DIGe!;4b!E^RloYL+R$eiym391Z_^iwF7qD0*r(V04=|zF(?pa+jvtur`g1>; z1+zb+>sbL2VQj3bH&yFUA~0%9IJf1=T5KbbJS!py%2*=GV>(>IzMAY zR5<)ECNXCxYD>?o+=UwEbd+SpI^W-%cxfsO^pYiy>lrguz^e?MG2Fqjs}2rVQh3#5 z#8k7~i5EYsc+&{@XQPKDLOQYojt=eb-pyby$au|SvgS?4R`=p6KgI?yapDtM$ooaV zh0c^c^wbp)#W)BO`e|{Wu09K;uzoM+8@6b8B&sb_jXs)8RA47Em@gdbSgYNv`ksi- zODh(BJx=L(Mjae(gX zkQU3&*h{wM5BC-OISMH`glTlsEp<*WZE+6UxxM}*eeUtEGAtwT0>KntLz8EZVK_a}dUk#7Lo>+bAN{sEd!WCQ@DTJY#Z67yp%-D7|OrnG1wI z3g6X_N=fg&eotTZ#!d&)yW~9E2cd4sq?%ZqnJSHKew1HIKCU=YL*Q8<8!Pf7=z0s7 z`xjds=lP4=saV+IuGRJ5rKphb&|D}gszX&IDLD4gMRJPUc|!?&z}c5sC}y+wrjtiv z*3OE+UegU^w637GW4}R`fud5UjiwseieHqwKHTiy2kIN9A!-L~EYI(~;d}ZE`?Z%z z=l4jJkf2+5S}{{bq%wf=DFI1zthGfeiwUHU(%GM@r370pQrD8Y6?^#*3|v(7oene# zc$M(bl|}CF$}mhj-%U9ko0m29F#3J9;HN*wdvhznpuQ=K#mLo*o0P-iz_&P^CW{QAMe`zW}av<(y{qe&TSS zsHAj4bo_gi2i)SL>N_HuN&vFNXLpqQNT)%?a)Q+1xv5@eB1>#1*G)_((WmlWm8h+W zu;-OL_(P#v@J*u3!eVg<(8&V>i0lc}q0eo)F-63%^XYKl;lVe|Bq8ipMgK$?`exV% z&dW~o=U;FHvj8%^b_5Cesnnr;2@v+<^}4@vIA51l;mypzZmx7OP>n?MAyeQ;e1@D%O4mkn1rhcl^ z(ItUB7Js%uTY4}^vIngf;Bg=GigFZpGs?bD=%bhbT(C7U+_%CKy-5rWh=?gVi;n48 z`RT3$tKsp!9QtsCu4;-=Co#<<^uDhVhj-l zbBo$2D^h{*J{7IJ?Z#9<=Tr30)B`cW9M4-+5_K7TZ8H*+bo){uXjhbvt@S-+`%90_iEkBgAx6LK>I{T$=z!NtR3anM`o zo%MCOXD5Qnyw#N3U3j!k)^a@zuMzolBv-F}nMQkgN2LrjTb4650~4;4)Z5-m3|UJX zGXBkyMfmx$u6o_iM zjXT`pv*UBT-mmxb0b;Lb#N?B(BJDnGIGhZK*F4EXe>r$79`KS@n2;UQcK8abxC9hE z@1j~b)Xh_;B>i~aC;18!buW08)7oDcjy<6_rB{mkvqW4RH~To-8k8bCE;HQg=5A)K zYY}3u4(QBh+&7OB8_%PV0K#+rEDrrpZ8<0R^NQQUg3Rx z(ch$&mX#mT<(H3oY;!v9Q^{Qlj?gkrBiU3URv1HRHHi9#=A08;pS{pL&tq>tS+zdj z_}+1gEbX`fLkVjUPr+f&@E?V%4tugD2Ry+GU1)a;KS8`XHF|SqbML~(YCd65k^=wg zG2Em%*P+w;)(3v;V{;P%2i;~ zvY?=^Y>fcy4xoIP2peT;{#v#zF(aPf7AYr14lF&M9y3q<2&Ydl*bw#!O^yqHgI%4m z(i3qQMlai=*%=vg8Ch3WxC?HUQ&lw7mcKEvn&7e6vC&+T|HXq$?DyUwoIudLWvjMU zkp?~o74SzUw5^A;3)roRa|kN1uJGHr>;btb7sh6~=uRKAtk{;#EY}Xe_5Eo84XNf4 zE0?w1lKS2JB2URmI1DRS1V!wGv^Y-;o-*9h#Zo_EE_e&uD&W2>5PQ7xg)2|1@|PH7 z;yD8+#zED)Z1E8qAXtO#C#k{L6<<|`;f8OV(v&%Z2ZhTPs}vIWw6$uol&thaOx%H- zc*l0h{L{%vg_^xn^7w#|^3_9Qczu;7)1xP88ga@CPjeqesa!r?I^)zOMd>oKvD;?| zGOI2dqa@c07WWI(DP#XEn|b1KYWGgZPfjOTtQ{VqNcSP8S)JlVdZuQEU*)X%U%Vgve~Lh@u^tsoz_A zl!a4~dKCG%AB5n}W7W;Jau9>IVOTV#nzGLJOrvt?DbLjBy8ayV7xhHNX(q1+~ontj<&Nmk4Fqx0@N zqd>sWQ|03l@P(rlU{jZJQ!u%7Ng5A(v1lWMww2ga`(^*Ud$TMdfuMSk%pCIMp(bH? zIFJ9c$B|q<(Y(4Dr5u!eB$Oj0BCLQ<1534z>apD3I}zUaq&|ZT#|R?REH$0qMXxWx z{;d(n#1iXcheZab#adf;8vIrMXJIm>!R;Gy95$|wwjtGQm*VPv9GW^qYEcT@$egU< zBtD`0#b^%fVl-neXZ!Msaz2ZOZCpEVct0PR%36HR-H1=`>uS>pc{J^B!ZgpEp4~bv z5IQIQ;Z92BUwmIiF=Qt!z)Iyk#!Q(L*6sB6mow|__jjLW>bG4%4`z%kj#btQEPjtHLc@Vq}I=@7Q}1}2+;0<0+tg9>}``87Z-1&);#F#)`C;DDz;%<$*O>M?bS0db#6>s^}dR5pdORJ*t z{`2s=LQfY2O6qbsJp@WgQAT?R9TT+y(!Bv9+iyIAtsC5)E3{NvIi%f!Lu%zi_XUP` zhQn`lbH+>VdF%*ohXZgbU=a{Xw0}${WJ>KC!0P5yAiQK-m@JXgBjdcL=_+R`s6DyY zwjgx1&tIz2Wf+anIY&;v+8j-^9ZTK*77BN!#cvgJ`CicXUCni9++||CBHpeN?uhuM zhSi(y*HF9$!U?LEOfz+8-IG|Wi9fh4x^;0i?yN{xt$o|K8?Vxy5pK8I&&p01aa1+r z!Y>Q09*A{ECRd{~+;5B5sI3gBG#2K%T~@oQwfHwq?z_D+bdgz5rQJAY zsl8Scz3%2A$hAxL5|FS*YMvu>mMGcYxIxs{A)LbWOhT4i z!jezjRMXXTqUj8ukBG1l-s7yi zmv;E%gF7wFV#VyDv7q;T*}7A$I%Ss+BX(P=9%?$LIuCcfco)}sORMOihYyLQK0`dO zVtwxZr~rQS_BIrakddO_*==7d1&3>hxw>1W4L@YkG%egS1!LZaVjFa1S>q~gZWE*p zQ_loM8zp5ONL*dxd~lCw&mWaPYZ|`B`Z6n~zHnfX7+89h+bif&TH&LlUWezpg!E&M zKa!)!j@vNR+D}%`q-xz8z72j7wOpkMe|a=-M~}>Vwrke+$J`e?ttMG(8)oa~B_L!X z=>?4KL6C`nk$hP_N}#a0ntHDkp_feikAuY481R;v!)&xzDbwS{E&p2I+aDUKa{Aox z`hfq=Z=4Mp_B5?2iOgVZ>6oVh$U>ni8s1ac)nxdUz%|!BG}oZGcW@k^NWZ|~eMFXwGV?wmhT(9aA5#?E`Yy~am^Ca_`E3A2$s8c}o~U;ce5 z{U6Ru3jhld7@q8PaFayDCX4&`(Iw&Y^v^A6=#2o>__TJwPlE5coq%z-&nN8iL0 ziZbz7qC2y!(OG7fw^j-zW~02@P=1SE1prg}>%VlQ0O4>AIr|r3g#qYkgTEOpfIWOG z&hU&F0*d#r>dn^b!^`R>TPctl^`t852Ja)?=UO(!I^HYleB*blNceP58n1485Hm+O zf%JgHZJk1L^W~k+*2<26EWgW=pDo$ytu48Vxlo1HkJ!&GKT%?ep)IR2pQ&1l9$Yrl zp-UEnu+g8}wJAD&LWySxpYRb-bgHW~s2?O;>V+-K-1P8TeH>}UH+BiCsJOUO6L7a# zKIz$tA@jurPe1`azC=v@nz1aSVN0Lab(>q0@u*H8T0>0?0m;JSFH&#d{MPW}Jt<=7 zP8mwIQ>@fcu@9*GCb#F!Yb3hkVbaU+uh8Qt&Z@@@b!$mdcUkIT1z&v4`A|62J+e%~5@q45)V^3!Y`RKXWR zb;fR|?DzcUnYFwoSL+zgNn9^E?(MA8l%r+&iTgcarJ2(<_1sw;!SGzHrRE9@Q< z^A5bpqan+tNW=6%ULmQPCt6kB$q?{YqR0Sv{O3SsvDzCgR#i~fXl}obI zjH45Gr2cbgErdsEp-dG+rmppG)-TyXFHMxB{rs;QZoDdH=90&$sdF#)4(ea5-&n5h z7MFPITj!s7rdj(B-c4Z3(PF+Blk!&SGHL}zkLt<*Nuj}7hvC^Gz7xVnP1I~!!HQ`j zhJ?&ma=S8(q5&-*JYrgB;@L^H7zd_bBpi( z#7(AaY?(PK{zGv*eNUotI;e*4Ad=~xG|9cfQTP<*JE)CJUSli%mE3U|hl#&neh-fI zGlt(p?*8an0|aA}1ixpYx)H;%m)(g<&1g?PP(;0$I6Iir3r_aX)v1T;NYRG&%Sy9T zq~m45n{R@(1c`mCzQ?cz`ZoJm^cLwhiGF_TKu@A*_ufv$K|HgNVb_L+#P_h&FZG`x zzn2G?X(S4YJ~}#%{v1``oyFaTpYz@u(u%mhk{&`Tb%H4P&}>M?2|ptlSlS>HGU?nA zf*OY&D?R)qjoDc%j5o9?5j8QXnlyb!O*qnLm>u}mEZ1m;I72Y_xRIBO+8$$uo6osV zwB{67Onh=RI5X`=@e11owu7AOYH=12#TZe3S9soC^FiW^1=CeZ*1RN7;LNYA#TC6arRo!!)<&xpN8X$p?2V;+-Q_%;J+e7{zH zNjM0l9a_@Z>+RajABBsP8#514|9q&qf9}o}Za#vF{9DWXXDv?M zC5Ih57p+5nSrKMPjgXe(fU*D#v_ve;U-sd+DZ-iX(&K9)7f++Gc9G? zKK~MxziRI=WeTC(AS`9xDuxHx^UXTozC1~MB(2u_aAGZw&{Cly!PjMjnj?hd%cELC z08H59Aw1$2=lvkOQIyYgD6z_PpS=4xiE$Yo@%yc>%mf9I!A=Fl1nvSXlNqx zDPboJp_6g`aM;kGT8=@mXz()KcRviKudBwUaPt1s4!XqnGk^P1Ye81K2E|++;K^$R z3Yz$*)W8e8e>JRoJK?CBC@6s!)B%5qa!V|lK!xJ*dn2Eqj!r%9$ohwlSvK|a4|UA9 zk7u+Zeu-CiruWC+A3Ur2lkJ%xoV_6U;V%)4M-)K}BS@Y?VgK3lgX{g*p5M|U;y1+` z4Kj@upmVh<0!5c-)a1(+O|0E29(rJ9TC{NHq1vfPcl0UdixoqP%6TVsk(*1Sdq~xy zD{1e{r(P&_;A;YQ`Asl00Ki%nDdsMS*34UVB#VxM6Lk~$+xWp_9V(xK@gHxyc>4%6 z3urIo<;W(l^*r{S)>iiv)N|*IjhU^NiQ(NC3_Ujiq>V#shfv!vV zh5wp6BL0~>J_I47B<28b^r(Bwam8^HDh`7z5(JgMg?k`@P5d+J?(b}nBg_81VhP2* zEDHphz6KvO^sS-IGg30xT6odyCmmKe;Os=kV-)}KNjmXax+XLjH=J$;07zIPsx8r> z(JSgyN`O91w&$Pewhr0O5eFgX7_z5Qc|R9!8Z6cJ3ymcSNsVLX?*AH$7$L8lta&AV zZU05JX|0hQcXu3D`;2mFc*@eP6NYfNePJi`lLi{GE&H>cz^!9 zsHNBJAazho@SVZH{4TsJ?+DOn`Rhj8iTNgM4++G?`LV6TvDfQ4iE|k+1enK1H zp|hqj7W(;a=99Cd>S3uH)?5%l-C*}{N5)Cb-fvZ9wpa%V zN9rP7^p>!ULc?0TZ&5`^jw6VB;}t{!$bZH3aj`ME8dJ-Bio z_~c8ztGexy@kxpJklGFBXZ{N(PL;Gn(kLX3$Yl$Cy{mM%>66`O9jO0{kc8 zb{JPsl%oy_zY}cv2MLSO?Qe`JeIlnveocSzPL3*x%vhL$IJb(i{G|v=!H_Q41{sNf@uMc#50!MbYOgmo#$v#nz5Qj z<}sQ~3R?Cf6Z$+N`IU@E{Ul3HzM|$mJ;&LKY!3F2O_BUv8mPJ?cwLu|IHkNKG~7v* zDEYkY4L;a$@fULC8?(;~GA?@ZTjDcyQF>)ia^@V1Yq;~iE)bx?@TQFUrzVll7?U$l z{^?KV#-4YFA0)dD9&?P08zaa0E8&s-wY(p^+I~~Aw~SBHo_x2#81i|D!Z?Zq?n`)< zhzhTWGO4eIuG7z!^WyHYqm8(LKcB34v2P~BI5FZ64T*$PIK;;2rH-V(5lRZGNw(Pi z&O?g5=8)1(ky@1CW2#?^JpRmuxyz9vLxK;qUnhAhsV9Wy{9?=Qn!@4nQm{W^RpqBF zo}`@mhSX;-xs+;=LX13cox$seQVIceGu{m4vsc}fe?7d=TEff@17eEmQe$;eX_|t@ zbqv^gaVDt5;|Iz#E1-ih#6tq=JpJ312iF^tQCbG{^;=@EPXsPb%&s4B%>#3Hfl(vtzc0hx62(`8*5;6oQ ziEhwIIMqp#(tYQx`~FlXr9e0TtxlQ^bRdV?uPLzDg8cg{Sa@h z=Wq4Lqzt~l)tYQDn4i!ZrZ#W@XryRpOr}sYxXI{EsH^}eqT!Gaw#<$t@PZUhS`>sr z+L*@2n4!^_<;<8}`aZYMeg4M#!jt#;Rn2da5O}_1Zzohl+CwU7ShTWQ`Jgxe%sC!BIzTC)a4 z9iPH;-)on{+wZQvQ$ZJLR-^FEn4-Z0mKX_}xmv!Cy2ni2q>Q{^a@sotq*NOg%TJK3#ca9DLSZcx;)wMerg+9J^0d=E)*c;2G%iE)<==sBgn(qSp>i;s-`M8 zqbE{-crlF-UyVkIU)EPtN(}XK+g{QM5)QBxOX_~7&+2qTU93Z@bRI|rw`4sRU%-n` zyd#G+q{-LSpA6*wJXLIX+C%G_Pho8LP`L%l_KsHb!%L28D)kT3nrC7abWACQnu&A$LQ1?P zrCy^E)0+78S94Z2@T;j8)49)PQ{d~r1gB=Ed?>$I}^$De2}e!-EduwW$FD_dp{3QhNO`BJ2xZaBl~)YU6KGoJnwcR@Yq3}bRY0c4Q6cKA^os~#SFevFw(wvuho;F zp-E$&eAE7_h-dmmC{Uk4qV_>dOiJ4OqZdl@t%wV_qbl=|v~ugYyd*q`h252O24+N? zfuc|Sp_y9lG~b-(o~#ux{5{y)0*2>nL+I;NN}v6`i)iOGojeuVc^+zJVY@FMfnl&a zm47qc4{ApkU^?NA08FH4qF{@$h`cbyKca9tz{UvR*u`8~o6qU#=8SmlHVYH`SnyCi zgFG~&G5YC;rKEX!zL5{~i0_#zp6^@s{S|=n6{o%TSX@7sE%|CLn9bLFpg<)^~OQw9m?t$+lkrldOrQq&T zD)BPKr%?Sv-f+(t;@Q2<0Hr<)5h}))`;VNT!9NC=(OtBPU1z`nSHbCdg??+`AvCY& z`%3g9#kaFu>4D|4E#;4!eL3fx!0-w;MyP0}m_!gl3GXs&FEoS9Fy0Zxiiz*S`yPx z>GV*yR*Gum>taP?k&I^&8D<}r>`vfhZ~gc_E&0VpHqTsEkt=j=mO4qB1H77H4NC;U z=WUCjt$6Sz#VduqJjkmczSzL5yL0k}ik$bE8nI@Ujpb7!`R|Dw^WHHq*RL|UZ7Ax; zBb$gV=NHCRCIi1ne36%7=2XC)!Tjz~54OK|{dKInDF{|JX8)>VCss<(<)X5@)@dy#8@dZD9V3d^~_GFo=xt?`deaghqLaiC<+8mMRkLCip3u6 zjHPgn3)_u1W&h&88Go-h)0bWUMOjigTaff-lqzIm-PbA7vhYE6h*^kW?w6sMUq8Mo zFFp+wgqy%V$BpW-hXIX)4D2BAkekCm#Cj z@(06A)tfm7*xv_CVVj%-o3bfxBX>`EQuk8=cl%7Iv%f4CGascqK5AOoK7{YE(7nvb z3*V=i(;Ywl_Gy>lYWJzfnmo2mxr2XjVdaX34{~+Nzu53_5hb2Gc}BnYwBzI=8%e}+ zs7yoCLaSZYR_vX-y4=1>d}sS8=f&^%c?uW z&tCH(tWQ5L@(QWvO|f1sw%?X^{9sYJDG$Cu75qUx1_4%L8$!av>6N0z^1CC*m_+o| zcw>5Es0B^ms%Zm}IMy%l8YEFPki?3m88t>o6c4`RFetDmk=)Qp6SKY!VwWr($>zeX zopwr=jppN)Q-b+(KXPWrVE`H$7%jtgP?r`C9#w?@reDb#?TYyG)a7KPS{D+SoWl@HG?f zbll!tUtRIG%ZBWn!VZD8{>9nYMQ{ChDsD`P?Xk~wgQ?X9vzASV0XN+Q1{cA$J z_(e6|h852aiVw*0{HcYwP5}Z^D|M44NT?vVn}DJ0tYPA97&+N`lo1+gM`&60sniqWQ4GcY3a$EItv>{t4QeZ?N0 z+s;-D7iJ|+#gV2v@AXOQ$O)fk3?z}R#&?fFmrj4akrj8Pj(@{+fw>0-{FVf1r{$d_ z5wHn8Psxv00lPJfV-25g7?g(g7pc~bIYznV+c73lRPL<~Ho2l)s?Dtr{HmVpFT8V! zGi*abU`(~&#)zk`kM9#sErn_^;*RU^0Bv3bl{LMLah2M6*Ff>!k^6d{eYDo`8HLvl z&*7n@C5kYMM`R`x0}msgA3xgN`782R_yLWmq2a~RJrx=3>OB==z>=zTcXR6)#}-8m z40r^>N8|+k!4<2S$TRlp*reh-Crzyrq)mR2Hj5V-s_{DvKGiH5ROyR$gS9%zHh8@f zy>s^If%u*EE~qaSNiK34VnZ&@>>d719^W+_pwu^VKF%kHpU0^^dCr&|VsXzfV4c>Q z!%%suNIbb;4?CXJXX?9Vygf^<%0(!3C1w{mz}KW=Ja^tVPra`{Tt$}|{31*p+c8`x!9q7I9p2H$op{qr@fcXdmw`lWT`x=;>Ng>NF1<|IA#QVVX zr&Q@jk;=_u411n0!kG7#oU6s-5-4m!*Hdt>HesRS{;sO$dODQ19`PZ01remimf*9g zEUJUUVE3Q4B(*&9P*Trm4HHt}@iK8D-@g3D&wHTm(RWH)U8F{31vDR{`-EIP?P7Fi>faUg{}KbY1FX*y{l# z(0d7q4~ZGj5b#QhcP-*%vjA4_Jx#`W3f!VG-}GI)QZnPUxQYOSMzLORi-d~#@5Kxn zWuPFAI>mz4B;OxY-zRueSuFe_Mo*2AGVROWy0FjocN@|NNu6uOWCZ5Y^0S`rhpc#5 z&zfN>3PZ?$HfO72hFx7=X8ztQk?n{XR++YiW(k$b{|GRA3c}CYb1hX|B>CY#_%i3T zvQ+sn=11_(%iI|&0txYwAxBd0JX~0wQnpSb@%jjeVzy_GA~Aka03eV|?_#sD35|Eb zdKWV9mucT29Y=e;g>Z}_b??QFzy07{EaXRpqSrwDo)R&S@HSzWg4G z#ZWG(bdqY@y0`&@sJLT zTS<;JjUy~zjoCt-n;WUg@@Q7;zu3uc@Qxl#*%hPZBX4t1X z#^$)9oH;8BG_PmaF;mK{Kgk?tPa-#V4m3 zX{}cg7C|V`+y$wBr$PBg=cBof+ecvL2{reyB8&VYk z!>;c2nTuqba^C|+ysPW8592rGE#KEN9~?*BTyLs?A92f;(BnOU;|s9K3&gr(Pg5B7 zw{&fBO8n7PqDGcSo73XUZ!#ON`AGDq?vpN?Qo3 z%jsM<--0h8d>&C(Ge0PsoJ)kQ>8M*q$*2#~N0I6O$T6wf(N_gb#W1RAy-Cu>7?>Q&+h4ULO)*xeQq08l4p&L@=HNJ@Ny>Ez@W`+7&KGfBq2hjqz_z*&Xu zaxCrkwA?ym*P88W=A{N~u1s4&4Wv3~ULw^=r@Sqz7Cc%1inBVZZIA9}`d1B}%Xck9 zhpI1bmJ6R;vBEkssQ@}`IO)`SY5hXN?VB+bKQ%SblF zKynCzmo=~r6zdM2a)EI;ms2QTS*Xxfs2E?Elv5aBiDikMbqx>jD4lgzmC@Qi+^#I# zema~fiR94F2nT?5BZxfFkcRFs6;QaEToeZ=Qb#UQe;O8Kjs(N<&Jk)UIb(1`Oe z)o8}cezu%uw!AX7f^@bb^VsV@F=h1F*bmWG?M7hcT5t;hpooF0z}2=#Ba)Axa-FbL z1lbFZASPV$uM>t#{uM6A*6_tOIK=@FfaY_UMonB8JM;wxCV8I|;K5mx6wd^Ut2d8p zN{^$EN)Y0Z6s6>xcH)fVWSj>976;;224MC!5MhcK&rzrcH|K#7XODS2jtcy^mGGTD zaRih=Wd0^;3sx^i)~ypSKkg6XPpX|HS*Za65JX!>LZaPqOvaF=B^Zkb=`uP&#RDR4 zgiwqYP2PfNI3>}SCjmN>n2(a!<&&lBOk+mLH)_BVDMrC7yid-P8CsHlZY9BIU>v&1 zN}RmjcD()tyi9m+MFOx%8vH3*Bmij=0P`rhHvo{tM;cxSlfgh8FapfAAYt8iVis>% z-oMlN_U=hJnk5PR+cQ;FG6@&#e5MJ&r8m!)pjkCAQZdM9G(H)C9zX&}1N`HDvGC)~ zB0(2)@c;~YXba2>10|$l47o@{$)`sIq{lc5C0wL4)sp;OBKJfSbuW=idx>>W3KcHD zN5;GlcTSJKfX04HPux!Z6e`%-Er?DLYuHZv#E{XVn*qQ{T?{b|dFjj;sJj1q=KOzh zsb5Jl0LaY3mdxLqSw~-C<3M62Y1`#F-?>2Ra1a6s+C_tyJc(wFBs($Sj!qay z9`N}R7Cf^gP?`rOH-EoL0+`}w+`q^i%e_G6Ubeulw{vl-X*LGBP67}dg{sqM z0*taqc5*QMxu+L-u-4q0i`?oJQ2?hH!Beqb`Am-1Jno&mzwdJaV#G_M;XfF%f8r9U z0ePA7jHGu9$RFj(eaKauEnFc1+(AQfI$=Z^s=Lm`W`nBh9wf}mBzx&fYd|$NTdBSR z@*5k;8zaelk2E29#z%w2PXzF7NJCh}OOp8zTb-4#>(*Qx^jeFSl>G_q1psWn!R(z=1>dI@EtjDc@{{kD%cMZD9@uhF z7$n?Zw5ASZPFhj>NPgFbgt?1k5d%{gg)+{UV1db(P{KxUz zfwc}+ke*d6IVFVER!G!AVpfZBF+wKKik85tS5j4|2Z0eUyuszmxu57>2l=#^B`XDZ6&_fCPDnR`{1t<& zeTIo(z*`>Bbu@Tz3da9F=<{D>As#NY2-yK+0UL4c*WcT5rr+@uUSlU@w-c;Gqk2E0 zV_C6%J*a&~oAoM&!54iHp(9Nqm4!n^zo0 zP@OQwmo4;ncq=R_`@Gpn7lIgxiZzT|*yJ(L(I zu@4X{_UbwQ!-soCOh-hw6mFJ617Vd^@;DNWnehkitfGO9UTJ1V4Z=mf0Y_lC2&N zA@O58wG(yz&G;Aa4FCuKqWH!+n0F3~ae)ukm=BiP_K{+8QNIT#nJWZ4fisoEGfG{H zNO06;pAL2Zl{k1ES#z!`SrRL$5XQEO_?~J5xqy9`BOUgQ|H`aN7G(8fmTkJMlnlM{lHCr(}TeVMZx;I-Z zJXf#Gmeovr~oA;~cq@B>Sdc_ZjTO>s}v!tVZb_9(fh2QbzM>e?Ch*P}7i zCaBpDOLVhDqL>HzISZq)A^p9iNSHE@#Vjb>;2tD07bBu2+&hj9%BiktB?jqKujwC%HQl_^_10h2?f~S0_H6>OVj#yH;3nC|YsePmHr|=o z`)Z|?_bw}ZtOn2-ShmNOCj{`)Fi+8clgSoxpKm66lMa%DVXp~W>o zlo14*M}IZH7=wG^5(i-rL;^-Hhz&R2S!^3d$0z~_;t=zhki9N8=eMqQNgKg?80fU{=3o8yZxc6}aA!tMkX{UNx8cG16Q67&$VT;^Orjj_3MyJ6HUF@?6u? z)Bm&3^&g&VJpLc5YZM1_jsDx_x*Qt1`j^UeIy`(a+>8DC^m4 zj^z5=)_(E5;c}q-vOn*ttLWzI%jC>l%hKB#xTpylc%Siv5=PDt(Eyh2uD7vZQ znf#FSZ=S2Xyu7ru6lZf?<>cPJzk8CASyJ#Hm@6kICo3!K{D0V7w~0zu;bAwpxNUgE zzOP@#|1-=L6cps|@9*pD>*eL;;o))e-1Wj<#$ZiOb8&|1UO|sHg~z=i=iN5D?(y z<^8wK#lgV=hr`*}*jQOvSy)(@nVFfGm>3us{x_iu27~<<(na>aB3=KR(1nA!uy_C* z(#3^)9{yi>F4#Xjm&E^_=c?cAq!A8nz4+Q+`X8RFfnSf%(e6w7-Np}-73TFW^Mj2Q zQy*=5Vp;S)RnFA^o9C*stP>yNb2{Id1C;)o=lW><#!-j#|ITwgUx;rZkN!bPp=RE+ z{qY~3tK!LH$^JW%64c-P=Vbo4&bqp-jtB?+eKg-bh7Wz^D|b}a-$g{bN5T#d5i!T{ zTy3pqJEFI3Heyj-#s>=>epqeNoNNEW^}ZdznL z;;##VDkSD`q!I%?Jd{LY8vPpFSM!7U`k~Wu1ij;Vo-gUaM1B-x=QKZ>eMQR7kT=7; zK#f9RjYQ$4Gv8{w)UW1@*Zi|@3ljww8lD>58KEvhDZ>^;mX>C&_ z?sFr${>^h)`ED1dvGy)^rP-%CJEoGrrHb^Q_fKr-z38^!Lce5uyQcc$x<2e}@Sp9? zTsGtFd4R~d%|ATXhpmEmnVl`D!}Zcu(Oc7uGO!;Fb*WzFr-|*mxuK7Ele87QOMM8x zz}12)Kke*P)bwKo{tuq3lSpu{rkD1r0whWePszhYL(~YLX$iWeF;{kWHB9GNph#6T zO1H~gLw8G>y;4aFTDS^6kCsn+ZXA5Z^a~z-IsNtguzK0>r zIijm+=Yx6u8_J-J`Vmai(87S!7z( zs6lft?R3m0YJY7??{7ujkchV1&k2&lA1b6gG z%}UoE{QwcDRwePyfK0%mRJFZn=?K7S5u6+Z?kr}l>PtpXt9*@U82hb8qFOqT4P{OEav;pOqrRk4y@m?HVl9g=T} zuzj-iSEC0#W)sSqi+a@U=Y56Lo0}ENi`SQXg2nB3$G)1x*+er#033${%jC+RJv^f2 z4v>W1T!`40Lp_X|@;W@@us0Ub1)hM>1vVTy>q}4w%%RZ7C+==L)+BqejL)v$PY0t^ zTMHie{Nrl&Yd7tReFR?&8vx$}$vBINlpD&2Jf}y7M-BDWTOZQbqVwTp}Z1A)e`?jc{Mzvkac%M_{DPzwWN0M0>@SNGw{{dx}jsq zO2p`9bbcv&MV|mVI}u$8sNZ&Ufasn(YpMnTYn*g|vJ#$o&uG-!?zaFPgxE@coNiI4 zCwh)`nMYPzq1{W>hk%3@WJ5uvLJ$#Pvdrr94g2F&V0ap95<9t{&S>ayO*%em?Pei= z2o{VV3Jd@J(jOfbyOBo-sM#XLabzz-sQ^Ho9^Qt02$P11-!65uGE3cfWP>-mD2)!) z`4JhVkwGejYOV`l=SR*ZHM`P!G?^_vnK_qtG#SgZI&t!6mTPr#Fl-(1;b;uS)ybR= zKnm>@8g7?2WWNLMuJ^XK_y?|0-^ghxe|u!AMC6uxC!xZMj&dS_?2NmvIg-po?5z&Z zWIn|tt4Q||F;kW*m1n1&GG%SpJ%3m>K(2>pkOGMK4TJ!ud*%G|LOEL~OECmh`V@eK zSEII7jv;eL$Ig1qBWI1clGbBsFS9i4ULND=x%SQV>}auCs$VXMSY@OZ%)x9=wG*u^ ztc7RDcCE(p2NTInP={~R8^-6R&wn_*qj-S-<8!axz82Bg8>etUDH!@ z{XQKxPrJ58XW0_ct`};jLFn{P1#A^tqW(R*rpf~QZJ-0^U{Q(1%!wwR-0b3Tb;}e= zOd*>EMUB6rnRa%GV;2d;a}i;cL^QY7B^84~$+#-fz8>X4Z)r=CErv0vmIb3I4F#TZN1tLh87f@N1vF~-sg5aRSNhr2EGEbJ_9~`j2DzdX`4S!i3#{3k@VxQBB;e;N$rH3;u;h9P6i%}%J zqQEa1Yu{|JwA_!(R8ogxt<%bFCGI5e`Q~4)=3)VS2o%LA5+oJPSE)+j=Dor}_w{}2 zXT{UFbPrgK$jeq}B0600dY<=GQiK5+n&#oGW5*6%CA@^94eZA;(MUFnQk%B_r9!vMV-Rs z?&l{L6>*D~>ly}v0l88-GIH$b?5A8?D&K>)tdqlE>4bsFmT`wq%Ih7UpWNY}`n*Kw zg?cr8`=|Lw+kxMUD=_>tJxPBWTGYW6cK2(pN?DjjWaDPr<<#QUqWbN}cI9mi;lQzYQ}062X<~-)yf+Dk ziom+mh_A)SA@2W!8AOe0am_F+x_)aIzjDgRSjlg=iiHX3vEs)t_AE_;`VN2AhXKA%Rgz&s_4Jw;Lf9{}G#AishGsE8ovh-ljmiQN#sEM?Q5wnPev-dQIIBbb%il^v{PTn&)@AJ&h2S`fjwlH-_JWi6iguEP zptFztIFXx3jxi)>Eu)JADHAc%i}z?p@Q4xyz+`$*g~|Al`Pdi#NRbq|l7jLt0i%&Q zaWDYrjy6eYEB{f9(V&OR=#aShhb$SCEa8%7(<}f3E!mQkW>PKJqLfalCEL<1s~3_6 zd6OW)jjiB~4SA3cDUK0ok@;a$LaAU9Nn1rpD3+3zYWXOUvX*YCmY6b?R;h7w*%2pj zVR&$NC+U;Y2$AInme(-=rmze&FqZyQSCpU)@emKyfLQ=Q0kOai@~{gm0C7br5LWV( znzSDajljZ}$~>)8=rP+np1i_+pkfDFzc1>2cR@s$99a1TGQ zbpkOCmv9gg5FbA94>G_3bHD)%@SqSHp%OZw6k4GcdZ7@?pbm>Hp&~k> z7#gA^dZH-G04AEEEZU(f+M*Y#3V>DvC;Fl=dZQC+qaG>))A?c5$r_U243e;)xHMZt zAP@TR4wxkf_dpQWFbW5eL4u(Ob5NyLdZk#JrCPeBT-v2x`lVnRreZp#WLlK9aplN#W2W>j1beg7$(4z|XqpJZ0&VURKK%{*%TM&=~WgrUb@B>Whq)=)Q z2mksR3A&&SildS$p*lLLH(IHd+M<}6sVTatoJyjedZVYw1t=P-pDLoJN})VTpVSGM z_fY`G;0#^>sC)!s!5|9)3IGIpp4G=rtGSi!DR;q|5zPr;TG^B7*_W*9qpo@%k>Cud zK&vhUV!}`h;3=K}zysyUtIBC+$jLL`dN(LR1?5GLdG@Q{SZd3fr_FjDGvEx%AePd~ zK6NDuYCuM!un%w0o8!<1Wk3zX$*t&WkH!f{152>OiV@m(3=A2a1q%QviGzB|8m!<9 zg)pyI)~-+_4)>rA!LYB784K+&54(U-0{gJZd9ZkwtOk1$B+zkoAZzD3pFk-ih5z6T zs(`WdI}jpvlq))x%ejbqxUH+T6H&DB8M=*2wlq=&eQLL<8#b%!x*Qg+uREF= z(Y0UOhj@#pPp7f>fdKf~1-m<9O#5SlJG#QEx#}sr7*TrCfCsvJx7MqyrT;r4&uR+K zyJ*pCYiqk*qFa;LOPB3y5s-Kci)*~!n~v+6yiXzo@QMND3pTx5zb(tUzw5gNaRH@e z2hjOl>)SR97``$x0I|9U{d+Y33%i>uz%7Qs1kr-CtH8BOa!|qu&^p0JQ^D^Gg(obu z0K5=W*b2oYBdktG>WHz$=^(cgPQT zP;ed`!{V3%;y?>$U;}Tkb{LTf|G+va01Mtw599y~CnFGMAPn!|4!|%51Mvpd5D)6G z3o?eQhzJpB2fqa}Ak&2(oee1TudczH+pbP4N4U>Qo9pDXaFmVH6S#wba$U_AG z;C6qI4+SF!``{g;Kzsm@3%{Tcd%F}Q5V?hU%Tkid)!WOyOu#Ru5yc1%9ZYo62_K+Q z5cV+2WH1T!&`lO`3#9-6&@2#>pbi4z0qfui5KsZHzzuU@1NWc^2_OQw01N^_48{Zi zi2x7eEX%0@o3g3SQNqqB49L5D!AX1&Soy+Fe7ww25cm+V0RI3B)nE~Uzzs7~&?+zv zp)e3Y@D2O058a?j0@DCX|5RD1~*`d7pah=&o(oka3D!kIF zwZOir!ScutdEmtM9K-l59|bWEvoH{pa1JGw4#q{$8!cPb;0xhV0oHH}W^e|&zzr?a z0^TqRWS|Da5Da(W)KD$e1tFy*fz|nOpZUqvPvX@;o6>@e(z;9$3W=J=_Q3^_3ydrf zr9jgX;RpYq53KzU`=AeL;sMkU4AP?r=}<5bFb{zM0HAOU>1duBJrEtusPS>td=jKX zYS}h|*}SaTA#}v%Q#>OX%%Kg%31J5Lun9RJ2=gEa760J@KoH(Qa1FNr1hQ2P!@vOq zVF~DvDGDGD-c1TTClD_14`~1Z-#ifF{Lzw~AAIVk%3UMOtouC6`@C)M5GO9cZ zJx~d+%-?(htFjv4G&10u-Pt_e&YUd~EnRDgJUy&qID-+#0PqIH@DA-D4CW~ifq)J2 zpbosy19D8q;Bdz@&L__rtvD_tI{w@m9MABKW*Bjo{lL9KPRz)Ai6E^S?;5XPt|4Lm z&IOLdcOKmvcAAIW;0ONT4(ucqd$DtlA$5-6dH=5G&`stPQLL*Vv(-K1jvFO6o3n*} zA%~u|4zB5cp0WvEUPl}0Y<|CP-rxG+w9X*Rm(CxV?&)K0=C8iy6CtB64C|6^yHaAd zs}4ACezIk5>xs_jojwpHplNvt?3`no>&R_)54tu>Wdqhm_)!ySLeeDk6=#Vb!-QMOoZ0h@Qy2)McxSnM`yXmg} z>mQNsW<{<$sp!@{=~7|^xvTH{9%ohS?}i)f$d2s`A*07|tfHRm^sbNgt{=?n3|7GK z(hd{M0`T%q@tMu;3h}c2a0dcl@V7qle*Y4r=EDTbBlTzeDDn~B_izQWnZ7up7TYV_d`F{Si7*QzV$ud^`u_!M#IBCT=#ZQ z^8K#%VZG>p-|n5;aR-R!8bA0Pe>8hc=!nm*XHWH2kM^Grz(woQ6VLTs8R$}Sv$nkX zoPYPAzY%&b^#U&uSg)5bKkBF-CFkr6>CF0s@A{q(`+Lu}jvw_Ap}l=x`hkD?2=6B% z?fa$P`B2aE?q2=b&JbvI3|jy8G5;TaV58OA3H?mb>TA#V25$Od?hqX3apjNx;M@Ft z;sE#w1>*npO)tH8Km1ca{b|4a0)cb@0SyHJf&~p8M3_)vK?ZXeEQA}=*Mfyn_Lba~lii16BC2Z4eV#Wpw7<1;O@np)CEi2w>6|P~ze8GC=3VN&P zrl3#tJ7z%eMaHBFBEFn*asO<#k({BTom=;A-LsW$X5E>y@ZiKJyIxJvL9~8^lp;_5 z5jJm+zNvGi;cOX+>)pM7Z)%+=@W#-Inh%Per+S>87xja-;rVd8$ftvcC?0=MR?hb9 z2QWYZKhlpU@>-*hE%w?=aIFPx@+_)UN^4Lp`!*U-p#n3UsSsyW;V?uI1>6v)0~31? z!V2jsuD%t|;;V^%__>0@78QK4Ck#jIDl;BwDuEeiPWZ7%BV#M^rW1`TFUP%{{0z#` zoJ<8Zt5U4#LXLh+@<@_L=Y|}=GCSZ<^E8~dE&wEjTs7`Uy(Oxs!b3{~4EyxsS zB4IXKX)#(BfL{>#VGLi!>42bNWN9JXuNJx$&SUR9_fiypP4C4lW~8CmCesDrz7VTr zwhOWln6_Vk55l*g75-7f+gC6ux6yfxWf;?lR_Uh|U+InRuw+FHxYP!aab}8tKkheU z0CM;T2yfL{hZ|8iNJs(@UiRT18911O0|su!IcJ@B=DBB|f5w?+n}H^}Xrp@;`e>z> z20Ce`pN5(Nr~jj-y6CBSMuE9Ks;2sCuD{;dYolej_})%IPKYH_&}O^Tj0@<6n1UvG zg9t&)*(D)QW|dWuIsOJbaKQ&Byl}%0M?7)G7iYY2#~+70a>*yBymHA;d&UpTH|M-_ z$`vV_Ly<{c!Wm^8XghU6Gmb@^O$~D69~=;J8D^Qq1{-YLbN_mG-mCWg_o#yxo@w7V zc%~myia(lo=9PAyXR=?%_-xeycr3E(w?8sqSjw?Mp$`6e1EPfUVz*t2fn8tyg%zSy z8tx`;*kbC<9+!InY{N}||MCCG0AO(r9V{db{~&_-HiD&@FtCB?TMqW4u5B7?%n z!!c$lK>>i+F#=#jhw15l9o!=KJOrXA*6}(@3`rN+xUMpqv5z##;Y+H50%-JO5nj|F z!a|oJJbJ1G&TvKv>^RBZlrSfHAEXiAkr(X8y#nS$hJKQY=#bPl1AgNWuqD_Tktj+A@Oa*0ZX+7@}D z$)z*RDM)piQv>LsAJ0IYL6xdZk=AhvWKqpfwMr9~+UlrFP3k$P8c+b#K$nl8DOj_~ zrJ}YC0UWEsR^=L#uGUbND7hsiXOHlSe`ViD8Y+Lk6X zo{HU`0XQZF)Ap8HsFjID<)zk-uJ)EFXhlDYQCa5h)V4jHBx8L$-H1e1Q-1{scC)+J zXCn2QU|^19T-)5*R@IJHAPYpPyIz0+HzvYGmqzz!To#=GV#y!?c{^KP(AsfhCuMJd zdxTq?z*k-Ll`4Y02!@*~Sd^dT6oI$rENBUsz1HQTYW17o4Hp+j_I;|Q#yevEMwpWN zGRB}ROkE5k#K4e}ZzjDfDJ~=rtqz_qLd|PO2ZYK9D`v5KVe;aN(RRN_&i~6FoC=Nk zb@;)EH8CYA4CLvy_#i}PUyLtG+`WK7muoXJhn>4)J2o`MRPL>nkyTDE=a|GuKFbE2 zDh+Ff*~4S*?<6zeO*ETU%>}`-`)2%P9CKw0QR$zZ39aKiPm-RE=yPfR{2C3vSs4t?J2}*F2FnnlQcO_G7{a5LF!w;^jBlcP ztEvuk1YZi%Vb8MIDbX%Q3~+}b7PQt|hB89-Hmh!YN7Y86rGYf`Hu*kIK1a236k z8YCAP$JQ&l{rV_)dV(7&RDrd-%{F3go7=fgEt|(}>wQC8Ez2HaB>&Vc6z;-AOAGNt zHUM<(B9TByM6$O~fz4`IzxvV@Z%Vn9>xY2@w&UCVWhp%|k8^+n7cr1GzPXpmh)aCl zDEYP+!yVse6NLbL&|1NXJ#$L?;AJ3?z(L>u2qL_J8sqSQcNkuzIksG-6W4d9#VvK3 zuSMg&BbGmX;~gJ)oY-A!06;xOV(%2c+m;k-kU<)Pq5qB*eEygq%)scwS$fvP zxcEgr%jEMrdxKVI z`6wULHel{PE5G0Gsk=J-U_q{O^9y^`gPiN|tcgtchl5E0Sn!5=AO~0wfr2mtVR#33 z0ERIrhylO^Z@7nZ*o1;$18lg5Z=j<5C_A<(owA5O`3u23qPUAw!8>cUtth|nVu=3h zJJU zK)4450Dv;s5hD198~^|x$cI-sh*98%g2;tm0Kvo4AL#Gciz5onQZ6-I!^ab}Tf2!s;06j9#atu^6&Qz5CLr=xCJvf1OHv%1{RWqf7k(nAcKE+6?J4scRYw` zn-zNesd~ysC)!7UtiNNtzot+|S}TlBd_I~?zfZggKllfI;K_g32YpBY0Pp~62nK2- z2t`N-^@4zT2m}E5gnTH73LqZMYq$lI0fA~529_xZOF#z|Qvi7o1ORvg*&&EA&`1CVz1%&=t1s-wS|D9gX7vw=*@8eGd8qzO`F z11XXjf_MXBc!zcnhBGJ#7ubb(KnGf|MS|GCdjN+IR7@_Uw?O$#{|QcH6wb-~$DpWz z6;T%7gqzM7|q-an(%{)HHgGK;~sB8n!?Ge!U zgwK|&%$ulzLb|bo%uh~iPW}X^dYjMyMbB6I(3;##aBEPM5CDjI1`NQ@`z**5Rnd@Y zv~Y5`At}++sZb0hP%ruA(QQ{m!1*Sw29IJ%~1D5)BlF$I}wQ59Bkm4cvv zSYQWv*aa5ws;H|{DJ@hpy@?Bw3Qz1(`wUSq4JRkHQ-7(JYsr>v=@tNp1#)nMGN=Y> z7*vCF)E4DTQU!_l=`|!ZRV95;I8rGwoz#$dxq&Gd5x|E(Ac!9L2kn$BLN!o0mCRtB z2@FUcVqw%IC8N${%Y{49wt1wqi&a@QNrE65lZl-XD2Q>m1iP|PRee)K{Z*AX4JHH8 zRZZ3<#WkSdedU_y@z^kL}c|LyNw77(4|$_zjFOnM2*vQ6{<#XhWbR?LaCM$N}+Ih$5qL&y^{hD1sq!1pj6{R@~()&JJk! z2p6b_SO#OZ0imd}hz7vkR6j)bGM1Dy8R044|pC>Rr==8LXoUT*4+(A;Lo z13QRdZ@y=HHfD+-g>E5*uJ-D#W@pEe(4p=rWOij(R_cmIVI+3n6aEM)=!brA1Um== z-+knrW>FcY2w}ihVesp}_Uo{oD_A9KoFxgfCWsw~hfP*%1_oSf2G>tXhJHW=J)r8X z18L0GYv`J*on40DD{R9Cfqn3WT`+B42#3T}lBK@pr*>_omIzenhhzW)J8)sm#_LG# z>Hm}vfszJ*6lmv~kmWLY=Xefn{P2o>$OT$pZduTTcuQ+3M&+x@nG%9Uh9``YlC3pet3j1AZ2hqW$B*o ztnP?*@BxG90d_!dxoRkxWbf|qiVDEX7`Oy2TMxgtOdU#k^lxu0DuulhjOR~8INw-<+dl4Qj^eT zR+s=h=xBj1^6nmSj2MGl;D&3Mg#uFXtr`ntSm``R5|YpcOLzfzFy1mi2ga6eFfa5~ zH;H|Ih7;HVy3T13uW$PH-g%xYpmt18uOtxo1AN#A9@d2O7IZat^g*9HkWhjl8iWs+ z>Z*qH5Z7%+ONj*d15V(CKM2Z9-zs`iC0@@Bw`c(}P_HxS0aQ11>CJ6?9zzE}v;e5> z+dg(R zCUFx7fH9BUGEJi6DW=UKzvG}%djCN~lzV0G2b3VwbnWy(OkMxNc0bbaLd$@;v;DrSwjNvYnXO&UE zZw#;4_s|dhqi_6ZpLh|Ei2FvX4XA@gcYBLY_%(wG9gqV#07UZz{QuN}j5hUr+y?v})^X}@)8HZAq;eczu2P%wy3m<7^T z{&^pN>Q{*OfQEQE0Xw+tm4Exf*OZg^>iGxj%+LK&`;hHtXL!JLg3tk81PA~E2NEo3 z@ZiB0|6VYd!vG<~h!Q6vZ1|8O#*7**YV7E-qQj3OMRJ@-16sdD00M-u17>8#k}zjZ zlu7gEL7N#BzJMw0C(xk6a1tE|;va~jN|!QiTCjvOW*D4Ot!niu)~s3y9tD985kW-h ztn$>kwPwh(8`G-AXtpiHw*?y%>&J=!fEsq{Y_KX9uED>63I7U)$aC=7u80>ihG@*0 zmBx}MQ?AUkYo>az3>ktoFB92?g$Iu&&DL^hz@s1adsYI#0zP(zTulwvc3a#7597@7 zrUHNgmH{XpZd|J*XOWIGZ|d6bs&r#oe)(9G1_<|js+#C)q=)_=+}pg z{aBS?sPvP}Q~-csM;HNkIAUc(QWf7qH=#2I04f4-ga14(CY2+Y1wB?pm}Q#T+>TlG zIGmJDwb|60O#QV-KhiiM5DIqKaYBSaE*9rfRQ5zuJUV2FUm5Ipd1jcVD90$IkuH`d zR%*0^sUFW`v`StOx;- zjxYD?&-5GcHpjy!F~UQ-1>pSE;eucIs`m#{sI;TdYAdgFqA9G23?l_v!Dy z5GPb+L>+kJ#xUg~B*G@S_!5c>!x4M$a05Ix1^>w@t2~inhj3$$J=z>nEJF^9D6q{p z``BI)(eyLOKwH?shXD;stXj@M9$k<^K7jDF1P9$x3IG}3IP%JqIoe3pU3=XXCi9FU zha98Kb4h45FYRp7M7BNU+iq%i!7=@);v@hc`W z8XNSDCx$YIwbzUJS~=zs05FwD&2wif`KG$5*f^n2*4%ZCMEaSlO%>&z&Jvk7hgFT_6PVn{E&mOSs1PxLr z6$9m&#|MDpy#2$q4|$EG_ys38@r!)?!FuS^8Jiwhx*zJy0d={{K+vNe4tB4J9RcA%dKZy1 zyaFBb$VCfh*p@;#14CN;Vu2J>23%kR8@M0?%_cY#HLg*J5_BU4(_)H#G~+cH+FOU1 z7(^l}O??=VqCxD3KmBz;Wc>r9T4>-5WKau{j-1>f71S>$Udn@e1OT1*(FKCM4sYh8 zqyuLM#g6R58kb-JB){}Xtsnpy&i|mnDq~rht~{-lAn*VLdXHs)gNU;w#u{n-U6u>DB7x^jqefP!qGAjc#&;SK~IL=C+-$3OfqkXjh-AHR^u zH^tdbaI(n{syI^Xl9-o|Tb>_j5r3`xMYwjSw<9PXiwSRCr zuOJerr4Rlg0}jlA0}Qw>cC)M9?Q*xf-u*6iscT*ElDE9(?XGywtKRj3H@)nA?|Vs5 zH)V(*yBSa?eDmvF_v*L5@|@v$(}Beld(=EaMr|xW+cVF^+Sr;~me~ z56EbZAy&L3Jp6&jMm{oSRzOc;_(iG0HPcA;07Ed@>)s* zAUVsSwv}s0kN;WN13#AVg+w|qhB5r(5@U!#2S{-S8Mpx(-iX?$H4D^vvsE%wkj4c| zq8Glz+SDCYZK6eTzyvO^AmSny0D!OyIpDwz-p~~QI=~KE@Zbl!KnH^ua1CE9TOeuB z2PS*~3VfgtBGaa{7X*auY$F95Gt&|o&>;~vl(-fZ0ERm7Ar4ufG9nS}H@!>Un9yFx zNgPoa!+>7zrK>gIAF&}0b;v`5SPWy169^#gp@7Cxj0pdbour*bF{%U{U^|LUMue2H<5RM3qXig0}MM?DJkBqU5XOtS% z04b13sQ*JC9$1GbAW(rrtf5o^h1 zxVAk<-r+Z$i$#Rp6Pj0BA$5M~Y$DAoND zp8y`;;&p^AJq<1q#0%&S?>G(!Sc5NILtP5~xm_TeF0CeB?g&#qXSVNUx z`V9mZc~J>!RaXqaCdh+*)I+V%UjXLb45|fdNW-KJL_;VMwhW;C`Cw+T9pkA4c-|Cg15G)cp zrJza`2L$}U85B|)b=FAe)f~!U9r~R|EJ8p0Oke=QhU5_tx)rPiAx-R4Kgq#A1=K(> zAqkbx2@yv%3{JWTPY>8bEcn0= z+`>DAOjwj%8sq~e^nfRjoa&LF8b;GJt>PM*V&0KjAaWKS4$)vtfzOzNT@8d@4FA(E z!eTEH;!Jea^n}$|8HCl)T#0cQ0K5S)yhA$(!xfc*8wFo3xRm`87g4iQ_nW zqYR#7YR#in1Oce10$v!z0W8cqX=Fy$pgqC_Vks75Io4#f;-gJLgi&Nlxg<@zB03Ht zJ)Xr0SV%E2&p`;y9l)JQ=HyVu+fC%wZuQo01=nyj22FBV1~7v&{GLo!(^JBPO_n4^ zo|;-IV z304_|0mudy*x^UeAxRKsVS39imWf?bn6=TRRYGJ_;N`!OWL{w!mA8cE<0l>GlrW!&8GYDmDI?`-DmAqMIWftX9uts@61gX^3aK^-O zl4o(=VRDXy%N+^;#2j?0;mK5IEL|tSji+0b=Y5{%Vd`h9sYGY)MPJw_MF{AC;%9+^ z)J@PGd*0o9rXUQ3<&~)dpPYayK&X61Ra;PI-=(EiIz<=Y+h`%g2H-)`5vW9%=!qIA zS|BJ*%pQB%-YiKb?43X~F~hHP#6=~86IjTNUTCn;r{ZNNcV6a@-v2}qpad#>>sOs4N!ghFZl8 zG=p6T9z?{WX#pRVf`opKCWlUp(|H67y5K&*;9JsVRA!koyq-t&LE-enotP;+p{Y`+ z=_l#sO;$xYNlTI-1k%xl4&G@_c2@x~1=NM_Ndy-RP0@6!s3K=9PHK>zsYR-xY-Je=W`rsfjv??UtzxKJ zNNVg*YKIa90z}I*z*0mAU*Gg!v6`o@wkg0VYiy=mmMudXQvZZ4#LoawsD)Omnb;~u zU@Pq$Yql;${ux!HLc{^6Q(%B7hs%vaMMwW#mMu;F3UM#QRD**~=$D*rtdPJ(tRk-TO zxE`#*maNI94|b|7WG08RYD7K!!!5`x#x83)+APOT?GN6B7vP&M3M|2f>d-#Pxhf#T zGG@kNTYzL4GN6=1^g!WEqSMao*w*C6R;}FfB2hR2lD^|lZdAhN?3&&z*!C%-&}?DN zh@m13MWn+&OhVgQ>sjdQ$?`3--o%^Q#jy75@a-*|_Wv!_o}}ACZ3+TVmJOCfR6^k_ zF5^m))Xwc*Zth21YB6N0*4lxo#6{2&>(@qZzJ_g>2yS6HN|uEvL`VP^#)9c~ZidD! z-DWQCj)V~%2~|P_Q1&3^`t9o`W*7EuJvxKM`UJe zfU87^Yl@a@e%@}sHl5KzrXm^Y^A>~$6b>weZ>_%VOgJvlqO8Y$L~s74L}bwHR%zD) z5#)ZF?t;nq{#7d(YRDo4FBFdF`ETF?Fjkf?XKBC#j4%n8unC_q3a79NuW$)#z#ND$ z3&*ew&u|L6Fbvah3hUv|%y9IsXao0=!Y=0SdjBw`MN^j17DCuS;g}u=cd+M9CI};j z3tK@IRIwFbF&1aB7H=^ZckvZl!5mPr7mqO+m+=;Zu^5}N7B2$6p+XsFfgaew7sx3C z6EMyyF9ZW_0TJ<|(NmVeCPI|MKez+hHnG?~F;fUIR=DsKEP*3GG9*W`Bu_FWSF$BT zaum!#6kIYVcd{o}awc!`Cr|Popad&;vJ@-~7*xRn_^=&o?)j$dqatz%E`gy+#X)pH z;h>QrJMrb2jfYKP&S! z_cK5P^gjc164XUASOGP|u^nW=5{UEr{;)C0@51VFJ^N^2W!becTj|oXFJCJ@1BN~a zv`AO;K##OZGjmDvvynu@9#C@=sIm|=bSpo!InOWk=5hVTX0xgsL6kw^5D!Q1u{{@s zB40&FpEObol^EWp^OgnTPlk?-^@kHk|WLANpE{_i4!#{vSP~7TAFvWC1bD^f+sER^Rki&$5qVfK+Cg013n_6wV5i zwNU>u!Wx8HyY)%KHDm|0WHU1r!2c;L7=cT}bY5FE?ZWSYN_1b>ELTJ3syaifxKG$|K7xa-xfm9F85frmt(==8OFgXjc1oJVaA#E1{fCzA* zITUhh(-3lFXJZ$HY}X%4zNY{Av1RE3dD79cQ$u7e_L}~KlL6)H8o!WiE_a)oA+l!G%`u_dQ10Erys;- z85$H$8`yV6zjk#K#D4!bcL%tK^Rs^o!5*|@H5)-o@WF4Fw`Wf;>sD$_|26iSDa$&; zH2gykVfcM(czy#whle;yga0^?leCaC^EOM%ichn6=K*;qc#CswjE{CKw+cE#xT7lf zG~j}cXZTse_G0|_kSFtqhq(}Rw-NN-6jbvSYzTrQvx2+$l;5#mKls(Ocb5gom^uS= zZ@G=AGoNnwK!7=!J9Ci_I)GzyGfRR|wKO#!foz09lC$_spSNF2dGh8iMen$e&cLhQ zgEJT|pR;#_Ypj<`u_hb(ha)HU}#nT!AvbIg}5#*9LKw*ZHW!-T?GM z{Df|(A9t_AZK>z;sjqsFtGco)b)g@#6qu7{Cv+Tt!7|%=!GiW)qj#>SD`5L*DHP5$ z9PzM=I(}=rL}F%gw#xJ86G=brOy*oS~uCtHA$OF;t;WM;8x+ng5QHB)10a`u7-g(MAyjb% z2PmLJJp_YS{r|baul?J@edf1)GV5?5#JVuidfrd^-`_kC$2ix=$l1%&92AZ^psh)L zDeNl#bF^Yj-PGe}!aK|X5%2;y#H{7}{XsB2nLB-mJGB*n3MynX7VM3+PqWoOsqj-g z-=~h18U!V1Lp;PoHAEY))8!!)4m`l&K(Mo+k_qjLJOG>30H6bFGq*ipVZ5cik7NGZ z8^4Dy^}8QK5>&IJGYLQ#5i*cq!GcSwJOHqeVZ((C<}h$Lkzz%Q7coAJn2}>gj}9S9 z{5X;%#gHXm{CiX;Y_9 zp+=Ru6aS~qn*aPPyzy@gLt?KcN&qp|$3Gby=5S!JmTg3mOxX^Iq7`L%#lb0V5_bc`s$*TUO0(N z4em0?&_fYTRMABVLShai7>!iYNeyxo(t%9r2O29TJt7P{!Z?CbArMjsBSAq#HPwyI zRMn%Dw)@AEi6F?K3{lisu+EC^+|}2eT1aQ8GB{$TI7WU=R@r46>eZt>2SA5S06?%O zkUv#&wL?Oq7}eWvD}5B)alN&4pgpAN=MhS|umg`Pye%~&Z8@a3URKGp7o(K69RI7! zih_}aS%#b)*x-q#8;XODBq1PV*MxS0YE{=o?v#^H(Q^#E%fEJ!@ZR4x6RG;87d}i;to5&0GH>B zh-R*DztQgSZ-AVQRV-cULxtRWsCmZ8u|;iD4Xqyh5HIsZxPrvM#1xs>0A zTinvwwiMld7MawDPx%ma=Y-}BJVMcv!yP%@0VtfJS;VVy7Vb_j4uo!o5i+I0__LLbuAI!W0L zZ#B~!?Ru8L4}owhOq2=<4Me>Y&M-FxnA|_gQ8k*(;7uo>;uo(r#h=`8P-^Sp4o`Q+ zZ!tj`L2})vE~7FInnZ+vQ{ocqXh)Pp(S9`qV{=k)j-g;@Cj&r6asT%4M@1S>Ib>9z z8Pzx{9!649nSuu0B-JkTt!$1HaUxVc3CcV!2Z}4Ho){Mi6gO zGJPezX9rmtLY3ZYs<+E$G&$GPoiZd1@E8g&S^$+oIOAbkH7jzoN|K*OD5yd$2vIf4 zihdk}Fds$K%`(U~lQyKEOzEp%qbgOG0yL&)B?$+Jv7Hk^g$B;hkYOP^m9&mzt=rS3 zTib?NgA}44(vXZ&4OJw(y=|`y`Rh+ki`u|8@v3~J;qfB-5jbo|8zhs8A)WEf*zT4o zll@3#AJkUO!WEq|>jx@?0N0Slj7T5hQjfiO@~MmXclZ zQU$xV0WO1ti&^6OGE>cvLUKV{kjm5nUd=TXGNC&{>i>!|zxwSjMX0343m&O^9|k~bdxGR7m$)g`g{g|iI{-^; z#}XA#4pI_XV=eRQ#!|`ga(1lI9-na$o%KSa;!DI(71_C-WHL~c%#%3p#K|eHaSYZm zlyf*wIgM~e0Jj|IW_39#Usg_-FFIx&K4E6aMYCOn@H)$ol+E|WXNZ+EXPaocCUt)8 ziVF~m?ZARTN$4g51fA*!bHvc2yR2q29A9*{_x}lR1uat8WY@fYGn`LMSSZKV z2kaP1Jc#fh1ROF>sSfn2Gtz40AbOpOX5fW|_-KP}AZizO}8<$2{Y`Lp_})vv9_O&phwBDfdUt4V4af!wtg#i$ef$58;%- zKt%XQ4kqG@S)iyF46%m5LKJ#xf{vxkV`e!1yL&64YTKJYXF>0Rpg&8~DsCNMRw!;Sw0)6SP4^ z#v&yk?x6s|z(zn$8fzIcVEh=Y{Qo9G+IS=6d@1eNMiu6&<=SS*29EwL4XS#NwQA4? z(WL*HA`rNNWCXAwRA3zXXCZ*#8}?xzy20X}PC*s|ADnI>Dj^-RqiZrSoT|b5=wtw( z#|uPoyhxC6&M%kJ5B5~>WmabpU}g@k;BMATjdm|z?hpUs(APdLz?k9%(jnOb@c0%2 z1gyaqM4|$$;TFu`40M4Ttc)SrU>**EA)JsQqR;|C00Yfx1@vJkh+$#sgg5}L3wi4c z8^Q!Z?(Bw3)_SO&+z4j;VC6=NlHPDtZg9F{vAS$dD*WId^dT4jVITA%0RX@Qs390^ z3jh=$9jXQb=HXfvVh!YB68{<^0w=Hnv#$zM=>>veDDr_=d<6X7fGLIC|x8*rcnbkY}lz#d}32Y%od-k~}cQ51Bt1uRE8@&OZi zz!N+V^d|C)ct9P7LLQVbS^g)yIuf!zvf(_=?8Z>vN|IbSiuM#`2sn%j&36#AqJQkkgfqyQU#<-S`b7^8U&<6K)Pq>Zb^ZmQ>3J0 zkVZhdLlNFV^gQlbGK$RRA6%>o31w33iL6zv6IB>M@f3n0qDKL zWi=7&P08;hV)kURceTZ)qwce?^L;G@mdeyr-S2yE)_1E_g28pe@Z*Y1N64`Ef+z4v z=WRPC2o#>;3zkL6Zn}!)Iwanr(M-p7&Rp^eQ~doL638e9&Pqv@lBHDQCpzScoC=B` zp2==IkPSY6$h;q~xlA0M4->Y=HdmiA+sPN5+*Lh^Nq5r#bqzxmZreVn-s@FfCwO)k zrx^G}wgx08zDC;clTHlf+GInE9#z37R$WQC-&Y?#C!n#YOu0{NZSH)dR(CI+NA>iD zCcC@(dV*Bhadedu^BlrQ4WbUDRPz5UT#~QuzNHRXS1rl|lUWKxM@Y<)Ybpywt_d(X zPK~PD0PdTK^RB!~V83p;qiw6K-jyW%`h$cD0p)xZ9Fs7K&-m^h>`E`WR8NuW)9|rGEfRCmS&Cb8L4)m4&5|jT-=7Th z_Y6Mtsiob;soG+G7LV|8GqR4X;?_ zD4B^Xb$thw;x!FMtLr3c>yYTrSjB$1L&9443sq(}qs09|v}9VRZpPqM-LsN#oB`z9 zGp(?Md~u9`t+kD9KOfKdsNKtA9(yNv9E$(Q^d1J*YX!r%zEOE)T`$`zR3X)%CWf{R zlO?Nn4ZGALCPu=9@Ek3b9DB9QzIzzuG{6`4{dUjZu+Mf>Hz+m=3Hs02i*7%bb`1PZgS8a#)Nokay23*-)bJ5sYmF>&zwL1Mjf=I8_bxG zQ``uP>Gh#!DKWjU_Wo&9z-mlO`0`8bObEhndLl$_&Qepa$4lpRTKemUb;} zT>o0UCGTfT6KhA4@7xKY709l?$>?@2XH-Np>mq@o`GMhFEZ?8IzfaZq82|7A(w0%XC4@<8qh z;<7YRtn8gnSw?0VxG;8|w)mSxm|;s+k&ix;1Kx6;5JNsne+{MLQ~25V{4#&?k~hVo0Ml(yDc4f9mnkSO_EF*W$Dgc1C^|zey14bmqGM6Kj|TcW zdvx-77E&3kQO$1YQ`rW2Z@SsvO>brxie@f(JC%uQQM9s#psNjqiDX+-8=6?eP>eiX zHF@*VS4|7Nt#A<)I-aZAkqp;wv~J?9Ub!OiFML@o((7x4n|f`dmCZ;k;G{t^j5_E~ z!t@Q8MkQBYjcR~W9MVpABZTx`ShL zqAfC_4GM1>LYJ*B@|e%y?g!!~0_uiFRLL0!eW}6z*Vqn%;d=?^KH;*|=rWPZv2sG-y(isvTMTcJxZ5Iwm zihPz4=?h&Z)_Dl&ST3z~bZq(tZ_CP%SggY;8a3A=gYsYgq<^^)>8nF49l*g6$4k!N z`nt1*^!3nP3H@oa{VUgFNZHYQ!yQ`cUa`wy-Uvt)oG24V(*C_UMTcu(qoj19zr1(=ffnK7JAnKIDM$rz8j$BZja zI5IN^@1x&*6`#%hm8Tt518m-HS1@%^r+l=S_`2S@8yaXX#4xUu11I#z0@!L&1r^mnF zT(6XUZ)9YW;ug@c3S}imQAgy>5@h{!|KTH$v)h+p8!f4^k=i}+U7c;~GsW%qm!dPa z#y>3m6Yu4$(y~(ZAjjgxH$A0x@-*WE103TS^lMDl4~mzG@^3ElpaFU--voYae&5dO zKtIBz!VGnR)D3p_q{e+a7L>DDRKE{Tl8`vx{|dAGI%%@~*tffje#0;TZQsrc0#J?O z*!{ZQ=ge)Z4)AD|dQ0S%q-ZidXkul(ag!9VPPw#KlKsQ~2dnuC9yqi{tPnnz3#+2_Zr_eYDioj{|(Zvr`KphF<-E(`!mlV zF(=QTjEVbSf5Dy!;v&#U?Aa&Hzw%tfeuuyDgGEUg4B8?N^TR|nLcIQk=VHUCWa33y zs8LCI>@E(PuN6MkzR??O<9vLN{Jn(t!?L60)t)F?Y!&?3Vd+E>Q8>SU`Ba%^#3PhJ z`%wL|Or=q)&keCqk9{^jl5EEUqLU~WW-5WB=mXqzN3h_sze@+gjDgu3} z&DXwUr}|Zo2_{wM7XH2uuIs0Le{?oJ^knwjFPFu2M>qEv12M%SLjxIs4j5YkW6$4= z4Vo&Rekmd>Ws_A{MpEli;CPmQxN3B}O4_Rtse=QFA*LDL2*_(lQRqcRD7K>lWHM3U^(E zsB9--)t~VCD4Ag1Nz~UTKk?J8&o+vcp7Nit8M-gbv-x|Q*S|{Td$Vqh3L<+}s%e-x zeb1AjS6|cX=R7RTn>o)miSy=8H%F1_X!BUMjrZkt&R}GVQ3{gDz@{8Ka=lk>aZhX^ zEygEA!Q`QT-nT;M)fD;1H#|w(RdvK&WwNMDcb?k9g+>QC{~WHn67v$^x{n@uh_RK2sQ72O%Nv$qp@HgwB%99u}~3T_Q3#6NEsGxvRWVyzN5yVtlfP4{mt+zpz+@~uoWVnC*_Gbu0;uq#winu`~Wai{Uvtq!x zl5yp{)jEU%oZ>uoI(p|^<>ukmR!{tk+rU-BA~EYPlhZ;?MrcRf=~QzA-;+11QcEs_ z;h9(@?$wJE#pB z8l|q%C3gqSuSW$MDwOdsoquB^)a*9>_3inW96#QRCu0r=9LvF}hl+$f@HkM2iU!kD{~fP6s%8l});>gr*0hli>tyo4g3y7Ph-!)gHX7ByPT*PHBU^xw2J zP6!(=R_cB}KPJafsLQygr+DplV9mhILW3bxs);z{P<&59F7r0zkp!70q2XQ1P~Og+ zcFwq$@9!qTf-VD zVp}8O5f<%#&B7T-G<+wN+>m{09rvpe^}PjTq?+43N>033b|p>1`s=s{*&!;`HvIfK zcNTeriAJ4?dr}l+EMIHSeV7{t1<+`w-?9EPkg1=fHh(fC^eMcX^+>~Q=}yTLW#!SB zbc%;NDr>CWV*~WIcEoQMy9LTD7QuUcXnu~Mze|?HF(9X@3SGj+CNDL?hQ2i(+5H)29LZ-{m{B|bb?c;^ALc5vP z(Ri|eaZ+DrAQ=@-+0&19A{D7oF?X}0mEYFOyYxnCR;R2B=wH&OT|N>!Z(E_6HxF~R zxmzMV7s}wg4076%g)^EGJn%XI8lwtW;nD;T1E7RHsZj0UjP})Eh!J>UNq4K?|Ar027ZE4Bl{MfY46SXaJi8!MhY2x%{Yr($&1=wjXxx z99o@4)XwyhUmiTe0W5M^kpF^45X`I)5o#|}E^h5T@Zw7ly1t7KfcM`69T7Ql$m7Co zc;)?+zY~U!wSZ|k3>$hsr%5uv%7IvfttjCAAZp}^R@O=jU);Yg1EOxInN-}VdJ z;?$}6zbW@Mu$e_(?-8jo~&tNP0~LYJU;LL0R4RVAvUC>|B5gxHyy! zQMI^xSAUSmtU9=edtE*)cIf^phReGBQhz=qwatbLdj`(3ij52NxyjenO5E5A_Rj>H z9CklBLH-Kdm18EtZV8scNNB+Fux$>6G@LhH8h~9EXL3eDcoOiQQV&Hv^jM*Zg@Q{g z1>@|L3;93TChX=hPo&EhkGIfM?7*gu_>VJeeW)M+vqkBqz6bZgL3Sj;K*Ab4F%TSz zKk##)_ujL&Y2S>H>c9aKnT8t7gL_&!vJ7X{eY6bu4(l##-ExG-`oF16vW&z(HQudj zZIVoF@GzKK4vY4aF(q|eM&YwLxkGkgVCL&(s^88y0C_~5;WYqytj7bGNPwuGped3V zh0uXHFXdlZG)7(^c`%DLxFcc-w5)RN#Gfy~z>p?ttnh4k7n-&%35u66V zLWr#R!sCq0X=R=lYOjuVn%BIfmWIaL?SD9UI}zfYtb`*EG7sopC;{xM`5#D_omM)v z@4SLs&3y?ttBn85oR9Y524KmiB>^cX_Gt&g=&as-Gc;~T03xuIzivBYt zNE)TE)pHzn0Fd{9fY%h)aVyM;Fx-VB+*K*u{UXe6Anc72E*(1De=9tYFapUD5iAnH z%1gj19T8a?5j}u-trr%5ftV+VOr{BlQ;JNni6j|73Kse4ZAFGocm@&x@Zp}%bbann z`YlXh+`rdFEloyAoJ3WpM~OeS(r7pc;-wf=kQ)fbJ%SZUJ=<`_Y`TBB%H%cIAIwB4?D7yBg z*Q%Go(7^N20h6N($Da|;KXJrfyTxq}#Lv{k5tYasT==eC#GMR?<8JHV&%113O_NAg z%v`L!W&FNU!Z}Uc9euTi3)Y>j1jc!09YRU~tsMntBC%}}yM7{VMm#QF64Q2)Gfv{3 zUJ_?yqTrwbwP-Te_VcTYBuRbvgTXtj^Nt|z1o>@ukw_E8!Ki23Q5Q|gQbg~1V96zV z7%SC586D1OC2we#133vp@jhRo=M!x@|oIW)8{_CH#QKIb0jI;^m>{U87XV?@7{5$(}`M2b22gvQtd}l9nj|P{$Xt)@<2Doe5Td95KZ_QiOI7?Y_0I9D_g=bI*0eEd~`(^A1oQTe$%k4?KW0jqD7S9Ws=5CMo+ z)FI1gq5}|sM;*K=4e3Myfh^!h<{Q5%oknPy+q~f%3F1&izT-{*zwCCjk1B3Ao|IjBX&MUT|ndNS2XXCSEfY(42V1+ws!`GNkcSz z8*Ez}9Jx6jFE9+Xwh1q^@m;o!b+z^IwU=qM%T9r@&B;~-7*Gww8~_m|Wbd=IF$f?~ zhNycPwBZx9$O~;g0B0q(fBV+HMBh;$(m@O}+RVb>o?ts88b7mb(Lj+=x)~aPK%cdufqbBiG2AvV!4*8F2OrWeNW9-_bZFnT;EO)3 zKwo@mX1wl#M?-7iBzspKT-O!i!`)A7{vif=LEFw2SK`ohbuiI5P7xNtx(04Rffm*c zJ@D7qRHqZTM^?25VA_L=?0Gia(?1;@jwJ>Yz@|S#aTQGy4!dO}dK7liChvO)YkHpV z+FcaAx?X<;xDU1SYtp~&Gh)EDB6|U7oJC&jhf^ymffQ&4#7Khx(!D^lUcKEu!^PeZ ziT?2S18rH*rfS_Jqh8&`?ji@w5UBaHQ5c%bi`zclkeGZ2vP2Ow)G$#-X?04fW) zu;KFIq3&ToHP4rNhc8W)UjT^LVtucr`kWA9w1X0(!+xV*+p2knTWbL$Vb>7td&5AD z;eHa@leXbrv(ZtKky_MOfnmKr@K&7X!+m~3l#b(ALkTI37mg+iheItBNK4MZ9m`-K z3$7Rn)Q%wKRU~dk*P(gF0lZ`B$Z@)nai%>(mJg7-#uK?f|H0$#T0Gwdypy>)54LSJQ zB{9tZeB2~^TrGAI{$S>w@r?D}m^6y)Juj3`a*~R4PSS|%9WV5~dY4qT+swg7BBcG( zRMLuK$d$8QE_^6Obtsu{F4TYSQQ92VT8{nRs*yw%{jRSAM4Ryd8Wsy>9h)b{S*SnD zZYs7fYVRv~K3CR0Ur7pxA_aT|%wMAHx&eTg-GKz7d0dUbbmRg6wQ&FYLPx9}x*hVF z(PG>5HIQ#`z<(Y&^8MowSqd*SbD5Ml4~P}9PR6Q4q~Ao2`6+vT7Hy+lV*K$l8@m3W zm5>EzD;tBxRA_A&JKc$)J$e9Leg0#^*yeKY%@mi@$qd<9!+b2uGC+Fy)bYmy={M2` zkW^D3e>+5(p!r}q|9AH1L((5WwIxEcC4lM5TIvdY)zmgGF%iou0MHr23akTs%!Q+K z`JC}LJ@WI2W}%SfA>g=+7XN*^e{cVm$y6T_({cKf4f`J( zPE4DwCYzo)n@pqN#RQP_7?(1(2sVI*;1?6z;)Sjez*yc-t>sWZ2FJ^*wfx} z&%S*`?fO{PHLGSjaBSOQe*@J4ZS!q;dJ3xCX*oXFL!*$azono0mWy4PJ)Zr}OX173kp2nOw$a0ppxQ;)OZ3$dI|RV_8*|)9R?DhVd;jY29D4L# z=14sLNV4;&e>9Y9%VJgiRQD@aI)Dtd;)!7Q8mqy@pg=tuhK-?XC>G)#I3sloI=`zG zh#;fn#yvyX=d278x|Db?d=GbW$U_|D)P&~u_xB`XDM9_RLleGKx zpMjr+&(~1l0|>eAVm99ea0PTFT_5rLvMU96F!m=wBj_u&e~$*B-SoU{#he#poo@!g zhM50GkP(ylW@CFSDZmj)d{7n}dF)HKZU+EA1IY;A)-Rr6h z23|GID;~FU5<1UCLZ*13)#{{e%(JEsE@Rd)*T3m+N`H@$pe8;*pa48FHodWBnGhn% zhZb{VD{>LAduoMx#RyJM-K zx9+f5xV4!pg~FU|tDq@XoAiO4*^lXJjEa!&TLk?tobDs&F?}R#XHn&{6?n7<6UD1L z`t`QcRhHjo_6(a`)|relDr}7GtMRCK(`@$vdYf*;j9WMZX7JfJI2l>db7;*e!ny(h z_2kB8GaM4>aAi25FY<>Sh&S~c@#nIaAFaMGoZ8RTJZib18dd-=I^)cXugRr~Q@Orw zHw4;(jt>N#)DN^K8%aOJo%;Awa05U+^O=~95Aq^Mg}uk=BVDgmGq0L zS?{BH!TIgh|N77A?@cG>@h1Ra%$FpW{hAGu&$uMe#I@8c6|y(G+g3?a5?+??eb7Wj zQjK%!2e}49Kzv5up!vK95Xwr0FbKx1;0ev^6cOB6Dc2WLS0~3``ILcf>at+L6LogU!7vmRoAil>(%pA%6E}B? zPBc{?PrFTq5|6RH_o@H$8ZO#V^E4eJcS|dSdeYSVl;JD!rIQTcvpEcE{;S!F;Bi%A zKlKz|W+6RM-s*{-Me<9X;pZ*hKSA=l`al5v0ZVAO^sojcg8yvAfJ7d4=}1NW zCb$ZLrY;PL`=_52$)7=ta4M#Vpcupz`eTuzwedSVaLq-Z$*&RzkyeP8^xDutjMj$C zZ=bHz962Q@hZ4Fa5=!&{Y%MeUm^836zAH%eu`B;3_A^)T?U-0NwN(`@B1?C~dozdA zWNI}-Z;==P(ZvTOdSYMN%v~}Kqh=-L$1}c89S@EW!ol+6R&aHOFg4L>7YI5co zssTU95alYeef4(u@$7q)`iv+Z0YA@5O+v}=(sOTM zDUKeYyj5dCz)BwJ?z$Q++_8l7a2v$z9-z@}r4^dDmU{}Yq0Ds&V^_j8Ui=f@^^Ijo z=NyUGwUOfyL3`?T_RaIv{PQ92z<|r0r8e@%Z$#Fz)pyS^fq>%5JDb(v!XkMHz{uj34^z`)9)YRnUwl{n_F`4T)4skx z-QEAIYFKjlIUn=o&GqNE*Bw?D4GmX~zBiwgF?A3BchYeE|AsWIu)vfO{Rh$z@4TY) z<^%ix?ipU@@#yuAOpYKS!r|39gQFv#DBjEwC62h|YzS2aAM97yKSDmNOe zE&7ti`+DfTa$WIAmWb=G#lgCgzp7!wpT_^G8g4(sw{-aLRYRd64x73Epc*d4S^hVw zVaC6zhH3w%8a|)w>*N=Pe*dpj!(pO4=6_QS-TzSy;s3d62>+`ZUPS+^YUuQTR1LpZ z$N!sZIFJzdpR0yF|E?OA(uH#`q^v#{|CL@4k6qs=OxPg(gT)XjdC540gtoD&;aSK} zA0lp57}u;i&0 zE-wNseaG(KRYN*FS{VVZ?ZOn+U!RTfyJ(Y(d0l=bmE=x{CYN}a=%T@_Jte=&EB|ZN zus!NP7Kac2St&7P`u1*}(c5ZVf-xO?D|{{h%(yte&z3E6shp;&NkL7!+TLU+68190QwJTIIx=XAQKO{kkrM)QknD_?Acn@jhk(lO}GHFKkTKk{&&?7 zl9f$(aoZ2Tm)2f>gcf}Xz{6jR`*OGE5noKwi0~vs`7oifDkC8Vaj-cik0Gib<9!~< zKP+)WfACzT->Aw*TUQd*thDOsHg4qkeQid0^PBP1^ST&{dEkm)(gM6@FY%kxjvw!c z)C+=!S+7mwmG2KZF*mi(?XMr>%Bb1*C=20^*M5<=0poc-jd#7%teC9z(DSpKwLkNc zkLP~#cbPO2lb;WXCZnXG^@uX*P;0j)X;zZBgjK>s6K}=F*D0+Et;Yd>o)y{!FmC2j zJGH&)`M4%L$(xa*zC+VK3f&`^zxC~w_?mH3I$JX3tI)Mn;l9DD7hg_33fl+K1bP6acfw*c&TkI_gy zC#+G8YOM5tlS&N-!zgmxCp{Gec77O z?>dOYS+D;Q#u*kOve*s5O~eZoKnO7^jp!;2QtxKNf+1AY!eN1nDD1x90Ig^f9J)^u>yV=Ky-=%PwB_g> zlkNJ`{fmBs1Hr)}+vyEhewDM_C+(022B24%kCcifj*wsg$8q95M~}2(jWU1@ zKyx^tz^0kd)cf+c6aJ3LsH*pn;0zuZk9XjlgS_Kfyhd?IB-LfFNyH7UL~ zMojkTfU%Q7hW$vHFKwN2y%m4rgtpWhX-&+adhlZ)y$T5m=*zBP*gj}jd3LJs9 ziv!z<_Yb;hSrX_t8Ec=-jA`ZY#&XJ z9t}APb7U)w|2EqB1c$&1jmMC$7cX~$qR@R`LCY@#qQ6*Saso)-?^^*<;@PHb)Z1~{ z2LZ5QbTY$xoExh16VvJMDpBt1)_g%aX(xaA!v3ot3tB;%@i^Ik`NBLfD~5p$>lYF{ zkkxn&zxeAHg6;)imxQ6cF%0j@t&sgM2L)%}ewkK+U&3Nj$^~klUj8ENrd!yLbFZi7 ze4vK1rWjB=YfCB`9XPg7=hW z?g5KGx#S{;_F>-!LnKVgDOi zA=VDdV+gYP2O+Gd*tBRd+G0V2MaS6qlXdUBaY?;V)v4y2H{$bEr^E9 z&W~Xpy3>0`9_)JeO9$*8X76r>-#O2-#CX;5Ks;)0L8gm8FmXg=?sK?}eP6?+@36vRBjf=biIHj{ ztTG`75Jtj~9dU$ri?y2TNkb3K?sMzW!GHwcl8r584TZ-?>L)GTk}PL!h#%*p=N(r! zzkRG9%X$oUSFyiMjP3#CW{2ANB7E%-B-=W$f zVcZ@FYm?&%H4#mko`#rwuPUFP(CI18aq< zssu}=pyldeVs`+K=K5*IQ1RhHm=>!|^Kk-l8dLq4W&6A|n*ss{svzPK6yZ-@mvvqC z57@wuCz7VgGw3O^=z0Kr*5Jt}5g9>kFpMN00B%o!y-SmE=ns0tXFO`^I6E7Jzv5BK zhm=Yr7*Qu#r$T-X3&w-Jf#>Nsth-6z2eK&XdW7owxI+`MyrDE9mxxDts_jcJ@*cDa z1p+a5ZoN?QnkoqA%NWVy<>2q25Fkqkvx`C5smoIi^}|h(8bQNP?$EoYkcg+=+9C+c zaI*(2z#BB=6$)YO1tZ^d{qD(JI7Sk08n%cD3u7sC84xlv*{~Z;Ll`LqGoO$bCcG4o zj>t?8a|Ve;dNJyZk@O<~aTmc)2*~X&$nj>$xtnBk=fb&G0AI%-G0SEddeN1Q{)JvF zAZL;hb?kj7YDIU zKo!UGLL+>tkpyM2b$zjg)+|7E64%*yx3l;pLg&g<3Os$ay{#Z_93qDM!ACSng4nwa zdQs7KhP@-3a841S`Fc6yLMxDSgJvNUf(lmmFcZ}qV zIxe5S<>PtAtBFTK85BSuB7g>=(?mW^NE#gBEvf8OUYPXIJ$_~d5qyv$N%ihW4bO=A z184pF6S5Cn^wac%9xNp3Kh;kV&v2Z)h^s)jD*j29QA*9ROr3@ij-ZI`246dHa)fAd zCW&Um9C0MdW~6gwq~)iD5XBnI!+51lJy9OPkx8NY@s@*0=Q6mjX@IfH<^uPK7NC$r zb<#+Dz?}o)T{xr#jZ4c8e`%ifx$K@P>-}!d_juhI#oHPB-sJE5NanWEd~JhE5@V#y zh+{4?$rQC*4nPuPz+41G7VDc=OOrWDgQlfPJ84sg{$!*zy!R_3$4js;JFuOY&rq6= zrJ2AN_ex$+);XUhi@;)tV+6Q|e+P6**8CT=xunENBY$8jRHUZpWPk5miL?~j2|y1a zK1TUf!8<^pGel|Tu2)fcBvCS$SdRQ_5b)dz!u?hQ0ituipw4 z+9Y{JoA|sUk6#n_HAjFp{R9g!&vuq_~Hq@)(Af@5W zRgRrXG!hJ(q9XM`N1GZp^7uABG-MPT2==o#kEJ&;X!tZISFb1D1VPr0D>p9LH3lLZ zpC;lAjgcrrn;}BY7cZN2D?X*}NZ!z?{nA0mHP=U8HAmC8l#4S)>lK%ZKMk<2H=J)7 zrmSTjgc)Cb%Bg4`+N$3r{`5x!zciw$bLVwyw0Y&1HU;iB#FutTSfeY3+b(LS?E$#` z0tx7`!Jnpo+NDw($nD<)ZXN6Mo^U3Z@@*Xkw+y(pPaIaQG#28Qt61{MxUGEsfxM*{G|4>&;&fLAHkN4E;y+#2@Y){YPeeq`Vh}G6REws zHj=x#E7~)_-M!ynyn1=_)D4&VcOMcZ^B74zTx_T3iA@*pX29tXPwTYU#%)BComP`t zpjyfOm{sOU)aJYUj=K-IyX6@=SsGx70f;BB6PrU@KfNti2JR{^*a`uBv+PdeLWFS^ z<6I{G%N{Nhv)zSSLjSUdop2EL@O%c#9-_dxg<5~-%@|Wc%ihjOWU7u|Z``o!_XR7) z-LAB2m_r?!RH9GB4~pU?LBPlsoW6k7ahbFk4rN4>)hz>M6Tn-`j3TBG6bks7 zmt+nO72$>C1MpH%5HWGBxLY5noxG8Bn zl!?-mv_TzYl>lBu@jqB5&Eo~x!b#B1)YjQE_Qp`RXXGya%nS=8Om?#-!L#=CBNIGR z&Bib`qU@cp5qu;#p9flio+9u1OCS#YLm=8<2}A(Na4_LE^e=%J2ms_bljfJAcrlVt z{_o|7IJ3U8#r4MD#IudxE#|bee;d0VCWoa=Uw`|Vg`J^7GOB?HUI;=R#>9&Ukiwfa z1~wokhB zXz|A{8dD-hM@S{qrTQ;{xKs%n)tX;G0cFNnLDO(cOGjKRsc zj=$s`0F$MM89La<7f2?#R^{bZha*=x$)=97Ua2W_PRSH%>C$o9<}u4_M8Avq!Fh8!D9frCAS zRr}j-_91+gitXEfsyh8^zN#hSytctR-Df-BZ~3sl^(XE(RHo`v)n5F=2H%NRB8*_g zC@Wsu@9Vhz&757RO!YW=7tr||_bWBt?>i-4B%c^rcS~S^QC} z)B$}bUH2TxFYxhW*5fq#oyIp?cOWpOifCN*F-pk3#!)Or<%IhDxKnS}|HFyO??V!1 z?3?ztxYKc`&7p5n{1(<=$l4j6^Vs;$fwd{m zY5!31U#JIO#C*IgTf#0+MnC>~T)2PS)xn(LaCwcq^oieP?L2QBff|3?LopvnemqM4 zNH-XB)f{+TqW|Yz{2!O!zb+y@%A_+t{J!E8z3O{)b%`1OimANT%(auu-fM*%wLKXl zlj+Q*zM2cn^#95(OnUnp@`iEgR)7CA%n74sN#gzDqV@>}fFr#u{jaLwifkAuBiZgm zr5-Yz@_|WDy2ek%xWB3)ttOic6eAtu@Ygv6y`@3n%^%$xj_0?Xar2%mc%Dt~E!G45 zkc-Lz22%BUo#YKsD`oTZcpq(RXOqPV`pUlC(Wx?S59p4;aOIAYh?Kvc(S3QK$5JEQMAHc+86L_4xGAT7y-RZL<|?RVmE|Gg0$;o!T$> ztiz0Iey=9PDih>P?CJ$ielYF~`#x5Wne2ajH=OD^qkO-t?Qm5`uQ0csE(dwFE-B{G zH~*!XiesiS+V$7;hZ0AVdJprZPRFI&oGUMbFGZKMk4+`~me;sH>JHyBZ5LP-uPycG zGF$j%e}j2GB}V7t?M9-rI9vglc|P>a;vm$m?0D%WJyffo(PkR_a}~Dvu~zH49nhqsfOje{xYM?&~<@GY3@hCie(btnm&% zqUFlVurh6`d-0^TmZFf)Qi7sa7Sm~vG$_z+zm;-am~uQ8ytT+X_5>nZM62*{y?!!_ z=hR01?!6BV8j7=QF9+|iL+!|vGo4ybh>}ltX}@GVo5rXz z^7e{eBEvq3n6)eE5C!ht3AW74$kTOf3>{*N=54;u0QynJ6(1!g$2>VoYzD1J+fNc z)|70Lw{vU7x2I>8A#_c4#3h)L{gYY7TUu6g_n8&Y9Wt^c0A3C9ViQERwv52}G;7uB z*tirX{-$|WN_?;Rcb~XZ)6Pt*Q|IQ!l~WgiHQf0#r2pGNqXv`<(gV@Gb{YI0C-IwJ zt&h)Ajp%WV-PfzaPXLoJS`KpI2yDjEm~55J*bSC=*JIwgq}}72Q@^C=chAjs&!s>D zDX*1q_71O~@$5e|tS_WHyf<@&nP9_?4wuKsR2xNFg38U?rv_#)>+PV0i>Cy^pP5>B zhuCxd{Lk)rV*Go4rsXj9j_ z=7IpmKahkPU$YjOhZD$%aD~vImAQz`ksAV%+`VHy)I($7BClNOu2n`mlpdH10AREU zA`y-NiYPU9GkX-qSncLPCQD1%h)G!l6BM7kN61rfjrgk7=fvUiDM%Txt5?aTv0!7< zX4TzHON97%>_uHHC6EURxyCF!$k460@mh|dk;^?lWR0qh-l|)!~zbIBE-mu zFVYCL8^&YD&CRn9E}A6-3-EG#EbV2>>K|WP#ByvGJu)uqGs8U=i7}nQH_(3;j^cgN z+NNC$N>s56!q}$X&=$2Tc@J5>NrtnVDq=`_hf{iLHD^zZ;Lb0fdk}*%M}~_z+smH& zB-u&^IaB1ehE~j&_#4zc{?tWg?&fe} z-Ih4qUnt(LIgw`D!7zSpxDk|?^1hfRU52X;bGCu}{Rxdswe{@vH8Z}SMU&Z@Zbc{W z(QMqD6G{9%85hlExeTZnE1taK7dK$lr{ojBzAblq__=`gn*2RCQI{Z;`z3-MAx*? z2d;SZu7e^ zI{b*xQta}clgc;W(et-ou}i1}ev~ALOXBno)ZV-ya$xz~h9f+AIS|fNt66nJL%h2E zuOQ0B<)Ens?SgxbuEHRuhtBTpfR3v0D-PbENWBiW`w@{UrRJyFdJ5G01jes;evlP7 zH1NH{L{vEp8#6%U`}Ii=;?65rA0B*!X@tFvi8V6afAEP`QI9`4{yLGJ*<+wXvd-jE zoxmzFp<7LG(@GT0h&?=JZ8C_+kNM>6>Rn;JxKJA_a-p1{x z7R(CI!AGN3=6-3u(3cWUZ!9$M&(F@kyt$_lAopppRp(QRH|chLwRl{-(uLZ6p10nu zDHQWwRz1d4W0Ehg%c$d>70e$VCl>In2~m@f>Wo9o4^}o9GXBUdP}r*t|72Kh3MGZ_ zJMJh?t_y~GkA!CIQE1(8;*H7uER;G8#Q+J-fk-^!BhV9Q7wHsDI6+nL?}si&+XAtd zUj@nC!pGWKJgf`(kQr7I+8JJqs`Q`DsiCMx30i7gs*iq1lU$ z$WyQ6@Dfe~MD~xU##?04;AujzAWOhDF;=(bW!&D{b~qWkUh zy|3%{xbJ^p+hhGcU&nboQP>PD*o0UBh9a;50PFEASPl+hKgq!=7vOy0;EGi72vmuE zj!&^d=s?24-c*5WW=+4xk+#hXMsdAtdHtJp=;Z z4aa8%&e$362L)Sb0+BR{+8~4~0&HfjaMpkY${n?cRC8)l;p-pjw;E5-)CdNR#p%Oe zdcrkcC^(RfRo=yUmjfJk)sgy0|GRi3O|0(AU&v7x&AX@q^ zNstY44Fu*xG=8`PY9Gf2ykN78SFvhVv#w47*nvXhK7>#x6fV9KSj3~(1T$W0W?al{QpZD5)NB$603a#HwL8>6D#r(Dia?5zlmH05i6mq_f&dHQ%>eP0 zXKvq_hV{{-w1s8qD8Fq!xMm>-{nCiW9UtY>>dGZ5(kO>Cou zJXQvCVo*c?2;diYNeU6=c?^Igc$<%!>OhpPbDj`L4+pV~Sbu7|o<@(r@hKp68<$fN zPF0bSDUSbB5g8}gx*mWL2pkqD)_*D@0D(1-XitMJ)}Htj3VB4Bz+4os0Mf{4lw9{> z*?@o8&Fxkdz#s4LoO*biA>P>_GbRbB?jVI=n9NYOBs-Bfq#w`*1r91o@S=dQ^n?9a zhF0Y@lC8LJcA0J|lJ{oPCC~CM3Ii6z?xx*wIRbEPl4(jw?Yw5*AqgV88o3a(VkVQhe$ zSQM>z*Bo{JJToO8){3m--GH>Dp5witUKMXJo8BWq8u@f1MP~yI96Vu~?$8B8nW!$6 zzjYanHMAziK6n&v`do~{0so}A1R5SqiH&pu_wcMh}cF z%cA@`&RU*>!;qt9@yFn6ekoFhEWTg%YySH4f*Okt#TMP78Iv(AdVH}%Npm^+Thi?gw^^eCdCy($3yIf(beWJtE<^eKH6{UgUZKJ*~(ie^|M*< z$sjQ}=14(EItP7L*YoG27SHpoifg|0y?g#*^xM#zZ)m*ut#d5E@way^Uwb*%`Wda? zeEsSv$ioOz?r14te_lbyhVmsc1Dpc`7+1n>1d?hLO4|{Bj}w#=%;KgO{(u%rEaP3y z^(Wrt@%2>-3~8FvfTdWlJv5i5CD+xRb-C`wAtc*kaGXa}lC${F7tBF})3+1?7L4!u%h)Y(< zLBhuEXhUGsm+jpR$0|G!OX5{;>elpkE6Jysn{hS+VBcQQ37l~6FZoct=x-dx`*o>5 zoGY=M7@Hig4}~iNQ9tFBwcbNfwqry@u|Ev`h%rkkAuA78H&_Ov|x#BfQ7%D+b1ci^mfYf&j zNv$F!cXfgZ5k^LQ35&rA4#xEa@?oTM8Cz=V>*+MxqcppU{%Z#N7N;V65;x97I4)_3 z9l2SofhN2AlfElwjDq+c^VJI(Kkber9ay%J+wN9-&_UYxI$16!X5Vyzm@iqgv z!MIku&%WP99iVFP(cvzR>LCshE+}=o0=f1$>~mM|vF(@{lpiE1iUpia4EDWC2+-XM zP8>~t=7tj5BdB&YKC>wqL;c(%jB4F=tetbZMcL`=Te-Lw+HVz_cB9Vr?7EMhwjQMU zA^zDU$N{kD6Pz=d4j#>zyq0sQDv+e0g5Z?XdgZvMwjLV$IHdt>T?XRhpc|!BuCDJ4 z(x5mf(gcj7)@SPWQO>cIs?`No(~Zg#KiV_A)SfR)2bSe=(c+P^zrMGMvb$Th%Q~4X zIO)d~*#2Yjp34Aw?g=3*J5b$b0UUJBe`NqDvRKmAEm=mIHk~7z6T=#S+vK#{*n!A-`?JE{H3%@>{ z9!s#;JTo7NPa-(^lQ2Gbwl?`OZfhb|&TsFu%cD2LJN+;LleE@4#QBKZ{BGu~M%8u| zdRk+8Jg>MHAGRCq1`=V}-}d$$8uLhZ1GBK8nC-xS{_&Sh|EwXOrmqJnKAir;^{c)8 zIp>4o*_WlO$Ce9o-lICp%Hp|$ib znr2Wm`dRRLVEX)ekER)Ch-~M2VasP@~gDq(~Nq3IqO3wdX&GI zQsA$Qz?D`=q-g?PFLt--xmw#bKZ1E`FsMy%%6%WC(SZ> zz83OaFm+BCICMn-1+zRFyB)QK19Xzy2gtsGX@d2|@FG`|M91RqO@r8yu8Pn6;`L)? z@Z*W>ywzQAJ%YV5H4%!lAl*akF3?TKs?r@%$O;7KJScQEN^A($^frbd zcJ$7)T`!YgI;XDyeT%?e1Bu~>xDQuXN})&o%QY23qQpHRB)%a~4G4Nu7Z-yY-e8at zZco`B;mpGXTYY`Xl{;Tyes0OTI52QsDtz5G^g_?f+0|D;@+A5Y3n+5#pdMJD;cxo^ zMa2!lz=l~#jq(lhtY!o?PoG`dh9s~couJ%gXcx*4zc$ChQ{9qo z7$F$juq=u1AN{jRW`cyw8?tQ4b^Y3N}~z0eJEUDdX#2R3){H{h{%9Q{i6wClo1WXQ($RVkOB20Sl#ztV>3< z5=JK6{+j>wtJ?P$@zPD55(@aCgQy()F|*I}&o|8R_V9%u@*8MqsR6=5s zN4+NoHeA#WnJkOi%Z!L;0q}AqUT?;ZynILv4VwCS^D%`ui8%TRF7OEpN-qm%@#)`! z!iY!>6cueTd3~Im+v$W-OmmEHYVVKxanH{`|I#kxosFZPP(zpikT3x5f2twNP`vQJ zcXljEupx|UXsB}tbr?;fleS$uyr>#YV$sMr(Gg8=c{F2bLquP zOA1Ajiemy9Dsg)PkD((2M%5M>ZVN5~ zAEhd-;)qZ;Mrr^+x?GTydHSE*^6wvTu+bVPyenSI!zt9|5FVQFsdOZ zMm1y-oG0Y{pK1u^Ecy~Vny|8*l=|1)#IE)_ju02y-(Z~j|Eh+}sxlSq|EY#q|EY$2 z|EY#1b2_5-CE>M!j~u>K`57wi)f)Lp?U^zC)!Z3T=2jL2fvClhBj=$Bg)nj{2c*$9KLhmBCWBn%2_^r`Q)8zqT9|g@8 zO<2FJIA%)4+x4A{wCy*)_D2etnEpo_ZYoWZaXE0Eh2|r2mbjxr-Fw3 zBjE=BeMN+078*G#{eofY#gYTF)PU%;0ITdi_pr4->sC9Xbar{tdvTx2Ck>_9lbUi_ z+E1%*LiE~q;GBzw^iHaBaKiXtm3-^hpC$7<^{sb{KR7=YkE8j}|H|f6A4+l?srT$V zrP0%<=e0Nv+?1fBWbo4!>9BY62(w}+1~h#AKhRJat`M}Xi&p$VAtrp4O2lUJ@2~W# z2^W54vbWCXXE7g{eve2(^YT(y2xj9NZC(4Mbw%{39x@|$=6_5pn>2`q;OPmajUMHntYapYU2@K3Y& zL7%XxIh`sjnA+1^dT~=s1@z4({0O}4cBmYCi%;Ch)J0AG^qeUuEH&pyT#Q9k>5uiH z$t%2dq$zBg@~DSH*AK*bCu(L+sqLtnahOzHn6AAMF;V>l{ZcaXI=kkNb1oRGly^3V z7@O9uefr~eKtMD{wdqNMuzpU5m`ySrp8^0#&vlttfKHoNrE%l?`2`r+QdzxbTb!L5 zwdq+}nST(Qm>!Hnz#ospJ;TSHqdkkSLoy4jp5@y2K=C{5 zw~`&*0My0-3P0Y|FbryGJfjULW#?7ibFrICXXEExW<@chR8T$~yF_J&!-{{trc$*_ z;9wD%!v=%(@n3jv!LzYq~u z|Cpl&yJA!*1@*cJpSRwx$=#?=`DJxShE~pXEt-Gf*`yp*Q>FIwM4HF-(wn7f{&F4& zPd^YK_QH|P6bB%t&=7>)$sap~@JD21%6wY)e}BUJVzKoPRjA8*k?Q{}vlt$#h`?JT zN@xsjpx--0^g0p9o47EwD|R+dIOgc#-tmk8laPJtXu-m0AD)s)iTI zq@v$5%`3fJwZEMxdh27-kPQVG5bybb+m zZQ54&q1i@KMHSzS>J0B%9b42_`jgjE>+|nk>oOR_!HZK%=1e1NM!{f`oK;PnV(S1F z%1P8yjynlKCUOlgv0!3{9t7A6BV>8=DOzx)DaV|GB9q$Go6g^7@?;V6nJjbKkQT3e zEVHmGrd_`T2*fbau78;E!+;?y1ezI2F+#H5J}$KZwc{e8WBoI%|0;Qn^4Y`?(_IBz zm}?#=irQk%hsF`fvEZY{*UE`j&c_xx(pOA#tX}0-#7fY)<@BG7mY1C!JF5|q`K$!8 zU<)k2@sb4DjKIL&=ZS3?7&GM45LjgbM~-F$;dvdqj17xZ6aa#rY+}cgZZ((XW(_&< zKjQthFi$fpnk@-0qN2P@!1#q3=0S#R*!etWBvQpRSyL2x#}mWHP|?tF>kjf3EoNJq zVcI3ABi-8_5pA5inkRaBaor-L*H-}ziG|~UzgAJ^` zAb{mvWB-eTf{?ckecFUz!fJMPY*jhf-;j50lH8WNmDCL`lGWHOWXCj^QlddjDN#A) znw=bA6+ql(hc0D+;VN@?UIaT7ma+_qJvmVOMhW(8fC@VNss3o={^dgra7jg-UbwRE zUCYK=MCk8~;(*=}RvVn1I}j}Koaj#w_8>qXC_4{8G?9at5iAoNBRN*aLL46|G*CQk z%&V<_!-N;g*er`MJk!;eH-2bsj9*ApN;bkus!6HiAskZ_0e?XcbLKPCg03Cu`QreQ zlGj-3#t6w3722Y~w-1R(BG464{1vS1ni3TMH}}Tb#m>)v{*w!_ML1@ZSybd?$U&cmnE?Zj zR?wS@^`BV*h&@vHz839`zwKf0^s>{Y6(=qTgrq$ur3wFX61GKcTA+`#SGQZ81tc=} zXaByi`Rz`rM-lsIFjs!g2;dF{heIJqWl0D&m;!`B3qN4cLV0GWpFY>fFtj&si4-Im zwmzz5e_)^|PJ^TrqFmX6e|yDBF!jQ27a0C22c`@FNlwyr+kIw@|LYDHi8P*1rqH4V zEdk1<4guO-fQJW!!T=WLJ_P%*ClNSH6);8fAre28QEyuuQ#M1BN<$k5U8hRk4JPjQ zqZAM#-WQaxT{Wk!Ev|d(`YpJE45hIar3ocyDa$&Zwv3)|_)({-NYNln0&O=RKCIvu z*Uri=P6fB#W7m*n*Hzw;C~#0NNg&L^=UW?vF(`X|N|bo!s9Nc8<{dA+hPml4wm11s zckJ0wrp4z~YVI6bfNE9zT}>YxLXP3CSwvET*sx%$(vF;*A`KHO2nu$ErmNKn&5?{W(LhcB zjRj?xvn-x-JuRnZ(VhjHvrhS*vJ9e&1N$puJaC}QvH)(gx@T;-C(T4)kwR6DS7J_O z^t6@Is!`2$32skUYXL>5D8v!MM@XUuY@*=~QzK4>`#6*Inlxy-N+6>0rkIk+$_}54 zgURsNpZ#z4t|16Pr#8&a3NP{3bT%FFn%{SRHlhz?d@V~4P^NctDIa5u!%yd8C8{<3 zvJYo*4cMr4@EG;T(}0(!SnzUNi_|$YxfuRq(6t*L-_n@)TZ@xoBR<0EPn_d#yVqM$ z3#qL&@ydLx33|2$e5&uNX?I|0>1yS~r8kScx|Otwti!=2)5-$yNe~j24;dA>TIF*Y zp*Tk6Idp7s`eX~>UIUDW*6Ujb7Apq^0X()It~vY)agSU8mr z>jji=Jej-t#isfILg_)ZfNi({|5ygbdtBoxtyo`_GlC=GOwT!zv$<~Pb{IhBp55)y zJi=QPc4UnMsZPt$sE^%*Vx^UM6nc0V&@@&bA9EPsU`gx;XpWp*=(cQoL_2tP?;pad zD~s=rt)?N>&|Hm0l|O_7$V=Xi=%$W+&}&8XkLM|$JsO{utB(NFsO?r7;j^w$0Zlrl zd?kn#cq^-EvHRkzS=U6$+vk1~` z=sZ9H!_V;^0o}6*coKgm)dszc;PxUfrMZ;Xz@gPViB-OAWJy zVLZb)!Dg@F+R=}ES>r=q20^esWaYbU{+Zj8_xsH=_di;(PKrS-1`4rxIi6|{h|TMY z`3`}Fm$f5I9^X9T$Yh5i-TOcMqB@@;=nav*YfVc1B8=mbE zbL>P5wCzJy=Qt=MK#duG4x zWA{(6njua~EglTX;13h7LHI7Gw7~#=0MC}IF}UaZTDYIl!>G@N>HNZ(;0>G4t9(SB zRGhljh!BK$_riDJv7ZiM8@5^N#aKLTER&i@+vgHr$Xj8!i_gTf^Kx3+YMv+XO~j@( z6F5eYFcSnh$ie?3qNT(0#Sq=JVg92Z>L3z&;<&Bq%Vm1EtWOi8;CJ{VBE{OSH$058C+v(i~}UoL0J7SFCU-1r18g3 zJ;&E*+Ys|#VhG65Vyj;CnokzuSiV?&*-EV{{9p(we#NY|=1J?@#92oCo2vcvvWAzN zwj4I)ND88b%$#=yaD3 z0>+8G?Kt1QVB&xE%@iF^4w;4;d2;V?0W*CiR8NIT8l{sqWO)N%6S14k1G2(_a>E@= z9|Hu~;dte{>rU_)QK#0FfYX^v0<0^=P$qS)2D~2RrumRE`L(J3CFf5u-SBvzx%Ll_ zk!B%4MouS=!fS<}HH!Q^m&*7Ygz*rL3fcY(jUIgwau)>>5gmeHx~4htdSNxUD(bI4bf}9k)RR})c5r=y1G;l`#sNu0V#v2JtK zVvMemW50$mqi{W$uTGO5=~5SLMHTYA+X@|&qk!=EsVZ&` z3&WNUNRsjz4{^i3gJ1irx`OcQX&tzF5LdU_Xs`2v10KkX#M;MbjdQ0Mk?_}ikEDOV z7H_kA&)}PvSl{bn`0rws+9N%sqp(-FH1B#%ds&}`X}a8v&~+!$#|JKZstF`BN(d*5 zhdmuf|MIm83tvT~s!oZ?1JcSuVz7S)j~mbS*QxUapYYtpJbe>wDdEpHssxF{H9nsd z`i=DJ(TwZL9hO!x2iQ=AspUz+xxT=KJ?g7_+t-GE z^!E8%%89|=p11vpFT%UN$*jt$y20NQu4?Se)#o@I#Ok1kp5hmBoa#z0+Yse=7h{h$6LWB z{4T8@Vw~i?L}^-q10p9suMI4G=Zasz3Lz8nWYzCh+Z4X_y!-Y+VQu{HsyLEC1iAKI zVdFqyZQ8bskLyc99-WJO8$Ff8m+N=`chBA$ugqB$9VfAU%J)QE-^Ld1_+VLF*) zT73T#t#}Upa2`{X;p~I;FsJ~6?Tb4e{=>Y63$V@$$F-k_z6GG?ipS(2q2_3q4lTr( zc30!Qe`yp2T2-anj1=HmKFX+h&I33)_$7 z$>zG~J{ME?`^Oc}IoU<&`Dm|fo|{3HMmCp8-y)ZGp%nUJu4o5cR+K($UGZP*H?}Nc z5!)9Q?kU38u5+~}Z~s#b-LfZOmjymHZ@qVBB()pAi}QzOA{wywC(<}gm^f}Qh2C?c z>6wa&*2b5gTI7NQ*zoMZwED-fI#exlM{Wys2B}`zdfc@6qX^u`3eQ8lzxCJ`B=S)X z0D|O!i1uF^{L53lx*38Ih2eoc;iVddK2-N<^7HqS4l^|~rTi`=-0II5WVJ5$G+t_a zFnBlBLM2)WqVoK!zkYL3r4d&=tgWf6HTh%!h&S@{eUThgH7$mZbQl*Ps1NSw)T3cKDBmt}sEyF%dcMB&naP8~D&9K;xbIAX0~3>-;UC7rY;7!jL$ z0hBYkuiS3sI;r0w=yYK49Rm)J2!8%{%iunqtE{zy%clHwJe^0kgltaDkq$srI;+LX zMT79b#Z?!b4l+pzJwkfx3?+UTMuUE|+vV-fWkDWgl4=8#L2UjWS z=BT}hSOo6t>uPx>uQ=*9meZHE8YtHSGk|;~P7N*H@_O7?d8Yc4e8I+K?>NO?q>mu5;=Go6++{EP^6DLYGTz@mE0v&+w4e>$(p*?T#aQNzZ!lim=G8=lu(aV`PY4Q zfHsr%yn1Rsx3eaNEq%!z&&1|5e!lImL%;0vzg`_k%jHTI!{O01 zZHw9*&rXs5@LISn^TVd=b)u&k*kF2tS z@c8?m*`*si>lZtWccg+!-v!xGM+Y=qC$UB|l}CCnclK^@FMp3!mRUrer?SO9I~<{B zQ^qH}#0)e)0T4t^i)fU}`}?9NQ7(p7ILq^>Xm}j-$WzO zhgfRQ^-10DUput^>*deUdXnlQfe%I}B5A3W6G2KBC9JH;3=&K5^gVla(irLy*tIHM z_{6S7s~=eQi(01SR@LPL>chj_NJ0j`6NmRD?kBe$m0XybxD&Rv&5TPWZkA)Cu^=<7`m47u%Cm!kvd|H<2!fjgy^ODH0{~0u5U279ELWB2;psi(YmM2?;Y2 zy!=sR(IGHQdjnNWJIS!OPbr2$iq<+N&5fP?iYh>V0S??9+(q!)Gz6U)D}tAnymS&q4#6Udz-@G9&Q%65FfQv3fXJ_IzGxz9e+J0A3uA<+rP z8c8d27pfpFFPbvVK=opEzxyEKRZm*74qe=jj*z>Ippb_grteqd+O!fCNhgbQd8`bp z%9qd}QZQrZApM(JP4J2+0W*Y^8Z$lOl1Jh)8aprxU<2r`?eSQ`u$WbOUL)9P!Jpz| z(aMgIS20Fu^OV|WZ;28G_E_eqQ%)^}2c}h$uv&6d1G{HU2sPF$)n2dqwIwd%*F=)LlemAqmUAe5B`n>szbdAM0Jc&7oBJ zq@s^cXuT*hCzyN^%5>*zmiSidUXAhq{JeAEDvWd&1DN0m62CK+9zi)N0?uFXKq^D4NM||r{idQ`??T?j_*)?}2`SC-AodLJdGjjjv<8Hv zmjSN$ZY;goI)r}T0F|B=#qOf+l(mR zVFG4Q6`1td#32t%E|dK8#;xJ}kv-<3?3(oN|GzmMm}ZFuAU&E82JOQb((7SN+0e-e z?dZ#pw!aa=fJD8^tr8xbPZ6C5ji-_hp{twkLZ49^SXSAOt;XV6CcK1K-|21NfdqeF zx?j-gNyytlIQ$^3gH+Z;phg&t?Gtt$AfufIa2I*9q|AiovgerfX0J!CcQow{)B#k0 z;)ys0w@ox+19D;m|ETcM0A;jG99n1`Ezj|JqcSifT?abLL81SZX128;v&={$8Y%wJ^@l8lp$VQj8u5n$`$xl%7%J^%mQ0rnTjvA(`k{)j6o_){XPa_%Csdw zGAeu08~~W|F*tm7fUap7(XJ}t=CD?YYw1KVy9?1~!^`x+gB_nke*z6uw;SQ7{WC;~ zTa2r$G@q2&-C(Ej_UsP>^k+!=39rBA?I9F)6e8?Y&AtY9! zJ@X^gWT6hu{+m}xVlWKm1=CbH_T-ccGMy0IZ7#DlpF^jC#TmZUqHO{7!9fn>D_#aJ zoAi_@iZdwwh<{-S>94*YB%}iU{R#Mq8jn_n##AO)zjz*%h_KUU{I2$XZz$?D59s>` zqoGPRr&A_9%cAo3C&k@j3Fc*`CFPv;_g;J@8+}%{f))SJ%rzLtl$}CLdd9SsaPbl! zA%~!&Xt3-<&_B1QeSeW{J)dPq#^dS0HJ8YJT1n78{Bvo$qlBj_ZI-*3h)y_7;G-eW zU?aQq342v73GOjv0}k%{Y+}3s(q5LL5a8d3kQ!T5;S(e3b2OfpiB{7Zs_9UDoc)c?S`}q zj-oMQqLk!PrRnU&A4Apv;;j|fkTLwTbEOxT#KL>xuv`Y#Bcc2c{75M(+ULa+mvTpG=0|JA z;m@9Yp5GqaXjDx8sYorNl<&)qKAppREAAJtiFs!-Zjw3IZqj2GbaYN&^gJrzEehxk z!FhbTe{8Bd@H>zYt%5NgtP}W)oZ0;~`~w%TRh`>S&_i=m?E@*bGex9Z(08uR?|hxA zX`677YXKgy*U=IJ%c+{b12rc*buv478WJJ>kP(#~Pb}bL+8~{}#gInhgVwx*jvzS+ z2wmc-fbs-j_!*)g7*pqHcAys_`XuJUsMHa< zg{NPjE2kZNMa!>l0YB8PyQ?lTX%(Cy1q-T1U#FVTg4g)Y?h?)2e&!-ECdqYTwH|R~p8mTwTfsh0zxXgxv!+VL zN(Fo2b$by}89%AEt}yij{|Zo;@}nj9r@Zm_?Cu%5^oUtHxB=|T+8FR_De(EQFR<{i zWZ3)0$VaWmB)Gti%_umE+Ta=QsYn$)!#vZG(1?rW zXaj0a8CLodJyy<6g~1M;Zi?i^P}kKS?(b%gcFb%Kdd_sHBYsK8@S4YF#**)2=)Enf z_ud?aXKZK$W)%#;#!(rsdlyfl0-C_WGw)5Xxl6E@NpucNbYDq0Lg9JHBsqqW-UI0@ zYlyp*lU(mG4d$q-0elHS0%vS|es6N=3QN&lat%#FRai>P3TxwCJa1+6O-(5OU25B2 zwDdO70|K&!pc@;+p4B^r!id-I(zj$X_QEobdNWS%GA?8?Z^ANv_hzmak*sl1S~`(D z^kxzL&LWk~rVP)feUr`jJNuM|l+8Q_bMX1WrA8gV1l_t;HjjUOmjaVbFzZEWy~%Sg zLg^MKO7qgqj}jREPB8eLZ-0l%mC2*s%=MdZpC1f7B3-ZJw_szgLPxj- zzoo5EiKpa!E%Ra7@5wOjp=xb4#&-Y`x>alQXD@w!z1*Q{Ko=JI_cc_+2ait$=l0Yr z3_%=1_!r=n#j`JY`=0xH$n9%F(-%b- zmo#5kDu22^o9#o_-s1ZZlJwh!O*PdcgOKC%O@Se`q0r_Vi{>l2j%vXnPUEVxN?#z|n-15T_?D(@ulq`$TC#^d zqt&8|{y`Ue_0{rLw#z7@>#siIr&o*BF2R1SdkkGqTXB!}Bmao!$cx_`BL8#vLI%M@ z;Ev=+{mw(ZpI>#ki)p`N(L1*zFs}YJf7{(qVnZ5X67#LH>Cr1%GmgkXXuLAvGkb=h zT=PV${;QIHgQfnq0J-!5g2XA}j4u*Z_JNypeFqW#2PK_99-$fN0T_%AJ#SYv_eC^_JUwV$hls^)Qld?L7Pg z;;=-_vMR6=Uth6SUsE{c$uR6|y%!Y8VFzP~eXfZs|4H)MCpGNRt+#^hn`67xqtg!f ziLTI3W@DL_GpwaEg>;;@6%2j|%loy@e`sg9RcDDF36>xTgj`;Kt$eNYXml&Gk~3T`eW{{GNj7x{(#-52yb*;xB6#zkd9 zg(pU0>r2D5%k-+tqoae-D}(E7EiVV%%f8O-tgVbPe*JL&?8_N5A#mh_^=eJ&>hRF& zUO2AGUx#x9L9~M4YMpkHjZSLm+IVRn^-a;&s7E%j-dn7Zc zeXgoMn(sliE+R<0|JAP-OUtF3!)xomJ3i%`5_b&Do|fb4l?tvtOz_(}R=$<|`E5ve z?Yl0$7EJNLtbK%A+PCIDvUM}*ryT)qn_#)!oQ>j_o{}#>#hu`mop;s;H7_~f(Y%}Q zRQK1Hi`iG?9~~wCokQE~c)olj8gg9s{y2a8xXN+M3QofCPZ0mk89n{5N6_>AdGt<& z;HK#6$>)tt(h>zm0s;{B>wXrd=Z?AM_T~q+M|*u!Kci1f2#>#%{+wny%~d)5$#!TJ zPh9XYWBbs5^it1ZL(Xy422-ofsC4<{`6b@Q9>A#y}o=__w+v4?58)~AF%D8)Yw0;ze%zm4#9VVz3&*yVt$#t`}IH7 z5JW&Hj}l>pVOH;XA|av<@I+!xGR&YeVKklL(K8OnHZv;oKh;n^S*&I%U%;v_5>LEV zCzVxWMgnz#Gy0rEaw1uby?(X=o=T_SaXmpL7knJ~CYBWI!^Ln^=xy6|Dz(V;5}VPI39``iGy~RX42T>oUn@{R)kc*31)(r zypE5O@(e>IZj2os81priK64-|lAh-uK7EWk)5Vqwz`d)4L)43A<0Upwju~?I&W<{i z$G1kw>a^Kvj=_i7qtVy$^+Rzsg*Rjoo}St5f<*IEti zYtr}H7tsm!FS+vh$X|{A`?}mfmyOrdG^0pxYCDat<>0sPlq*bN%HVwSvQ<1@rm`(N z`1nOTCoKVa-w~S?<6AtUzMamw8ExNpLX#1OUC}llzfqoj@lT@Gusih5-OeCr&MW&z z-B@sTTyv&9Rm+$2j_PTesLowUweQmhhb0hojv-%ltEr~y!Jt9*+ZS&*)Yiy8i7Lsn zOv_YEd5zNk{1o_^-rL%6JTi)KiPYBXkfN3IwSaLgpV^+Ei%<-Qc>OCA?_iDdV@T&` z+n8yOWoEp0)N@wOZ%=Cr>9Td&o_H3t*OfK6y|ytIj|^U?-jc6fu|pHdRLJ$Hb=$hI z@A(=5Nt&e=#0lB9$$f_fcNg7`1ee!?q)$W+plI*Xs_)25y}r20K;tmmBx=gbi3`Ta zBa?a^J=qijU*hNc#ttuKe*zF0J4ZDnPvpIahV!$}xLSnr<}^d=FH4QfUw}{5)k=%@ zJb$0n9ZUv%f2T3MQZ`D2|>d-;X+P)a)~hZW(xEgzl>Eefhqp zXLA032SX6t|1%hZ4lAQX2qW@_$v_vX(kHLdrRCvKhx`?IUsQ$`IYeck$|I|U{7X7Gdbq2h>FH`A>l)z~LR2_*4Z z1VJ(&&|z-^^q+DjS`z{yx^D+T<&l}JJRAw!URCrKLt~*WS*TN^1p`az24Ulr5Py8Q z5@yMcflMvQdale0(JLfJ1<6jPC?j>A2l{rxXutv}=CcX_APaLj0L4VsUSR_?D;c3s z2u~j?)cV|kWeGJ(2mUo?K9wWvFHosRbCi=wyXB?}#CGzd;WoZ@42k_zu_NQCnR@=y zxi@H1thiwUTS1Jg8?zb8X zgxyP;SCaxilb^g!Ra-b9U+1svoSu&a9YDiQ`O1UZV z^fJj?AH7+U&w#=oyGTY7Zqff)(UA6G$$Hvr$O5|qLjed9WkM&iBM}JqKcvx%Rq-a}_Rz*sJ;;Jrkxc#Au1SL;dneNbB@=cJ-6ZV0qjMj1^v%NiMnA=vZ@&}$4Eq?daqS~5Rt-&v{1Nf};jHHan&>Ex*JH$+Ufr@#%Mb_3kI;ne+>iMuu+jd7J#wh139m9q6_X(91_wgz5Rnf=DeTlX=(@+25$X8cx$p3uvIZB8~b1m`^F5EYV&dj*3=8rnk z@$FkEBfhEEU?gQBc{!n#akCXAw^${`4Lg5!>J=Kf<0SkGSI;h%=6Vq1<@@&Acj8}| zxbj(0(x26JJuITbsGpHP-+o6E-wl9mK><+YCJFOhM{2}Lif?2u?a#XjalmDculyeM zKYtPa<711T@|(9O_)5dFlesS&8xj;ww4WSYlS_s`Kj^$#dlr5BXRlxF!7ft;FgPK= zqVS`s@&3zOMXs8{lXLpwXF8rtI(Ieiu2hBo|{cz81V54?tcbYo_KRb(LVvWaL)Hyd&Y4^3Ds zK`)YNB6bcd_8YhRg@!xFoxX&dJ3A`&dz}3$4(p%gSS3vwVV<}(*H~Uu97Z){G@8D~YN&}ya6=`b{-+w6qi8Oak+4JxRHC~~awsrPv_7$= z4(S+6>a?F+21%*lNvYCIsc}oGL!~s-qf?qDQd$mE+90W~cv4?$rgpidb{{5+!4l}D z;^7mCId`eFZizOUTsY@gYy+sMBJ#TAP-@(1WHM!ua zR)PCufj4h~=TU(_Z=o=tFwniw)uJ%8q0p|lFyg4t>T98!1?~%qe2i+yD_Yc3Uz9po zlzvo{iC3J>Tb!#^oMM5Slw4dqNs6zJD~0e@J}<0j$S>n9slmX8wEw||(HPh;ybuE$ zhWrN`7QPNIkkZF3t}cE%`8;%=j!lc2L-zki*nN1j{r?aDe?=l<$KJ#&HA;(GCAOkU zsT!?@s=fDah`k!ss@iJrP}CNCwpIs98>6VLMNyh7@Av0>UDx;g&hLD$bMgnsc{vi# z$K!dwJ?$M~!c#K#J7b3vu%mO??|$SAikXkkrPYISr+%b0@#hK#=gzj~uBQWeaJnOa zE~~%>z>_t4(H#<~Rixqd0Nqgm9VrDzUP!jKPcJA9cSY0w-lvVl64}0S*+4=5`H%b{lR~n@!pklNkg3;KF2n86|6+T_)?{f# z7aXyxX}M}2a|2Csk@6+JCM5v2#4=0p6^_o!3mguoe@;q77}NF{Lsj9_E0Z8H21;iy z@FP6+D#8j}Pc4<051_%n5L8GcQq_kw)sz{)bBDp!;21G0M>$2 z*i36bWY!6kDYsQBeH>Ei+*ayN1$c6n`Chg%vnOg>6l+_BRG_pT1=Lr>Y*xf`RzgfD zrKpN1akO{@)U$vjO2I?t%bswSXPuSgxRmE-mA}3Wf2&^%kftgHP(>u{5Lp^BS{6Z7 zZudI9ZmQ<%W;!7;eVK~u+a~8)8|Mb6K?f;wSV;XA0B-ElYY-ea_bb^B>6N76&k!{3 zUioAUR14DZ76NrpPwg&M-B0~Gz!*4of#(<3i6QCTQSc%&eE|M2z#B()PK>Xp7h-Kg0c;c-`I`Kz9V)*CjNd{Snja}! zeT5h;YZ;-%Te8lYA!tQ4RGUWeE?u$lX6ZPuCP!42moA^;ci=`&9t}o+gr(& zS_`rpA>Pz?p0~MvX*L~e?;K+z2dMsF>HnZ9$$Eel^gr$%`62Z+;eXt{EOF305~grQ zVytKf#NnR%^d67d@Zuf)t{uZw9phUalU1!RN#Y&>>HyFz8tZ!v+>tu!>{0HR5A7If z?;uVRJIG`xC%8HVwC{*KcKAsR`1rFCLc3S0y4R?IdU)dmC-udbRw6=UPWd13(6`f}TK7-&Mmt`RbdB)%3~>ePsWlg#eb4Xk1N#_aa^JFcr32Dt&Tc zeRm88RB8G(I!qj2n7e*7_k8@&PGwN${-AMkpVD|A0H^qdsAM$k;YRh$R(0xk^aiL8 z-VPfKS?CKt9}<>;YZlODNyBe;^h+g=yxL~`E=>t8q!f1@&>M7wPFY=jL8L7xq5p%o z%*D1>wYLZKjO5XbN{Woa_2DHnHDT#=c3Lix%GSONV`K*-5Pq^I!_i*|(+cv`nj@>u z`>nWzkzSRt0UDrafvUWkK3|vykZvmpZL5)hSBJ9o&;WhgeS=}|a$mgrgL^0Of{tGf zUdi>ou6pFiZ9=Gr?wK?^lRyjY0YBuveMrbxB0Pu#-1S(gz7XC7rA?4DLGpu%fir)y zoqFaZByeGKIh2i75`Mlt0fgUUPOydc-BK5XhC@uNd@ zWbZZO z?L4)p*O29#_zwVq!W9elLD01!;EHHUdlc9SPrZ$vISuX%<)l)Rru-7Z7J1_z-Y}ta zHsxYA?Z%u!C-njvs)?swAi$-dkFK&dxGc@t>d%rf%qPB^1qicP$+_pWfN+4FShJnv zv7L2Q)b)3;S-frEUVCN&gx&-xopWP-};4jxnGLh;S-lfnh|!A=$Xu# zxg1FmPibloEZ7@M_j-~|)7)OyfwKz*(?AfRodxB!ky`qV|JZwPP*4Q|G|Pa!e!e2? z0GdBZaWj;14?&@Yqb7J+1x^v@>52pZng{~efn@K&4R|N1RuFmlUiHuawfFM8>ZKSFYKtfFm7T1|8Uhz6YCpM@D?tviS%}YrHO9Bo|Vo*tTMCvurN4YGJdw zL|Y{O(sUWS@*BQhWk*SvWGfoSp`l#j`}EEP&NSJZc8hGJd~d^41CIgwgc7hJT_}K} zuWMp!qE;6Uohamek&hrQhk{&$7sjgU!NdZcDwA8>O`HqTRIMa?Px?!kNsE`b=?l6d zMbc+xR$JlcA6ON*JC6R|<;{`5VafpgTUE9RR(BxVr^*EAfd8mUGvQ(}k0$YZ0M$P+ zUSJ@4swZZfZ6Xm$-2Y4p`Rb@_L)AgEK;5X(ULyrnVL7R8P4*4m7z)}E{mqF((8)Nn zJvh3H^WZ!|(t?+$KB9L5s)svNbv9LTyR~e2?*WbE?W6Yx?M-BAz)ybqpI3Hin}O8Q z_x@yQn-K?8-_ajR>n%6WEeo~TS0?wKdC^s=zh4X6?fkoSAhFFxKSG0}o-ZKdd3t!h zPWBZ|?XN`K=(PcgblJiCRO_hEr9BV6lH1hmvbA{a0Mb;{o}A)~(>JcbU#b=&a6iJ* z8nq^9U*sNo?*;#%qmeTH`YSiIeVtBmiw(C==VJVoYn$`SF57?Qa?#^eQ;RX3Y&;04 z-9G&b1T@!=au-g)?6DLKI(>HgR33Tw9RdBGyXND0mg@k^-(Z`$7j7B8n>W0I+1m(b zp!k9!{oURUFE9o9f43(7?(C6*ro_he9|yOIM|BrD zNMaj!ifqM&c(F&Ep@-)*fDr#r)lfTC$Z~r1=5w*Twf1wXt14dft3LonYNf6}ud3T%cZRMC2DZS%1hC^|FoO z99mu=LUei4r>argeG`Za*zz8q z49rSX8lVZL09gNmqWgHfa9;mMHT)?{zs(QfH*ORgW+Frj#w$c${o&p{V&TW2!$GN} zo6i5gRl{+Fnq?WBXRx4HwoBtj&r_ej3?Q@&)m9<4A5NylD`SR5Uj1$bA!z5@Rk|yD8Y86P32gM-{OQ%~$j0y`dL%f8i$8WEn*G zd4a@@J`$`KTmR#ZP3Y0lJrqXxTDniP-0?rEVZfZ!B{4w?jjyNCmM&FI$5xbJGJyXS z0*C?tAmK|g_4py@|AVRb=g;~1`JX?3h-b%VXJ>y;PX0fp-r4c--;iu6(Z))mvYKk}&F*P;y_dmGa z#Q5RF#M$`x`N+u0$mq$)$l?3DAeF zHd6hkCyO}Ze9`szr1|Zix9E!|J>nb5iHV7Wfr0n$-;a-vkB*KG4-XFv4D|N);_>+I z?(VLxu8xk5*4EbM=H|x6#)gIl91cgUd_*jRkz_q$F>p~W{I`PnZz=S+s_J)f+(1=y zU0q#mZEaOmRYgTbSy@?0Nl9U0;Yn83@3d!UDJcgjsU%SEG%1?+jC~OqDMpA|fm-EF>f(FfcG6Ai&?>-^a(t%gc-8>$$nP z{Rh{xx3{;owSD;Tp^c4=wY9amxw)ySsfmfn?c2AFjEwa4^>uZ1b#!zzH8qh)vbA2L}fm8yhPt zD+>z?6B837BO@FR|NjN`ILN>h6ckV>l$@L#0)c?RU@|f?A_yQ!8p0q_`VWAS^3X7D zJzPN#2F7&x{xGhvFAgrKpQBg*dLW7Yn#;m)ebLZU<{^@)=fnCxn0o50Qc+!}pZ}Yw zXF%>`kI&R^s{B}G@y2Cww5jTI9jY&p$Dp}-?v2w-<%6;28taCulcG-S;tN1o(67zK zvA1>K(w+VvrrzAG_z6b1hDF@}HuX|W2i0V+A>RE@rXCGdAtL;Wg+abiXWP*hfI7$Y zpy@D0i`^LF?^M~a;Ga70p0efhhHLF0RpVgc(z92#PkwEEo5(K>*xfxUwh7%nl`V(_ z{q!q9Q(m4$X%Z!c`c(Z69hYL*9m)$eh>|VoaeS)fO!0z=@k|Mdg+Z?qxINy&MK{Kq zmXc*ZIX!aWX>dwUynfJ9l&Z$MQGnIV(-n%A5-|f5s~0v%rk>7-Y3jDHanJuY^?sDR z8+wOB=<{&9gSB16i0I4YPYcR2bw(S*;u9e@%D*l1@f^`+u2w{bx#KG~^$IoC+l@ zyw=`K2F$5b^Juy5ykf-xT7Frnm)FyTquO7$tZ*u(ReW|Hn)~mj-ls7sno$on8!{wr z(i9{ll$74=%*gCwK=I}|PM`YPwqzMSb#$%2pxeFe|8DBV8CC}fu2LhwEP!oKH)!1+ z1ZVLx@OaA5{Xts)`pW$`<<|sdz5V&mnaB#X*xor#YW^v!3ltj~XTpJ~Zok_H|zCl_MJF&Z5?9-bMtC5w#xA zUu!y`r-Z22Fo@2<{0y!zf#{G6JnHY$Ryj>i-(!aeffOvd8$tsL!wMnd2jf zvSt&XpYlH4Z^N?VV!Qljdn}YsuSARrdj37tc`?EGOJ-3ZQxF3t#4G!TU7L{NVZLgl z+`uf+BfgG}lS}l$8We+hn^D@!fN>|%4a2()kEKBJvy;)ShAeE^K)Yk)AntHGzUQ<1 zXc5`NSNqYbCg1dDDbN5n;XkIHULPA2!7nJSBN@%8rb`fHcf|H75u*x|5aUa{QE)xU zZO#JarY; zD&$_*V`8a{j-hD5{KwQgcp9RD*2tp(dKl;;lmK?g)g@3QfMEr&AU~);@?G|Rb`gen zxrSkdYv-C!@`^n5$ys%14A#-vtw?KIo=185;05kOytqk}E^_{7Mkuqr2FzLSbOa0l z2ISYFQPeg7l8zW3cXcI={sDk`g>}>Ahmuhnks(06=piWq6S4uB_aPXXY<_{eT!ag#A}<7KMu3PimREDdqHfC%NCdL;DfuA=H}q(&ft z43KCf2e2Y?HHxBg#dchq_(*kkHlwDLbay^~YrXI0Mo;x3`KAESNBtjgbN#ZsU&$4Q zlw_t)ad43yYz#6)Q7w|u57D&MqxK00H>9&q|0d6&Wh^`zzr+ zo9Y@G3lZ=ge!4JX4u(xr0VeVR^whesHwy{GDs3Oo>cgVRd(adn z?`J;^Maub1!A#>E79WP%hS7oey;vG=ptRzk*Y%A^{)?7 zp9C%^!3i7}gy^h*@fBv@-2q9Xp9fN5X*6H#`(%Ge$J1`xW}!jt;_N<8N1W}K`7K9K zU%ApHmship!6J9)rZUvq)}D6UBQhU$7AB}IOf!7l8N2Qbus6fkR97C4vxr^0^O@`L@$42rygZsnmBAwjBWwwki5WY-@{@7t=Tqwq|jH@lb$yYqkokB^A4c&893P`^~ygqBXx%MjS+w_h|zr!`PIxkarg1SSmePdj5}9Z-p2Vv53Ry4;&n0>9~?yo-IG)P7SCExNCR0t z-xi|`%^g|Wda>#iCzV-s9>Lzv&w3Dl)9*4s?OmH|>;l+bz zG-s9RTMT=(9S`+Avk^#+Ny4@H>w64M1`A)7XaK0r?X&6ZzlY^~ojDA>W4vTGX~}*< zLc$}GfY~%+Za*5Cm6}%3PPw*At{Rq-5*=Z@LfxmP5`A&Qo6$V%(kt|!sKV`wlpvd* zZh@T8v!09HP~sl~y&Cbi%;ZGw@&3ym?owo8@VLFyn^zNNB0^WDQq&WQ7(1_reZC#B zo9^|Rue^Y4>=wb0fljIopS(~}w<$3|#%=0G_qG69_pP2n- z96~;1HpWDs_#6;Fg#{jmDXW7g2{f1Rv6=DaFJ3a8oHppczrLgfk*AFs(igiEAO!%z;KRsdm z)53VMA(jFQu8U_ZLq4>Ao4Tx*j8*V_Hq3+ zWMJZZ{rYpH#q;7fS0#U3l~zor`klrR2_OeyNfuah=jZ%4g9S&JERX@T_!nY7(l4nC zpD$mrRg^{=OY@Sy*y(?ssGBOrkDWm!xjAR-45xo%d8r%;3^4oe5%P9O>PcGHV^MmvN}%{h*|ToD{L_r$3nGaA*#%><^As&v3N+0R1Pt z1wb?gy}{ER;HWQ)MuP2xi{|pI8ATo~=j~8t);eV#S2&2Lk)9!BY%XIrh*MjPL3tK4 zKN4IjN8ybJ-@s9wz#)J%_4j?KBZ_tq9WF0wG&+}$b57&nbf4A(#vQ1t0^Fj1MDgk7 zqT*gEdc&M83bL;|Yy*^nX!=M5T#a=4hl586U6gr!x<5L$bI^2lOVrI5RG)Hy;Z40NU2j+sY_d_JyogQ zXsH)xnNL=!hf-NUNST{eSrEz88wEnUAs&=m^0HgFu+5l^)VhZJ0{ zEUqlMzgdzxTAs{VyWCd3YE>Hr!?cQi@G{{Z6Su zISs^q4?NxG{YZqS5mf@9OO&!+sZe2Q#|pWq7$B2DHHw)!oVhAP)q5M&ini{rq;Y@b z9s0beuUQq5U_OO5T-zzmAh^D6q`|K!%o6?Jx^w+sVnsbLTCZU8Y#0@Q$aXIspmHT> zSL5it_6t@Cq^C;5QrW=9nd$CqB)w%RDnkVf=gV`|6P-Ch`V6$_V2k}X$f`GFw$v+L z^qUA8UFE#*V)Px8#zxk!k2sP}IO=6W8Ab3u$^Hv+&5^xegLsw2col`W3yX~UEc;$x23dufspl+C(k32UIdu{ z>6Wjuw;Xe~8e(9@S8ujI*kIU_rwu7cwH#}({=@dbnjsODUH8SYUc9Y{tEteno$=sF zIl8G_x%El*o5(Sy=d&~-#vQf+9m&}p!%23F#3cCD_|&j3?c+&LpHp{aBr$cKB+XaZ zFNAi{iFd=fx+o4}rr@n>q4|tuZNc6td(_=q)F>K*Zpo?+GuLitT70Qjo3=>j-z2t1 z2UpO7-N9IQLMh(uxD#p;_5s&EliBuhn2p-9Miof>iMA=6K`tBGvQ0R&Itn9DNol zeH1-Zx7rz;5OnisB@G<4Zvog7ple6KdGU131h6`edSm||iLa^v>|p$_#D}1-`&Z&~ zO@iax7^bd=H-?!9SC4hxZ~qn6&TgB!q0rxxGe|i_i^EZGVrfYdA1^@XiPVD>TKIZH zZ(fBEkwKAIda`R2fA)E53L*e$9jf~GEGCfI)AtT66Dt-I$A;6tLK(=M2d0JF-~55^ z^Yb0bz>o3o9Eb?YLwGz(BsGq77;@uZhwlKi1yI3Jp!&&w9X^1PQktv{PD5r(Bk&ux zhns3nW&&?w5I1b@-EwFdANoo2NwBkz&34eNbpl!~B{aniiKHKppfF6 z`>Uv%Wc-jN62nKJEf9jc{mbwTN-GnLIms9(h(HFoz9hep$H$FXqB7Q6(p2Eqgk8;? z{o)+6NqVHpuvX3|BK#jXaMk!{}o$!sfyWad=si*JR@$-I~wNx*lwO&=vObklfRy1`qC#^X5SamIsx z_`S7%`90^Kpg{!9J22%BgftvMj{$&6FIweSMR#t%&30r_)}|9xO48~ zjlqFWkDOjjEJ%(+BcZ2gN@XPMClbbT0MfuMX?T$UM$!kwmw`zTX;8m`6{CXFv;U>? zu6ac)fC7{M(0i@un5>NjRZz{T4#Cf!a3gVXu5;|$%8mHo0rAB}sLa2k1?fr71C=+O zv`TPhDXfSZivA4%QO8p6!g)M#^!a!&X<)p9yShT!Qj(_JaQmq6l?kAx)yA*XudZB5 zAyDkjp~4udf8gWq4aXa#NFAs|U1Kk&0lZK&yF|FU;$=7nO?yy4*R>C>$f2#?9(Bv( z%`8qs9Gcc?Mz?yVLrY z!0b)dPn8SYo}aO9b@yO)+IWBJq53Ccarf_TKJOIs9v%@MW(p^_SQchHKfGcH{`?kV2u?h(yDyz*_A?x4jq_|TZ|u)ODu)T?8iH^)Cy50}0kJJB$dRK@${AJn{O ztE*+`iy#lFyB@Z;7r}R8{qTe?t$kSclu0d`f^TTXWG7`$?kVvw{po4w{WF@SjUfGqXc;`jU~&ZcF4?GP^k49gE;068tMR;Dq@)FZe3&w*kr$<%8U zO%ouQdRJTy+3yHxUX1)FO$@JKQ z7Xn#kKkk&?%2kcw{D?BHfCa8qkHTF)#aOqB9G7P_>4=}UA6+BA+x%e>kS{W?;8f66oy5|z=iNW`S(A^^ zef+NVt;c**)$iQhMww?3AKHwc(6;>ETjS1udHbY*L-x|fVs~8K`T5L7)En3Ch~E)2 z7Y1B$Q6s><-B=y}&t+?;t`qr42U2b_TDrG^*{xD_wpe_>=I{BKaXlTi4>BuaGu}nB zWDujL5hEH#Pwn*F8L7?TSbQMD`m({egP!BdR6XyTt7+u}tgn(Wj8AeTRdVlCGoZPq zGyx7LyiGU)hDLY4} zi%QizN|(A4clN6c8LDrX7(qN)61YY7$A0)0%P+TDs8g2Al99oc82ah_yRX z6DD1r`DFJZE<>K5^RP7HBA2z>t!bx80F?2A;#L&3i1~e$FEwe*PK=gs?UM49SlM-> z5G!mxDx&3?R`(H>w_8V~Y3eu@Fc_f|Q@G!3PbsqJ}06Rt~@)1m9d`X+%c)yd4 zQ7QIcQ%_el`1?!8e@wkN)sP=$WnCd#bwjG5TcG4M`kihHwXkjen-{m@T^E+MA$E@4 z;g=@(oHM*zbT(3+`043+wC%{}`c41&{cQta$B)xu(J!tMK>XK{bSg!BS;mBAMt1d~ zTX3)PqHleM=7L0sD45gQ>mh7RN6Io2OhJ8sS0kVhWszGNrlFi4P{UXyzp^`)zP2-0 z%au;1^o;x%ZQ(Hi)u7>JZWUBK=U;CKt4_4b&4gFud9VSo2(j1?R`DR?DSDH5eOI=* zIgEK+mVn`9u!h!3TdEv&ATH8giu6^(kC1R}97VSzI@pyHq#YSvZ>qRDqv3%}i7@O* zLPH*%@_y{&pvB+C=|2*B=`TT89AoGbgDP)>=7=0>B+3m-#3+Rg(FbX2A1x!}=?)C+8Vns1@3ROx zMw2-qiD2@!{?gna4g*wdarRfY(y?C3H{SYbhRK;U&`js?M}yMIu=zD-p=MGP_>KO- zcKnrxry3FZ@AAnlBf)YE`T=X>xs$RPvW|yu3g%`ClZu7?tY8L-$8QY2%ic8V_Y&=@ zo_QM5QKs?udF0XTcHyP(uk^%aO_HFDX-~EX7=SWvjNPKF{r>xPAPSk8#ZhCXw^&KsD zrbQ{|QR#!Cs%R)eSTFC>+lZSryqB`mhNIpz6sdTKr7MqGFi?#=``ucqGPXl3_mz?7-+vlS_hg@dhov2 zhbCIK*l(}RrrD~Jc@l67XW@SFM@g=GlLhB`v^BtTe}|nhR$9+{>nkS*xfnIn+m!SC zX1iTxchftsTLT0|Ci={_?OUR8&d* z_|D0rWA*ied$*NSrAZ6;%QoRlb*9G$pQzj_mbv3b9@^YYts(pVw^U*5PID^N)%H07 z-O~Y*^b%6g1Cjnb=Vrt^>N2Lh6mB=C`Ou3X5VAdG(R+%cZSZ}qEU<>z2)1>X`c=Te z1oP8>)a5jInEfs~aFF9w(&b1+x6WT( zzh!QpT0`I`5n*&kOXRA33~Fx&uB~!bXI^~CUNv{R&;Q%tYv;i4nxBN1F^3}vlI=HP5!|0J=ou#pN8z+QMA{L!M4V6+2T(}!O55R zWq(u4oMfv#NKm6VRN}`_|GcL1ZL8fzL-c_{T&Og~1AP9`qYN@E<7E>(`6Fb_mTDo_ z+e#R)j1jsJq@?0j`z1)aZ6t-b+;gU+{(9^>b8&ZFIc}P(fwB?Vo8EK2(p^rH_)uBQ z*ci`(I3H{bgEUMQ4*dr;Lx3?Pi4P#fa42p|$IFu>K3JTA3k(dQA)dT`&iz4s-kLHU zgXGK6Dg*ukvgFm~=Ffno`o=%#!m*n1LM$`JJ+6U-9?_L_}}LaJHsM~4n$ZHn-03H+^M2;wcgwOUvA~h*rUBA9s%VXBV+t^o7m55M*HVX8vR`o?bqM`@l zu8TrT)#H&Z6yyN<8tNJUNgNLe8=`# z0_%8R1fu7LO7F!l%?WUS8J^q%KtC{y*E5cbIzjsb;NsD3Ff@ zIR+l(MMC)YW1GQ%6$#<9z{n5B+KR%w@DNNq=1F`JW-=ch6pv|q7Hl^h+cB6nJgC|> z%y(bA)JZ)tsmI5#bM;TPf+2;-&tVJ<kU%eTuc+!VaglM0$AC0&|q>FnLq!DA5khg(-*l!8pm|DKr2;p(Q^G0d9bx&1a#QVR9$trow3K zn8B@9t6TA_M&^e4B`{Gb4UICbuA=18Jk(It0+c66aDW8xWs)OcQTM&#{sZvYNn@_z zVo{>;Mt&rK4`L!aoLJvkIciijZ?rc)mh{KyH4Kg7n&_4t#V1n*xMB1gvZK%{fhY=F zJuoIH@&TH{4;S-90+uPODO+vSQq8zI69wt4Bp)#Ny#1cjor=o~VU(#(95W8*jVTm)p{09TJ}2%$aq+#RE6)$_{dh-A1oBGtF!=#FXWSEc>YyuB4MusW56|_9?Ap^z29*Xuhv?en@eC_$Yg%WTAItevF5E z>>ao2MyfQnVEp6#L59UC$=qp{oEpiG{;!(6xbOew7ZB7Cz?^(WlLLGRi!{l(9>%-G zukMM|UIMni<`ogeb&D=*5o0zGWOOuE-^*ZIFinaR#{C zJ;sC?1qF%-)Zxd=+jsBnJeZ}-qtx1nb4De7V?uowAiN+kd9$%$C*(+Auv@`)ra;8e z>kf+u7p(T3x!eZ|9!gF)gXtuJ_Upr!op-a#A)&Jr{(3QlZ7EiBh61x?2F4ZQk<#q; z-4!;QSAarHL{Kc(pe-HmLweN&)|O}wY}|b>j0OQp+)fgZPpK4N5msGcGk7F#zWQh2 zTfTJkE*=w;vm(Arc=>=5c|smG4AtMCjhY070kxX3*cJ>lSaOx0@$q8G3h4cksX!@{ zmxbvG*_7+|1A&L>K@?Unu=!Fa!V%eq99j*&aX9(49pY470fZH$Z!~qx_pY| zmZYb-pnCvLD{rmT%+dUqQf!b`8B1wp^O&dWdz#leCI}Rg=@_nqC2F+@hc&Z%t$lr* zin=rig9NQO;=zK_WlwaRl#k;{2wylJl3oij*oY|y(}c*|brQ@I9axj(ZS-x{cOJk5 z(x56N!wvSsDz-KH80HO+3m2s*VvX~J#YPF+#p}RrOMhg=Zpw_cu{(UcC%leDk`X&G zT%zsTv7=(0@wTFoza-a`UsZbKZQiWh)KPYL{Ar`w$RWuKO)XEZ!j4&zbIO4_1?YTj za9(UKbxF6x@JqqSk*E^U(dr5>q43HEUCf{oHwUYBpj@eIhRC_T{hU&>6K6tM8#PZ5|k zE+%}E9Qu~r3Lm{@lsFjcR{h?orWrPIl&XwgyI^&J|K3XlVs9$IZk~{@IPh)yE<%PF zdru(0VyLKJTKr`_Al)L5n2nZc0sD0w3=i6=@lXZ;QJ51@fU)!mvjL>;0Uq_#ou)Q<55b695?X zD0~Yj6g}P9Qr*25eA%0QNFty!B1)wNjNSF@=5@x)C)i?RFq!0A7vJH}*b{?)iSsA> z!~Vndp^+Q08?`>k9(J_4Yl(0tt(HjTlOJDo{PskApBjThq+@TNKpqvu4W#=0{&5vj zbLf^E*E~c1Fcu^?@$1IJ6;-u>bQ~cu@9?PkEJu_qIT-GZ$Y*Y*7?; zh3@+AOU1jFL)e2T-dL&6n5a*oIrNTSWGMrXff!@35ML<223}q(Y)c?iAtucJ={cH< zoMsRW4hq113VGk{M5HyPyibUgCFy;7821+PUdMcpg0%ka@a_i}_Z|g051qw)_tLx? zr92D!i! zB%FT=jXuA8uQr)|naR+6uevkj@ivcm2IYUwS;4uNoR6zIQD%pRLt$0x8i5)r#(0tu-gr@y&SgV+cX6VVpZH$I^OQPpPjLD z!&bzpxGVjN=U)}A1d1s|jSbOUk9_=t+t;nTw=e3lxVX0hNz%6bf-MEb`**tEBFk^x z;|byS|4eWdl?C5ofLjIe$2zE=M6@rr3Z>Ik24WF|xV}`GC@&U^)P%RH(LNOSS7f(=T<%wj}@Dk zUYC-14P3Kw6H`zaMot&-NkitY?3HU?4O>z z64ry!1hsA7k?u1LruKNJxHbN)@7}IXLtQSk2T3WiarbYryH^=h)>dG(XDb#TL0ezQ1y{;rt%s_UP%2FU-qt!lK@~ zp8fDE8xv)mIeav%?v!ea|5o1Z8oDDw1Z%-M4RCPMSzr_RlXd7;k_g$$qCMp!niew** z-Scbxd$I18rJxgt)rc<&nHT5yZ62r!z+5>*6o!5Jv2BpoR|Hj-a`ytBr3$h~2hr5` z%N={C=(hm!r@!(wpT+gEB#y}*iw>&?q3FSP;D!`h1!VMgu;9l_h~s(9$nkrcJO@=? z&{I-BwXpx+eyWom{T)zh7(^3YrpQmt(%UWJb6{M$1QmfVC%8{a$2nA^$diidF~jjX zTWw1XtWFGqWCXBAOA)*_jhf#~h<0w4Vy?}JfrW}>xLv)4I0Vt$4kBYe1++M(oHP~X zt3>HGCZ5>6ES0;ppPX*US0TEr9#_oIx`B<8B6HS@bMt;tOLQ|1e2*n*eu8Wch{ZbN zX9f@KuH5O&VfK=pdg_Q5HO=1qz$G>!ycqM7zsO9Fxy(YF-thh1x-b}jUB#_)6AwxF zpW;giFkO~`B)%Kbh=%7MZ{AEye%iGx5KUI^yW+9NO}oFwi4h8Ley2O><-A$X9?%KDepmdFc1v3u zEl>deiqhjY2gR4Fvam~?xKfr|DOIORlzLs=F4CKN>Wl#KXDvVf;9zAD*o@0op?!YM zh4ATJ#(?Z$fhZ6pO%D)IjdV*@>K;?n^=5K8m;7sN@ko(bexayMZf>{VG3{A@#cEt) zNc(u=3&ojGZbe0ycoztLEoX(loE%ST0;hV8N0CPfyPEco8uXt%YZvdaP=jYp#^_|= zw7%46-I{KmJ^6%{^@7UgNH3f=_uuwyiIaCB)%#~3(E(UUzR{K$hQ^Lg^F;G{?LmLE zUO_(cWQaxy8Am5w@ZU{6)(q*G8~>VmL461*nMBj=C8nwt(jKX^+H-~|YFB)TRF_Pg zW%3G7lEsk9-}>0_`^y}~fkJuU+>J`bZ-QyP?uX%5Z?<8;=KE1>)tNooc}XO~Z-tf$ zq-{n7Q7U0u#~oC!WzAHt$-QZP=Mh1AixTUKGp+9fx_)JYB5BxYm&g54oQQpi4Rxlr z$yn9HTz->PtO9+AFP8Uc^zmGC9!jGo@@i?W+3hqZ4*pGSv-oT94mx#%yR!9#e3sm8sxzf=BSlxM`6&?^uyXykvFnnrBII@2 z-o)N#*Yt_8z-TME!-?$Mece7TlInF?Us|_uhDIhvO8(+=zwTrRUFmp7!$yK7OOUMJ z3Un3iWuhg>Bty3&;~SRQ;I4~#PUx&~WZTw~x15sQ>p1(M!z2p`@ioNk`zK~h{0 zn#TSlPIwprrf(6Ty%q$P#~-wN(g!ST%ah`Rq)CSa8DPW!kL>61@W)IGp_m0ZSbUnQ zK}cA8CWh`SkopRQ2XEtI=%Yy0?VNbf=aZNo+SkzV`(&_6JOv-u^!{BDGR|StkN%nW zimnci{61d=EAdXpN`LDm>oKNK9W+S_R*EjJTRgR=1=|?elZ%D=7QLsaJW-Si5lpym zFUVJc?Gq+?L_jI~Z!qH)DruMaq#;OgpQZR}Fu|Lm9x5rS>ipIPSax|59#XAHFY!>E z;y^y}8`Hx(FU!aWhrIB%8Fnw`F2WB696RbY1q`g_8H0L5OVtGm=`dj^o&q$Q+-{2Y z9hgA74C~pTzmuxZEyOZ!d{G+nh1FgKIIg28cv*Kh-UH_M8~vp90Vn*$W9FGPWc|HU z?tEa=Mth%CzvK2fl8+kOcbPjH9^IE4grQ-FP(KGZ$KyzivXgNUB!~!ixAmc3Vk@5m#Encak5P%bcA_Sp_Y)nyPdf z)5kO!nC3YzMY1n_M#D`{CF`WMgV8a6~F|6sB;=K zNjbl~vw+Z=TmE01-Dg;n;hO0CKmsHLNC4?AfGEB9n$W9s1O#bPRHXNsK&T?UcaSb1 zO`0emNU>3*ND(R0J0eXWC$5=Ud(GMV%*;OdnlDMN%jvFbD_rn1Mtbv5`V3ci6 zA&OpQEAIQ2CoO%54z7_S{aJz5C!Fo#BtmzRh%H&`GY<&#NwW#;pzw})@@A2GKaDb& z(0V3A84kPQ7D;iL0hJ$vee2@~px{3vr^AW9*&eL&+GRRz;#NKEoHWl?g#~ZvogPy;APf7` zO=mKA7+UH~Jv`U$m;U7Mbn-i2bAPv{E!}f%$E8e<9t^<KkGAYd16ZOezpi?K(wmApIT5&rA0x1i|IXUyS%a-_E3?W zH0$*{j<>n%ZkxBPhZEioAmvsDA)o5@$q0bzJ>$b4sYc3jqm{XX)NZSTBHr6E16<~t z6mqc0NZJkOdxw=on7O;rP7b*sj$@S^an-@HuaWlsPv5yT%ra=vxkixV4iIwGQ?OmH8g@4b240{xs#ygby3o-2R;~@MjL9eDwnIn zm%AHj8Q*6h?*jz;ZkWe&=ks)wJtRo2g5RlOsR2>Z4|1okDi_b;dB20rYV6TN(ce~D zRS0M&f{cnc^wmPvR=@2=~Cn)IVOr+AG@{!@ z*d15|?=#Y!9_^h*UcNQ}KOGODxGO((ttwBI{%zr!?x~ut<-#(vn!854+K8S2^*$#_ z5McRZU(L29VZ|L@$Uu{UhAY2EovNVl7$CViC$W|;qt*bv=~7dRs8FR4q-~Y#C-|fZ z=fL(F3A~q7owTfbpSshkY;n(Zr??CRs?rBi?Y?K+)hytr6cqT7sCsKir(XhViZ*4t z|D<Opcuq(r*!7z$@J9H?3d>$Myee%e4iF{7RFs|3pZL7 zoYH>cTxp{Q2PFGOQ$Y%sDuT>=Gq>u=Y6Rv4-9F@k=s(Rb%BoI;k+p9LR9UvHxZj z>^yVd>Zbcu&7MsrsKZEg=g#g=!I!@)_E#6&Pu5;~y#Fvzs2uhP3-Vd!2OS(z9GutJ z6XdyQ!EfJv^?be}?rXo$Ui^#8FG8yeJM4xHvPVL+399^6u;hS)?r~vlxW{K@;a`b3 z5JAh%M_JINnd@&$UFhqEy_1GbWeb9U{((dd%@Fj(5Fu>89##Z`!y3m+UurVDM98W# zi5%<*icna;1PR5RIE_ua?NBu zg>(HH?=a&^6L38JXdFI)0t%@eA>@MLQfP#b!vXrxM|?@ImDizBk}O0bDlC1)UF zcijvtbEzWtpn*%@gSWY#PO0Hm+JQP*p{^*%OH`w&#*_KI@JXi#=j#jzNKm}1UM&E9 zF+a|4BMNpFy}kWNP)e0JWMtn0WKS!~!*;|7Z6u=`5qUkC;^X$m`Y-TDqlWW#&+xW6 zY815b9={LbEo@N3HsvKYu}A(API6&d;g|n)gZ#k#zzB-~G|1^RTg{7dK%2*0`fCr1 z33UWAlv{Kuy^$jx0xArr6(xT}`x&bAAp$LW95U4_Wd{7zub;&`uV|Ug;qkR?M188s^$^Dr~y`> z3ig9Y;(FOf8~$5K$=Cc|KScPEP#)ip;znwRW4nwaX@?;uC>7&TZHPoalY!{nqL#b3 z2JJSVt!oLDd9g;T{>Fq}LhP2V^YPK!-%50UpXrs+s}z>csntxM7od+OI3}$we!2{;58NYh$q}nrT=5RC5WVW zweXhTy~pCb-nSNyT-|P|!mE;)Mo;7(`^kIx5dcrv_&}8O8aJgtm9qTyPbKu2eDBow zIc?usC;hOVxT}Or^`1Tv|KZo!|7mqa~4YMwLi zxfAG$WQhM={4ImHc(2-J6a9q0f03j~QiHN^Ym~Gf`>xQ)yE}xjxX6oRbezzcfmA!s zO1ll4Ds}r8lyN^BF=g=m0LGWn!U~>a%BN`-9*nd-_-{D#jgFLH>eOvXUw2Vu6VkK% z-+zpVMJ?JhM#=*maFvVlVqCf zaHB=?y75Pxb` z3n2U4IjERPb^ACn^*$C2DlYwcQG42!IQOAi>WK4hB+cs!z2|57#xJYZIa;iGPO&3u zmy*kq_Ra2e)$Ydu+s;rE;D~G=mQ#+OT<)=9bE<#qhgQwI7C0<`pXBgOg~y z&R(TOAjY|^{rTWG9vWkE^W-u@+0jU0v>CFqEx5bwF$NQ#*%&HS-E1S*RoU7Kl&*!* zu~a3==KpFd`}MZ_LKDvo6I^n&16i0cLa~uctReAym!&W%<$UzZEjbnbssj7quI95Y zA?!_8pnOlHgl_r!Z724s5xD>)3U@Z>FJ1e53Q(+4_6)7yiulML^6_=oGEJvRh`Sm; zdhpnxfBiDUIauWriWv{^)e?eXv<>q@28Tk-$*;U2$*y?cTm(&N*f~AtL{r!10V= zpRW6mP3h=1E{|vS>Q)b89ykYkqjkNn1nx^BhG?m`ZoLfq3d`Q^dn-7ks2pnvPR?C( z2#YFEx)4KOJnv4_Lx!glg3_}|i&yJkg|DuJUmIUvKoxOm^vF+VBsW!25CHrZGnIbP zYiS6(db)Iqz1mYcq3AO@LI;f`Hhe%(CiSMKDel@jcZkGN$3<8B-%UL!&$aaGl$B56 z;qbLHjazn&=CuDYLzT>t4Yd@*ZJE^QQ9EtX?e=Q`9rhAL4q9qVa~wYpsODw|5`L;Q;MPxxT=7yJ>W??KaEN9%pCL(v@_c{~b15;} z(x#8{lswn9dNcsK)%b}@hYKg#IN1FbLigO~Z$$ikS29{i9hE~cI81um0Nq()<(g~9#QN0)DQr01B z+DT^LRuY-StzRiTtYpbFf5g@FbvhRP-A@*}oU2lH(<*{k&wWhqZkgLxD!)#LUwwYv z>L$PyPST@xm4x$z4BTCf$4kejKT=xsvaEge_!fu5Kk=Y%8d=FY0J&jC}PA_-*`XsH)Xe&}`B`iQhiaMM9^0xP7~D#hAHI|IL9&#@H!$<9DuK?xNY`RfluyLM${rPKS3fy}zC!_}&X|QpT@UhG7>XjAfgH z@QeH?v#n=iiDtWlTV=Dh=I_JEBCM8;B5$o(@~&duQii9y=6_mi+zZ=x;zt`_7!pU& zJ6}fpXo)eCI2t&L?sa}kP2vg)G9Yxu=CT@8Fu3>$TA%RKbypu6E3rw-s$Aq$z+XYk zy%Qu&_vQmSy-#t5?%7&J3Iejrsh~=-zZ;d;8@n6)^4z*51AC+gHnA=j7Ff$^b!-01 z{3&PLp;09*%hGQ1spd0(gRS>O1vO}O29hnhp3TvuTi>DIh*^`7M1si}a-T&YJAE&a z8=3-~zDOjJjUvu0Wg9FmCgLQ3G`u!RQ3hu_YI7^XS_nPZqHQcF8 ziKo!)!cZnwqsq5>{dEdjV7KSHv^I>mKPK0*3w|>wG1WyA^(QD(#s}m{FU6(F4*X0k z9_A7|%+a@3H!iyBzfE6Z_}2PJEZeR@pRUkDk1FU0TW}2K4wV=Ij1zLH&qC>E?Jt_c$9UPc3J$zv-m*@D`j zjK8fOACN;(ViXc)t9HVrLP z^BK#Z4bK%)>|v0ZflSl3Pt0mcg{Y_x+Ra%L^FX?QnVHty(YghdrAu8V9Yh0=>wrGO z!KG(x`blYlc>b+iI;QRK3Eo`v|jux+Ni-eDjI%Yrum$^(0`nXid z^z};@-epl}j0`bBy-EMH_ShE{1fYxjPHX^M?zf{gvo`{I?op9i9mf4W?Qd$U--cM& z6kexyaJ4>>M&+X2im@!;3CPuH4Bt3;q!Uy431j7q^oO$P`YyUWl7b;-kI+k5dR;k-ziMkc&Xw0JQYdZ6s?*f(cTP0e!4< z0pKUk@2NohIRw4v`5!dReVJ}Frd)V+=<1n3$)XfJh;&*@BL9pXCQK{N4*l$;()E)v z+^prMVx!F{0v}XY`;S?oHKPBYvqWhk>KcPc3f@MTCjk;ie$ftsn_yt~mum6+Y@Qq@SU9p~cTZ#x`irjl=m6?af=w+F`DT z0Ov7U7twfWPxB{TD>7CvECv1;RLSuraYJ~S5WL}nsn%b0A=^P^F@Pt$X$#BJp$LAU-)Ie~WkMx6CoRe#*`f8@xdT zI9nuBzLi1|hmKHz`WH$Nx*_a^6lUanFEmQR{9IIGw#>s{_TTLso zn56L2G29EQg z3jG=mcMisSktY2=%-dTCirNay5Dp6=6@_+0Ywaj+AM5I06$<<=Tn1uoiK7-7z3is# zU()Bo*m((9+SLh`**_2PvvRX@90;%{V1A@x30_tJtk?xF%9Jgi9#XL<3JMpB3g4@L zDJ^U8r)Ib7#%JT$xVcmq7h)PUKZP-Q!{o7 zYXlKonf$1iDhzPL=h?K`5Xl4q*D}FAZ$G41h!Va>y2JzJvhq{ot@m`+3h_R{Qy$+!%H(bP089@ z?Zfe!Xb9geqGbZEd3KVfvR7mT(9BhaMgtZGXK2)O#us~xOdr)UF%WDVv|$5=9KBR` zXV!7QGB+5V)vr1*v~D8iQe66y2_lmJz{)Pf(V@ZS8Oe703)>rQ=&TbZc5?_1&bR9y z%fBF^GwLqnV~G@TokDkBm(bg4a{3-cJBgahkBcLzmQ}r8NP{aPv>-jo&C)41R^Bte z)+D#~A}@Jy+i?J>yUFI|b^8^Sc&P|`1*LF=*KBlCd5`U{h~cpvKu4w#^GE}`9ToX2 zIPsqsKJgS>4NLU6Hc=s#=X@D4U8T?7$qQea8NCsA&85(;ph)G)ddmD2E+}-!z8=qM z%|!%~5?Iml89z`A}@WDFUH_X1rv9`Ot%2n!7$gxJBSP{I0 zt&9K~0^zX%5&=yV?zZr-Q2X5f8d^&Ieqxnod6|ZoOy@BDR!fVP5K52q-hxlJ=Qw` zm>NrH;c{vXKT`6tP#JNinY}85|6F2I#N2(AQ4^AJ6Fpg`NP~>a$ZlC?C`4zaqRBY# zn5I2en3=F(qQ1XkbSKmi;DPdJm9PoUu*6gt%LrRVd0Rydn+L|_s*2=HrJ4>e>vhN3 zG0~dQN!}?jvEh;QJeja-B(((^+eQvkkN9Sh(Mn8bSls@s#xQC6#z@jSN|LYDQE$bb zUGg^e)jR2vEO0BB%uI$-((taYA{=o^7r%AV z+IG>3zo$)UHS{3KdZ4uT$i~EnZu&9HsSgp6S4S_*0`2v~@0Q@*HqmL9vL#aaQ}0P} z&mtPnj2r6vw7!^WeS{R#zzZ)O4nOu6?olmll1qM`S=qGW_JM5{tG`9ceI;K@1iZ?U zI-lf3qFBG6n7w)_sh8JD3BlKP#Ik4#Sv0}?Y3Pzv*s6cnW?R_qX{ZL8;)5;ZtS$WN zG@L*hO%#BJdVA~XCMcV^X7}dsN3`ROODj+tl zJ@(mIY>ISTMnGH+-qbsb!66>#_9|X3#?_t0H%dQ!74Wp9{VBdB(0dlkj&fv^igrFr z@NNlKi2yASP{r?ue9ek74M^OT3O|*Kz?*t>0TI8=F@esE2ez`EMO}7_SG;z@_`+3%r%C-lMW=Hqi6D9+4W@L06%;~-? zv3^3)`SkeK1#bDwKqD=3I?%zt4P^y1VsX+~Z+utd%BcB0?A2AMp}jq>r|6bC*0V!0lJ=N@uF*>N(r z>;lU?Wp8U=2z$MIpQw6h~-i_9DZ@(sDba&)Cc2$3a136wyqbFaKP;><})k^DOm; zRPCyeNp8CrApM@^Rwyu5v&jvzQc>3vuuhcFg&=&-XPdGZnokXz|D-g(lzsRPQ9~#P z_t;^%9OjE`QwRfdv(DYjPRw{`lxViXoN92KSHiE?uV<^CF}(b2QCn0erM#$k8_(a_ zO&7mznvtvg&Lj<-)6wdvOIw4EQj=YGh-=Ap>&f*=$ah&pso>V^IY<}j5>Ty_^1T{C zy;se>s0`F!@0&`rlyi#&n<|0h~zn(?3l+bP*ZdLPif!FnY@25Vd#I) zCb0#~OHq7I+qG?3{hsON*d5wW1SHH{Ls9dNaa|hER?)BLjk`k}I$-ZIF1gv_8jGwxKc64a&-=jUMLUlnzf3-D zQT@1|Z~yDk<}@UWD-p_?{V5VsTe{>xQZQigwSH!P)R@)?y3fXpdb2A(9_c?WM)~&r zQDgtSh1;XyP>5ozk84R+_tUx0YN7Xsb0^E^CaWo@P`|Qq;9&K4g!z#V#m_My--6M= z&=2=IMos?=Zg=%Zg?8S(O7ooYdd4EZSq$xY*YFzf8N)Mx^O;VY?G6r|7?jOvD|i#f z!r%91Q24vz&LXruF}uF_iL|@L9b?c$+?_&GbZ=9~0pIB!v2YoMp z^Bwy3^Abyrd(e`=>!mlpmhgKnc30jX@<62T&I=VT{!nP5R9G^#o>RC^Kq;E5y=`nS zp8t&?BNHtOsPr>sov@hrUj2Qs-0)>{=-TF+xfcu%!+qYKT0^2!y}Ya!@4g*~TbPz$ z{kCeo`LT1Y_tkiC?fWNNBVWC9xI-ioueMY|w_(?-Dzn=-PsW|TlQrY`pIO#<8Jlg1 z>{Byg8)AhM(^kNg`%A0WO*yOu<(4E6#eekUx_r%ecX?_wtf*h`}8`4^5THf zW-WZu#>RTb7rJ#`Fm_8;_c;nNeSK7Cc2K9V4Pje@&HwtGyZ3u)?=WtME6gG*ZfoVw zzQ~UaDfttbx4)kJsP_E9%ZTH@3L(o5eK@^cRHCpEHFqY(b|S%6u%dWA6L?-(dJZ*N z55D&(D{lYgy)zq|6YICLx9=6a>8|c&%kl}&UJHi3wOuX`x22hT6Y=BsKTSQ&WC9jq zFq3Qun6gAUnv&15OZu>M;29O27xoZFJeYzv^;pRcg|Nf_Vd{O#5q~_}71xZ=&XA#u zz@{{=50LxR-jInGuO2Vg&Eq|{U;n})VwEdtt?V2(Sr&7l=FlWjYyQIgReWgaDrOXe znzqCX2^{n7@O86GEvfx4T_JxiuAtHli@h|bM^_K;3L8FmU=q?B=SrH8w`S%PkUKHy zHq4ZBe;*?GWWFDxm35*i&Hm_Ffbm!H9a+4o*YbFdmNZXrd9s==*zc2Lf{B7%>Lu|T z8nW&%+b}u(_z*tJS8jT^S78PIk9HJQ7Tj|Fygobp`7w`x&>s;;2YFo;YMY=@<~gO`Yu>u%=-UvZVI(i`fT zW`tWrz3&&h;%_SP#);6_`T|Ka5!NE4Lknt9qi@Mk(tAS=Ns1@s4tMAWD(vD@^vq_W z`Mg$X%z1)Z%Zvo-B{(yL-UX~al(6(!Ng^cLbi|u_S`})x3*rxg)f9%KLj2**R`G_c zRmztv^31d=$uyU4w5ti}IT|JDy#^&P_j(cl`) zZs$|iCMKC}&X$RVr|xfsW}wuq@u*pgyuPTC{th+Ohnh;`s&)tFo3xFBcRntNi@e|G z2xyGJCJw)R%NkDBq{8z0r@QTJG#5{KreugmyUyfrlQ~So)w8RLH?J{42Bx}SIu%Xk zGpej2?xn*8^z$;-!j|yGinLu;8=1R)82nn);Y#ya($tE2+IoMd^fUSIPYz=$Mb9Kl zonHDJ+h_^BuWK_Cg7Al%rA0}gOQQtxrp3<{jGLL(eTJ190m%{kKSqrc`8mn3(ZYKz z)MN}m7P|z6H7jKU!~*VHvmP_7uE1}zBJ0Zg{*ynyC5;Gw*pc-5s|W~otbO@1@hKR} z$h0VW&YHH!@f#a0J*>;kzaOnWlZcQ0nRHr=*gA_|HN;k#Pq>%LE=>CG;_T znuxs;03aV@pmH`y0YKpQup<$*2hm8M!>1T?{4S3b$e%m0%4X$4f(I))uG)9*YnR5`jxy zKF5c^HModVNpVl;RSDU-IW={&--*|VDDQDbetPh9&Kbjl zNmSXcJz|M@N_B`EpOM~d!~pTL6El(jn4OS;sK}^DZ{mx}gn$E)Sd1xwU>98G>+6e=eKAkowK2&QNk%Za^&(e}}z4EZ0%Mp=_Mu@F) zWw_4R>@>Jq3{5; zhQT&sxA?2I2>QM_bQ%}C9g>rkbEt&wdB=ookVrHjzFH-|FA5KK{tVvA1upyqDs$K1 z_u)SMg=(f}L1=P~iU2U&2v%$lLXNwM6h;WZ0!5;4@%em7i}$US)T%~ui%p=-Z4Xp$N4E`a|8DuAwJrJmS=xA?-nqQ$rRjJ8Y3b!WT80BIDWAh#be(c(M z18zx9VRtIkRRcMVReMf)P=Q%XB-@Ur+3E?zJj56&42_9$> zTTy{GR$##1C?WgT;}f7B;-DTNE4NA%+2epd=Dmg(C9-As<8P#xhKT4k#IrDF<+k3{ zIgdEVN(6;|PmOrPGxz*)x=R&upl6iCki`HTu*4>|0br5sLEq#H9M*MfN-H9B%Q- zIxuS^E`8#nx)S_DZ%V2gSMVSlnE!*YySdbv|5h_q@RADW%RmAH^k-B+t3XM>`#;-1 z=;@>y!b2JpK9+ezKV^PU{Yrx!jeI(Nhj|6#5cp9>P&3K>vOA1)$Mg1$qm*rC8`4UU z%wFSEYZKktC0EcG?qMR=bNA1y-3~zq2~gJwNbtIezTFp737=;pR@(r-3myJ1R1Gh0 z_CVZyCP&;lU#Rrg31*&8eZTKr_Hlb9N>pxkf5GGR9CkM%G}z$HwQrA&)uztvkb%uR z4qbfrLm!2Mf5=_?_nn#?39Sds3v{1U?N=Q>-M?J>y--!#cXjk!Uv_Ps_1rIl`MA(M zv_-nx>w}W@NpqH5F^J7?e!cL77%Tg(4-`BN{UP6L-2LhKSWOBY7^jb-$d6VYfz$&I1b#L&24=wdMpRT!or z49fnI!fEK2HZ(XpM5rq0fe}Dhm=Hi8uGAZ; z6dSGx#;Qn%D{EpkzJ;mBVs)~^w1=?!QiQ^2Lr_4-jB}KDd#I=;vQx_Mt-sL}9i8n4 zt$i$0tv~AnbEYIZ@4GIMma!tj?ZJ!FXd9R4{<|@&m}r@ln4o}|2c^-WTrme!v4QM< zw+v&sP=1>&G185(Qe&|ahq1}uVjPZQG}fctrDK7EHuVle=tlo6&Ghy3jGegflw?F$1P8>LUwxpTZE1mcymKf)u)i#v4 zD^0&y6>-R&^h-18w@cD#Y|?pE(jWRHm&HUJI61Hczrz-&LJV4sP400?h72b|hm*mZ z$uO-%N}iPOnkh8H&*N(Iy)D30M2g>X~AC}Eoi#V-Jvyf6;l z0;j-3aQOBaQSV=G?xryO3ErE7QzVYkY2>8q%%tlxWEfjy+|9|jCj(Dx_{+^Td&uN) zdIn-LwTIIQdozu+G6?N5%&Rk!Ic3rvWG2hAw$$iCt25D%j0g+-DN8aO+7*BRb_>I{ z7D?G50DG-Wr(wF}^Q=2EIc{3;%(xsv6mh35#qlUPI~TmvBJ&Y-dR0bVr%XDsDNn>O z9RSaNcb+FKk}n?t*+!7yuigg-YQVq2QDQ|T^yeZ0Av@%;FwkicA0jmXjzPN*G6*ri zql15la{!W%l>Cn~`6CPkUo8rz<50811q(cX#W`#-P(v6;VpFOxzoHO0R`_W%9{?yA z*D9EbD>#`cfYB&?HCCAB%qN&t$XBByx+nxQ7D2U(&Up%lG68c4vIlUIEr1rl;2$2J zR`G|2#Rt{Jzwqw|UP^cfZtNkJF#!KULVi9h+^8;$v5#*wEK{$E*VK;J=4H~@V!V^f zXi#&f+ZKv9@;d&(&7nN*Z^0qNo*-N?5XcUBe?Ytf0o3)7<2|~b9y*gp<>vTkD5>Xt zeB+c9z$FZGw}msbpa7$&K!Qp_&vJ{-a_ft7BFYK}SyZ1fitcA6bD61+NEN`K$~(Ra zh$3EFB&>q~JR4vQQKJA*B%JgL@vp=2YqU=9+|< zn#JxlOXW4oJ;v4I$+-mp$wLI$LIdi1i&jB;3;%YLDqpks<7OPX886Pser(43R2eOa zR#3o?bUJOORz00o11O-y07|%2{mP>i@&{Hb)&jI^(PX0Y`Pc#wZqitT74mwU08 z1{0KRR|{_8dD@Zlm^IRtB2pL>)kA^gL(L=`^c+AtWeMdQh~J{gF)53jol=DIpRzJ3b@cmpVoXWGK&2ry7UhR*BgZQ4(HuSewGjz508!PKE# zOi_sc{qNmt&xQ67=rXMxJSSX&q*+?<0{~O#ETR&_l5}!%yf~L^P>pPo4r=s4^#DD4 zKq7>spL&Q7djJPurZfthi5dEPtHgbRgYYOh7_2-8N zTEU%nN4 zg|ej?KoV}!GLnMPr_6M+yQ83u|!Q9mVE?#XY>dF!j387%Gxh0Evt+$>sqm zro^&#)e^`;-?IotA&I+tit7#K2h$k;R%8DWjV0!zXACMvQ+sVK^CzHe2Ay#itn(&p+Ae$UmR3s*ixJ!DQXTXg%1AGb8E@ak5=$;#>^Sv z+)&g^CJRNj06h2eOrZe0SYWp7$?Us_(A^%2E@6kMS6Mz|vsnc*dEaM>SZ1GF&jJsv z#w4r*1FdVVXZl&@2K46i3v%*ia$W**pA^rw4b$~q&AwNd>(PZ5K6+RsPEq}4w$Tf+ z45wf9y}!xD#D4&LyvPV?!6Cme)7RRPwHQ`M$-)v8`C0n9= zOPYE`H#lVrqh*pifUT!7YP4up|3{4WrR66e-%DVkE8d-ZdcFi@?I1kFlb(5$ZY!@l zf%~@0Ates-x8RDjOhgAzTmfTjndTR9`V)Nq)|NOG2`iPOkCl5Ju~hx&0Jhs@+5lZ4 zHYE6lE|;QM;}|Br!JP#-AY3|V4B27EJsZ+Pg?L3Y|5WjJvZfeonYp4E@3I14ieW2%!fepzFe4 zuqYGtC=+Hu`VNov29NcK-VcsD>)=O=HmQqff~JNqgj+tH-u5|4hUhm|{yNZe7u_B8eXyz%r4s|5h3xNA(vyNUnZYJmsowws9i{)I6;v0 z&eHKDX}1--P<|t(PWmPDw_y59VgHvB>=-3 z^xIhfx2gN@yGg$-UjDu}@>@@T!y0yCCv;K{Y6LD3>d2lve0gF8BX#UPafhAC+W@kY z(`VsepxxUOVX`Q61*V7mRG5O~KAa{=+i4~@{uX!u37Z}Tx_FQu0?3+KA>VCb3&If3 zr1Kn`w8Bwx>s|0k4>4~%tbP%gFIVW?04p2?CXNn*>#fkDFU=eMyHjb!%!Z0fD*WQ#a{DYN*xrk79s z_0plaZ=Hf35Hu4cz0L*!d{a~?ixfhs8q6TB{{U?Vlth7Z%q$y2ENEIB_-Y=*x&E)F z-s+d~d((U0Gud`%QimSRshC=M69sR?=c($3vl+dLH|4tvxKC2}3p;(}_$f!ieQkc` zm-A?eTBX&i`eX{RjI-sQ>6#dXH%=WO+&p5Or2LCn>*kFlGAINhCns< zZuMZYMy9%c<^As$z5zQke@(s6WwiFfK{c?|X_49EBwFj@uAMEy?QBRZi`(w*>+shx za*`AlM@Z$Sj+g>_z~LSeL~Y`MB4+YA=pB_8A;Ft^EeFbEViO)J6f(J>XUwFY&KVRs z;)kj?j7>b%XsshwnS*-{RWY=WTMpHky^r}3|2G&No}&BD7~T2#`Ptdo^~uTA$;tmw zqPzO_>wlBzR{tTUfIo{|ciM{jV^(URt4u*7LUigwZ)U^=JQg7@gQBZkIFOf5qsW z{u_)ghdg!!2ABO8jLv&NNlg64*nfr5)k2mKp~C;f=f=6~Z~jucoG{uyi8+9QC!SD! zzJ-?D6<1g1+%0;$(BUek4}gZGO-kjxUYNF}4sc8Trl$9udQ6zQ_p58$Zt{$A^CyWZ z(G~Giq+(IJlxA=+Zldi6lCxH9Y@%1dnxIDkB}CR%i<&n zC*OTkO#>eIYdrTh=~S>4b~W* z2*M#*Y(Hg`ODYRfe$k`cQ;xsBd}~x)e=p|sBMH@Cx{%hG{o@nC%`gewH+&XS>H}ge zm#EM8_8Ufh#`SA1c?@kRPtKM#!X8z{5_9%zAeF9?xYnL(34kKO9|-`I`>}me8zoQ* zW_#v6v|2A~PrUahAcLArEY~0e@vgb(q@r$n=uykk`m9zyJt#Ij)tS-GuP$&L*1`8PW%mJOs}2;~iu8)eb= zsq;AKI{F%azjRfuy#pzve8z}4OqDb$)y@t;D+C;+6_b^7Yite!xo?I7s`5WDwgb__ z_N*-MA)yBZXa=M+q8A>8O0c8CAUKnXIQx{G43bY7Kq;~hl3|gVL+aXCkFR585ARTt zYuFy;GNsogHY!D5NJORfqF2-s!vcc50J<5omSX&*N zPIuo%S6LcJax*D z@oSH^#V$(H%jEHlp^Yf?!6=$Y#ez$RV8ASLL75pd)XN}9Kq526NvSvrVug~T#c;M9 zybk>_*tX!e;RD3=gfn>Z|?6)ua(CKKOAz}ahFfdcbw7I9Xqrt0_euKz+ZhFr~pYp=e52DYI8|sRREe z$W@l`MPdh2j*3zZYO;nli+#je&*!%hz>#~elm5JFSrtiPX7 zL`_N46MjRetn~V$pf3mIGyMl=1K~3b>aq!G_{mcHmk^JRNA?kqk0YT1k_Q+TCWmV4 z%HR<&L1JYs9g8z|Q0mZA4_*7oi7M+>{sxISS@HwWNYZe!&yg?THxl009XKAd0dVG% zQpa46^N*-KQ9Ur)O0!C9c;xYSPMg~fTkx@1_dDW7%ONQ;(`8@8I=o{)f>rbpWb zUvn!dB<~nmr*?$Ff~ZF@bGR7o^;Amelw?j_t`x=VJ>9}Vx2U7x&j}OYan5B zeFuH*fdLgWTpfT~nG~0Uqym+S%q_d6zNCgLi8T|(Kx9NT4g{FGzU$)D&Nb>kZ|0cW z_1?>F|G@O;(3<3MVX~LdSLVyFw17(m1c`@^0i?^l=nvPXlYf1d!mpSFj>aX|4pZMJ z`&WpbcNQBRQ*uY%vFS`VtK^5qtW%E>0@mM!ASj88CFh)?H)@hXRwZ>R4ovP>dj@&I zI&b$60jjU&k$T4dCMF7O-Jf&u4`y!vCyW70~Gg-DOc#m78osLp?+DZ%cuF39f`O zH_S13jE-I!Lx(nUnN(ZD-r2ed-}!mx;HLiZ1N}o)oyehX-V7&#v^yph&YkTfCYKsbT-Sul z$1RHX`%VljKDF1VrLCHlCiYClZYTzK+6zkWTLdl7T77m5s@Ab^zLF zBDh5;cUGMMn~AMOK}~jdG<-j)4}^2-F^?TXyJa$$0!3O267jn~cmHsmKIZW=aTS z{E%TXE*WF78C0~HUnxV!ghOpQd^OHh;8pP!t?4OK={?{Kmn^D0gj4RfG^rdGB5*td zhaBm*EX&iZWC-T};pr~in*86m;g4;=$c=6oNOzaS=$1x6x?55~0T~P!-Cd(wK#=Yd zBt%LSRHVB^KvZ_~y?^)f`~%x@T*q}C*Y-Zo&-*1@o+9R$8~iM{B!nCfKmylFOxDV| zam$&F%~`;4R&mRdkIgd~7P=eG15to+qfER$XQ%K;yVYjcz{s}u>}+WAEa>7_$PgfK zfgD#s-v4wv(W3u!JLRI4|Et^Wpz|5_i)haSC$Xs^)wOBQ915Su6@D7>MvoUV>=yEi zaYsAwTw0VQ0eR9LN^Z4Ea_5V7+~d%bWNLWnlaGsWUSypIv$7(zB-e{iC-ZSd2vz~m zGhgB!TmU8PK39cyuLGgdaI^Fxwr&o4QO*avWnEf@7`puCD)IyZ5)F)R4^Mf?xFKc6h89ESpQwY|Aj2ijKqGh;Awnj-RG!-5GIm2 zQ(HnGzia@?7plDe;vTgNafU(REK1ljsQ4g`|KPo9SDR^BoBg6TH@`N&yEc=sHvN4q zhQ6*WzqVMmuIfcyp=DjoJx2E)Q1|5?qpNG8uP=B(7#9tyzgOwH>vQVr%d|mzUHLCx zFs1*h9wAgr=*#Pqy4SDloL;~nr>8@897zX3P8h-iICz$@ zalWo5@t~&veSPn3Gpwhc{9#LrWefFc9c@8NO?OM%tr(N;D+vFt zDrE$J!Opc^^>sj%bkt~afwPY54@_{ecJ8sGuCSi=@7hw zmY(QX7~11&{CKMMZogG=s^bX}IY;xe7qF+%e{wn9>2p6*#Ey4*9=0*Ea$^{}TUV`| z{=kyprbnIGHT6w=4;xlQJhHaBrSVG4|2!^S?TT0}E9N7^@eQpoNbP;uQ(NHJtiv>* z-YezOJ6T{5^DyTvcJ=M|KPil4xI`}aY$4r?hdo>&eG4M-->dpE$NDz;p8oP2u;T0Q zScOSScPf7F;a%+?OkkR#CDDctd{P_uqti1(RINWr#yS}D!mjdQs$=Pprv8xPCwg$X za`4AX7b347mQYv@7fDY+Ho&W$p)BBiYCq$VA@kaxkL+-<`Uoy-;(WsJA;VzZVgG_( z(8tsup}(dgy}e?z!?&IzppUOU!O}l2^nFWcE8b;Skr`Dz8u1^m676lhUTsxx2xR&= zAoqLJnmBfBa%B18;7uvm+I@`4bky&~sCKWvL1HiOa~yKrp#{&Oqty|QM5Y&$IX-Hh1p`@C{zi0t?} zvwMz}v^iDI1x|drPC6I?2K~UBfI$y1MB>6Q&(!~B-sriA*K$nnC*Ny2P5N6+5z9>h z^2tCl4U)E{HM(6VNb6N30N z93~?SZG?d{?oYTS!019LkKAW9P_uD#?^wMj*saN!3DRFQj9?03U)Kq{F{GcHA+#TH z*0FPV_ENAe2^!=_Mb$ItAQ$8}T-a|A`n`p4?OsYdBO+}1sNRD4IEP^tP=F^*9Pkgv zS;Y`6Ll@^JN)jjkKh< zfS3?~v;l$VE=)Y+OVd%b+G7n{)FvNFVhN)su`yjs4p@6H@R`(Ve&35si17Y5{CaRc ztkd8FV4bi?o-E=Fdh7cGI|#i^%vHPY1`1Veim=OWX zj3CV`16)LGHKuON{f4^TCt32aPRt^~(4xl2rX{saAIHs%qBW`6^}Ix~y!IvWj(Gwy z{I&a80DOTyP2oo$$;12q6RDgCJ7^0Gtc=nm z$Sl2JkFj%L>RXa5wj==|CD8ri`OpY&zkl~%w!`n!42TWJ{C{{BvUT46-CfAedx zKka!LO6T~Q&#~c~&d=Y(S7*nnlMjv`y@NYNIl-ngaw?H-_ijh*~Uzwx(q;Pw;r-_vg}k54hElz;Dpey$GCZy)`m z1>P0f-dO8n_dmcm63_dDE>n-Vm`Jby9K<>z^8d%^NC+Zt@P~h>#seMymn_CJ$&)Wm zoNrFVvuYIwx{+_cNAX(pGw%6sya_Lc40?5u?LNw*5E@^hqvTYLQ%+*8q}{L(XVCl) zqcgp)2N8-hxLs z%+h+cEBatj?9yjrPo2IZ8A%o5#apHL{3jh69~!i}CGXziw7MCmE56A-em1JlYMB0x4zgG`@SQqWiC$X5{DZZod=OH4S&${~=x_&_f@aqcLQ ze~v=Tkcwg%xiJbe(Z_dS&o}nje)~AvYfNiV$vNzomg!@TE4}Etz3LL)_`VZeOCj); z8AVy#IM}vhJG;!omi%hYv4f$b$3I2+vT{tWC2`s*>le>^rh#9VnQrv^lD1*cvgeh) z4Dua^E<_YTd-$9=foVZyM{n>6yaWkT`vrYIFeN*vjO8fEG04zmt=RexAC_}3}bUx@aT6~O0a3prAa!@($3{kR+kSfw6oH zzqShe>APBVz)OVscF^>(_=HynVI3bTEF}z;#zymda*Ww^n7=C@>7W+ zH?EMD|6Ds$Y3V&2m<@D;gCD+wPOW|To_;@|zii>_$&Pa>kE zkIhO=wWtn^bw&T1d5IxtuMY{VJdV3gN{(BC0Zq7D^~d@}586xGra@j9A# z+y)El!EGak?jAXBD2gvTCwD{ns80=4KHJCyWx~uo7`8oqw9N7Q41XNV-LO zMK%lT6m`SLln;7uROSioqXk21b-m*=-fg8*F$^n~umS-h@c%2@nJr>J!d(g(IG8?Z zM$oYXjx5yyXzF*`X7BS~O)b4n?V9~SZ0w9~Wt`~ztmmD40O!?Ydmw$KZ4L}be*Uof z`|B)$XVl`tCk+g8lU*~>RV~G-c8j=IbowFv3+eBt3;HhI4U(@2%JqkKhUq;%q{+_1 z*&@^xWtBeIa!%O~|J_?+kBLuSHsOb4Z3@VjEfigd87lmuRim>=P5-6hLs7I_AxLj9 zz{5eW@z&ksl-#%iMd>V{cOc!Ool2rQU%?@;r6}>vWWZFf&h;OqY2TK1X>v`Y&rF>V zoouQQ{D{!DkxRwq7G8J~CtjuGX_qwr>9U!sf#3Ow%{gHNfu>*~HbJj}F{fJ%BD_lw zImZ78vI?tL;C<~X*I2{(2@5G>3}SbzsILf{_w102vu=$ zjjCT3CA8aJNc4)f0>7Uo?UVPcdr9- zFK39*TG&W}*s_7SlckcjCDQnz5Rq*|Kfg;$0vGOj9IR{N&J@dzB$5*qhVyH%#fZkW z7QEX4QcqA&i-x}Q{C1cv^)8JZ>G+h~nJFjZ-N<&K^Zgn;^9Xo^EuqD&>qt{5^V#gO zw{x6*{LVmL(9HGBg+#~S?S*u@4;IMzP`rEhJv+?z6 zdT!>iw+42a``Srido-uADHWx;O|ND=vhDJ%wC{w{ool@<{a>=P)clgbXnVT+DF$NT0QlBngn?_c)T^~r`$|mN7`Sla^ z@oSVY!k2xfTAqWoAC=t0b$$tSx_yhKtvMp6-#+%fV&ad63NM@&(EwMJUglP#w}rl6 z!Fx%;Q0@r^FcK_98^y@%n=<=6b9Qpm`h@-S3pM9{?0%X4HePZNU@t{3xCxZ;Dqj;q zuwIH@`EFw?(P>=l@pSGz(Ew|iE#!)-?BDCZY5<2h=4&#xyB0v}Ws^#na%yS(j-oQ8>l{KoSWEr~3h_5HkZ1JtE4^AeLGf@yrNFU?GmX#eQqtMZDTKvpNuN9#b$k z*tR}+{BtmBBKp3AJYXW4PIf4W9&qBI3=aJf>t#GrNPQ?4 zb=&g5O9^k3vF}j6EI~?Si;$syh-Z2rWvT;P(~Np0Tu2oW{j?_5KLVGW79s|VdG3pE z2WLmpMrZ?KSw>O!C!xGLV|{%&qf_OXYu_xaE6ZyS_x*er>^NK=tjx8F;GLFBNf62v z{*SF2p#xf@qnO-4zH_+9J-{Zw3?xJh`4R|+;jY5Ve}<0%oxTc9;zf=E>p1w@O6u_7cPv1pa+Uf>ZO?5nUU&2whRFimwvtg8@B3|bxmaA2r!(_xuj_`>u zF5pZ(${ZX7gFwyk^?V};gQKxNv>G}$G1{v%@_(XY;MknpHiD|z=5!a9CP!JoWFFjLZnHl^icIR8Xg z=1^U;2qVK(2TCc5m=JM;9|oU!wT>UA2>_e{93e49ln^yde2u_}kb4?^4i!p^CZv4; z08AojwXpP}@{LE_^##+vYNvBXr9;Y9Yasx%ku;WKYIbWB&yfI18+phG>=$Q(NypgR z6(KR;z+7?M)Y$u^QYw`di2x3RBc3xtta9J|1y1?U)jZ*w9gvybUi`4du2O4&%+wa{ z=pEO6GE!qc(X$rA1gl&G17D(};V|HnV0>CY1aJb+;r^yT;Mu_-)=s$aGc~&g;R$e& zL%06ir2d`PWco#BrG%-O3BvB|~$N8BIBE=o^+zsDeItm$qV~xfS#Neh- zqLt-FRWtR;|1p3^%PGe4DZLH1O+HRveqc9}+*6$*Ju+hQdMF+V@KoBtiR8$*}3>Om5-bMKv2AoUZT=a>YuS>SR8{U+n=%py0`N#BMXsV zlohh*6!jJ*8t3l<38kr^#GS*k|8!$P+y!3>+yWL8kS5wxCJzNnGgp8p5dpVLU9YXh zmN&H!^LSbkQy;n|DtXh#&XYNCfH7uBBw$=<#zeJG{9vo>_aeH91*?B(wU(Hw=4C8SU%QZ; zRFtS;`0-;=D##EkBl#e{5)1;riG_!?1W_&9^)1I|5fW>%JuZFhkYrYAX%ZD_l=O8a z3(m9<$NG>G;$MS8=~)O`f6lD`l#E`0N>7z-cMJEeM2ap@jec&Jl)X_}QSQW#M8uc^ z9x>z>eF-UJ2Cg=57jv_%?$E8aGL_voa&xS3$O<#Jnm*aGU+uDH?wTp$d13i%xGcB8 zvTl2Yx{R`6$?~OmGMzhp6gaW0c_Bf<*0v3(u0?hg98 z{?>Z^A5&kWMU=AEM<#2t!*WG7NGb^!d4o)+vW%Co%nMpBYL3Wc!?jDYi0RV}(D@cg zh~w4raA%uBAIM?&M%x08F9`=Z3gZQtn!7MsmW_R@ijIF|m&pL>`!i-+AZ``|GhZ|x zm7khB#JvJy?x{Qa-@<701gH>NnY8)40w@i$JEU#FJiQ}Hd~h5HDz zgcfoY?{xw9Ws>YgI#QEt1i&^Lk7{MKeCFHBMhIdZHxz)cgP9xBw3ENTg>1f4af)Oz z{lKSOH-CW&uZa<^Q6`?XJMWu}aYJg~<8^z{2wIInX$M&uTWq9}gKXT7^S8Rj+v~|S zIN#5}7c2H8E}Qhu1lrB`;Rdk=H?zImjjr(0Edh6Xv6|q2aG7veGlJg57;uYq07EL>kSD`#T64q z6Hb6_Id^0nmtvkq=JTNZ5(a+K(@H ziN=7nSMYUdJ+y1UHWPSR?YncoU2?+rN7i>=Re2bNImYBVc&tasN&|)u_i>76F^?dA zF#K?C{5SV<9RM$bV>9c7IyAP}U8mFc zI={8X7kkuK{iu7rALj2cLl-HGeqYsbdz}dL=sS3>W7+t_>{qM%BA}c`xd2KdL6t z84x9pcKYk%JE*=F2ge!4i=cAzm^twBnatw;clxW7&=P|iK7mVFjcd^fu5~Q%p$aTcuwN2{GhpHVkJ3}eW-PLLBQ&}_=pYrmcL^M_Sv z=aX1HNR&L>jp*Ic^Rdkow^%qFf`!}RvqKw*2dRI!Ts#^sAiSBS!+^=M1b909W1T<0 zFx{Q(Ldp+hWT2R zZm`vWipEb^pn)OG1ojcQk!W0$_aW4l1^euBPdG8?UWqUVdvgPn2D@~ncAWY>ZMg`N zUBHYhpoe=N|Gr(yL671PQ7_;zx)WfBn%IRMm&ec|vXmf;cMLDwdaYJ=Xbl2wPTigE ze)+S+6}aRRbb|WZkBOdMJC~qE2BUo@@GJopY8reTAD-QRoi_$W8-Xtl0Ei-Dx3c{Z zjs7=P7g4zz?!ri{AjWITtmjbuiWqu4ZS>R4?q`^WT`$?aTNkU}k9t7!+^8ftpA!m53UcWv?{wmSu^wj6BIK8YJIQT@0L$z|w+;r3W z_*VEDVtag!NT*k3>VtKp853iJG|gMgGOr+EB}BhI*Iup1;I>RI#O zn)f$JAO2#SN)Cry{~0xnLIxs0kRV31YhB7qWiEmz>oH>YLY*|orzZMK3UA4Wuwiq@ zXxo#c=ckeD)}D}-2P^jv^XuA@bKdU`(Qq7__1Kr4v0>}c)~}y!5&k)F^=RzC{`qt} z#}$^E{kuaS!jF&E14yoa4gdlEhtW->A{p^Wx$ZGKKQ`4k8Y%yy+!n`S+It?jV&%aj zMrMx3Z|)@n7Ie0#>wJTID_gl+iOE$gkU=^3@LNP0K>w>(|QV!PghKaU7O){gL=s z3PCUFQX5pOGS8x_&Vgn(ibJ3DWiadZP#%Tofkq=9fb8W}4Q+SVse6Ad%@^;_ml8)+ zIb@v0-Uan>ZXe)lC&z!J&U%F@h7U`d@#Q8=1XgX5KK-`d^VeU+ET@n~0PL=US$Y2* zUpIY!(n{%aC-=g>-4p+*egL4=O?_>l>FIY5??5yqn|8Has2Kon!YTkf+in4>x)dYC z0jxFSGcyFct~&!QCBA81Q%MxYFxdoZi-!eEv&C^dGAZErHRyn5ZJu_Vd__s`@&iTx zRlVF@RIp7;aUmBl2n;&%8;zEwj&XdVZlubrC)a6+0|2d!7sqkN+<0q0=SMobj7j{PM$VDFT=YYvNmAGBBE2O?opksiBOerG0SFzw zL%)e_beL)YVR@Q%ottiG-u|wQ`&~t?e&Lm>1!U%Ofj}8dCk`*6a>(DWBgA>1E-)|( zODXjURN1d!;w4KG?Yh0?voU!eGI_9`M1u7U`C=Nkvh^PVLe444jh4{eHr-CuVuVF zbn8u%q|>BglkOIg<1f@rWx67VEtJK76(BUt7j+lm% zDa>Wm9 zmoNoOOP-4E-dWSFgxU?$##)K*_&o1^M^X&T;Z9u!XuoCKQnJL}9nGAEPpBEKK9~$vbh9D{t1KJq@wN=+xuD z>Tm`XmQ6D@@@9h|`7SFqBF{HUchok95r}@ZSDt`fk5wQSCS!2}GX4gri{ue?y_`KQHx`0HqL)%(UHl01MgLq`I!*O+p})DzR>`q9YWS6Vrv`TVe|>&JNhV z=@xMl;+>qo-{hk!C&FGfPEnx|X3;e^hR>b2bPgSbPwP^1mm!6j!QEkCd6)qCS zlVsMss2md3a=MQzICG}Fc?twL-OB5;Ay>{x%0E^m8bfkd-8uLlO-CwM;l_A;^pC6S zg~&)5soZ0J$kOs^y-czs9zg}xtJo{Q&0J~{L ze6#9>Y~Ww0)=ZzpnC`n9)_)3q~#{3^lg@U)-d$@Q`V$qCg`&fAr2(`>jOY&efs@Sk|Cu%+8eZv{@ zb4z9EAsH-AbC}vj(|f}g>OJj1{iRuh5r7qrQx%YU4PjMfL<7)1aFs-&5QKWv8I;}^ zLCRk7#D;^kTTMBUm;YU{c<& z&7v4GWh3aHGr+&Y97{JT4inNb`_%oZ<>xR}mr?fGk;~N<_OhKGqGS zBCho56}K{JjDmO>MdO~DSog=|aPf)<0{dFV-SgS~;#Fcy?g;L3jaQoDOjo|K2)FLV zDg}u;@m&jdRjy$S}jz`Zxpcyyt{62Dw^z{Zvsa#bRZ| zAmdC;O;$KYV8!N-QTk#;4Z#|MCROs;@6TJQc1Hq-uGPX^xS5nq^ zxRJ){$j1PP!6Zl@VMx}`=m4^Vq?UgXkZwe55^V&rZ382#+gvP1B#bar^Fp=#+4Irn zh=3PDybM%e8oD{dGznsCH#HR?M)pi3*+QK1$mm*j@0ynuI06N*C>3s?Z>=j{+tiX* z6L72L5g6tBvu5?I0m$wPo4FDF7VN`{@sJ496(Cs{K0@$C8q8@Tl1(hOVUE7#rcfxJ z`2}7MDS!9}Bq;ab>wpd<{|f*W$}TWuEI-QPvl`HW%9}-1{lvJ=qWG1WAm@X!;y)q? zd&?O5@DU7X5QNrNITOUej^cES`pNX|wfp?#{xTSczLRmdkr>w|+pkvY ze~JEKY?s{EZ=J`m;JLpz0HV|=ZuU_a3Zx%0LJYsh>qh#?;L7VNtn8!gH}4XhGd0^* zH~y*F$-$kLu;UzoBXol*^pugZj2K*hTfDmO*I{Y^X(9=Bq%r~pMkC*&iXmpDD(uTI z+!xh@Of-98%F`^6qat+^0DImL-5yX1K~T&JCIv>2USOb-;}`?Di1!3U!*O480tfQ0Lk0C=)NBCuVv!eAS<(@(!Xa5L z3dJBbqt8>~8#)p`;9>hu)OSi!Y8zfj>$H(<8fYquF{DLlmSs!X19>C%u2B)<`}5gY z@V#62jXOf_$POk=&N(;&OEtUTK#7Q#{J>$GC75C0c<@NxR?iCasiK7aVvKQ=04{<8 z1^=)NEGH7a39}Q#|4`Y8rZO3+k+xEno6xe~l5%JF^xaY;{^ZB_*gvUa z#^4)fpAOKeB+{$$5Hdn1tjY|G_|L2xESwfue|=0SHo;(^oM|u%HZ)>2p{gRfJmh_LA)GSE?XgJu%Iyd$x|| zg_8ekRdMZ2{|lFAWmOe+yLvL&L0>rad6S;GaN_xJ8Nec1bydi8Rf|@J@C&P7Xgix^ z+v%+^^ha;?w>%NOSiYIr4f?k8z{7=WgUbLsh;IR+ltKNaRecdT_JX$>83Q)8RD~Z| zeTbu-lc^CI))41Lq8_=0oy>&Ua3@>V7{HPXb;0j_H2^4Xjr+nEa;zJYZBJMFTL-Q7 z7Rkbf;YuPKMJOkEnvH6fWo=p{SaDxRQS-a1(*~2~M3&iTZn}GRyxYrV)Gq<|PPgy& zy8F5_Gn_N31ck#Xxr01tgG?Y%q4MKAhtWLhee~4=+C}L!^}VXsAX7#0J}z%IDenu} zgYqgKJ#-Y9o)A}-XO_%fPkKsJ75V4yR`CXPwEB--dpE-!XB~EA(9O0gc(4tH1f-T! zN@qE@)4oP+B$ngaAXt8|tEyJ1BY+r6@NwlXMWAb#PVWk-WoI_eGTi z0a{Y6QIY0|{8y_IeAuyE*JyO03om06Eql=I#wr=1TAHvigB@kr(^tGqXmy}!BV0;4 z;C}n)P)|3HM|DaSV`K91ps~#TIrDu)2o{rdB>j3Ajf8ZYxN7CzvvpB&!k&HU9!VQ6 zLxdi2W*_yf0Kt-cZYM*(Il!F?s7@o*_jO(YUk=A5;oWEPR@q?Qy$>uXk8uUh>3okV z8;5rAin}3d%}UYd(J8 zaI%?Pf7UM;*r>CjY%(*`u;CAe?di*1o$TJ7tmJ$DkbSDBiVO+_8fSZLc6++Pfi#7Q3F7JHO2@UPNA=C%{J-H18UxXM4M6D&rKt0u;xoZbiOb#y7cd(dd=WpnDEpa z!EOIHq+DKI2vPZ=({ihOurBK1B0t~MYd)gajIn-rA4D`$ZGKCFL;Pdcfc`iPXZ#~4 zaH2GB5Y7II4<5MaPIW=F;{sPlROlM}28Qp-)evL9HD=vc>AoZ7W5 z_U5PD5O+7@mhyDuT^qpc`ck&z=bmMty5^b~umHi?h75PBWA$6N z4p*ngqQ*}~@%5sDjldo1bxu72uFo&HsN2DBpE)V*Oc!4OLZj{?);zH7`rp9@Kd-br zh1Gm(4Y>}=NE@=hNN{ZavR`UEopptdJynJv@0ykT8Ls?SRRgg87Q4UHDUm^;Z7RZ6 zwBTl))Akq7B`u$$Ef+FC8X&PmmhX2e$5~QhpMreK`JcIVxZ`m}`Hn8L(z?ECf2?yu z@aGxw!*26z166Ot-5L;C(1G;qV3paTicI}vhJx@PY^3fPJr@gqCFWVuQLue{|8`e2 zpO58xj_#1wRrGc>iK6huqHrp7Y5#KgBy@V%izgmR`5sd5sH=?KMM1YZlT{?2>5FD} z#8F(59$2atp?Ct=x}FofiLP!=w9O^M=w$ZbWIgUO%MsT$?sOGW^}YC|wti8Il1V9$ zAQS3}Ig*mkdz{(fS73WnFwmYGMWdD(EVk~W*6dBN|NF($j`SQERt+A>y%a^XN9ntp zWc^$8V{6wl9gV-u63jQ&r!p@=VkMFxPGbn(+bEyRfNIan>ec67`kv(6l{r2rcy6I_M#ffrvg98h5@?chGhbwl8?DixSb!kO^mOTaD_PjQc;9lsyneUBcz9{LLyy%Pd&S~dXK!TiON)! z=pknPIT%h7v3`ov=eK z{rmO!5W{5z6b)2>C@nl-=h*wOz%!b`*S^$&zg&=8lBA>zQ#ru_v>+o|(h551=r*Mk za_t$mJT3Ahu#v9ZL+Q~w_=wd_{qS_H{#_}H-B^W`r2gc*RrR(gwzV);(g=aQ6e)30 zW!i;l?aS{vySltA``0Me& zFBQxB^8g@hSbn9ik!ur-y}x{+%Crbj-UUGQ>{#k34-|3oGhBIV_>@m|Lr7sS<1Q^v z;chec?(|iT766fZAoU&x6opU5N$KbMAq@p(RS%s|BE^rR5ph`zPAwZtVo~xqqD^<2 zL_N@&zo7xEPT>RW#@X5QzxPOq`0XrqWw`2>D89O1Q3bjgmTRPOns#UM%o||uEDnD2 zU@c8e67$8Ey0bhVH`xxwP)(U|8@|Q@h8EAC>gqZ)g^u6QMBV4Kjswem37_h1`ooUL zLl>Xs$Ccv^9}zeLn!XP_VNzVCw-7acud%HhU8hwIVs|cHe03XJ(JSXFJD|d>;9|1^!{LeeZ)9* z*d8jUn(Fn%s66bagU(WbY$FQ!+7;s&l+vUH(AeBGim%ftK2t3 zX`01xNdx>Rf>zEw?+(69xK?2on3vI)6K}p@xYL2 z7{v)tY0xXJ|NL~WX2m~N*|_G9U)&5!T%kvOTb z&6oXS9d)DS@52B+X8tc@9K|X>eiPbdhG+T>))4rAqq`Z4x(?rIPg*vAdDO*L%3L$Z zima!DBrQ^Pj z5o;nUCzQkz&Ip0DIP6q)Fd$o?eX{Zd75Gs@ly}_^cU|G6aJfi_&v}KoQqtMPG0tc^ zd#YU{>JgedFv(d2p^yzAo4>&~THSnu3R|w)I1TfW0+-S71;mHvDg$8;$VR-3RR<%| z{JoqCXcTLN1RTh?7~wH4c5rG61HDZ^mhaKa>ZDg-!$)Rhm)k5aJ?K?yg6wO|H=Ob5Zj9vncW+ zwAwAWKneO@-z~c};J9H|AN(sNY))Hrh?kB!`IkXb_;#@-Yej(BWL7Gtb7S6b;E@{F7}-vKq7xxMeiHWVY31+HZI^{Z`syB2T#BOD`uZ`AL?oyG|a!=3hAzG4SMhE82Pz)`4js zn=xv%f4gh72QaeM4XmD8nKI*+$iBh1`Y)x!{uk5DvFQH4m`*cdl0F!j9O70ElO{t+ z9StQFV03x|8wUBrLHP5?oRLj3!E8#tub&0q0a)TW0!EELwfW)qKPVQ`{Neg_AXka; zOT-i`kSvy|4TrHiLJNOIDS-u|M6=gP#HoyoVKQ)FVFm%{FYV*tC?Jap#@8p04u7Vh zY{Z(`AR4P|eCNp9g?Ab`=E7SGE6K6(55o;dKquwpQV z!gdbG*|n#pn>tin9BQ6CJf{oqWpv*aei2~lAK>@g7|3+t!xc`(O}|aFs~q1wU)>VT z2k><*x{uq0{};CrJ$J-5Nb}(F*%^^)kE&99nVSSz0)bt2bg7Z%yRSHkyo@9BJXty4 zdObB3Ha2;?@Jx#*@Yn5;RF8R81uIyJyTYTeIfAhaJqa6bNeK%c>5--zl~)G=Ld9u0 zGc;o#iJ!B(K+kAX%&rD<^p3P-3Rb`D=#a?izIfKYQPm>$BXXo<86odRzYUOHHAj60h9N3xf8pHB7^=7zqv_Ifm~{Z! zhV9WHHW3GNhSAldpCZqnh(_GRDq!xQ;d>A6pV0`B$d6h8ZZ;;Rph3B05QW6V2ukFm zL{nJbUf75r-VioITVXmPpsPfEm+C?AXj*uFrI|{foFAg*1Yyz3Wjz|D-%xnIfn?rLXt&@3r0}nd+;LQmeQ%jgd@3(NT6tsR#bnWXg-|F_@j564?iLR3Hzjd1A?AY@&bblaD7znS#-jP%@qG!H?V3y1zYgB~{9<(CqiG!xRY5d(0D zIL;E@q!K})9X8y77&Zz?ViEyAzD40jE534TFqr%~1&$x|4~$YPjkE>voVgShpibNj zzoPeBY;PX(nJNUI1kDe&-r3V$?2(6%Q3Ravok1mJTPWjNDAihM6ATlxl?aY}39#fN zq;&`aD#PDSAI}*5I-PWr!$oXm2Wii0Xofz@x3};`o{Ptj(S7^~O%Y*IG$g8vB0Dl5 zP{xJU4MHl;sq7PhLcU};gG5;z6xflK7nOJ;E%3)KjLvQp<(rJ3TUd8}nV9CGQLiaa z&WNty&~^anX&TEagykn0h~eOc8Rk2NZJYRlJq-w-N)x9QWn&^|vz{kq+M{n9BxUi1 zcEU-e(&_C#($}Apxf_P8A;eNkK?WDxAt2Tc2M)e+4o6WY`wO031NfsM(hfWOUIgj$ z^xvFw4@w(}TF=un-@Nd&K9X~r7_kJa zv(6;7&t&4E%yttu5f+8YT++WJR~>0x)col{Y|nhhN|6|-i-S=6m8O={ti_X|@Lg0F z^Mhc+fMAXj>OZd?5U7J=tn-VK0oRxx*=B|}NL?JOo3yBli_%&WCoQ35Di5UCnq%|3 zfHqxn@w_!^&D5XCFpyZ%f3Bj11sYN;{U65eI~uO|{~!F-r!YnDMu|=c(Fr1gNJ2y; zf)ElCC3-KTcSf&KLqr|DchLn2i55nS7NSNsJNbS;yZhVU?*4Y~nKNh3ng8$m-dA}( zK=gD>-4@I^S{P^TgG>8I*K75SlN9_PsY$y$!6P+w-`uGueoW)?I9yyygjWCF3REFZ z-)!9O+D(4z;(hx)f@?`@Rad+%bz zMrKH)W-ys(pgC?(ssFs*g&FVUv!riw`|$3-kqN%X2v1_1@z_{p&yaJ{c;V}FXiRY?kXVLb6dQ5P&Y0V1xW4L>rCoqT>ktM}Q(OjD}Ch7OSQ zXX%Y4pZ%Y@p8DYX{<-!0OP_&ur0jOqkTpD4Zh z4zHw19^-u;S!sTo-okCdbo-0t<)%fTtMz9Gt7ui4UyH0gi}WkkdC_Ip0&pBwz%}hW z+gmS5lQG~GSGx@YMz{UfZcpmnQJvkX{kzM*b}Wnj>!_!Asdq{Cq;paZ(gC(~^$vV_ zT&&WL96z{u>K&PmxgQf-x9eCp);YnyT1PHXkrILDIvD#qNp|lq(5k?m*1H%VyO>G4 zzH)PYQ}1ef?CK!x=Hlk|i~-RfLaWsScXx9SuXm3=c8`#O*aV{sCI!~e#aRij>XqSVopM}N;a+wo^6?y(;?IDu5d-=!mIK39zlJSip!-0$fMc`+ z{WAf^haaVkUM0mKp9%aJ>3 zjbl5#!W^8F|rJajZYF~;|RI(nh#HDN|cNDaZqOp z_Up2k+=ghp`7`B6Ckuzuw2G5t61|{U;@Aa8|9Uj%jwuxKn#q_c&BHap>4~M+U%%Yb zOxxgy0dYB(?(~93udjKS_2fX(0p_Jmffs2evT2#n#)NIU_e65M&K{f|jVVXFDFJ}d;6#?zp421GYkWZY*vtjYaZa4 z%cx-Z{z%U1wCVk2Q;L~0II9l!gc0_6Jr;RhaNJng%~YE}r>JaN?xafJo14reRdM~f zo`k$~gdFcRXQ<=rVsAZISx)MzW7(@`d3-Ys=Mef~P6|wLiM71QI~Hlj*=s`Isu^Bq zY-2Nys%pUB!yi7ct*GN82k5`#-c8S_%l6XFKbI<$=UTpjW$+AtLtD=3(m=z~@-e;g zU>4)TML(}X)myQG`rP>Kod3tH)Xe!c&a~2d7N7RUhP7R8glD9^nrZ$tbJX={;fe@Z z$J~mCD%?@LcpKWpPu;@#!vWl;T(I8(^__(UmKQ8Ib_q3=F%&f~8rBJ&chj79=;ilJ z>(a)hbJE^!+p_;;*HmUGf*QlT{ zqJM9!vQD9QW3DUV*|3mN$dUJ`V*O~w{%8j6rxCTssu^!Ko-4I`XLl(i+-l_*m`fI6 z`FbqZBYvScn)H?PaF8Vv3gkxNccm;RhG^c8U%&W5CqK#YbE5vqSM!8P%Y>1=ju8?1 zGCXI^HyXi-G=(1rb7?+`Uv=Ln-(}_Zo}(dAY`f2#`v;3XU&Pw}ta;Bi@n-HD#bI_n z8`|GTGx$l6Ol*LCr4-5Y}vZZ58;>HXTpMJ--kYO~= zU`!*#z;#($l1tt=-(MHS}{ zFb1t`bFx0GvCXRvK67SmKjM@=#F|X#`@C>yW2{GsQ?f7Sn=Gzj<|k>_t?#WzW~}2I z+qU}jH}<$z?p}>}m~1a&7WMYl%G#!1Ty0kRZsoq;q5Hnmw=|<`)Zd97J2v^gy}P0} zzewV@4$a=JW&gd#zW31QS3=@@2e02mx?p#fd5QN?__4LwtNmrA12Vte<&zebg#!k? zz0X{oB^|&20NW}Ky44+6n#t{0XcQm!(lz$eq@^YKg}=7vTZ%3lnjG+w4k-QW)T4PC z2K^b;q!XdBlWE9BH-4Tfd*OZiPVS4t0|QM!Q})E4=7l2x*1zJn4lHl=jry56 z+!CHUJtTS=n<}CXVO9teTU6n7OyyVTFIuSKg%dEkR7?abp`Pq{0lM*_{~t!@Yk>;& z|A*1Vs1dxm;k0XJUkMmp{{3|EtIz#lNh=)$UKynLAB;}U2XeD`;*(Z5bAeoyWz_qp zmTxh)$?~6a>v#R0b_$J*uViGBt9e?yAW-Mr_jY9}iT6i~$npNGjpK@e4&hpelFboz z>2nl|yf3A!<4{jTEw%5(O`D%V`YkKd34KHHBlJHFhaJnZ>A#jr*dvbu; z$@n-r`%vKEib|njcd^Hd!PrLjczd`kn*Y>sO*mC>gd@Ft>QnZo&B;H+A4eFy-B;^B zM@kwQ75zE*ID7O(|MC*>Ee&y@Fr6msny?Q)G-Mki=cRBcK?Zz1l0 zV7>Jo%3?9NIHs;}c`2g@*SgYrj0wAU-4|DzyAHS%tM zf1X1>haZ*e)MMM<6aAPZBTT0AjAnJ>3cGVelC6P-Q?7y#`Sr&hw+hxDKK?fcsuo%k zCdcN1jp2no-qn)Uob8IdYjaUe46N!b#qrJr9Ri>%{IPS=R9@_ZGaZv}Yv1PY=f2-4 z|09K_%KckT9alO(55Bld&$r4K9cUd%-2q9{f=p`e3S+nWKhQ|OxUF=Wn-b%Dwi&ACs`uJFWI^SpFN^3-WxKIX(NK$ByGoOE zpS#jxjbejquW(iBE_+vu1mDv`Al+~e+9vlDvn?^XJkDA5eznT48Jn_e59ea zn%PajbcDONAuCoxqgN;5tM+S)0iIqnxJ70zkClb?Yr}d9`J&Yr`<@qbIx0f}EB4|f zkF~D*oc6V_id_%1#!0#E23QCpL4U*UAc9OI-8uk(M>$j^NG!}ljS{fx|5pS7NBKJ> zt_ZJTwBE$4%yA=CQ-kFVmE)g?s+0KberMkW%8kD7qn@pQ+jeZcw{R4f(s}qurIU6T zrS!_)n*YVA)fiHmcA0G((JLtbNZ2bA&;5)Y*(1HPC~Orxp2;J!;WhS*+M*+mn{3KT zLC;O+6DtmsJ>BhmC|e$AVJUw`$-jFjqZ2@`pX0Ahqjf)G;zNMV2UQ2O60jI2{FR`Igy{tm2m0l7a+fNrgA^$OP#1yZtQZo)hU9d=mTOgFS?R0mUeCa(*O)HXOD%6f zXT~C2Yd#P#x?8i9f<>;irM6|(FQBtiUGz{#Mxxj6B4_7*)m6q$mc8?fd_GU?*3k35 z)IKuO2*=LQAbG+hpfdeqU8`OQ?@6U;N--PP6=2~F(+^^8BVcq9ZY?V!6&|Bd6LFkB z?MK@RuZ43HYc=B5!?FsWKamR;n{MqF+ZBFzC=P%=?TE17NiCNDNh*|j4RjTzmpg;} z zy8q(0C#@L8oniCu`^k}m{Ojr-BQ_=jiHbKsUaVZ8D*I5VN&2hn&~L+@%MuG0ziDr* zsf`7aJL~PvtVjuYj&r%-2YLD(;QCeZ#mbj4x!|HTMN8(~j9)bc5@loTt!d*QMAwS^ zH8$9MJtvc%xRe-2zvbn4I#N)66!1`l#)JB3vgD;pg~v}p$+e{Kb)v4$4%^hmc-pCt zn}@lgRN9t&keP9M*SzTH?dLSl1qXMkD*ULnOeMT5bEL%LFz>gW^X+F7wQe>ni0s%) zpU>`nscjq`uyfgxPh1y`YTlyS^@wc_J*0OpjZXjLBQzIuNk89C1$!4paq;?VmQd|h z`j{8=(<1awL%NL8h5|ej$Bkd?5iqg$8%o#U*#*CR0Xs+?^8O`R(Kzxh<{)#+drjd_ zc#BGZ|Tfa`z7@TPSAwD_1QA|)AZwC={3^l zx5f45>Cu?KH6=dVHt(8e7huN?L&iHoc+9u_2S*?885imBopz2tMl)hi8*)D&i*OF- zZf@T_1p|d;j(1Ldw|)0-q$sR9JP2UauH4`nm7nJ>cN_D&THyuP%BqNF2X#{%h3Q^u z8fO>U`JFDg75JpuUZ+)EP&;n!^GO>rcKcA(cJ$!;*lvp4*3!d!f6;UDgoh!U(et14 zozfe7aej7F)oW+oi&yrk6&r0CnTNimCuzBG>Tf9rMCtAwsZ)P^xjJ85ZTtCMc9Z)C zrnirt?zmK#5fU8ybPq8vas@0rzezLe>LsS@GVJaJ#J$bjK>_ zZdj0JQP919g83fw8VJ(m4`$5+UW<`L(2>d%1=EBDKVJ_vUJo_|g_yYqnrnoJSrGvD zfHy@ULj55q8Iso+Nj;5F7ei84Q0ILUJ1Y}7EzK8+GkpiMR&^2Xv`xps3Cv;Hh zGk_(ZwudjGL6QF9>HXnZpolz;h{CXl;{FJBf6%Ncd=mlfc`4kV$Jj{V=ckaZG7$w+ z$d9QJB~wD})WQ%_fa!D8NNV_Ke`KyqG)f$3+l3>@0SO%RFb7sD7FwkdSr-<$*bq6c z5z~HxTuY5%42J&FfzOZKVH5wS*K>Rfd!!Q1Rf+kXfPtK1bjC3#@i%=FpZo~mVJeOuXZ+N`mK)fgzAkh<}ND#B= z5`&S5%YTY{a++W$kjSA6UI&?hJE%Iv$lv9_Mo0k3HwiMI5<+#8l){sg8r9bOOL%+3uf-uP)x$5H$uIMiCC!5+2h5T;V9+WCWzU7y1Ax*l zT(#rTrdU$XK3slRv3rahJB2Lipkj}Mw&ySwhNl+~q?dyMG9ZJ~pS1d!(BT+4C-SBq z383%9*fEX#)RMJJ=}cOBky<$b6ij8KCkWFn!;h_MTmwd~KIF{FMCM-ck(= z*UQgn*~s|jkv=JqIrS{FZyJx>n$FrhK~|zD8yhnWoU+4;a-eTjQ^jCPW6>Kp#rwB2 z*vw$H05uy9vIM+WMZ+Yu3~W>9RyH?00e_B986u05Hr!r;~mU#()yUM2NZX}Pdnf#IW#L6s1OdQ zBBos6hU0NmbZ5YfDX1ze0{~#&Gst(la7G?RxAc!*Gavn!i|}GaY~tWx&muN6@ClB} z&Yrvzho{oZSDDIJOp5sE3Hd~c`-m1S3VK`g`b=S5LUD3glhv6q8B&s_Rg!5KeVUe9 zJ@)C%8GLlVh@JCO;u%9n#3uk%l5SW+aFKcibEp&Ge$%CKa-UoT%a;emgG^yT%A_G3 zu+TB2MGlqPA+!w#Wmh3q#E`dQsQSJ^8kI58XJx={X{cHGdU5%02(SbBhtB z<9Aa;uyDD?VgOg-Cyw1{D&IaUKSNX;%pi|ED^4K*Qc{J^S%qn$q)d>J={c4)1AD+s zffGw4fOxFf(iq4mfTdi-tDM;y3)-rL$XDNNF1wurOT{7a%-EI9nui&@zYzE|Hh=K4 z=Kb9u$^j6y{)*xZ7JjD&uJ!?J4=HpMWPG%R)IUe^plc1cOb>91;kyzW2yvOFJAVFk zkF9HMpujU0Y64QHTjQbce8;sU-(9{I$f-M=sRMQ)8Ww8jVw3=;fIW`HNUM$wSr{5u zAJJSNeco{A100WPWJ!d1P9t9wH@=3}mTfgDcEQ5Ez&Hf8qF80-ZFqeHNeEB974YzA z8rgu!@k2JVi#OMLHFG95|Cr9Kb!<+aK&Cn~ex614L8vHa8O@{#Sc*lh zw@NEu+REYIO5m(QBuVkgU|9fr4m{l7@a=#CT_udGUTy4g__i%;jU8w^eFm%)p#B@# z9-~T9of8>B!t^mwi?9ilf~MTdiMR!@R>dpC5&b6$REMAGi+gO0Lq$bV3<(0Vt^@B> zj*ign3LgNPWZ`S3&~G&cxeamtIk1v3WB`_24n?uNTPSA_wh$w+8iW28YiCF1#mmA= z0aD*jj569Ja>LyKu3K5ShfSqNJ*r1*4%yN{WhF-1Iz}a^d;dq`{h4XH$2Ol8FS=C} zdhU4lXi`2LUeO-ox&Pk=pPn~Nwx!#?^z%Cib+~3q*AltMMvsp0=g`I8z^Km-EuT5# zQZ=lh1Bb*1_Yz`^(qi_>YjEUp1UB~q&$!w1V5g=hb`KhcBGte_jXYS6$$}dZl@6V#XZ2m@4-_fNnh+_V%yH`3w@e_GmI>yym_I?NlL{cvI~D>&!QqB$#lV3tV7wUoAsTE zDO?s<*8y`{!wn`FZO)JiC-^2p0OK)CyT-^oQZ@5U9B8HPF0=*-NaDY z{APs76)G7{AP9nw7&&`xQ`F)F`#AZ9X}Dh54=+V(1psb!$?)UO(-0RHvN5O%70YKQ zg+Oj5g1DBaOdhENCud>$+Ek5+OSRgCOO{CA>R#T83W`17Hoi@e-|%ZW@oriUU}Cn20b_kcCDV4^snriV$krD#CPjuem2W zN#io{-ZrC+;ldnt@QiB7b7Y|tAW8QgbX2!=kW$s49^h*}^n(2Kd>Q^yizxur5@TZ{m5G zo>Pp9i!Q|ccWfyz6{Yg^XpWI;RfjR6Yuyyy3FJn0{#w<8jug09o346&S@YRh^MkGX zi>?PgSP!;a4~qhQo<%6wSyA3jXaC#9{01hc(4ezoCMKgnb+QXMI z6Da@HRj0_yDWgCg$|E$Tk}3H#3f_k8iR=)b$28P^+5TxVqc1-gW(t3cO*!d++)@Tr z^b1*F;b}OMFl-BlE>UR*)j*KSuw9WIg0v4q)rBUv0AN4#Kx+t)ECR%`wGFP=EjtGe z(8homv;py+LaVXC13EAW`H508oI#$HgVc|8JjMsW(wAW0F}cp$6wf_n!>)myZrIuV}dDp%qc7veYpU? za$Se4nZj`x@E+sU#-BMNqW@7qQwL5+&WS?tgzM@Ge|339_`bZjyu8F;oZ`<9ug=f^ zCjsq0_89>}J3T!kSZF6F|BnvZ#o^&U2kmg_=;-L+;9#HddvEza4%(k@|Lve%ZEjxu zmxH$VzjV+J{&xrMVs_?yauUB#h@Xu8UpQ!!lamt@6W_jl`}*}Oeti6Nd>lXSJ3c;s zH9B%SHgY~Pa5*q=GBEH@K6?dv<~>pSc2zHDndCVX1kP6sP424l`UQt<{!augi}F7R+Na{ftmu}Kr2jt%+HqVQK|nhX4#r3G{SFREPD+Z8kB^Co z2@4Ag2?+@f4h{$iAn<3tzP?8u9;Z%*hi|Q~EadvF-xByUFE1~GfJVU1{vl}E*YT>t zS2FzD&kVO8KG;ydJFlSR;^IOO(B8d!XJcdYKk;WKCMHHkMuvul{}X?vp`r2r!Jl2{ zT)%!D&(FTfCxAyW?{abd7k>s{VP?hC!>_1ecq#}ULV+hI2x!Cv0nLz??>_>XsHm`z zkf5L-A0OYfYuC8Bxlt$-2L}f`J3AX28!Ia-3kwSq6VrbSXdKkkbaZsIw6xUJ)C2?# z4u`{FFe*w)C=?2TK)_%y2n70n6VP7#1JD2vADx!0e69CdwVPj=-_S}rli4YcRG4;0u-&UGovs%AcJX|uu57m6 zetGcyz54Q>&F%-AKZoiG^VDb(D7$t8)~w^58h;jAjJWxp75BX??Z&Frp;V%Yla$_G zE|w>sJjvNSH`l)w-pWt*^gR0Zz5IPw%!u<}-CA1-PM!}B)qgE?1VT9;C>%ujNiYtZ zp`OVe{2JnuPhnTwcU~VYGl+Hf4tt4=f?wg6^jlg^57xhxti@c&86N+s?;BO(kasz= zT)d^AWNsGi<5bFrLzB{5nLfMNFh~x74yI%Wz805B4x&+=Lixh>>UDV6tXy!Rs1W|8 zFvK-0vtULO_l1a=0uB1$mz}AY5HOwC7k-{!MawY?#g;E!!B0^u7&ZDgD{&gUX*?hY zbk0hGj=H7=F=zmkobGa>nTR@jo7Bo}GlE#*V2Uujl_;ig{WRH$x*eXqb;rt|kV zYwz8u9mtXHe>c{$od$9GDn?%(6K>XBiA8xPy;JK^{ozkLD0#gtHwsc;7jG11x^8ZK z%n1?PEc%fAcJotFVew{hY2Bt^(Thtws3Swv2(?<)z_rl{WnbAWNn~gc3wjr%cO6YK5Tsn;djb#qTxgfb|3#DbufbcDu;Ir!c+mB_Y<@_T=( zXe(LFhL`8;b>zeZH|( z)N3|U65q%1!@8)SM8zuygb&lf@s2s?{TdQuIOgtQ%y=c*^m05?JW@n%wtDp15|nFD zkcOX3a!3Jj@KyV{)WK((W!B^`zvEeH`UT9W;=ezCKEmGzO0z+YlhI=+B~2vD{?1s- z4Fi)m8~0+tq(4h_d1pXsL!vaDcoD=84x*hn94peK;m3}rh^xN^!#YT^2rF{BBB5yP zq}|oPr9&!CDTw*Wv?ziBJ9F1atNN0do~V~tPspiPbjQfFL_jaimPzMG#YD@UQ9at$!|M8)^(E4!2RVX-MdgcQoF$L9c1=xE{~W-x zAH%vZmLEwG7PkCFXzM}8pzHyw(^r+G4>YmD`N~=QM0%% zqV4f#V134jJnFzi@4bB`x!ih2lSc(vC;fu%rBc)AlVi5tR?Bs)8;D)G13 z^4O!loR5{ek*-m%*!DpEhBJ<_0oou=sp`c;*(x0V;o0^Et}(H8yydD^^Mxn*-g<-W2BTK&cc-XTxo zciy}hPh zV|Eey86>(N)zp}g@k%`($Q@K~Wr+v8*B86J%{nVjwF01ZJF{dif1bSDk2C-UrEIcT zsZcn|5vuuA(8d+zDBW>?o(|ST04?0VJTi1ymdUU3>2}Q^q8vt`%yiV{Drai#U+XB_ zvFh;UREB3Z={w2?hYQD;kuW5#V2H^IRgx?t?LjXo-eT2Q6Q9EG04g*(E4;vjJy>$W z6miV>`&uuOlmTa%cwK*7;7tJf&0!#oIhEzoFtc9o$b_=KvLVU*pkd+Xqif1yiJ)F1!)rRh8O z7OsXc#Cw>}%n90-F)JRNeP3r|dGERPkCMV45oFGK`Q@7pv&ah3o;Gl0g}|9^L?BMO zy;i6~KJss_hH^|RNGZXqoA?FR)U|r0XGg0gg5Z~#L$3<{ENTdurcs|LH#w=_qtRYs z6=4*nx*81B9asVd2Ga=LR1UeOun0u*m(2!-aA*yiBj2A036u{+h{(({ygA_{byvTo zpj*J*{H51cp~9b;DEjf?$somXE!~hPI&q-fvH%M+I&FelSAO_Bh~U zp2i$_)@aj+j`j?t2V>(#ZQ>pscGF(Zbckbe{CRVLV2nG8Pca-%(8Zgd`GQM6X3 zXLc}Oo)Du?Gxhl^_PaUuNhF^v%Bp9`$;2dsKbUiEh}FxC-tg$rlE=Q$68bQfW%ael3L zCpAH0-)8U22goHh1eU32H|_9rCg*C5?s4R{=RNf)c21r(txMaKp!27hqC!;$su8{@ z?vychnGbR{GwvK9qK(@6o{@k*F^GNCrQJaLH7jfMs0HcdIt9Y4SuwmhVK%XRd8{`~5=W5I{~ z;`AHy8FgwGEl4~%T>I6HZ)pQT7S~$L#_c8DcAmVyK2hI%dDfQY`O^}FkIGgd{t=q( zQu(eSMhBp>%EA5JrO@07e270g@I7g|;L|zK(wQSh%%Moi zG633&K^F3<`?@(VNF%hRskUDGO1s}hhdv2#L*=Qz)L!Pe&%izc0KLGORqOhG1|Lk7w zNvY8E296ot7k^$U>?QfoGd_xv35Tp9-(w%innrwdM>Hg}H@Tvoq8@^<;dSoT?^AuU zH69AOhTU@aRQp9ug`(o(Gq=(R=RLM#>gPsKP#M@qj)8)BR>CRCBVfNG%fbTtpCZ34 zQ(P)jmGwm+8tiw!a|?Gnj;F?GHBdA4QQy>1pY4w>SPvAfd{L<5yR?pm?nSI4BPqU; zHdhmE6vZ?$-ZbBfv7(K|r9?A1kTkndB;1W%K5?V$3sJlQl;oI`Fhy?_QExX;g9IK> zf@4K1!9tUPr;Jgb9>*x|%fwa3)t^XGn@fB@p`+)HIKcDAo$=evh5_R!M@#odvYL*A z?%|5mFaJ;^WSnp>sftPtMBXGc^NQl-Hynf)qX}HvwVR1PDX;06+-(`TK6UtOH74S2 z2ra)9YOhMxtrBYOO16K-(|JQ!(;(@|n-peU`+l6W>L<*Lr-}S-ym^0BUde`5E%Bn` zQzO#&ysA=TKBWdcN_i}sh7F;n`wsW&aPv8hB<+k{Ta4w{4;e#~1UFj6W2yEK@Ltnk zdH}jj;KcxvAlGDKB#(nfhI$vzgMf_sM$!1wS2UlZg*mN9a|jx4O5dAse-GYrT5y4Y zr6Ypk7C=hi#Ryr2mCCSp_T;_Fl+_zj+?w%=_%zJ20Ft!B27``$8yC?Z@ z^v&BHEQl8k4@4nU2?YXdY)yDd*R!nrYdHw<*ORF5foEA+Z`gBAIjI0KeX(rEWFXic zt_HXgi^FtZA!v5lZWF3qI3gz;5v5KZuV)^AdY)iYp72Z_uV5a}X5J0Ce95LfF~fYB z^n6jze7Tu?r9nX9EMHYFUq$YNNIHc4BZ;En2lbf`0)rnU-;$_US>2Z55;nJ`9yGs; z`e%y;zWQg2^>sifa+Pf>K~9*$w@rmMGlh0%h4#!J9pyec8-8^4{OF$k(X;8J_smD% zvybS(k7!dfFBHh%vnXulW29I?BmPMNmnxaYGVpBB9El^bL_vNllbQ+^S`6m0L-KSs zKRh5HXfq!^7#835EG|0BFK#N9n<-Y;$~4C1V>gRs3`+zA3tk8WnF$CWr9T;vQ&ysL zft=hca8@T%&HyB;;}l7nLwWHzWqTm)T6Yn4y@>0j>2+|a0zGAoeRco}q0*7vCl@hu zw`@f-2a!nqWY-wch=IHpd1O7C`KNPW@DGy`OxerFAXW zG?H7)Uo0akG^3%XvVk)`90Rq9f8O|-r6DoHlcm#nRHr6{rNY^(%vGN2AepjOrs?C8 zrXuSmbaQiY3G!7@Z4#(i`1Hm|7+FI`Gv1@AJ)>!4tC_CS^ZRaHcXL&iJZlaM*IH^z zVPW$qv{eD`(V#qw{B%OO*x%UG93`GW+MG``*K9S<()KvxCSPRLuso6p_sl0J3;VIo zI!@b7vrb6KP;AeUMb05jZlTQl3DmST+`)jBT;D$i2~Q-x-yD6bMUak!R(tW zuP6>-!dc!D$=D?)TMywRsT=#}iCLL;R^Q{29P`y|>{R&PIXKe+8}5dbAYb}K=9y_`2vowWPOFB;m8LUivw1ab&1$q@!^t`YE;MWeni z&%Yd(bgWP!|Axi$X?Hg2B2JXC#CwolQ)F-l6=VLWs2D7X2ceD!VCPu){H`YPIQd2n z9Ir!Ja6pwThUk+_AQ{h%aA1|lEGen2w?R>M;OJEEPvA`_ zh|LOZDkpgMbH?oT9{x1c70J@O9IVowq&JKIwdK=jWNng$s7Lh!V-S8tBtiQ=)0z3F ziYZ@1=}>mq%SK{gGBiX4A`Ac^Dtw5(@ocyvf_nRtrtvtBV?p%x6!SS01 zj*)O9Ngi{N{so}7bx7-WVQqWl7ich{N7RObQIiaoqDbR)25F3oD0;>|caCKf>w*Zy^(`z^72P|7?X{g-vdJ&I0h^SJ z>65aXGb&%DbV!?soTg=MKG)~WK1=soM5 zY9dj46477u4q03b)o7Eo&1NZCe8yU3&6?ueFZ=mbRuLq*CoWv(m+QRbeW+!`gS$~m zLw+XfJ`Zs8{vZ0W%Q-vi@1J!>KIjX5XY3o&JHM($Cu#hNQHb$GGepfEiliWC)cB*yH{i+Uwiw~|-roy08vvfD0#;Sl0Aqo}XCDbs&Tx=2Q) zfDKAwkG;ge-JSV8_J_YW@K*>TpsWCqc>VeTwbzEVUPnmZzJ1c(`OfO?>suEO5VqD- z+oF4a9{iHB{-v-KuY5~Zw0(=EeHRjoL+t(eqPS1Iu$2&)s5dI5|L5pg#gW+P8jQ%1 zc53(j=z$GQpLx5~tA%ZY7aNu@df=T+g;@vdZ3leUWs4P#@9Q0}!8X+W4#h_iQWa_1 z*?)fsv7WSY=Y84;f=h&q?#Z>EgjMWOaki#Q{q~EU-HmD8pXX-qITcSheabPtn)NsO z3j!Z=P|WklM@Qd(U7v!A&w%5)>o1A&9ubG9G!{C!OyNq06Ywxog`T&TO5gY_cUkB%7NxiUI_fc7HLbT{rJ$AX zp=b_wcmA9U>~jh~uN}1wRiT@sr*4>6fFhj_nI>egO+H zZhPUQtFDLKG0Zj)IxA-Xe*)U!P$B8*4CXcw#f4ZaOkfrp(0rvV)`M3v{G)m-7Bm32 zdcp*#v%Ir-*gpO^%36)u}+i2c7Z_`@QtgxZ8CS3BI2?;T=Abyh4p*S`^mXS3n_OR;lt;5CCK=u0;tQ75)8d zaa{Ob+^bADDYbesBl`#>Z)S6N`vIKE>EOPW*FAgazJ1QOM_BsI{$53jk$$LEyb7Ri z@Z$4&u-}yFL{j81CF0wCS-PV>9)ID2Y(4MGq&wth3Up5*n4glT3nd0i83uTt^nui; z%|cmp6=bZ4k!@^C94rc{-6Z5+?noQE{CHJw?6zJ=QvpUg)g2g zmB^2Tw_)CY`c-ba?>c`fE|4X}{b%TQ?c!6)ge3ah`z?bF<_1t)aH>C}|1#+I@c3$u zb`PafoUBQR?CUhk!p7Gb?|Nk|-@E;4w9NJ+m$S+ZUzG7UQW(dPE;a-G!M zCYlJB>%*pkypM158m@;3otaYPgYE=iQ14W@@;3O7lrDNk?QcA~L-RQ-o9{1wWUp-g z>DQtzc!0lxbjK3xjf4urlQCc20CLv8hQ7^2@ff`iFG)S7{1?-7W9r}LW?@oQz(f(T zu{JRrq3-?ckElb*7FEwmO*NF4Vqzj{@-H9X;nqmLAr&8l+I4?AK>Q@fAAYec_%XhJ zMdYh5+=`x7yK(4SPQ0^qrskRg#qbrv>HY^@Rq(@p&1a8-B9Hg-mM&_*CQtBA;%z)n zBuGAK=`-U(zxFdrkZmX#c8wIe0AS7oh&1_YUP@|tfv2p@`H&vUZH{00mG25 zz92C${fz8bWy^uvoLZ5RKOdUI&^+WcaY-q5{o%PSWj5*OB7Mq;4v(*T8GaTj_D}gn zW3?i(e|@mJEYA57RaYaxLUmt(Q|l2fnA1l$Y+YteW?Y;r=hR6J{+QGCvEM?-CkJ*7Nq=0R)jNO0lbxl4lv8>&ft=Cr< zE;Nr1#AR|JLav01LaRPYk1n$=Hr%0FzgR!xgcT*0*QAoz%wK+I7A9>7?7Bc(u|zi2 zd|>aYR}=FO=rKdwL*EwfB_iH*p7!u{tz6%)LZijByk@HGuBVaNyeyPRAUa!YCo{S;h5<8|=w|X~;CcG~+E>6#=RX#0t&x4rM^D7P&N`S6I^A0SKDh3!`<3wgWIHtoYQo$myaPoWfmTSi zQ|}-mFi>aQ3f(-W8}>y^7Wi$-UdGtPbEx7&(b?*Iqsw%2*5mlyn&LMLeE6e>ME7Pg zvReeNPPCMEqoqOJPsj)A zyYKDxi#+MvuvXvH*1xmz%*|EVMZr%1;9LTvZc0I*uw46tKn;MwddOu-(7T)c33oWLdD;e2N$gnUD@2ql=9Ov9MuFOW5 z(G4X^aCO2BK^9QmJ&>vqff)*C(g>Z+RSiJ+o3E2)HlWRmf+ckVjd0{!alw87vA;~9 z-!An{i`&w|VZt;ta?V*vS|P+8w@tp@?vzl4AKu2863KFA1&H<3gIZqD)Ss|~|I@k< zz5mg=0RNXjhyZOELF;-#iUy^Issh0M{!sr0V1NkC$_irVVKK|-e*2Q%3P^e)Szxg8 z`RVU&Uhi<=gp)=h%qXhQn6e(82}XzocuNMDW67+MMCJ%`JEkyA8H$=mfQJ|o|U z^TcRtVjj!3)_}Y=L*<1vOKTL@$)twcy{9QyZ|6 z@AuX&YY}tZPl$S~E&g)2^l_ik^1X&t^^)gn$02;rCEKSxof0fc;udWU(y(Hu!pcQ>x19I4_+AE zbY%t-Faf_T^48{t*Dv}vw86wO!I48ki;|-uk@ve)KA)*5?m0gw^ltrFqio{@9!tA1 zDBcWguQ;Bi^Ij_!dHV&rjqJPx z5MXG3lX2(OL}g{IN4Q?0v4+>v}%&lm(Vm1=Rle(A8G1Jnmkxm|U@3S*an2-3rE2 zUSB~`t=g8+)os6P>f~a#VtMp5dn$x6N@FPsWrU=P@-|owAy|2uwCw(P~j^RY2bYxq%;Cf4i1x`yzX4&lx3CrcA=3n$Ob-+aI zXUL#WKyk?7vjY0dRRAjAtvPo+p_~CqvyMM@WxZyQ7dVbGUD#sWL%|J16xT_pu$C_rhSgOWF`&eNf#E@=HzAE_Rej*C>hM-)JzGF*`I#-=* zT^rBtzIq}al*DK&M%c`ZYdTM{0yO)dDa9IZ{ z96#1p*m|>v6{_OYp2WH2e{)ga(Oa#!;$E=eN}=F_QZYB!I5`=8w)ath@*zkyw!p&N zAMn!m@Gm&Bpm;Mx*qy@fAuZqXMGgCxoZ4yaqJik(t8X`pJ20kwY)FF)g*P}4b||+n zUR^T(CWt98{QC4Wq1Alc(=FVT)i^6Ce)5@PRG>?RhqDeIfpM?2@D_O8V?Rq_&xwS9 zV&4I90lB3UhzFLXB}pc?B%2rFMvUN=m&cj4#mZ_1z-xXuD!4))5(LrW zM8l&4w|=BnMbrKL(Tqhxnm}4x!x=4xog|Bf@oupiTShY=g&8njgj+Sq_j`;7#qfRJSz(q-98N?9 z<6@%GxODd&idPXiwEXj)gn`^R04mml8?C(Fu`GDhsqm#f|3^mRW`qlbX)8vq#lttk zr2sEUqAtO9CRT?wK6Kylx7t^(VwW93!cct)OGFRdy!-cfPx^?jo25(5Kk*Ig0QoI& z&Zl3iTn7hMNg};io-5wGuZbh3! z?9EU+t*HwdrLBJmKQ5xhqFnf2x?`JbyvjcvU%&J^3y(fK0h62UJCJz4PCpDXNrJ$! zC>KOoS{?6R-H>%0l~6LRG}y%$%sS)E5ae)R;)J*d#fR4e`_Z}i?=saNZ@z?LSgztj zX5!ro@x4a+zmV|8-nifEA?OILz9Q!`?fh*~hik z_l+j^l*u5l+J~m)pXC;v+&G!>zqd~jb|$7oWB+7&%5Aiz9*ed@-*6?0WG1MwaC73I z9(X00qa-Wx&&}(6>07sTGOT0ov;h})=D$G^p-4$_yN&e;(-TZ5l}`+j`>M zBbj3o50gf3w0yPc`T48mM{XOgr+y5G7LeG&d#rJ>F(KyU75JRl=@<0@zoV;LFb;s_ z&7BC{oi9Z$e`N?qS^Y1~wI26V&1-A5BG1*=-IPm3v(P#-QheyVqr`zT1}{ zX!)z(DEy0|w?Ua#Aeqb~95+}v-bD~Ect&Nc#g8Q6s<#=6 z`wXjj0{X+cjSb#l*2eC<_{VsN6W( z${WM-6l>htdE*Bm@Kmk{oL`;S;S2I*ie485{an3OdKNZIO+W+1i&)2J2GHiTVNx`_ z?oKd_CYqFm-0}o7#<{sFtWv|gdz&arr7Jf8>GaHVFFN9K zNf-3{b@aD$y4zQVUESjP=t*aQm&W0xMg>|pyw_jXYE{yF(^Xfp>FoWZG3$z|U)*Ru z8t2)Hf(&;^GsU0%#ach=pV?33m7hli0b!1V_u5}#Qf za?U?(Yzd4_bE=vK8ou9A1#!5cg`sqaB|TnckWw^rc$;v3j*8mjr2>rEwH_B9)mR#? zONR?wx=0-FL$M!yot9ZmLqD(jHbMo?wte#_D{)jzmzYol;%k<=0dYOCOzrw z27Uz=FfrX)+D|G)9>a9<5wz`{WYg<*NL5#t z&Wy-BkAE9zT;`#!(&+tNBCf)#>Gw_k)s_yLG2+wV%ic((qy3fd*1yO@! zrTe`p3)Lmw>Uh5Ib1~WrI$?n^>GD5rd(xcOvvnn3millsTWL33?Rc^r26qVlr6(o? z2V~;2$ka_qzbJjf(WdIl@Ktz%JW^>l5^W(#CN5ofCws)fNfPow608;WGxU>ork;{V z`oLh%7nsz8HA5V5ef=~E4e$I_yZqU+B$**70*R71<|caeG@GY+^F0^j;EmVMO$;5` zJNmSK%gKctDgyEC0mWAstA9s+ig!1u&ox1!e|c;#y4Hq(n(vTVc*z%Q>dxs6PxLs$ zdhdq^iY-?l`uaiy-a>SuFB(U$0)fvixJ{D56iYlPJ*|i%0)K4zgJn3AX#iT+jaQx_ z9;Gqa8vW>Hr^tLb5MD9KQK(#b?D0TV-p({y85#{|qXnd6rQqZV`cSqwz9ThQ$2tye zzB`v_X(cI7E`_Ub6r$iwX^VV9qfn>-`oKO9p4Ce()%`F%uu1d&Dn6QJ9t_CsKUZnu zhCe>CPH@-0sJ46Y^MmOmK{{=)zbeza5Ff zEsuT-?{X!1cb)ouUc;P*yR^oWhvIrpcpGM;=YjihS-}0J`^RCtj z?mVZjU&54~cGV6xi*tlq#DDp~yOuehi#S4Imy>w7{2Ox0=x^QRWeCmE2m{-w1)6M$ zfAG2LkGB5e0Dbe#T#sQ3?7+j8DR7fFLPIH|8GNXk9MnV{-UYBjgN>dTX~QMgt7ye! zAq(i+8k`^(0iue&LNNbE%peABNj)cQSxbyPROJc2EE7gEceG6#b1kIA zg`;5hSNNP$`Z1(!D#Vh(s*=OXH6NK5qY`0-UNUyLZe2%Qd#_dT5lxoXYU?QzUp1x` zFw~+k6V3{NaJ1mp`538iuncgeBFQ@c)89APFcTig!A8o46W76w9WFJ9LndOmB<7JXa;F#MC>Xv+4%k#;`khSmPiyNkfKRsqh#;A9c6R&A!E=$CdR)cenuyN;YfsliF{~7H^_t^k<~+&uL2y^1-Cc}+d0fJu9t=azCmila z&jF7YuXCZkN7+P- m2s|xn|fc|?R1=gj2>)YRG8f2{i|J4{3+n4GXU!WipU-8Ny zW7~Kzo~EbYT(X^}ePUAUd!Ow315e-gt`iY|2fo~0o3_Oqu-g)W0cbKP^&x=+*#SBb z^34DW495Jt5iVo{l#ZepEw=2~q?Z^v<|YzEagh4s2XGqIY*S43smc?iH~Rs#5|aAR zW-3_Km??`mP@jYawhi5W*I9lG1K5P)h2@npHB0T40e!Umzx$AKD>i2J^{PsILzo(c z`9`YH4BEu!-=0*^X@ykx_o1DH2g6eccxKw~vAe(f|nH9 zkgyRus9M{koD&jW(aOq_3s>QaEp@LJvq3OuNcWyU14tk>?L~We8Ro_yiDPnKVq^$F zaas29Pk_yXuVnpa3oL0Y-Z~o(UsD1jAQ7~wa9xx#zy!d?q&C4}eFY~3TZ_b70CfdK zz2apaE=iXR1O=P-cltHRLHXem|0s(u zk|xBAG5K>T2kX)hf}N|J-Gmvgvi%4Skm!QRIbzr1M!4uF`4@MXPb(P+Y>{pGZubq` z)2K1TTjcpWCuKXogIO7U)qpE4i7g@(VXbfeY>3q=b&Xx|Z)~)7$fuu7BYx5dlRu~D z0*i>2i?AU$s&*ckC3Rc zT%CIq42t6{QuYV12X|J>_DFdSWJHyq!bI1>^KM5Dc9Pu(TbZKBQP7KJjeb4N*~$xL z8(m@0n~G=>W+ZTy4#a*GxVC-t*bzw&QIkcE-?yC5Wz=J~qf$~8-K>02f&S0C+D8J^ zoM()jS~Yf}s}sb?n054H6?w$pd5-(mdlF829h=pv(oD;mOe^R1Jc~+WGO8Ay5QLeQ z;#r&py<-ejwG5Y|2FEhbF$SqpQ8X7^s-pt2x!^=~l%f=3ca=ZCtgywDQHu|LV<~+h z`!7beZO=iS)G|HMCUC;#!!C=H(z>v!J^e(Tt)}IXlkV&bWc=qRcZuAhpLzzl3_Ov% zW`qdXp2x7Gqun={uk!;0x<@nSkb9!{{;W@VwP!vTNU}CV-g%LD#!Y41+d5W&V-7%9 zYdC#B{K`ekb5AyTLi7SGq2Z)*yyZ@d^m^yulKd@NVd8#rN|>M}SbxGTB3m7aei0iT zVOaCWoJ%?MySmwogm;-rDm`hRT8tzznwQ&`%ekT5IRm*rrgl%f0_OoO(G;`{=`!rxLxuM+mE6BsCaBQwHnK$&}UO^RaYQyV> z3mY~QYzQ7JU4i-Mf4t!Rp`vlvMgOBRG##wJ6HZ>cQ8C?}&zn;2YB}s8*^pd9&sc38 z%V#$GPMPoM7_-k7<<^VGr`%TcDDArnyuRo$U)!SF;7juyW;e{E%*HWSRW$m=VD!Kg z$>2`*D_Qpk!q3G7vCP$G_9HhpI=>FU~%UH9Q>umET+A z`~XrPCm5Tz9@X=UZ(7jx4Phf|USoY}z@~J-pyXDzTM#;$~LcHhH#yN+ADsxrMuPO zeOsALdawQwn%YzL~uy~SsRCMEgGA&>fT-MvHQ(Eqsrpb)ay^` z4D$*PRNFA)iaM~ZY>!3yib#46b@cZhnb_g6pPSa-77bAl$L7_kS~2%Z75G?Fpy!t1 zVUNnMS56al0hX=IF4OTXKgb0SRq74}Z9Y%kOJau5nxgG7fId-H9`!QwM zyixAj@bdeK;FmqoN{g*=MKt*Av*1)!-L8Tsqk2@Xv5jh}XI0Jb5ZB+nnx4<`?0GzY zipm2jGtn;wNB*h{{aVDmU2Q!kgix`~eqcu8Uj0y`^nS(VUGU5O?(;VSidm01Ud;V@Ybb0e z8rzD(%&6|asK;sFZ1IFY^el<^eR|@xgEN9ftzLN3kRGOy`kBGL{{sD(l$DLut|=n& zI)O|#ze#5z)^oz+^P+Hol9>@cv=X6?^bF!{=jDZv^CPr*kv>`UPuNcANZl@{>L`R* z%m!-$Sa%{{t^{ zb@079<{KA%ZEGzdKdMTL_K6xbVm=XkAP6VzXvh1*`WfK8ryAZc=6(l;3;T)Xh=_wR zqCyN46dFk?vaxH9g((-J&$LdF(W23bryZ&9KXf`Kx@)o^~~46=SBBj^?2_Q=Gt|ViaF;Xjge93@c#}z$A|f#zqYbsM&}M zMw|+T2}!fC5vGc1*vGKt_>(T3Fj06hQDFZSi6Qxa+4PG^5s50YBq~1m$Re%6%h9PQ z4d(S~)N4)FwC~ah+fhbps;EqWwSL|w3eea4OWSL0b3XGnX&B5`$Grid9%QDo0rPDp^1dgOs~N z*5h7qml?FIh1yA#t3X#>W|78O@SqgU{T`C3(Gs-TbB~ACbA6j>*l9k{_u^f8F;0 zpIZh7!k?q9ezmJ8nIw3hJG>D!`qRYWt|~tfBhs}drT2~1j1W81=VcM&eeTOXvEm;V zk02hAp)4U-AOHNc(kDgO+D{UIpnJ+xD2?2?B-@Hj&U{jW$i?oxpH*i32f(oi7Nzo2 z8ct3#Lg~yTmNTgoIhP4s*>bO>NtB-6#YmmelXL|~PV=Yw#Uq+W z6=!TJw{;hO8tbLymA;oLTk9*kp+soBz9&qD0Psvc$yDI?SCGn9vOhA{^~9kZyAKBy zP&{wC0}D$Bf+6BXa?zOb5a;T@#iS6yUK!=DSLv!Ud6zkP8U1p3{q;taxUs}MN@&IA z5gR?~2BW`COZ{~vp_zv{N+HIbi6hZu6J#?n3WMOM38(5p4BTc~oU{|drlAz5(3&?_ ziu1i`LMPF+{xPJN0cMHfsBUGmPA5!TJbp)T0g}j3OBsnKEyYA}w}GEC+~~5{z;u2n z{_{{y6f2U#p;VG9_M?cRDS;w-yD6lwDY6+6P+U>poaEPwACiudfvAh?Ru+gb+(waQ zAgey4j139Wm*u?~B?hEl)v86_nxZ!>ID5yXe0qXn0y#(}9^)H$Wsil62BRttb3M9s**O}{gSPhF^7W#@}ulL@^bX1 zwD5-Y!y)IAfcKbI>CJIjVEjYp?Wq-7%1leLqUjS0hWN8v82=?TK4bDcjueZ_sV7AQ zoZ&8LO`LT)tcw^e>EN=5dAm35|MJcART0%s_aNfmM8i_<;{Svn+`Bxn8hNp9a#$c9 z{9SA=i~ylu=pV#2H@ItfsL+=(EHxg6p#u2Lv}B|&jxlF%o^>l|{D*E5?-$33D z|GE4#T;tpO`<@k1#k^wh^#w)bWrEaM?ej+=Vakx8v&L8Z>GzcYxO65;`9A^8xHq#> zg$#of&y~)yQ%j){c^LjD!@dSYryNfylkK3HbI+iLQD*lG49}0Yj^nRr&0LnaNAjR@ zvrSnNmRnrN>O?%OqDy0*EHtiHtD!J|=OVj;VMR8Wwp*uqr|iCxFvkjLa`{bf>-64` zAWKZPK6HRI&b9HB?QrG7`yqutUh;n#7T#b!D-m`@RgtpOo479_@27v!;m?;Z@^#E| z25B?P2a1`=-qwK{`Z57p1zQsRpRhoQ!?|J`BYyWj4!aLM0`CrHp+R0>UJ=_fH}?jt z?id+hr>fk6DxBe`nZ2Qw0e<7ljid=5$b;2Cei{XvfirenXtx(?O>GRX9FD@83)EJA zQ^sB4njdfHfDgl7++hZU1dg06GAe(=y5?eR`?Fa`@mW*bDlSkg49(l8nJb|ev)JyVW=R3&qAWM?1a%0Oh@w4lDlZ3!EB9;j0fa=bo(0I#&vvQ^`4Y7liZ`CQH3p(m4v$n+=GS<5yS zeHceL=%XcAV)wk!oqT-hy<+R>>6pxG^3LkA>yzgKAiwzxMd?o*XUN&|<&P) zpKgsTFX_E?eLbJ6&Uvo;!th|4a%f&BJ68TmKl-&%?elIEP3Os#3R#aq%H=G)!s%p`u08}?u4%Cr}$jQ zM&sPiZ=qnP>y21M7i2%0RF1b0)1~4u;IYJJ?FI|7iYJ7>Xf!49T;GoRkVmoACCMWe z6V@Ci*ssz>M32A4It!P0hsyGKgFz$~W9l5fD#y{=56^v-ON%f$O@DBPigb6y|Kh1;loGNjF@HYbr6@O(Rijs3u_-gNAa+Y|m2H>K4ga;qwO2fEk+N()0xqR> zKs!|T8aLe_MZAucW|MnW>9a5?681F%Oy)rGj60f}`X}!77F0xjUc+%!BLxS%XRx)H zVay#1iW1hPy*}4$O*#$CHYWJ(OP(0HA5)6iN>CsN05~O>R-Al>ZLv}uK%$uAXf+tV zj+R6r43czoX1+&AfKlEYEG}l>l+BlQGJTewdVzH}$#FnSO$SAKA1%}fjAnDuBTy!Z zF%fr=0vW9;?Q6yvj&}yKxHI5P&&&i4LebGE%H3!T$K!Frk>nPCY-2DkQ{{;XW~#L7 zR{-Gxh~*5enA+f3ualRi?iZ~}#%RxQKXLTY63_n~)iCC28(2!<3Cvh4aI?nhgp*>I z`c?YwSTp3Wb6XBUuFJ*6*|IYk5d^l|`mrBgdRU*;KQSgG`GnF)UspnSBh+`JEAgV{ zRocgBXAr|ar0+t0)f^Zq@%6K%_^;-59rW?_KtJZf<{QZf$=GT4$<1nA{o2Aijh(Yr za6-JlGRbrQ^jh%yP@`|iF>xPSl)HeA4TlOvp|}Z#2wL~GF8gx+(HnC@^yNKb*$cUu zyhm>swtoq=aw(6Bd&g%IE)!!#oFt#DozI)EgM!v1+(*5McqK7)M=WFB`oW;1l9P1N z?guA3JPjsraN!gQ6WS}h(X9ch-8VoNop#Y?6if@!s$GakE&x>wy`b+>wC=~RZj9>INoziO?voh zjL3+?cI$DIzs?ATl{#Wi_xiP+Itqx%YXjm$ zYGkSv9GJR-WmC)Ty{;0Jh$VaaC0jsN3yeaV@``{o-xp&9g73c7TQU9s3fVO9M~grC zQo9;6$kt8ZDV4CEeS@5AF)^A?r$1rxXkRZL%OgpOuZzNo@vq3KCy*@eadKb&kgqjs zqK8BOmW*Aic;l0ODD!R` zESVa6cW&@+KI2Jg1%e1A{L{Giw@*q~uY_RF2s`9)dY4K$q10bv+7<`z0tiScG&cHN z%^)_lc$uX2@2r59r+1XRG7N$LVE*Jw4yhFnPiyO2ukxHB^<5n>D|+~}V!3GdnoYbm zai#U)d9^8IgH-g=OTjy_WoCN-DHT>{S#{oo-OcsD1l@exW)A9mU-l~?QV##yNZ`Ql zPrukJ*4RG}gPt-K6}!HdT_nx$8@>BDB_TT@e;1Y1saMXee(yEjH*_4Id-#EPPMs+26N8cYi8d|B233!WMcW&gzv~b-8V9!m&eO<~Defp2I(4o>zZ~^&&EU zhtG}$MUL|;k`ETJ5}fy7Zcm;?-u}i4Xs=$;ep7<|^8#)&bgDswN56^Ac8My0e-lEt z96SG*GcT4iaM-pD*$@$eEBdx_2LaUzMtqKU?Z zNl!>&=f`*H!UVa;u!VWh%KU}O5kaLlAxLnbDU*chM2fJUZ_t+Y2+n@oMtYt}D&hl^ z1Hs?IF^l>+h)le-Ok%REw{`P}^e1HIS(2hr3^TL1+*w!DyW}DwFo|~3*ADazN|X6; zN&*AQk8SW5^KqYrse-(yEPUuV*(oqx+g~{JS=~>l2ZXUVJ_yj&6#du_Pl&SClQyoM z(yNu04u@n-m83|7X_DiP&T@Og0un{w`Xc_e zL+bQka8Xt&Usk#fR;E){Rzud;D3Tcjn*jEu@{Z2<4Pyta4Go5pvz%ukG&?wSMGUbvz^+OB-fXx zsDr2Ml&4aZ_k}NSeFtyzDQ~+dU!EwuxROOnSrJg?oAl*>-NFC%lz%}~V8vHp!;qIo z`QH1idry4@C&wULwqzJ|67$a!F1HRL&?4f^78|agFo6+_tAmY5jBU4;{#uE&3t+oX z&S4?Sa@!$lkS!`8CU%)6B(WqU(<$b5DyAuVkH%o(Lx!M1jzGF{x+w3@krPBs7Jb}2 z{ZQuTOjgpDBbY&vT^QL+=#mssVz_d_%b!?aLe%ie3tZR4u@GKu{(+w9mQmgkg@U;E$ozea4ZueOk{~q*MSCtj6BsB z@c!h`z7}~)`+N7Hm^|(>mp9g58fEmZ#CP(!pOSICNkNk&4C_IWURSd01CZZFUn0cb zw~5JNa&Ga&k(l2)GQ`jCvrs~|{UF^+q?Xf^D#EJD&8kuli;Zu{A7fU6N|w3K9KMAsq&W=ts4)C>5uT^(M1M(%Z!wg_V~4 z^$qNFd8%|jiDR~MF)sn+F^Y&+olgB&J4;7hw_T6a;Cp$lzKp~@SO6Pb!T>|6p>|9Z zJx0=jg0a{d{xMc9@;^b%tj{gT?R6M=P|;tCv8p^WKJ+p;(bGN$!%7hZFgWPs40oK& zXkg9|Ba|mcvp}BC%Diez6OA^(JvV7zF@J7g%9LxWHgEb9`$mEK-u64oS_*S2^Hw8s znOv)nE9MkqG~|`gDKyPg)Vujzxy}F^+#MrMJJS#<%N!*l)Skglp`C_p!iSlL7IEgc z;yRPd>U2A}cTvQPsy2TmEN;750Tbh=RA!C11V4oY4M9-4K#QF7N45cS&s?F=nyc_J z{5w$iX}5{kg_Bf1tE{8}O#sojV7`s3=~6!#HFk8Iw`FC#z2H%Yo2H8s^^P#iyCWrf6blm(Ua}8Cl92g$?O2@ZN>=HJr){YpL`@3?DaHP@~Nbmnk2^f5tJZE z&q~6CREkUh#){fz`hafoG}A>X$1FbR>%3+c}HeYS?Vns>8RBfVb51QS~+np(YH4muBtG+)*9X$x2| zwYM!0aJWQjw-F2j$OcaL8$H#QQKDq;pjScW18ZRt=aFFPm<$i}QWcto62SCScwTLh zbODg*mqeVs(HWl6JksIH#xV<~Pi=Faek{P$m?~n)u-JT{7U69W9A>cU{YLz|L$};p z8nkV%r%W%uyqV;7ftObSz!y&!Xcl%-p!ewNjoFoz?qysKt*_%cqBxkMTPbQB9i^&| z8+nx+RuFl+l=ekBc<3sHJt*n5UFx|o5wb8A%o?if-CD<*{Cka9({!)HEJcX+Rc2v& z!CLw>PR7u2eB~}tsS@fiV@;nGX4IQ$dX?#@WB0unIj$lMJ@>uM zaJd0R4|(TAUe3#hyjKb_QVYptGUwN!gLb1V^}uNYe@9L;^Amz!VzzoUsZMl)%+YjR z)K3ac&&?Dy%nYoGFr^6k{N2K+Uhh9W>RxoS!tj`9MFr18WNJ5b8!K*3(M10ONjv|B z-YC=WgrpJl<=^)&O6pAs_*>eZmrJlyfIm+#tdutjr0s2F92CHYiqdlObIATvzn;CN ztEiMooD42w5idO7P5l&9{)aT*(LCo>Q4qUqQC?qU37wKis10r?0vd{G2$}4vNd8M| znPyI!RrJjCacPRQXO2&njjX)=V}uhure>tJxu;<={1GyK zSq=3JC6zKg+UyKf0v~JJ>D&Ikjid_c%v*1>r)iH7Zi;zSsRw^p*1Ab=%Wj#=3i-?7O`Zx4Mg7ww479HjT<`{+%D~6WskG-RG zecu_N9$`^lWZFU3)Jp?H8w1bU2W+|-Lf-d`6c`N0dG}$?$4N@%DAZ(w7Cye>3s=`; zoV1Y5l?Ydo`3IR~s1*@WyL6?mR+3~d9lP!CZ)WH$>zhpL?;N!=J+$a@6jR$}%kkNq z2xII8hclXnw?&mo+mr${;Z4NB<*gMOC1TU2fn%>2=Sb~LGJkGN(-emQoiku z|6;z=X-IWC^=qrT|m7s#NdB^=r&p;K(C3G+rHA7`t(#6jc!$#i&8P z$%+H9qvRq39JCPp8Vf#UvvKl#c7JAlmd5*lWiI&{#4hR7uuxQfGf00e2NByWGZC_y7bb16db{|k>|NC54vjI- zYF*k96R?#ip*)oSi#sEtvIamy?`)w!MFGx}OhPvDf#?CMi0x@6K0%Qww?awwbL7VT z-EFIPF%hPM;V6C0yrZWLmYN8ZX1>eod|>Mb7oQuTl&j ze#sawsYq44-kiSkWq(Icd2#e~;5FD{H{tViQuK3q!fIr4wT>1-U+ab0j~|~ZxsbLW z2bcgC!c77jd`@M?qitG_Mv08Diu%@?*1mWedW>NlW%$|mGM-6X%TodQPF{tNECuU&Gk`sV{VAp{e7NyZJy5y^SRh1J- zlvn{RQRMkl8l&9*6VQs~lSKDs>|3GK(o&f_|Jw_#IQacnVack_mfLeSmy4-X9~72bwXe=9baGP@>vYS`cf-IGuw3z*Jc{_tIfI} z^Shg|{aD5|?d00O4scI#vw0KeCfD=p(_q-mot6I7D+ye4CO2v2*i%-FdvM`yRMgqQ za-+qo^!s5K#HcI8A-=-k)yda4C5jmeL%~j1@i3B9arocgUvE*{6=kD;_W$18U@|^M z0NC_)AP$B)5fy!{T#JeUGiy{3i-QWtJ^z0Jt*+90g3Q5EwdkKJTT;qglwC4!%Zy!$ z;4sua8THj5IaKm!rlJ}XqpaL>dZ+F*;;~qU)d;pX|v<>A8I=0nOO4} z+C-93()!LOjgAP-d7#^L~_jqPlebC(hYu2rmhs=(YO?6_21XjJu!ROWWxx2~g?dtiF1o6&E) zUfl(1uMai7WuP9lrYofw8v)COH}%}yY5Po4o6>okuDTAMG{9?T+dW~=#ZOIH z^m4sgDQxC^-v}P&pETV&eAHnkHcj6#By)Il^6pBZ{^zU^sjmNm=j5ivTgOkS1&bUq z0_4jEVsH6ZATQ<`=heO52CN}iKef*(ym6A~ax{{=7=KcG!M{4-`ZHkD_q`Q-eL$0m z{4?UGyW_3ZaX+rVm3O#C>ta(X|;S2|Ma||1j+5%P;9+zxsc_3;R8cAqhVoBh?E(nPPc% zV_o?XPx`@Iud_k*1$*)P=e0DJ7eAi8Gq$_@97!5+wUeP2f$arnU+qi;4S<+1=rph=A79Hmn5?t{_o?Y9 zkt;liZnFaa$=c}G1IG{tRn!txLzJ?3F7};ajgOv@q!E0Z_&}$M=9LB#)9sR; zL|thYKbOcVZm5yw*0mGY7A(UNf8zNVsm=6rW^(#IY{ro3gXc~ z;)q20R@*bPU(UQ%BM(S(-(;R%pVo2p%?YU=Ra`{HsI8;$s`+2==q1e>H~8i?@jG%q z*qAk&_04Yx=M?ZtdSmiIv|#XP4;Fav1~rR~74m=MO?ootP)uIbsWYzVI`Y~@%dgnM zr{=aL>8-n~U&-cCjnpfGcizc4$R`ywGVhZfW^f~jB~b6+xdiVG`^C!7O7Gp@e)2wy zOYGS-C70q2-CQJ2R{>6*Bk^Jd+Mn0I64qVG5HPOZffVPbIM-5pd4tpC8n$S}8hnS;;qK+|T)u!<9)+^)ly78U`bN6^&YD-whv^fS%S&zXPCL2XOrcj9%b0zV9hvJ*Yl?U~xRXUG$6Gkhl? zLdM-Z4+Cb6p5f#nR5%;3KM;=^9A|n(8)LrEuv)*k+-&-`!ID7~ZT-()8>j;b?YEPd zaO5H$#x)q9FPb!tJ!_JRx*Vhk}JS%xNn0;Xuy>9Go#PdFNpii#nAH$vpgfo8=F=<^$a+G0Yw?4UXG z_>5;`7GH2odnY6Wee>Q}epfN=hg43;z!qXSXQB{nSdT7Q9~vsmCbWI);hkWyxyu#Q z2e|z5doK5hw9B4anOjA0J}T$>v(&4bJuk0Y?a#oof{~w(j`GPzh*7DmBu8*u<&J?* zzarMgc5b~wa8o}=>yM2?3}X2{jKrwUtM;z12nL;x(yLym�O>WD$foe1R89X@Azu zdHb5koDxa%5<4ruGk_E{Js*Rak12-g!!@D1#M-!IQiRb&Hv62jMlGj#oiH?xyE&UR zo*&Wv30{)M7!w&{hI=rJMv@|S)?}(9zt4SD2n-PG$zsM7!vXaDOFAIZx-%F5r<3Y* z$h%632QVcfwDi%qSyudmXXZXm(bXG^9)jYfdvkjt!Su_-QEI|-soyexgsu(dzu}w! zL4Z_Nrg#ATd{igXcfN|1#YIh;OE=bUd4$*zZ$#MA0IoIy9vq>TY)@<6cMvLJeH$SO zpyQxk*k$;FjyM!l#1NGfkY+FyOR{*H@hsKl`bHdmp)KH|EB-TjEwTmaR$-XxNnlveb~{w zUj}Y$In`1n2 z5GoK$r2UWxx>?z42>>Q`7Ax{`Ke66r#EB0f^b2G^5_tsxBTR>WwS2pD7MT)X?I&|0 z`{(pBu9vl|;d|T@WF!kDNcdOShpPmI@P!m>$_a=f3M|xN3j(@uXmXna4^)}X2ircM zw-ww6T)e_I56cmQm-mlB-bs;7SGYGRL@eS1AZaxAVOo8Jq);DD zP#4ND6D4FylC2Lf1Y8C#aR6_a;|iQim~^s+_@;vNx{dT@EdgVJ2TKAC3vD#J##7GV zX!6SF$r`9q4#|z9_wfbkX&{ZX2ApjM&NULlJp)&S0@#Wft`eNr4Er011<>A7&}i+t z7+@=w%gm%@gjA@G6w^jJ1_0CvKJ*V_m}_aYpn#4>v;!1yN{n}%iQg(9;WB{>nA$UG zB*v}l|2&QZPy}BPWQy}o$wfeCh)4HPkUZL0H~r{36Ku!KDI_Wpw>>fKDshH2DK6g` zn8(TJ#W-8B655*4Jkx+zuEW!N?Or zSEM;@;L4YzoMxzFxJI!Cyp%gNi8}?RoC2UzU-zcIg#v1sBu(@1Whl^tVvs}-J$gZq zGew_`Ai2;N9Iz$8*7~qHGv#9j#WkP)|62oWV<w1;VHb*Im=k)Wl#aKJCohb@Q$Yk71?PL?Nwi@XI!Wf&jaTxm{>!UvS%r>f zF%x7%M4;^E+4l$lp1y2>zuAy>qRlou^%0^^XbLWrjhYhl585Rl3zH*xoW;74!|^1W zyFQ!$Ae)o>|Ha$r4{|T5@{Ba|n4aXx@nkTM)1;ou~Kw6G^RFUjyb0epD`{_YihtT$=05~O2`MEEcLa3)ku7;g}6Kkz>d z!dn*x0R%~B1)dy$PwdQaD`DMAhF^(*c9{_T7RJ|ZBie?ChZ=EEW!N^@eSr z9wN2~cTq-_!cTJaNv?!RDukbi&J!J=N%y>ouGit(YsMc?=3%3y?+8fdHQ|ezWviO- z_4=~SgR+lRML#QuwEaykgn2^@%HPwKEtzA=){4qLZj|AI@F&_#M^St1=o3!0md^4q@hUo-FuNw!byB-=9Og9ZfK$Mlut&cfRa zLdT@;BMdCZ#9jzk-Cz3WO0W@D7eL9S59A8=CaL9&zsQWMkMa#Z*NNY+*1Hy{tSGIo zlWRlz zc@zLr=TI7EL&oV*2HX*%`~3{qwBaazO}{NEw&3VI0zKaf?^_5gny!JgV;8-%8q~wJ zw4wkMXak)ds@3q~1H*GTM!^Ob5CupI^6AlpY|;G;?FbTW2L`cB5^W`TN-@KgJ`5LI zP4uq2Sqtw6xfb=;18AZ$S6b~^;8jp<4R7;OGK~-dvXw0G&=bVL1&y|fP_Pddi#`v`u`u2A`LzhJM^cb5Kt zV}}v0w9LunP0AjhI^AJOBo_c|^d(K01zQ(__46*CLt}5so8Gj;-VCC?EWW-R?Y=y> zzJip#qQ<_GH+^M?eb0#cEBX4LYxlo!>#t4euW#&ceAAB=&{~NG+W7`LZ)E(n26|Ek z`aTL2dHdj!fi-FdM)?NEQ+Nio2d7g8U-SKcjNNxo6XE|a`Xvb=Kmwr(h!A@3h=7#P z5m5n=-jUvsCZL2CLJz%3M~ZX=sUjsHND&1Q5fo60fb_1CoA3GEd+s^6oO@?>_V0aW zc4qha%=>x2u8`YNUT;H08z9MCY5Os-PyGL(iB{|?;P$WhxF3}8amAqF$G&hh{y#L) zYak3k5FS z4)B$P4C4{~O;8tr#)SgF`qD%-fup7{2V4D|?A;8Kw45NI1(Q;acL$JEPC?YEZ>bhh zbi2qXF?WJyLXHB|=Ak#s?VT2hzR9_@i0;Q&MXwwd}R^0iYoBF_N%2ty0I zjg;0$!maLFozYHJ!*&3GbC34OmvDloQTH5nVefL^qxD(>du@X~n+bQujY%V_`=Z>h z!-gWbxO}OKNao@$<^j`@*ff zBJ`2#n8m7Tip(4x3buY` zWp@(_(J6s_6?r%0IWBS&$Xr64HPQ5<%jsY=(;_6Qui*3TLV^{N0skMQ=zHy3pLb)B z<*_TGMLUx4DBtm4b(4uESEJ5#A>R`N(eER?mtjb0dSC$HC7SPL}H2>8=D*I8yXs3 zym(PnRrUP&^RlwCl9H0*;^LyBqG!*Z<>%*TXJ?aSqSVyX%jD$!lvEO0w4ac;mzZ=K z6MGS5ei9UP?sNCd$%$w!m71I!A0JQBi?(fTQ%QW${{a}0#3B+`6ciK`5D@TRERmO& z*MG4@PEJnt_V%{6w$|3xmX?-gW@bl5_s{Q19O&Nqt0l6lqI#jkadcghD8@k)K&^|4 zlI)?MLc)Kz*#8H62uUQ_LvR=o2DLCWG%_+WG&H<-@1DNC{;gZLNTiXLmX?Nw1{#f4 zRaI3|Qc_S*kdu>>m6iQJaUxOC|Be&!^73+XbEE!epNNf(?Z0p$l1#+F!0=x(5fX{~ zFPsSeKjTD1axe)$A_Bky2=xC56#@Uhi6YA$mS1a}|5u_&rZP%K#^L{yC}MSClr=u~ z`X7lRSD~WwxBp9`Xn8R5E5-~?RvH~p{88_JCyHdspY89$leJ~*jQ+7(92tMCycc~} zjOqGTRfFx#WU&IF-{l^QDeA5`PWZ%sBZ_)D{F0?EhwLQdA|I|z7T+i)>4!(HpPuWy zeX8tmfJ#)8C8}&BecAsHQDpo6sq?|=;(O=y-fO?Z|LjkE%PF>vAYymLNTJe4tu9NE zF#hV2$lc$j+0nF@I?OQ)dV1J0pThGvXy61E2(Ix5Q$c;>98hs%-8%(*O&W6B8t?1sj+itx~*oJiRS_8 z5>G!l-Laiytjv`PHLq0T;655wRYCq*EASoeEJ_35fCe&Tt!BL_{69nyhRPm`#4x*W zl!gtEup-BIGp_ony^J*#E*}})@~N1S8X^BLMA2q#(=btZtFCpH%>zyzuC-n$>WN=% z>{A(4qh^PAcxGR1LK1wEO!W9unAE#VTc^Lt(^XRP$IZQ32-^DHzJwLo>G+vF<^}H( zrmzO7HTjy5@%|LfZn317t+{>rDsxxw&%st*Igu(xED9y)vh_j`A_HfkxUs!Ah}03? zCor0NHdl>C;>E+^nn(h4clhQkR84bAv`riezyC(4d7z%xvI?x4|kd^?{-HtE#;p-MS*yVrEbK zQ(Dg@I`fr|$4i7vukf^|-Dg{_sWC|h&-&AE{U3;88EH<_gke=)N%=JXk_hcxsuIPaFx0 zZLFk_N|`aZ;e5)XDi9!vMH%yP$o`?%-1;=D(ASlJCU z<>#6cLe&7KRh-WCyZ-ol&wgBMl#g8@VaFP-jvSj9Z3^vWW-1!Z@O2Gas^V4Izja7E z2}ZL6`U=%Nz=5T;ub3wIERC%tCIW!WB0(&38(JUa&L0D`7bKZ;k3%9Hi$y`$@)FrVPLve1QeB z9xJ+38W@4K9_WLI%OG8I2T(J1L+BSDhKIA3Ib{T4XYhfy%m)HksVzqoA9wqS5{&YSg)#z) zAFxpnoVtFQ_Kg>sce^Gt3_W#j+(IWH{G0sZmfq5a^civV0Dzbm8Sstu{o`37M8ybH z(cjnT+xfI7pk-Gs3p=A;F8oh~W{Q?qEOs34`F7FA=*&V5u1pu^>l!QLbEqvCQYc*4mT`z%R2LDzS=rC`|XAFm<$mNd=X`BK|qc%b)L}kyupya{V&NiUDkdIL=J%hYq zf8A^lA_|vAlW%fm8nk!pQXRufItIdZjX!HFX38#I8QhBs5DBLG=YC^9wLI#& zW}Yb_?bKwPN8~qM+fOM!W&*(mIr5k2)1qB|N)cm;G-^Q_nXi!#b1)nyCF<(Ai`yy;(qcDS zV;kFlyEOW3`w>(u;!e>s$A@N<$ zS64s3+4Y9J!mz5Xe}8OssYCi8;!TmD$950_SLA);Xw(;FvO1$gW*$G^T}=a7v}?|17bMH1wbgg(SyJBTMWL(LCag9zqNT@xPj+5B{}p-=;z z89dz=NVEwFYU`laEQ#>A5&u#b3E((}ade}t`h<=Y4!@LafjFBhzAISAd7S@3wWCBD zrCuP|MLq>=n6kc{!t6&eSmL!Ef@kBxyGA8l<@Y`6h)Sd}5lRgP1p~22YH70!iBXqKU7u`M=Ie3PhZ`9t@ksP}s=83Brg`cj40|?0 ze|-vLijTYDmU@jcID?DqK^3{_dA2?;MzuA|dkt^0mSumQRkKEaAqdCMrHXap<*UOD z-I)C;a&Whh=0Y0&FlmSTS+Z)<$S;{|&Kbj1IUM!?0h87V%XK}E73T6#FT228r?Zf&KzG|Dug^fhcvs zUtfyWYXm>U=h=?93LApavlK%)g{`ca(L(vLZp;&hO3UZjh!fbCJ(^uKqKzD&>!aEP zXh)Yoe)62UAD=PL^WHb&yW(DYOkX?`@5FgQx6KbXX!6Zu^?7X;pVy29hh`!8DSW5E zDt1&CCQvCexxOiLE9(zb5~p zI=8E)=%NNbRa2t)B2)N9#b&i$4z>JJO=akdh8NZK7B#ZSe5336E@>(Lis{U=Rz zzYQ#Lcv^@(Ld5~e`;$3YlHy%g-S~XnSTm47H`WcJ*+0gpA{QCK>`i1%WZx{7T zYz>Q{F!TvU460!xzv0_FtaaXx_?VeCmbz0oop}vVvV&G)Xw;E)gBEq<%T7qEh+imoO&^$QZSQoz>SpjdW)uZB^iIWNCCQL*-)dF`${GfDw2C)r5q z_MKXydQ1g`Z9cy~XRH&Sd2k+rQUiL3fZtqA#r&6scIR4`NWT=PmMt^a4*<1k{&Qdt zY_-{<^1D?6fWV_Sx#nPgM8SMtwSzNTcKIJQ#1orG|va!2V@F46k0RwWucb!UC zFEDzA1{hgqeIq;b*#Hwvi#j#PveWaJwHhmV{){zO;&X+bmf z41DdD{?mH3-~XtDf-SGTsk>d7c(XeqJN|tb=EK+4W`&oswY@LT>7;V0LlS$w*Y@O- zB^8At>8x?xpn3wq{sjTC-z$4Q`1)(-(0=C?sjM5O1omJ;re)_G zb+)x9odd4(R%pK%JE2c4aBwNxEGf|9?@(C$;AV8McaK6S3eKiY!4r@wiSue zeV-fD*BM58B1MoijTorH9<)7*yS1X~S5{ivp==tyJGFH4FV zc({KP*n0{wib7s1p=sO$tK;EoOY9`)ys`=GghG5qAr+9cHAo1)j~17hm6gN{5u7M^ zHucGA!m@7S>-HPEe@JGb;a-8akHUlhbs}o;@C{!?3Wo056v7(_0!vw1*h3Ac$%!Rl z*e2QoZi-9d5_?rsBuRpwEJ3~xr_<_-hS&Q%gTG@?E@bkWVW!I%wtL$H>t5<-A&;cJ zu!5#Y((XN^YsOOnn2(@k*aiy8fu|{709z|$t<0Tdqo9)+CVGX(lzJAKnM zUd*CwGhgLqe8NYt+n;M+(dpH^@NR$EWr)1!dj&L6B`DLyl_2;BKZ&Af8hMc#dx(Ei zv)7SIK9|52Y5EIC2R}B!&zED>@{3{?WF@>l$fVvY= zh^Zx}3T0$f;XKH%&P#0~ovdmA_O*EUbMeCGHtT`j*T_ZoM@v@7my(m9G^*rlbkTdX ze}Vw3jwZ1T*faQ1 z;~N4Z0~7I3z?W)X5~=9*c~gvaKXizb!*Oq7sBmFb^WQ4HeZlQTcSHSJ{}RMmAA+Zz zZvJrLOB0x9A7lxFob^$up&-puG;fxnmn3@206K}JK`~5K1CUg^DPv*^2T#}o^CD+U z@eelQ-vv`980-s0lD>;g($CAt`}mCmd(i1Ank@ifEsTuwMeJc{#sJ7j-T3(SIF~nb z5>spP<-^o(A??@ZI`6JA*%z~XdCi*qwof3m*(0UdhS{3hx^3rS``r&2cYoP&e5aKv z+aFtT>g^x4Sxx@{1RsWvHLSk%cIDyt^>K3bgZB=teFfw%-N&1+L-lhv(`3lceoM}7 z>)zSfu-WObp>uKX?@{?>q|dHgPp8}T@Q(H_gYz!m-4%h$?IUHnninIvPk$eIusf}h z8Yiu(zVE>!y1G^N8SFt**y66c`{GvYxv(NuTJx*B`xxtk!@@xZVt>~snghUgn~Zg* zU`^@w>jSe-2QhySwi`a|T)x?yq$KzJos@LAP;=;1>an?TsJeU9uYE)=u#ILrl>WXC zR%<(2+SN!szWXPDDS{p1hBvxrh^GCWK6&g}yi1+-LgCM@73ZEs)$dHH7QTWLCavQe zb33M-{eGe+zqU@?;?h8SpKquBR!BX~Bx?=-ewre&()xRkcK77flZm=NIg$~FN#Bn$ zBv`Gf^U@kMJc`dPRL`PPztXGqAWwl8#lOPpI6TkWpMTe_ia0-``L#azhq{y$eLX9( zJz4+ow*8GpXT$)f&tY!kU%Ipxj^h{nKEoS^-MzluZ{KT-zB!&C?*6Tj_(#jt$MWmn zV8p@O{vPM-fAhPi?1(cA=h;}}(Y5zo^t6|&_x^2=xe7O4p1%CoEOGSTi6X`kI~s5d z;+jg#oB`J$j!DeoS%~2h>D(R66_V#`uba**6P2_tp?xb`%rfeXVqjH2ALaq4HYr=X zTcrHt62fM@VNiC({+(!oq*GGHt?P1up>*yu3HNK%TSFhLj3nx9f66eDtu={p^s7j=bY4Zh<=#KMXO+kyspg`=_DZjEf1TpiYD zWhj}mQQ^YfEg{wG^RU^dU!^v*j8y$qQxv`!F>`t+CC&(39a&9jB*{ z6+fJ7Y*D|aWxTF)x4pagaz`|4K6*nL^os?WLk4@;q(<>WTC(O$aO~b2VEx5j6+A2< z3D-EVmn!plAk4P}_NAaN$G%mtS?h}J!Y|D-{(zlY-r^ znLPwOd@Rk%&%j$8Bdr&c$(W$M>s#lcL6fMTJT@Di*~bzl8LxM{NLz_sTX^iyA=j1- zFMU_R)`~$;gp80bE)zWevQouG5uUouay4CDf=JHYJfxVWQIca%$dxg=_0@8w>gJZ_;@@Pa%Ch^#(Y?@{z~0 z*0j>c{bq?T$*PbxPOrXd}Sf$+mJwEJ&xiNm#k&+X%`_BZTf3x((SLT-I}U>1*9 zWXjlP-V1g}hI%(GPwBI0cf{)OcM7asL4T0!2fB=ECsoN~|?m#Wu6pC7m^ z1}z4!KM7h0qfiO?8gZpJT%?+=i{gyaZs_Mn z%hdH(G+4z`vDcNpA^ZfD*q)+U9OvzK16VYd5QaftMN0FfH_Eh?sbcQwoAsNirLdza zz@+9#jlXgdrOC;DN**w#Z8h4$nK9=Z45sv>ZP$5g+!+jF%3qdT2TU@{DG;{?RfkKo zvRK43QhAJ51jzc8Fjvic)l{aT7--OZ-|wqHI6^{F*Emyugeu!*E8jh6%ueArFBjO z(C~^!Nn-P&A=Tp~OTMKJu9i+sv8`dY*om)UnUza1UI4Aju_4%zz zzbvB~=j9di^x%O<1u}i0VWM652KoYD zNOdHW{c~aUM@c-d1ssfokqbd@P;t7+$=V(&J-c=9g^{c_Bfx#Od{u1oV?_2#N01lY z0wbeQ5j3FUuKC6aO7Ff!b1R%_?9_SCiG*q z&hdI{S2>xMH`GD%`In3qHnu&5UoU)OneMt6e@t``u5(D{V=7sX30cfay~kAZOm0rC zgIP}2BXHA%r)+L0h>4e&G?d`@`xc%;F#XE1lE?i&&eLV1ZJKvtGVQg-SP9;*oNb@* zy5HaWJpRrfWq@R`y09?a^EF8?5=(nwcHQC|w6c{YwoW5T#A@_z_N$lV7&3kfIOWoD zN5lgWZ_dm*JJH(q&xKBNNze4V+tLHrZxTD zL=2BKI5<}jcDdy{R<=ZLnwyyPQbT#${x;Ru&jTA-Gmk(1uxA646RgT>BX(qX3iKe|8-cqToY|X;xT}t(nvipfj0+iLR)VHCB`uU#r zbet9A&isCktn3}Kst>ujo3?c}MVz95Ol8MPc*e+8XO$mXT|w`pGXIEd9IUueHBb1L zy-(y-Qgx;t+#7;iD7lsYJr_`$$W08>-?$cUS4MCZ&(^y0kktLGMlOHln&9hAP+pfn z?j&oWjF`t=t>w6!rK9L8^#nLi4SlUcU{lpkcXM)!5055~Q|dKv@oa-#{{;@to?Za^CjQ- zP&(n=tL*nCo0yKuq=6s>VeD`z>XP%Cd-lmfq9n z;9hJK^uFMmj~eN6`{dLHsU5=p@M=Y91Vo8HKJO z+C}YpfO#K{M<2piW^$~1vzv;nL^(`12Oa~b2=9}1hZ&oJ*>u6K=s0E;H5b+<1}oJ= zN6MaPJ}UizhqtMy|H9Z}253BS=7MqIf^p`$r6|vAM6ED4p@EUT)67xbHzN_isU;+; zGgqT%=zC74>1lr3Q^$;I@%{SUx7aF+%1ctd*h?oC8I?_7obqWt1~I!#s~#D z0LaLvi=X|cJ03L`mo0?5KZlLXC3jiU^bAi&9K^bO9Uj;m{uQn4tEu$@28cAZ5dXbY zOH_LMd$7L@7i$b)f@NVkXo|=^OaKcx#T@Wp4jP(CxC_Mj`o=OLac&qLzzz~Ds2juz zwCm=_%GP0HMttNY|K0y3&9z zCPbb@_QpP8!6Ev%fs)Zk(gDr`<#yxTakTWb(!|tH#b4BVQUN2rJqe^RA-5z>R{yQJ zCnYUQ)G0g214lkdM&^!(eqe>^N>X$h0wHJ!5CUeT$4OP|1M=ivNZlw;*yZjd&$ za<`~utcP%W>#(cLAd=Haq3_`YbCSdh;1;qP>p2&B@8AxqkHQ27;=;uSVaNbMj0YYo zEg9_|0*%CI8v{`~)x*z>Ssr|uf@xJ#wi&$cnc`uhI%F>|&X}P2J@|}=3jYx7sD3Rn zB-+h2E)WBiWr4BiVuK~)O!2oOI|%v<1ahrAL<;*}amJ6)+(z$2K2pWrFGEU%VFs@T z7(I_Ms%B&5|57g(I4!%FI~z9AEow~lkCJR7+flIm$avzD=#4<$*J-!1J-{>eq4#;S z?%z>1R%FUJ`eE>SoZ0-SZ}MQ$6JC7#L6!dXk0y)8rpJ_8ZE+6Og69PjhV>IqEpz2Y zDIW|OtKF&7dGKC|N&f{5ykRdPJEm*tbm!J5_1G_?_Dv95CVrDApFDogD3DWu3@WVg zGR{m7yweBdc=IA|>$(r|dQ6zy<$J&Pj8bSX>&=X=!}E#$nNP7o{Y9Flf{J;W=ByDU z?aPil5EJ*%HxgoLqI1VA_Vok5LRIh*&N5_(hz+bx@BSRChPUmgc=Ck1Dw3_Hlr7RV z*3TC#Qv!8In}rTN$O<%jfn*HzRS9_bCBa&+@ID(v{>qcpx&6+9o?G-!Bq5PNRK$`I zJNTZ4muW?^Zb=`;VFPy^ZkoS1-Di}av^ZDDR6PEL9gyduXMy=`#2^`Fb+q2)eZn_@ z=pE01>SOKwXBKcvwrAI%g+uf2go+R8V45QoQBBzUO?R2~3O{j`vC=Q}7jp1OFDwf! z5GG28oUC{-9QsSw2u@bt{TALKINm+E#+%TQ);!%Ywa-$A0JZYWbY)8hLjF z`@{~bUh=k^#qqnYgDig@zm0`g>;u8dcs4xZ?i`I`kmF4bh4)Y&XGN7qPF>l==d;a%e-p$ zOq3ge#w z1Ce%-Peb6|-;zPT)OEG4i7Bqs%)f#genGe5*^n7lbKsb}8=|k4ZxvBS$h$>iA|IRm z$_q+EP(d#f-0m2;3-GwaVrL#Td@jsg5k3J6vM7~6SMo{r=tkTsfxd{n*XK!$>xpTrQ0JZsw2_h4fo(-w^Cjkc#uM~R-d^0txUPRS}xI6Pp} z6lb{?EdpCIx!isk?Lt(!R?Gv-%e~_z)C|9V<``*!;igG25;du{`2t_Fb2tO5b~r3f zdcCJ{NY;&gaVz%s+Rkqi52RwMD#AM`iamoLm&rl3+UvgN{Ut9DWZMr>ZHnR;_BzS7 zaD~RZ?#;U{?Ov|!?p~ri9H;k9Y|HpzoFQ>X{Ki^Oy)fRtu`n{bru!=Roj0$1#J+jG z_=i&E^F7F>bTYs`b%i2Lu}%O5`JEl|_U*tsKbhiicbX_{szIuDPSo#RDej5n0AwGb z7$!-tVmr4V)sahQEi^uZrXl1Jx#YYN;M*WdZ@6_+x=u`KM@^Vz^gd@CXg!Nb~V`a9acQY zEDnW&p$y_=h^RG3MLC~CMBjT>9K=I^zx;`B(&eMsSGcIz*sFWdMI67nvPpk5@gW5netvUyiA$RvB!}RGI+$ROSzbQ`-msvLy{kOlK)qDP-7P}^)UdW zj1Jz7+@MxaZjgK?@2z2A~lQg2cd&ud}tH8lD%Krrx@?Y z0_E`#Nr)jbR()^6n1YMaH}m1|bC)NP((-p@0Z`^?P(i!5L#kI;Ni2{HVj~_@ygfqu zP;zWwLprb?I12BPfuY%u!1JF?wyB>?POXYVZ(f1XK(R;zGO=}k--t6jb6~P7)|ur# zb4PdsMJW_*Hz1(wbmmJh@T67ZY_xIrY6QskF^FvLP$f7-g1FiK8fGMblfqCCCn-vk zp1V#7q?Ct{|8zW9jv${_z3|t5`a;|?5$Ai89JqUW)Oqi8b@(yfEH0fBCu>HrNJMoO zN_`Ke4U_1|^x1Q040wJ6M_7ublE)~KT0=W_4;#bE3**h^NWUByGBnr=L%u^qJtD`^ z1JM7OC?eqK1&r!k|3ehftNjI+?mHw!NU@CD@9kHprSluMKu9&YB%aqa4(hqMa*A=`IC z+N9U=Y_Q}qY3DK*>R1>*T-`dB7`Q-lop zl{vX!dp|N&r@d$V?_*61+tT}u-v1PVb-*f1Sa*|YJ8ei!;EJWn_IZ5^-wJqXe&D*S z2mj)mq?`^Q(M(VE4L@NCfh_q?xvd!yNmB1v?qCq&A=d;4J^gu7l`mY=g4RThrnuJ) za=Dy^K+k{b>kqV=fxG4$smXwarMDbxCAf#gbSsnD6(dzS-jdwXFOuVuyIGz51*-0+ zqe`{B=_A7X;r>4p*g`vVGQ^Hqr;ET&4)>&r#PD&P20yO|Iwrj%U%RE$(@X|{aoWxW zxn5DUU$M-4GOhI!E8N7LftIVjo|wrb|x`|qMQtIgg%%(8ofsqS0<>F>^Xw*6dVDx1fbX#z5B*lt=5@1DpXr%*k_6Gv>IR zv+Lzo8R)#GSeG7xgVi;jP3x_r-^a4F`5<-8rvG=^C)VEou zPrp|l8|w)ugW%rxKD(Tfi96K#<7;ML;1E7(ey5WzUlt_FHNPpT&%`~ za)ywBYmg6D`Xh}oS58XEhcx>rRI352R*#Pq#j>ptczjH`{0LVo9T{*Y!S$VmJf;ZT z2ht;i4)$>%9&Paa#%R!y8$#qc1pB!x>ciJWV1pPsP?YAjCWoxU3V$x+pJiIeg@`VE za#@O5dKXpLgjKDhi@%cOj8zOD0p3>+L)<7hGr4qW_qYh$lZ_94bw?|2E<>WWlW3JQ ziWz^qD!k%)h$Jpia1)nlpYo!)R8U$sPWIuPQNu|dR=DG+$idtG^osLeh6`cbR9@q0 zPb0%0!2TJtUuEHugb>a9nCJsvDVBZo9X{+s`YS*@2o5kBH4@it-*s1;SI3TvUwTYX zUSn^NwG0_6b7F`yqDseAW|lxIG@qZIbD6$Wa%$YXQi*N#<#IKMRalWqwC8`xr7dZ2 z^M`r;uRJwo_cSfmVF3=o*_7<%7}OwcIWH19ENKB=Z}hySi_JVlr6yI#Fn%EWb^Ue` zLaI_rCY1R$DAxB=1&{hUZ)U;F4@&a*IRcIQMCx6?XIJ)hu5&MgSnu8|r&0j9K;5Sc zowaU0s4JsjM^9K>$do2HK37hukx@OPbFG0es{T>X&9UIc7S##eqvbAabZV=W{E*Uo z!8O~Q5Y0%wAxJz|PiQVnXoWDh4*h_FZksD!e}QVPg)!+pxaTKZZp(s|;8^=a+D+X| zKhf2O+HY+r{^A<=eEI=I} zRVLC_T%TuSY58G()}H0HE81)DHr?;>!56?rq!NISJ`#`V07ni`R|<&How}qViAhCgqD)?QmgaKw?ly`PF*6 zNdHsf<3%7^R@Ry)NA2QFhu-!jfli7;%jzvV*d>5|uxV(EtK+1!vYV<{N1gp5@1NCx%o9J9HU&K(q8lgj8EGymqFH(j@O zJ@I_p^Qp|UvF$ba>AXqrwm1pxrBw<7Jyqc4VeUG7L#@huDn=zB7ct??CVIrZ_{Zi< zucn%Csj$yUBdoMozxRWjzFa^M{O)|ddrUpO8-gK9xwgW@br3}qu7@Dbl2>w z-s=sI>bI;9yFT|`UT^ZdgR_~7W{JZDqW+dps6)EHOg@!sEf@2$yHWOmNv#C5+J`1m zn0#z&n;=M{(|-BU#tg$)1J$OManS~>5&t>LPA9f2Arkrx*U=*8mO7*J)iMU|2Z_bgB2@=D# z>#Cy$??;5Yf@$DV!P-(U_OE%oMIQK)tKiAwoh2*44^e}vifUNa0D#H0B=Ty*hh!0V z&rWe~sc-u$kP}L6{N<>El>C!tV$n0RFBz=8h3eiJGECFwZ4AI8m z;g14vWV5c&8H#l1(-3ah^Qkxqrl`O~_ehz_MaAg0M+nZSI?|2+cGVb>h#&=>FJN&Z z&RzIS3YFc7#j*GsQqOXZCTZW??_5g#Zj>xJoi~-ariQQT5vL&_&kfMAUuI(?dgy>E z+z_`qEyi3j8uiI_NZmx@eFMClzR9O4=qH^!{ugFlgG*(shS}9#8)k+V*9B~0^!WKn}wRboAfApfBhM@|qwuyt*8r zxIH$9CFCD=L~86%3$BeTVdw#2!@kodc_!ql+k;UXaoB+W`w3jB>KASpq?lC zI$?mdByz(bL0Xdqh~WZ~>{*NK)haBU>q|ox`z4put@@Yk+};8>kP^w{8P^Ej;Nm{8 z2UdnkrlN0Aa?=QY1IQTL+QR#Ms03&{TxNuhBvQF`V)c?`0oU-Q@fC)c!|Qr;O` zHbv_}!dgjv2?L!FE@{y6krTn5FPmM|#8El>`sPRRW1}F0Xjxyh8ahg$Ck508W`#zI z#}C|utNAx`su_U)*4V%kKJ&#`Di5#RKKP+J{}~Oc08GfQO;MRL#efM$daRBTvsR00 z3z|zNGyB;-*J6kU4szRley`CyWMnE$>PVQHXsgB%GXCOuze)fInFQMGFA+|-G8{Op zAC&dijX+DYgsU+&7bU|9a;jV1x-az5aFg$yP`PHNX-viEPzAn)pG7ZX*?^vY+15ct zG?pVx6rV z(rmRMF}GM^&CQ%cDz!eSiS%;2I5T=j#VpeCX>d3^$nEQ3w^Ik=I2av0Qk=Qv>^;?E zQpxi0ba`o9=1zZ|m2P2_K05liX9k%-TonZ*XsS#Y?FL2Z)CqB%5cRt&6|V1`G@Kz- zkJ+kk&Cd>1bUdl@nXM4tdG0&#+)Nk!0~q9|iyzb%iE&oLG?Gr1Xc&nksVrK_e z>_rtVRKPFaG{a4u~zdB7%kIqJryptRe@ z#QDY}@d}K)mfCEjdQ5UWq>tny<-c&tFoIM(By2w+;ffqL?b(7S%d`0za(Z)fpfw(H z>pDHpaDoI$y~%tPLMgXuY>B4$gfX}G+|RwF1dhMwM)@m!RKXJ zII_(fX~Nn{WPb#i)EQ?E`P?-+HfzOSX!Zzc|3pYG$!k6UvAfg|En!Cscp*_)>_CDhnc9$a(WnTwW%0}5AYiqK~y%&r3;^@ zAkZl#qgNebC@Th4`!u@rwyO+8At~-Xmu~NEG|6=-C9Aj8M3?R%HQ(@SeiW`BvhjR% z*R%WMY-LHjSa^&W-T(y=nLKzf(?aNW*ct(S)JFk6jNo^?5c&o)13S_3Y|*)(U!yJY zll0T@vQdOvjHuv8z*l(C`*;4hSipfN=3;xvgn;MJAP5sk;SVk#$2`2GvA?w0KckWenYxSo|d2l)?mfWlqDd+uAxaM$gCY|5n| z`i@dc@t^=dmpNZ|AdOpq&K82XD+&v zX^#(*=$gGX(X}GNUc&G9+_l=0I`rAPp2>~GWfE<A5`^){=P`Z-#(uU`-gFs~ zbf%Da`gdQ12~_WW7~Z<`-u7pl-eDwlY8@IQ3Gu)kVRSX-h)3-pIsF zk;dQRIa1n5zciMpz&{RnyZ5i&ehL30&Hj{(Pv7g(DC$H`lLn7$Cshqo?;;C`-rRqL zG`6iT%Gj$T(ZrZCfBWWTNu`KI13>TCkXb`T;*g;V<~+UW1}zi)y#W&9SYV z-j|eMtThQk%O9a;*!$|=$`~fY4n1TNs3Wa^i%*jRZ$K_5i%<=?jo%0RJkq}p3FQ{J z8a#dd`%9JeL(MDFx?h)=4b*p14xfubNN5>fbHMGFFS$-zH3wzX@%3yB^#}aR+CLuY zI3DXT)ZUIWg&9QgdF~_|f>4qHGv`f4jgJ7GRyvLA_f#P$6~e_gX}+-lxJMfwu@x~( z#-~e>578h!2_sJ&jQU20%%Q^x4@5ag6Iu7)fIm9kq*|j zc%sg45XCYctMYg72I`eX+@3?up5;q9HBqwfY6Ko|ol~tYpUVmHp}(nlA1_QsEJltG zf8B?MAc8lbE(vm|J&{qBkxi}hvoQckXdZrOV{nm?(>c_C?{e(Ve+|+e9CpgzNv6mX z?4K%S$Qs#d{X-tEsX5LhivBu(%o-M8^XR(Ed|z-x@WW_~LUy!y#%Yx2iCW*0 z^-Z~bbwUY?29JbhZ z)uFn#8}t2>*ZUCF(>4C@@_A2pRP{4br#l=nIs$D^ai!~W%9=l`#k{6Zoxa}i{tkq!jfPojnKiC5$^+OAZu zLwg2QVbg_=I{mj4L>*5f*Y5_X#gO6dFqJr$^2ndB9Ou(^c++N6hLbh&1M+x0t#Q}$ zf>ZbVt@X917csh;dodh9kyc1&<>&UG=-o2M`TvcuyYP$h?;3r7F+&Uk6NGdO5`v%% z-E9yGC@8Ifh?D{X(lT^+mkiwqNS6bMgo3nmr_>-Qsk7&I-{-l{bN1P<{qRo=*IMiQ zc>`!LWxIdHH(4X5rs~A=Tsl%O%Qy!|UAI57MUg@|<+Q(OFN%vml)gK)_HW7}i{l!9 zS1SEdz9clWoK(6BmfQg@8q_AnyjoKtK$MkZO*)>bFT7pyn_mi&davEORp%VkAuW~J zl9cFOBW0+5sU}8x+QF@!nOV^WmJjA6rNQ)J6J+$J#iA_blhp8Cn{T=oQIr~LDcbUx zsjbpx@?9^aRCJZA@0_SsctmoxIl3tHYrgrdRhjP=ZML`? zL^<40C9$<+^aIuCHQ(UX6ZZxZ%4XFOvDRDa49^9O3X=k4zJkTmQlq}Ncr{8~RrFVw z0`JJ)%FXcX>%A=EZu#~h{>zIAwm77$`sH^-*d^I_r}*}3b=_=HouWS72UQAR58A$F zD!20yzkjLOa(4>)PGtIXcDb#(<=Vg!rq*9_F3ovCl+E3W@Q!}_Aa58(#zVDvIZ&G6 z^_rS@7X{$B)zvQh$@ISepx&Pi7w@E;3O1Yy;uIsW6^N|+YkUVp=?R{%dAr@(k&w*7 zj0_S_do34$Yn7PmDrG(m^~)t=J0qm$)%1$6b!Im2Q>@LN=J;i%f4uB9y8Nz`HvchI zVNR_=jaynt`Ts){S*V2~xbBEcqb5K4&C#omH^o1@8_TKk4^dR0f+Q$oE~V7XGyKrx ze3{Rkl5S^4Z>)_sC%(|hQSv9hBAaCMApdSW-=hpMq=Gj#hWzL1HNx=2a)TP{iI!yh z@8!|Nr}Ak_x{6%9Bck%@qAyJv9n}tNY=`L@VQpak3CeQ;>jekqQKbq&T}9 z*v$r~M&11vQS>EM z6Q|^oUJh9fT63sUl{EIdGY!l@$76M(&oJl-8J(zF-)=ZTuk=O23gLRpCbAZJT#4z^zL3HjH=Lq2@hTU;k*CJ^092+j`@DPc-Ws zTo^*W8VWKziJ-=q;&l znA6?OiVLO^Uw*>I)Nsk%N7_@}%ezHZ5VI#7^yh*F(zsc&&s804^g8r*%3;9On>BjW z)Ed<5e4PW#VGP7GKC-1N{7Tdjp<>4?h`aosXldiak;^!72hlXqDw=!Rq?GiClb(I~ zPL5x?UD-c+%YXaF#|Bfae4R5SRs?uhUt6wn5fpx@w&M<8KjcZ`zB`JEe6FgpIAD%p zz_fGRaZ1c0wPYeGRlmg%L~2t9;l4v8Ny$dJqfE^>8}m8M&9Mp2k)U3y#=A-bB5r=; zS^SR#kP=gCELPMTBAeXVu^qgjT!$enq}rtu6zX)Qx}jB44F|Egox>kQfjI!c|l7 zvS;wSopB-J@@*7vT<^AwcXB7Y@r>l21%d8yR8k4gF9B0{*%vdr(8stEK;>0Ix2d&Q z@q_UVN%!lY-?6wvtLTQ_UKk0^i%FK{g{^9i1WeWyxpI%*V$?q>xP4RdXBmHGxf$I6 z&pQyl%lT(jex07wU4;*AA0`4>v(8zcVeAQe>^`(pU{0>A4Z9q zQku-=>xy|S95Nx8&BRLE6Ju3RV`KwcN-O{u+*g(z6tWg9n{M-2;Vc7i(8nXuo>9-P zP|JbEXFB08qEt{0h9NR5{xD)d138BamCVXVj*U8i%d0img6d# zxgLk_rc>b$Rt&+;cVy_mC1rX%RPHUn5HWY$&C0`dve-4ouiMllBjPL#7H5Y%I^Z+* zCbGjYDfR9~GLc(~qLv|F-Ih7!(duGPxZ;e^&xlj6;1C%>W#p}HzF^2<^5VmV#9W4+ z$i3RsQauo>>ihQ7<_!jWp=T`R(`{1PT0##=01nnqG+W3pict|Lg@f{yS;)3>kw4Tw ziklY9bz7498QZU0%|0P0KFVsg?K+z?TV8Epv(gWgg4%Uosna&ACWRKoKX`s|mkE+w z6MqpTs8xtuq`F7V_M8&sUsy?pi^3^@xai0XmHGgQdd9mR%tvxZC^lG5sM zLFo>!y_3RUy;{GQ++$Or$Zn1V-M->I^v5Z|E3?avAC}Fgepgfi91OOh@P-@$%uUI6 z(edN+BUL4jToPK<83@VNt-K|9RT4(sEk%&al8(vlzUJHBtGBq?j)lQ@9c7<<3&jcF zxQAmZ65t}B2A~``5>_M$Oq=Ns;|FJfO0+nh9AOE9<$)D!|EQ{txsudE zx&U!V2U9h7j1zZ)F69FxrAzN1PaFYR1P&U!>VTxE(S2S}?SJVwep6G}0VnWo4+UCE zd1FH<0fKR>!oF8i%78!?x~^=4SF5-#YVmLiRSK#AirLQ;N_i2Y2jL<^Jjpy7ruKkdNrdc|Z8@+BbLe7` zRi-t2fS}By4(#P0bFGsow(+J0x@$F|`-f7c99x}R(3P9{G+N*ZTwIgI7@yr%FG!JO(U9s#!Aog7+_GxFToD!;ZIMaN<)_Fck9Md3e z!}+I%!f%A@sS{f&uFGvPBB`ZALdHN4k!jJ#6pzsEFNDn`Ue}sWc2x5 z=;{?xd;X_2{7PLsj|TW&(B3@V4}o?8lg~quAU5`{8_b}as|i9M4=K6ht`Ry%Z!wv( zm90bDMY;M%e#O*YCqdt^j!hvC045WVvk5m{Xn8Nt0`5-NY6`FI<$-BC?a+APa8Y!7 z>=)D+?MNPp>A)qqD)1^C!Sq4I`R5Jx4_s@nxh(a#KG6t*`Dj*_IdA!kwI}fO(0*0b zFfuhCvl?rJ)(_binDogDv1g-WjCzfOOshXi})-tA|^XQ$5AXgyP~TI zOVZnNku-8qR$39dPY0YH{T>xl?)|A`OD8LwBujOyEK?Um~~qFk?I zu{UqH${5s*G3noW|C&b5^-e2~iioRqiZip()5hwjuqF^_*7xn#n;3&ORuk9UdIJlvb;&6sdvnmsn67V zjC@%kyC|kn@2VYrUz^07zCq>45V+^4e=ktvYDz7WDpr0>|Gu9%$;G%1;b4F6L-=lz zHkaGxt}A`@^8N1do=Nem1IHndUog5Wdb7uz1aSt|D=M544Ih>(0mDj;7x1gyxLKsuL8^8-doA1Ly!-pDu52$muVoqQa=k4QK&XOy&X1Y7Vji19aA z3a?sD2zisreg{gSY<4|z(~#bR2ysjAP-DtgtaljF4o;_;YXAie(G^F9?DKS5Ci5iHt*e^x3 z3Gkx$3wKEe-YZY9fUZnp$VUN|;aoD(eLYH0WC!Zi`kPnV4X+4$zh50nI_|uIA2&E| zOH#k?e4bjx&^T#rkaGY1xMa^8XSuEl>s+>x&qREzohPfe+D`;aj8xz-)Rc+W%AUS!gK?Y$0%x>V8)oG;6sCuXHE7Z zqR!97Lkp!53Qc(Q>FfI^q4lR8fgZlG7_aFb${5V$%}z*?M@Tvoz2Fq11e5#WL-%6o zr|wgVULKM4O_5_#lx$7VI2`101+mW+b*(8}!chNXs(o$~O0kn=frLF}nL_Bf&uWvH zfHS5zKW1+#^ibL>Q`zA0DI{tMa?_eFhdDB{KBfQnwpOc@DNIiXRlym2Pz%2bXUZ{8QWB*hI-Djp#D>BuK}Rd53@VVn}7Kp`_=! zwa&@lpTV2yBOoUybWxiq6_$vBhJ_%CulfCM`>*X@egq&TkHEC6Qnu+l= zYEU}&{KzB;Dkw-#h5t~e_L3{jHg4k9Yi+!+uQ_gFlxi0CY)+po-b7IcWPIrL^3*wR zp}1&l&aBJyV%4c>>dbT|xS31$L3OlfW#WOgWaWW8%yuZ^fG>%x~I|<9)qKxn<(y{nP87 zh^&sySzUj*ruNKFTBb2#84uiKGW#<>CNh>3UquusBNq&O1^SrMlt0&Ges;X%$u}LK zo9=KoeWBwc{IIP!8|Qz5!l}r5nlxl(w{_>rcQ{{mtFXQJcroxx;>$0~FO5b8+X8u6 z<{sUb9z9rWvioO^nz}3UpIE&<Y0`#@^Pu}a4gLyVCMiiK^IxC( z4)~AFerz9*DCnd33$*fhueYi{xC z{CD^9VpYUF_V?Vrp4WUA%*@6n=ITD`4PP7U+@5Ya%T6FW?LCqqjvOf`$*`ejo(~j~ z3>3V!6(%kIi0E*v=XlKtbgVd^tw^zWNGK*2&JPV`mdSi z$+y9E%A$9h_c`Vw*>^^acLIMH-cvjjd0Tv>I8%rnD#y+f-g@>nU5=*y_(Qk2`WJsYXZWQ3&~|)r{_1Wt z&~9|Ots(tQsr6{O+Kil_pvHa$;)64 zu?rm46L!O;@ZX=D%`W^%7hhNMW6CF7l7KKce^M$I`7m^DS1>iJtPeya?^YPx~W|VO-wT3qJ;y=7FDN*F1%j{(#7rHeG;Y68sx_9n$WBDspyXlZ!{8>7I}??ff=||vXt6PzKvBMIU3bYoLwUsyHx%5gnd!X-~R4fHrJn@k5(szOPakt@0?#; z5D?~=`-kq2-xLs>4Ggq|du}}m+!#zE9!$>tp0zyech7xsQd)0e%nnU@YDBzcgaU#U zql5CR6+f>4FOu?$C5SEPe>DSM*Nwg(-;qg&ya!n)mML}-ZAweZb ze3T5z-#kW0mF;RQH>j{P_L@pk-Zvza*VC#XL0eP6I4+@n?alqkV`GO86ORj%{Yza# z6?&OIzq8bcH)1G%)_i_FBPE*f!K;wjB>FP_ps1c zYW@3yu>`1*ZT;kv$d?aNW0GxcAZ2Up9&Zgro|HUNETO&87H_azR?9-M@uE6H!qKp< zOy;prDS$0kiNSKmQEW%8;K<7yj_ifLP>+9B5(LoNJmC0*XcZ&|b9m>5^%v(}4wtq{ z!});UH#DK=@pqYg(!KYS1w@>q6x^$K3R@2cE^hkD?D!m|D-@Sb7>3%=k$h~0e+rN; zq89%o_2;;IkQ$`0I-sn2NkW8fQbYGZlcs>l01G+CI zCXER$H{!lCJfjZyY?~9~_2XM*w)EWqgJAPw;Sp=8FCIAsys6^l#^XDW&N!~%J6VUg z4qtH%O`r()?n|Y=_(bBoLKl301SIiVn*=0-{Kf_Ff35CDY6&5G#!@Q1h(wVi!;WeF z9<%*&$E{a;Zx)|~DjfTan76jG#xg9QMT>*j%x~HCTtQG<_^Val5n>|)*{KJDN&SOl z$Wcf#T%digYJ@-<8SnxY#4@TGMzq$u=*xz=t_4AOy8L79uqs^m*{`O=aAVS5&)XB1 zX^rvck=M_3c*rhkNk}|WuFg1Ig|KOTpqAMFeOkwQ#qx8 zNuw#?X!8P|8>JdL5u-_E`h|$<08V0sGi|`NNW8N2zGK8#)(_Vr+){v!A9NfGohW{C zs!IMiVmvWGzd++nFxtf8&+M0RD8|6lYYLkJw z<9VP?85mTS8zp06OS@DdM zYPwJJO>I(T#q%4pkQ&YFl`r-xUMO`>2l$9(ftWXyC7}T^Z^aADUcS_nhyyYAVUVKI z{x2OPXXk#rX>8l8baa-RomprgW#+GPj*XmK<2V6T@opPrQq9LJO0^KGvTwSX*w630 zmS|On*$-D;nfVss-j-rlqE}V}HCcI>y3S)`QZ#)pXhy5U++X<4uJ_Y(_)vT3MOA$l zQ6Qr75Ck~-xbV4QsJRic-JbWi*e=cgydvwO$;GP)`B+dAv~&Ni7kN@puONF1abW)- z>7QI`Ec*!`IYz7X(Yr_{sav0uoDcDabCzs@>L22-)`a;{uc30^D+@}N#0NinRy=IT zrDgp(0Ty2~VGWXbq7?R&dZ6I@|xlB^5(|V%T zgi|$!tZaWiT)4a!Zs<~Br2Qd>Ahh(VJr2dZCVjbB+5Sj zj7!#Eljf`&Ia+u1rOT#~lOrF`y(!i(X}Ya%Pd7o$?7A%9zIgwO@mTQZ>HI=sL!#X4 zdrgw7k?Ef&4>uVn=@@?By7dxib!~Qvro$~%u+aXAmR#`2EA$7hyxl&eclYeu!+No~ zJ=SmMn5LT#Z(Az2xR!g*@4jkmU4$KYeDPj5Cf=DI5bsQPycaL`8$S|=xh1Ns#iB^6 z>PW^{ynd`i63V43cNedrnE8;kv!F*f<}k|MXO-=ssaFa9GcM9+jYqh-Unk~gQn}B% zkYn=~Gezfnjg6Cv_8y;Xqg{lx z<<7og*-(7@V7=XSX8tCsLycme1YLu{kdGL`yKoBq_{1~u0hRg}~ZTuOf{h3Sr4|@IC!`^a20yeJ&a7(}C4f7RqBLCQhxv>>c zoapI)hed=xFkdB*ug>%3rhAHWpzv0p5`ZL;_F< zz>n~-Jd6sk1gh4B|6HP0KqIU0u%mw!w#Yg`>v#mue;RVbOb?`kA9(~DH3gfU23tsn zJeNjB#t}dA;q^S4QVHD7T%r0l!61uJ)2(0-Nr9@-h$y#&YFN=YL#TRaL`iUz zArd@HO;9!_9!m_O5L+0i5QG3YY=t=4ggp!kbDIkHP)B0 zKQY1iEQ#Tlbo7Kr^mJ47{Ao0Rj9E2|840}R)phOd%58s9{$SPEk<++S{`d>ScoOD_ zf@EL@fLQ^=>AU#uRt%m$mfJQKnI22m9}6C#6cj*4RYUEu;BXXTQa$m2DfTGs#(OCi z?X#p0jLDT!gyaH}IVT|Mj74+Ak76*tZY+k1T-fH8p%YIWjyora9GD0GTV3 zk*|)dK*F2^Qr}YsbqZt|{H9!90t0Ab5Kp4JHU*>tuhvDf$3Yj((^SpjVon-6(y+VT zkbULY&*51El)zWw{~|hqvd0A!zf0j*gok+RnfR?dH z%?vUwsy7L_MEa<^Kko+AlFSMEw;J&`PD_sq-d_!ZFHsVJtXKd+z`+J7Nv7i<<)Bgq%l%m;M>QW^PjGx@jDoF$AB8FXaxC1eYw z%kt%CBn)S=fMIbRIte{J39BD6+AR6D*9-M$ir#NS-8D0+fGjpVLOG!TOhR#QhQWrV zP;#K?@sF^8vdqw0#J%(qP)*7GA9>k7O0C@>YfcceILHqy1Y|)VpQ@H08m1mZM=4;* zzdFHgCqh3gMc&OQ)fyHinb#)pu?JOrdlK`!Zc9fQLn;6e(lfxTFQ%B z2=j+By!_x8ViW-AjB^|V~_iOPSlK+Zz zB3Uxh!cu6;ZKNZ>y3h?YVt6>rS){$7A8=$vtRtz+c+8FYqk}Q*KNg$5TP%mui?Tn)GWm z%+C^T?h3J_$E`bc5Ko%+E;P2&fmxrI7?-`>2SO^|$ zqYIlvn{!~HE6Txz=4o-t@N*PALI{Z-rryLN)=*TROpw#f#AZm8vqfLnB`l5_h}!MT z6C(5{IrOLP-hPjR|G-i&N@y0Y^@nElMb7obI;0hw_NU4tv(_}QR^bIf;dY1p^+L#k zs4rsj5rrNRrA_^nQ%pT<0}ZAFEn3I|N`q%~@NaYdHmj72)y#<2)ExZSt^n6_!mx*+(`L9%;(B5a1Hb&jODlHc&18*=HPh$ z(s*3wH$AR$ftM40uqpBpkh1br@cpUgIarOZ8#zoHa)YHp8D2%jGSDsm@IrpGiFpN8 zMXZwMj?_X~n{{9S2W-?G&N2EDf?pwj5Z`qi*GY4kgvYA;-Pj&SCbTksZ1RDmxcklH; zip+O08Sgrwd)4H3+sbouC*L`fU*IX_F%U6U7RBAplo1juWdb>2n9>R*@eT)nJxu1F z)oT~Ocrm{yhMieMlizh1oPjM*wL=&;nfXF2JHCuCY)0gdEWG2Qn86_CfU!ib!9029 z)F6#v+x86%V%RAw+JEI4n9Ab0vjcKjDrQxtYE^D%RbhWs3BIOsb4^Wq?e?p+yD@7T zRcl&9Yxnopbl~d`Zm#QTuRnUVZVRJCq0v~D)E?!C8eadYF@E9QLVT<{@CUt`05 zXyfHg2J8I|=bM|ap8z@N;AwLRxU=dM35#$l2&smhA>qSjNIFGHCyz*r=a4ZpVsZ)m z!W@Plras$&D0IP!(A9hgMIY<0;ObXCK2;lXj>V5j$)uXcOit`f~52Qr|_y!?YnoudHNH>U@c z8b~KaWc>mJ>?SGbXdsJ-!p$CDflPMLe0gptOU z7#?BdI#7Mn@%S!L8IOZU5R<|{G-YuH_}mGqXbxFJ@jS==P{cy2w2@%|!U_i}GuYws zD^PWezq<`K!$E>#j$a=9hDrnRIM_J`K7<+C`2q9!3n7>*VD|gEeT@5YZ~|saQRlbH z)1M%J$jc`9s4m12aTb3Nn5PU+a6C&z%*HyA-=2mSV$O09=R(=gbqr!21ubJbFFjZ# zA^9JLvOk1B7k~czAzWS%E`Ad(j{gfOJN|D-*%9Gn=ig2lfvA!F%OfK?WrSbbgrmi? zqrKzffi8 z*3{HgUtj-kbc|3fTU}jEC@Uirn-Hp)3FUNzQYu0*IiU#j4>wi-oR)|;S7s2cvC7Iy zA~aT7TKaEmEI&U#H#ZlH#S$_z2=VcRXh%XKd@9B3f78d3lamt@6XWCKi3V9@WMpV) zD3KTo4i3KXwG9jm#9%OfetvJ?z9lMSUS3`v9v%c|XM&wH!PJys#!b-CA>3yss0tO> zKK~Cu=H%q$=;-)wgUrUp#@gE2($do0+?>deJ$drP)YOzHkr^2oJ%0RHUtj;gwu5S?tc8JGXA#QdLz|{ueH$sHjMg<{_Z35(GF2+-w96CITbT zCW8@R5CRlJpaB0vgMmQ=5|TfRbaqmbM2t*MPLAl2NlQ!r|4A}IK|!KQCLkbi?beblJKnUG+)4uB5?ocGRW|n$QUQZ;GnB81oO@41Iy+ISx_BtnH9KT+f zX@6}YF&gn~AWK7RBS28p{C^V49x@v+h?DmGZ$jCV|5+$&^)VD8Sq^lI{BJ^8(&0hG zM2R?PY&}?Z?QNc5j$`-wGlcu|UXp-qv>Zk5HBqZrVIe{Eh7W)?un>e0s9?z4&R( zpDyN$q?!c`DTB?DKluFQ-CL@k-%)QSWegeKUOX=_SB*`}zY@UqW@|YVHR{S`M6U>0 z_Ms{ASh>y3Vg*Pi2Jx>(iBHE`RSF zd<0@6<{+hZR5(%Np@|gU}F};SLsEcnol}v z(Y#m&79Z@$trwN`lZGEcU6De5Jv~ZdO>-mMV-QzOAvzIux7PcupIo$DKIorlx`UU* zyv!U4dnb#Qzu6N9%)ix9@q-lbs!(f}pax}bY~1h+q*=xR(cfzunf6b(Hm9DzYPZ@>7Pz)=rr#VBc=bo6fyA#(EJX6S z&QgVAv577s5l|o2kU3Iz8C40#(&-2!7QldA7kxd1T$2Mn%w!h9)4KPdLxI@>Ay_BgX|fiSeH z^q2WCEJ+|w6G+2IN*{*nM&;2LZ+#-==Wzp=Os1n6!TwQ}9Bjz28+S+m=3{GAQ(TZr z7FUG7e15P)IcORRk_*HShkAT{_UAYMrwbbOaCPbeR5wUH2^}91c5jWYG7TwYN8@?K z1mUR?LF%`G0L#-*c}am-pK1`0#gi|GN5|>l9^7rh+!Z8^2i4cyc%u@Qeksl%)iN=f z@*$|7782K(wDvM=LtqURs_``ia>NbLn}bsO?~y&BaW;xtk|SSfIjo76Qd;tt^jrb~ z4vAy{({lkGN(_k=3GKN0U3i62v*E(%s{?%v;RmAMVvt&*lm^OViB9_kWh zDbR2XfaYt01S@l-%iBf7W-FeCGB9-AkxFnuK~WS}0cGe<+`|+Vp2s&`8otHq=W%{4 z*}VI9yO-pOD;6CsaO+7+d|+1){Rq|{+Jd?t3MYM2h7VzTjUl@o)*18*2tuGbRSiG@ zRb+Jl^@dX{8Zf6>I`xO1y4+Qa5HENt1Bje=QY3o?6*eEu?OP2@HdqH0^`6aao38}E z7+&T4Ji8)J_VE6c1VFohyDRg=A}CNumHkkf?3y++sYyXM#|(dv@?%V-N19dWK3nOS z_2$I;tz6E}IE;~8z~o}(L}khSJ+&oc2?t)7P`Qb*b!UXgAYs3vfPMS6(oGV~$m@bS zHp@!8P_28**8TOtfj7E`M<1d7R_j;^sED5X2QI8I@ZfI8Ifs9l=YIA5ZC|$FeakO% z)2|s?6zHkA&$*(&hTj`r@4V3Zel)*7)9C(d@0myP<0o|lq5kTv6}MRErQ98 z#)s}R7qV%UXUSprdt2vH(@&Z|2MFK%QcF5KxrAd0c@ajoqO*GIw3DB2CY(!jIX&)s z*WVtem$rg*_m8>hsC?OW z9HI)lYx-%bKjpaKMQ!L?>Q&Nj4Q_SL(a-HKOl+nU!y5EPaTG0B9+NC{GU2pN*c&9k zNxclwQjg=h%#Q@Br4b9h7M`4}(>Kq0UQxz5-XBX`3?ck&90;zkPvbcPp<|oBzR*6( z=$7w=I9rhl@83p8#79{lM=Ouo#Mz3gq7ppF?=1ON0e)?Kx3(xmv&@k;Cbwq%9L@$B z74tEyq!`An(5YVS-?f>4b}c{R#28sR)uC1i$!%7AGSmG!A+$gk?v6~mMOdM`Y3vbP z{+^KYGa7xfMT5I%b`Ht9%r=rj2^py^q5DaijwQE0YIyf2m&8nPv@%Kce_e_O$;P=;~U%5$?u#+4QSWcZ{orQJM>X_tQ*JFj@MRD3`8=L1-HeaT&k zFw{V9jNC24K~hL&e@&!E@RlSU4a)n^U7Gr9Z^s$lLbiM<3}x3hY2Dlm7AAFjPxRg& z8~95Y20usgnPOs_0eiGG3csmsi+$p^V0~}AgzZHpOoE<(n9Q{gXT}fL{5Xf_?b1; zEnyJrD}2_co2Cy-0>vzzrJH-WH2J!{3H2c)hI%uFKOYJ8Itq1X2=kN-3y=yflM3KH zCGRTsmFe@P`W%qp5s{)2{;Y}iIfUVbw3t1F=4D?<4L?$zpL&`iD5}q<(8k*$ECL5% zC_9ya=9^ZCF~Gqhu2WX|VS%E~zyRP)l7{@iL}MBj`jIJWhM%rG?8e;6jn8QeYY!t4 z52DxAW8fAsj_O3q3c2AC^JXfNyeayapJ84dSw4Ebu{Kues$gALEFi31IIn$Ak6_ChOzWUbSKhC>ws%4&GF8n*VxYDQR#eM32`*dQRUVN*97QB z$-K#yVvySjho{z8WD-SG^a7P(cmja@g1fde2W7JBWU|IIz%lB#{L<6s znvqV=Nq=Gy2L$s+Z=4XMG_Wiu~uE09n$F+(bOVK#KKi|-)*M9Be%$i z^v@{M$mSc!`0AN=y(L4SCGXly-c8wTG)w-VOuqO)#xFi=U z#s#!BW=+aatPC>0G!4a+98FoMlR-lYP)k{Z$ioxf7o{567Cae1&K6P?qtjlakV=>| zZOt&}?X(Bi3k57}KV!&qPveZe>_w(+r%wx?XzC?m$wbA8J0h~@lyIAE>LFZ;9yHRe z#W9kg=`Ea|8hsrZluCIIh<$u!uXY~hSyp^oQ?C#YJBfogp-L2{iMurDd{R+nUwC+n zQL-nEF1a^{dFlI%mo(=(bOWX7p7C}wMK*@zRRgp#EM&E(C9X5Zsioxu*O6^4Wl_^* zjaN#qPnD1?QAusYL2WA{!{qu~Dq3bL$~Vg+pcNxCwCaGd?QlZfd0JV<>xHt4r5`E7 z##OuL0E=KEi=Rb*NZBcY)8-zn^h-ly7?rsej8>%Zts9&cwy`%E{DNXs6Fic~x1RKXl z-(G?~BW~lWVU;K(8xCHC2dfQ3H;FoyIU=DN{0K)iO4PB?h<8ZRU@XEMi%dFgYh`E; zmTS)}Z_cz%cm(mb)~f%mh5Q)+%Nd4lqhJ9T8seVo3CaPi^2peNY{rt5Q0?pzhgcCM zzg%L=GKYaXp$+D^p-7xp3GT3`IeQ0p+1ovBm$2i}7z6#3l+L?AWU(v|r&?qIx(H7v zni4!Efa(HqL4FYZu4;HJ9=HNPr-&?;6T%-0a1TS9P{=mmKJlX-Z{D38**)yt&Hd%W zPrF|Ji+cLQtne3~boynQA0SViNP?U6>HzSN!atP4DZrP}$2m8LGyh)@~F@i?6c%?YVY_ON0hB2N?;x z5RDAfh5zw~e>CZFpawVrSUr;c3IHo{A~PI@PGZqFt6|x?Dyd{Aa3k}5V%dxkfS3`-5gjI^Fkjgk6k$!W=O*+{qFz%ZaBRCyH3hAZ-xoZ!}Z| zO)$XLn?;qJb@5_Sq4` zXDZ<7F!jMOyg4on^nhX%h1f<>DLb|Gx3&#Z4Po{I0(?h8vaR%Q)CRpo3R2d+DVy+~ zRiZbWX?CB{yD`x`KT|SDqt{$mJ~+dm5>$78rh)x!)1Pi4hS=6V%PNxEI#C@lKlAAZ zo0jh!B4sW#d&aGA{wtx6CjP9ZrhRHYV!pFvzN~$2c7DLWoQ68Q(&+wzxcx$^$?Vdv zfr_Zb;L4Gj8HyjW3*!p2lP?#KD_?KT&o9hdcfM@jZAZ!&mkJ0h-Z5GF^>WUwqSws3 z_etwA?Sn!o$#NQwr6^bk{o4i7s;B4ei-YY8uy;tOnHcEJS#IrS-oK64Zd!m8r*3rM znDz%44;L11tgM@@%J{4XC9Jl$uU5CM2)&{~A)ouA0F|n>M)_4A`{i5vjueXP0#&OF zdvlEO`OT0yQN=Z*m>?65RZ5N(vv+G(Xn?B}7|6}FBj1e`hc%&)HS>iH@0easHkwU4 zYMrUTdZ8vu#-!b>R+64vg9#;P7yt$KZLX#*PUAeH{4QHEpwbv80 zSKqc#+OaeH7g@#lBkSh=SPb*}tNrev{oRT^yQ~5jy%`Ox=Z7({J4H@r{jcrE_#6ARx`yXprt49fHyl z3L6d5p`ak$-7TXL=@KaiqJ(s-z;1r`d7kGyf5Fb#Is0DwUZ3lFzgP|)9Q|PYzCJ1J z?@)WPTH6Lz#KhU0@I@aNR~@}yKUou|Y`i2^!mb>1VEyUy;%Spl2TM+=#*ZkcHfUEU zs6Pn&DcEIytUPaZdrol9x8W63rZ$uFKNZfJfFl#eu2;CgV(yR z_Tr37cV9d2;(5!(@8t_!)^mg{#rAs=R@F<1qaKaAOTwJXhvZkb*sCzIYXWbBPk`Oi z(95mKt6)|`kM9G5y@xuihoqFi@nQUE#p9sf>$t^hrRw#xu&Y076t1cyWL|%qlCS)0 z|17E+##4}wcn-#@L0pDU@prT@dudc~4gj)N$1sQVq0_otH8Mcj!vOa!bZLX4>g z;xrKBZR7Mx9U4En)(`tz&`Tku7cS{_n~#0b5{qTLP`D{@uo8giPuPyXX1xyWy<7Nx zl08k{Q@`bxbg^mcIXncy0_KdX$$le9)1h+!AQS^7WF^7-qgK=hi~dh2qtoA1CUz3k z9?a4&8jh!Z5(@r2W3QgZ#TX!-oyIwq%$;!YxJZmsD_epusaoR)YXa*331upYIM>HV z1Nx;;a}}Z(jQ5NxjcaU%-W&fmskP4Iw$@xgS384nQKCLEs{;AScRjBe%g6r{%GQTI zm>$`DdVPC`%Vc(p=#L_0Rn1vCE(smjwf`D7);C2r<&mE61a|9`yAYaK0`1`%ZS~h~}%sqaHws zrmoDt#=nP9T-yJHGFCtSzEV7jk{p)EvCTY=X~P#?z^~7a(Bv(Qse=@WFi3i+2(V^w z-^!yBN>GvJrONnXP*jb%tMa5=fBjoOE}H-V5u;k2Z%6VxkWEvS;^znQ;orqMNn`xF zf<*X^fAtGh1aWWD&}1*gE7ioNlpjBpa1n3fZO8lt0q6qlMp&N95Nh%A$djCDQ2rCA z)D*#`<_8R8LkZDZu-j_)DG8MOnZ5>3NwdK?``Y*nEs*qlN=0@e*)UHBQko|ZYievZ z`oJ`2pe+<7VPft=y0`E}eCYYYj30HPsfxTrWm;%#2f$e0SN<)Z6<;Lkm@-wUs` z?$yq-o(Gu1P3yC@0CH6+yD5^%c#QQn*MS9q?T&V-Kuj-nD88v>Y(t#hM9MK$?Jdz( zm7JsrCYEnKQ14BY&t{3RWkAP_iGW15WA4jeLHRkJlJ%BJF}2cT4jg)vGcm?Coj*Qg z8&|qiV9QD^%JV8<^p-{0rP(tzG4_Q<@+QAzoXR4GrS~eoI)B)%DjN&lY-|zkl#P@3 zr9>$(6e0KDZG;BTwykh?d$}!e3q9{Pm;B&*KZ9Q>V?>u+y}0ji$mk9{*?zUyS7gxL z)TI(*^?Zc&s|m6v_0QDNoDw;c^`LB7&!w7T48Px`>i3@Wq3yf1(|Zy?3bEmve0%xL z)8$hTlXsZr)kI+4`pa2V?_D5Zedz(=4_h@B-@bP*KfOAmj$G&46)pPs`gh0(%iWKs zdioDv_a!U*3ID8kFO)TC*(RKS6~7^@d0r0Eq_Sy@{P&vF_2ZB4SWcIPOsm&v66f@?IG)|iWP7#t|@iZvbFG-cn(rVZwbw%IQrc|kBN znl{6uBQ;qOXf|BiT=#~8-=5~DYnPOd`m67Tg;W>iYUKMhbddUYm-A{WVhi3$G2%IF z5vQuPuNo5V#2r{9mcV1UjYypCqSNYFb)8B5RH)sS3DY-qb%nIVLP0LR0xHx(%k#wW z!7V~rX)Wc@Q=WqPF<$+kF>9OCOdPxLctIe)#(Rob%VH-n9#^eAjF>>@xD$Vfxwf7t zHlO_S4nAe9dH;=*PuK?|XDRH+_(!RS0@JTb#fv_F@oQ|##pzQzY3)#33Nn1UMdhMU z6s3#GI^*AwE0g)IG4XuYQ|s|#$P@e^wKg;tW0Z2K0+*(2=vZ7z-juH9dcnr#NSO5wdz=$uQr+oGIncTqN$nQv)0 zFZ}j}mqm%8Jn6ECHg4I~AaQg$D5Hq6Dy2^&u5%%ii2AWm&6t)ogW-Eke3ftF)ySI+LLRE+=^7kf+) zY16Z8I>x_ELUN-aFSZiy$#BbNwujIDpi*0k(<$7lNNg*i_)OEXuFE6@kw}>u#G@WYw zagL*RG-=Tn89zg*Nowx+7kjg!j{Fxxmd^3scIIgeDnfxssz?~)1%(=~sz{2!)+X~| z`%pAk44~}sgXO2|AhaEl7~;jD1ON6r+@I+^-lMBNpn_Kbo)rRQdKi=2fen9B-mt;m zZcie+(=TbkMnP6TK&40r6PRSn({pqnk*@Ej1*b&>-8WmKrbmLRFPE9yzSVjB8Vf8j zusQwswY#I{@yDV@8-yI-?SzV#i&Q=7qka1Uh3o-&8UR3`e1rgt0RqBPl38yeA1=}n z2za0zq`JP%k?%FQvN72iq&tt^-jfE~9@}zx6OYTU?_ct7A1al@A@*&G_er8bF%;4*B@O@p$#r6`=BAtt%UamC%cp}DDr+UHni3C6r>82sF_(tbJ)Wk% zrDO|P$m(<<3Th<$0f-Oh$z?;b$2b&HR6p{#S;WDbz>zVYPMr>Wr&RoL@E2&;Te6vY zGG7n$cZB?^0on02nalOVDz(j)zHbZ}_0+Pgq)S2m3cFTzl6K+XuYqHT!VB}Y&eMw$Hij=y6v+82;70(L*06#Q+ zyLuZG2So-V*aDuFg8-1!WRwwx)n4@y`j+%V8@tu^ix`fnhQ{;am=!+t-manFlexev zjt_w^h%niks(G>{AQk8<%EHumcF0fqu6n30iCxmY0}4E?2LV1|7*I^8p8$-q1YTqO z(>nTXFSQ{tI~={|2W&g-J-b>2w)Y7^&MEXqaC0iUx(hGJhd9zw!KeG~`; zkU&Un^!kXV&_h|`f8$qK=oAHDm^XS+w6}m)sQ}vRAk#zas8q`fCBK2vMYhkhqYMaX z{|2J(mlU*NCuu?#wMQSMJD!#^pG>fyZZ(0zBf-9}kC~~PX{(R1uxq~@%BC#O-drC$ z2a91OWeSXIppSh>LL>@~r%K4=Z|-j!fMGd(qXX4r%*w@4SpaB2d(aJ`n0ArE7O13xv^b8wFL zD{>A`VIo4Icwyc{%H2J1BW1pGCA}YT^NgV?b5z(g4uB5$Dhu?VgH*04A2;kK)^A6m zTn9ke?ZjyE!d*O6odtVM2jT9;YUS+=EY~r^&q%502)v{s5nwUdt$zD`5<50L5?8fA zImMR=YOdg+o63<`!E`q!Vl1LLB4j7d6$5TfCyjC?OAky+zKKnt(nvjyP4i1yfqssG zgbQs%{M7rL2_{U-(8!Y0$h?>2GDdSrp!0g9sP@r>)zSA3iXB-AMapBvMq?$8W2G4h zQpZuD1bEV3W0lQgRo!pK0@az7;2&4(atM=8C}LmlkA$5QM!*S@t3M~?e{S)MZS~WN zMt*6}`SM)^A8vQ;mMf zNB$U%ly+2!wo;E0R|=9FaO2db0cW!krm=NA@j6y<@ru@^QkC?W&?h0)qC4E5_6dxJaT7vYO<$NqB3eR?Yxl?S8tFqZ89i z6vP`PXqHlYGqGqfFzTkW9XVbrg|yj;u@ym0RKtJm^Hsz~n4x1l)g!l7q#-vt0wlUi zub$os>eenrgo@yaxsG1?4G=fQQ$xY-qcP?w5h@(e@8eVZE4m5%YF}@3YwA()!HnXfl8i=eh zir90YS(tUby>W@_YcrojBBEH$r(O|!ya49;C5b4rzUC#lYBC|D-j^@Kbqpi^{NGSQ z^JOVdopvH5rGNx}X6d;m<;RiM=aB_m%LNyU8UBNNybFd;jkBoDtexf(7v{_LaC$=` zBx7-Q2Nyn;e9L=%|EX%$6e|tXD@7_6nJP@7m|D~^(Ajsn{K7m*$gB#0LLi`$t`X#1 z-(J36NWUEqm0!_Jd~X^U^*Rf;|23}parA6gW)?GVZInfaCy~|;J|Z?;a&)GsX!3WC z`J3S7!5lL((5hC&5?Wq(LIl?kgKwg4Z3w|t5vgdaG1r$^@+pb$QpS7i3X&{0z)rMG zM($gwR^q~T;*|1nn&9mRIMdGfFS%M z04D&tzD50XumV7xi-J=$X?t5`Z?1pJTrHHEw`oU7>VYD=rA80dt#jjpM8ZFc-~{v9 zp5f{Y_C+ZH094Qz?{a+Hw`+e?7MFkOSEkI`L&Eu7BV5*OK1nPFW)fKwM17>db>>BY zXwZ9RG50)?Qa&Ci3*_PTeJazI@aPDv9-i5zCy{P0>3KoAhF zvF@NyiV+khBD%)KBLVQDtyaVwea>wwFhI{Ne7BV7pi#UV_f6wPg#_wfa!FQ#G(_J> z@F+x3YX{b%WSg#+%jNk|78ph9@+fmXCl?#3`oO3X=xTuT8-Y(wR<#H%?)b_QDInVB z0QcAPx8K;Ji2#Rj94RrrsxGb|V#Cp@MPpaPd?)v}>$~!%*urwl-?+$sEenmC+at`s z%3bjfnPLT9@x$*&l|pM3X}|8|-NfD!jon5OLjmHhASUGZgpY2@ALEVc@dWPyB6PUB z6mBYu+mnc2p?FT2rCTVp^^sk;WEKv%e0Qg23)whETS-@fOBIQ9BZcZ7H-9BWh_y&rb{5RjR+_{_U9$sjiJBQnx}_xFH~$57}_ z0l~EWF)gKQL^qdv`6oO5fcU~p&!V61fG3v0f=3u7BlU60i7XSrZgZv0QW0Q8Y?hZeC0nP^_DP>TSW*`;o z!=kqqOOrW!G^=tNk--E}vh5LiSux5x&u4`Xj#)hOQzjJgknh$pznq`HIMlbt1F=`g z*;%^ z5?9yj7+=wPg=U26k@u#8w-6Z-h13wIzOwy;ypIy*rZ6(;n;jg*yH@K6Dzt?FH<7ImbXihmpFs;qs&+T`@7P zQjuHZzf-@~?bYLV|MCnmyAS;aapbw6Fh-FwM-ph?pzR|QQ=NR*&a%0f@((fv$3XR^ z=vU~d^zQ-1Pipt-qg8g|R4L>KK3-MS{cDnZj)DS6@8+Yv2fx|&&6nyPwCo-hAQDW8 zF7xHe3?@cK_a8b?ngCJ2Gc z>v9wKmrOtp*UgcW<@aKf~&*@R#9)KY9AKrsie6lnkfQVMiW9Qfoet$X>`oBV1 zH0hZ5=*|g;I)G6&TF@F!~Ug|-xX{xA=Ps5%yTl!fuUC8&exxI-;FOexkvzYFj z*C3kp?zQ^fIp2J_L772~`vt#AvDOFv!NY_W_yO3@^TJI$$#3J_atHE$?&uJ0#813=ENJ>=NxZBIqg_^7lJ(*5z;GDebcCo_=^}9tNUidLK0W zr7%71b8f*ndU4f0}a{fKZX9Exx>3*YHu9A6))tA$q|K1V`DKe4U_FV_HDLn*=N8b;(Jsl!eAFeCADLtai= zd)kvgk&GDZlN0`+M_+`xZhX?L_==lDWSPzymL#8Ka8%fD{<-@;rwQFNdI?ittgp?-xqa6N)KW zl8Mwr`GrVt{ZAtQZl7RCOnC6+OP20Qwy0?zN_-=|lPNZ%QM3||*)%3fd_^6hzc_JV zRyd;;Hfc$(1(};-AzKr1z&nmg`nF&+H0e9dZyvD-OEfy0re4?M2%xM@Xn@nMG#66f z?`NG3P}JlYnuBJh4ccJlI}z#>sTjjZmDl)p^4A+LO>)J#M##WneL}mK zGg2&{P(t~S>ADaFYmisFtHwOd1C)3(5I-e5*NB3S8XO?Z=`$T8#4tl(xdkU9+dxZp z*Aq8LIFenNp`&D+BE!6%vgN1`v6kZlOvdfmrs!0zOt?SM&(=r3tRRzj_E!Mxpr0AI z<^NVylVOX0F2kj#swl1mjFBoJHO$hWI8#$z+I=L`Vi-ql#762?9!^BAG{gg_SBfEk zF%#{gWmry-L`WP)2pCG+d4i%6R%SXjAmA*gglB)NPY%6tctiA0#E?(uFim?70@4pYeBklFMc?HO+J9rbE3`oRNV zb)d&4m|rzLwa_mAF&yXq$A$r#!PQn(E2v!O!#Syuc>J}&-NNmJEi(D%OAv1yzFqj*&t0K)?~ALgBK(017}S5r6(6tT_E8 zT&$%+f@&5NiNqx{aw_H_+I_-hLA`;&htli88K3JZKehMgGUGl4X?yG69;D_&> z))MFsn_}|72*q3aXC^{2`h|Lz9HmN$?q)wyM3*xeWXlupPkw_#64(jg>O->6hbdk= zv$4hk`Z-$L)J7k)wO^!pJXVt&{6eN)WuOlewV^`hjmD~e;SvattyoQe#UuBFZ_0gW z_|xSC5#aysGD#`t0kR?_5A70rNWZpU_SB`O{2Q26HEK4U5O%hpO3&Vp1iHF{9!BCJ zZsIa}=~F491S8p|c4&KPK8d*UlVmm-Omr|`zLlTd7L=X76k7%zHi8R-=b&)I}N-Lrcr%M+2F5Pi2Wx362jw1tr8J56i37!=A-ylmUr9vsx!CHrFdM9Lm8r~ zD5!*tm&1^Hri23|Lyxpvx_E}$0M0ce&ZgGy{z9`2i_Z%jq1B5mZSuKZXz^ zxtb5fm}PDvAc6(pLWIws^}VQd!&hraJ8%YH3{8ODQA5F{{01tL?K36JDr;{0mV<%-M z&1IT9T0R4a5KY{pXiNM-72e}b9-K`_i61ds4zcno)e{V=g7zFT=7MhrIn#bfH7ax2 z|45N@Xc&T7byG@oVo79Sk%aLG^3F~9e*5n|D@`Tr3})}8eiaG2J4n(ngO&^Fe?hHQ z_2tGmU~jXzPMMWtm<)LPc8ill8&WY3M^t>bbE%JOLl zwZrfF1X@Qs@UVlyiEo+(Jyr&+FBE~q` zggY5E7gMBROByf0_f+n~r%DckEA}>E#GRAd-ysK%dx1%e!f)6*< zDfodlld5xMf>oOPCii%1iD#&)W3)NnATIHEsk;5I=o79h!m>qUn>agIi@7qGiB1Q+ zZItBn(q7ry!0eg9N7_MLb`clfMQ*>+JU`7XO(ygQ>UA}_zW8iscXnroLg!HaU+%MC zyib=12&kp=IfMUh2U@HJGay2^e`+d|h?3-~Rg*Cy(q13(I0(DiUT$~a@I;d$B?qIH zsdyb(Ty;&HM8a9rvrx0=9I6NakZUO_)P;16cbjv^&ub@&P|3;<6+6j=h~!bXclG-i zNve#cO$bzWxwQfwm!&lFB;rgM%iNbkzTVtM;9l&+%J3+w?ivVlG(~|4mRP8qz~2@K z(iJMioS8;Scph~^t;%uU{&lql@aY!rO1@PFWLdFW44P7>I7n86FIT{)`KnS}(Z&F| zn*oKvikv;%g1d@*14ng&5z(bwH7X?4@yO&ZPyRB8_j38xS|Ls#-0B)ow|Cs#~^ly z-|JbM%wF4`Lk&%pnqFl|F!*($O-l5$=cQF@Mgj<{D#QCR<2(*(tf~^j+h?-V6J9lO z!mU0!8cD{9CUa?4*w3Qhs}~wl+=uCi?nejjzyG-NE}jdZhfFiyRtrSGS$;OGvpu|6 z73l8P-vYI&#{b;NJ;_p18UMSp&;zbKZtffjkV~Wz=Cryz`o=OK>m=QaXp{K7%2DPL)x)|5LISw#By*m#Zeo-m+13P$_WW zEUcWMM0buPSI1Ex>63|np2ZBa@*4P+UyCxRf#;9Z1g64{`^6INEmplIGc39)yiyaMAmIe2p8q}4OBF}H(lIWuI zzu6;&YBVliT=@C)VdKYiiQGL~*GCiRlAS?p|(aMkDbSSx<0a;{ihS*V(N_fy>{o=>Si#yOI z4)T(yZh6s@Ss2U;&YQObm-4&i+aL1Y9im&OIHU$a$4F}JaG7?moprCQ4m90e1a_yr=>C`}Gw3MpLEm5luj;6KPte|YXBq3<4@Iw&tiTgE28XZPYgNeWf#xY^ znDP%fovl#-fHPdyLqiZ!%Po7zMBD^w-fuJ+6qVWK`@Sni?*4YSpARiI_Y-B6Ata=G zq?z!}O8N29#|U{$cm^9wO!)daDv6BWm8J2JP&T3CLFW$LG=;WX1oN^Km)S156w zRX_sFDrdmc%6E_K_cwPB**14Lq;D75s6v1a)ds$4IFogN%*Ygc%Itr#3YWp)+>2xF z#!$&Y6>&Nd=!#b*-Vy5xBQ83U3kg=sWLEy*_rAY*lkA-9y=a{#=r+->XdQQC(`C@4 z7M6APk-cds%SZWZt+wprr!QjqqIGdcho*M?pdr5v9=j?H6vHU`cER~-%E+hZwZ^O$ z5F3dDql@3)nhoiZyn{nh)AdI01UVSDM3NsjF(X^5#nU9u`J?>}x_oUNvdtaT3_&_X z^+SqGQ`tD$RbYrx(hGST5;-v$eGM3&TSk$Da021T72&9N?7> zFP&32N7TfB*HAW_<()e{YqiH;233b!ZE3qsNe1LYE3i4MG3p9O-Tx-LVAHtqG{s9yCe z9|x77mEtH^HFqZR&ABsg8;Ze5a^j=pa?(|Z%djiRfQEBV5e;){d>L|d85nVuYi{@` zfe*h`GGa=C$1o6bc1buap=1ttG^zsPXn$__BsyIztch`j9bVkBgNphQ>C&of+3um+ z78QlE(t~e?w_Bu-LO_tg5>iy~X=G`Mt**4e zN{3XscycPtYJWhrEGUEcJgH04l`5K>>LolDVCKp5E-a|%-;)nlQE7~y0aW2ubp66O z!TE+4`5}K?>JLPV+f_t}!bA>=en@)^1kNV~mRl^5RKu+@BGjJ+hrbCdV{CEJLmqfO zfIm_-V!x`fY^}uFCq2#ts)t*};?!U#-Zym~;mPXJ)i8Oa*|+=UlK(T4m8n$?9x3d& z1_Na?YAFR}o05YPx~_9yM3cV4p8me!{>jkM`sPVxQDf7;thNYpPR=gNbXiZLzuk|U zT&SWS#3U8g`D$ZjyWzn-jAb272{;J2Rda;ENl3@{kY%CnRal4)vXgW_+D;W1$s^Zq zE8DppWQ0syN=f{d|J1K3aRr?S^Fj$`4ajMODg+1Dwn*s}2a8$NakuQPVu7xPuWIlM zhZ&zZGoh2G3gG853k{u@YFFCxjoO+srb|x0L`upquEEZ?GH?u zkzcx!Ux~aO>K&&W#pR*6C6<(HFqB8Xi1y-zr)#LT7`nEyzGfYf4SFPu=SIP|af2U~ zqMx8gC^{&JI3Q|Cfpuf`UW+c^?}S@f@vS{BSo?4@_ux){y3PHuJiI+*hgc!*p+atW zs*Hp(eXc%3jXvW<@MFJl7#%gsF69-@xPj;bQ@B^bo5M|S z=O4`_^lrPS4FZi)>MJ$qILH3~LYd%FzBVX|oUs2IA7rl*D>BVY*-lK=M?UQ?4b}rP zR0^0`m{&pTzsSjfPQKBr6XYrpvU+LWAX5KVD7$nlIQrh}OcTy++?nBKSf*Q`nkhq# z-HQp6t+2>Y7ky?B&E6$^%h2iq(7qL+WRj&oWk?!AQfk^wp6hk`hpi8-7`~XU@%eEx z_vD&Y@ih^^&nx;_KN`A2LhwqYZW1kY3Z|rb=?dX=C#tbuleOR{u~IoRXX| z9S`a4-xvE)q@FzcE5RDQ_FVIuG;|n^58~_|N0X$`pu=CEqaM{Tx56oZs}z>-<6s7w ztkv-u#GXJgI6-1SuT;}=NR>G#HxcKxf6(g)JQ?cStD(>^EEWj%lKfg~dDyW;HuxK0 z`?p|Avfj%zg7jg|o5^0V?ZC7IDJy@ya8i3n^m}G2UP@8OK0Q|~n?cYvF2EuUTdYiL zK*9Uw6$NmU@>Q#rD;nVNPbs%>D;qeQHlw3yl zq4^Geq)3RGay%^H`HYiFe0yG`l>g{`P+6{3J;e@{B=(zAzI1cP$a@hMcOQ*znrmf6 z0}4i?85MdbBfZ(_$cgb8?#w+Lr@!9@@*A|xiW0eTuEoag_=l?IJ9U_OXH`KZ$qV%c zDP`p^{Q?&jExn@-W@b#*D8~O9_{S%QBE1oF(PGddQeGm!rKvuML{iW#WWqn+y2f~n z_?C(7(aMWH(sz6wCzS!?E&@#cEf3;%M-n3FW)bm{#R!PDUqJ$mE%<5y>(1^?&Q6Pn zZAO%pTiY<1ZA8)2s3SVYg_^#T@Q}Sp3l%5ypOY$d1(A}g*R)Hxb+JnexMMx9H=^-3 z(e$?uobQD)Z)@r5SdGWo{JE$`V0LH*bO-fhSr62avfwZ2c7H@6TOiu=c_7(su|~$P zss@O!3_Efv~wq%QH|Q z=*OmVMcUA_0Z4Yr3B|O5h129b>~wH?NnDh+hTUhK*a0Aa6oAA>PYHr~%cqQ#mR`-K zOm2q*#%ht&U^7yDCvYHD2{SBfgSuhoAus>WXdd{ck)}Gu<8uc(Gj;+TndoQ|0?ve> zKby$zXVITS+ZO}%Ulntj$w|8?=s`TRur^=Ud&%bBD zKfg15pOP-)SV$^QSZj3Y0(v<;Mc3`G>2&9vC2!8f6tX+yYB2~zk5VatF_DthK+nEx zZt<|7zESVfYz=qk*M}m>VN&+l2jDH~+l%HIjol9v6$T=_A}Ijz4UdsZ9%d}zwAXA? z-09#NQJ)0B$gwY%bb?(@z(5C;UTkES858H?2yEWAJ9juS|4p3!2W3o#`p?D^Zbf53_KWjj%|`_ixyd z@T`6;jL8aUn9si~7Rg0jRz%zim`XaIUV6zU`qHqGUr^`0|e2s-b(>wnIO~XF~l1}gnb-1SyQ5E0JN0Xc$&&n6Z zvfp$cT(k^H2Q_`!8kFq~M4LD6NV7iYpWRDrQo@O@W zIB|{iz0by^u{JX~iza7}J4v2p&*V5u)R~W=&?hygUmT?I$v^TU)gT_>>Ev{DeUC4j z!k^u2E8<&BlkOynuA-wEv$Ce60=$cud+gQK-Vafgp63e*{a}1?W$FF#tV|kz##I}} z_Ve|=?+1fkZ7;)57d^GU*37HzyL8z3785=>>1i@}#@`8Wg1^z*m;{B@v`=*=43)%u z-^{lc7AGX#`DGh$861JMduG5oX;Mi?9u;u*jv6Z?cx?*e8ue#H!aSevE;F> z*9NA!ATGd@Se9k{Mmf^MPp33jp`An)snj=c;?HfeXER~bXYbw|emcKZVyD>TrSOK7 zG4B3zD+@f75G4p!V1?a_DZ!k-avt51)E~MQ-LEy+aUEC|5k;#m1;|E%pm}e1v3LZ)YKV-eQrJ_8#I=$Em!1*DdP0PqH`{eD(Ym0H$xnaDdG4kl zsvC^&pO@>@gQF;bgq*nMpK%^huq&g5meGXbbr5L2b@;D45sK23>7Ls9vW%x}%63dX zXmE@O$w?I;59e=M{XZgh;CqDsbp8ht*um2C!a(x#%458a(R4g0)mQ=kun57>F*yo+ z`HB3HXcPQPC3t5F@^S2Vi-MG}0q?h0wVWH(x*f5zBNx#mIneuIYCOrx2tl95j#&Qo zvL0Ko1D#AAj;GfNyEj&K3Ua)~dWXJ|YM{wfreM>@(B%`#MUlQo+fZ!^hL%&h9aARi zpChM!dwA1>z_i%plPkP?Ukhq}&a+C0Tnx5vKO^=19d9T4MQE%AJHc{luRQ+Aec6(7XT=T1Fn2dv@pYR zmdb{!&U#YG%4J|GN6FqRdh!5CC|5!#n$I(TNDC36+7W zu#53l7zjtFasC?s;iVChJm8J=25QZI?SEjrH_C&m=bvd5sGTLc1p%`l!Np}95rtrG z3PH6rAuO|j;DA2;T;rpvLU!F#dX1vL<@!VzM9j{Nub{z=uYSZOzFG@SS}z|95CQN{UCcEzv_lG&dZ?aG&Fhv?X*p2ogc<70H48MS z+jJTdzs6B9KG*$oCc}{lEqW+6m8usptH(youbjU}>PNy}AC_`utSt^a|at_8E9BG-alPmKBp zee2syFtC*`BpmP@W0p?+8&U{PDqxL88n9j3TwK_dwb%-@@;?e-L-jLvI9fJPv(MMk z>b2VGzID`Ug^W`G9&E76u;ap%826NzV0K`Ux_H#l`rva3?sctdSmOxSRcO6W|xFHKgyi;jPcg=^7_2Z% zXrTm=LNaS_;78|EPxi4XV3>^T2=@Txf8a_CSapDW zR8m-KdM4CHBT8#W4P&U#=N>R-qoVPD-s-9U)vxAjHYW|6-o`@!+Mf_cF|P!XK`^sy z0Qmt_^-2MTY&3X<#CHX%l0}adiXa60AivGPIk6xY3O2;0P|9f#B|Fg{Puq%jNaDcY zhIiJeLbA#N(QZ?S5rB!)4ib-KytHF&>{AB-Xw~f?kr-BNH~?U8&+T3aNzztKpbZ1+ zhso2hfzz}IP62+4kV;N6%4^NKHa~JHdupj4V)v7zO$#WDQ@x*455^_g9)Y_V0S}DC z4d*@;Ovji)D$TT|0cK(nh zfXQ_a$vMJas=ywEJ_*ESS2zz$Hf+o$+F;xVGVCco2nkgAN6Yf_B)aIU=a7`KOSb7m zpg6QxR@G5ehf~F*SjEN>Jjq5KjU@Y3;QfMA4IAJH0F@@I(C8bEoVa{2-Sv(oRAWc|2m7EKt@>1Vm4XrtwcD!5rx- zl0+MWqa0kU(OLZTZ?V2iiLMNI3j#Li1XmvJ(OBeoW*2Bt!;MV}Jw-EZFsyW%5E&rD zj_K6({wzxkiFm$4_x(SO&WhZ>6$LW)vx~}#&dLwVv@GcIM;^1y76W26Ra^&EeVwyX z9@U?Nhb2Ar{DaF9o6Eu&0O8A#C!C+LOM(;Y2-3Zg%8TH-Kf!gW!0|nqdfbqD!mj%J zAOhve=T(o)mf`HL%RhLR3q>u82n$2sELY2V49G!1!Vs|Bza}NwW|fd;jjraWD@~Tm z%>sZX)`Tkau0E@OE%bt|PK?uoovlI%twMq|6&DTC-g)r8yq`fu-%V0SuG>>Xa@;!C z*_YdTO{{m(ET<5H>JHr4e|}w39WKEg1KC}5jApqXYEJ0ciGWOpz|5Js0>;kvuZ&$U z%(}7}y9fTYG0T4Pv@reluXO05C$lTnH~3S`bo|=$UdnG>f4WLZb7B@4(4g*5bN5AQ zS&Nmfw{47{Si3vuUqvzBbRGRO#>(FKF39%7yVL3ZB}vK+Y-^)EGtpn9`Ycz65@ib; zuN09FhTdom&1hkXR{NW}dS9=WXy%mYtPZ~<8Bv)uQd;e~&-#+DehTsJj+5I>urklQ z84By}uj}r*4Y5;2u%GXL>605DdNuyJdwk+%d`50!;nl>q?uoUVi4D2QpRXo&yC)BB zCQqy;xp3Uxh>VKT^q+j_Z;|^F!Zd2G%5E<@L;ZS&zGsH{c7{!Umh1H_U(c-2?X0N$ zoW$!n>7F_H+c_ocncEvvMY+#aHwC)P3%I!hz+nIa0Y0^wXk%Y=lb>|yS@h1Gcp?8a zXl?vu&sUW7c$oas%quV=KN)LL)KODeI{m9tdAv@EJ87SZ;!?{Dyz~ zmii6Eyo_D__Cel1k94Jpc}*i?r6hc9#d)YO; zJBfEYws+g9p}UDTyV-ZUaV$Fpp?fatyLop+cS>lz(BH}6-|*YteG2*#Rg;mM~%C8?v6^}|1*hqre}6$;0=tb2sL$Juws z?`-gDp#f`mC+~DHY~kPe(lK>wr;ozyMZ;FOSWo49+ulW-O8cFa!Ooxdp25GhP(dDa z7qGM!PJ%{T^wC`FLDW(A>lU*kkbnq=JG#NDhk&$084gj5&NC7wy%)BMmoB}R zFIWLSVOJq}kUJ#9J{$92diRpI?wNTP)~uJfuuHe^m-zO7gT7zk!v2S~yMBx6?fXW* zW`+r3U2eQS=EEE&!r&X!J-(z%S}sm3m_x=C&87wf)MBMN11s--45CY3SLgpSn+6)@A6#g*Kyv~;&brP4Lv~$LPH@LpmZ*&p$aShlBuqBUJFqV z+Z~5KfO^{@)hnje^083PQgj%l+V9cuE3Z`&8K{us!w~4L2E499f3I zTp_d>;i(A+01zhuRoEu*S}u2sJI$1S z6ED!{K5eVYL8;ocnCQ-#ITNK8+D_K+RNMJm3bRNZiN6Ll?(%&P6f54;q^O>C<#X1uCM33vlc7!zstQT z{A3ZkmquAOuB)2irn{eax)A%QCpra zB=~4l=%E$9iNY~ygaPV3INHlei1k}|_G8FzF=Xd{ugp_MZ@7E_okO=2VauLe^n;j` z8kI#K*ANNd-w~slKECHYb4q|J`7cMo%Vbs))UV2}r(ZitoC7MV4Q-4ViX}&mu?F?a zxEBk*SD`nR0@i^$08;3l%~*^y=Ln_B-k;^GXZx|gDBBq4yheS!tt1^l({^9?{_KTr zDm`2IlIN*-I`huli2A!!2Wrz{@xt%obTRSy<=GGAJ%6aQ33p#50F0u#)!D_Ul>6 zj#IJ?+4eQ(_q7tlV!Y!VM2eU`bR?*XX;9DlYg3&rH%4k>*vV&9srMN>M5>8xK&3Es zQ%=6W#oqBAK7A~!eR$cc4ysqdDr8F;#lE93AQ@N*gqfqRH&Q248uI|eIBq;(13EH7 z$MKo#T-wk8SyDVaR$jgGmz^ltwsECX9J7CYNg~mr3NoGf9LY)pRL8B0JS4?%<`>aY zE<36M0X=e8R#;9kF#4lnoJ$usTg`9PJZ8SD3ZGQ2>=G*qEAS;TmOR{rtay4SV@f|H zK(kQ_zpBxZ=hss!gWOtG_?#5Oppl|ng6_SymQQIw=Rj#Ws>;-|922^wLT!pyrFUqj zw3Hz5*bi@$pb*qK=X59eq*gBK9L&am{`*3PAs1CU+jtQ=Tl%m0Lx|y|7|u~!cBN+{ z+O8O*2r#CAGNM#N(9Jk*pBiz>coP+gkMTpCyq2AJH4Jt$%1`$x<(K}hUgeX0pA|&0 zy|wZ{fo%MEdb31T+ST~>cf9ZwPPQ^HtQ8!AsU`Yikaa4yeGq~Z-$8T{QbaGs!np_S z#Gf@1)9KU(@~@UyUbm@HwxC7jjkTnF$ijHmmZ~(Gizu}4H*bi%;1~)0D8tR)-;XQzyrw^|qv_L&o z!}Tmzx$3UJ@`B4hIDDfj-pRhEP4YbVl1KDdEmrTunU5~d&&74YkQ z=yMlUL)Pg?24CtKxm%%3A&p}=8lMtjWE(5)caEZ$0J=_mjf{ZDM*bs|kq7kseTGq* z4kt4|h=vmcLUWA{Nr8MB!|C4|!sDFrCPb-_kH-wI zX9PntF;b?78~P8QeaRm7$=*I6VHspcRUBh`vNfm1f(RQqTUAI~3H`|`mC0+Fe!!u#V2?~EuVd=$R z(%LAliXS&}A~8_uJ4UnO*xeI+z#Wzrw) z#JR^~&uqBfv#P`>Qi1*Is~5CF_qN{0BrOU};j8Dz+%5mn<{rbSp<%_xFISFg5bV>o z?2#R`_v_@)ltx%Gf(*%(plpO+TsxvhM)bLZ!IPH*ZC_Vq)cOdV?uW&~!Q1+I+MI3P zR1Y`GI*PK0PXt!zf}UcQ@vHT-K)SE|y&N(0TWY5)@f#V0%?6c;Dx3 z)BKNwU(GwgKZ1TVEfOeyw~>b&gkNi3rb_(XB^+`X_o#W5gX&M8UdU1E+vfFaiGKzk zh8$=AXx>z&Ivb4*IVryOY1=UIY=Wg_@Xe!7JJwWxn-xRvQ+Q*8>=OUZ?S%aD%~JgF zoa%gue327o)OE8|93E*l!rs^y_G-;5J}{`Lhw=|(lHpxW-4`s=Pa=j~g+c~QaIJ*4 zMJm2i#VwaVzu5H);;sh4*v{M8@AnBS$sLBt;nmemr?t3)4hV3cHPn?+(kYvJoGHNs z;JNAn#aKSMxe9bnj11}xUq{1b(eMvbAuN4Zwo*SDF{*qR@CxIavZMv&BxQa_RnhUW7IPzsAlu!*-Sc+6o;n6D%GC)K? zIV0|vp-k(Q%ov?M|AhYl03rh8cMz#C>h6leMVI2nCP1g7kCEb}6K$xZ{7?}_H}7#& ztXJs0-@eNmQ5XcU4k*WJ$GmchIp-$b!RNu{ji8ZUGO`$|>?Meg7$rdr3>ZN#Hz5IN z45clcxMUDoVkg~-PCttBP^F4of@lJW3BQ;TMEqFBHHa5t217-B__<9L=h}k84ya0@ z!7b}?k0;3X52&X7XmUzrnV-Z#ZQ+P9%4RftTs!fnOXBZw#Hv@~-@e2P0nKnP=+Ysj z)mkFd6%YS&EzgMZv>F+&fB2-W(XaU5@ruv6ggysCYb&84o6uoGXjUiG z-5}KRkB*KK&5GgSVWL?vFfj1>^XI<4zV7bs&d$#N$Q3OuEzQl%M7g4_uI@i_MNLf& zp<3a;@QQLdLd6wADcOJIinCJTrpk08TTxY2RZ&s#-{lHIp4YpgqQb&LB3?n%DhR15 zge2wdq}zn&Aq0Pw)j;2zoSf|J?5wP;^z`)9)Knr~k&uuO9Uc82ydpF-^na2o{QUfg zLdBCOPrSXo|1DGyTwMr``~=gx1T!Xrz7#=SB+bdr&CSi(*_mio*xTFN{2$E z6ciNXSq*%woUQX({hXs$ zS2f?{fBb!ZpziHrD+WT&u3vw!c#WM#OJz$Xr>GXst(U9c@NRto;e7tZ4zm%){^m+Qlhikh`p^qY(w3Tf6NL7_EipKKgFn6Ms|?w9OKR(-Zv2dMT+r#$zwUMy|4#O6rSwSDm(dx-2@pE%;q{S~WCnTu$n4dne#;Zq3 zY6~i`L^LZHGoKyYEwKsR6`i)Z`B#)qN7kIlWjTV;snpiDNBs9v)M)@?A&%x|h7oA- z&b#Fpk&jy|7zBMPhU6c!B3@>rbTvWdu?h^X025rp%kmi+g&a-3SPORGjLu6ol=y>> zMnoJYQeAT@TTi!Cqc2i{G^4sQ9MWAkGKppdUzV1ccUP8IkDznbH6LDlisSMOPimm9 zY1hl&U;l-&2`lc|UQF)PYlKJ0+dswg`5*-CRd5>C~sX4tG)6IEc^zCP{19dFei z%v^|Fvz34#K$~H2VT@Q1}H4)Dyn%WA_u50o#Tu~8r_1?Xln-#~ySA#R(^*dcO zOALyqWRwihaeLH^Gt$0U9#YT}{W-z-$MWdjgL6qRFqhkG%rpKkse&|ET;I7h)mQIf z?U2;BM^vfaSfkq>zvlfp96o#&-y;-8t5DXD-u=pk6~!a&b4y)UbL!nQnH5p3N?uEm z-@iWgOg_hUKEQ83U?Om2txh%kiGz%KEXRb*hF&c@?Yclad((Q-eWe@N?B`W~_bnsY zzX-bjERY7mo9$sluEGSwvGBe~r=HqUZCGI>+XuzH*>zi&*A{}8W1E<$rM$|l(UJZW zQhD__S(9T=ZtllGWy28bu_xg|^o$(1?EAfAU1 zp^E%))hr@ZA=4S|P}`yGWQ3n!Dvm_kS+f=utK$xgRFo(R*?(zgCy~bE^oV9f=2lm$ zsxkIhCX?sQzo7~TB2>ZmZ>S=5%})MQ46mP04Uo1$6)bFVbhvo;H%(c)D(^lgzJJI4 zwyTc@A%-`5TmY4-G z5NIt^5Ah~7b6-%_8 z8O#%8h)@NtM8SI+m68j8<&3O!;aux2kACIjQ1*s()4#LkppYXMjnEPd)vF;`Al?@Z zReCZcPrc3e6?xMw^zexQJuOcWhXH=iL6BwY*+P0nQ+$=r{9TKdi1j)<(yG53vK61* z9B4VDF^@kDSdPoxvmec=diHhp{#%}ye(ZhZ#%ojNd|LOTG!Tp+*5qWK1cSuLy-4CpW^%q$(I+kDB1yjoBR52AJ^4h zzPkTRd~oHRn;9SLX-pIYh24|AIxZd=*gd4gZ1luwvk=THHY$7hI~eJhpeP>yRxU;5 zM4gdo=`ddLXtks=qt9$(J=UJaK5I~>OWM;sT#yE1a}q`i->%Vk)7&8J{D&~4GAE&j zpIOfgn(48BeU$pBVG}1c%_yV&B=5_NHF|Y;$jdtp~pB7QEW%46oj3amk)%*YYkZ-!mAugQ`2JuM zImrfEuvo|%T;+WfFcg@pQh4LjccyTf5px9k*U=nj;uLgqS>ro&PhSS? z?L0O_PP2-m!B%3oSHwrLs8lpm6ai4U;lu8-_EBHfK(MO5xxUSzMlvr&R1RbApRX{E$aL!k;q8U+G2jL}dQf%u)evK}EkOz=#mZv8C8#JINSO$eDXDw3y=hUIOiwZ?63({koSG~C*OIrpbO$&MK zPceM8uOa4hlCNZk+%%7~#FwJ3e9TXL2n!mQt_xV}R1B!Ur^HDwpjmlkQ|rH#O}R8Y8Ub`DXbv^XEeXVuLPQ ziws-RM~9ML^t_+%hBO;{zqy@zc7l#XYstx&`}Prii;nny!b3$6Xt;I$w>MSe(O1JW z45=vJLl5DaB95#?EhjYoU2heC75mav)x}9=8hnt zb~o|%z_(9ASR$}WudyUGzS3=&?iX0vbh{|}XDI*B4Nk0}Dpt%EdvF~5iGh|@jKbL$ zKqJCnsXDgy1GMsyZly@n>hB1`ofgTkx& z85ukxvnaB$E7DU2mx7JpD2NbkkFZ&fVqgq~5SATU#exjAG0$b(!u_K^*-Aqt>2ZC; zcF^FsX1ls)L`%bU^SE>QwC;avwLF1WB; z5F9@*uF5R#fvr$!p-}C+IE5pjnvS^9Qtl6rh54?>+}y%x;o|MLJl-JUNH`-_RU>+2 z5)>sR=6Lv?Bqx0L=kqw?+xeaF!;F6t7h9;ENN;O-(FP-Rj-1YjAL@=-W5i$aMoa)y z2TK$NykdpbM2VYB)JSB*Uvx|+>G}${idqt*AZS@4vGKPp+cq`cj3hHX=KOc!Dj!}z zmfBGarnm%2#ZYP4+*}4=rb`rqKoW>>J4%izL|)KZ*cNcwAochaJ7s3Vv*pE?k*r&W z+BHIOVW@omrA(N&-KUntochNvOh<73b~ZkUxbSyH;)3+d(~(JlpBI(Zs3-UkiE>0y zx3Q_J+@vsi;T!P6Kl8=2h8ICIFMQ2GE=Hgb*^F@Wj3CmCP}hu@hK%6ojJQ7;c=Hzt zOqr?X87bzO5&f>YUXYl8%#1&o&$ct;bRb#{kvgvFdYS(a6Z>K?00aM}f*Q3Uh1)8* z8zWrsFB=K8FhNsj5UcS?LNi?i|NVE0>UKIYx%_p)I(V0ZHB9+Ki{K+^I z%)|GQ#LndXWy;6uWEKm?<=u>1GEXPU67Hmcr)!#Qe+pep8b`FRkSYM*B&C9--*-(# zSlE&^=IdsXmmH)TlLE>rX*3q8u^DNW+l5qz&Vd5yw%Y|8P&`jeR$3cW_zvkg3TAqO zw6=i`jZ(-679~F|;_ffj2q<7`cWqT6x!fvT5@27cFRC&lTks;H=;Uf|@VjDEZ&hxI zk`-Medqq<6nm);XlF9Mmna5}C{M$;w%3e7ST=A7_=d*OXN@=D!sxFO++uNB@TL5R~-`<`wg%%Pozw zF^v0Lxy4y|t!{a{Zsp7=_3U+uFx~q+ve9Q_Ii0_AMwu()Hrw(ohUx_i zt^=XMBa7L1@KZvU>Jf0)h~TTqr2EBrTf`g6Fo;5$>f znqi9?enL~K;A{Zg$O8}GUj#d5QF@QqRc{rAy{a`66Ky3`E4878I%^f=}f`_`zjJ3T@A7%^wfg{TALnDo-f{1Vgo)l2|1hz$N z6KRWl%A_TLE}wJ?{|_7yfd{z$1xF0nX!nP=+$wKb>ub46-g-D&xdE@~+N8D@c+YUN zgJ0jGjtEC!iope>*X~jKsUXSK+k_90c04HUf5s%JzP4$C$Dl+DnlMTcoq~)PL)jlt zy_7+DXEJu%*0K*at-HP5XzaF#t7b@w@>p^ecJB}!dHv`W{oO7jOVmd~1HEZb_s+}i2l^lG4s^5J zrzQvnXvCt*RT{uaq!J3$kBMr8*yn%L2pb;OQHuJu8xdZV{HwsR7aR~H9YrhO&1{Dl zE9~fWv+ed(Av!Fg>$&xN7BvS==xtvi?yJl8WCo$k@KgzH5PvZ$e{^LEhmP#^2L z^aKs^MWY;5kf%1tk#g#y9U0!^msMN+mz*$jf61Eh*J(2q+F1+M|ZuwvA%Hjk3Wg4eSjcLsM;`$yLNq z!GG(pdLx2+<#@|}E7tzh!P;N`mX~Cs(tDU&!8L}rCQZn{n6OPzQzuKkm~?2EbZi*M zzpDR1-tZ@mT7~p}zwVd5@*Dzu%jQtSpHgnl2mqdhHVm zul=gPV@lQOTgj)H?4hZQ`LB?Ig6c_7o#Hf!-fTqRv<-67&SNeHNsZal6|o#FuAJ<+ zXzxNcH-4J>Xf?&a`D%`Fw$19>7$Ls9G-n#eHrc1RfLwmJ-+lN-ewpRIw9`*j(lp-}tW1?2biq!pgsg-LQ zy=#BjRwee=#VD!IpOs%{Uy=1+PpMoF?^~a~Sh-8Nj^0O^WGy*fPQJ-nb9)fs&c5a} z{4JP$kUA+q`f}YUVWqWTC4jL1FfgHCWq8YTVV#OPs7G(>`Bi1v2PN{kTd2A%pNlR0 zgYA%c6go!4^)2PjC-x3XanOAzqQLWeI#H$04eGzF_j>RhyuSmZ4r;lz6OphX zm%IM8%4KH1s&e>y?(io0A-VJETE0@rTEg~5$i7$lKESg4)L`#R0!sD;g{Hyos^?Bq z%+BxJA5Htavjzvp!+Y>{QV!@=chxfK;wrh}A<}SrsOpdm3wl3w_h{j8(({nP(C;jv ze5Y!cg=2#(39dg4uoDcA&~AJD99HoF@(}Z13WR(6%?aMcR?1yX~J&IVW~^XT*00m}Mhq7wBYjpBOS!LjF73wG;vo}uso zl_k2DIlFjof8XHRzR3>hMH_kZ{)zh{iznfp&X%raE-GJ!30^K)|6%j8ekpdjm3O(`no;rSX#DN{LNw)y4~qGK ziZ6IW!+HVu$E*m2BH1-EPyj@Vf{tibh;yk&(TG0Co<^-|CXfiK4SxB-7@fci4Ux)} zu`)60| zOe;wn=oJpi7x^o#o7km<$9M;8?>t;^XSuikFSBA^@Us;IL$Dw)eb`5al$`Zd42toy z`PLA(E|)<5r(%`2?@U^--1tyuNYvVM;}1R2tax=RPc!FW(QPUi=$ig8oJ+W_=S9o6 zAQJG{xx2CHtmU%|rX-{d?BF!>@>kD?vb!<9>{e$!-zPU$OmkVU9V`v}c%1l|5n4mU zqXX;6b8VjNFcj29aadmloxy7!X<6S>9J^5e3wPX248hebDeScj7*>va*V|HrafFMh zk*+sVwL`w>Ro75(%vM*v*F`-{nZG*mR=tEi+XxN6?ND=*!P;S;qx7+)ch}e@q*`;0 z#-u3E!M&RLJz?73`zB+ehJ+5ia2H;q(Tjxab6)Xoe+5Msm#{W-P8_a}F8+>$zIbnO zLO)Hz8fvJ|XUt*IKRN_+U`7!JEov8-vDX*Nv({cso#J))qch@3?0@D|hEzGodVS<6(b{=t+} zdFZeWBD3wBK{}=X)X4H)eD$PR;?3(bSgBiIOm93wrYryOL2MCBYPNIOx|;&1oB-n~Xf#e8phNH1L$6)#cUvz0wLdRC&s+-gxQ}e~

7bzwQL}57qUDPE=FW`f`SRUD8>%BF+TyyEB>ulYTr{ro};cM?)^y=ojLtFJ+uE zm&qHxL}|5{uVC|WlE^fj7VTMhLr#NBk!pFv5bo)NGiR)>O)5}Acxh^6Zz`)K_ptJY zp2b9VW>38XHdo-Me!eJ8mTF<0Q`25SBfamsEL&}8ee&@_K48G zMh!(>Pxs&EIH_fXR7eLNzOk|l^cuMK;_eYvy0w0d5+@v4+*h_gzFuzIqwsWcF(>Uu zbvK{Y9G6=7#n1d(L@s91Z}Z|~pgqHjn<3>Y5C`E8^=KHIWd6z^zr@8h z9M#pIOsMdaZzbiSncRvcH*IU*2p)~RNxlp|yrDqW!wYtoiOhc1rw%al(2VCB!XMRl zd9I6LDMaY#0#@4KLZkdQ&e;br! ziqlZjJV;Pud>0u_;`okU_U3hoqXeF8^2S|%UA+zOMD{IvwR~ez!z}UCI-f~_#cAz3 zmx))U(FS66<~py;QCuuGT3l|?dQMz=FT9D=#c~F%tO-FfOVZd;876)!`%djk(TAMC z)iEfu3y5Jmqu?p!jJ|KnR_4^&hJLf)$U`;BTt3iio=vZjjKSM{>K!>Mrm6{narRf_ z1?=UoxRv>Zq~r-5IxFvxjx>?vCtPTEYOsCQ3vas?ooDHy&BXUfYhxss--Dd&-4+l( zeq103a*+w>z&&>X1A-{%_3zY_w{SLSv%U!VZ{D$j6b?XaUyownG7js{$^2_N@*&+j zgCx_ZO30^zTCwIPZ_M61Q%AVy5l9URZ3DRx?ftaDThPRcaEAEp>|9(6YN%ggGk`e!e2`frRzDg~oa*iTyLu;e@S0V`O63Zs;cvO&comULQN^e2Bmk$9$j7yweuh{$WtXXsgrNM;z(10 z()NTbQPRiqG+zqxxo81&r7A@dCDu!YEy)XjO4-IwTm`elY(?JCO#)*@irxe0E_t8X z`=_CC#k?oHy7#8jQhpXO^cr8)IugF}4z^A?fd_m>gz;B`!e}6>9oLEG!b3bYP*fcy z`EhB&62Zd~&)CO!dB_l|v6Oao#v|~iq0G`u9=I-wMTfFzDu+6eEys!?1|LP zHj=|ONjGC^G6l#LvpzN9H-`)+=bdnH4S~3oAGl2Ms2X-TI1I2z(wz?sWK`tXFQEX zuX`x%`kc_y>U63yYC>~|V1N$I+*BHRB^yiLHrz?0BCu=gC+cWj*L1bbVE@Hx@b;TN z`JR)j+Qo^R)Pb=~i)Ku{Nk3rr zU%WrVwZ>%xOi@uE{#_I{K6PGKpNy|#6=3`ItM{q)ZVm!-uiNHDzvHEb(|}Y+vv0s? z8Tg6bkLGyI8~w;Wh-}W6IWI+L_NEA>pG+@gTJGgNnu_28Rw#;8pflHA|Ft?vE>%zx zDS7towwg~(UXZZ;Bl&Upci}RbWV>E(>t;EUw}ChFKa6by7uH+!N=Cu~V|DTcQ5xU& z7oTR_AZLrb94T$r9vlK+o75N|{dq308cZ+Qw;`T))Jw4Zo|5;BJD-}$r_1gmI0+*# z#YuJVJs@uSwNa-ggkV?5s3Ib$j@vSR;E&BvEGX4dQgt7T;?}pNUmV4#Xi`&(;a)P; zJz@)bVyLkP;pOR5d9Wh+BW-|cF?K#S=xDMf^tl%Z;A(@jk$}UWOU?Ps+^E^F%d;y8 zvSGYHkqim9*0HoMk=K7QZY5zw5J3eaNZ4~mEcQ3-rVRD@tm4J$r}G_BRYug9cpI2b zdHlE`QBD!+-T=;s*nt2F_3%&(Ob`A39$Dz~EfB1_ou#Xtb)ubZt)2a(ouvYhD#dW{ zbZ|*^uv2t!Ds=EVsB!3b@P&5>yl>}ERTHEG5A=m`6n6-%sd3G9TqWsbJMZ8t#*TBV z(%xw`K7bKE+Nd&wxAP0vtEq&^7I(_M@09QARG8>gT^wB>QdLx zP)-f|$0^7N(+Kairn?>Y!n=i1yUm;1rHmN(57ao{ci*Y#e&Eny&C?;l+ODtPddvMrkqTKTM)?l} z!%^Bw#?#{XQWH-eL+Zt9n9l$>T&uObdCb1Ah@~GV256o~(4urAe5B%}NM&)*pgtm5{c-4^ zFHye<->gNq^XejnRCx<-Zv+`;Q3wo`%QOSs%#RGpfXZoCHr4B7XUpaAv=tVYCI=x{ z1R{x}Tr_Ci3Lb?QsnHtM@DLTaj@XAroNgI~+?#Ce@;QNO4IJ=0Tr()N$G+c|RxiZ` zd$alc@W2L;WK`bu?cn)QQ14GM^SjmR4aP;*yr%DP$d16??F$o_|e$svL(;ChX4HXeXkYPy16!gcl6$oF>ReF3x zmPs(cR=B257zJ*qxmfet9Pa&Y-@?gID`XgzI<(wu0AL1h2!P+&8$4_tvOu-<|j`9lP!d)5cX(^JP@l$j7BRzgcGrGJ&n(I}46 ze9(u^Bc9PkUiS}U&Zy&blp>QR)yFC66Qg5S?x1dc@#Qi+))={wHmWpla=Rm%Z;Kdw z4!eN^M-Lk2N*U8jkXqqXtbj?Q$q2Geav{Y#gUeAqGzbn%)C)-?x?4sh>&hv=F*Y*S zZ}>yf=DuhmuPfhdMJe7rn~5^_kFZON@En!Ss~?{Ty5q{+yh;KS@DFR+opeGDNbVu1 z@#8PSMEG>lhK)7E40;=V&%}k~?q0NGgrQR9l*CPhr3Q@OA95pO(06h|_9n|<5Y9q{ zBvgjPLhO#$CtmF(twN)Fe;mGA1y4)`WefO2rhV@Cc^DAf*Ac!5a3~P^6k&#i@{(x} zFd2onKE5jxF=?LmFLt zq!j5DHW;lys2JPrK*ce$oNVi#mQscPunU9^_izi9`AOdXiL|){8Iw3NkmXI#bI^_N>| zcj-)V7QC{6&CK7_`^ym%o1YNA=y~ik*cY?R=rnTg!#q{UO0ptu^#n>T1N59q1X)Rl$%dBIdY zBK`7Tbyhk|eOP@Mj{ukIS&IRH4Op-H4sDBV(5Ly9zYb@D5jtpuj#z|-lf&k%_2o3& zD`+x}f0*T`Rnf?qU!M?aX&Y)+)~sIV`7K!zd4->9>$DFX1omyh%w|_oP2C(FAN8!$ z?cXtWbT%2XewfSgq)i6c3VVWb@|s!}nA*g;0M{-^%F3|mcZZ!GIO?`I%tdVeunm7U z8m>4EG0uP!H0zxOFP&lxHbcFvd}V=>h*8d~PKioe8A~AX-{g1YSHpW)_2bVqp9to3q-ntb>A>%rt_ z4p_$JD61vn+68Zl$YQPz&4*eOB?SSDDMt8nmHXx0osU(n9}S!#rFup9)dALgGlYeOn55?f;>qDv`dzsX$bYPj1pB!h1z^W*+`&-&_zrs=fMx&6ILCwJ%= zw~`!Uvr+u%k;AWj#+za{B*h?l8E~>)r$xSvA1z+kYT(*lxF{J&!Ro<}j|ZbIZ2A&7 z0$KHz8qNb3?hcE8rY}?et;hFQl{EFb7+j;7*>XR9DUfiz9VG_`GD&S zbupWet9#O3K(rGgwm(D!WrT?=dUGoK{E}WY1P*dS?xP7l5>bdWy`%6x@GXI;0JDf! zxhI)5;Jf+OcT2&4dv@RYY~Y}P{E#fr2PjP5R=;*ET1Pc#`7_l2Sf({XaT+6#_q4ll z_d$tOb$ho1pa^JN3zRzE894;qb52`|a@Ho9WkE9L`RWC{y0-$rmwY5|_{P#-WigWr z1)hjA_&xh|;%!LEVE7Aa{mWDEJ5=&_@NbyT(n3z@X(*)~Av^PX4dA8rV>p=VSBT-$ zV8s^fVwNH*N@sLU2LV_23is`M61Eg-j*fbc55vktQ0Pu2WO>GZeVkQC4aS&KO}N(G z^nLl_m*d!P$Ccle{ShzN5%Q(giqrXFD2Q$bB;D_i1+Kv3*6H7>fVkG*C7qt9OgP(- zFL_!%6!2$nt0%w{a0cAI=Q&epPI~c-d1Lx^?=9>Mu3n zZ;$3yt#X#Tj3c&`#N9~ru|J|TG0;y1?#>9kqOBd}Y+YkW$MU;1`R|b!$CHZIv!+(s zY}`HrgMUZV70G%cSQTM{hXoSD(lR9aEzHh=J|wi7^$c+Qi*_Ko@eA zu4iTOCa=b&Kn0+9U}97cur>oFqM_?rYAbb@dyKf)y>SwTD2H;$e`G&LQ{El|FkNHRQ z)rdQ-ZYKicF9>Vz_5HLRNT^K0&Uf0Egr+Ji>K^ZX|0z60<|2dER$&l@Rg!ANi>Vyqf$o`So7|i-F zvqJPuRy$DbJTUZ%+x|fESfWRnIp14CrPJoR$87zhsg_SHuk%7K#=|Lqbz~~g3Oac} zS=;dB#b{v1KH~&C6<%@ogTsj-ErzbJdXl_Er%OwuVeUhdG%ru0|GvspgHz%+#!RWA z;~zf=${5h4=6{I>xKZ#I7*RAxego_!8NfFAx<2s8si`s3XV<^Y94*+XgpaH=~q3DjeZN{|s`D!)7owX4A_fYcs+t$*N{yA8bZeJ7fPpeDrsM=I)>7JN2%U@F ztv3LsJs$o(gpN{=T}J}>HXYd{)`^s7Mc=Riymr~A9D3Y~7nRDr-?I{?+W0R>>^pq; zn-6;kq!``ucfBG62UjOQBW_UhtC05{H&TPbyRQG;eKJJBUWTG%01&&>O8!CNeX>S6 z>mYYBWd-TUyZ3|da8EjbM(F+XQ~J8uoLD#No6?5Nft+dHuBa9!bT^CsiQlQaPneUR zwiw~$estHEb5n{6138`pVdTelYN<}b0hI$SxV-4yiB|*4%7hC_ zc`prm7WY%R`mUFI%ANX zL9~CPY4VfEt_8F)HI)L|G{y-ae+^pNQmB-(u ze-ycmE-}-YmMt+7_-;x&h5>0(7d(%wU;&Z>200&$^UsvdX$fJGcau7m6`Ogl*Om>< zuZ=sVo^N>SqbMHUQsMb9mQF`$GiX)yh2LT~nrUA=-Xv9x`IPv@rNojxJav0{dCsqr zIDTseoARQmz*IR%H8e>KP06p0RqZt$)s_CjFI(CrEbx^du#(JYzYx&&kT8P3dy-t6 zsnVx8l}z5o=}8mpsu6HBJoZ$o`1&V7Z7sQG#}HWT%R@mUiu{kZ)s?&&TWtEXnRjvq zQ~3)y<6Vt9$3j-#zcHPBZBU*u*yQn{#EMN9`2ILC_eYAu_58F5AMzF+9;=*qHNx1l*!+`=>C%hDL@ zPb-eHkcr%4RhbZfQc4Rtc&=Ug`&W}Y76U(1?8NEKKc9_Q@(ZJBd^$(~F;#wgq1pMz zE=9WW+mCL13AYzG;za~OC?(1>hwLI7UL3mKeo9j_WvX9wXWauc0gK}UAUCHkJQuoP zmMIAgl4@vJ3}PvnzlD>G(#X>(Tb}6;AG9%gQfKPp)Q7j`4DXiK6G<`4RL@T!j2|zq z`3slpPcWNGUPoyvD~(}ZR0|}ZD1MF*r&#-N=_Lt1t2SO)bCM^yq&^+Bww=D4rh1ZO$(L-Cqm&b8O^(kJZ5I9Ks4!s!n#C zwR_w0yF|6>N1C-A=z#(g-`1VY#3&jkacA?+yQkHY$*hi}K461qTb}$=B94c!7tK#K zV~qZaQ?Rs=K>78|XZhSVRX0h7?%uA=mQRVx87To>}HCSM~ti1_?Yb#uB3|q zo{t|oq{*_n8A~$Oyb)z9)$*m|h6yEy8*X`SfPIyuG0f3}4^%bQbzRi51O8oNckqI{Ay>t(V6N0@O>r z${NN$-<)Mn(DS<(^8qnewdT-NHZEVDb3Mte2e%IxZe9)y}ZBJbQ})x8kbvD&+@ZXCgcc2j0`n)H@dz+&%X*)J|9%& zIQtA&{4UKf-@{EvHft-he)DT>wei~DlW1nxIiu&C_ufsVTR# z=k^t&F1x$d_pE2* z(paa{?innx8|2e=^K#M_+Q1}IXfJ11exm<@4BXYPSQOA$&?CP+NJBFGoDa{ldU?xo ziM+@5;BfhX_rW0%@JR<}SF5mi-X`r~r3kfU{1`4%(09JhSVRZf__Q2q&c!6Oz!^%y zD6q(9H%aBh*#j!LRcbS~OhWhSHt%&V)&yJswB?DMWl#)o7T5VFctw<#Yoca_cVEK_ z1<9KyiLF;9eb2#Xk|_)xhAC0deVzwwAldowt9B_@Ef%<1!rAvZ4SmwBXS&4pra8`* zg^mhiXY%K$EP$*zmP$yc{DP=!d^G$ga zB>&M~Kq8+$xlk`i#V;7F)T0rhVUNU#vxAyC|kyGx4~sNhZu6qh0ein~j330ho>QyQc#QmoM86f0JsxR-36b9UeN z?9S}0+b%|xuKV}(u54UotwqDjh^cgp0&2o-SYSy4mW&`rxVHvIzh$|Kw|ZRFJ4 zDAGpXT>pihthN)YmeeW*vH~UJ7l;Qh^W3|NmfKYBn)OvSH^_q+0TC1 z51UuIuW$CM*f)l#^jL(-6~2IRyrg{BTLj8OhB+SC^+$u)zJh|WP%Q1(w45QlZv9OT zmL{pJrWtv73bX7RDtLRJh`Mc@jh{y>&oKXE6od&^u(^M;9o$EQ^18!teYd}3PAJm* zS$xBxv;CLtDxMnK;dO;y@=EV(&1!oslc^ND4%^+2bzpB*p@~-{z697-`bh|Pj<~S$ z?E51*E58F3uv=`30F~8Xl_y%NPw8=yk)I5~+(qoTMX<;sYgM;J925HyT1%7_>u%9l zM5#`d>65CmPMq?bPu7F1(&VAJ50(KWR-S3t?@2DqqhW*sdOsD6P@u+Yl1HxeV7jVy znY(VYs_x*W(l*GQNJ&*R{u~+u}P6X*r$IhbsN~lNi z%PJuppyp*Y7OJ`@38EYE)OOdxsj8y@r?cGAh;a0<>)?)42$XR-H| zd!fJd;$SY^pl5LKh0`~sO_YXeZz7mKS*haLQWdG`*fZ@g8MScmD9igW8dgQ#3eJgC z2bsPn*jgM}o#8Ftfeh|_{#0kJWflIszUei3rh%al^Zn^){k)0V;G8hbd*?}_b7BUE z)?A{1Zw)KU>bJgHLrVU)%LZ(2AR<;pwnJs=X>@Hb5sDKPBRQMAylMTEwr+is4S@E> zkk`IujN)!}o=9c4UAE-%?UzMj^V`;K7SQ3CV&^IJS4Q$XCAtJCx$s~Gd%dR8k+Bbd z$$OOOaFVfeJGMYw zxy~Jv?t0s3DFBNBTzj$iy;5C$7)?OYm=C#fYtwyCeAlBF^{q50uQjm0x}yEd`*$zj z-F$XN6#NM)Lj~O_r$PnJa1QBxDeO4 zj8c>HBqCOQmuCxSOPt^&R-!IWADzQSNpvvxK+Ka*ZZ|msJE3v(;a@pQ_tmzu{+_!L z@f;lrQ3S%`PL1C}lNaP|!$erzNpBA0z6~N~RRunSK@A5~83HtgZeYw*3&9BGdU|Bv z(Bo)9&M`L{gT|mN;PtOVP2XR~osCRPLU5`i_((QoH+CKhi(>bPv8z@zwMM%l;ePwO z`2s@XBv<-ee*AIwhUue+Pf!qZ&{bIYbMI-RQm*V`szuL_{2Q*f2=furHzPDS2`tSu+21 zjhqWLB)4)PZ6^%*Sszp}%F%6rJ^GtY*IM$W@JW*gzN5QB*fe1HTb?y^i9tlE+2ii~ zp&dgQ5qKCIMWlD`$s#W-cu~T?t*00nQMEIu8 z_!eHNT9=9#JjF7^&TCMf0MOpXny+j=zPIacQa{Q0OkXtUB4(22?eNe=A3MS)ILbFU z$}ha}bwiZDZ#dPUlH}Jg5zf(v(_aF4oiz7E;X9gn$sj@-Z%fBk&7fB=5N_@v-fGYm zMay7=N8+z$UVV1|oCL;*GwLby>bUpS(`3}sf#7>up_F?HEPMUe)-f4wF`0+D4}R*? z48*Wew{75^n|X@aVS2Bu?AHDRdM%2sIjygFE-W8Ed3m8y5kLIt^+09maFt zEot-R@;O*xa3K5J(q|Bu5?fk~)3Jlu^Xj=w(v{YuGt)=sye1a`k1n;i0Iv|4;6)T~ z;SH)y`X>cHN?p!0A8i^`_7(O0n_EZ2y>K_%-S8>DzcSK^(jyKNyz1aPvW4`cW8e(2bA4 zs<39~wO(_;h)rYfg$ic^DOWZrcO@y1*T=cv=kigXcjwFJ@g%HUw!GxfvuK&-Okd&V zYh6Pi9IpxVsn=WpL{8<~YA5+r)9sYeZ>Ka^1{EWXfPPzl()^KQXgz!%z|KqrtH>+r zb>52g2QKyp*iPvaps`uWFJ|q;kS1LASqdzb{Av@f{w?l5+OAjc$(et-tw%}sJAsVu z*>V4oUFJf6ScBZ^sY#O4q1zgo^g0xYvUume%ZUl0E4SX5i_86y z*TNr=%u{=PNFZOqUzdovxeEa-XI@86hi!f-J51PSm zkq1&ZTL>2z$Pw2iBs}Huai9O3$h5me=T~YtBsprnS=qm&>4hf}MJb!(wbPx+RH7{_ zto_kii^w|pn0+`jGF@-|N7p>hpV}TGWBw09CvF*drakX%^ZY!w#+?f?2)nt@QosRc z1YU=|PF!$yi@dsv=UVZ|8e*2evuCav3l=wQ(Q=HlpMW>0Rw)t!_HT_iXR7QB`q zDkK2?P(Zm@sR%(=Ysw}crwx9wS<&sF(&f}$ITUfb{VT3 z?tCn&?5`{`DYI|u#lo1RHPtV>c?C(86dV;2Ebbo>1^3c|4Z21aX&3joFie=K{tKcAwH% z)e^eD&p3DNKNGTiPLwbkQcNB>9TI6s35op7S7}yM{%gm~xB4k`fwAT6+0Vc$HcW}K zeUp!SIXZqn4e9lhImmI153 zipU&I=@IjhI`j=+*$jF1>2$H^cwc#@0u~adkv`)wZYJY8W|ym)akh*e?Rx0vxZx~^ zs4K+XPDsd3W&QH?@5XWSoBhgqAOXLf*y8r6<$^Kbc+w7m;`xbU{<||8WN~-3iY~aj z8A@V8|LvG5M5F7sVdca-Z~qd5e;L`esJXJ28W54yYkyMbs=@ z(sHq5YzB~$f^V0QMD=?rKl>b{9k`wI_ujww?J@V>%sZ{%>@=F&)$eNxbj4%Po?U7| zo$RF)57OqQfBI?l%O{-Wf1@DPm?}{vzXw7o(%Gkhu)+P751#HC^bVJnO+G0Qi`X>^;{4t~L5^fG0&WU| zF_FeSQ|Gd(2Y+H`vV~emCZZvja(~#3Jy~spYOe9lGyRBgOEDLeq8>Jq#b;C0&?&I| z`P1XBu-Rhbhgp5RJw>1!_>YFN78>iRG@YzkZa~~uLl-YKeMU>Hgucw_xil@N+#g0z z@~X-qBv))&U$YT61h_#0jGKZZK@&X+tz+u&gGULwf1b;U^IX{s5@Hi1MzehMK#FS!JA zH7S_Xc*_$I`?jz86*<1nE%?{1q^HZG`+4n)~HA@t)eY#2RYWb9N`Kw(-$;o9> z2ED)kY{k9oXp=qkr(7KVpmX^}yV-4Fw+#F#qpwjkmE2l4W`MGAw^R9pL6Sb*hA78q z_x{UF7#LqOxII`cOPU(1E1;J4erE-dy=R#?WGk~}1a$C$m)&dSDZ8($UqXR#JVD+z zxVOAZw#Tb+ylf|%$XC&LVV4sXEfs=p;B@b*JF6LC*pV&0nmyuYNfDRiXS4W0>w>gh zae7#>amU|cueQG@S-)`Q7b&1een+<>2`gtbM3+cpqz}*iNs6n*5`>ZfJ+z0!0jlt4%Wbw|;OQm`c@U8N3e^5<@BeKz73aR=Hv)xDou} z0=-LSB?KVG`=GWY%l25b@dW<&QS{w7&VC}nYQwAULo8=&umkqh<|7t%0h~E_vEc+n z)(!ZpNw7WvO_>;Z*@ufhz`fSKq{PB0ONL?Yt~rhnLdgJLBW4*C&X&N22p$BNK^ajy zEPdeHO32h9!Hh1Efgn6am&|IC)UJU-Iusa~09o*DQL^B>)?+n}Q3dI3Qs1YHnf(2t zkw~=%9O1+XQc6yOrCGq|gb>=4WkMFNNYI479_hOj z+9?udes_3t3U!+vM05?roe&#q`8Aw~IW&=UW|FpAkaTs2;-?jxJghWtf z?<3S!sIL{FmwFT_DJ(of^I-Q$+$K1I5Ej=OSjUMbOprNJgMrV3WwMb8ua28~l}Q8y z=qr#n6fyQGlBonE8W2>AMGP)h_)sOhj9$h8D-!%-SY0n;g%u(7+KQOaAE{I`c-aCB z3?a2)CAMBm#yNVTPy2|J4Lg;y0ZCWB%9etn7`B9<5Ol^?m@mM8qWph>oq9dKr3{_TcuteDPY((GWcrn-dP3slvAhqMz+eqlp@@|; zC5&f{(-T4p#lmZ~Vme=?&42)IA>`0C=p8c@0GJMg5%5)dcIf1^rz}IgEV_+VsWg?S zf>b_jk0mLM(jZ+`^}b}_8hyGYA}6}<>lMXq4hpkml3dNKqEA>BkOACW9y>82@|#<2mgpDHrlg)p6hL?n8=y$eoq-lv5a#wkSn5+ltSx&BET}n6QRI`tD<`0sYml&^P>lc z1c1j%frn(K=pMn&v!dcgB1ntqm%#wJ0;A9qQRYxmb73*OVw#s}0)I~*1rd>S_c9hR z6Hq$9&hX_DoaLg(fb<01kj7tk6Ie`dIrGRKS6V@q2}OcYjA#{RXd;4QaTNzp0DlEh zB%)xOR`)>)1jmXb!3a`t^CS7`r*xyRgAjOPF!_84j{eXy$tvvGtpx#Mur|OlqOHdu zYH`-0nL@^sH$?y+ebpCCvlznQ5%LUz#kp@qADxQW1?UcnXw&sghbaCOD3aqA1A`$X z^H1&gEj6+gej*d7%)Bf#Gb{qnXn!_XXO4kR6=6^;3fm%^`~9Fb>-2<06xXzzmF`4P8w9=I#!dINF2q6|FG@c*iY zct^QWb^a2Ba3l&1o$m|v7>t}o5@D@7bG3Q!wRxmi!5Mu#CEGk@FFX~+y;L*9yrB<@ z*2M_KyG4E7?JA^c=9<^9hw!M}ggYAV7 zhbowv1i$#?6OjAEfvZ{Qx6eA1Dv$(5(zD9=qUBi-h2gq^q4v4$&J4x4LC~Wl|93xsQ-$RV>9&wR=a2}0>Kl>WD$g@3 z$)6S8s1-)h?@uOd$dnaeLLD*Z9RA#J&)%2Y$yXe^eGOM4>QxrQUox_w%cIb&chS^Q z(pj3sS+QKRQMt351-{Ws&Czs1F&tB|{t_Y065`qt@x8NeK3#@aOC%g!XsH0K4UUOB z?TP!BiANGiXTC{S?MZ(xlR%QmIDW}^9mzyj$t02~6n-gxsgK7D6PBo7viU|W_@=h` z#Qa&mhvl6n*^wrDm8K|}uIiVr-jS|-m98iG_Nm`nqmH*`S8uIoG8pE}6thwv&t|ww zX3ky4j+X+~3SjE1q)#kaF;~e^9a$+x$>=1>?Ck8M%#Q3Lnxw*xls4+vj#YRfnO}XC zQu{u4ayAv47Rh|2x|LlRrCd0rR5TP?L`Pdx-Ivom7o9Yl|I-gSDjv;(AQj?O5$h~b z+$c#(D!$d=03Yqt|TuD@=)~>c7|JMI6w(*A3YI4d~7W zqJ?S_>Bi>QjWi2Y3^$EsQcc;faT^pwPNbSu`-&E@i~T~IrTtCAu-BS?vWv^@&17EFN@=&0SL~(UPvfhq=>-Fl6V_LQbRw|k~i`pw3JPG#%HNiG;HP! zYj$60Hfm|+e%LHJ%$`ys1YxR30iYn4QZ|#lV?oDEu?`5B6%`6OOx8vVwWe?a@ula_ z!LjAR_1QTnWR{_a(&ahb%QuUM(`wUmrv* zrg#n*fa9gbvZb*~OM27b?;r)j^VPt|Ck%#Dq}_oCl-Xh?!_SexpHoY#%;sxEO5`3O zM{!0#>P?FoqY8a5T>t=-uh0uki_|j!1FPhOO4vdnben&n!&bOJMkmOU2AU3E?j3nv zu<6VQxD_D0d$xiKM8EqG*I3aTTk-CBA-c(A{&ep+-fb=fBFcLZ0gT%qOQ~wi8@O4g zW9m2hXqw0R&E^-z-4XLGKSqEXMLU5}!OckxzYL>`@Dt^BGT%&py4xvP-n;1egI?Ys zP@?#8e2AyCVN;Bic|+kJbkT@iA;O92qUhsE*~g1o zrpqt6e`)d%fRbhpX4c-;@d+H26@*786#x}19*805G475QEcu*3Fa7!!DpWd{!iv_+ zk%JTZ1Yrf)t)|JSNoxBHE?|g_S&SSeR z*}6CP-f^KPLAvc=soN-4IsI_5C6eVC;LE;S6z1m(s4cvE^iwV`72uspPoC&n_!vg~ z$AP}XV-tY>jY~PqV+Ja$*=~>TtL`7*M34~|F0LMLMvPH#wl6a5br`?{j?tqK)4-q3 z5lleNAz8j0das!PNL5S2=nYS-7`$;DzL&qI@JjPc#WvUg zeun^AD7{mZqB%SYfA; z(cs?L;3%bzmf&`Kk6e7W_zox@9 zi97Th_iX_IgVL)fGAEfYHhi3=|1`4@7i;7e&dQt|E!-tsrFT$D3>KGY?#FRYqPmCyr0Kak$k=S zK5%>1(V&zJZwyOFtT^FkIAZO~rB46q&IiP`heeV$q1}Y1oil9s>!9tkN6M7r3e7IR zN!*b`;tl#jJOyhjC!?$_9~DL>%^S`QBRxd>IBXvN2VEC;{)c#e zx*F2IyF<+tHF#~tCE_@lZuVM~le!LYjt-;``>^4-!Uqj$nsv)z_vKtha?t^&yFPsU zz*kK0U+oJUxo-D5+ql?`aeSmJNl!xHMs!h&>} znJvK9038(mvugSNFv*Lel%i%<8&1FyVn3^!j5#yqbB!5!^|UXv`xXKx z#R_x&>Lwoj#8#0yrbN%T#9t(~S2A4}u6d5jG^!TOo@aG$V(?eOJFVwRhC9R3i9DSC zU&|!NW5&Fynpt^(Q0bpLV@uDmDbRBX(2sHDloc9 zI~7;_t)30FFO>7_(S*UDM4mK^#lJ**mC)~3C|f2cJcYj(XW~UkJWwkEMTgQacalJ; zBf$2hN^v5_ID`bLF)x2`>Ht|};*C#Xs^kOMa$fd|+{Q#reqNPY&Q*`!Lb07!uyCzC z6&LqIs+mqDV4bnOY0`$u_g>R+IpK6elqlg) zF0PcTxZ3J3E+CoDa~7NG<$$&WpD#YG%nyS2+FEDVxP`@C@3!v!TGt?g#T9&?_5r>+ z_oTSR4Q`)~ug-Ozg#=668a|!q>Dszi^>IskFMYZe_v?H<5-cCa`gCvb)%%UdEuU8T zeAsiY_y0-o^Kv+|vOcdq@K4;&TW)buYK>?DfwG?ffiDVN#}`BpzXIm*?Um(LxMwa( zB*i))cs_x{l&TMxda};A46jnAckE>=deG`^_&^r9ip{H_%-Et^#av^R#XoesD}dN0s~vNqW%NM^5(HO$3nw7g@0>#hdiBWxr>_OTNuydk-uP zAVY#C)+f&;z7$&!{Wf$ICqQpw5xb0HpK5h})9COj7vG0JD#V?J;{Zp%1jGkG;-FF3 zb$%0%j5Ph{r{(w|dyP?11Cq>X$maZ{7`rG5rLlh8V5cp6C&GIsbC}_5$10*fz9Tnn z>ADamZ_5ak30BBuLpbpsA~7f$#jSo0V#?Wr%M6C$^PtGzP6qDTQVqaQ)xwEW6`;i9 z{_FIAd>=xRqa9bU8CoTn0nVB@<=cB+w4aw?`_r-Bx5@(pk?oyqchA=wZKymC+sA`o zUWrml^osX8Cs~phO;s!vA^vVr)5);23eCTj*@!6FrXwg=C-AqaxU~WRFkgWIP5=OS zy#ZC=4Ey$fWdr`A|K9wE9B_@kIY-}|-rnBc+}xnAPp_}9|6cub-CdrdFMeNMUS3>W zpwIug&d$y-I{|m6d+5{E|H20R`ZpVJ_~Y>K5W@zb_xJA(rqElz(7%W7w)@b(+WsX6 zY;SLGZEgLF4fwORwz|5CVFT_~deA@1(R0)2#eDQk^8Y~&_?C;Fc#Zz*x->oYFFD}u zODX!Z8M?b0-5HPmsD@3r|AGgIi;IhiiHV4a2nq_`zki>f zpP!ePmxqVvf9D4v82`B#7#Qg3>FMa`XlQ7tsHi9@DJdu@$jQmc$jC@ZNl8dZ;BYuG zF)<7V`@duZUSU25002b;ASk_B1F|;^O2%zE*ih6T1;3|}r`A~fDUMqB<>Fvt$(JOA zaxA@iQ|V9|=i@5Vp{BBtOaYtWJoV=C(e%~3ooTM!@_(@by*P$11`Pkr2DDUtuQqIc zxis8T{ckp)PPlXES#Y*Ux(Jw#4R_3URg2X{th2dx`!wKJCer^Sd z!h2!3VXPVUYcXPy?M&fR`i4c3Vn$g-aiT+N$)19|tV5EHMceC13b;clv0yHN-V`Xgbwuwo0YTen)rIUL& z0o;dLZRPuJR&EspobPN=yusz(M*8=lvK6hy(kqIe55KP{N%)+;osAc9G)`PZ0}q2T zc<=7KLq>A%R+MJE+^wuAuiCAuY2DqeZupGm{$2C_$7^m)6)fE?d1{%GDUzOQk}`3&2O|)b$e- zDh7onr@-2Luckc>w9mftu#}2=ng*fwFMhH`j*{Nbg`NfzL}3NDK6pvM8afAUNq{e6 z57nmr%ACq4-OP1N{MItpIU~MOnt4#L!b6fcu|^|0mb?Mc)oSiP5B;vs^4V5~|vL2cTQ08Am z&l=L=a8nPz|5a$hw)9s&nM&$XKTAvhsD>=eJ3a&mEzNbQg2B{>!B8zE7L`2;U{wK+ zBR-j=Z$Sb!LJ7!1l zQb6*k)6fa1`+;B*5p;vH1V9l^3n!aC=|hZf$0!tol-rC}nfjQadxXczEW6`LK_b?h zU`e%_>>;0Gn>8}3p}}kw!MNmjR*JT)Wd1kqekaH|)+WK^Cnzl7A57rEe_{fqS|!q# z0&wkV5&(Y?N5<40O3^Ut+-O2O4ZV_7NCd|)f;N?MfR>%-Rqye;TVXOWRHKJrCA@;E zfPNW*0X27|X>6^>UoC5mr=8<0<+gZ#btCa`JHI7TdpSbQDs+5arbHHplTRUg@mH`O zIQPZnHkjZ@Y$L;XB|-_gY92Db5s0B$CIyUq2Pj@xM)^mBfFw8s{%oaCu2m%2H&<6f zW|G)~y19Iikd}qGQ>$S9tPXaxqy7dU!Yudrsg`XkSk45i2V*mB21k&>j-jsxuqiTq z%iu04Fn_0eBv@98{A(msOh3rV?EbQuuG1RdCHz3J>OPRqJN)r&?J={z3GDDtV__bh zp@kW7!24}&{Y?2h&WDvmMLya+_y?^}>u`3hbEdz+hh0h=%m(G2PA*9(WqK!dBflb+ zLi`&-C6@WoI#cC`2Aerl^<#lUE>_=6RuaE{V0KWFPu0Udw7y^w|7D^xK4M{4KEw7q zP~HFg?m}{Qc&$rIy`y5P#oR&LN4WV$kO`?}CSkj(!zVX&Eu^um7Hjtrt7icnZVLt{)8xc zEt2~w1Ja2eJFja}nd(^wrAFN1R9Sx7&IYp}S{u{ea{Us@O&sQGY|?1BUBh}DhaSSc zQZXR_Hd$tjEC#g`Jx0H7l@uAVW|BweJnnlT)H_%1Z7!s))e!&2_j2q@K95e(;+979 z-Z;a~+A68IeLDGd8^4&BTa*dbJr3jEhPUtEa5?Wh3*$2*OFK~Sv`^M4+?Yz15^-2^ zO2K9|`r7$pFySoE#(?hTVb=2CkvG=tFVR1Kley++b(tUbKe!^^CgUpBki^8T%%h5M zMb$Rq;^_hDZyWiijWeU=wvOOXQZJBRrk&zHYycye8BkGEA}dZts9i#c!K8Ew76E8Rp@2wL zN&=R9iDDH9FXRaeE%nuTZVRt%$|92KuY__m6~DPm^?YwlPy4s^uucNt?~ZO#=k&X~ zQv$c69MVzNZn3$cN0F)NWirpXK`5vW44{u4lGnBRk|F~`e$4%=S@;}6f> zwrC{%**_f9rMnyDf-98rFI24L4NbYOw~&HDqyA;U*S^vrVv;q__D z??akPHG2@b1nsFfY3mEpE;~^?LvaMNkA$w-`WC!DGT_s*5KajyDo#=wLsB|lKY06d zI(N{Q31T-)iN-fLmYwmyF7z-nRDqhDhnkd6jr4v+uvB}PU4b_j!^8e_^EP9Vbj;R^%bNZsjx)eBSYeiPiw2+MX%!W8_sfzZ9- zbq`0FyHZ3^ROA~dxzQzw2`8x;b(F{K3;JHXzX0LpgUEgKm#9A%QK?xhqjrMA*k(dS zf~y8^G<>6rKa(&86N+)VOBzQ05{;>#CR1tR-}i`dhLW9x3U6gPx@EzGCWt>Dg1gS6 zDKcYwW=T7mcs^M34j8iaDe->Fiq{O~9rl3dMZavxlBOpCK2ALI@-fq!^{&K?k-Lmr zzSL^?tn*5VbHgw(5Q}p&D{<4Fb4((X=qP?-JBEzeVz>bp+z@x{8}KD1;OA@-I0X6w z0|o#@7NUa1DA@5KJ|7C+QOrMlnXF05_82P#u6}<%D`8_R@lQnx0Z1iwn?N<#o?1QB z#yj@THx*Y8*JcGkcY!wHuourp&aGv>09*_nmenIaQmHdkTKV`4QB#Mg%~8vyWgBL)i+WxB!l z`>7&>asSV308Rd|I`rf_t{37THek{LS}sX@o0ZdZ3CN<|a59iEC3tSLQLZaZrYB9# z0Zn$oRl)HbP$F5FZ&Y~hmwlOCnA}mAIEUx_9DK4G8E@CgM3~|P=QLrbhcZ-euNCYWy zRLV>}JD!#MFGu2hjKoMKP)7B1g3=Rp$gVT7c(gg8KG^4FupJKjLhucN#I) zSZqFp%^|%BzvBJts;HM0>GNr%DQ^NgE5B4F5ya;7$EJRYttmCG{$gB7a^xvSja7VB zjUQ4nDOEclRWX}WBkfcE)0iYX_E`dV%|=zp_o~|M*Ogwe;pB>-90&i765hHM~ zc0#w6+Jmabpy9?!n#P^i_2$s#$V+%14q*;Dr)hjXOrQaOPnUSc4TokDiq@6jhT|{j z60gJYSp?vQNP<5ruyzF;Y-Zd^IPvZwKIuBnv>WmA3WVUOlJ|E4zhixSY(3`31nCh- zbg=%#bvn1}%tyaI|Y#bYKa;u9RTjB0;pBr#Ly={~v!0ef%(KUh= z0o?auaI+RlgB59wLtG6XV%5?t%TT04Az zl>%OFAihBo`GEnmVA%B`@i-v4xB|r%#6?@iV1qJ$tc&8UAgT<;F5oKB8n4$b3-di=bO>oCFABKLE%^I%6GS zm4kpxH=+T@ZoH6gWI&`-cfX;-@VnbaT;>lw6VdWcA8%N#u|B4aUkq?(EQ#kPKF}6P*-lZNlHiUV!uF8_`dn~d1)}3*STh`qUDRUwyX6|4 z`E=itN)Du(saTL z6k7Uwz47-Op1I?Pb2UzL`T0MB65xWH{pJi!NksE0eDfs_=j|7!YCEU&o#7B_O7l-Z(p!s5{WB7AguaURz>cA1oDd6I8=U3=+s{_JM$qGrMmFtbnm--Vw{&#MbVd0+6+S&f<*8WetH*J4yQSK0{ZN7Eh^tlBoR@!1p%7F(v ziLhOL_T9aQ+w+0z`Ockg`5QFmLRzp@9oX+8xpgs@4ac4x0crrXVs>G_*T1~ueYArz zw{9wkDmUMZCJH;P*z~_!{cy1Uk#V10Y=86N?;kGP0@0QdYJ1!Jd#^zIE6WyZiNPD@ zyE8hSvDfyy%X_tVd-Zn*B$R*h4S#jH9F)@8ydK+A9Xs$^J-Bl*2bhvd&F8-#)WIwX zm!JN@`}k*n`47>!1@Zj|5{reCgZegK!W^ALnxFeFcl!)X3W)+l7|*2%4S=zG2?A0c zRI+bCEjFs_w&}C>3IvWw$A7~Xj(uNYMnk|)6bROkpmRD`ejtdcKH;t0Cf1*c;}$|q z#3>6?h^p&p%O@-}3PF<|CUj<3D$PSmkit$6@U7vZn8sI7rGz37c zkzhYvSfMT4u7<3mGQaBMbC~vXyIAQEK_r6Rq9QFiC z<*f~7FCB+;u>gr+G0QmhEd(`^214;L^3&6UhzlIa2Le72<=x?gL6?W#X!E3aN z&y@{?ogR+&KPpyDU{uX{vZG(Fof-Rj=F_KXe85+sQ>i~*+?lVnsH{LpL?+~ zh4vj5>!7{z*c{E5N2_-=9kfo58-J8DZNP{E`ZmNSw-TqZ!$XA+3(aLcb_!YuaQ}$( z++GA}v;Ka!{D>hkv^3G|}Bn}E)>;DgY=EUbz005LsW zkysuqI1o$D>eN%NWs3iaoW_X&%jS9&+)wy?KudXDZckT*!DmBIfz+;hq8C9hg$eEN zA{#%m(&ahHz#?`9HMri{9z47>e6RVb^!*~KW)lpK``~^xop2YMxQM_*?it%=?XH?9 z9%|5EFCc3|(I^KO`;(rn$v37R8 zlrct1VeZ>?fF&_&jrbr-X&Up8{YooU^h9ggJCESFBl z!aRQXT;y%5S3DEAXu-Y+JitFH6?cRuYHWw>q zhF2OdJ?;JV?ek$y*nQ+%Le*c*sE-R^uO<7>9q)6}avXmo!!T8! zs%REJe(6s5E2Jw{>%l*+`0mRZUfSYi+#bv2#e;8ed2|{UMSqFK?bLMs@!RcB*ZIBQ zhXe5cUo?TQhiT<%bV*! zO!JWk!wu06Z%QUpHZBSRq@=@IZ^$EEJY$JtnTUxPb4J?+Zss4m2>rIbbmz~izjRTp zk5Kwp3)@9~0YOYUzv0G^?Xj)nqez^TfA__NRA2oeRlH;>2i{jAT;cA}s^LS=OgCE6 zRLKV@vz#Q_=nlcQ%;#!d!b{Wf;1|sTTmk6$t;@m zwfaVzB59|SRgNp)EaqX&VxJ)Ko?duZ>%-KK*>N4rFs#Qt`VvS!%|}y z7S`7Vk;|~ag+Z?DvN16e^;t;qoovz6&t|?;PRj{CG{%S{27m{5 zd7-#GM#V80s8a<*sA@8eBQi8qj@l4$G?qfoSVbpqSX^Rn)R^A*VkCBIx}0=*=5e#` zO7`6s%ulkiH*8e!G;;gZ4=Gy*wO9d+q>?!WX&nTl?>i^fFbM@Td-4tHy;0oG=|a5LNftid9XazO0(gd8+jOJmW&!ks44csaVy<* zC?inQVxsgMZ|_E(!j+36TLCu3STwPaHvoP8ZO_s-spH#2b+U2Uhv^AIgYa>v{L$uC z5j#$h|5Q2yQR_*SZ?DVQfY)brO}hO!f0<8*J%i=%`%egyn1Q%>(vqiI@2W&qXQ#l3 zo40iN9lG8CdhR0GI~)|+T8zH5q)C%f5`pd(`La28jIqq22E74p5P-zuHTMCG>1r~H z<;3I)feJW~85$@Vmn(u<@X|e~t;{V}u;8V-RENasi?e@=cQ|_>LrQ^|;v*R!R%HnR zc*rC%6-HT|5kc*NqRKbn1?bZfG0cGdi98?^c6)xpQNWfbvWd!WUE|{A_?O?tXpm8B z=xZNiy{^9w*P^Gnwy&G%M~l@m4zxZZkK@tWfWaM34M@s+U#LtH3JzJh+BCJWCbDzM~ErlmDxi z^YY#51vcu}HkuLKfxWqCet8Alm(HmFNdn^Y2I@Evova7Wes6!+lqrTqi zH0g|8fYC)gBK2)MNS&H;?`KEJFAZuwSe~0bIwr_|VVKS^QTKWODal-yc{_hp@-ne_ zph)H*L+1?5eVbasSV3q)W5-kn2A@d3_$bwsPc@r`}wOM3CiNk>46ys-tK!0|JlD7_OCf~a?VKiA(^qu)zXm+JzOViBu+o_naiTg=#dIEzGfl-OTWJqAPCopyZN-Y?c6axDl0!t8qt%A%3 z=y668xXEmQ5P|atfmsRU6;MKET2ah;D8m8a96e#50Z~mo@`JNpsq={rg^#)oGJOTF zOS7sg6vuC%n=CIhsGu~cXgH{3KS)yc8B~cJypS@edS~!|vjIx3I^GzF{@DM^251@> z)ay4DsY>;BlXW8=RL1#Mf6_@mZEr0dwVv3}5Z?m9e02z(KVa!IUsyxqGAy0N8yh{7F$iJQ81qO7aX~ zQ^hBx>5u$;+zom?Oh~3|z)^l>N|)`z`p2X#D;gUfsu7cVDH!0YVg zrbm`SZ6G-{hOfKqUPnI}^Uit2mCvomj(+*(RhW>;a}C3S0Fd!m8o4VhON0agoy|kT zEgk)>K1z>j)gCrxfSvo@F<{kD%_of)A5*_7#z8LQ)5(Q&bO&WTlDg%GSug`N^CFFy*IpNMr!~(fu36pZppv*`a-+uG9v2S9*bhcyc9d`yls+6RZ4~8+1 zwsBj|%^;iO$3AtueLeV=Lcr2~bCfD3(-IF-bx!`3Y`IvW6m6J!OI7UeC&a+y_*!rG zw|KK1sOh4T36nKMbqv&Q_%2>?B8!;5$DP4ek2tWmJY;?|C5b;_R{N()*u5Q*oC)HBdxVev)ce7 zl$ajoY!f;Uccs^xNaYG z*xXQjHxoNC<6~kX2xmfq%7;u(lx)^qtT*Fq3zo6fn#wyGSz;EPr2CPUU!>k=ojgsz z-xbY&&9h@oYca-LhqPGNvLH@tuh~)2*cBX3V4aipHSM^Cdt`2j2|8qO?ehS-Ak~;; zdYqkxa-Zx@hTD3-8*#?+ODdd;T9n3qwc#E1B~i6oo}0Jt!aUr!u(+$>zRC>T6!%U@W( zthaHy&6nVjY6m#khC)Ry&W=Qy8@bJ7jA;bvVUAt#0Y)F93~kF=QVqqBhV?MrHOHVV zXp9e~*W0_|S|6Z1`aeJzZnP0J-^#mgD%LkMiXMwaf=N-6A8!4uquhVZ;hgd^P~E|I z*3rl@-wipqoqnaBmqGY_YVn*(-?Y$|j96)K28($)HPRWHW%6iq3$#*CW!YXRp7#yjqp68<_er2Xqhiso3|U znbug&DzwaeeAxV5CyjhPOQwWJYEUWMZhyFM_|wZB-fPw=>==YJ>S+Y~XB^LbmDUs% z1;n4in7|ljIg6QiS7Qh3bZOoR;W~AE`mK30l1WSIl(MUg(HBGM3>+6WNfkqkcj~PB z!nCGP@&yU2hoCV~b-DI?!(SA_L6R|wz!>=r-N$Y(e7mu@C{(J0LZ-Mu;F!;O7GJu2 zGkNFJVsY@mQpEMpXHVX`6Cm>j5vGSfZLueqk}arIHlPwZ@`&Z@$JDRI^)MHYE|wP9 zWjvV;;J-p<18A=RmQF+Gqh;Ia9wz{n-d4O`>Ko7Ep>Rg!Dza1>De+GZAku(8a5gQ` zSbDOsUZNG2_f=g?8nac!D8asY#NKi*3qZVA&WOri;*jb7>o9#JY5<&>*(Q`M=FkKu^tuUl8>Ue;4^z!^~)VC2O2!4;y`9LwM3+x!3UfSHS? zFO^rHw?bnuaP3?07~I1FH*$G@wV!JeYkg%~$xG&?&*!(ZHX=A%Tne@nYUjM_#OhaF ztWK{ypQK8J?k@BAebdCcXYNl2{GHaHTLWX$$6)}U?yRTL%%}Uy$G4f(b`dCPWZi8n z)1sI0@i#axh1HGkRu(IP+LaL)RbU?yiTvg#^3B+>5Wx8O31={|k4g8fh46kAd}th- z_Q1G4-I@r|My8Tt15)A_{S%r3A~Jok^q5OG7JOd@@I?8QuY=_4DebcTQ}5o_2u+I$ zK=^k-29D-E|E>csOZkCvNfD&~^<-LS{~PeDtcw{eldy#ObRGb(8%rrNzIx>4os_z= zQJ=h_=?M>b_iOuVnTUIocBXw784N&>!GP8}av0#*LlqaeQVznoAMKa{F2+LYuDUe& zS|s>osUoUR1A+M@cHV1kyh`m8-W@VIyd!t9NYDj(uk6YVUwGi{3`Ek{mLzWeE}OPk_Nh6wKGi)J!6S!p4E-ku(DrOQra2Mhl1jEx z5!OhO#zXtznq1@L3tB_FCHRSv8~_eXMfR_7?q}*$w3tHDY1aAV^i?fod2_!X{Gv1YWDa3z5Ae$ zZ)q42y0KbpSM%AY_SAj2DgK*vLNKg^J+vhRyABD(1?Zhg&WPAu%#c&w<4^0k$f%bT!;g@cVVFd9yjbMH2mHGqK70; z)&nZZgQSx-x#@IyNyW^QBvWEq{8%c-hp*zlxPz=Euo&p&n$UAge;I#D%CTTm+IjN0 zQIGGsm*be(n+}Vuj;t|opxlhc=+R&U8ClXOl!b%RNE?cpav-UoLuN^U1F?cZUE0wH!sv_ms8 zj?_kB+Vg<;=#9_S!H%8etlR$U-v=nZpWUXN6k#DCA>{CXsg*I>9{(jQ%KDC656a~m>XYgmxCtt*o<$zch>*{Mfm1Uj3 zb>E$qqmoKaQW?@R292X|A)oShqN`<3>l+Y3$Dn(&pn+m!10T{pAC}v79P{C{whQx< z3XXBl0M?^C(sjDHZ>C)QQ@@nvz>74Shfhf$vhw2q-PC9_`BDNboJZ%3H~!WI3IzU< zT?x|vR>r6ESn5mGECsG|LYu&q0mbcLF-Wmyc1RZyH+ynIP`bB|L;z}-dgi;S;pS) zrjWpp^UC)ivwa6M{LR#iGwgg)B9NRKS|ukm^dB2QI{!{m7!vg*qk92xMyVLMCAT_^ zO(AG~|NpQ7BROm|=h-0QKQ_Q5%~ffykVCQbo3sF#4Hz$#*E%~w{eQ9nwX&qQVGXqJ z(G7&xZ#hbT>M<*0h2C{TFD^HJJt$w(-ERS+%G3lNq;X0 z^ANQ2sWakx$8D}3d_9RCtQp|+%#cOZBFX+&y=vp%8@Z^SeGsgri<99x{|wbNs=xko zB$W}wnB5e;8*0PwQE;&*KdR$nkBXn4#ro;5e{4Wv;*CkWEG-QnA1y6^-P(wSBxO5H z&E-=Fqw%mFybW!61@}Ntg{?0oq5|)xxnYOyK)8bpQC^8s&%3zN`MQz1LA(^HZw2}F z!f8yMG2XYMO?z$ObRMBAuT8jGA}Hz6UEvcUfRdbr^uaAM8<2z4BeMafc%Mr-|HB5H zn$Y+hum=pQ$^XX&RNI1NHi%5L;?hIRpMyLny1qV`gx$2~eDgyP4aoUU!nsw^6y7<> zDx%^cigT*=Jf{m_3Zc$bgHbeBCst?-~!AkUbCylbi=`4nA3dt+E)#=1R= zMX0Wt0;tQ4%uweGYsnR&vu`m~c?rXcw`Af3d;KQ=F)IPvXUc)(rTM;yE#%;}pOP)|{o!YJXT zx7vRK6bDTta|U4mBr(N`7bT3fw6}|;|2#nNa!Yyc65kqHM$n}&L)7i!g=EpZXzw>6Ea)Oi)=OPj z3mAa+dS!AEg728N&K5GQ2z7j_yir%4ppJ%U3ef4C%^1A$<1l&rYw>EQxrU7a^R$&L z^Oz5m+m>7z+bv=Z>D_sDEx_CQ40;|vxoqwQ01;<3bjPIq8Zz7vx^FIXA<+k^J_Fgu zYsLWkw8y905x4jOW@<*#fQ^-r^5*ZY{{BHaWWg|8RZt`Bwq)!nq1-ZZw1;YJ6&gY` zOV9l!1>v>E%C3AK#|$9Ct;vD_Zb+5(02#fS0WnqeB#(8-f&jqT+oFqR4$B3_`+yDu z?$KMHAY+8|$b!JENoDJk5=>^Iv8DiHk#keq+gvQR4RxJ9g9&!L3{eoD2s0Egng}Y$ zw$9;zmm!$l7WjptCx@?g$TP;qqB!S>NmR@8egBL|eO;`?;sLlIz>?~>vmw3Ed*M{^ z*8DV0pE)=ZClj1jP!?8eRv%zghC>@&KJ!|v$mj*jgoypz2St%5c{~}mLWei))?c&2 z{d;S8UXaEH&`JnEBWQ(pzKf2Zq2Z0&VWD}J;pbA6DTim4Vc~^K_BF=(%KJ&QhHnF>MzXzOO(4aeu-o_)fGde$(_f>MQMi z2{S_6#SE{V{&5?8d7b z;vZj4IEt6TF1D&NF21}1PHH(xO++R15yGNf>P~6#e9%;Qz?mYfjVJmoPn!hBsDj(7PrY=GDp4p=SQyoUjGLN4XH#9BH{qM~cpD!nC zoNq{Sey7+KYJGYud{wuILx|f#Db{m`WA_Y__8Kl#M|bVJSAPn$zbpKK9W;PsTVDLh z$Dt|Os&ms{5XMW=W$Y$#?o8i|Yf=A=f0nAZbpH;Xrg|>4=gX}??{tl~uPiV4MFOHU zz(Vs@nqN!m{m`9(BXHmPs9f-5ksRsX{2#}FPQv}bsoOn7eU4F`k#AuwyzwumUv{Bs zLl?cM38KZ@z~GVF2V)ez8_D&2@1UZ>&LfCh>IfdzsC=P z`(7%H%I#t!N*>rNKq%QduJ`1I-1)HZmAW#{N(B(LMe)|%;M;%Iug%E#ljN``pL!_M*aS08w& z7j!RmGosp9dxwt$D{pKJynHma*Z%eF?rl=Rz}DY=LY}GWUl1Lqdq1whDg5ArOrh(q z0gz5Z^tT6JBX61U&R*|K_+{z^QY9$-g`R6y4mKa>SreD=^U9Xon2)pfcGm1coTyzR zx49JeUpAM{=D(iPJeW593Izk8#)_fyln2+#PoI5lDky9}qm+rYilLhS=ML&j4<(MztPH5S z5avmY)8F_9l(p+=_Dn7`Kms`mdGt1$Ht39dyE}(*!!JJia2}scX!Xa1P*!es{409?N3)?I>C(Z#_#wc2KyAiA22+^!Lr6MH_&PJ* z^WK9mNX&CX!e{I6SMLg4QV|}~tZRD@su-t_alg%OkHx4Ao5&4l;0Vm)0~a#ry1KtR zONjbIN9BERUvL?QAMb~}^i4cm+xQKt=t^#95u3a79jJipgD}YXP0>h3X zORw2kPoD{`?ua^4)|#QP%6N#TE(zkGPK~+9DTvQhnH0`?SdZPs>)3w$e}wp?mfnNGw?8mdY?MYdTJHV1TDOW}^`2(O2{T@FImUtAkX*5n4 zlsDiB+SF@F;*ODc{P6MPCW$A{1D}K&+C5L^XWon&_#}YOlT3L-NM6NkQ)8{jX+wP?XAHv$JuXZ>-X={T$|F-cgc=K7!p(RNTsJhu<8jyH|#eKJ?SuEw5&zz4+51>{Mjdmc{MytLbHEwVchjfXGW zPL1hgY}w~uLu=~Nxh4tM8@$kNtdhCRHk6riS!zfMovev`FNf7AO=29=Pl;;Gqm>Go zNtLhn$z4uy!U|76lrnA#3I*%R$nj3hN!;ZDSL{RRPNe2=wiP%qQ1M-D-aux(c8XCd z@Nk4agFn~y4wJ$#dK#(T%o)r!iD7gG>!c*T$gP0IKq_<%evywki%(uFH2KX8%K^C6ffQ}H z6&O=LD^X`v`O&OYUvUYszyQ67o*FUib-ABH*UtJrJe(iPr zlDhANV<~*-Re{9b=FP^0v=KyONv7eR*|ym2%gu{{)rs2FLs@gg0n-aUA}1pcmzRTg zMU32_5J;7*sgwx!$*0rH0Y3wq{tn3oJk?bndvz{TeWK!b{gaWrzQZUKxEf9b?d>gp zdt#g=)>xodp*jFDkUPq4_IJhnzPy0eo#EQ|LpX^cLgZ$W_Ny)MlH>}$haN?_+#g42 z{~yhlL8MT0{T_L140NUWPlL#l20Y7Oh)Sp~-JeiK$uK|75ZDLiZloNDuN9Ff|FUiS z4`Xx17rhGI5oWss>giDOCwenXUpEa3PcMa!hO&QcWmBx9Sz%|Nhg8&pscH{czsYh5 z9&G6^(EoDk!eww(V5qs;wl;SWieY!IW0ZzWQB;Sh_F!He1z+lp3_r2`K_kM z+bE4gLjsLMnUl8z4?<>wuhO5bM?<8_6THg?@&@=$#BNQLBK>gDwGR(h>$O~$a z+T{ErKoI}qsP+$k??~V?wNW%`aeVxv*QHksB@QQK^Av({c*uPPm6~vgXoU-d%@;~$ z04ebbcC6H1JEuvT3L7j_$N(Pb9LYPX`?*zLRLS67yTOMey#u@k{*}u5W22BZ#po)( zczosk<|sYPE82IQE(iM8A`FV;1H>^RL$99n{m^^mSLOCyhR=g^I-vum<1(MI?A+6- z36;(bBWB%YEd8w00-l^YH& z&usGXyFa!p=S8_2LE~4WY~w`O*;L49eE9$-pFXnyS6(QWS)@w=Xo7_UKy+dQ+9yna z$A3-${do8m=HC!-h}@WO+cLG8b6dM-F1qRdO5i8ar<69L`oFZTYb$ETfE zy;Kw9W_>YqFW0I1YZBA2al%FaGG zHs8C;qyNY%e@x!|*uwt!IkRq&q(Zo8bfApc(&RO?80|`Y%8G98sc&T^>I>xOa(OhqUB=f)lSg5CmUkAVnd`%ZK|F+rXF;Wveg2HJu1fB ze9KK+L)qj{omO{IVx@n}e@FoN#Q7rw?*;=Pc2jt$fa=6LhGc`HDQx0nW(j>Z(4%2Z z5!)~M%c{bu;w|w?kyQUz&sXJw_~;SwxbNJ= zTgACbGEl{9SIp?`axJX?IrbQYzW=F@&Kok(A&j*pd^?K$W%h@W?WoBhhhvCB)_&qB zTe}ycSn+j;ety_meJ;TWBt=X56|H#?_vKDDiN6k9u?o=*0R3NVfTuw^9Y2{3DDX1M zW|Q}u>5}&(k0Vvnl;!~oNP#G#P${$3PREjwN;9cl1Y%GuX0y{bP zrjEf5FOY8+g-e}euK-3r1sq;0wb-E!YZDZ$OT)ZJ^Z32bI6v-vc})%Zu_=o7qE!tI zQtdU5iu^G3@Vovom1_7H;i;93s_@STLi3$r-{+p*Xxp55xnpTQy;quQ*PCPqT|Rwse1G|! zY@hs%tu>z4wD>f`s;7k@xVbd}#-$OW{`WMQzIrL^H&D$uk4dHgZ5Fl2o#%t)4e9;} z95ipT+oSQ!6on|BhOsbG(lE!>#`mHKL28-NEHUHIk_d?S9G~vd|qtlS)%T^5cXT7Gcn0Z{X<*a!PA+K3HL(B6jejJ0MeHSY6yXk*Z70Lbgvb63XcC9MU{dBE7QTr5MZv8S%g&3oc-Kc8jJv(^iEv(+@MX;ZTY;j;gm4WO_o)n{qiPf2UJvasK&!!Z#m`EPHNc0l7RNH#&s zeDM#t|Gxxch@Cg%rBr~zkjR1z{cTUC`}5jj#s#NyvYEyvypwuKQ2*;C!^5&L*_B2(Qnm6iS);v!p9?yGfH6$_f<rHZaV!ev41zqEIraf5748SGH(BT ztnIQXkt$(^RrTULK&MM#ta+2L#m!DkTN{CoIVQ;aayFP`F8#r|#uqI01`Zjnh;S+$ zR1#$eeL8%s{lm*(75~Ir9A@eHtSc!fi=g_uwp>qUtt*+@;GP7XuKY{Q;dh@q9Bo^H zJ{FeXJZSPL2`0b0KRr))>ZiYcA0dRx=RFgoXqyeVUiJB73?rvP&7DQnK9~3Vq^t{FhQHIp;!0do zG6cARx3~R1mlJLKeih?{2$R73>A|ZJtwTGqiJgHSKnj*y9iYduaC_;<&p*Zm70c0b z$y4q9sy?_Sa;=*Z14^mp)@G;AFsfLQDu}7}sL`#4x28=uIrkf>gqw|0S=;p1P{l^* z!7843i}PiV{#ktl0PpF%4f$iS_w`tW zqnG2_)BT>vR0<5uO_%4;dZ_ep7rvKe;(ET~izT8Z{g7~F_!DbQLF9Eb z1$W)UErs`=BPb2QGG^v|Wz=H`)z{0UXpKufL16i!ESF z`MDIOwOw$9;iC)HCxo6Zt-?&-SM?O8^Yx)evO2%F5f66Ctp5H|Ym0YLet-hEBz>uo zTTP26UW(^aBQEigc1q&+iJkpE>N;mdIFEzC7En6M%e-_6)Ut;gYhI(J2c17%J{kYB zy9eqMAl1qU>Fy~eyq(|{0Lar1R%;L&%}-l8Xk61@5~>Btr++50>=?Lr9G)jI3FbJ) zL3(z7P+P(UiTF}FU*PhY>r`jtNfpr3p^OzW|cPaB9-lc!WIXM?2N0}%N z%hKx%N{;1qsTQRDh5*u|b_z$ExDWXrLRTY$NZh3+wLoWE445~z zC{4CisvBi63?C-p#d36fVc;jZP)T_j;mJe#Y9Ji7g2N#%415dNr5&|mKCq_0MnBSM z*(WB?vbV=r;(ZB>f;CxF+Tssn2B3F9J)}SewvhJ>(G1j}Es790JIR{e$lJ+dS8+~v z!_v!bjFxjJpZiS#=aaBGp@Yo?2CjZ9t}T55=mQFc9+d<%MB1iwhYYXyQ#P=f9Yg+@k z6eE^G>N1aX8JOzi`#b1FHr|Q10Njn9s3IcEYYYO9;c_KM|1mt4AY?wCWr852N#u3} zQS4)QY5!~fv+E(n$Za_@qbNBccJzl1d{MzYO9j5)B7*_uLlD>xKDgg zA_UIx^)Ah79=3=h&UPvDTBv@=k9>V@>1l3*Fva_mQsqaB`Cz&xPq4nC47vC}RKc5kUCA;(v4s0POSAAq5yFlQ3g%E+n?^W0_<%ePAnfu!3bE-p8g;QBiqX z?Lox++<|}>!1K@pWoUP?mcZ&*4X)*9X+crBg1B%&ns1K!C+)NlSgq*x=$ne#(qSwl zhrQp`dlV0w#e-jiD656jZPZGbbO)_G88ktMhyMEyl|VT<>+va+u#0(%r&B3W?@L z9-Q`7-I@Sr3;|53&oBYf13W;hdRl+Ng(dXlD2h;(Ao*5C?S>z7jQrf&dYo+@l#*E_ z?LiVSDG`k0t7tNF>o6))H2&JmjEEF8oQ6~rIAidyVw8~Eddw*Rh5ZtbJ9(vr$ZZRv z*!AG8WCS`;|11b0f<&FYHKKTGm&i-0heQ*2G#mWDVI~s$(%}GvbbnymamMTlv+*yR z%VAFx%k`D|aN~FZ>WU?vPkL;OH&9|zystrm6a%!+mv~zUg3-^Mk}Wy)JyFy+ZcfkM zToyZZ{PC{cua;%_@h-|al1p;dw&B_3uu$WV@7?TnK|efckpe7!1b0CQ7|DM+a0r%D z@m7xVR(tNPb?hyRqhMTPLpMteN19)1<)eGf_TJp{=ML9# z`X1<%Dn87AY(VDofZN9b+0WU`i7|}<{$KnPDpV5gsRY*e2R5k0B<+0kq2)nt0IFC6(Z{sDQXCTGGsM@PSIm&!~{!&qK~xL)&IQ;j@PEYL)QVQP;~e|HsDvd{DlZvr-a7QuvepjS|wMzRU+#U zk)|av=D#AjP}%fzY*bEPi4N`?4qjBpI#zcTZ!q}I9y0Un-w4~G-L9fbndP~Ri3+)( z>unpo*32x}dc$Qdx=fm3Xo;8J!KR2UTCq4bnoZiGz+9N(X6Mw!pK{VAPQL9Q;+@{b zBBC!6*gkw?@~Be29KjaX%of`nV)voM>GOwM!%lIX7krDOHTI)Z`ZQt7v}_&?N@mF-n1-JLD@yHJ@UTQRmsD>h5xcac$d zra^2@`#?G*D*0L`AyhSE??TFxhgcqiyIje4IR@`SASF}}6W?DbaQm3^=2vpu$5dZ* z$bKHYdC&7hItL4>egzr^LU#`(Qt-0``TJL79>CGy&7qvF0HCF0% zmpE&jUetMhs=D&2s+Gt$(2fgJ7kZA#|BnrLl%!stdb9o?8*o~G)xbXdW`nXm>@SGI zOZ_p&CrvUN!1Rv|c-*S~#QWxx?t688r%&wE8;9@JzPefE4^V9uHhkpNFrJqfQWIbN zBu-ksEU?Kbu*=!}{e}49i>HLnW-c(<3}}WWw@|qxw(7U&OtmEIx3U?6#6aYbG1Z3MJJ>uFV<4`gh?H9^Xp&A_~aVXA1enEvU=_%LFYH}i|`)XV_l@}1S z#7EBt_+ePr`FRvPpMrFsUHbg&8Mr5p3n=V)PBYL$h(pz5SjMV&+X#8KanD>_B)K*C z!LE3Y&!TW{e%b{TqbvFTZc)|>Oan$_-${#j+2@K=`q;DRE!dfwF~>SiQljUKA^6n869u#LxCv zmwHA|1LQI6ayIPk`ijsyazB1NO!GBjd3=itp!8&V;ej~8@G|NRUs@RcsVBMnTb}dF z`y&no-Y@bZ_vIzNObPN#eg7C9Kp_7*vN(c(1Y*OQGEZT=0Etj?Qpko!4TFe`ElDWn zCDyL$X&tQ@6CR3-=QG2~vlNBAEkmf&Ls>}soYpNAN!M-0ln0>3&(L{M#-GbP6_ouI zK98uL?;Myb;Q3I}_pzv#@-+eW*OmIXD&{vMFOq)F_x{{7{m&rO$B0`WD8LKDTD?^I z%#og`nOi7lLi723V_tsl1OTW9cxDu39qw~m6HrRJOfQ#YQ;FPuC>NU^b&6_wqTUFs zl1M|o^Q{uaT)D(k2_%)!wN-InCaB+yMEMk{6vwYn{UzSIh0=eC;{3Z5$E@s7r0m9| za_Ob%l?0;q;)*{n5V#0#1JMA)ccT0e_Gf&J_+lJ6Sh7$X12`Pcd9<`*8SVzDQJNMxxg)KiPWfGge<+?Yf+^?A0tYUf|*AN0Bd zyfa(5^M!YJt#WrK;aYqH!@eFDIrJZ{$Az5KM+|6o4(xy6-RC0itR(DiB^d0v&vs91 z5F$`=e1KB_{`AWuCY>J~q~~UysJ|7=#t*hg{3E1F6!gJ4T zAmXpi>eFVOKb>D?`mXTdubd&UXK(q=K|}^%`3gG#IBzpSP;BB@Amxl{K< zZeHQ|`JenTb)R%@b&>)pxY7I(T`_HVuk=;uns zPMLSoKuK@;(UfckR3!TFh@sH&{&Jn3n=tx2H75B2ruU$@JL142#-jSoSsvuwh##^R9xCQs`A~2)cjYo#jr5oYPE=VX$eC2*{#zbJ6viMK(hrk z6~W9kENo>|OxW&u4u@`4qC9)G1{75+m3HNCgRYj1vfgOEo73GGwRZkUIMRKjDDDDb zu|LU#nHCeX^{V*7!B*qmS8aDd#KF6MJJ(A!g-V6^crOcQ|GF4kL(jYffv4HLmwNL@{#|a3aGmTd*XDxIKr!i<;@Is|9 z+KLsVvK!a(r|XL)m@4#r5ZHx&5+7H>Q z@}-Pd$ueX7$&yai`hV$vIG%qW4FH)U)o71=fcm3Au1olaa4CRFq7`9mFr}A-PkB(P z{)|z41tC9?t2O1bgv*~ED$148RZ_PRBz2gGQ$K03d#CJVO^E^DL2l9rnJJ9Hq`$Qo zO#(#~c2+XlLZzFJtw57N=22JA4Lfkl$;uLp(=B z$K94;-tz6Xx7t*?9n+3+(tzH)U=}^P{xG-s^l(cS551=m`eKXMoZ$(jYcds!SM3oW zu!xnE>4t>o1QWIeq!^x<*4AWEsTXyJcb&3}jfi`0d%)GplwwA;QjvOD8uJP<*?eeg zy=+xZARDGS=dp>ST&gHcrS;qgHU+onT}(8yl*EjMBU>l|!9CnRETAjW<8#PY34NJp zpdeLg8ZbLC0( zOe0&Q&IVJjT*q*EAnEI*mU0F_7}kd#W0H<~;*K;#?p_E6xeelh5u^p2Pe!SkkpuKu zp(#RARTK#OOoH?}=(Nir*bmhBZvfVRF;!$9@;E49fMo-hHp2NcBlHXa>~&52IENqe zoYhcL%X?r|#^~kt2O*-3)hx{!!%~5*Hd>fbI))!uQer?7e`)?mGqr9u6iZ2NU}ZA# z_|V1K4^XDpBWyT*0keHUzBBwqXh>aZ;z<_j>3$L1Z7iR{8iI8Rsukp;c!lD`V=1t#j?T`V~Kl%DApHpEONE>Vq>177vFjc-Tyrr%{(a< z7FvkP5JS|r)bJpL!!j*aKP9QmW1OA6VIz%?wDvOJ#V5ev3m!04o)n$)gJv5D(n!tk zrzCBtIK{LzjD~BNQW>nv)Kq(?oLD>IVnGUJfF1zw*#C#L`+jSx{~tVm5)ueKAiaj( zktS7o2PrDOSLszix(U5EL7E`FgLDuOLr0p3NC#;mO#}o)K(e{-+5OCSc4l_3Yd8PF z$q&hSm)G;L*B@xN<#NSet*MvrNT9!n{w)$UWq}k6IYYS|IV+Z`oTLc$Wb&cSI3gR< zQq|88q)o*X6R_bTVuNA=jEM@R+$ii>jv{_@Cw)Zbm_g+fI(xgQU;A_ROk;w7or6vq zGyk7d<@hb8#DpS_@4xw8i&PQKH>!*GE+D?&my^CJr(risYTb)O}n>FF` z!dO6i>;D@YFcQuB-`Ifcc1(sOsj>yKV((uz;K-@=VD(=%;7bXJfrZ;`7R92~G$MG_ zC=fBrLjN0vr_SMP^xG#+AmLr4=)Q0=vyCm?X(P0qB%L_KSy}FzM`I*2(MHdGR(iVy z6!YOHXx0YX9R;+q)MiL@n8GGrxa1=h-ZXso-9yfszj)EnK(foB9ih?gu+OOtiS#a# z#6G?;^*PZtOxuR(HMakM;}B1N&fQx(3Z-okCOZ}>8;U`|n4DG8)EbBB)hBdSBZ+o| z5~aE{uoc}Ye$vn!VJc$wIND9^WDOw*@#Q6#a@k5|B{vn}=RbJ41fNI%XY86@p+$CD zct?dV_*38HX}^5ebfm`bB60U8cVB&b0GD3QMFd(U7B1o=C&>m$e*y}Gx9NDAzY+OK zo^7?(Kg>uLB1!KwMct!O!snEs&0NSCWy^f!1aQBMFHX4&Xy~N*qM>sWp6x9<=JEb# zDD0rmpt>J2Rr_Y0WcxA}OO->(umv*C6b+{BhtZTp)kA|+=S|v{oWb0icv{?pVXu>a zh91y2FN|_(Fv-o6SWVl0W%${N ztw+OrLqoUO?@GDeK}9njZ!q$Rz8$wFd5R@C87|gw+0oR$ULD*|1cClL1Mn1316Ux} z{|g4->i=Q@t}!?NRRTEwA0&Xw|CI!AzK{9!_3Z5I*RNlvr>B^c?f+Q zZ{L3VhS?jyeDC>xzyMCL6u`e20A{@tvpDmw1d#s!C;^OOW}-14pJB#5R%b{5BLQGW z$}z*%|4IO9|40B`_c854m}ZXuodnR|-;YM4-@kv~+uPgI)ARQ2+m4Qowzjs`*4F0c z=D&?{{}=$()tE{rOg%NGmJCx(jH$xMRN`VPz*q(VQwm&Ga`n``z)Aphb#?!h0Vpjk zEh;K{{rWW~HwTlNg2~dx#00hFW@FR;`T6z6yQ6H5Ol1Mq8q zb-d%}D!(-jA=87-e;5G0xyue{%@(aVWHIni^3-8WPryE)Cg|zsslx0C5)U!=pap6xUhDwl061AxB`6Q$9A?G7P^55Tbuz_%=uC)M9x zT9Bkes5Jd}c5)nsh0sb|d84oMI0CXN^4&bMSOc5>IQ|y~;5Bk>&q|vBEaXT?TX|^e^rhdHH_fsmy(H@B1^h*2?YwkpakaaA&*!hXEiY`lMux zo3>tNm=&HgU1>&^nAJ2AL$F^l*(R}uhY3Zlx6T?Zlef-vl_8+YCg|EX#->6LC;>}I z)?35k{D$VCX16a@YqoAbdd}vS(|eYbc;Fq|zF!XB7@n9nbbk=Z&+59%a+uN2+qcZv zd!fdEGDxU6G1I;kPI#;hCe=QE%lyXexQ``~KWAXV^ufs(|8lMGz!iA9N!#j1SxFJ| zq!s@jxarZjiYW7-khXHILF*?Du2*MT+}L&dxW2mO`e$z2l{Z@NGg;vfp;wyvQ#3#L zr(qIo+oDR?4Rt>)x7V}n%i0}h7aBTz>TR=u-x=3dIZZK>kLCzaVd)D*1!4M2&`HaT zO*Y}Rz!eo`tG1TSlltG^a_F6;G{b8L2~0y5hydoFnN7s9?cR;psDBRYA*3`%R8Pzb z(W)VRQUxaX2+&x?Vx#^8Z;IHgr%i#ESzrq4%4aP=t>wX8;zY`9ID%z`pp z@fdPH@L4;}HXE6^i4qGo7-F(r5(ekiIK@5fN%d=FV}{tCEr|DL7?4V>d@dv~?#!Zy zD0@nPj3jc>7@%7^juA0HDgk)Nyj6ZbS!_KAVT-4l82 z`tU~2Ktw>=18M-s$S7k6a2uhz2Fi>wyNq1jyP8pTGpt|BG$e;yw19OR+EGc+nSv(w z*bf1-=A_E|kCn!g{d76Hg`yQMG%#H@r@Hw7&@bQF2kioG9u41&EfLFlwi!}w>>B){P}03AyTq7{&_f}mB|M83ote5t8W0Yt7q@hQ!} z>=1vaG_|$nn!z@8G@3kGNZ_B~zn{?gcOj`gK=+^Ef6)**$xNL8U?gR6(Kg(#7#sW_ zfP;Pd1UFAow}{zmjQuqnXhlrN@=pIz3GjM?n;VC<%bpO|JJUwYC00@LMQoXi z^6X%FKaaALlB~fnZkc>*&B$})T*FcL+%nR6mIi`6^7hRa**E+Bj%`Sg&z{OK+dG?M zExF$Jg$x;(CbBk_@8@>e^`d*O0*B0%#2n@zpp>JQmBe+D zj;6w>D%|_)AmZ||!+%;v{8nfIu;UvKhxSsJO^t z0-vU^dIlk0KCcnmK|k7oq>R!()M%SI?{8!7yN@0pmT9NO%B>0G0^1u*kaRU}5)l+N z@dmTJH?lz{EsBt4eI8BH-WaQMXh%=K@Y5dENUab7Ww>6PP6=qdn-)c~d$qI>fQC+a zqufKTm$BbQ=g8k59?$Yuc6B?t#wUOHcVDk=i%ayp@z`)&u~|EMDbf4;ohNQ~|Q&36UTu4%49e1^}qyBd03GfskW z&r5~YaZ;t*kmHF4VrGccine;6Fb}J1vn8ACfVq@Occ<9DhqjgNZ3FdQ;oY*U9?!d1 z`WSz|U1nVNx9-UP?ES30qxS?cGnBwW%CbYj_ zxs2t$(R|nZkY_*&<0w~&Vw$VuCTq}I^UFm8GKI4N8d{+bfuu89lZtr>*ah!?(Bd_HY-eFGP zSMBM%DIC6ouONKI5-*x?RS^C0-3`8ho?+A$6Sh!zthbU9G;NnV+Htp#0-(`H;szpN zIYl8*<^xar{04mx#fKdPjpc{Tlp2ge7AHo%ue@-xXhobnT3hgGF7RY5S@^ z#-1sDXnimV0YuTH#*NUc^#_k7g^ajEz8PzwIwgG`gD10a3&i6Vp)u{4-w_Tp@sUqr zzzcUFoyeS=c%mx!pR*Vrj>i~3aj>dB;Ra!;H^JL9GFFp_Q1J+|jo@JfIMF1oaU<@H zaAZbKq9rO3&f>z-^hn@~^Iu59Q^Us+S&wD>;gL2Z2Ss=_lHrer;;4l~*4UHRTgCQA z!r4_4nZHCh;Kp~+q%`y;l5Qj-`iwmNg9e-dQKyWs` z9fMDs5z&-J{3(t1B#nzKeLN$Y51%YyQE%M28da zMq54%>BxDZoBL7_lm+4zy}wA#?LyA0nW?NPa!8S;+DNXb$;7ls=U)91X-f7y7tWbW z?qf>+)Fs>BR0yt!FUbiCUd-ZH%&rs8K?UWK+UB-OIIeBpHQXcL^v&8HNgs`lW)Fnl zrG1gEnb)S0TU(r)Lz|Be%7+#su<%0R-U|UTex!+ggL58{ZRRjCvsUT_lrw+y?MvrH ztOd^9mBF1sUck7?oyJ-)_Xm+_$Fuz{ziuG`5A@QGR;mu;qSsJO*P8q4Lr@{kL+(dP zoJW5OEl)XY!LQFuIjw$auJEL9@hCY*Wv{orrnP;^{2_DKw1}a&Fm&-1xDPSESVZp2 zLc3Ws&%?j`Hm8_9*CbjkB_2PGr*K#*9+$3!4OJ9KBf3`o`p;rUr6!!Ch)C$I5RJ6c z8q6EQTOuw^#%{)4<5WydP_)yL)BhGMv|n0r?}^CqKUw-YBsBc(D~YQzg7i|(u2Md& zY{QxyLNZ_g9S#;MW9EhP!%1q3pfYgWwcmNV1m&(~@JBU8?}JKs2`Y_h;3~)nwIVSU zIty7`0`#%py{-zRE8JtOlvBCN$}F3{%QTkG86T5QT!tXr7b1=nDngl6!-cDi$8ut> zUi0w61+Gd0mrRw9S?}n>FKkF(dqbo2Nz)B-U0kd65~|TWl_t`)1_^LQv#LWys(gKH zzC9Gnk0N$!o)gp}d23s1u&jA$K~4E#wpDSLRp~x!xfXo0hyX_swliHex>nWhv`!tdWj^sJ`VdLg25x)Q8NfOai>vtQ3b(BMVaaJ5u$Ee)rq3pq4SfJ~gk>sK%v+WCT5hj$#=2Uxms{7aTHEN_3<#Ux=1oO;tx0)pW`wmCA#I|G z&5!7t`r~a~^P5EXE1eSC<@1dc3EMqtJM_n$B$hjT$6Nf(t6j9)tq40q2|M?s(=7QK zpVG%Xkm<}Z?Gy{?OqOXwb{Er`zD?ol%;>Jj9B&Vi>55w}unTGO;p6&No%Zbdtpsh? zr{LzM?slwntQJqyY|>TI+(pp@!xY`)xA_+^upww;g_}2s<{R zpRs@e8jtdGR|8*0V{J<-hOjqhxzl_p+`5($oIqv@kbEh+rzJ$_IE`b2CT_;^0BDk0 zI0QScwChbTgRGJDhN6Xt!A&^7gb0*vU{^MFFvXHpKJTyN)%m=AFGJe)#vo-OlzVPu z3}|8-v@!%`V1R;Vwm>lOaQ`&Y_m6OIyy=U*iE%)LUGVaiYc!0uk4d^u%AzmE4PSCD z`g?bGYAsp40s;1w6h|0#fPgbLlH>y*Dt&@Q1xguj(uhWY4NlmNfTO3iOL0hXAG!&W z)2F))=)?~URS&pK42bcyC*<_~?C*x7@a7Z*HHZKK1c^R7Tx*^9x{-9LNEMid?iG<@ zj)@!xh?6ivaQkD@0x39Lg38f-SUi4Mlc#$#zq4&Wcob+DFaaN@T` z^i*)-`ZTB+f^dFaKnP7->f|~AA z_i|7W4z@f|>`um51i7h$%&Ze=c^ge16H+U{W4uYM27uEvJV1z`j0-M|rUBptbMOJt zo~airQxX$XgfBZL+&f2mhD|!7|MCu+l-^?oh`&tZ{J_CsW`$gM6Ig8${KRLxZ`kGWNl)T7qY7tVl*1Q)hy1BE^cox zzSfy}5k^j*RH5pzXdky&{A6NiV)$Uw@#DQEyMTGZ#HAPA^Y0eseqobUlW)lbtftKt zTnrZ53trX~*wzt$%;A^tJGPDzSmvbo60?CGva}ren>t-E>m4Te0vWN7*9yWysd48=i$;>@X~g2$c|;+dclW%OG=4p3ti-zAKPlQ;_5G1v-2N{ zJFcch^;!5wSk~XZia6;&iu99A{-1Ba^I{&NS z2FM%=OY&HF;PI^M3B(yk4@s?+*_Pq{;^D+^3^;YHu-q+l)ZB#NPo{)KN<2q48>v83_u;5p@V^UDq;6WqFJU{@I-SoWLGPK&{ zYM|7cwm=nqgEwV!Xl>N-eYNs*b#??gfH!~w%&rjH>>c0ieq!2M8e|&B5T(dfw=iJw{IxN4f!LcFODGI}Df?^cLqBJ+X z)|M4gHhGIdm~&V_N|v9XV}Bvd;MCEHfnMb?iRJXn+6+z#5-P5by9VsSHnwhb`+mP0 zusp$AV>~WhZ2lT|ylJBMr1+gEKy+wBx(X+dP5JqJa;FVLzsBzc_SzfMiM z9_4e)PO1&nwUvI}pqje==$1@v+CnAmmx0_yDbtyd@I#GbaN`)`&=_FX%CA z-l;Ew<$mKC{g&Uqs4rM$E(T)+kBw5zp{X>!UYARem$W{=^FIE%{6NX{o`@Ux6ZAFx z#e3OKk3W#`Do76Giifj`W%v1f7^B%@DXs zU|ubkU#)p_?KpIu|Ks|N-Y@KJ%@%+BKhD<$*6o&4H+Go!HxI*a_I_MBdr_*Rzs{5X z&3t#Xa@T+A>*B8bt%*E2LD8O6_n!sp{77b+toOG;pKq^6{{SF`bu@}(N)nNyzo8UE z%qYhn2*)x2l(cjz&R7NjP|Z9)D221BXK=7R5zF=6OnNSA&>N+BGVq>M*kf%l_wje# zLfNoe2pz@FM4l35bE|FZwnjO7uK4ODg{x}yV?3&~*`EtI>E!ihbyry|+Szu|$&B(b47po&RetpJ zMu}4OPnuqZ;ii4oGmY=Fx|<)9Xws}XR{JjlAddMsrzIeIadWTZ%c_3Jfx*K%>$1eE zI~b~(;PwZ3;|21uOshd2r5&mCZxSu41BzEXZudrr)O|8Ln>q{y!&v;!f2_WbCCv=e zKUn;D@b2fF%=F*8IyU>U88KJa@#un?M6cdUDu+fzJmyEol~>1Osc#6d!L}A6lt^T5 zcpQ!Qz@*BnS`Iw6P$5-H<0O)yLe9ZAJqHf0slzmr&JmN^Xe=yWH?s>*<42t#uQFxG(ODJP;l+Ab5btj>^zpn|~7-@fU_nkHFxNhsV zF%$tminG(fH%)osp=WIII{HG<=`n%fLu-0QvSop`NljE;lH&S;ZRDc>wkKcm#m)TZ zvjiO;Dtx_c7QZzt z2P7`)+!o(3d%PsP@tTydPIZ?J3Ap|-t&Ycg6uuL_;Avxsr*-OPgM0^_kp12huxvfX zP}0{C{Yq)>gH9;RFpit#<)h?EBligL;)=Zz&se#u3}5T6ZMu->B5p<771t+X&wt04 zv&bQyM?{JLGuvfVZF}*(JXSs&=2H1F_-m8ISxBkp<><-mi7}xz@9$I{b`_$4q6nHo zmK2hSnBdb$L^sny+Ug`>=y{h7Dy@loAnv=@Hj*LYxXuOBD9|zoF zNc`Je`R*XTf$L_=%s_m!kCF315K%fVx6!2>H5FN~kc9?R6j#A*F^$WVN3GK@r!VB( z+f?2FhPUJs$3pihQQe_9$|2`HTsl2T{w*p?Y4a|hV0p5^04t#O2}moT&h~3{Bthz&AP1B@0RmajOG$K0&N@VIxP0c>bXTDQ1DE{tY`h(Ub zy*Qh4uFj@(&0p;3&A0|3yO}KLXLd!&KW&e(S%;xoj!oa(G((Ql7ZIU}YlU~ljj0}M z)Q6HG@|}l8GjzFhkKuP7JnBpo#;D~;vy}+9@hCc+I=pZp| zH>{R5i~u>Dv6V=D*|P=j_vBEW>xmlf^z)kO1e2d~rtYeXJo5gW^)l`W<3Yv4wuCRJ zIa0rKcW1;v9yvwmcBKMit^OP7_6E-{_4nLrY2F9FuaN%IAXKa(pCoKpGv_ZLkUXjV zRobKq;otDgqe7G{pPVb|J1K^(e%}Bfr0*l2YgQDlvmVMbYTv*<#x5S`1Hg2$!m;^H z^`WDoc7EM{R0Vp#McRJ(xNWw!tC6qa^zF0ZyvAg!2Y1)?#DsxX&GrA-iU&wDX7U#udwyFt#!> zQvX?27)~*oXMrWvw5KR|b(KF5o8HJ+M=NKh z9DbfVJ`MdP$O(aA)SSoNtiFktchP?UOV*Ita!iyE$pSbM4lHnzMte#{jR^kfbh5|J zr9?7lB^pR`WKfbFEM_{EhQW80W}cSyvoCgJ4M38umy&?V`sG_~K9!N1qCpjW54^jR zB-u^+V#Pfot@}Zq$PH>T-8jahJ^--k)7HL>B?W|{LRTbMiaUoDY>E@52Ii;U$R*a| zZ$>`n1_3sgc=))iDJt9!V0MOn`S5kXj(T}vL@l5>>z(@(u4}MUr$S4)tcR=K_2Q?7 zfc7?>A8uaD%U|UJI{L!gDefDS>(l&h9xCt*cuK$YBj$Ir2f`(*HG%@@Y*oT-B0>4t zFyfbOu`Zt-eLSEpY0w8o0XUz5b)5TVf9*_+dw8Zq&;m%7wEHWOh#6S45~qZM z;;X)GF7==>!(QK)9V_4N#s*C|%011SU)hlu37Ycn{gvaS^u{L#=VP>-UkUZ8 zX#P$?3y%_#@e>t_pnE$S2QB%O!0)U`HLnrEdkcb~EH;>bb966$3hxDtF&=fyH!RcI zVF-K=Z4jMvZ3=-p&cN3@Gg`8DrF0&lY@;rS=^7nRvzQ;0zli!rgShxdgWv}M#z5S= zSRzKTYybeG{?Q-+-EDgW)n#lRqg-0tbzYRmNZ2jm!9FObpFtiGCwDChz`%-Zy(|ZH zd#tZ~P`nOtk!%Vad*+q1RdOl200&xuBMsNMv5gcNW8Dcv2t_@m0Z=wT5cY2y7Wur2 z9jJ=LJ z1jYvJMl0TlqsfU5RERaSkwj@UQGQmYZB@cSeQ7V+e#m7)d0KdZOl>#c&5v!+ey^-(M5m*nY_2 zhZm1xPO$8NGdP-cDk>D8@oCcJgQ;g`Q%i%|1wE6|h=^1eJ|!~pd&^WU|5SEbtl@$v zd-~+jM8nUUk%Jp<3!-$DKIBem6aYhVBXM9Bdei(5vWguWw(!nrM9-OEdF(W>%-ZMXCJJ1;j9}PUAC0-1|&0NaK-4a;uR? zT-azS${7`w)})(dSZ*-qU8bY*clPG~=b5zhtixDaG=NHbFc$SmUv@fkJ=Sh@Fj!;G z#M0<@$rp3z+zC7T$|GDjS=^q1j$zxETneLT$tdN8Shdl4Wetc~PK>XtvGoIE7oErV z7z?TY6d`FeF|p{$ zVb=LBo%2U57bA=@ZH6P+WWQP6ditIf|s#Z@`4M< z#DB!vq_IA>#F5l6Y*;nNyaJoUHhUJ1gl<_z8`wY=eOA&Lr-GqOqx^;*1ru!( zmW7UqTzBFuxFHb;h=t_x#=Cbz3y>cc!}DRYqn6gau&5b!k_d%KZuocBFWM1p6_spRiUeLC=tNvjuJ>54ep~*?5f@|vjxYfSUs?kV zokI&yB>*7T!1JxbBMZ0Mv(%xy#aD={IiZQms-MEI*jUxUw-$m%NJb~~S(Kfxv$f^= zV;5&MQLaLO%qTA8$;NK7QIXK_J-WD}=w7-hD|+#Gfhs(kg(w{$COB|O;e3O+w``~= z_98wS1I`1H=x%UY*@_>jnN zP1XcMXT-OmUBhE1Vu-v<}dXH|oR{ph1GB!EQFuIWJvAi0w@i%&r~hUku~V%o?W4#c37J zJhyV@^Nhob?21Bw%>SFNP!vs6`n`PZ8)?x_dw`qknzKKNQ$211fkrc43XD|Yi<;5; zC~XaQesk<47FfV}7&2X9yYFI_vs_&w`=h)%y9Xe5~U=+W5%`*9L`2#8#^i= z$2D_!w&)zpRygOQ@D!-xn4K-=b!@)MIS!w~F)T1x;7C-3o73>u6CUPh8|lie`w{S! zQznaYHP0tuOn%&|aoVw+M$T0Yc138^_k^e`$~bytWJb!7C!`A0Ka0viO)TI4+@LwA z`;)pkSG5Z7@idOCP;`(9G6H)@A4=7=Q@g8o!k=!t1i|0!4;)!BRaIrhgv zZ_F`BSfiU<FVKlD5*V8GLYcGkOg+&okZNc zlwKA`eKdmgtPWdQKXo_8KY{`r8nG6gc&4LRMCpl;+7E}+q9tzE1UQafr<^l2%xDzK ze74HI|I{qibx9YWfqPQ>5)qw-oS@Y5RzI_rZ@^4!i>k+A4>2HkssVwiJYx$u|2Pg+ zxUyAoPN^4WIXXVE_%X(Q|`=NeLtW`cN z{p0Uv`mr7g(C?Enr}*u*rS}J~yDPjpK15!5ya?{+15MN6QrNV|ls~Ymy{dlG{su3^ zE##_cUVJ4vJ``nQnMUn1lxE5B0OMGuj*>3tJ zZU)qE2KC-bAHRJ9gJhRRJ`=+ks=OKNxEYs!TlRQQB@GwLBd7p_1L40rvI~bA@di9S zLpno3^Vg7vAnB|Y+%ds8!qqPo*h$o3N;?qFic-ZPQ33uh& zRr%X*#^SB9_=t6g=V+{D&UGSJScF-Un=>TBJBpSlcup_QUtzRhi3`E)KmPvmEx=;`lIkMv<5I6-1j0Rccw0# z>{*AC=p=j%cCj}&Q&`nA&S1^#W0|z_F$S6<3T5FF)86;NPGhJje#=vXw=G=L>GF}} z1tvaf4*@f+f_ywaml;xwoI<_pIq!cM0F!D1GP|IA9!s@+3{oadr+3q{=or*onm|wJ zI`HZEtRM%!%D%oAz`>LrU z{#viYk2_tb6#l3xZ!ZVCA8d}ixa)NrI(E!F*YXpvDE`MzjxFNUcZ3h^g#2eeVAY3`^G~>^=)YZwW zK(Qou(lr(nqlPZOpvV$hi;|`GJK0iYVmk1o3Njz6ac#jj<7ATkoXLVjufDOH=(|GV z?6?CQUQj?gO$snb3tcXbPz>Trsmq;=AkI9Ons~FocPr`BjPHP=SaI!(^WyBmZ!Rl^ z3J-%yG}@+yAUN^qL1 zJTj?F`8h3Gx~6d9wEBl@$AuUgSkGPLd;2Yq&^FL<<#94^jlO-VN>oxrUFbxN^Ut_T zU&s$OHb*pWBAry?7ql_utIQ7GAGXP|7Y3#3-fs(Kgoh|A+t*2orj-b}pFN@EtzOBi zxtql9Gx}ckIgH~?lo)+tN+`VM&UYVaxu@cGiCl29I>4JHg ztL9OOJX3WcXWV;>}0YK*-%+?f8W`c1T;%HzOZ5H8T;MY<@&RCxM~_D9yB z=5{Nv0C>9w7n$WVFIR@zeyWynxpA9FU|GwcQOoOL^L(P7FlQkm zti}Ce%ZhtMs*vY?5;}%zy$>o|H2{~S$odPe&R|w6ab%B2CnO*!ILVXJai6mH4^mKE zw0@T**Z?HZ$B8iBL6YA#3Qg?zNRAseA3XeMzDsX4U~rQPhC$)-u4{~#&WNaQ&?4Ek z`$)rQOYc||zjn*))L?v>lmjRXh!i?$WGpxk;L}tfQn{G80?L$Vn$uz={nCumz(Bs= zC}Pehjik>04!lu;rx~OLAUEil^*NM=QLrfQ5;~GxAcPki(?4x_z12qs$tZ%(++=9Z zoLPuzMm%sVQE}xpDG|2C)y&n&d{T0VpBAOU&c^Z~Ag~b^+Vep(s#SsEwL%^ee#W@LFi2p+l(Vu{v>RTh6pzjXNdwcOuoR})G3$Q_|#B>x8`9u$yyJZUIfw>wkh zdawE-Dv!bE&Z}*e%Gk0<0=z#vr6uW!FHI11^`j9ODhD58LI7!xm(Bw?yFPx!3weF; ziA(=ijqxPx++Ia?UlE6ooQu1ZSxX0hf38tFj?U0?u4!LQs9aJvhyd`rjFl6)CdKxG zLBK9rG>~j262{876!k9?`pm(I`5Ik^01$e?OQLLHt9+hM2{V@?_TQvX^4rKLnG6V0 za(u2`yI?hw_@)+LW7f^BhveY5qdjQR>TDn{+enZI2k72+Dku^8qMjnM5o zKY)>Cd`i{6ufU=w!<_)s|*~EIR zY|-($3nvZmKe@W_8}79f@_t@R#)_~Xq14A`-6$GGT+j2V^)jVD1e=C-vqPYPTHD%ZXdo|S-k1;WhK|&U$AIYUm+Fw{@Fxx00ls@#&&$zi3;1Ck)Uq_nOf0?w7!0si_+ z#vYd+K8A*^iTD0l^hg|@obLN8fxYgK6i$Hyz3)Th5Oa9Q-XPs~jGI98-DAM)d-vww zm1p|B?|P!0pi6=Sb2x&ZQlG3Nx$1&-ky2|KS@Id*(nH&{j&eq1FVZ)u-b*nGlTajY zeO&FiAO~@ON_Bu2bIqRWjfIgM#XjfD?ml!JJW76=l8Ge8RR?is37tRP>#2#1X&vXG z3#fA7+>tWyqjJR3L?w^^OR6W-ydDU57b8o#hxJ#$xfB|PNL*Jrhz%STZ8_} z!t;;OZ{L(P1SL6xTmEui9fk}A$%a_1c;d+@#py5Hp0MM%r9IuC|N68--Sv078cObV zgLLA1q45+K{`#}3;NkY*Ss6h=z1!^a?MSBedX!9;gLPPxLxi~Vv<%1Gd%1Jcwy#kn z@5Ho=e%sgp+{&Sm_(X-L(6y~TtL;x;uUrP?Lva9`g1HaO2a7D-@lxAl|Jr69wQyV2mP}4EjQJur8+Mzg7VX zOhj+j4^R5#2XTU$Y|39@Y}ECOlA_kh_SVxLeprM?6A)GGL zMgxLHox4~?$~Iki;~Wz4i(g%j8=Y{OykNOOp2zZ&cAfNPF4<0>e33F)#70@%M*1T2 zak7m!?CUSMswfZAFmR=9lqLDnhS6hV?vonf<;KlMv2ogluN13ECc4oQe0efR(ch;m zz)E*T$3;iXo`H|(GU2&VUNG4t(<*5=U+X?8a*bl>^FiowD>U~N^UT_Shl1or`vC1Tc;wZVe-He1NI96y(bjpF_9*9yCE8!FK}xiA#K4z^^#d3{%$`=sC`9z zX^}^5S>kF`eluU{W}xY;RKCPsv3g6OdCRp(L72t}P>9#5La_#{D2H1plVmZfm8iL{ z(M;ot+By8vaTtbf&*-o@B9Nn$^nhgitP1V`@%DawnROdG-%?qO(BMWVgi?6){nbsXm43hQ@{y1@=E>&TRILZv|seK5UsNtt1at;&9! z!R;&%h3S`v6WY#|+4dIwS+#aGPC;rx%4F{jb9CEW^eM5U+IeE0kV`nNCb-V&?22pXyXAH|Xd!~Lgzu!8 zWXGdb;T5p$wqPH*`$XO!$HOGUZ+Oj}fX?osLN^#{zccxATkn;?wp9$5g&H`sYhI1g4UtF(JtZEVK1Y`9`tE8@A%`ET0befIR`v?B9J6iC<<=SzLW9bpzyJs zYsMg4N5@djnc?(1sQvq+sR8-X0cpqG1oGVwx+=RX)d0`$5eZQV=srBplGuJH?=-H+ z9L#rqe6UArX3|Baws)U^fx{mnfa{gA?6FdXJ8rBMA|VAr(3)#cm(WbJFt!azW2#C{ zadKaZOP@+758TKQ;Y#F;q6zGG%t~eL8KBii34{(fD>@_xROMPh^?034d?C+)bq3FB zpk|kGhY4>whWQ=OiwlS{!yxcV`6GbFN(HXAd#_zx((IsFh{!mwhI%0SWYUzDm-o*X z`#iPLysk7tF%CWr-dDJ)<^3P!O+ZS(fCfvHWf&TMGe9bdY+~YT=B#ZNnZ8LIf)jhx(0BzEWBIlsCCwy&6$V(ldqp-Fmfe(BCv74^8s~yAF<9X0M z%=b>DmiQ9EVt{iWjUyI^a(69+_6*1$D&sBemz}CKc=pMsEhr8u@o!UP;`h@&;2$!o z8?xdbeo{B=$v+ZMHxkZ28dEo#ayT>xs&)i_a6M#ze_|-B8}H?x7_OU`;-8$Wn_#VG zeA!2H1HePUa_p!)aVJj!B={C*n(i8r z+S|OOhpumK_YI!#P~o~h+OBeYq5_gsr+@)PYgJ+-d-6n}kli5_ehijH82D6S{i;8Q zXL^|Btp00_N`sYaML1A-6urUeTEz(^U|-7S6B|wGjm-cJGUlY*(0(jj2b}I5l>%OVSY)xiKr0g*m4%s}2;589T7Fk%| zlpb^?*!$DKmNzB<94qlc>Q9#DpWZ63?!37rSMyhL2H`*nc4_tm8kMRZSaI&)By!=a zIozFfJuzcoo{r)1_TI}gz339$ynuk>7+kF!l`@?vr7?|vs80U;L2!Gci1|U>$I3J& z-a{-u<+oFaxda?Tg#wR+^bn2UL>r}|n$+gT_q0C3OU1lV1F}^(ckc^RY?-r6tBJEa zQ5p~B+4+RKHfc>b;fI_k!jPBg)dVk2j?|8=H|d>jBP9lR8MwYdzdDe-afQ{Ykp5f{ z0SN>8+VnK(G%v8P)s8G*mw+m;2Qc6vD8lyHnO#}LxJ*kVvj#sANe>}{JUiuQZi3iz z{+*h6emlUQS;`Y>FBr1Lmc4gD1tp-Mq9@-5wGvS9Gm)hVi)Ej1x#bB=AK(3Y%trDn zzT#B-vQacd*vf2tyWu#zYhM84RxzX?K8-tIg?WmH7sE);RXgPfer>CrS*4#MD&XbY z(NpvN$r9x(uHxHYGCz$EYJ7!pRPoc6n7B-Edu+u>Pvw>q5nQPu$5)x7J^&7D6VOnsNbw ztgm0?stQAsZ?t@iBhw;`02= ze&jgJA1%iI)6s305_8W9Ph6`^OSH&bKS|)!U)<)SzkB6{{4zDA%2)ZG2*>y0LQd`G z73c2sPxCoM_4q{@Mp4060e{Hvxzd~mAehn}=;`WkwMu^j)y7f}zR+*Qf zBb-ZumpL#9ZwM!o-Uu%m7f2!#DnVg7F33+UF|&k&V2_;08?{RvdcWu6qEES0Y8VD^ zE>ys+S`-w>*!=y(>yEgOzx8O*EEo)qe9dKe%VkQp(_;Uuc8*Q=1_V znicMkIagA@$1H4YD{O4nF?^7dUY3&_jcc?mtEDJec3Xaam1ruV%OhL>3}(K2QMP(p z_V^=czdiLM0#i!yl^ql32<4ObyS-+I@zqja z%hSztP2Y$zC_am!b!7;2z=KuxPyIXJo_@AZ^v$1iao|dduR2CMCX3uqxlX3n4w6bh zgoXV%R6{q=2GY^4xzkhY+k8GjH#a1N`=;OhQ{r2{sP=*UMR(nTIBMv6xb9u&vxmy$ zcb@be#eN@Uyn08&3n!i(5Bqj#Slk}mE)^skSI_!otbWSe=^q-RV3gi`riOAt9 zWFT+|`Bc=TeU^|t_x%#<-V3vTK1lkPCquFLg=0TPk(6J2Sw-FH3AM2M!bsE!0lh?0 z>qIgTK<-UQ5lILLE3iAs6EO729C%Pw>r;0UW*$y}{jOwj6*l*uO!>ZC;d`mUGQ@vD zpJp$bakceOS$3b6X;_)G7ARnT!OY5@zUwDuw<&a-fGOLt2N3L`HHX;0W@! zzfwtx`O_@@dD7KD=CAWp?r!up|D`YNVI+xI&)Y@ zLHRcn`zcW}9RJ1u=rco%QF3X5J&CsJ$?W>?joOmzG}HO4hjOk#MPHH#UM)54uE#)f zC4Gxx=8g@3RL-wGoJEP~fqnjLnOI6=)Sl)CV`G_|KvICtkp#HoVyzEt)x}QrTK%Z| zI5zU_5i4f|pKhPRF57Ex+e0SPZdpnsq~i7d)BbQmc9V`)uJNuYSHYiN#%?NOG_L&n zs!FApBIu)QE2^djyO~mfCo0d;z(fBpFhR%p@gq) zQmsu(&vl=o-rZe10+9H58?dS%sQL>QfFT1jKBPS%91)74u~QJ;0e7zdE4QN5Pau!0 zuaqhna*&_X_lZD+l+~?>-p)l0g_c;>%@l)2_h#b;$2?Q2h6m1)KR{R`j1;I$Q_xW$ z`+zn%M#YIXd;nv+0uJzP3n&$ty;k3$G~)MrtyHB3Jm>p3q-8iRBF{rOLM(FUT2GIS zc%QFkGy{rzXvCmCF>ntRR;9%ZeW2Fu^td65&dT0Mj`2X;E`r6vn;ip)`ctA$Va8z} z?MFmtL+qE-G@>o~Z0uRBJ)PqGys5SF!CZe&W3ArV>t?LjfFw>vR?=@s#qcDsbd}jN z_s}D=8vGw)qI|zs;Dh`~@3Pz{O&k%a_NW_HM#+}8Us(eDSt2GW=5-h>0VC3jYi~FF zN56KzTzkFT?W5E)p=vOLvceO~;vbu|HT|^67u=?BUGaR2*Zy0WK$3Osld#~W&1iux z?Jp1Yo8~J>u+z%p1F}FMR#*v=ISQ&}V8)gH6yIApv-?jOe+>PESRt7gh%?{G1K)hd z-8~LZCqediMlogtI+U7%^$&g^C5HVozh)@wIo(Im)1T4NLrX}5-+MMYjnmJCoGSKM zg&ll9{w~h9;gTE068owKDy<6iSv@4U35(naTMRRc@W42iJRGE4tU1YFnRwumX*RH) z5pXNVi7B=|!dN<5xR)g`rD*!Kxp&L|&Jt5+8J-HGMl%3MqAEOY7TWP~%5t}q7=g)1 zV-40BOQtTb>0e5yJdlfM=`2cSq=;TN^ve1>w;cRklq$%WsdY47*+!a78Ocu3f{ zPrkO@Wwn2U7O&tQUXAaJ6FP|!&u;(TTvZ12#=mb88$BTWi@*SBF$Hp#$Jq5p(|6Hf z^G6_B$x-x`*-o*p8k#@}$Qp=Qp82tf1HSJWKxq`tVH{c+ zc=ZbXDPN8)S!kv)^XkdTBN8H%Q%n!j76n?36C97Zt@vj?CQ|kW;xXAr;?s^O(Qnjo znMq+2to`UmEL-z6^KVj4M-U0r41^p(XnHl!?GYIzSia`Hr%f3hQhTSdz82qLj4eYa z7CofC6^c|S!pxBvEVpowg$=#H*#O5&Tlc;O9P<3l!AWbu_S z($VPy45H0;go`6X_TG>g$BJP7_O~8Lg+!7#)L2=7$}lrYEuV84Dk7#ZHM2DP@}t6z z3JwFRS;S1Blqa-QA1_oFcj3)@ZI3;yOrIp}Fa0#%y*jd+PA zVlt_Z<*md^p&BWdNo`2AR2Lhx!sLqBK-YfDJ!xf)5Q<4_Dit|&(9brXuSsjJ_BeF3 zre2-aL1%#rf*p6Q!lcLLTRJZfodc;YHt^G12Stut!+mAth+a3Oc^tWmfMl}X^y&WD~s!c1P-16ODlfZmZA7$DZXXoro{pZOwn@Jb?f!L;JxBo;b zq<8<-j(7uS!qc-*D$~a01hzfpVs}Q91d7Y7y;cOhyUu&RMDe&k-hGPaeBJ#=8XKK% z#sa@f@g+?wP@>br{i2`buDQDz!soC_GIkv%{A4NgGTR#eIHP-mMw#5H4)&z#Sp*s9 z3E8W=&5yA$6a*s?yc;edArd4N48{(cu3EAL=NX^L@z{C3xW>En6k*aCZ|a-k08re1 z2VETvVx?q7imlV0F|7t2i(4+>ZRRA?S9g^-sdn*MamG&)7#RFTL88d_fKZoU7JcUU z-OESA{w=~PD5syQtKy8HC2|#mI(v@R*=gekuDQDDKj>cH%v6iARX!uKmywx6DR;K3 z;Y>VyiAB&J_V%cxwi)BVtWqMT&hxT9He;7CKXaBqnxLB}$Z<;eWZ=C_VO{ixT&YhQ z%Ok%%r`jzEA91tw4KU#mJ_!l3&*#HAw*LOU+Uan{i8^QK{�B`Rk~d)tru!f!u{^ z!MELyzilgBzTBx6_1((esGq%3y0+APazzDX?yAOc6oEYna@HN<-t@92pNL3zY_R_N z-S?R2G>-cfM|ycgk$nGYs$$m9@deK`O2$~P@?tW1G4E1sx(mPJ99FLHA}znfKa1^(@E6!5v9VzGzEmhq#633TrV}B)?3L9JIji5#J@d)) zW6sp}XpOC+=-z)r3ktg)2=*%@eyZLka+bg-ybU2Pj{v;}#pIjj{f^%9Rk(YyM>5^3 zqpKMKOgV;dYSQe^vvdYFQt}e$LrFIhe6t@s_1z8M`CZHTiF%6!>q%x61FS$l818d7 z9gWhibdK0(w?QXWd(OP_@BeU8`P)7ZIOQCJ_P~pPiq2m5rEuTBsM^y8CqS#0CSbjE zo8X>=U*ZD+;8r^%16|9IUjyX8OT~CcBL^e3hhUd)4F@FO3gM!qHYk?Kzho!S;SvzN z-b54uTNslx+G-}V$GgA)$|f+J^#JzR$M=B*NBFQn1W5a2Xh#>)rnn2p!S3yFB5*K8 z_%Q$0?&Te)hw)=oPq`AE-vw=FZfV~`kg3Bqa(mL;kIy}%R`!^T(mY$?%DdjfOJ%(XotnR{`e+XX(^DlZ} zw4R9g8Dg?dcmhJaUVwL73+Z=;jE-Lnd5$O|3^6Qh}K`?IvDL1X~v>1rsr(1FY z+YzxihOXqM&q$qJ1#k+8Zb8IF1^9G{QvrlGW{FSS^zl&MrW?Ae7BICHW)3RJut&S|_N)V7IY(1aQYY$OTXobZ7eFlCrISvQwS zZ1^8Rgk&3dVXt_1XINek2)}By_-QbkcFK|9h9juQs3#}He?8R(*!k~lQMmCXR`@Jt@{B#RfH8JUkNKIU#MiKsACgrJT}yDJ!aHB zQ_U4p^B`dZTfx9aI4|{>HT ze?O;%dM*D$xMGP!VeLYDgHLDnf|X?*D`*feMovYjNHIM{*JDzb;F4cDS?|@XUa<}< z{yMifCQd>Vi-jw=*vNnpq5aT9{F2zP(ZDd$nYH~wvww~y<&Cbs$4?+hxp+(7&_(Z2 z^KT1MQ*{Ms$$K3_ELOU8H;h^>l=G$5VWY0`rNKLq2f_1?G@10toAphZbfqUv@-L0L zNiF&lrOHyx{XM?#8JG$cq2H^ga?D1?V1v$7gQv}pszuC4n=Kw+S};C9$0nJL0OryH zU2_{F&N`z*4}&rR(_x|fF~g^zdh^0drifJc1vyNmc-EJs*8Rq`#3t5n=QSLOZ43=; zoouT=V>_72gw-P~+l>9x#x$bvv7M*& zD^Fp{-`e12Q+ksZ)d?>ioiKsZ-2DvMw=eC}TMQ%@o;lYzyo-2R*s@)+;K-@~iMq5A zB4fifk$>^~$;ULu;Z$xiG^jEZ1k*~O(u9xA=Quq_VYqq9{{&i zo(v}lvSdvf#DHxJqV?N^Ol^=R0R%hN3V;>-LY^?JfLM)HD=*DWcgjuv>Iz9F9J0X1 zRnU=!uPW>LvXa>P@u|;35eor$)M@S244i?6BUs<1;)Ty1sSaH=NRxedvFZ^h*(>)^i8t7c#86J zvV6gnpio@)mAj$$>vuM?w~F-l%yJkda`;ey$X1?eTV6?wQR6xUn<=z*NxVrckzE+{ zY@NP^ff1#^NR<(M+3>lGh8wcfPy44ZtNJFZUOcjgJ*%ba|S7MIxBNX zqjRRkYbLyNkKr%$ZPcQ+)sk%0v$oZXN*KyZ9xN?#$}k4}`pD1)^^Uxu?BC5uZevJW zPEdrm(PTAk_u%maW^=X|@vdZLS`*Rv6pOe2!vM%jlqj#XrtI?*!KldW4Cz=6*h&o^ z*g>ZXNt4#`e}cSZS&dX!&kEe#;I}hmZHe^aNsVKfpT=_Gn$VvG5CyA>%=U`h+loSo z52X^&TaDbrvv%!fwHSgu zM1{ANo!3NnQvhhzW6135*tIUbm^5Tn7V{H(>3j|Ebm*ZqK^Q}r>_{#9&C@MWUxOlyTJ{*`?t$_-l?=^4&2#I0+LTfd>g%2Zkc>F{jbA$v+JI%*6B+&uO@g0 zAI5H6H|w_4RTAa-&$TdnHq)Ne{_t$lmTXIXECKQ`4yDF&&Cbku6R7yOeLh90(sxNM z{WjuH+h6YX#@LU_iyv7(H8F}cc2c)TO47c4+|f+lmYLm=xzINI_}$`aE9YtlpKse$ zcDH6y*Z!ZsJ=tSM;veB(+dWpFg^;(hJ>Vb+b3e5TU#+|0ROyrUl_ zeb+B9HK6P_px!Z{eK(*lHE8TN_^4yh@@~*tYRJxS$l>cCeV_BYPt73Tmig4-&yTyj zjb6|NVMcb0#NLf0N{y!ajb?U?=H87KN{yBJja77vRo{)(OMPzk`yB1}sS(`0f7#RT z+t8oWcZ%COKL9+pg1)@#Z!Q|&xEuT~HL)u-_^V^$G-u#gYVw9=;HqO%-4FU4@DyYF zG@SEgW1){bCG``hLR;T7b@3;9%Nh30-pSBTW$J0-wP8!@F4~#T;S)3UdgzSt40GY?l4&7a`h__{X!c7<1K_GrDWmuF{LO;q!!Fr?9`y+O2jw{K;msBA%MGK}G#t zqGns>3tP@!Te>O3Nbtre?_8<=yHYQ`+U&pDCcXMf4&hX=I_Up()ch!u0nz~+g?RU!@z-XaL_q~bmA`F*6w2(n!d#`aocg+3l;!nUC>f0G9 z)1_%Q!v}!uAGl&89bR;FEOVT1x!l~p+~0rG2D#0qUlCEdEz7^5tRY+o#C0mb-;^J~ z0H~0R@E``#)*1$^K)BO7j*~SFl!fsnhgY?zi16x|z;gjylx zf-nfVY~bx_kl(VR?L)gJ!%i(bhqjaW+L9WRb}4*J9bn>Ji6lC zi1RKEqnKfTjvm!!$!_tZbpL6TO;r0F#!zlVPUo{jNu;^JW8U%~3_$(nU<|cn0Iqn$ z_Gk+CzPj6A7Z>IEy<;7%yax#V$ z)uq~e)uSnhVv?RD7Ph>@XG^!YeUpW%=`y)KA^;ESIg7>FWO(0?@q9&kPFld@`(h}h z&Hx`{A;ji)r3QYrg9D6;nvcD{2ie_rVVg_id8nK~dDM@$`J&jC6 zs)1 zSu!KBmlb92+h11J4rNVMHNS7gl377T6vFsc_&;iLF|wXcB1p&__i8^h>~U2!%)E3| z)9`AXlv$Ze&}&)s{KH$Z!K8WAfL%(&kYB;?`%Bj0hRUF>f5EY;bu{fWPdBza)ePB9 zNFt)Q2Z#FQ5S8;6*I~MMxNgt95`u?`eCiri70mR`<7L{{lQh+s?|MRcXZ3&{jyjem z$H8u}l}jjdx}V$FYW;!W7r|L4p^4Z#MFHT!L2_CLw(I_3h+=k3!`H((5G_X@S+4aY?j5sZUWXvG^Hb>2=0LNvn zpE@UkFdUZ<-&aWyo@Emvyjd7$4(&CJzQ#P_XAL&3E2dlM33^X9g$?sT4>|83$X{FI ztKlJuf0bkM1z5>J8X%m274)InS+Kv7HVbh9COt3(VdY39KrQv{Dp<$fo7smmo-!gr z)smR#^o2)20KBd|2UQ5H6HomiASJdLOoXDx_NSQubl8v#j1C*RSW*xx4B_O~hszo< zlUWxivEFYXBmp^poic=%769m_6w!HSs3cYq0!Z9#1~_N&n-Ck8*pP&GZfg0)A%U27 zYQr27Z^C^~7_lo{Fqx!FqK!>Jz)~+)00?&R z@kkv23-zBlNOTNR>9_#fvRtb2X3FPfayBt9c797kG*^T?Ey(GY&p5mK zbqUm?6^x;zT%x^^N#>BGMEHG2PgqNz%AKdk@WC}Ex#-}(roG#@5gf?ViVHnVLqDn> zaUw=h-#5AyS^ILF1NCyc13QTAo^UY=kc2{Oq5>Vdvkdlz{S{bnIV*CP5|%9ic6o3Y2VW8gn%2Xu5$UX z_8kho4#34&WRT&00wlp~VJsxm>nZ3{FB9#JUMjK2&hHPb<8>_p5tsZ_?|VF|v`!t+ zevE^H4Pi8>(rb|Cb$v7+6lZtrnqC1b61Rh}0FTuR4u5^}UXL(t+{Yecw?ILGCx+8c zikam-GA!g*nAjh-kO4OImC@6fA3ToUpDmt5!9#$b{K4Y2U+qJGxBpp72zhJxo&l3h zC{^pel#hvyNHq@I8ee<4HimkWIN(yV;sM-eD&#>^v|SIL+0=4{9t@=;{ywVWpIL3O zuSS^Q3aCSCUq?oeatKH+iuJ|I_{0OfN0V8E%~U?~RcHo4fIay2i2{aFD2OXnIK<=| zreT?vD)~!)ejUbT#YZEm%zg>s-gD%J62`meX=fPs9W$W`GM(wGei-W~Mj;r83Wb#Cpa$3KnG^xGtnb`@!S< z4+DTcTlV`YT-!G89EWBA{C-I}iw*eTUlhRocPhU@?@&bGU}YlzT`lMKS(M{NnWq1q zQSEIAZVwjBq!^!ZI$PSWKHOsg^bY}Ht}1x6L+2_ZdOb{w)F*HN7~wMsst=xsM>s7h zQis;He@Ee8S4g4>h;`6E1cc}2GZJ|;0r5H{)L#sY<;TCN#={@wi109TLSb%%19%SC zHgMA&3@)M~O!ql!OphJ&^```XmR9}1=j*NtM)g8^N&<{|t<&598IDr|%O2xy2Ln-1 z_`5f*gg;Ni_Ep$lE^EHKo#PY#xE<*4y0XQHNj&=kbi zxzGPbK_s9C%u$`4sMhp@9pjVA2bM5ozOoTL}exFeK@Ly7F9)z zs(}BCf`Fh(|D{2c0JmjaJyo%24Whcb`hV9TP^l@X1f%JcBs2?=mzRg8AhNQu&=f>k zS{j;yNJvQdUmOUOpD)T=9re-yWvhrXF+mv#qSVz<%G^;wLCAmc4@K^;|AT+<^78r* z{=wbd-PP6g|DJy^GBPqSFwoc6|KIrs6&02LMSws_a-xJdQCw6g7IG9lIf@$HorORV z;Gp1GC`=d%20=mo5g_i!33a6;(d)lNAb5Fsd3boZxw-!xfna84W@2JuWMpJuVE8{G z5X8j9|D^*#0fFG);9z58V_~6xSeTfY7#J8Z7z_%9LLd+@7z_e|PypbM{vQD7-2ec> zqEV|W=ncjq#>qL=)r<*8Fl*$f)fWv$lR82_1lAW1$J2?pLDd^r)DqbYKjcKXm1?H) zJ{`NGaDP7@ZgxMeH}YR=5PHQLxi9&Lx~Yt^Ma5{ajs4ln-RzAzAjPKTGvvrjI>nt57n4L?3-2+?2o-UvLM%y07~ zla_F@n{sD%{Fer?SZD3t5+mXKYPCf7*TSo;v%}^O&*1br9j&KZsxOF*_zT<4e@zu@ z=IeCcLh)_I%)U?fe+tU)J`O|GO6J`ijsEDwP<=fmhf7Ge`8i*=yX)_t>+}8Zlil4Y z6oA38{vR3y7F+px(5<{DsXU~EVF0Z`*l&bVJV$E~#7wR*BAPIcq6j|RDMKIk!kx4z z?mTwNXoKouI(d`7&;C0NqGCHqOLTWTSr5Fs{uHdu7S@A2+@AvMnd?W@}xt}3^2@=80^1KHNV_o^@ zTb$nA)Dk0o^NOrE>pd$Ace3qXS-Lk|d*vl*5~*&)So(oQF`LGL2;viz?XFRyig9Ii zR@lPo6Ss*Qhw}Fr+y`|7Od(uVRiZwoAL>=IDr-uuJ@*Y~*HUWTGe4%FS@Y^W2Slom7TuzJGN_? zetI^VW886IoO3!Mb%i@W^xESK@hAZQnmmSCAA=Yd>CdT{)m4?Gm>AhTIG;Cr@t1hY zJ~wEK{tkSiDrsjW6wl2EY~o24%5llFZ;folkYlmhOh}eG*$B^g>Y)tdC0gyRu;bnk zmt4qeW!t$&>p{}Q4B{cmm#!v`uWo*rJJZO4bKV}^{3-~a@CL9WdvG})v;rzi@7CR; zNi9l}HM!OP1vjKNd?Ax!u!$$YShLn;kh9&K_y+4vm}C^;kRQRIu2az5BOrOxDxXN7 z>aV}*-hFMpb}roJn)>YZ{SCQu4nTA8@%aAF$?#+V7zZ1#r|WOfc(7c_2*ioE80f*h zux1NfS0Ki)4&%U>!QBS+;GhcR=XX-tIljM zIUmP#N#>SyAmExfTM8ox+mQoKS_=S__n>&XK4$tV07-y?jKoRfZWH4h0S~@TvTPhZrVUmk>rY%m~QgJgUM?(mdZT zWr?J=Av@fz$$X9R}dcE+J}4KLLdNG5q<~ya6Ii$z5Q6pCa8f_fzu!+B8p;q2P-x!IdK|$ zo%2G3N@Gj7<2B4Fwjswjw@LH6M}-mE z7xcJei$0WEO<9&oFHj>^RCHfaHpCSOJqs=DbG27WADf%gA^{|u;nO29t$|AtuCxnv zlV+|)09s5RyR>dxJy<~)^r6CD+p&JFODETXEie)##(sI0)At{rk&6aa1x!oj+k=jR-qS;i8YF!qsr;cYv{Yd08+2+*KjpgW zHAC0Q_?T5RBi}i0e#00nz#`>ys%L#hB}wV7fee>f`A?I<8-pF633P+CK`&#E%n(OH z(I&$ed!5Ft#VVaC}v%r&#&rdMU^GBVY zOH*4+(tZ-kJ@h*Xqt2NOFlj1R*LGFc?bxKyy%-dlIF)nun}!d`4>SKgO? zS9dnE?BE3}oA|7Cb?UD_e|*iQ?NaESwXRBW@+X$hB9QXSb*+x84(V*6jz^U{?SZYT zj8sLi+&y~-ocI!CO?c+zQ4H#bODJf$#02p7Hif^%S$JCPQS-RVu=Hd| zdLj^A{q>gi%qx`sRoCz5uyt^`Zs(rqg?Deg81=w3NTg7yrMwJg#Iw6jWA~p^_WEh z{}Vxddy^^CP#=2%Q!!HVRDG%8P~b$nu7rY7#DLWU!E8lvRtIuGiM=CF36d!dNhwE+ znSwoAZ4ENQeU~EFX2J{SEnP~(;$e?cIf8IpfxfBN9$UL#=0dN$UEh<_$ zsz!~Z)ZREL!gw+WlS$R+v2xxPF>-kmGF2>r;qnKwYO&J2A<6s}nb$U> ztufyyc*Z%%CppNbDTL;igc-dMY)ITUJN$1s9yeUao<-1X?2v8kkp7?$DKqnvBDCn9 zG99{(BP5GIH%sW(k9Ty9f0P&>*BGrZ9o>a4X|9V(vz+fm8a5% z0!N*+794pWlKA^!&}{^wPYri)CoU@@oK8F$^TsGViGv9h8SQ?`!BCzwRg{!mptVAg zAb=e&?443uNCQ~0nh~+-WU``h1YPme2>~`cLDSuc5OsUR!zqFhbcDz#1rnKJ+eW29 z$;h0P_L7o`4$S0ulg7d%XtbT29FpV^$Qf6l4qzvLZH=_MNl!0K0r%1vJ<6C3q+PMj zFvR9GQ%^tGOdzOW!{^7fvP&FiPZLl{K(=LiGiI2N#>Y{n{oz3H-XuX`nT*ir-|sVX zmb2b$WX@1z6-7opR!4L&q{KU<=apvhjAYf^WZQ$Xe{y7(Rb;znqykf^Pama&A0hY) zaQ5^F=3HPwgNZ%fxew2cny|Bq#dGx1(@`Ti87OfC*E-(&1egQ@1F7o05Se>)BeXJ_ zyUK~yAo5A%GGnbW^~CbP_1O2UDu*|D;C7O}wxsi$OsuGaJ~7<);@KSr&I>2l)h_r` z3|Q)<1(2*l75xG{hn#O)h4dOZe&UEuWcDVfz5)Y1(Z5uMEGt-$9)U`V2gQd%Q7YtV zX2G}RT#WWy#r4$qt7M{3<}@^{kl+a>#OYHl?(#0y*?VNAfEg?|~B&2sCBNcp% zPzgn+^+nKAyi$Hd2tWS(a*1x%dzrN2`q5%(^HK~S(7+UdTS5NnNa=?*927Q?k1RQe zeE*WF9M)U-*gW6Gy!>nw^KVaqGioLCG7NT8hb5hWd4>$r;wsO;DP{60Ggv8q#f4y% zz&wYFFMsR*IxFLPt4BpA!4#xDQ-vN*)2sPVSSD9bBK0vFG- z%8L8LDhaakV{QMw5r7k1VUISUF!N;lk_OiVGQKd3a=N4E~ zRakT9lY4KTbL^A3L6tqQ2dA*AJ4vbqK2*a$*No%ToKn@1J z&c%}~0{hm|W!r2;f%!ghj-uKd0#_Q8DC_yDt1{1k?y1+Fx3wctWRWKXbj9F8B;F-} zU&sK41j5>;@DHruM*IkyDcoZuevKUK69Dh30PkH7F-~-2PDNwR%Ld6m_3>?1nmsM# z(bYPEur&rex@2gL9)=Wvu{?zXt_ST|;m9GO)q41rg^&kh5R*Fi6azwnfdEZ~hoZTF zP=uXh3o^3h#Jo|UvgK!QNEiQyg%9Ld+$7Wqcve=jP*{VP-@52|n02sof7A-Z$p?TBk_hztD7Y82YlTgq z2P&|_tFDAxp%7R&4B%=PIJmGKxsH!9ZFg!-N=4mKE#5(XQ+Mv$v7=DcXI1ruTVSG+ z#7hpZUa%9W1AkAzh9p8)>InY0;1RJPEUoZwPYAvs1(yr3AOaXDM3Q?7^D(?To3mSE zsBvPi5qSz6kYWG!t>cI$5wOBHbm?+tLC~$^HX+DJ*Kx~{ut!rk^L1Pg67X^W$xlc) zn?Wx*daARxi*CJ(?yiL4z=~6=N%}K6Bl%!YeV^*TYz2#d*$Ur#L0^#Ybt0^v1v~@{ z1YQ7;ae@o6CZ!AO+RH}ttPTj>3}CBtGj?=)5T+!rD>GS;m;NE9Nq~msKqnJ$)X^sa zbW^yWtUyqGtZfECI6&YH0C@>-jAsx)5B6Nor!LK5F2~`%)p{1(hCI!VWP$J+(vjN8 zK}|;CSSdWI1c?VHwDML2MGR221e`AiaOCSN<`w*>wqF~1|k_&kNbp8%(0LwEsrCocH){}=+zS9N&L_P@~L zj;nHxM?7p_=on6t2S~7sXhX6(SGw^ozx?(aejhVtST)65Mc!wI>kdpMa!z9ljAZH$ zWAesde^n>(R|n(K(XVBsxMn9KW~7(X1v952!`)DO`tn z)RyWZucB6ST7plpvMvB=yeDl`=pyx5Y`oc;gPAfv@?`aJ1ZAXZXO{YSgC_4F-}u~I z44Fe+IU)Z%`=j|z?|Izp`JvT0i?x}z^0oKu3lRM%vRF!rR||Qqv%^=ja-CBig{C7` z5XYry2HquO(C74*i#3spw`Gg-Rg=E;HeqGMd&*Pf=93YfF;TpvF0{)@(&NZL+nVO( zK<$NPpJktNtjQDnU+7>IKjIUT8PxQir*l&8%hIJIMJ&IOvdBt{HmSQmrN^t4F=O~U zB-Drj{=ES7>yPJyo~%si$d}dgxs~LYC&t!;%hUdYDdQjdI>UKTCj=Hif7Z%sbMBhs zXY!}7aM=)x%Cw1h4)bf(;nF7r(L9|y31}h(JAr34H+M3wbKcE0o8!y35Z)OtpT^Ty zNDKzJFBg_g0n~>9U%aUcME;!Zg&XVJ4U+T?DxH@!-!}4pZ!mP(D@}Q61NKZZ=yc#F zSAac7_&W9j|KfE#&W{rNZN05*&JtZ)Qs1^@?ziOVwiRl&_x4X@Uh>fWq+0x8+hxxx*Wj@3`aIxgn&?m4 z`^|ve?dgX=AwRy~Tg2lN0zQjr`@@DN%WqDHWNq3;M%v$!QFvQ#Cftgq@GY%AqZ65_ zE-(>2jMX}L?aObzx5paA6COCpVJ+XLuQXYD=TXU*P z2u>Nrl36<}J3GXtJ|g?>MiCze&tD`wCTWw##Tz*cM$vtY3OLKnIOA+Pi(Wg^ng%^3 z-D8wJU$HzFtqm7@mp(^#p&+~O9=N|>eKB}HM*Q@Q^y$U5=f$gx3l!RmlO{(b9L#rJ z+-Y8zpn}Y5rLSZbXlj?sZ{|l_ASDlef04PYB>ZZpYyIL~j>P0|bG~!8K;Xjsk+tsr ziO%o0^oI>yy8{!u$RjdMt4)jtS9|hj9?oasy3f4ni+l;znDR-$h?K4#V}F9v(!7~; z=ZnbiOEKTCD^Vn3Q^!T!zq!<|vaGMlYArG+qaAeDN0x8334u`(+)uPuA>a3#-c6^y z`*WQ72PA!aJ#l%@OD4)+=EuL(kWbS6in68lt_d}GN9_N17XMzFajvgNy}tW~N9(3J z|L$x2pNe;f`p0u;e59-=r*wyRFW=2RTfTp=^OwHq4*&w>f`#y)bV~oJK}fLJpKPEt z2zHgGjCz~mfc^(&1LgYLYGI7(c_kEEPjORtEt4)zCi^wBME+faSTV4REqI_!#_CP7 zt5&KhBnr#2Hj`D=g-dArknSs{@_dwt6+hoMYp@&7Q_ePdHTF(v@j=L~XpKd+Gx5aX za@o^*0u$C1<%las(;o4DGL;;&Q?v%*if_q7QN2CtL1;J>$w*-woAKF4MPo@|tiM=0 zUnST4a=j&ymmEV|^fzj8neUQHX!=HEeMMHew#JO=+GTSvmR=U?k*jmrm+a$~{T!B% zr+?`pQ=SNan)p6KigQKxyrp&awdC0KXy%+JW0Qw%157up`yM*>$tyu07De zK{Ba;_cTO6WnK(d04+JrVXKBA?D@G#7iaX#Q}5jMRhZ+I+<2+HnWw85TzzKVa}a72 z=RbRWGOfZIeo#BY(hU{TDoCR_9R_E=A<|x+bE-hnHCn`t7ntErY6=_=2u&uBywUwE zHXfrlk^G_Ktb`NgAYsHJ(b;IIt4beA!YC6+LQ<*pw7scR5xe{WQHtQ-CWCyk=52aI zR2xRC3bS3aF+aOB@f3kGiARMZ_TbEvc_O%($)M7eaf#F@b=3G-JSp*loSk%~sb!`% z@k*N5;qa_psU`7hky`9ft8pUi;n%a2+)G{a=F(S-Q6Gfa7GM0;iZ=2d+E7WQj3Cvt z@W1*I|MmGi-q<5COeIqm%#ivC4&*ZT(#LlpCk!^&L`3~@oC8)rsqszzq&$a^| zyiP%re^=fUMC_IkD$RxwxulRCmPAuEwZdr0*7H8O4(IOqRF(bhTRqAdqI>VuXt|(s zBHdZ#`l_glWt3F{3^#bw7lQI=&RlmmTxrAdWLcPAy*KNnc%&ZI<*?|$8r zcw)^*QpJExU!us^i|{oowkG=ZTycp|AVSBFi9qBG6jIIaqW3iyQTVfqY*a7u=@%;E z;fHc{ZFOv1)EJ0jHI+t^smD*C&uC=Xh9C}!ZU!`uv|n4r1Pla*HuY~Ad^MxNADd1{ zDB8NM!y1wEiDd&ND9Hv`htM`m`>6QQ6A`qjyRaI(i+xiT?I_*e|MpNeZq54wd!J6UsO8c7PbfFQ%rA2}wY z9M(jr*(__p_k5qrzX*12W3)yq654ue{$w;{4rb9|tZmc5wG(1*cEXa{QrC&H#Y{@F zRfG;XOq_JWa{Kk!C1D>Zl%=+4e<5KAd_jw%^gtj|9_xq^QW}~^L1RZ_19j5 zl21;3$UC-`oqa|fpIo*qb}rf-`)0dziB*9h$Ck%$Pd`1q97^v-HNVD_@gX+y0|RBo z5e!pko}r|lh@c$csOmLWvf4tdov3gcF(9CDDB@_Rnk`V$W{^UT%m5}wcNCcL!bO3x zH0cq;1phOt#igN#L#}Zi9na{lmWE|9+!8{iY?;WHM^sf%XL0*=nooNIvDL%eQc9)l z&{=f^qz0R=Tp$oq{F{OMT7?Zi3Hs{b8U11b$nbDFhW9|296TDvgfAHO&WM3=JT^l^ zNy|oN)sE!bNmSIMgH1_E^7a{+OHuRwQ{{(Q?J=HB#f-GOO1fDc_EpYMj#rkN&OY6_ zzc0LCJS*7)Jv4^vb?KmW(2FSrCQ=s+uDXO!6Qll#lIvjts7>fQ4&e#+8g~UNzYo$^ z%S$h?mBrq;AhwuH8OExsl)KTlC7u_I57!^FtS1Bu1bA?xl(1><3klp%!SuIi@LsG3 z*TUryLm+=R2zmy1uY-WJkzskR6M`;J3V{B3jXUbn&nc+P4k)AuCqQg2Nnk;-l4Dz% z89844iQERzDP5X5B=U8zNoq+8Hf9q48H*G%>ACt?C28}wxm zfYc2S(9u);*zqdD8ZL8@6;VWMiIoOFz(wl&ZNW{gFofP~xMCRmF(78SJQZtBxTYf*FrYX@w);y$hGaJGV>O@?(hgwq}nyEhE;7%ZK-K71&KNtpU znDupfb|Qau_}%V!GSbH{Gxgk40e=b=9iV2jFV}l%Z9GMhRgm*edoIm z8Q){|!-9G7VKeuDa6o$9x0*5uLJWt|-4L4On^~UI#%?*PY^yrZLu4>^-AnAA4laV^auOm2_;C z844-Kipolqg!6S>*Y`g-Kb+e+ukn06?lo$plmeez;b!W|g4h9}CIv*kASFLPWDCzM zE=%Gzuw6Dt6M|(gCf61QDPR)lbkVf^bx!Y5Ec`<(CwLO*5SylYascpUGYJv_7AljY z$Urkq4)BN%iCeIxOoE(3y$A!I5vqx<8yQ?5vX&l+ z;jMyT>l_0BFcz$UXiR^hRwJU7+Nmx#GNkV|nuHt?SJGm5qv@*-FW?~+9|S4vikg*= zN*HP_+#hv1DKIGSQ{2)r@QQcs(*RI_EI~;rV+4AkHAXw;<%6|y<9AKe^y7_lcuWpV zfE1P#-c&bIq>XypYou6&kuIysaqRBi6EN_k~7>*`Jj->rIhbv)79!w-_M%;cWHIbl0eV%O1|s?`Bp2=Y-2>LnSVy9;yLr2vHEauBX1j_ZA+^|a5Q$E;a z^#D150D7RC-m>s+dDFmrZ!}y~$1V@cLtrmtfHQcG+~U_y@9*!ifQKVV#7(f|O^I(O z-@Qv5oaCsPx=;;%j=8MW1rQjb$<}bg$=h}F$)vuw@#S|`wosq)N7pIU=%euTZ$=#~ z3>NxT7Y(s7*5x;@tI6$#+x$vj`}uZSl;e2@1r@OWF^oobP0tD&B@t5g`CmmHO>aSG za{0B#>-+z-8fnwrPv!mMI=C`JaV+XB zpT&?A<9yfAjK4BgSaXmlA}~XtNoH&&+Ndh>aBpm`4bQY83?I^@s=f_ix6VE`1Pv)W$#%iC*rb`oEpG~P; z%t>DkOUBLVXI5E7B*o;A+>J@H-X+ETdqLi6M60sU8(=2Wl>Ti&$ozB;8A3*jG|S7I zt;bndX0n@0k;Gb){3lCdW|HWN%w7+90#t64XLK9gMZE)u9 zG4=Y^<698(fXllPDioJLV2%NpoSX>|$z2K(!6IuI4+@JkNeQvEGJ1@8QU}r?JTdLC zT-RK1lBJk_OGV7UW7fn>JS`|nHQ|va;6#)7NaRwyN}U}G6kq`b!&9P!KYGP1*^MrC z1el$0V4qmOt;?|bP5H5CHpv79H$`iXbqN#U!4 z#VWib^RY>}>?>M|k6KF7Z%TA%g2k6FSTNddl%z!8Pg=?V<+v}WyH7NRl0_9jsTtw% z5rB%!WLc7RPhG00b&^*EskupCj)a|5DX9h)6h0gOK@`?7dN*lnp$rbBQf1t78j+K_ zQ@;2q-C{vZ;M0&L=k05epwB=HM>3wds`OolO^bqCiL|7`Rw*a`G|_I_-XUq$I?)89 zWSvOVYDx&+lzvjvl83z`<&;rQ9X0jrz{QS5VIr*@gS7%#eB zI8MZaSTN$aWb>SLR%+v4+vDR&t51PD)7IE`RFFBOV`Su zEBdq0a8FVNchd0o(w@xClgzbL+($@*H8C=?C^zuRTuwaeeBx-MpfxIj#r;}R&!=)+dj`9S!myG~Z(u2o{KJn|f_(#5o39(RD*FH;D4E^{ zi^xGS7f1Cn|wP#hu*cO-uUunYX zhDu1Cuo?*qI4oS-`;6535a6Z=?Z4$_l#{YugQbOG%so?r@yVvR59;Z~8WgfxkZ!@l z8<+7xKy(oB&O;Uc6cM4f_xM<3=IO8Fpo{OvQcv56rqN`+?NATWjHKzGx4$K;ps*^t z$!UlnWnqW_4&og_N(kM?Kk5*LoS>Lb&_XBbRUHPqu;2UAN;wJK4G@i#6WyW{y{8>w z^j3gEq6ZNpFl&*K|`S6)Dm&}4ptl>3A*N-CcL7E#bPEThn6H_#aODQ zc+s;Ijiz|kC5+KTJR1PJHLP1pHp)X>v!m|6L|Al`D4bOK9^XN@d zS;82PpRukemnbHYw0iOY^x)!?c4}$WgLI^?$o}_5 zW|z&e%hj3ED3f4rz=qSwZt-bMd+&KrZ*=;Z?}xRkh}DbTqS(qe$#+oLJNV=eY_JWV zi<0c<@sDs-1@6{f?6=9)Utw2YAD$V&-~bp#iSRtS)*#54Z~9e@Ds|RAS5|(waR{c*j=C&_9-~PSbnbB>X!e(gQqBrS{Pa26Cmr16v2?GQ>Lwm@6d+sY3Z&cc!f4q+~u}>Hi1qzsl8_d zJnrL7mvAJ>3_N7<)KVl5>gDl4RWosevRFn_v{~ChFlyGA;t#nV0;%&4I2WspB?>Ie z3{*qK^C#4B08X7KytDu@66R$|)RNq9ccoy2pB@?AhAjtXsw`xz&jv}ZL<&_#n#s)E zxe0F9h($N|@MR4!dNpM+oStoJ8{LL{9o1s9P{%0S6JB{IfUv{$VM*7s zrrsgSG8%?@KO^nwlMm+bOT^7}StPM9^zpi{%#$u-I?@Z_%Yids!2YK(R{z4a3RPZr ztkVXx^QNPxGI;l5$Jri84K<3G-C;WLsUBBMQjWHLu3+i&vyN0Tz_*8807uH9hRc-wo$d`nUg*hV}dV#{-4L z1G76(puG{9LE5PAp%$-o0qcUlzP^6kZ$>$<7a{icJ8S@MSnY&o@ZpgLH#q>nisLBo zWc-M)1a^Q6NuvzlIO!I~Re9mpF@!t!4K=V|t;e4KnQKp$(=@oS9lxz9-6((dV_fR@ zI4wmh2twq;rQ~3lKrUP1EX^r22e)W|U8gh-T`<$5qYMk^JIK^h5(%{#Jct1bP+)Yn z6LUtj`uNC1kC^e$p^P|bH*5KRKCWL&xg1%^sa!udxhYPEkzty;n&ey5k#LDM)>*#g zvr4pF993i{ACK&>4Vef+{2fOr_-{lKA}1#;tRLW6pI29D%NzE03zH=Y3hItM9uTieli^2>?>$9#G_}a5U5(r8a9vK_!E#-+AtN zPRG$PgzUQQD6yLxI;Bm4{wC~b7t(ct1TCu189r+11sO7vb>X-!n+B=L%QN!Q>jW|j zHU3q<&Xxj6r~RE!U%ornE`3vzyTmB8?NP-{2t(bq29d7mHCOUts!pXNt=ocpE)xe( z`!7*x9qL(}u`u$pw_-7HHzc$g-sE^Gnx05r+1w-0K**ycg4!%I>b;;KGfV<4*m^N< z>eS7R@tvgzxYm8DNn2Th#Tp`Jy@M@i=;?9?9xQZZGk~bQFc|y87ccBSFz`Rv_)!Ix zEvcmLc~*I8;G8bH%%4@*1?HLAQ=$WZT9@oJtKaiDR?2mA?y+&W6!!}*E1EUy?ixDT z_XkO_AY&4NZ;?X>j?vawOXNc{*qtW-qYsCY1qCORv1OrIa@=rKDVqLaq1MYe z8EqkT>n*W&f?Ds%tTSI?G!tXquDuZ~)`&%pVbqAcfUxrSqPC<~C1xLSxJLxPAdswf zF_(RBp?8$)v()89w95jeGs|Vp2nbIBlXF7~DSZk2{`RGD8B_YG9Ca$U@DfdrYDu|* zoNtQOuZ`G~4KR;%oq0x!n-{0z<8SUaJId|1vx<>iMC^EmcmLNQM^-)efvT+n8w;`S~DCp%u8ipm#^QeJwiK^kP5nb)Vi z=hh#-{#KtYl8Fe9e*dzt$1WLg(Sh^pApq94;a2Z3 z5(&ujwLza|1_XlfnZEvN$my95T=4yF#Mq04DXHWb`7* z)u*!Ym`}8s5iiBAuNES-kCN_%Os8)$|`&{w-G<* z@#XSa+?{8Ojzqmm@Nv?_U)bSP2|129BRPTmKDP!FMA|ZpN}H5iS&lrfXD?iK@^2*^ zbUO`MLe2wn=z3_VzOpeDjvyE`wiUItN{}f9&g{0x88WB0uLx>6XqJH)mRNgo(xe}k zOSn6l0Z?0pGhD@}lWqWqf6Et5O6P|R>yH+J^Y*u#FO0e9O4*a4)Pid+{Q1h&b`M!= zO8&0-eXFcca7mZN+`brA#%%DnX$u%t2y1JZvLu{Yj`*{@Cv$Wbe@vLpE#(kg<;G=G zU#ABG;>0tC)n?<+lz?E4h6(}vR(eE?mj&TCieS-LyRXZexm4S~zlDD5H zuASC39g7xRK;LA8@^%fg8WPds0T33^5t+2llGB=S{rJ>oXN^QFl^9-<~(}L)-*xD&5UX1+JSm#_AjAWKbT% zgxh@@x3GhQ)oyh*DA9vq^b5BTnL4Hm4G}U;v37O!@@yHBAy#ogSGfjPRY5oH1~(%? z_qz@5j)MRF*YKYo@hj^j2#W@L+-<0BALK}ExL+yg)zIM8Cg|NG=siHN1EW|o;%F{V zf&>U%28ZKx3D^m8zSVH=1>A|e0nPB=*Dgb&1AaS650l3N!KxlM$pRsy^-#Rg4MV(@ zl8136W}ko$`L8h~Rw&r3F``l+ve3i)g}YXZ26Femd!j3V4CLHeFMwRg@Bm}@zK*c8 zsg=bb#+A!6Jtif^`GY6X?ys?4p4)nT5uz&tDxL@?45|PgdM<*N8me_3 z00w5VC4TA=|Fu?ECJwV*B`2u4;-;Hgx*PwsQpQGIT^OXit8p7kPixzh2?C$*?Id4~ zlUkq|FNniD7K4-kz}v3DDhv{z-Nf=bDGcrE*yDeo)z#W|(K3tsPHx(A)rc#NgwDwX z-Vw+Np3xJmWFq{q*v0P@IG6{p$djHpCa(U*>Bi{6VP*ZhmF zC?a*fjAIhvf=cGZN55yM#2If-iu}9y#v@vzL#jp3lEffblLZA<;=bj_e(REbjNTfm zIM|I|vF5>L3tB&B$@9!871ezJNO5Qhht)6&df_C!ipLrR1JG2$ae~(cf6edRRN!-` zsuoAl)`qIq*pcqD_@Z@IlSF(Dw(e=+)wu&m$1wm@hv-8@t(Kd+BxhJD>S5-$*8>_@6H?b-ujH0eY}awUMGlm@wU8U^VO4T8Rp{U z%n+T^mnhiCdEExbUop_MK+gMf=T#+UviSAv4Q}9kfGKpZE@5QMcj2zXWY5IM_yy*= znTLg~_ji4|d|S0Yuy)CWgc|4kWcgzULPtz8xCm*z>LCI*`BVbr`jO2)0zj(PXkc{o&|$ z8U!WjuY_ccRNsti@cMRbRJn@#g{(?c)Xx}2K3#6}=Sds!@!ZgbV`_Cl(7GE<)O8<* zs&9NR0)>Fj6(}yvc#p~JE_p`~b)I_Ga21{nLGpk-(kJLKW{L>NdCmm**3l2@_T!sS z(9uv*f#$vpi8pXWlHi}EcgUM};2^kf9EUy+P={|iLsFg&k&`065p+;Qyqz@K*}7fg z#Sw-1;kQ|-7aJe0=eEu#x2V&lD4#vmHfddRb}>+4nsSh4dM7dI7vT37f4fBtW+6?J z9Y9J9&}#DCOVt!2=c4<^$3n!N=Kb`rL7!{Zu|56CS&P&O5xq$%sp~05!LG>(si70< zp!D}bJL0Hl7-)1gp6MTOKRkp`bZRRARR#XKNPM7H8n66KKDC?tI|nv>H$w0?s8oRQ z8sn<}j_EoBTMMPsC$*&zqPij1o4}i*umGenPJ!zS|2sP7x>+?(h=g~Q#1FrBN{M8c z;p7NqwNz zD+j3?fhwCFq>VDV-5A)6gUV2dgqjTMULx7q64OIXvP3sM;xDr&ovROmsU9u>7V77K zh?$VA<&!TCe|2w+{6r*7()Znx5(~8q4+c4((wCW2Ave{Q669h|Ip3U|6doZW9_t?6 z;5fUX@u!QgOhyJ4%E83oa+M&8kaPUgs{QoWD%bVbgtd;0Xv2OY>XdWx-|ZewVu-P3 zSFqtp2PL3Lgeb!YUFkpH8W&^AW0!_Y>)=q~u|1Zzr95w?(m(T3l*Mz_&3tK*^M2NC zZ3iXU`W_y`YR=N(`?A|@*zfILkB(DnVL)mTCbbw2Eh#1|g(otPfE6b+WD=9m{d(oQ zyXrYTm2PNN91Vo*&v19xvGy!W&qQSOM9$a^8}yP zGD{AKg9SZ7G%Q1^{ZL>}|LKK(`-16j)jK4s>gVNR4`{-z>8oV^S<8Aub#+>dZ~wW> z>U*yHN4xIbi-^;gBk%eb-o4^a6fcfPT^QhJO{4sY3PYGURsH~q#51vPr#6wlovffX z5B+quLgbz*#Pt4j%a*hcPn?8iO%W(b_YG$*3}3R1+zg3Fb>*PMrvl&Rb)q z6wVWhbn8{f&<^+&KSHM4E%m2&|8JxoHcab`im>3e$uPanKdmZmq`o?sXk=7BqU(Ir})pHe4={xi>u}5qE?4m%>b}_RI-f^VHt> zx6cgvL7XxRtnSfFX*8bl^DKD=_?(cy8TO*FF^Wn~vylxF7X{tn)m}OM`_TX7u^nTE zD->FRAhAJ^-bb)RA>gSdT3{42J^{%AErk##Qt?!y;RW|Wptlo3Y}w4%0*|GvR0VZM}d@eC(&np9H8gwO}!5%Q3|*j)w;k} z<9T_FH|IW_-0@CS?r52?`m2{NZP#_KWp8%N?Y-c0lu(SBaHg5aw-(DSE&9o+8dcZi&wUBTQ&ANhfywNd_gY424tALnRd707=_x$~1DSOq?3zYCk4T6Uj_m;TFN%%$ z}GTz1_d+T+10m;>$W{q zp9d^itRyj&q4nefX;zO5>xd@4gxkdd&ci9oj#}mPTN`nH0;dTUW&pi{xB67^ zr&%OnMi($;& zCHJ$UD*QPxyEhtlKVEAPMsq#iwu3%uSFX~+I207ZVjn(62Hl>w`@=i9A7gL+GqCUP>KI`>0*yFCf!2KnY_5ilWtRFvGNZ z;?km^wc4Zh){!5=P&tAVkrxBAJZX_W^b(&`uay!H)S$b6G&sVODo!WJKrxvsRYq+% zTLZ7tB?IBY@*nGq6--LJYl-6jslzu&X+9~P+Y(^V@8cC%+c~YD{`S_77dJ%}t7_;Q zC3P->CRP6K(aRWIo$r(;y|t$`I_meT;fBhK5>nsY6ni_}AXtAg``eF$(wO@6WPaWl z-TF4q%U(E?L|q`h)lBbI+GK7fScW67kfp)#|7fqA@yRo%g6%e9e3L+?kjKJ%0hIX`^zAG|X`_kVMx)Oq-X(4@2R6jDN_)tAU` ztslQc|Lp!4e@lFV_;Kwa=qh|I)`80U3&-TUK|<0tXYqOpPs7J`tVnXiMw&F~*+zz9 za&NL@>Ym(ct{&4}%G(Wygc5%RDflc3qNwq;hF`xURn zGiz68vT%F8{F1qUz;f8H_@(SH?edD9kZtgZt@|mh@x{D{j49lPGklx8R#1%GnX29@ zKFyY`V~S~fT1RYEvyJh_=MX^NdK@us{z~GQOpEQXn$jem7bK4Ucr*NSfr^hEpr__= zw(jxce`i;T*TbvU-rB+D6pEKb?MPcRrU6lhMTb;0kEN zvCaH9b1j{>3U;A=MIvpvnf>wi(k877Xb`pBu@ep;@p;nw9a^ckzSVNSv6cX8ekOSN zZ1NCkmj~s)eowQhgX|u$l&c&|=ajR%a@etGs87%4q@HXE$>$9pI-7}7!?o4Ua%y$I zOB)rea*2rTzP%jG(=pm&VnCM|IB;p^x7KZ&pUu)Z8RE2|?S@_2f7Qjt{By`mM{a!y zq_zf}Zx4RjmZe`d(7fyvf$oxsexuWK6PyoSox~~1W2dS8%#ht@5V|I0y1yst_J@(L zDj%EfNK2AZU9yb9Hh8D?&do|D#XWAZ4#htVsIKfA+0ppaWUT-Amr$-V6j+VN=ybeK ze0Tj2`|t6~xDx`mo~Ne}PpO%lK0`+Oa;CH)#`KS;MP5#Alj#-wQF*6ZLzo$*1Ya39Prsg4$Yfe0E`9@i$ViV?;rS>4hNF75bt6A8Ibg%RFb~P~V zs->t8LX#Ms+k7s)(M7yvC>1TuH&#gqGQ$zP)yVB;X#cZ|(|^ky^wREIWn1r#%p?dC z_qMQ{heRqZzAWd-;+yx2*9~_^kH)eu{+3q3wV!p>lF)I5lW}O{K8K)DJDUq)@{$O-%ia;&m#Np9FOjF5F14vvc`XX+0$R`)Aq{tZUoJY#cCw%3sO> zQ$jk&o`oD`{(b36#GQ>>P9xF-U$~_>PeO6XTRaN9S%GA>- z_O{?=bJ{hs5=8+jvMG#H_aoJh8rt?M;CDl(h`fi*y={z+p{^> zLmnzlt~q?kc~Ws$+k75W#tU%RA5dxIxx)69!(F^@uSKjqpPKs;{^pj@#Hi$3GG5{R z=R;Nlnlvw$mIsW-&12VfGtak7*G67@oC~oQ%diKvI{_@#Kdb$l_bXm}%UM@Geboz} zxmWWF%HZsmG|r7)S)uWW{Cp7JtGo%~-hTD3@;q%sMFTDs@e38#4ISKY@uoT4)u=lC zBpDO(r0S}_P4%l98vV6C2W&}SH|;4E^-DhMVf~GPpD*NBzb)PX%685XybvyTtji6a za}gE}!qwT#_evV@l>a%j9sIoZc;YE95_3ktQ)K}Ci1^>XvjL)(0Z}{PWRm*Wa0YBM z+qh&rqErI}5rXms%@{UFBV31#5F}dJFd_2ltEVJMM=`nxzzn$Bddf2}^OrZ^;`}L@ z^Bs~oe|U2a5_4n9Nd!uL{Uo%V=X*BUEd*(G`z6Zn5717&cu4L+{ph;)&N2c)=kPGK zgMJ-?DonsXO(duNNaosU7EK6~x}^7y$b61?G-pBSvoGj6UK!4k*Gt{rZKV-7q$$bb z1tUp1CCMLT@&+JSLlCs1PcJH^D4TaLkhy>OX-|c7_c+ukrV=RJvv~{KdDHx0<2jTu zQmS0Ew|S)*7yTH2wDGLupjUA4_7px26boH8lUnv)B2zAHRbYkiEVB)QrGz#FfrL3} z-fzm}`zpm!+cBz6%Y5noU^<7*k`|&9h?JD3m+#=C?w}r)e#bWV>-!w*J1O{F2T3a} zB?t$dRF4n908TaZYNlM{rj&ZQbnD#Llm8Y-hW2VMJP(7W6S5u2yb{Oh6Gu+! zLS8t?H3XuC4^g)bay2v(t{;ThjzV0a|EEgC6@;xq)ob8w7r(R|7{4hs<3krNjbjqE~kBhYXu5VxTykNvTL zmZTt>7C_+OJ-K8rehLVqSogCTBlCEOF=nlpSrIuTJKl+zw-dQX;L_Y8M`@E?RsTx|4HGy(wku@e%0tt<*Q@v18|&d-)~@iP1O|{V$qz3_)(gsR!aEc3`YYBxnYh}#|TcmdF~Xbb2D7e|2UO&lEufMfwm2 zrV!oW1ClE=1!+8ec{TFw7-VJJ0V?FG4+uP{=9ZE*mkl*n>^4`CHBTRe3JV4Zo;vGx zTTp$qFqL((2(`Sdw{(zogztzbAjy1W$trmm4c|gaoteckNb)!iQWTO2;3ChLMyu2F z2HzyY;#no<#c$1QspR*Y=;Cdjs_cC#n}G=A)tZDvWe}r}lHQ4vV4J z-D-!=j1JGnG!4M=k)do6_?{IR_#T=e5g;?G=5z!AO&o^_i0lBx^@0xQLUL2{z{TUl zYt3!7+H|umka-KH38H4MvMxp#Y81g0E$5~c=BC%xwgH5J(1u;@?Me7zQEt0QQ4wHtU-%0>9U}WYkCF)Su6* zA4MKPR{pFp+9rpNyAV7hjU&XcfDzt{b3)MSLHGpm;+cp2I_SM zYRLr4_iEDj2GvUjpb!0ctb9NIUPMlMql*qTnYr&+(cWWb)BBU58Xl_C7D`*gL?RzF zo*6FScSGc3*gSPOje59Fc$hy;E2Km!#D@2!#P!8IWWijv zB}Pm7zh;gz=;fH&5x+B>iiV_dYNRzP*fvjJ*DzUwtpagle_r6A zSYY+Hz&)~1QL*s;-$IY&!obKPQ=6j5zeUol*S&g&&fek*7Ya><5@JDQNy+n)ioYe* zilz0DrOkhDwBw6Ao(o$LxO0HwSIdt+X~72~%VibI-~26i#h1_hEnAGNc=f#Eb4k&< zVx?UqX*)`@Q?bfeL-$#H_WhwM;&OI180Qg>yElY8RjmGJgR25p8w^!*msVGRYpOJA z%HnGnm1>1nYBIsK5<|6WrM2ncIWBH)eo;U|4@2N27Y>Ki)?aY9IEDO0hz!)HRYa5@Gr~AvCAlZdM2VM ztNKY=n_XJ}QwtLh=LC*)kHC4?1Bhazz+f1@>LHcoQ#T0c2}k$b zFRQF$?+q>M1rbDQgG8Uu0c|(MdT%;EcX>Yk>G=%%i$yymHKP!FE_vm*2wH`6W{;HN8PhyV*KnyROU?)yoL~?Xr>ZiU_bgkZnnp-sk=@6p@2#Cd$ z@ttrS-R36_#z5l{VIa!*Ys0>pjnswFYhA)fdDNBF*^g4GHhtW!{PA2NO?~-~D_^J~Bwc#SV-(aZfS< zq=TG2p5xIMbG-w-XkGxww!WyH>G{_zc08My~697Ow z8UrCYjH;0`1p2-~>0AuQe<+WXb2-TMAMPM$KKpxtiuV!@Z%EYV6+h4S3j6%QvyD_U z>L(bJfE5dFy|#&YFLwDJrv8DfW}c|_`A!VILee9J%x51j8J74QmhN%RXMP5^tWyGn zDd|D$#DCl^_yrj6;`YW|+FOzNGyTkim*?wcKS#Sgxm%>ZQH4?-Q(Kyh}|TK zXK1*X(u><%zU0pPv<~Cl5USjWyV{V}|0-L#ndyl95`$!tqhz~U2jTAT$LzU7Xof&E z`6!wNXBy}Rc@5}}w=)yb(;2CWhxH+uaO<+l&U3Ka;}u*R0+kYzT>Fca`yl-Oy5qsO zF9$!bWUuX@elEb;i94@sC#F)2RBiv`!2X&e_eSgi$^W7bAf&cOm$rY%4$*v@gyGkW z<1Z@ipDOo$zC*D?T|bG*eS-~wi@AU+)ji0)qkFH96xDw24E*+g_ydF_n{}oo-S{(F zxmV9EGqgTT;zG-N>!f6ywdV!$s0&r=%>6!ud-mkX-Tc+%nsXTVADKF|=k-6bjen*N z-jmg0k(|H-mCIIcV5#b0Z4C)*#Pur!;F4PafI%q(CWHEL!aFragqUqVR=Rd9ZJiu# zAJSR_X99@jsbCRByOU(+*kvsw5D*MH4ft!4q4@0U6#F7=e3S4eE$)9q_W4qW zGys>LE#$m0iC@SIVYRq%F@MW*j!Cbq2Wxwp{m_Z-u`m^8_5~@KEbZv$zrjPZwYd;u zDjeeZ2*8BrYbsX+c4ni$S5CjI@dqSrd#^lnVSw~MT`*$H2#i_o_AkmFunTSI-r;(1 zOavV<2r>OEniVCU@+XTp@0lbkRw#Qea{dA0p(1-rDeIQq7jaO=&Ih$md?%`Ly#bY*XFU?ZW=L7rPclHpH}B z)N0XnS`3%Nw{h_!oX2n%j{;fylI=>z`0MLEx6)KW0KLSQhS05hKYjh2>}^wRj(X%y zU8L8W?RpkYG7NZONj-^W$8$rlJm|fM`;+|dtlm}3bEPAS&3*Wm82>TF#(ZWX&roI; zvm(8|I%&ouY`0p+5e@Sfzb>?#lcB7ncA5AiKjY4PaIV~+Y7KGe zQ6R#E{Py>LI*6vZxNEk;-!O5hLDKC0fMFUPWob=k@%d?`=eUB|N!c~Z`f;W7@_?CV z>V*iZXOjs=LKLVituc0kA2JiSbsUa6EbNYrSMEm-cYox_E_-up|N0_rk!tk#P)p_F zk>(df_3@iKH?F*=gj&lXQ;#EWY)sJrCeB%0vGXs6)htnoZEOEugLp_CwQKU5khSq; z0ASZFR~UW{>TG|a$hDwc^7r-crP@@+_=RUFYotE^Lv9GyD7M;OxO%C#w(~~)npUHU zIeBmVbV<i0^ciw` z{UdHDZXT7H(1G*bn6?HLxvmkY;lnI%1CnK0*0r2+GA%K)_mZ3%Dx*GpTJCZ%%i0o{8|9V)Jn%ETfRD*v6a?x4M{2D$+luDbsw>nHhS-cI7`aH-L zjfhXNC0y&rwG^H$n4J}!8{%88v?|w+BKeEtonJk6U~f`qyb8pMP67bdNryEbpb)w~ zfzNNL6SyH#sOEIYeI+^~e-K!>;e6;@Hq7_xEs84IdN|~Y+-_pGyWvL#7|0VzQ3+UA zF#H}=)W27M<009k6M1m)h?XmH7-Ps6P$vMEpf;L?Sb2HB^nQ$Ak7WvhD) z@~_FJ1JZ)ax5OJ2XHus_9tT(K`83{MBb$kM8(ewP(x`HnI`iOra7Nck<8>Et7BetU zcQX!4al$v7C>l~t`AQJYPCkd#52=xo!SMF*Qr$)o>nK;+QzU=m8xj|)uO)_LCW#uo z?&hz$ve(J`Lep%I3xHw<1Cv1U!@ZX_+1^(-89yXnz`6WK`vEabedUxb37}wSyHLat zGAqZ?nY-X@kh|SHmpr6~ZL*WkfM{yLBeTi+Vkw@nOFAua*O?=97R`Agw9xl9v@L`r zOL?d$$4tSKzDrM6Q2lY5T~iwybEL5502?-u5T`(<2Q}?NBN+5M+VWdl+!@mnAL3n~ z9pPa=oSf4#lNs0wFcYjt9U52`Ii7o?>gxP1+^Cjoz2|IPS;3no*gmYce_ul7*-^IS ziBq2nmeo`1li>SOrfw!131DDFJzZdnW?>&dQC#o!H+~}%2KL*+U$YxgFF|q`mq%of z@nm>%Ii7N4ix$(I)d%&4`Z+2Qps6e;FrTUa;#z}vR+1XB7YDm5ta(`cHkEsohl7X! z0WGLS?mf^G#y1e<$L-)tl+~TzqlYnHow3})AcWB6(^TV(4QFaR;v;@s(ThhC2w131 zI2(TiNSP%`xAM|?lH9)Pc>mWnYnb_$6mXo=5xQ4HE#lYts7icND-rV6qOG%_R}U_} jhoafXzAbo7`Bh5n7yV|tj+|(Rtn`z}sd)-GaQpuO(_5`= literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_intersection_module/scripts/ttc.py b/planning/behavior_velocity_intersection_module/scripts/ttc.py index e4633981570d1..6d1593d95f055 100755 --- a/planning/behavior_velocity_intersection_module/scripts/ttc.py +++ b/planning/behavior_velocity_intersection_module/scripts/ttc.py @@ -126,8 +126,11 @@ def plot_ttc(self): self.ttc_ax.set_xlabel("ego time") self.ttc_ax.set_ylabel("ego dist") time_dist_plot = self.ttc_ax.plot(ego_ttc_time, ego_ttc_dist, label="time-dist", c="orange") - self.ttc_ax.set_xlim(min(ego_ttc_time) - 2.0, max(ego_ttc_time) + 3.0) - self.ttc_ax.set_ylim(min(ego_ttc_dist) - 2.0, max(ego_ttc_dist) + 3.0) + self.ttc_ax.set_xlim( + min(ego_ttc_time) - 2.0, + min(max(ego_ttc_time) + 3.0, self.args.max_time), + ) + # self.ttc_ax.set_ylim(min(ego_ttc_dist) - 2.0, max(ego_ttc_dist) + 3.0) for npc, color in zip(self.npc_vehicles, cycle(self.color_list)): t0, t1 = npc.collision_start_time, npc.collision_end_time d0, d1 = npc.collision_start_dist, npc.collision_end_dist @@ -137,15 +140,13 @@ def plot_ttc(self): c=color, alpha=0.2, ) - dd = [d1 - d0 for d0, d1 in zip(ego_ttc_dist, ego_ttc_dist[1:])] dt = [t1 - t0 for t0, t1 in zip(ego_ttc_time, ego_ttc_time[1:])] v = [d / t for d, t in zip(dd, dt)] self.ttc_vel_ax.yaxis.set_label_position("right") self.ttc_vel_ax.set_ylabel("ego velocity") - self.ttc_vel_ax.set_ylim(0.0, max(v) + 1.0) + # self.ttc_vel_ax.set_ylim(0.0, max(v) + 1.0) time_velocity_plot = self.ttc_vel_ax.plot(ego_ttc_time[1:], v, label="time-v", c="red") - lines = time_dist_plot + time_velocity_plot labels = [line.get_label() for line in lines] self.ttc_ax.legend(lines, labels, loc="upper left") @@ -218,6 +219,7 @@ def cleanup(self): if self.args.save: kwargs_write = {"fps": self.args.fps, "quantizer": "nq"} imageio.mimsave("./" + self.args.gif + ".gif", self.images, **kwargs_write) + rclpy.shutdown() def on_plot_timer(self): with self.lock: @@ -277,6 +279,7 @@ def on_object_ttc(self, msg): default=60, help="detect range for drawing", ) + parser.add_argument("--max_time", type=float, default=100, help="max plot limit for time") parser.add_argument("-s", "--save", action="store_true", help="flag to save gif") parser.add_argument("--gif", type=str, default="ttc", help="filename of gif file") parser.add_argument("--fps", type=float, default=5, help="fps of gif") diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index a9d0f56266181..e6e6fa0a1da9a 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include #include @@ -1304,14 +1305,27 @@ TimeDistanceArray calcIntersectionPassingTime( const bool use_upstream_velocity, const double minimum_upstream_velocity, tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) { - double dist_sum = 0.0; + const double current_velocity = planner_data->current_velocity->twist.linear.x; + int assigned_lane_found = false; // crop intersection part of the path, and set the reference velocity to intersection_velocity // for ego's ttc PathWithLaneId reference_path; - for (size_t i = closest_idx; i < path.points.size(); ++i) { + std::optional upstream_stop_line{std::nullopt}; + for (size_t i = 0; i < path.points.size() - 1; ++i) { auto reference_point = path.points.at(i); + // assume backward velocity is current ego velocity + if (i < closest_idx) { + reference_point.point.longitudinal_velocity_mps = current_velocity; + } + if ( + i > last_intersection_stop_line_candidate_idx && + std::fabs(reference_point.point.longitudinal_velocity_mps) < + std::numeric_limits::epsilon() && + !upstream_stop_line) { + upstream_stop_line = i; + } if (!use_upstream_velocity) { reference_point.point.longitudinal_velocity_mps = intersection_velocity; } @@ -1326,28 +1340,46 @@ TimeDistanceArray calcIntersectionPassingTime( return {{0.0, 0.0}}; // has already passed the intersection. } + std::vector> original_path_xy; + for (size_t i = 0; i < reference_path.points.size(); ++i) { + const auto & p = reference_path.points.at(i).point.pose.position; + original_path_xy.emplace_back(p.x, p.y); + } + // apply smoother to reference velocity PathWithLaneId smoothed_reference_path = reference_path; - smoothPath(reference_path, smoothed_reference_path, planner_data); + if (!smoothPath(reference_path, smoothed_reference_path, planner_data)) { + smoothed_reference_path = reference_path; + } // calculate when ego is going to reach each (interpolated) points on the path TimeDistanceArray time_distance_array{}; - dist_sum = 0.0; + double dist_sum = 0.0; double passing_time = time_delay; time_distance_array.emplace_back(passing_time, dist_sum); // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so // `last_intersection_stop_line_candidate_idx` makes no sense - const auto last_intersection_stop_line_candidate_point_orig = - path.points.at(last_intersection_stop_line_candidate_idx).point.pose; - const auto last_intersection_stop_line_candidate_nearest_ind = - motion_utils::findFirstNearestIndexWithSoftConstraints( - smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, - planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + const auto smoothed_path_closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, path.points.at(closest_idx).point.pose, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + + const std::optional upstream_stop_line_idx_opt = [&]() -> std::optional { + if (upstream_stop_line) { + const auto upstream_stop_line_point = path.points.at(upstream_stop_line.value()).point.pose; + return motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, upstream_stop_line_point, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + } else { + return std::nullopt; + } + }(); + const bool has_upstream_stopline = upstream_stop_line_idx_opt.has_value(); + const size_t upstream_stopline_ind = upstream_stop_line_idx_opt.value_or(0); - for (size_t i = 1; i < smoothed_reference_path.points.size(); ++i) { - const auto & p1 = smoothed_reference_path.points.at(i - 1); - const auto & p2 = smoothed_reference_path.points.at(i); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { + const auto & p1 = smoothed_reference_path.points.at(i); + const auto & p2 = smoothed_reference_path.points.at(i + 1); const double dist = tier4_autoware_utils::calcDistance2d(p1, p2); dist_sum += dist; @@ -1355,12 +1387,16 @@ TimeDistanceArray calcIntersectionPassingTime( // use average velocity between p1 and p2 const double average_velocity = (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; - const double minimum_ego_velocity_division = - (use_upstream_velocity && i > last_intersection_stop_line_candidate_nearest_ind) - ? minimum_upstream_velocity /* to avoid null division */ - : minimum_ego_velocity; - const double passing_velocity = - std::max(minimum_ego_velocity_division, average_velocity); + const double passing_velocity = [=]() { + if (use_upstream_velocity) { + if (has_upstream_stopline && i > upstream_stopline_ind) { + return minimum_upstream_velocity; + } + return std::max(average_velocity, minimum_ego_velocity); + } else { + return std::max(average_velocity, minimum_ego_velocity); + } + }(); passing_time += (dist / passing_velocity); time_distance_array.emplace_back(passing_time, dist_sum); @@ -1370,6 +1406,8 @@ TimeDistanceArray calcIntersectionPassingTime( debug_ttc_array->layout.dim.at(0).size = 5; debug_ttc_array->layout.dim.at(1).label = "values"; debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); + debug_ttc_array->data.reserve( + time_distance_array.size() * debug_ttc_array->layout.dim.at(0).size); for (unsigned i = 0; i < time_distance_array.size(); ++i) { debug_ttc_array->data.push_back(lane_id); } @@ -1379,11 +1417,13 @@ TimeDistanceArray calcIntersectionPassingTime( for (const auto & [t, d] : time_distance_array) { debug_ttc_array->data.push_back(d); } - for (const auto & p : smoothed_reference_path.points) { - debug_ttc_array->data.push_back(p.point.pose.position.x); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.x); } - for (const auto & p : smoothed_reference_path.points) { - debug_ttc_array->data.push_back(p.point.pose.position.y); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.y); } return time_distance_array; } diff --git a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 71cdd9650a598..7fe8612cc6858 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -88,15 +88,14 @@ bool smoothPath( const auto & smoother = planner_data->velocity_smoother_; auto trajectory = convertPathToTrajectoryPoints(in_path); - if (external_v_limit) { - motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - 0, trajectory.size(), external_v_limit->max_velocity, trajectory); - } const auto traj_lateral_acc_filtered = smoother->applyLateralAccelerationFilter(trajectory); + const auto traj_steering_rate_limited = + smoother->applySteeringRateLimit(traj_lateral_acc_filtered, false); + // Resample trajectory with ego-velocity based interval distances auto traj_resampled = smoother->resampleTrajectory( - traj_lateral_acc_filtered, v0, current_pose, planner_data->ego_nearest_dist_threshold, + traj_steering_rate_limited, v0, current_pose, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); const size_t traj_resampled_closest = motion_utils::findFirstNearestIndexWithSoftConstraints( traj_resampled, current_pose, planner_data->ego_nearest_dist_threshold, @@ -114,6 +113,10 @@ bool smoothPath( traj_smoothed.insert( traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); + if (external_v_limit) { + motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( + traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + } out_path = convertTrajectoryPointsToPath(traj_smoothed); return true; } From c6d6fc10a4217de804b20ee87717f60702bec0ce Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 8 Nov 2023 18:32:41 +0900 Subject: [PATCH 070/223] fix: add_ros_test to add_launch_test (#5486) * fix: add_ros_test to add_launch_test Signed-off-by: kminoda * fix ndt_scan_matcher Signed-off-by: kminoda --------- Signed-off-by: kminoda --- localization/ekf_localizer/CMakeLists.txt | 4 ++-- localization/ndt_scan_matcher/CMakeLists.txt | 2 +- map/map_loader/CMakeLists.txt | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 45d420bafff10..9944cbb84d97c 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -43,11 +43,11 @@ function(add_testcase filepath) endfunction() if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/test_ekf_localizer_launch.py TIMEOUT "30" ) - add_ros_test( + add_launch_test( test/test_ekf_localizer_mahalanobis.py TIMEOUT "30" ) diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 6fe61cd25bc6e..4beecc2625fe3 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -38,7 +38,7 @@ link_directories(${PCL_LIBRARY_DIRS}) target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES} glog::glog) if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/test_ndt_scan_matcher_launch.py TIMEOUT "30" ) diff --git a/map/map_loader/CMakeLists.txt b/map/map_loader/CMakeLists.txt index b94eaac7ee34d..115f7e5b17464 100644 --- a/map/map_loader/CMakeLists.txt +++ b/map/map_loader/CMakeLists.txt @@ -46,7 +46,7 @@ rclcpp_components_register_node(lanelet2_map_visualization_node ) if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/lanelet2_map_loader_launch.test.py TIMEOUT "30" ) From 3462f27bfef26c34d2ec1f7d97533f03e192231d Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 8 Nov 2023 20:59:48 +0900 Subject: [PATCH 071/223] refactor(behavior_path_planner): remove status_.pull_over_lanes (#5520) * Remove unused variable and update function arguments in start_planner_module.hpp and util.hpp/cpp Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 1 - .../start_planner/start_planner_module.cpp | 43 +++++++++++-------- .../src/utils/start_planner/util.cpp | 7 ++- 3 files changed, 28 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 8ea963fec0b8d..91121598cb3ae 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -59,7 +59,6 @@ struct PullOutStatus size_t current_path_idx{0}; PlannerType planner_type{PlannerType::NONE}; PathWithLaneId backward_path{}; - lanelet::ConstLanelets pull_out_lanes{}; bool found_pull_out_path{false}; // current path is safe against static objects bool is_safe_dynamic_objects{false}; // current path is safe against dynamic objects bool driving_forward{false}; // if ego is driving on backward path, this is set to false diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index e3670710b64f0..bd042f8ecef4d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -619,8 +619,11 @@ PathWithLaneId StartPlannerModule::generateStopPath() const PathPointWithLaneId p{}; p.point.pose = pose; p.point.longitudinal_velocity_mps = 0.0; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, + planner_data_->parameters.backward_path_length + parameters_->max_back_distance); lanelet::Lanelet closest_lanelet; - lanelet::utils::query::getClosestLanelet(status_.pull_out_lanes, pose, &closest_lanelet); + lanelet::utils::query::getClosestLanelet(pull_out_lanes, pose, &closest_lanelet); p.lane_ids.push_back(closest_lanelet.id()); return p; }; @@ -664,13 +667,15 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId std::vector StartPlannerModule::generateDrivableLanes( const PathWithLaneId & path) const { + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + const auto path_road_lanes = getPathRoadLanes(path); if (!path_road_lanes.empty()) { lanelet::ConstLanelets shoulder_lanes; const auto & rh = planner_data_->route_handler; std::copy_if( - status_.pull_out_lanes.begin(), status_.pull_out_lanes.end(), - std::back_inserter(shoulder_lanes), + pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes), [&rh](const auto & pull_out_lane) { return rh->isShoulderLanelet(pull_out_lane); }); return utils::generateDrivableLanesWithShoulderLanes(path_road_lanes, shoulder_lanes); @@ -678,7 +683,7 @@ std::vector StartPlannerModule::generateDrivableLanes( // if path_road_lanes is empty, use only pull_out_lanes as drivable lanes std::vector drivable_lanes; - for (const auto & lane : status_.pull_out_lanes) { + for (const auto & lane : pull_out_lanes) { DrivableLanes drivable_lane; drivable_lane.right_lane = lane; drivable_lane.left_lane = lane; @@ -693,11 +698,6 @@ void StartPlannerModule::updatePullOutStatus() !planner_data_->prev_route_id || *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); - // save pull out lanes which is generated using current pose before starting pull out - // (before approval) - status_.pull_out_lanes = start_planner_utils::getPullOutLanes( - planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // skip updating if enough time has not passed for preventing chattering between back and // start_planner if (!has_received_new_route) { @@ -734,12 +734,15 @@ void StartPlannerModule::updatePullOutStatus() planWithPriority( start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + if (isBackwardDrivingComplete()) { updateStatusAfterBackwardDriving(); current_state_ = ModuleStatus::SUCCESS; // for breaking loop } else { status_.backward_path = start_planner_utils::getBackwardPath( - *route_handler, status_.pull_out_lanes, current_pose, status_.pull_out_start_pose, + *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, parameters_->backward_velocity); } } @@ -761,12 +764,14 @@ PathWithLaneId StartPlannerModule::calcStartPoseCandidatesBackwardPath() const { const Pose & current_pose = planner_data_->self_odometry->pose.pose; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + // get backward shoulder path - const auto arc_position_pose = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, current_pose); + const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose); const double check_distance = parameters_->max_back_distance + 30.0; // buffer auto path = planner_data_->route_handler->getCenterLinePath( - status_.pull_out_lanes, arc_position_pose.length - check_distance, + pull_out_lanes, arc_position_pose.length - check_distance, arc_position_pose.length + check_distance); // lateral shift to current_pose @@ -785,18 +790,20 @@ std::vector StartPlannerModule::searchPullOutStartPoses( std::vector pull_out_start_pose{}; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + // filter pull out lanes stop objects const auto [pull_out_lane_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( - *planner_data_->dynamic_object, status_.pull_out_lanes, + *planner_data_->dynamic_object, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( pull_out_lane_objects, parameters_->th_moving_object_velocity); // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. - const double s_current = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, current_pose).length; + const double s_current = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose).length; const double max_back_distance = std::clamp( s_current - planner_data_->parameters.base_link2rear, 0.0, parameters_->max_back_distance); @@ -812,10 +819,10 @@ std::vector StartPlannerModule::searchPullOutStartPoses( // check the back pose is near the lane end const double length_to_backed_pose = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, *backed_pose).length; + lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length; const double length_to_lane_end = std::accumulate( - std::begin(status_.pull_out_lanes), std::end(status_.pull_out_lanes), 0.0, + std::begin(pull_out_lanes), std::end(pull_out_lanes), 0.0, [](double acc, const auto & lane) { return acc + lanelet::utils::getLaneletLength2d(lane); }); const double distance_from_lane_end = length_to_lane_end - length_to_backed_pose; if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 40b100a1bc070..7b4d4566bba27 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -89,15 +89,14 @@ lanelet::ConstLanelets getPullOutLanes( { const double & vehicle_width = planner_data->parameters.vehicle_width; const auto & route_handler = planner_data->route_handler; - const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & start_pose = planner_data->route_handler->getOriginalStartPose(); lanelet::ConstLanelet current_shoulder_lane; lanelet::ConstLanelets shoulder_lanes; if (route_handler->getPullOutStartLane( - route_handler->getShoulderLanelets(), current_pose, vehicle_width, - ¤t_shoulder_lane)) { + route_handler->getShoulderLanelets(), start_pose, vehicle_width, ¤t_shoulder_lane)) { // pull out from shoulder lane - return route_handler->getShoulderLaneletSequence(current_shoulder_lane, current_pose); + return route_handler->getShoulderLaneletSequence(current_shoulder_lane, start_pose); } // pull out from road lane From 3e8c7bf6df79a9f4027f01e0310036606098aa0a Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Wed, 8 Nov 2023 17:31:40 +0300 Subject: [PATCH 072/223] build(lidar_apollo_segmentation_tvm and lidar_apollo_segmentation_tvm_nodes): remove download from cmake (#5431) * add include tier4_autoware_utils and dependency Signed-off-by: Alexey Panferov * remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * build(tvm_utility): remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix lint_cmake error Signed-off-by: Alexey Panferov * build(tvm_utility): format warning message Signed-off-by: Alexey Panferov * build(tvm_utility): add logic to work with autoware_data folder, add nn config header and test image Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): refactor, update InferenceEngineTVM constructor Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add lightweight model and test with it Signed-off-by: Alexey Panferov * build(tvm_utility): make building yolo_v2_tiny disable by default Signed-off-by: Alexey Panferov * build(tvm_utility): remove test artifact for yolo_v2_tiny Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): update namespace in abs_model test Signed-off-by: Alexey Panferov * build(tvm_utility): rewrite yolo_v2_tiny as example Signed-off-by: Alexey Panferov * build(tvm_utility): clean comments in yolo_v2_tiny example main.cpp Signed-off-by: Alexey Panferov * build(tvm_utility): add launch file for yolo_v2_tiny example Signed-off-by: Alexey Panferov * build(tvm_utility): update yolo_v2_tiny example readme Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add model for arm based systems, need to be tested on device Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): update config header for arm Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): remove debug output Signed-off-by: Alexey Panferov * build(tvm_utility): add find_package conditional section Signed-off-by: Alexey Panferov * build(tvm_utility): fix lint_cmake errors Signed-off-by: Alexey Panferov * build(tvm_utility): remove coping model files during build Signed-off-by: Alexey Panferov * build(tvm_utility): update readme with new data folder structure Signed-off-by: Alexey Panferov * build(tvm_utility): fix spell check warnings Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add no model files guard to get_neural_network Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): set back default paths in config headers Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation): wip update launch files Signed-off-by: Alexey Panferov * build(tvm_utility): add param file, update launch file Signed-off-by: Alexey Panferov * build(tvm_utility): add schema file, update node name Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add parameter table to example readme Signed-off-by: Alexey Panferov * build(tvm_utility): fix typo-error in description of schema.json Signed-off-by: Alexey Panferov * style(pre-commit): autofix * buiild(tvm_utility): fix spell-check warning and typo Signed-off-by: Alexey Panferov * feat(spell-check): add dltype and tvmgen to local dict Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm): remove test Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): add data_path to constructor Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): add data_path to param file Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): add allow_substs to launches Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm_nodes): update README Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): update README Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): fix schema typo Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): remove unused import Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): suppress cpplint Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): suppress cpplint Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): return test back and update it Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm): fix cpplilnt errors Signed-off-by: Alexey Panferov * build(lidar_apollo_segmenntation_tvm): update checking for models files Signed-off-by: Alexey Panferov * style(pre-commit): autofix --------- Signed-off-by: Alexey Panferov Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../lidar_apollo_segmentation_tvm/.gitignore | 1 - .../lidar_apollo_segmentation_tvm/README.md | 7 ++- .../baidu_cnn/inference_engine_tvm_config.hpp | 55 +++++++++++++++++++ .../lidar_apollo_segmentation_tvm.hpp | 3 +- .../src/lidar_apollo_segmentation_tvm.cpp | 4 +- .../test/main.cpp | 40 ++++++++++++-- .../README.md | 2 +- ...r_apollo_segmentation_tvm_nodes.param.yaml | 1 + ...ar_apollo_segmentation_tvm_nodes.launch.py | 11 +++- ...r_apollo_segmentation_tvm_nodes.launch.xml | 3 +- ..._apollo_segmentation_tvm_nodes.schema.json | 8 ++- .../lidar_apollo_segmentation_tvm_node.cpp | 2 +- 12 files changed, 117 insertions(+), 20 deletions(-) delete mode 100644 perception/lidar_apollo_segmentation_tvm/.gitignore create mode 100644 perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp diff --git a/perception/lidar_apollo_segmentation_tvm/.gitignore b/perception/lidar_apollo_segmentation_tvm/.gitignore deleted file mode 100644 index 8fce603003c1e..0000000000000 --- a/perception/lidar_apollo_segmentation_tvm/.gitignore +++ /dev/null @@ -1 +0,0 @@ -data/ diff --git a/perception/lidar_apollo_segmentation_tvm/README.md b/perception/lidar_apollo_segmentation_tvm/README.md index d1337304fbf06..72fb26105e63e 100644 --- a/perception/lidar_apollo_segmentation_tvm/README.md +++ b/perception/lidar_apollo_segmentation_tvm/README.md @@ -6,9 +6,10 @@ #### Neural network -This package will not build without a neural network for its inference. -The network is provided by the cmake function exported by the tvm_utility package. -See its design page for more information on how to enable downloading pre-compiled networks (by setting the `DOWNLOAD_ARTIFACTS` cmake variable), or how to handle user-compiled networks. +This package will not run without a neural network for its inference. +The network is provided by ansible script during the installation of Autoware or can be downloaded manually according to [Manual Downloading](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts). +This package uses 'get_neural_network' function from tvm_utility package to create and provide proper dependency. +See its design page for more information on how to handle user-compiled networks. #### Backend diff --git a/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp b/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..d7541df046532 --- /dev/null +++ b/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp @@ -0,0 +1,55 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace baidu_cnn +{ +namespace onnx_bcnn +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "baidu_cnn", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"data", kDLFloat, 32, 1, {1, 4, 864, 864}}}, // network_inputs + + {{"deconv0", kDLFloat, 32, 1, {1, 12, 864, 864}}} // network_outputs +}; + +} // namespace onnx_bcnn +} // namespace baidu_cnn +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp index b9734a41d28ae..7f8c5f51f73a6 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp @@ -141,10 +141,11 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation /// \param[in] height_thresh If it is non-negative, the points that are higher than the predicted /// object height by height_thresh are filtered out in the /// post-processing step. + /// \param[in] data_path The path to autoware data and artifacts folder explicit ApolloLidarSegmentation( int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature, float z_offset, float min_height, float max_height, float objectness_thresh, - int32_t min_pts_num, float height_thresh); + int32_t min_pts_num, float height_thresh, const std::string & data_path); /// \brief Detect obstacles. /// \param[in] input Input pointcloud. diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index e6c95f202106d..85f0a69356d55 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -108,7 +108,7 @@ std::shared_ptr ApolloLidarSegmentationPostProcessor ApolloLidarSegmentation::ApolloLidarSegmentation( int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature, float z_offset, float min_height, float max_height, float objectness_thresh, int32_t min_pts_num, - float height_thresh) + float height_thresh, const std::string & data_path) : range_(range), score_threshold_(score_threshold), z_offset_(z_offset), @@ -118,7 +118,7 @@ ApolloLidarSegmentation::ApolloLidarSegmentation( pcl_pointcloud_ptr_(new pcl::PointCloud), PreP(std::make_shared( config, range, use_intensity_feature, use_constant_feature, min_height, max_height)), - IE(std::make_shared(config, "lidar_apollo_segmentation_tvm")), + IE(std::make_shared(config, "lidar_apollo_segmentation_tvm", data_path)), PostP(std::make_shared( config, pcl_pointcloud_ptr_, range, objectness_thresh, score_threshold, height_thresh, min_pts_num)), diff --git a/perception/lidar_apollo_segmentation_tvm/test/main.cpp b/perception/lidar_apollo_segmentation_tvm/test/main.cpp index 9fd644afff1f2..06cff2a67e908 100644 --- a/perception/lidar_apollo_segmentation_tvm/test/main.cpp +++ b/perception/lidar_apollo_segmentation_tvm/test/main.cpp @@ -17,14 +17,18 @@ #include +#include #include #include #include #include using autoware::perception::lidar_apollo_segmentation_tvm::ApolloLidarSegmentation; +namespace fs = std::filesystem; -void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bool expect_throw) +void test_segmentation( + const std::string & data_path, bool use_intensity_feature, bool use_constant_feature, + bool expect_throw) { // Instantiate the pipeline const int width = 1; @@ -37,9 +41,10 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo const float objectness_thresh = 0.5f; const int32_t min_pts_num = 3; const float height_thresh = 0.5f; + ApolloLidarSegmentation segmentation( range, score_threshold, use_intensity_feature, use_constant_feature, z_offset, min_height, - max_height, objectness_thresh, min_pts_num, height_thresh); + max_height, objectness_thresh, min_pts_num, height_thresh, data_path); auto version_status = segmentation.version_check(); EXPECT_NE(version_status, tvm_utility::Version::Unsupported); @@ -85,8 +90,31 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo // Other test configurations to increase code coverage. TEST(lidar_apollo_segmentation_tvm, others) { - test_segmentation(false, true, false); - test_segmentation(true, true, false); - test_segmentation(false, false, false); - test_segmentation(true, false, false); + std::string home = std::getenv("HOME"); + fs::path data_path(home); + data_path /= "autoware_data"; + fs::path apollo_data_path(data_path); + apollo_data_path /= "lidar_apollo_segmentation_tvm"; + fs::path deploy_path(apollo_data_path); + deploy_path /= "models/baidu_cnn"; + + fs::path deploy_graph("deploy_graph.json"); + fs::path deploy_lib("deploy_lib.so"); + fs::path deploy_param("deploy_param.params"); + + fs::path deploy_graph_path = deploy_path / deploy_graph; + fs::path deploy_lib_path = deploy_path / deploy_lib; + fs::path deploy_param_path = deploy_path / deploy_param; + + if ( + !fs::exists(deploy_graph_path) || !fs::exists(deploy_lib_path) || + !fs::exists(deploy_param_path)) { + printf("Model deploy files not found. Skip test.\n"); + GTEST_SKIP(); + return; + } + test_segmentation(data_path, false, true, false); + test_segmentation(data_path, true, true, false); + test_segmentation(data_path, false, false, false); + test_segmentation(data_path, true, false, false); } diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/README.md b/perception/lidar_apollo_segmentation_tvm_nodes/README.md index 488eea4f92168..a9ffd59f228ec 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/README.md +++ b/perception/lidar_apollo_segmentation_tvm_nodes/README.md @@ -28,7 +28,7 @@ See the design of the algorithm in the core (lidar_apollo_segmentation_tvm) pack ### Usage -`lidar_apollo_segmentation_tvm` and `lidar_apollo_segmentation_tvm_nodes` will not build without a neural network. +`lidar_apollo_segmentation_tvm` and `lidar_apollo_segmentation_tvm_nodes` will not work without a neural network. See the lidar_apollo_segmentation_tvm usage for more information. ### Assumptions / Known limits diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml b/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml index 97f733f01c794..30bf0ba68d28c 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml +++ b/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml @@ -24,3 +24,4 @@ objectness_thresh: 0.5 min_pts_num: 3 height_thresh: 0.5 + data_path: $(env HOME)/autoware_data diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py index f4c81d6b154d7..2d070f2611ac5 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py +++ b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py @@ -21,7 +21,7 @@ from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -import yaml +import launch_ros.parameter_descriptions def generate_launch_description(): @@ -29,12 +29,17 @@ def generate_launch_description(): get_package_share_directory("lidar_apollo_segmentation_tvm_nodes"), "config/lidar_apollo_segmentation_tvm_nodes.param.yaml", ) - with open(param_file, "r") as f: - lidar_apollo_segmentation_tvm_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] + + lidar_apollo_segmentation_tvm_node_params = launch_ros.parameter_descriptions.ParameterFile( + param_file=param_file, allow_substs=True + ) arguments = [ DeclareLaunchArgument("input/pointcloud", default_value="/sensing/lidar/pointcloud"), DeclareLaunchArgument("output/objects", default_value="labeled_clusters"), + DeclareLaunchArgument( + "data_path", default_value=os.path.join(os.environ["HOME"], "autoware_data") + ), ] # lidar segmentation node execution definition. diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml index 0d7bebe986df4..c97d7356f5616 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml +++ b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml @@ -23,6 +23,7 @@ - + + diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json b/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json index 8e56cfb820766..aaabbf2b65879 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json +++ b/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json @@ -61,6 +61,11 @@ "type": "number", "default": 0.5, "description": "If it is non-negative, the points that are higher than the predicted object height by height_thresh are filtered out in the post-processing step." + }, + "data_path": { + "type": "string", + "default": "$(env HOME)/autoware_data", + "description": "Packages data and artifacts directory path." } }, "required": [ @@ -73,7 +78,8 @@ "max_height", "objectness_thresh", "min_pts_num", - "height_thresh" + "height_thresh", + "data_path" ] } }, diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp b/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp index 8f1d3301cf3a2..618d2e258c99b 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp +++ b/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp @@ -41,7 +41,7 @@ ApolloLidarSegmentationNode::ApolloLidarSegmentationNode(const rclcpp::NodeOptio declare_parameter("use_constant_feature"), declare_parameter("z_offset"), declare_parameter("min_height"), declare_parameter("max_height"), declare_parameter("objectness_thresh"), declare_parameter("min_pts_num"), - declare_parameter("height_thresh"))} + declare_parameter("height_thresh"), declare_parameter("data_path"))} { // Log unexpected versions of the neural network. auto version_status = m_detector_ptr->version_check(); From e3f8a3763ec891f4bfe6c4873e5dbfbb3965ccf3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 08:09:21 +0900 Subject: [PATCH 073/223] refactor(tier4_planning_launch): align argument name (#5505) * chore(tier4_planning_launch): align arument name Signed-off-by: satoshi-ota * refactor(tier4_planning_launch): pass params directly Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_planning.launch.xml | 117 +++++++++++++++++ .../motion_planning.launch.xml | 2 +- .../config/scene_module_manager.param.yaml | 10 -- .../launch/behavior_path_planner.launch.xml | 77 +++++++++-- ...t_behavior_path_planner_node_interface.cpp | 13 ++ .../behavior_velocity_planner.param.yaml | 17 --- .../behavior_velocity_planner.launch.xml | 121 ++++++++---------- .../test/src/test_node_interface.cpp | 21 +++ 8 files changed, 275 insertions(+), 103 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 085dc92982663..ba2318c438674 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -5,6 +5,112 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -23,6 +129,16 @@ + + + + + + + + + + @@ -66,6 +182,7 @@ + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 577b0e00d133c..a8dbcfd372226 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -180,7 +180,7 @@ - + diff --git a/planning/behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/config/scene_module_manager.param.yaml index 5797704e8a0ca..91e34c0e91931 100644 --- a/planning/behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/config/scene_module_manager.param.yaml @@ -4,7 +4,6 @@ /**: ros__parameters: external_request_lane_change_left: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true @@ -13,7 +12,6 @@ max_module_size: 1 external_request_lane_change_right: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true @@ -22,7 +20,6 @@ max_module_size: 1 lane_change_left: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true @@ -31,7 +28,6 @@ max_module_size: 1 lane_change_right: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true @@ -40,7 +36,6 @@ max_module_size: 1 start_planner: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -49,7 +44,6 @@ max_module_size: 1 side_shift: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -58,7 +52,6 @@ max_module_size: 1 goal_planner: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -67,7 +60,6 @@ max_module_size: 1 avoidance: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false @@ -76,7 +68,6 @@ max_module_size: 1 avoidance_by_lc: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -85,7 +76,6 @@ max_module_size: 1 dynamic_avoidance: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true diff --git a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml index a4d3cab3c1bf0..d1dac8ad8d93e 100644 --- a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -1,20 +1,77 @@ + - - + + + + - - + + + + + + + + + + + + + + + + + + + + + + + + + - - + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index ec2d01e44940a..423fcd2b05048 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -48,6 +48,19 @@ std::shared_ptr generateNode() const auto behavior_path_planner_dir = ament_index_cpp::get_package_share_directory("behavior_path_planner"); + std::vector params; + params.emplace_back("avoidance.enable_module", true); + params.emplace_back("avoidance_by_lc.enable_module", true); + params.emplace_back("dynamic_avoidance.enable_module", true); + params.emplace_back("lane_change_right.enable_module", true); + params.emplace_back("lane_change_left.enable_module", true); + params.emplace_back("external_request_lane_change_right.enable_module", true); + params.emplace_back("external_request_lane_change_left.enable_module", true); + params.emplace_back("goal_planner.enable_module", true); + params.emplace_back("start_planner.enable_module", true); + params.emplace_back("side_shift.enable_module", true); + node_options.parameter_overrides(params); + test_utils::updateNodeOptions( node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", diff --git a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml index 276e8f8e3145a..aa51c38b55742 100644 --- a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml +++ b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml @@ -8,20 +8,3 @@ system_delay: 0.5 delay_response_time: 0.5 is_publish_debug_path: false # publish all debug path with lane id in each module - launch_modules: - - behavior_velocity_planner::CrosswalkModulePlugin - - behavior_velocity_planner::WalkwayModulePlugin - - behavior_velocity_planner::TrafficLightModulePlugin - - behavior_velocity_planner::IntersectionModulePlugin # Intersection module should be before merge from private to declare intersection parameters. - - behavior_velocity_planner::MergeFromPrivateModulePlugin - - behavior_velocity_planner::BlindSpotModulePlugin - - behavior_velocity_planner::DetectionAreaModulePlugin - # behavior_velocity_planner::VirtualTrafficLightModulePlugin - - behavior_velocity_planner::NoStoppingAreaModulePlugin # No stopping area module requires all the stop line. Therefore this modules should be placed at the bottom. - - behavior_velocity_planner::StopLineModulePlugin # Permanent stop line module should be after no stopping area - # behavior_velocity_planner::OcclusionSpotModulePlugin - # behavior_velocity_planner::RunOutModulePlugin - # behavior_velocity_planner::SpeedBumpModulePlugin - # behavior_velocity_planner::TemplateModulePlugin - - behavior_velocity_planner::OutOfLaneModulePlugin - - behavior_velocity_planner::NoDrivableLaneModulePlugin diff --git a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index 69d9c27331e52..46472619d5fb0 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -1,82 +1,73 @@ - - + + + + - - - - + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - + - + - - - + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp index 6756a82ca20d4..491df4c7a8766 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp @@ -59,6 +59,27 @@ std::shared_ptr generateNode() return package_path + "/config/" + module + ".param.yaml"; }; + std::vector module_names; + module_names.emplace_back("behavior_velocity_planner::CrosswalkModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::WalkwayModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::TrafficLightModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::IntersectionModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::MergeFromPrivateModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::BlindSpotModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::DetectionAreaModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::VirtualTrafficLightModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::NoStoppingAreaModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::StopLineModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::OcclusionSpotModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::RunOutModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::SpeedBumpModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::OutOfLaneModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::NoDrivableLaneModulePlugin"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + test_utils::updateNodeOptions( node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", From 56d804f14062752e009966ab197400f202ad4a33 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 9 Nov 2023 11:55:54 +0900 Subject: [PATCH 074/223] refactor(system_error_monitor): hide error log in no-fault condition (#5522) Signed-off-by: Takamasa Horibe --- .../system_error_monitor_core.hpp | 2 ++ .../src/system_error_monitor_core.cpp | 31 ++++++++++++++----- 2 files changed, 25 insertions(+), 8 deletions(-) diff --git a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp index 0bb95882700a5..4dbf8813805e3 100644 --- a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp +++ b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp @@ -148,6 +148,8 @@ class AutowareErrorMonitor : public rclcpp::Node bool canAutoRecovery() const; bool isEmergencyHoldingRequired() const; + void loggingErrors(const autoware_auto_system_msgs::msg::HazardStatus & diag_array); + std::unique_ptr logger_configure_; }; diff --git a/system/system_error_monitor/src/system_error_monitor_core.cpp b/system/system_error_monitor/src/system_error_monitor_core.cpp index e74ac9c360164..c7fdfa61f1d2c 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -140,17 +140,9 @@ diagnostic_msgs::msg::DiagnosticArray convertHazardStatusToDiagnosticArray( diag_array.status.push_back(decorateDiag(hazard_diag, "[Safe Fault]")); } for (const auto & hazard_diag : hazard_status.diag_latent_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, clock, 5000, "[Latent Fault]: " + hazard_diag.message); - diag_array.status.push_back(decorateDiag(hazard_diag, "[Latent Fault]")); } for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, clock, 5000, "[Single Point Fault]: " + hazard_diag.message); - diag_array.status.push_back(decorateDiag(hazard_diag, "[Single Point Fault]")); } @@ -688,6 +680,9 @@ void AutowareErrorMonitor::publishHazardStatus( hazard_status_stamped.stamp = this->now(); hazard_status_stamped.status = hazard_status; pub_hazard_status_->publish(hazard_status_stamped); + + loggingErrors(hazard_status_stamped.status); + pub_diagnostics_err_->publish( convertHazardStatusToDiagnosticArray(this->get_clock(), hazard_status_stamped.status)); } @@ -703,3 +698,23 @@ bool AutowareErrorMonitor::onClearEmergencyService( return true; } + +void AutowareErrorMonitor::loggingErrors( + const autoware_auto_system_msgs::msg::HazardStatus & hazard_status) +{ + if (isInNoFaultCondition(*autoware_state_, *current_gate_mode_)) { + RCLCPP_DEBUG(get_logger(), "Autoware is in no-fault condition."); + return; + } + + for (const auto & hazard_diag : hazard_status.diag_latent_fault) { + const std::string logger_name = "system_error_monitor " + hazard_diag.name; + logThrottledNamed( + logger_name, get_clock(), 5000, "[Latent Fault]: " + hazard_diag.message); + } + for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { + const std::string logger_name = "system_error_monitor " + hazard_diag.name; + logThrottledNamed( + logger_name, get_clock(), 5000, "[Single Point Fault]: " + hazard_diag.message); + } +} From 90f873c3e5c48f2123ec82a7cc7a99c7574c94e0 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 12:40:49 +0900 Subject: [PATCH 075/223] feat(behavior_path_planner): add option to insert zero velocity to the center line path (#5517) feat(behavior_path_planner): Add option to insert zero velocity to the center line path This commit adds a new boolean parameter, `insert_zero_velocity`, to the `getCenterLinePath` function in the `utils.hpp` file. When set to `true`, this parameter will insert a zero velocity to each point in the path. In the `utils.cpp` file, this option is used to insert zero velocities to the reference path generated in the `createGoalAroundPath` function. Signed-off-by: kyoichi-sugahara --- planning/behavior_path_planner/src/utils/utils.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 62a48da85ba2c..19c408359e5f2 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -974,9 +974,11 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); output.reference_path = std::make_shared(reference_path); output.drivable_area_info.drivable_lanes = drivable_lanes; From 6bfb0e5e3aaf136ae096b1f76e15426d7a6a6515 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 13:56:20 +0900 Subject: [PATCH 076/223] refactor(start_planner): support new interface (#5526) Update getCurrentStatus() function in StartPlannerModule.cpp Signed-off-by: kyoichi-sugahara --- .../src/scene_module/start_planner/start_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index bd042f8ecef4d..77a290835fb31 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -172,7 +172,7 @@ bool StartPlannerModule::isExecutionRequested() const bool StartPlannerModule::isModuleRunning() const { - return current_state_ == ModuleStatus::RUNNING; + return getCurrentStatus() == ModuleStatus::RUNNING; } bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const From c4c384124f271574e27ef30fcaaccf3ac07d4820 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 14:20:23 +0900 Subject: [PATCH 077/223] refactor(goal_planner): support new interface (#5525) Signed-off-by: satoshi-ota --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6d34ce4ecde38..69c1fb911c4f9 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -296,7 +296,7 @@ void GoalPlannerModule::processOnExit() bool GoalPlannerModule::isExecutionRequested() const { - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } From eb2eb5853501adda166d3e8167b03d5fb6f73bcb Mon Sep 17 00:00:00 2001 From: Yuqi Huai <34195403+YuqiHuai@users.noreply.github.com> Date: Wed, 8 Nov 2023 22:08:13 -0800 Subject: [PATCH 078/223] refactor(gyro_odometer): rework parameters (#5243) * refactor(gyro_odometer): rework parameters Signed-off-by: Yuqi Huai * style(pre-commit): autofix * doc(gyro_odometer): remove copyright --------- Signed-off-by: Yuqi Huai Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/gyro_odometer/CMakeLists.txt | 1 + localization/gyro_odometer/README.md | 5 +-- .../config/gyro_odometer.param.yaml | 4 ++ .../launch/gyro_odometer.launch.xml | 6 +-- .../schema/gyro_odometer.schema.json | 38 +++++++++++++++++++ .../gyro_odometer/src/gyro_odometer_core.cpp | 4 +- 6 files changed, 48 insertions(+), 10 deletions(-) create mode 100644 localization/gyro_odometer/config/gyro_odometer.param.yaml create mode 100644 localization/gyro_odometer/schema/gyro_odometer.schema.json diff --git a/localization/gyro_odometer/CMakeLists.txt b/localization/gyro_odometer/CMakeLists.txt index 59a5e1121b22f..57589837dd529 100644 --- a/localization/gyro_odometer/CMakeLists.txt +++ b/localization/gyro_odometer/CMakeLists.txt @@ -32,4 +32,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/localization/gyro_odometer/README.md b/localization/gyro_odometer/README.md index ec50a113af4d9..e9e390010f084 100644 --- a/localization/gyro_odometer/README.md +++ b/localization/gyro_odometer/README.md @@ -21,10 +21,7 @@ ## Parameters -| Parameter | Type | Description | -| --------------------- | ------ | -------------------------------- | -| `output_frame` | String | output's frame id | -| `message_timeout_sec` | Double | delay tolerance time for message | +{{ json_to_markdown("localization/gyro_odometer/schema/gyro_odometer.schema.json") }} ## Assumptions / Known limits diff --git a/localization/gyro_odometer/config/gyro_odometer.param.yaml b/localization/gyro_odometer/config/gyro_odometer.param.yaml new file mode 100644 index 0000000000000..420a9b0d80582 --- /dev/null +++ b/localization/gyro_odometer/config/gyro_odometer.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + output_frame: "base_link" + message_timeout_sec: 0.2 diff --git a/localization/gyro_odometer/launch/gyro_odometer.launch.xml b/localization/gyro_odometer/launch/gyro_odometer.launch.xml index aeb505270b2cc..21aff3e10d26c 100644 --- a/localization/gyro_odometer/launch/gyro_odometer.launch.xml +++ b/localization/gyro_odometer/launch/gyro_odometer.launch.xml @@ -9,8 +9,7 @@ - - + @@ -23,7 +22,6 @@ - - + diff --git a/localization/gyro_odometer/schema/gyro_odometer.schema.json b/localization/gyro_odometer/schema/gyro_odometer.schema.json new file mode 100644 index 0000000000000..189df2a2f63f3 --- /dev/null +++ b/localization/gyro_odometer/schema/gyro_odometer.schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for gyro odometer", + "type": "object", + "definitions": { + "gyro_odometer": { + "type": "object", + "properties": { + "output_frame": { + "type": "string", + "description": "output's frame id", + "default": "base_link" + }, + "message_timeout_sec": { + "type": "number", + "description": "delay tolerance time for message", + "default": 0.2 + } + }, + "required": ["output_frame", "message_timeout_sec"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/gyro_odometer" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index c14c48ffb2046..5de0ecd7cdc0a 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -102,8 +102,8 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer( GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options) : Node("gyro_odometer", options), - output_frame_(declare_parameter("output_frame", "base_link")), - message_timeout_sec_(declare_parameter("message_timeout_sec", 0.2)), + output_frame_(declare_parameter("output_frame")), + message_timeout_sec_(declare_parameter("message_timeout_sec")), vehicle_twist_arrived_(false), imu_arrived_(false) { From 62de92ae3ccbf84763bc2e485ed4cc30c9a792a9 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 9 Nov 2023 15:29:56 +0900 Subject: [PATCH 079/223] refactor(ar_tag_based_localizer): refactor `ar_tag_based_localizer` (#5521) * Refactored ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * Refactor ArTagBasedLocalizer class to use shorter type names Signed-off-by: Shintaro Sakoda * Fix const correctness in ar_tag_based_localizer.cpp Signed-off-by: Shintaro Sakoda * Fix position difference calculation in ArTagBasedLocalizer Signed-off-by: Shintaro Sakoda * Renamed arg name Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../ar_tag_based_localizer/package.xml | 1 + .../src/ar_tag_based_localizer.cpp | 156 ++++++++---------- .../src/ar_tag_based_localizer.hpp | 39 +++-- 3 files changed, 92 insertions(+), 104 deletions(-) diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index c0d1b00e35d3b..a22e7b1acf6dc 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -19,6 +19,7 @@ image_transport landmark_parser lanelet2_extension + localization_util rclcpp tf2_eigen tf2_geometry_msgs diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index 73e7b8b7e3587..bc40fb1532297 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -44,6 +44,8 @@ #include "ar_tag_based_localizer.hpp" +#include "localization_util/util_func.hpp" + #include #include #include @@ -111,18 +113,19 @@ bool ArTagBasedLocalizer::setup() /* Subscribers */ - map_bin_sub_ = this->create_subscription( + map_bin_sub_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); + rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); qos_sub.best_effort(); - image_sub_ = this->create_subscription( + image_sub_ = this->create_subscription( "~/input/image", qos_sub, std::bind(&ArTagBasedLocalizer::image_callback, this, std::placeholders::_1)); - cam_info_sub_ = this->create_subscription( + cam_info_sub_ = this->create_subscription( "~/input/camera_info", qos_sub, std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1)); - ekf_pose_sub_ = this->create_subscription( + ekf_pose_sub_ = this->create_subscription( "~/input/ekf_pose", qos_sub, std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, std::placeholders::_1)); @@ -132,29 +135,25 @@ bool ArTagBasedLocalizer::setup() rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10)); qos_marker.transient_local(); qos_marker.reliable(); - marker_pub_ = - this->create_publisher("~/debug/marker", qos_marker); + marker_pub_ = this->create_publisher("~/debug/marker", qos_marker); rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); image_pub_ = it_->advertise("~/debug/result", 1); - pose_pub_ = this->create_publisher( - "~/output/pose_with_covariance", qos_pub); - diag_pub_ = - this->create_publisher("/diagnostics", qos_pub); + pose_pub_ = + this->create_publisher("~/output/pose_with_covariance", qos_pub); + diag_pub_ = this->create_publisher("/diagnostics", qos_pub); RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!"); return true; } -void ArTagBasedLocalizer::map_bin_callback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg) +void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { landmark_map_ = parse_landmark(msg, "apriltag_16h5", this->get_logger()); - const visualization_msgs::msg::MarkerArray marker_msg = - convert_to_marker_array_msg(landmark_map_); + const MarkerArray marker_msg = convert_to_marker_array_msg(landmark_map_); marker_pub_->publish(marker_msg); } -void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) +void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) { if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); @@ -166,7 +165,7 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha return; } - builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; + const builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; cv_bridge::CvImagePtr cv_ptr; try { cv_ptr = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::RGB8); @@ -185,20 +184,20 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha // for each marker, draw info and its boundaries in the image for (const aruco::Marker & marker : markers) { - tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); + const tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); - geometry_msgs::msg::TransformStamped tf_cam_to_marker_stamped; + TransformStamped tf_cam_to_marker_stamped; tf2::toMsg(tf_cam_to_marker, tf_cam_to_marker_stamped.transform); tf_cam_to_marker_stamped.header.stamp = curr_stamp; tf_cam_to_marker_stamped.header.frame_id = msg->header.frame_id; tf_cam_to_marker_stamped.child_frame_id = "detected_marker_" + std::to_string(marker.id); tf_broadcaster_->sendTransform(tf_cam_to_marker_stamped); - geometry_msgs::msg::PoseStamped pose_cam_to_marker; + PoseStamped pose_cam_to_marker; tf2::toMsg(tf_cam_to_marker, pose_cam_to_marker.pose); pose_cam_to_marker.header.stamp = curr_stamp; - pose_cam_to_marker.header.frame_id = std::to_string(marker.id); - publish_pose_as_base_link(pose_cam_to_marker, msg->header.frame_id); + pose_cam_to_marker.header.frame_id = msg->header.frame_id; + publish_pose_as_base_link(pose_cam_to_marker, std::to_string(marker.id)); // drawing the detected markers marker.draw(in_image, cv::Scalar(0, 0, 255), 2); @@ -240,7 +239,7 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha key_value.value = std::to_string(detected_tags); diag_status.values.push_back(key_value); - diagnostic_msgs::msg::DiagnosticArray diag_msg; + DiagnosticArray diag_msg; diag_msg.header.stamp = this->now(); diag_msg.status.push_back(diag_status); @@ -248,17 +247,13 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha } // wait for one camera info, then shut down that subscriber -void ArTagBasedLocalizer::cam_info_callback(const sensor_msgs::msg::CameraInfo & msg) +void ArTagBasedLocalizer::cam_info_callback(const CameraInfo & msg) { if (cam_info_received_) { return; } cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0); - cv::Mat distortion_coeff(4, 1, CV_64FC1); - cv::Size size(static_cast(msg.width), static_cast(msg.height)); - - camera_matrix.setTo(0); camera_matrix.at(0, 0) = msg.p[0]; camera_matrix.at(0, 1) = msg.p[1]; camera_matrix.at(0, 2) = msg.p[2]; @@ -272,111 +267,88 @@ void ArTagBasedLocalizer::cam_info_callback(const sensor_msgs::msg::CameraInfo & camera_matrix.at(2, 2) = msg.p[10]; camera_matrix.at(2, 3) = msg.p[11]; + cv::Mat distortion_coeff(4, 1, CV_64FC1); for (int i = 0; i < 4; ++i) { distortion_coeff.at(i, 0) = 0; } + const cv::Size size(static_cast(msg.width), static_cast(msg.height)); + cam_param_ = aruco::CameraParameters(camera_matrix, distortion_coeff, size); cam_info_received_ = true; } -void ArTagBasedLocalizer::ekf_pose_callback( - const geometry_msgs::msg::PoseWithCovarianceStamped & msg) +void ArTagBasedLocalizer::ekf_pose_callback(const PoseWithCovarianceStamped & msg) { latest_ekf_pose_ = msg; } void ArTagBasedLocalizer::publish_pose_as_base_link( - const geometry_msgs::msg::PoseStamped & msg, const std::string & camera_frame_id) + const PoseStamped & sensor_to_tag, const std::string & tag_id) { - // Check if frame_id is in target_tag_ids - if ( - std::find(target_tag_ids_.begin(), target_tag_ids_.end(), msg.header.frame_id) == - target_tag_ids_.end()) { - RCLCPP_INFO_STREAM( - this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in target_tag_ids"); + // Check tag_id + if (std::find(target_tag_ids_.begin(), target_tag_ids_.end(), tag_id) == target_tag_ids_.end()) { + RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in target_tag_ids"); + return; + } + if (landmark_map_.count(tag_id) == 0) { + RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in landmark_map_"); return; } // Range filter - const double distance_squared = msg.pose.position.x * msg.pose.position.x + - msg.pose.position.y * msg.pose.position.y + - msg.pose.position.z * msg.pose.position.z; + const double distance_squared = sensor_to_tag.pose.position.x * sensor_to_tag.pose.position.x + + sensor_to_tag.pose.position.y * sensor_to_tag.pose.position.y + + sensor_to_tag.pose.position.z * sensor_to_tag.pose.position.z; if (distance_threshold_squared_ < distance_squared) { return; } - // Transform map to tag - if (landmark_map_.count(msg.header.frame_id) == 0) { - RCLCPP_INFO_STREAM( - this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in landmark_map_"); - return; - } - const geometry_msgs::msg::Pose & tag_pose = landmark_map_.at(msg.header.frame_id); - geometry_msgs::msg::TransformStamped map_to_tag_tf; - map_to_tag_tf.header.stamp = msg.header.stamp; - map_to_tag_tf.header.frame_id = "map"; - map_to_tag_tf.child_frame_id = msg.header.frame_id; - map_to_tag_tf.transform.translation.x = tag_pose.position.x; - map_to_tag_tf.transform.translation.y = tag_pose.position.y; - map_to_tag_tf.transform.translation.z = tag_pose.position.z; - map_to_tag_tf.transform.rotation = tag_pose.orientation; - - // Transform camera to base_link - geometry_msgs::msg::TransformStamped camera_to_base_link_tf; + // Transform to base_link + PoseStamped base_link_to_tag; try { - camera_to_base_link_tf = - tf_buffer_->lookupTransform(camera_frame_id, "base_link", tf2::TimePointZero); + const TransformStamped transform = + tf_buffer_->lookupTransform("base_link", sensor_to_tag.header.frame_id, tf2::TimePointZero); + tf2::doTransform(sensor_to_tag, base_link_to_tag, transform); + base_link_to_tag.header.frame_id = "base_link"; } catch (tf2::TransformException & ex) { RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what()); return; } - // Convert ROS Transforms to Eigen matrices for easy matrix multiplication and inversion - Eigen::Affine3d map_to_tag = tf2::transformToEigen(map_to_tag_tf.transform); - Eigen::Affine3d camera_to_base_link = tf2::transformToEigen(camera_to_base_link_tf.transform); - Eigen::Affine3d camera_to_tag = Eigen::Affine3d( - Eigen::Translation3d(msg.pose.position.x, msg.pose.position.y, msg.pose.position.z) * - Eigen::Quaterniond( - msg.pose.orientation.w, msg.pose.orientation.x, msg.pose.orientation.y, - msg.pose.orientation.z)); - Eigen::Affine3d tag_to_camera = camera_to_tag.inverse(); + // (1) map_to_tag + const Pose & map_to_tag = landmark_map_.at(tag_id); + const Eigen::Affine3d map_to_tag_affine = pose_to_affine3d(map_to_tag); - // Final pose calculation - Eigen::Affine3d map_to_base_link = map_to_tag * tag_to_camera * camera_to_base_link; + // (2) tag_to_base_link + const Eigen::Affine3d base_link_to_tag_affine = pose_to_affine3d(base_link_to_tag.pose); + const Eigen::Affine3d tag_to_base_link_affine = base_link_to_tag_affine.inverse(); - // Construct output message - geometry_msgs::msg::PoseWithCovarianceStamped pose_with_covariance_stamped; - pose_with_covariance_stamped.header.stamp = msg.header.stamp; - pose_with_covariance_stamped.header.frame_id = "map"; - pose_with_covariance_stamped.pose.pose = tf2::toMsg(map_to_base_link); + // calculate map_to_base_link + const Eigen::Affine3d map_to_base_link_affine = map_to_tag_affine * tag_to_base_link_affine; + const Pose map_to_base_link = tf2::toMsg(map_to_base_link_affine); // If latest_ekf_pose_ is older than seconds compared to current frame, it // will not be published. - const rclcpp::Duration tolerance{ - static_cast(ekf_time_tolerance_), - static_cast((ekf_time_tolerance_ - std::floor(ekf_time_tolerance_)) * 1e9)}; - if (rclcpp::Time(latest_ekf_pose_.header.stamp) + tolerance < rclcpp::Time(msg.header.stamp)) { + const rclcpp::Duration diff_time = + rclcpp::Time(sensor_to_tag.header.stamp) - rclcpp::Time(latest_ekf_pose_.header.stamp); + if (diff_time.seconds() > ekf_time_tolerance_) { RCLCPP_INFO( this->get_logger(), "latest_ekf_pose_ is older than %f seconds compared to current frame. " - "latest_ekf_pose_.header.stamp: %d.%d, msg.header.stamp: %d.%d", + "latest_ekf_pose_.header.stamp: %d.%d, sensor_to_tag.header.stamp: %d.%d", ekf_time_tolerance_, latest_ekf_pose_.header.stamp.sec, latest_ekf_pose_.header.stamp.nanosec, - msg.header.stamp.sec, msg.header.stamp.nanosec); + sensor_to_tag.header.stamp.sec, sensor_to_tag.header.stamp.nanosec); return; } // If curr_pose differs from latest_ekf_pose_ by more than , it will not // be published. - const geometry_msgs::msg::Pose curr_pose = pose_with_covariance_stamped.pose.pose; - const geometry_msgs::msg::Pose latest_ekf_pose = latest_ekf_pose_.pose.pose; - const double diff_x = curr_pose.position.x - latest_ekf_pose.position.x; - const double diff_y = curr_pose.position.y - latest_ekf_pose.position.y; - const double diff_z = curr_pose.position.z - latest_ekf_pose.position.z; - const double diff_distance_squared = diff_x * diff_x + diff_y * diff_y + diff_z * diff_z; - const double threshold = ekf_position_tolerance_ * ekf_position_tolerance_; - if (threshold < diff_distance_squared) { + const Pose curr_pose = map_to_base_link; + const Pose latest_ekf_pose = latest_ekf_pose_.pose.pose; + const double diff_position = norm(curr_pose.position, latest_ekf_pose.position); + if (diff_position > ekf_position_tolerance_) { RCLCPP_INFO( this->get_logger(), "curr_pose differs from latest_ekf_pose_ by more than %f m. " @@ -386,6 +358,12 @@ void ArTagBasedLocalizer::publish_pose_as_base_link( return; } + // Construct output message + PoseWithCovarianceStamped pose_with_covariance_stamped; + pose_with_covariance_stamped.header.stamp = sensor_to_tag.header.stamp; + pose_with_covariance_stamped.header.frame_id = "map"; + pose_with_covariance_stamped.pose.pose = curr_pose; + // ~5[m]: base_covariance // 5~[m]: scaling base_covariance by std::pow(distance/5, 3) const double distance = std::sqrt(distance_squared); diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index 6bd66eead653f..fe33a64b995a3 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -66,17 +66,26 @@ class ArTagBasedLocalizer : public rclcpp::Node { + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using Image = sensor_msgs::msg::Image; + using CameraInfo = sensor_msgs::msg::CameraInfo; + using Pose = geometry_msgs::msg::Pose; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; + using TransformStamped = geometry_msgs::msg::TransformStamped; + using MarkerArray = visualization_msgs::msg::MarkerArray; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + public: explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); bool setup(); private: - void map_bin_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg); - void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg); - void cam_info_callback(const sensor_msgs::msg::CameraInfo & msg); - void ekf_pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped & msg); - void publish_pose_as_base_link( - const geometry_msgs::msg::PoseStamped & msg, const std::string & camera_frame_id); + void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); + void image_callback(const Image::ConstSharedPtr & msg); + void cam_info_callback(const CameraInfo & msg); + void ekf_pose_callback(const PoseWithCovarianceStamped & msg); + void publish_pose_as_base_link(const PoseStamped & sensor_to_tag, const std::string & tag_id); static tf2::Transform aruco_marker_to_tf2(const aruco::Marker & marker); // Parameters @@ -96,23 +105,23 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr it_; // Subscribers - rclcpp::Subscription::SharedPtr map_bin_sub_; - rclcpp::Subscription::SharedPtr image_sub_; - rclcpp::Subscription::SharedPtr cam_info_sub_; - rclcpp::Subscription::SharedPtr ekf_pose_sub_; + rclcpp::Subscription::SharedPtr map_bin_sub_; + rclcpp::Subscription::SharedPtr image_sub_; + rclcpp::Subscription::SharedPtr cam_info_sub_; + rclcpp::Subscription::SharedPtr ekf_pose_sub_; // Publishers - rclcpp::Publisher::SharedPtr marker_pub_; + rclcpp::Publisher::SharedPtr marker_pub_; image_transport::Publisher image_pub_; - rclcpp::Publisher::SharedPtr pose_pub_; - rclcpp::Publisher::SharedPtr diag_pub_; + rclcpp::Publisher::SharedPtr pose_pub_; + rclcpp::Publisher::SharedPtr diag_pub_; // Others aruco::MarkerDetector detector_; aruco::CameraParameters cam_param_; bool cam_info_received_; - geometry_msgs::msg::PoseWithCovarianceStamped latest_ekf_pose_{}; - std::map landmark_map_; + PoseWithCovarianceStamped latest_ekf_pose_{}; + std::map landmark_map_; }; #endif // AR_TAG_BASED_LOCALIZER_HPP_ From 7b71000e87d1f9c197f4632a289231cae96ee214 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 16:43:11 +0900 Subject: [PATCH 080/223] refactor(motion_utils): fix typo in calcLongitudinalOffsetPose return (#5528) Fix typo in calcLongitudinalOffsetPose return statement Signed-off-by: kyoichi-sugahara --- .../motion_utils/include/motion_utils/trajectory/trajectory.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 5d773c5be32d9..61dc65c5ea3f2 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -1251,7 +1251,7 @@ calcLongitudinalOffsetPose boost::optional calcLongitudinalOffsetPose( From 805933c2dc15f7db829830196f53630bbaa3f222 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 9 Nov 2023 17:29:28 +0900 Subject: [PATCH 081/223] fix(simple_planning_simulator): set ego pitch to 0 if road slope is not simulated (#5501) set ego pitch to 0 if road slope is not simulated Signed-off-by: Daniel Sanchez --- .../simple_planning_simulator_core.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index d7e25860c8abf..f2629a0586045 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -326,9 +326,9 @@ void SimplePlanningSimulator::on_timer() } // calculate longitudinal acceleration by slope - const double ego_pitch_angle = calculate_ego_pitch(); - const double acc_by_slope = - enable_road_slope_simulation_ ? -9.81 * std::sin(ego_pitch_angle) : 0.0; + constexpr double gravity_acceleration = -9.81; + const double ego_pitch_angle = enable_road_slope_simulation_ ? calculate_ego_pitch() : 0.0; + const double acc_by_slope = gravity_acceleration * std::sin(ego_pitch_angle); // update vehicle dynamics { From b8bfaea163f74a4398aa7f6381f295e6919de2c0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 19:12:48 +0900 Subject: [PATCH 082/223] refactor(dynamic_avoidance): support new interface (#5527) Signed-off-by: satoshi-ota --- .../dynamic_avoidance_module.hpp | 22 +------------------ .../dynamic_avoidance_module.cpp | 12 +++------- 2 files changed, 4 insertions(+), 30 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 6c522c79a8774..077e0ecec0f29 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -273,29 +273,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface parameters_ = std::any_cast>(parameters); } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override - { - updateData(); - - if (!isWaitingApproval()) { - return plan(); - } - - // module is waiting approval. Check it. - if (isActivated()) { - RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); - return plan(); - } else { - RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); - return planWaitingApproval(); - } - } - bool isExecutionRequested() const override; bool isExecutionReady() const override; // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; @@ -315,7 +295,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double min_lon_offset; }; - bool canTransitSuccessState() override { return false; } + bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 2c5e78a267d5a..7aba1d1b2d97f 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -251,7 +251,7 @@ bool DynamicAvoidanceModule::isExecutionRequested() const } // check if the planner is already running - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } @@ -279,15 +279,9 @@ void DynamicAvoidanceModule::updateData() } } -ModuleStatus DynamicAvoidanceModule::updateState() +bool DynamicAvoidanceModule::canTransitSuccessState() { - const bool has_avoidance_target = !target_objects_.empty(); - - if (!has_avoidance_target) { - return ModuleStatus::SUCCESS; - } - - return ModuleStatus::RUNNING; + return target_objects_.empty(); } BehaviorModuleOutput DynamicAvoidanceModule::plan() From eb7ccb824c9d1ff812861aa02be7514a46e5dc9f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 9 Nov 2023 20:52:26 +0900 Subject: [PATCH 083/223] refactor(mission_planner): use combineLaneletsShape in lanelet2_extension (#5535) Signed-off-by: kosuke55 --- .../src/lanelet2_plugins/default_planner.cpp | 4 +-- .../lanelet2_plugins/utility_functions.cpp | 33 ------------------- .../lanelet2_plugins/utility_functions.hpp | 1 - 3 files changed, 2 insertions(+), 36 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 673519b6f7a0e..0fce63827b5e7 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -288,7 +288,7 @@ bool DefaultPlanner::check_goal_footprint( lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = combine_lanelets(lanelets); + lanelet::ConstLanelet combined_lanelets = lanelet::utils::combineLaneletsShape(lanelets); // if next lanelet length longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -347,7 +347,7 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets - lanelet::ConstLanelet combined_prev_lanelet = combine_lanelets(path_lanelets); + lanelet::ConstLanelet combined_prev_lanelet = lanelet::utils::combineLaneletsShape(path_lanelets); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 690a864fcdacd..126c673108b3c 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -54,39 +54,6 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) -{ - lanelet::Points3d lefts; - lanelet::Points3d rights; - lanelet::Points3d centers; - std::vector left_bound_ids; - std::vector right_bound_ids; - - for (const auto & llt : lanelets) { - if (llt.id() != 0) { - left_bound_ids.push_back(llt.leftBound().id()); - right_bound_ids.push_back(llt.rightBound().id()); - } - } - - for (const auto & llt : lanelets) { - if (std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { - for (const auto & pt : llt.leftBound()) { - lefts.push_back(lanelet::Point3d(pt)); - } - } - if (std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { - for (const auto & pt : llt.rightBound()) { - rights.push_back(lanelet::Point3d(pt)); - } - } - } - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); - auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - return std::move(combined_lanelet); -} - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index 3ea6237f38501..df9d42bab9444 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -49,7 +49,6 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From 7a63e68b169dad64b15303148f2005f6b18353f8 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 9 Nov 2023 21:03:50 +0900 Subject: [PATCH 084/223] feat(controller): publish processing time (#5537) Signed-off-by: Takamasa Horibe --- .../controller_node.hpp | 10 ++++++++++ .../src/controller_node.cpp | 18 ++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp index c108bec2671b3..cc43da7114630 100644 --- a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp +++ b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp @@ -20,6 +20,7 @@ #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" #include "trajectory_follower_base/lateral_controller_base.hpp" #include "trajectory_follower_base/longitudinal_controller_base.hpp" #include "trajectory_follower_node/visibility_control.hpp" @@ -38,6 +39,7 @@ #include "nav_msgs/msg/odometry.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "visualization_msgs/msg/marker_array.hpp" +#include #include #include @@ -52,6 +54,8 @@ namespace trajectory_follower_node { using autoware_adapi_v1_msgs::msg::OperationModeState; +using tier4_autoware_utils::StopWatch; +using tier4_debug_msgs::msg::Float64Stamped; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; @@ -78,6 +82,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_operation_mode_; rclcpp::Publisher::SharedPtr control_cmd_pub_; + rclcpp::Publisher::SharedPtr pub_processing_time_lat_ms_; + rclcpp::Publisher::SharedPtr pub_processing_time_lon_ms_; rclcpp::Publisher::SharedPtr debug_marker_pub_; autoware_auto_planning_msgs::msg::Trajectory::SharedPtr current_trajectory_ptr_; @@ -114,6 +120,10 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node const trajectory_follower::LateralOutput & lat_out) const; std::unique_ptr logger_configure_; + + void publishProcessingTime( + const double t_ms, const rclcpp::Publisher::SharedPtr pub); + StopWatch stop_watch_; }; } // namespace trajectory_follower_node } // namespace autoware::motion::control diff --git a/control/trajectory_follower_node/src/controller_node.cpp b/control/trajectory_follower_node/src/controller_node.cpp index e35848e9495af..322aa9eef5a79 100644 --- a/control/trajectory_follower_node/src/controller_node.cpp +++ b/control/trajectory_follower_node/src/controller_node.cpp @@ -75,6 +75,10 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control [this](const OperationModeState::SharedPtr msg) { current_operation_mode_ptr_ = msg; }); control_cmd_pub_ = create_publisher( "~/output/control_cmd", rclcpp::QoS{1}.transient_local()); + pub_processing_time_lat_ms_ = + create_publisher("~/lateral/debug/processing_time_ms", 1); + pub_processing_time_lon_ms_ = + create_publisher("~/longitudinal/debug/processing_time_ms", 1); debug_marker_pub_ = create_publisher("~/output/debug_marker", rclcpp::QoS{1}); @@ -205,8 +209,13 @@ void Controller::callbackTimerControl() } // 3. run controllers + stop_watch_.tic("lateral"); const auto lat_out = lateral_controller_->run(*input_data); + publishProcessingTime(stop_watch_.toc("lateral"), pub_processing_time_lat_ms_); + + stop_watch_.tic("longitudinal"); const auto lon_out = longitudinal_controller_->run(*input_data); + publishProcessingTime(stop_watch_.toc("longitudinal"), pub_processing_time_lon_ms_); // 4. sync with each other controllers longitudinal_controller_->sync(lat_out.sync_data); @@ -254,6 +263,15 @@ void Controller::publishDebugMarker( debug_marker_pub_->publish(debug_marker_array); } +void Controller::publishProcessingTime( + const double t_ms, const rclcpp::Publisher::SharedPtr pub) +{ + Float64Stamped msg{}; + msg.stamp = this->now(); + msg.data = t_ms; + pub->publish(msg); +} + } // namespace autoware::motion::control::trajectory_follower_node #include "rclcpp_components/register_node_macro.hpp" From b4a05f6f5c05418a6b69f473399d0d996f7d6031 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Nov 2023 03:31:22 +0900 Subject: [PATCH 085/223] fix(mission_planner): revert "refactor(mission_planner): use combineLaneletsShape in lanele2_extension (#5535)" (#5543) Revert "refactor(mission_planner): use combineLaneletsShape in lanelet2_extension (#5535)" This reverts commit c4ca645cbbd0a7b919ba1c2cdf78742bb81b87b5. --- .../src/lanelet2_plugins/default_planner.cpp | 4 +-- .../lanelet2_plugins/utility_functions.cpp | 33 +++++++++++++++++++ .../lanelet2_plugins/utility_functions.hpp | 1 + 3 files changed, 36 insertions(+), 2 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 0fce63827b5e7..673519b6f7a0e 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -288,7 +288,7 @@ bool DefaultPlanner::check_goal_footprint( lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = lanelet::utils::combineLaneletsShape(lanelets); + lanelet::ConstLanelet combined_lanelets = combine_lanelets(lanelets); // if next lanelet length longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -347,7 +347,7 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets - lanelet::ConstLanelet combined_prev_lanelet = lanelet::utils::combineLaneletsShape(path_lanelets); + lanelet::ConstLanelet combined_prev_lanelet = combine_lanelets(path_lanelets); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 126c673108b3c..690a864fcdacd 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -54,6 +54,39 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } +lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) +{ + lanelet::Points3d lefts; + lanelet::Points3d rights; + lanelet::Points3d centers; + std::vector left_bound_ids; + std::vector right_bound_ids; + + for (const auto & llt : lanelets) { + if (llt.id() != 0) { + left_bound_ids.push_back(llt.leftBound().id()); + right_bound_ids.push_back(llt.rightBound().id()); + } + } + + for (const auto & llt : lanelets) { + if (std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { + for (const auto & pt : llt.leftBound()) { + lefts.push_back(lanelet::Point3d(pt)); + } + } + if (std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { + for (const auto & pt : llt.rightBound()) { + rights.push_back(lanelet::Point3d(pt)); + } + } + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); + auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + return std::move(combined_lanelet); +} + std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index df9d42bab9444..3ea6237f38501 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -49,6 +49,7 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); +lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From da6281ffb0c63a8431a3025a304a44df1fa7ea9e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 10 Nov 2023 13:50:16 +0900 Subject: [PATCH 086/223] fix(tier4_planning_launch): obstacle_cruise_planner pipeline is not connected (#5542) Signed-off-by: Takayuki Murooka --- .../lane_driving/motion_planning/motion_planning.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index a8dbcfd372226..18de04fd9e317 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -127,8 +127,8 @@ - - + + From 54020ff175b01eaaa2778ce5be66fbff95edb3a1 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 10 Nov 2023 15:19:46 +0900 Subject: [PATCH 087/223] fix(image_projection_based_fusion): add missing install (#5548) --- perception/image_projection_based_fusion/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index 53aafa44b75d6..c021dd92dae64 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -146,6 +146,10 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) EXECUTABLE pointpainting_fusion_node ) + install( + TARGETS pointpainting_cuda_lib + DESTINATION lib + ) else() message("Skipping build of some nodes due to missing dependencies") endif() From 20c8641b09dcde57b6898f326d8ebbbff30c0413 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 10 Nov 2023 17:36:41 +0900 Subject: [PATCH 088/223] perf(motion_utils): faster removeOverlapPoints and calcLateralOffset functions (#5385) Signed-off-by: Maxime CLEMENT --- .../motion_utils/trajectory/trajectory.hpp | 1 + .../benchmark_calcLateralOffset.cpp | 77 +++++++++++++++++++ 2 files changed, 78 insertions(+) create mode 100644 common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 61dc65c5ea3f2..f4f9f45935347 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -168,6 +168,7 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0) } T dst; + dst.reserve(points.size()); for (size_t i = 0; i <= start_idx; ++i) { dst.push_back(points.at(i)); diff --git a/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp b/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp new file mode 100644 index 0000000000000..549ca4c0ae5bb --- /dev/null +++ b/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp @@ -0,0 +1,77 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "motion_utils/trajectory/trajectory.hpp" + +#include +#include +#include + +#include + +namespace +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternionFromRPY; + +constexpr double epsilon = 1e-6; + +geometry_msgs::msg::Pose createPose( + double x, double y, double z, double roll, double pitch, double yaw) +{ + geometry_msgs::msg::Pose p; + p.position = createPoint(x, y, z); + p.orientation = createQuaternionFromRPY(roll, pitch, yaw); + return p; +} + +template +T generateTestTrajectory( + const size_t num_points, const double point_interval, const double vel = 0.0, + const double init_theta = 0.0, const double delta_theta = 0.0) +{ + using Point = typename T::_points_type::value_type; + + T traj; + for (size_t i = 0; i < num_points; ++i) { + const double theta = init_theta + i * delta_theta; + const double x = i * point_interval * std::cos(theta); + const double y = i * point_interval * std::sin(theta); + + Point p; + p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta); + p.longitudinal_velocity_mps = vel; + traj.points.push_back(p); + } + + return traj; +} +} // namespace + +TEST(trajectory_benchmark, DISABLED_calcLateralOffset) +{ + std::random_device r; + std::default_random_engine e1(r()); + std::uniform_real_distribution uniform_dist(0.0, 1000.0); + + using motion_utils::calcLateralOffset; + + const auto traj = generateTestTrajectory(1000, 1.0, 0.0, 0.0, 0.1); + constexpr auto nb_iteration = 10000; + for (auto i = 0; i < nb_iteration; ++i) { + const auto point = createPoint(uniform_dist(e1), uniform_dist(e1), 0.0); + calcLateralOffset(traj.points, point); + } +} From dd2c3a7719abb9e4b6c82118e03240ac5a06ed34 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Nov 2023 19:20:43 +0900 Subject: [PATCH 089/223] refactor(goal_planner): separate thread safe data (#5493) * refactor(goal_planner): separate thread safe data Signed-off-by: kosuke55 * fix style(pre-commit): autofix fix fix --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 190 ++++++--- .../goal_planner/pull_over_planner_base.hpp | 22 ++ .../goal_planner/goal_planner_module.cpp | 360 +++++++++--------- 3 files changed, 344 insertions(+), 228 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index df21bad862cc9..e4044d7191805 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -68,38 +68,30 @@ using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using tier4_autoware_utils::Polygon2d; -enum class PathType { - NONE = 0, - SHIFT, - ARC_FORWARD, - ARC_BACKWARD, - FREESPACE, -}; +#define DEFINE_SETTER(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + NAME##_ = value; \ + } -#define DEFINE_SETTER_GETTER(TYPE, NAME) \ -public: \ - void set_##NAME(const TYPE & value) \ - { \ - const std::lock_guard lock(mutex_); \ - NAME##_ = value; \ - } \ - \ - TYPE get_##NAME() const \ - { \ - const std::lock_guard lock(mutex_); \ - return NAME##_; \ +#define DEFINE_GETTER(TYPE, NAME) \ +public: \ + TYPE get_##NAME() const \ + { \ + return NAME##_; \ } +#define DEFINE_SETTER_GETTER(TYPE, NAME) \ + DEFINE_SETTER(TYPE, NAME) \ + DEFINE_GETTER(TYPE, NAME) + class PullOverStatus { public: - explicit PullOverStatus(std::recursive_mutex & mutex) : mutex_(mutex) {} - // Reset all data members to their initial states void reset() { - std::lock_guard lock(mutex_); - pull_over_path_ = nullptr; lane_parking_pull_over_path_ = nullptr; current_path_idx_ = 0; require_increment_ = true; @@ -109,16 +101,12 @@ class PullOverStatus pull_over_lanes_.clear(); lanes_.clear(); has_decided_path_ = false; - is_safe_static_objects_ = false; is_safe_dynamic_objects_ = false; - prev_is_safe_ = false; + prev_found_path_ = false; prev_is_safe_dynamic_objects_ = false; has_decided_velocity_ = false; - has_requested_approval_ = false; - is_ready_ = false; } - DEFINE_SETTER_GETTER(std::shared_ptr, pull_over_path) DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) DEFINE_SETTER_GETTER(size_t, current_path_idx) DEFINE_SETTER_GETTER(bool, require_increment) @@ -128,24 +116,14 @@ class PullOverStatus DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes) DEFINE_SETTER_GETTER(std::vector, lanes) DEFINE_SETTER_GETTER(bool, has_decided_path) - DEFINE_SETTER_GETTER(bool, is_safe_static_objects) DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects) - DEFINE_SETTER_GETTER(bool, prev_is_safe) + DEFINE_SETTER_GETTER(bool, prev_found_path) DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects) DEFINE_SETTER_GETTER(bool, has_decided_velocity) - DEFINE_SETTER_GETTER(bool, has_requested_approval) - DEFINE_SETTER_GETTER(bool, is_ready) - DEFINE_SETTER_GETTER(std::shared_ptr, last_increment_time) - DEFINE_SETTER_GETTER(std::shared_ptr, last_path_update_time) - DEFINE_SETTER_GETTER(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) - DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) - DEFINE_SETTER_GETTER(std::vector, pull_over_path_candidates) - DEFINE_SETTER_GETTER(std::optional, closest_start_pose) private: - std::shared_ptr pull_over_path_{nullptr}; std::shared_ptr lane_parking_pull_over_path_{nullptr}; size_t current_path_idx_{0}; bool require_increment_{true}; @@ -155,32 +133,134 @@ class PullOverStatus lanelet::ConstLanelets pull_over_lanes_{}; std::vector lanes_{}; bool has_decided_path_{false}; - bool is_safe_static_objects_{false}; bool is_safe_dynamic_objects_{false}; - bool prev_is_safe_{false}; + bool prev_found_path_{false}; bool prev_is_safe_dynamic_objects_{false}; bool has_decided_velocity_{false}; - bool has_requested_approval_{false}; - bool is_ready_{false}; - // save last time and pose - std::shared_ptr last_increment_time_; - std::shared_ptr last_path_update_time_; - - // goal modification - std::optional modified_goal_pose_; Pose refined_goal_pose_{}; - GoalCandidates goal_candidates_{}; Pose closest_goal_candidate_pose_{}; +}; + +#undef DEFINE_SETTER +#undef DEFINE_GETTER +#undef DEFINE_SETTER_GETTER + +#define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + const std::lock_guard lock(mutex_); \ + NAME##_ = value; \ + } + +#define DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) \ +public: \ + TYPE get_##NAME() const \ + { \ + const std::lock_guard lock(mutex_); \ + return NAME##_; \ + } + +#define DEFINE_SETTER_GETTER_WITH_MUTEX(TYPE, NAME) \ + DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ + DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) + +class ThreadSafeData +{ +public: + ThreadSafeData(std::recursive_mutex & mutex, rclcpp::Clock::SharedPtr clock) + : mutex_(mutex), clock_(clock) + { + } + + bool incrementPathIndex() + { + const std::lock_guard lock(mutex_); + if (pull_over_path_->incrementPathIndex()) { + last_path_idx_increment_time_ = clock_->now(); + return true; + } + return false; + } + + void set_pull_over_path(const PullOverPath & value) + { + const std::lock_guard lock(mutex_); + pull_over_path_ = std::make_shared(value); + last_path_update_time_ = clock_->now(); + } + + void set_pull_over_path(const std::shared_ptr & value) + { + const std::lock_guard lock(mutex_); + pull_over_path_ = value; + last_path_update_time_ = clock_->now(); + } + + void clearPullOverPath() + { + const std::lock_guard lock(mutex_); + pull_over_path_ = nullptr; + } + + bool foundPullOverPath() const + { + const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return false; + } + + return pull_over_path_->isValidPath(); + } + + PullOverPlannerType getPullOverPlannerType() const + { + const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return PullOverPlannerType::NONE; + } + + return pull_over_path_->type; + }; - // pull over path + void reset() + { + const std::lock_guard lock(mutex_); + pull_over_path_ = nullptr; + pull_over_path_candidates_.clear(); + goal_candidates_.clear(); + modified_goal_pose_ = std::nullopt; + last_path_update_time_ = std::nullopt; + last_path_idx_increment_time_ = std::nullopt; + closest_start_pose_ = std::nullopt; + } + + DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) + DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) + DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_idx_increment_time) + + DEFINE_SETTER_GETTER_WITH_MUTEX(std::vector, pull_over_path_candidates) + DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, modified_goal_pose) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) + +private: + std::shared_ptr pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; - std::optional closest_start_pose_; + GoalCandidates goal_candidates_{}; + std::optional modified_goal_pose_; + std::optional last_path_update_time_; + std::optional last_path_idx_increment_time_; + std::optional closest_start_pose_{}; std::recursive_mutex & mutex_; + rclcpp::Clock::SharedPtr clock_; }; -#undef DEFINE_SETTER_GETTER +#undef DEFINE_SETTER_WITH_MUTEX +#undef DEFINE_GETTER_WITH_MUTEX +#undef DEFINE_SETTER_GETTER_WITH_MUTEX struct FreespacePlannerDebugData { @@ -276,6 +356,7 @@ class GoalPlannerModule : public SceneModuleInterface std::recursive_mutex mutex_; PullOverStatus status_; + ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; @@ -329,6 +410,7 @@ class GoalPlannerModule : public SceneModuleInterface bool isStuck(); bool hasDecidedPath() const; void decideVelocity(); + bool foundPullOverPath() const; // validation bool hasEnoughDistance(const PullOverPath & pull_over_path) const; @@ -352,8 +434,6 @@ class GoalPlannerModule : public SceneModuleInterface const GoalCandidates & goal_candidates) const; // deal with pull over partial paths - PathWithLaneId getCurrentPath() const; - bool incrementPathIndex(); void transitionToNextPathIfFinishingCurrentPath(); // lanes and drivable area diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index 54bba6aee2fc2..4267261fdfe84 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -46,6 +46,7 @@ struct PullOverPath { PullOverPlannerType type{PullOverPlannerType::NONE}; std::vector partial_paths{}; + size_t path_idx{0}; // accelerate with constant acceleration to the target velocity std::vector> pairs_terminal_velocity_and_accel{}; Pose start_pose{}; @@ -84,6 +85,27 @@ struct PullOverPath return parking_path; } + + PathWithLaneId getCurrentPath() const + { + if (partial_paths.empty()) { + return PathWithLaneId{}; + } else if (partial_paths.size() <= path_idx) { + return partial_paths.back(); + } + return partial_paths.at(path_idx); + } + + bool incrementPathIndex() + { + if (partial_paths.size() - 1 <= path_idx) { + return false; + } + path_idx += 1; + return true; + } + + bool isValidPath() const { return type != PullOverPlannerType::NONE; } }; class PullOverPlannerBase diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 69c1fb911c4f9..0475cd92f1bec 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -58,7 +58,7 @@ GoalPlannerModule::GoalPlannerModule( : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, - status_{mutex_} + thread_safe_data_{mutex_, clock_} { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); @@ -138,16 +138,12 @@ void GoalPlannerModule::updateOccupancyGrid() void GoalPlannerModule::onTimer() { // already generated pull over candidate paths - if (!status_.get_pull_over_path_candidates().empty()) { + if (!thread_safe_data_.get_pull_over_path_candidates().empty()) { return; } // goals are not yet available. - if (status_.get_goal_candidates().empty()) { - return; - } - - if (!isExecutionRequested()) { + if (thread_safe_data_.get_goal_candidates().empty()) { return; } @@ -157,7 +153,11 @@ void GoalPlannerModule::onTimer() return; } - const auto goal_candidates = status_.get_goal_candidates(); + if (getCurrentStatus() == ModuleStatus::IDLE) { + return; + } + + const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( @@ -208,8 +208,8 @@ void GoalPlannerModule::onTimer() // set member variables { const std::lock_guard lock(mutex_); - status_.set_pull_over_path_candidates(path_candidates); - status_.set_closest_start_pose(closest_start_pose); + thread_safe_data_.set_pull_over_path_candidates(path_candidates); + thread_safe_data_.set_closest_start_pose(closest_start_pose); } } @@ -457,13 +457,13 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const bool GoalPlannerModule::planFreespacePath() { - goal_searcher_->setPlannerData(planner_data_); - auto goal_candidates = status_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - status_.set_goal_candidates(goal_candidates); - + GoalCandidates goal_candidates{}; { const std::lock_guard lock(mutex_); + goal_searcher_->setPlannerData(planner_data_); + goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + thread_safe_data_.set_goal_candidates(goal_candidates); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; } @@ -487,11 +487,8 @@ bool GoalPlannerModule::planFreespacePath() { const std::lock_guard lock(mutex_); - status_.set_pull_over_path(std::make_shared(*freespace_path)); - status_.set_current_path_idx(0); - status_.set_is_safe_static_objects(true); - status_.set_modified_goal_pose(goal_candidate); - status_.set_last_path_update_time(std::make_shared(clock_->now())); + thread_safe_data_.set_pull_over_path(*freespace_path); + thread_safe_data_.set_modified_goal_pose(goal_candidate); debug_data_.freespace_planner.is_planning = false; } @@ -527,14 +524,8 @@ void GoalPlannerModule::returnToLaneParking() return; } - { - const std::lock_guard lock(mutex_); - status_.set_is_safe_static_objects(true); - status_.set_has_decided_path(false); - status_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - status_.set_current_path_idx(0); - status_.set_last_path_update_time(std::make_shared(clock_->now())); - } + status_.set_has_decided_path(false); + thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); RCLCPP_INFO(getLogger(), "return to lane parking"); } @@ -546,7 +537,7 @@ void GoalPlannerModule::generateGoalCandidates() // with old architecture, module instance is not cleared when new route is received // so need to reset status here. // todo: move this check out of this function after old architecture is removed - if (!status_.get_goal_candidates().empty()) { + if (!thread_safe_data_.get_goal_candidates().empty()) { return; } @@ -554,21 +545,23 @@ void GoalPlannerModule::generateGoalCandidates() const Pose goal_pose = route_handler->getOriginalGoalPose(); status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { + const std::lock_guard lock(mutex_); goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); - status_.set_goal_candidates(goal_searcher_->search()); + thread_safe_data_.set_goal_candidates(goal_searcher_->search()); const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, false); status_.set_closest_goal_candidate_pose( - goal_searcher_->getClosetGoalCandidateAlongLanes(status_.get_goal_candidates()).goal_pose); + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()) + .goal_pose); } else { GoalCandidate goal_candidate{}; goal_candidate.goal_pose = goal_pose; goal_candidate.distance_from_original_goal = 0.0; GoalCandidates goal_candidates{}; goal_candidates.push_back(goal_candidate); - status_.set_goal_candidates(goal_candidates); + thread_safe_data_.set_goal_candidates(goal_candidates); status_.set_closest_goal_candidate_pose(goal_pose); } } @@ -630,13 +623,13 @@ void GoalPlannerModule::selectSafePullOverPath() { const std::lock_guard lock(mutex_); goal_searcher_->setPlannerData(planner_data_); - goal_candidates = status_.get_goal_candidates(); + goal_candidates = thread_safe_data_.get_goal_candidates(); goal_searcher_->update(goal_candidates); - status_.set_goal_candidates(goal_candidates); - status_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( - status_.get_pull_over_path_candidates(), status_.get_goal_candidates())); - pull_over_path_candidates = status_.get_pull_over_path_candidates(); - status_.set_is_safe_static_objects(false); + thread_safe_data_.set_goal_candidates(goal_candidates); + thread_safe_data_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( + thread_safe_data_.get_pull_over_path_candidates(), thread_safe_data_.get_goal_candidates())); + pull_over_path_candidates = thread_safe_data_.get_pull_over_path_candidates(); + thread_safe_data_.clearPullOverPath(); } for (const auto & pull_over_path : pull_over_path_candidates) { @@ -660,26 +653,24 @@ void GoalPlannerModule::selectSafePullOverPath() // found safe pull over path { const std::lock_guard lock(mutex_); - status_.set_is_safe_static_objects(true); - status_.set_pull_over_path(std::make_shared(pull_over_path)); - status_.set_current_path_idx(0); - status_.set_lane_parking_pull_over_path(status_.get_pull_over_path()); - status_.set_modified_goal_pose(*goal_candidate_it); - status_.set_last_path_update_time(std::make_shared(clock_->now())); + thread_safe_data_.set_pull_over_path(pull_over_path); + thread_safe_data_.set_modified_goal_pose(*goal_candidate_it); + status_.set_lane_parking_pull_over_path(thread_safe_data_.get_pull_over_path()); } break; } - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return; } // decelerate before the search area start const auto search_start_offset_pose = calcLongitudinalOffsetPose( - status_.get_pull_over_path()->getFullPath().points, status_.get_refined_goal_pose().position, + thread_safe_data_.get_pull_over_path()->getFullPath().points, + status_.get_refined_goal_pose().position, -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - approximate_pull_over_distance_); - auto & first_path = status_.get_pull_over_path()->partial_paths.front(); + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); if (search_start_offset_pose) { decelerateBeforeSearchStart(*search_start_offset_pose, first_path); } else { @@ -714,7 +705,7 @@ void GoalPlannerModule::setLanes() void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) { - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); } else if ( @@ -732,7 +723,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } // keep stop if not enough time passed, // because it takes time for the trajectory to be reflected - auto current_path = getCurrentPath(); + auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); output.path = std::make_shared(current_path); @@ -751,14 +742,14 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. const std::lock_guard lock(mutex_); - status_.set_prev_is_safe(status_.get_is_safe_static_objects()); + status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); status_.set_prev_is_safe_dynamic_objects( parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); } void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) { - if (status_.get_prev_is_safe() || !status_.get_prev_stop_path()) { + if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); const std::lock_guard lock(mutex_); @@ -766,10 +757,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) // set stop path as pull over path auto stop_pull_over_path = std::make_shared(); stop_pull_over_path->partial_paths.push_back(*output.path); - status_.set_pull_over_path(stop_pull_over_path); - status_.set_current_path_idx(0); - status_.set_last_path_update_time(std::make_shared(clock_->now())); - + thread_safe_data_.set_pull_over_path(stop_pull_over_path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { @@ -786,7 +774,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path if (status_.get_prev_is_safe_dynamic_objects() || !status_.get_prev_stop_path_after_approval()) { - auto current_path = getCurrentPath(); + auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, @@ -796,12 +784,13 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { - output.path = std::make_shared(getCurrentPath()); + output.path = + std::make_shared(thread_safe_data_.get_pull_over_path()->getCurrentPath()); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } - status_.set_last_path_update_time(std::make_shared(clock_->now())); + // status_.set_last_path_update_time(std::make_shared(clock_->now())); } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path output.path = status_.get_prev_stop_path_after_approval(); @@ -813,7 +802,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const { - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; output.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; @@ -831,10 +820,10 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const void GoalPlannerModule::setModifiedGoal(BehaviorModuleOutput & output) const { const auto & route_handler = planner_data_->route_handler; - if (status_.get_is_safe_static_objects()) { + if (thread_safe_data_.foundPullOverPath()) { PoseWithUuidStamped modified_goal{}; modified_goal.uuid = route_handler->getRouteUuid(); - modified_goal.pose = status_.get_modified_goal_pose()->goal_pose; + modified_goal.pose = thread_safe_data_.get_modified_goal_pose()->goal_pose; modified_goal.header = route_handler->getRouteHeader(); output.modified_goal = modified_goal; } else { @@ -879,22 +868,25 @@ bool GoalPlannerModule::hasDecidedPath() const } // if path is not safe, not decided - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return false; } // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( - getCurrentPath().points, current_pose, std::numeric_limits::max(), M_PI_2); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose, + std::numeric_limits::max(), M_PI_2); if (!ego_segment_idx) { return false; } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - getCurrentPath().points, status_.get_pull_over_path()->start_pose.position); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, + thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( - getCurrentPath().points, current_pose.position, *ego_segment_idx, - status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position, + *ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, + start_pose_segment_idx); return dist_to_parking_start_pose < parameters_->decide_path_distance; } @@ -904,7 +896,7 @@ void GoalPlannerModule::decideVelocity() // decide velocity to guarantee turn signal lighting time if (!status_.get_has_decided_velocity()) { - auto & first_path = status_.get_pull_over_path()->partial_paths.front(); + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); const auto vel = static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); for (auto & p : first_path.points) { @@ -917,13 +909,14 @@ void GoalPlannerModule::decideVelocity() CandidateOutput GoalPlannerModule::planCandidate() const { return CandidateOutput( - status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); + thread_safe_data_.get_pull_over_path() ? thread_safe_data_.get_pull_over_path()->getFullPath() + : PathWithLaneId()); } BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { // if pull over path candidates generation is not finished, use previous module output - if (status_.get_pull_over_path_candidates().empty()) { + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } @@ -944,10 +937,11 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() } transitionToNextPathIfFinishingCurrentPath(); } else if ( - !status_.get_pull_over_path_candidates().empty() && needPathUpdate(path_update_duration)) { + !thread_safe_data_.get_pull_over_path_candidates().empty() && + needPathUpdate(path_update_duration)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates - // and set it to status_.get_pull_over_path() + // and set it to thread_safe_data_.get_pull_over_path() selectSafePullOverPath(); } // else: stop path is generated and set by setOutput() @@ -959,27 +953,32 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { returnToLaneParking(); } + // For debug + setDebugData(); + if (parameters_->print_debug_info) { + // For evaluations + printParkingPositionError(); + } + + if (!thread_safe_data_.foundPullOverPath()) { + return output; + } + const auto distance_to_path_change = calcDistanceToPathChange(); if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } // TODO(tkhmy) add handle status TRYING updateSteeringFactor( - {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, + {thread_safe_data_.get_pull_over_path()->start_pose, + thread_safe_data_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::TURNING); - // For debug - setDebugData(); - if (parameters_->print_debug_info) { - // For evaluations - printParkingPositionError(); - } - - setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); return output; } @@ -1002,7 +1001,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification() { // if pull over path candidates generation is not finished, use previous module output - if (status_.get_pull_over_path_candidates().empty()) { + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } @@ -1012,10 +1011,9 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.reference_path = getPreviousModuleOutput().reference_path; path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; - const auto distance_to_path_change = calcDistanceToPathChange(); // generate drivable area info for new architecture - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; out.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; @@ -1029,21 +1027,31 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); } + if (!thread_safe_data_.foundPullOverPath()) { + return out; + } + + const auto distance_to_path_change = calcDistanceToPathChange(); if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } updateSteeringFactor( - {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, + {thread_safe_data_.get_pull_over_path()->start_pose, + thread_safe_data_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); - setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); return out; } std::pair GoalPlannerModule::calcDistanceToPathChange() const { - const auto full_path = status_.get_pull_over_path()->getFullPath(); + if (!thread_safe_data_.foundPullOverPath()) { + return {std::numeric_limits::max(), std::numeric_limits::max()}; + } + + const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), @@ -1053,15 +1061,15 @@ std::pair GoalPlannerModule::calcDistanceToPathChange() const } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, status_.get_pull_over_path()->start_pose.position); + full_path.points, thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); + thread_safe_data_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); const size_t goal_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, status_.get_modified_goal_pose()->goal_pose.position); + full_path.points, thread_safe_data_.get_modified_goal_pose()->goal_pose.position); const double dist_to_parking_finish_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - status_.get_modified_goal_pose()->goal_pose.position, goal_pose_segment_idx); + thread_safe_data_.get_modified_goal_pose()->goal_pose.position, goal_pose_segment_idx); return {dist_to_parking_start_pose, dist_to_parking_finish_pose}; } @@ -1103,17 +1111,17 @@ PathWithLaneId GoalPlannerModule::generateStopPath() reference_path.points, status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); if ( - !status_.get_is_safe_static_objects() && !status_.get_closest_start_pose() && + !thread_safe_data_.foundPullOverPath() && !thread_safe_data_.get_closest_start_pose() && !search_start_offset_pose) { return generateFeasibleStopPath(); } const Pose stop_pose = [&]() -> Pose { - if (status_.get_is_safe_static_objects()) { - return status_.get_pull_over_path()->start_pose; + if (thread_safe_data_.foundPullOverPath()) { + return thread_safe_data_.get_pull_over_path()->start_pose; } - if (status_.get_closest_start_pose()) { - return status_.get_closest_start_pose().value(); + if (thread_safe_data_.get_closest_start_pose()) { + return thread_safe_data_.get_closest_start_pose().value(); } return *search_start_offset_pose; }(); @@ -1187,44 +1195,42 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() { - if (isActivated() && last_approval_data_) { - // if using arc_path and finishing current_path, get next path - // enough time for turn signal - const bool has_passed_enough_time = (clock_->now() - last_approval_data_->time).seconds() > - planner_data_->parameters.turn_signal_search_time; - - if (hasFinishedCurrentPath() && has_passed_enough_time && status_.get_require_increment()) { - if (incrementPathIndex()) { - status_.set_last_increment_time(std::make_shared(clock_->now())); - } - } + if (!isActivated() || !last_approval_data_) { + return; } -} -bool GoalPlannerModule::incrementPathIndex() -{ - if (status_.get_current_path_idx() == status_.get_pull_over_path()->partial_paths.size() - 1) { - return false; + // if using arc_path and finishing current_path, get next path + // enough time for turn signal + const bool has_passed_enough_time_from_approval = + (clock_->now() - last_approval_data_->time).seconds() > + planner_data_->parameters.turn_signal_search_time; + if (!has_passed_enough_time_from_approval) { + return; } - status_.set_current_path_idx(status_.get_current_path_idx() + 1); - return true; -} -PathWithLaneId GoalPlannerModule::getCurrentPath() const -{ - if (status_.get_pull_over_path() == nullptr) { - return PathWithLaneId{}; + // require increment only when the time passed is enough + // to prevent increment before driving + // when the end of the current path is close to the current pose + // this value should be `keep_stop_time` in keepStoppedWithCurrentPath + constexpr double keep_current_idx_time = 4.0; + const bool has_passed_enough_time_from_increment = + (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > + keep_current_idx_time; + if (!has_passed_enough_time_from_increment) { + return; } - if (status_.get_pull_over_path()->partial_paths.size() <= status_.get_current_path_idx()) { - return PathWithLaneId{}; + if (!hasFinishedCurrentPath()) { + return; } - return status_.get_pull_over_path()->partial_paths.at(status_.get_current_path_idx()); + + thread_safe_data_.incrementPathIndex(); } bool GoalPlannerModule::isStopped( std::deque & odometry_buffer, const double time) { + const std::lock_guard lock(mutex_); odometry_buffer.push_back(planner_data_->self_odometry); // Delete old data in buffer while (rclcpp::ok()) { @@ -1254,6 +1260,7 @@ bool GoalPlannerModule::isStopped() bool GoalPlannerModule::isStuck() { + const std::lock_guard lock(mutex_); if (isOnModifiedGoal()) { return false; } @@ -1264,21 +1271,22 @@ bool GoalPlannerModule::isStuck() } // not found safe path - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return true; } // any path has never been found - if (!status_.get_pull_over_path()) { + if (!thread_safe_data_.get_pull_over_path()) { return false; } - return checkCollision(getCurrentPath()); + return checkCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath()); } bool GoalPlannerModule::hasFinishedCurrentPath() { - const auto current_path_end = getCurrentPath().points.back(); + const auto current_path_end = + thread_safe_data_.get_pull_over_path()->getCurrentPath().points.back(); const auto & self_pose = planner_data_->self_odometry->pose.pose; const bool is_near_target = tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < parameters_->th_arrived_distance; @@ -1288,12 +1296,12 @@ bool GoalPlannerModule::hasFinishedCurrentPath() bool GoalPlannerModule::isOnModifiedGoal() const { - if (!status_.get_modified_goal_pose()) { + if (!thread_safe_data_.get_modified_goal_pose()) { return false; } const Pose current_pose = planner_data_->self_odometry->pose.pose; - return calcDistance2d(current_pose, status_.get_modified_goal_pose()->goal_pose) < + return calcDistance2d(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose) < parameters_->th_arrived_distance; } @@ -1302,9 +1310,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const TurnSignalInfo turn_signal{}; // output const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto & start_pose = status_.get_pull_over_path()->start_pose; - const auto & end_pose = status_.get_pull_over_path()->end_pose; - const auto full_path = status_.get_pull_over_path()->getFullPath(); + const auto & start_pose = thread_safe_data_.get_pull_over_path()->start_pose; + const auto & end_pose = thread_safe_data_.get_pull_over_path()->end_pose; + const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); // calc TurnIndicatorsCommand { @@ -1435,20 +1443,18 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) { constexpr double keep_stop_time = 2.0; - constexpr double keep_current_idx_buffer_time = 2.0; - if (status_.get_last_increment_time()) { - const auto time_diff = (clock_->now() - *status_.get_last_increment_time()).seconds(); - if (time_diff < keep_stop_time) { - status_.set_require_increment(false); - for (auto & p : path.points) { - p.point.longitudinal_velocity_mps = 0.0; - } - } else if (time_diff > keep_stop_time + keep_current_idx_buffer_time) { - // require increment only when the time passed is enough - // to prevent increment before driving - // when the end of the current path is close to the current pose - status_.set_require_increment(true); - } + if (!thread_safe_data_.get_last_path_idx_increment_time()) { + return; + } + + const auto time_diff = + (clock_->now() - *thread_safe_data_.get_last_path_idx_increment_time()).seconds(); + if (time_diff > keep_stop_time) { + return; + } + + for (auto & p : path.points) { + p.point.longitudinal_velocity_mps = 0.0; } } @@ -1499,7 +1505,7 @@ void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWith planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); if (min_stop_distance && *min_stop_distance < stop_point_length) { - const auto stop_point = utils::insertStopPoint(stop_point_length, path); + utils::insertStopPoint(stop_point_length, path); } } @@ -1631,7 +1637,7 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( bool GoalPlannerModule::isSafePath() const { - const auto pull_over_path = getCurrentPath(); + const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto & current_pose = planner_data_->self_odometry->pose.pose; const double current_velocity = std::hypot( planner_data_->self_odometry->twist.twist.linear.x, @@ -1648,7 +1654,7 @@ bool GoalPlannerModule::isSafePath() const const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( - status_.get_pull_over_path()->pairs_terminal_velocity_and_accel, + thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, status_.get_current_path_idx()); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", @@ -1744,23 +1750,25 @@ void GoalPlannerModule::setDebugData() goal_searcher_->getAreaPolygons(), header, color, z)); // Visualize goal candidates - const auto goal_candidates = status_.get_goal_candidates(); + const auto goal_candidates = thread_safe_data_.get_goal_candidates(); add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); } // Visualize path and related pose - if (status_.get_is_safe_static_objects()) { + if (thread_safe_data_.foundPullOverPath()) { add(createPoseMarkerArray( - status_.get_pull_over_path()->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, 0.9)); + thread_safe_data_.get_pull_over_path()->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, + 0.9)); add(createPoseMarkerArray( - status_.get_pull_over_path()->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); + thread_safe_data_.get_pull_over_path()->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); + add(createPathMarkerArray( + thread_safe_data_.get_pull_over_path()->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray( - status_.get_pull_over_path()->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); - add(createPathMarkerArray(getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); + thread_safe_data_.get_pull_over_path()->getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); // visualize each partial path - for (size_t i = 0; i < status_.get_pull_over_path()->partial_paths.size(); ++i) { - const auto & partial_path = status_.get_pull_over_path()->partial_paths.at(i); + for (size_t i = 0; i < thread_safe_data_.get_pull_over_path()->partial_paths.size(); ++i) { + const auto & partial_path = thread_safe_data_.get_pull_over_path()->partial_paths.at(i); add( createPathMarkerArray(partial_path, "partial_path_" + std::to_string(i), 0, 0.9, 0.5, 0.9)); } @@ -1782,7 +1790,15 @@ void GoalPlannerModule::setDebugData() } } debug_marker_.markers.push_back(marker); + + // Visualize debug poses + const auto & debug_poses = thread_safe_data_.get_pull_over_path()->debug_poses; + for (size_t i = 0; i < debug_poses.size(); ++i) { + add(createPoseMarkerArray( + debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); + } } + // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -1806,17 +1822,22 @@ void GoalPlannerModule::setDebugData() // Visualize planner type text { visualization_msgs::msg::MarkerArray planner_type_marker_array{}; - const auto color = status_.get_is_safe_static_objects() + const auto color = thread_safe_data_.foundPullOverPath() ? createMarkerColor(1.0, 1.0, 1.0, 0.99) : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); - marker.pose = status_.get_modified_goal_pose() ? status_.get_modified_goal_pose()->goal_pose - : planner_data_->self_odometry->pose.pose; - marker.text = magic_enum::enum_name(status_.get_pull_over_path()->type); - marker.text += " " + std::to_string(status_.get_current_path_idx()) + "/" + - std::to_string(status_.get_pull_over_path()->partial_paths.size() - 1); + marker.pose = thread_safe_data_.get_modified_goal_pose() + ? thread_safe_data_.get_modified_goal_pose()->goal_pose + : planner_data_->self_odometry->pose.pose; + marker.text = magic_enum::enum_name(thread_safe_data_.getPullOverPlannerType()); + if (thread_safe_data_.foundPullOverPath()) { + marker.text += + " " + std::to_string(status_.get_current_path_idx()) + "/" + + std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); + } + if (isStuck()) { marker.text += " stuck"; } else if (isStopped()) { @@ -1832,13 +1853,6 @@ void GoalPlannerModule::setDebugData() planner_type_marker_array.markers.push_back(marker); add(planner_type_marker_array); } - - // Visualize debug poses - const auto & debug_poses = status_.get_pull_over_path()->debug_poses; - for (size_t i = 0; i < debug_poses.size(); ++i) { - add(createPoseMarkerArray( - debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); - } } void GoalPlannerModule::printParkingPositionError() const @@ -1847,7 +1861,7 @@ void GoalPlannerModule::printParkingPositionError() const const double real_shoulder_to_map_shoulder = 0.0; const Pose goal_to_ego = - inverseTransformPose(current_pose, status_.get_modified_goal_pose()->goal_pose); + inverseTransformPose(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose); const double dx = goal_to_ego.position.x; const double dy = goal_to_ego.position.y; const double distance_from_real_shoulder = @@ -1856,7 +1870,7 @@ void GoalPlannerModule::printParkingPositionError() const getLogger(), "current pose to goal, dx:%f dy:%f dyaw:%f from_real_shoulder:%f", dx, dy, tier4_autoware_utils::rad2deg( tf2::getYaw(current_pose.orientation) - - tf2::getYaw(status_.get_modified_goal_pose()->goal_pose.orientation)), + tf2::getYaw(thread_safe_data_.get_modified_goal_pose()->goal_pose.orientation)), distance_from_real_shoulder); } @@ -1882,10 +1896,10 @@ bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const { - if (!status_.get_last_path_update_time()) { + if (!thread_safe_data_.get_last_path_update_time()) { return true; } - return (clock_->now() - *status_.get_last_path_update_time()).seconds() > duration; + return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; } } // namespace behavior_path_planner From c2fc1880ba11d640287e67d4b43f372c672ecf7e Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 10 Nov 2023 19:21:20 +0900 Subject: [PATCH 090/223] refactor(start_planner): refactor backward path calculation in StartPlannerModule (#5529) * refactor(start_planner): refactor backward path calculation in StartPlannerModule The method "calcStartPoseCandidatesBackwardPath" has been renamed to "calcBackwardPathFromStartPose" to better reflect its purpose. The method now calculates the backward path by shifting the original start pose coordinates to align with the pull out lanes. The stop objects in the pull out lanes are filtered by velocity, using the new "filterStopObjectsInPullOutLanes" method. Additionally, the redundant "isOverlappedWithLane" method has been removed. Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- ...avior_path_planner_start_planner_design.md | 2 +- .../start_planner/start_planner_module.hpp | 10 +- .../start_planner/start_planner_module.cpp | 101 +++++++++--------- 3 files changed, 55 insertions(+), 58 deletions(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md index 131202038c270..28a1db649cf04 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md @@ -252,7 +252,7 @@ If a safe path cannot be generated from the current position, search backwards f | max_back_distance | [m] | double | maximum back distance | 30.0 | | backward_search_resolution | [m] | double | distance interval for searching backward pull out start point | 2.0 | | backward_path_update_duration | [s] | double | time interval for searching backward pull out start point. this prevents chattering between back driving and pull_out | 3.0 | -| ignore_distance_from_lane_end | [m] | double | distance from end of pull out lanes for ignoring start candidates | 15.0 | +| ignore_distance_from_lane_end | [m] | double | If distance from shift start pose to end of shoulder lane is less than this value, this start pose candidate is ignored | 15.0 | ### **freespace pull out** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 91121598cb3ae..8d2532504926e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -176,8 +176,9 @@ class StartPlannerModule : public SceneModuleInterface std::mutex mutex_; PathWithLaneId getFullPath() const; - PathWithLaneId calcStartPoseCandidatesBackwardPath() const; - std::vector searchPullOutStartPoses(const PathWithLaneId & start_pose_candidates) const; + PathWithLaneId calcBackwardPathFromStartPose() const; + std::vector searchPullOutStartPoseCandidates( + const PathWithLaneId & back_path_from_start_pose) const; std::shared_ptr lane_departure_checker_; @@ -194,9 +195,8 @@ class StartPlannerModule : public SceneModuleInterface std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); void updateStatusAfterBackwardDriving(); - static bool isOverlappedWithLane( - const lanelet::ConstLanelet & candidate_lanelet, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint); + PredictedObjects filterStopObjectsInPullOutLanes( + const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const; bool hasFinishedPullOut() const; bool isBackwardDrivingComplete() const; bool isStopped(); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 77a290835fb31..75562f59a402f 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -718,7 +718,7 @@ void StartPlannerModule::updatePullOutStatus() // refine start pose with pull out lanes. // 1) backward driving is not allowed: use refined pose just as start pose. // 2) backward driving is allowed: use refined pose to check if backward driving is needed. - const PathWithLaneId start_pose_candidates_path = calcStartPoseCandidatesBackwardPath(); + const PathWithLaneId start_pose_candidates_path = calcBackwardPathFromStartPose(); const auto refined_start_pose = calcLongitudinalOffsetPose( start_pose_candidates_path.points, planner_data_->self_odometry->pose.pose.position, 0.0); if (!refined_start_pose) return; @@ -726,7 +726,7 @@ void StartPlannerModule::updatePullOutStatus() // search pull out start candidates backward const std::vector start_pose_candidates = std::invoke([&]() -> std::vector { if (parameters_->enable_back) { - return searchPullOutStartPoses(start_pose_candidates_path); + return searchPullOutStartPoseCandidates(start_pose_candidates_path); } return {*refined_start_pose}; }); @@ -739,6 +739,7 @@ void StartPlannerModule::updatePullOutStatus() if (isBackwardDrivingComplete()) { updateStatusAfterBackwardDriving(); + // should be moved to transition state current_state_ = ModuleStatus::SUCCESS; // for breaking loop } else { status_.backward_path = start_planner_utils::getBackwardPath( @@ -760,71 +761,66 @@ void StartPlannerModule::updateStatusAfterBackwardDriving() } } -PathWithLaneId StartPlannerModule::calcStartPoseCandidatesBackwardPath() const +PathWithLaneId StartPlannerModule::calcBackwardPathFromStartPose() const { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - + const Pose & start_pose = planner_data_->route_handler->getOriginalStartPose(); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // get backward shoulder path - const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose); - const double check_distance = parameters_->max_back_distance + 30.0; // buffer - auto path = planner_data_->route_handler->getCenterLinePath( - pull_out_lanes, arc_position_pose.length - check_distance, - arc_position_pose.length + check_distance); - - // lateral shift to current_pose - const double distance_from_center_line = arc_position_pose.distance; - for (auto & p : path.points) { - p.point.pose = calcOffsetPose(p.point.pose, 0, distance_from_center_line, 0); + const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose); + + // common buffer distance for both front and back + static constexpr double buffer = 30.0; + const double check_distance = parameters_->max_back_distance + buffer; + + const double start_distance = arc_position_pose.length - check_distance; + const double end_distance = arc_position_pose.length + buffer; + + auto path = + planner_data_->route_handler->getCenterLinePath(pull_out_lanes, start_distance, end_distance); + + // shift all path points laterally to align with the start pose + for (auto & path_point : path.points) { + path_point.point.pose = calcOffsetPose(path_point.point.pose, 0, arc_position_pose.distance, 0); } return path; } -std::vector StartPlannerModule::searchPullOutStartPoses( - const PathWithLaneId & start_pose_candidates) const +std::vector StartPlannerModule::searchPullOutStartPoseCandidates( + const PathWithLaneId & back_path_from_start_pose) const { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - - std::vector pull_out_start_pose{}; - + std::vector pull_out_start_pose_candidates{}; + const auto & start_pose = planner_data_->route_handler->getOriginalStartPose(); + const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // filter pull out lanes stop objects - const auto [pull_out_lane_objects, others] = - utils::path_safety_checker::separateObjectsByLanelets( - *planner_data_->dynamic_object, pull_out_lanes, - utils::path_safety_checker::isPolygonOverlapLanelet); - const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( - pull_out_lane_objects, parameters_->th_moving_object_velocity); + const auto stop_objects_in_pull_out_lanes = + filterStopObjectsInPullOutLanes(pull_out_lanes, parameters_->th_moving_object_velocity); // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. - const double s_current = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose).length; - const double max_back_distance = std::clamp( - s_current - planner_data_->parameters.base_link2rear, 0.0, parameters_->max_back_distance); + const double current_arc_length = + lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose).length; + const double allowed_backward_distance = std::clamp( + current_arc_length - planner_data_->parameters.base_link2rear, 0.0, + parameters_->max_back_distance); - // check collision between footprint and object at the backed pose - const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); - for (double back_distance = 0.0; back_distance <= max_back_distance; + for (double back_distance = 0.0; back_distance <= allowed_backward_distance; back_distance += parameters_->backward_search_resolution) { const auto backed_pose = calcLongitudinalOffsetPose( - start_pose_candidates.points, current_pose.position, -back_distance); + back_path_from_start_pose.points, start_pose.position, -back_distance); if (!backed_pose) { continue; } - // check the back pose is near the lane end - const double length_to_backed_pose = + const double backed_pose_arc_length = lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length; - const double length_to_lane_end = std::accumulate( std::begin(pull_out_lanes), std::end(pull_out_lanes), 0.0, [](double acc, const auto & lane) { return acc + lanelet::utils::getLaneletLength2d(lane); }); - const double distance_from_lane_end = length_to_lane_end - length_to_backed_pose; + const double distance_from_lane_end = length_to_lane_end - backed_pose_arc_length; if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, @@ -833,27 +829,28 @@ std::vector StartPlannerModule::searchPullOutStartPoses( } if (utils::checkCollisionBetweenFootprintAndObjects( - local_vehicle_footprint, *backed_pose, pull_out_lane_stop_objects, + local_vehicle_footprint, *backed_pose, stop_objects_in_pull_out_lanes, parameters_->collision_check_margin)) { break; // poses behind this has a collision, so break. } - pull_out_start_pose.push_back(*backed_pose); + pull_out_start_pose_candidates.push_back(*backed_pose); } - return pull_out_start_pose; + return pull_out_start_pose_candidates; } -bool StartPlannerModule::isOverlappedWithLane( - const lanelet::ConstLanelet & candidate_lanelet, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint) +PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( + const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const { - for (const auto & point : vehicle_footprint) { - if (boost::geometry::within(point, candidate_lanelet.polygon2d().basicPolygon())) { - return true; - } - } + const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity( + *planner_data_->dynamic_object, velocity_threshold); - return false; + // filter for objects located in pull_out_lanes and moving at a speed below the threshold + const auto [stop_objects_in_pull_out_lanes, others] = + utils::path_safety_checker::separateObjectsByLanelets( + stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + + return stop_objects_in_pull_out_lanes; } bool StartPlannerModule::hasFinishedPullOut() const From bde4eb8329423048fab9b9f075291c59a0c81a0c Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Fri, 10 Nov 2023 13:25:24 +0300 Subject: [PATCH 091/223] build(lidar_centerpoint_tvm): remove artifacts download (#5367) Signed-off-by: Alexey Panferov --- perception/lidar_centerpoint_tvm/.gitignore | 1 - .../inference_engine_tvm_config.hpp | 60 +++++++++++++++++++ ...processing_inference_engine_tvm_config.hpp | 59 ++++++++++++++++++ .../inference_engine_tvm_config.hpp | 55 +++++++++++++++++ .../lidar_centerpoint_tvm/centerpoint_tvm.hpp | 5 +- .../launch/lidar_centerpoint_tvm.launch.xml | 2 + ...inference_lidar_centerpoint_tvm.launch.xml | 2 + .../lib/centerpoint_tvm.cpp | 14 ++--- perception/lidar_centerpoint_tvm/src/node.cpp | 3 +- .../src/single_inference_node.cpp | 4 +- 10 files changed, 192 insertions(+), 13 deletions(-) create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp diff --git a/perception/lidar_centerpoint_tvm/.gitignore b/perception/lidar_centerpoint_tvm/.gitignore index 8fce603003c1e..e69de29bb2d1d 100644 --- a/perception/lidar_centerpoint_tvm/.gitignore +++ b/perception/lidar_centerpoint_tvm/.gitignore @@ -1 +0,0 @@ -data/ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..8201dd25c1039 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp @@ -0,0 +1,60 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_backbone +{ +namespace onnx_centerpoint_backbone +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_backbone", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}}, // network_inputs + + {{"heatmap", kDLFloat, 32, 1, {1, 3, 560, 560}}, + {"reg", kDLFloat, 32, 1, {1, 2, 560, 560}}, + {"height", kDLFloat, 32, 1, {1, 1, 560, 560}}, + {"dim", kDLFloat, 32, 1, {1, 3, 560, 560}}, + {"rot", kDLFloat, 32, 1, {1, 2, 560, 560}}, + {"vel", kDLFloat, 32, 1, {1, 2, 560, 560}}} // network_outputs +}; + +} // namespace onnx_centerpoint_backbone +} // namespace centerpoint_backbone +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..2f6943e90bc83 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp @@ -0,0 +1,59 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_backbone +{ +namespace onnx_centerpoint_backbone +{ +namespace preprocessing +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_backbone", // network_name + "llvm", // network_backend + + "./preprocess.so", // network_module_path + "./", // network_graph_path + "./", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}, + {"coords", kDLInt, 32, 1, {40000, 3}}}, // network_inputs + + {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}} // network_outputs +}; + +} // namespace preprocessing +} // namespace onnx_centerpoint_backbone +} // namespace centerpoint_backbone +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..521036b49a533 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp @@ -0,0 +1,55 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_encoder +{ +namespace onnx_centerpoint_encoder +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_encoder", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"input_features", kDLFloat, 32, 1, {40000, 32, 9}}}, // network_inputs + + {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}} // network_outputs +}; + +} // namespace onnx_centerpoint_encoder +} // namespace centerpoint_encoder +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp index 168a249714bb4..865ca7d4253bf 100644 --- a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp +++ b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp @@ -60,7 +60,7 @@ class LIDAR_CENTERPOINT_TVM_LOCAL TVMScatterIE : public tvm_utility::pipeline::I public: explicit TVMScatterIE( tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name, - const std::string & function_name); + const std::string & data_path, const std::string & function_name); TVMArrayContainerVector schedule(const TVMArrayContainerVector & input); void set_coords(TVMArrayContainer coords) { coords_ = coords; } @@ -132,7 +132,8 @@ class LIDAR_CENTERPOINT_TVM_PUBLIC CenterPointTVM /// \param[in] dense_param The densification parameter used to constructing vg_ptr. /// \param[in] config The CenterPoint model configuration. explicit CenterPointTVM( - const DensificationParam & densification_param, const CenterPointConfig & config); + const DensificationParam & densification_param, const CenterPointConfig & config, + const std::string & data_path); ~CenterPointTVM(); diff --git a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml index e838f01e347ce..2bd6e3aa15c21 100644 --- a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml +++ b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml @@ -10,6 +10,7 @@ + @@ -20,5 +21,6 @@ + diff --git a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml index e62808804ca07..c2e0801fbd11c 100644 --- a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml +++ b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml @@ -12,6 +12,7 @@ + @@ -22,6 +23,7 @@ + diff --git a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp index 7b31bdf3c8fd3..2e0f9ad28bfb6 100644 --- a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp +++ b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp @@ -43,11 +43,10 @@ namespace lidar_centerpoint_tvm TVMScatterIE::TVMScatterIE( tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name, - const std::string & function_name) + const std::string & data_path, const std::string & function_name) : config_(config) { - std::string network_prefix = - ament_index_cpp::get_package_share_directory(pkg_name) + "/models/" + config.network_name + "/"; + std::string network_prefix = data_path + "/" + pkg_name + "/models/" + config.network_name + "/"; std::string network_module_path = network_prefix + config.network_module_path; std::ifstream module(network_module_path); @@ -159,14 +158,15 @@ std::vector BackboneNeckHeadPostProcessor::schedule(const TVMArrayContain } CenterPointTVM::CenterPointTVM( - const DensificationParam & densification_param, const CenterPointConfig & config) + const DensificationParam & densification_param, const CenterPointConfig & config, + const std::string & data_path) : config_ve(config_en), config_bnh(config_bk), VE_PreP(std::make_shared(config_en, config)), - VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm")), - BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm")), + VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm", data_path)), + BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm", data_path)), BNH_PostP(std::make_shared(config_bk, config)), - scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", "scatter")), + scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", data_path, "scatter")), TSP_pipeline(std::make_shared(VE_PreP, VE_IE, scatter_ie, BNH_IE, BNH_PostP)), config_(config) { diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp index e63cb7e19ba8e..0054211a15f9f 100644 --- a/perception/lidar_centerpoint_tvm/src/node.cpp +++ b/perception/lidar_centerpoint_tvm/src/node.cpp @@ -65,6 +65,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod static_cast(this->declare_parameter("downsample_factor")); const std::size_t encoder_in_feature_size = static_cast(this->declare_parameter("encoder_in_feature_size")); + const auto data_path = this->declare_parameter("data_path"); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); @@ -83,7 +84,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, yaw_norm_threshold); - detector_ptr_ = std::make_unique(densification_param, config); + detector_ptr_ = std::make_unique(densification_param, config, data_path); pointcloud_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), diff --git a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp index 8b810c5a7d759..a08850a7572f2 100644 --- a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp +++ b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp @@ -70,7 +70,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( static_cast(this->declare_parameter("encoder_in_feature_size")); const auto pcd_path = this->declare_parameter("pcd_path"); const auto detections_path = this->declare_parameter("detections_path"); - + const auto data_path = this->declare_parameter("data_path"); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); @@ -88,7 +88,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, yaw_norm_threshold); - detector_ptr_ = std::make_unique(densification_param, config); + detector_ptr_ = std::make_unique(densification_param, config, data_path); detect(pcd_path, detections_path); exit(0); From a1dfb07dcd78c7387567e985abbf60c17ebbe17d Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Sat, 11 Nov 2023 14:44:04 +0800 Subject: [PATCH 092/223] refactor(perception_rviz_plugin): apply thread pool to manage detached thread (#5418) * apply thread pool to manage detached thread Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * clean up the destructor Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * use function object in the queue instead Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * fix condition variable naming problem Signed-off-by: Owen-Liuyuxuan * add utility include for CI Signed-off-by: Owen-Liuyuxuan --------- Signed-off-by: Owen-Liuyuxuan Co-authored-by: Owen-Liuyuxuan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../predicted_objects_display.hpp | 33 ++++++++++++++ .../predicted_objects_display.cpp | 45 +++++++++++++------ 2 files changed, 64 insertions(+), 14 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp index 5493f1dd594ce..2896286970217 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp @@ -24,9 +24,11 @@ #include #include +#include #include #include #include +#include #include namespace autoware @@ -45,10 +47,31 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay using PredictedObjects = autoware_auto_perception_msgs::msg::PredictedObjects; PredictedObjectsDisplay(); + ~PredictedObjectsDisplay() + { + { + std::unique_lock lock(queue_mutex); + should_terminate = true; + } + condition.notify_all(); + for (std::thread & active_thread : threads) { + active_thread.join(); + } + threads.clear(); + } private: void processMessage(PredictedObjects::ConstSharedPtr msg) override; + void queueJob(std::function job) + { + { + std::unique_lock lock(queue_mutex); + jobs.push(std::move(job)); + } + condition.notify_one(); + } + boost::uuids::uuid to_boost_uuid(const unique_identifier_msgs::msg::UUID & uuid_msg) { const std::string uuid_str = uuid_to_string(uuid_msg); @@ -100,6 +123,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay PredictedObjects::ConstSharedPtr msg); void workerThread(); + void messageProcessorThreadJob(); + void update(float wall_dt, float ros_dt) override; std::unordered_map> id_map; @@ -108,6 +133,14 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay int32_t marker_id = 0; const int32_t PATH_ID_CONSTANT = 1e3; + // max_num_threads: number of threads created in the thread pool, hard-coded to be 1; + int max_num_threads; + + bool should_terminate{false}; + std::mutex queue_mutex; + std::vector threads; + std::queue> jobs; + PredictedObjects::ConstSharedPtr msg; bool consumed{false}; std::mutex mutex; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index 24e67a6f44e95..2cc5397d18721 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -25,27 +25,44 @@ namespace object_detection { PredictedObjectsDisplay::PredictedObjectsDisplay() : ObjectPolygonDisplayBase("tracks") { - std::thread worker(&PredictedObjectsDisplay::workerThread, this); - worker.detach(); + max_num_threads = 1; // hard code the number of threads to be created + + for (int ii = 0; ii < max_num_threads; ++ii) { + threads.emplace_back(std::thread(&PredictedObjectsDisplay::workerThread, this)); + } } void PredictedObjectsDisplay::workerThread() -{ +{ // A standard working thread that waiting for jobs while (true) { - std::unique_lock lock(mutex); - condition.wait(lock, [this] { return this->msg; }); + std::function job; + { + std::unique_lock lock(queue_mutex); + condition.wait(lock, [this] { return !jobs.empty() || should_terminate; }); + if (should_terminate) { + return; + } + job = jobs.front(); + jobs.pop(); + } + job(); + } +} - auto tmp_msg = this->msg; - this->msg.reset(); +void PredictedObjectsDisplay::messageProcessorThreadJob() +{ + // Receiving + std::unique_lock lock(mutex); + auto tmp_msg = this->msg; + this->msg.reset(); + lock.unlock(); - lock.unlock(); + auto tmp_markers = createMarkers(tmp_msg); - auto tmp_markers = createMarkers(tmp_msg); - lock.lock(); - markers = tmp_markers; + lock.lock(); + markers = tmp_markers; - consumed = true; - } + consumed = true; } std::vector PredictedObjectsDisplay::createMarkers( @@ -188,7 +205,7 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms std::unique_lock lock(mutex); this->msg = msg; - condition.notify_one(); + queueJob(std::bind(&PredictedObjectsDisplay::messageProcessorThreadJob, this)); } void PredictedObjectsDisplay::update(float wall_dt, float ros_dt) From 567b9e5aeaf10d117a06d7f6a5bde10cd869b252 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 13 Nov 2023 09:52:56 +0900 Subject: [PATCH 093/223] feat(intersection): use the centerline position of first attention area if there is no traffic light (#5547) Signed-off-by: Mamoru Sobue --- .../README.md | 15 +- .../docs/data-structure.drawio.svg | 745 ++++++++++++------ .../src/manager.cpp | 1 + .../src/scene_intersection.cpp | 173 ++-- .../src/scene_merge_from_private_road.cpp | 4 +- .../src/util.cpp | 86 +- .../src/util.hpp | 3 +- .../src/util_type.hpp | 3 +- 8 files changed, 690 insertions(+), 340 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index cb65e2a3cc23c..3ed4ee8fd334a 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -100,7 +100,18 @@ If a stopline is associated with the intersection lane on the map, that line is #### Pass Judge Line -To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, this module does not insert stopline after passing the default stopline position. +To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, namely the `first_attention_stop_line`, this module does not insert stopline after it passed the `default stop_line` position. + +The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. + +- If `occlusion.enable` is false, the pass judge line before the `first_attention_stop_line` by the braking distance $v_{ego}^{2} / 2a_{max}$. +- If `occlusion.enable` is true and: + - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stop_line` in order to continue peeking/collision detection while occlusion is detected. + - if there are no associated traffic lights and: + - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. + - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. + +![data structure](./docs/data-structure.drawio.svg) ### Occlusion detection @@ -170,8 +181,6 @@ entity IntersectionStopLines { @enduml ``` -![data structure](./docs/data-structure.drawio.svg) - ### Module Parameters | Parameter | Type | Description | diff --git a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg index fb512902ef856..ec5878a0d828e 100644 --- a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg @@ -5,31 +5,31 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="2159px" - height="1028px" - viewBox="-0.5 -0.5 2159 1028" - content="<mxfile host="Electron" modified="2023-10-03T07:12:57.327Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="t-GOTeomSwFlDSuYHtEs" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="2382px" + height="2070px" + viewBox="-0.5 -0.5 2382 2070" + content="<mxfile host="Electron" modified="2023-11-12T05:07:41.048Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="NhhSyCkZKf7kn4cJ36_Z" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > - + - - - - - + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + + - - - - + - - - + + + - - - - + + + + - - + + - - + + - - + + - - + + - - + + - - + + - - - - - - - - - - - + transform="translate(292.95,0)scale(-1,1)translate(-292.95,0)rotate(90,292.95,751.55)" + pointer-events="none" + /> + + + + + + + + + + +
@@ -294,18 +285,18 @@
- closest_idx + closest_idx - - - + + +
@@ -316,21 +307,21 @@
- stuck_stop_line + stuck_stop_line - - - - - - + + + + + +
@@ -341,18 +332,18 @@
- default_stop_line + default_stop_line - - - + + +
@@ -363,18 +354,18 @@
- first_attention_stop_line + first_attention_stop_line - - - + + +
@@ -389,25 +380,25 @@
- occlusion_peeking... + occlusion_peeking... - - - - - - - - - - - - - - - + + + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + + + - - - + - - - + + + - - - + + + - - + + - - + + - - + + - - + + - - + + - - + + - +
@@ -649,18 +632,18 @@
- next + next - - - + + +
@@ -673,18 +656,18 @@
- prev + prev - - - + + +
@@ -697,18 +680,18 @@
- ego_or_entry2exit + ego_or_entry2exit - - - + + +
@@ -721,15 +704,15 @@
- entry2ego + entry2ego - - + + -
+
@@ -739,7 +722,7 @@
- IntersectionStopLines + IntersectionStopLines @@ -747,7 +730,7 @@
@@ -758,9 +741,325 @@
- PathLanelets + PathLanelets + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl... +
+
+ + + + + + +
+
+
+ + closest_idx + +
+
+
+
+ closest_idx +
+
+ + + + + + + + + +
+
+
+ + stuck_stop_line + +
+
+
+
+ stuck_stop_line +
+
+ + + + + + +
+
+
+ + default_stop_line + +
+
+
+
+ default_stop_line +
+
+ + + + + + +
+
+
+ + first_attention_stop_line + +
+
+
+
+ first_attention_stop_line +
+
+ + + + + + +
+
+
+ + + occlusion_peeking +
+ _stop_line +
+
+
+
+
+
+ occlusion_peeking... +
+
+ + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl...
+ + + + + + + + + diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 5c5f5eac16b81..5de74aeb82d86 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -193,6 +193,7 @@ void IntersectionModuleManager::launchNewModules( const auto lanelets = planning_utils::getLaneletsOnPath(path, lanelet_map, planner_data_->current_odometry->pose); // run occlusion detection only in the first intersection + // TODO(Mamoru Sobue): remove `enable_occlusion_detection` variable const bool enable_occlusion_detection = intersection_param_.occlusion.enable; for (size_t i = 0; i < lanelets.size(); i++) { const auto ll = lanelets.at(i); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index c3b429680ab91..476238f6b1e9e 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -936,6 +936,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); const std::string turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); + const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; // spline interpolation const auto interpolated_path_info_opt = util::generateInterpolatedPath( @@ -969,15 +970,17 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_prioritized = traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED; const auto footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint); + intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front); // this is abnormal const auto & conflicting_lanelets = intersection_lanelets.conflicting(); const auto & first_conflicting_area_opt = intersection_lanelets.first_conflicting_area(); - if (conflicting_lanelets.empty() || !first_conflicting_area_opt) { + const auto & first_conflicting_lane_opt = intersection_lanelets.first_conflicting_lane(); + if (conflicting_lanelets.empty() || !first_conflicting_area_opt || !first_conflicting_lane_opt) { return IntersectionModule::Indecisive{"conflicting area is empty"}; } - const auto first_conflicting_area = first_conflicting_area_opt.value(); + const auto & first_conflicting_lane = first_conflicting_lane_opt.value(); + const auto & first_conflicting_area = first_conflicting_area_opt.value(); // generate all stop line candidates // see the doc for struct IntersectionStopLines @@ -986,22 +989,24 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( /// conflicting lanes const auto & dummy_first_attention_area = first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; - const double peeking_offset = - has_traffic_light_ ? planner_param_.occlusion.peeking_offset - : planner_param_.occlusion.absence_traffic_light.maximum_peeking_distance; + const auto & dummy_first_attention_lane_centerline = + intersection_lanelets.first_attention_lane() + ? intersection_lanelets.first_attention_lane().value().centerline2d() + : first_conflicting_lane.centerline2d(); const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( - first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info, - planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin, - planner_param_.common.max_accel, planner_param_.common.max_jerk, - planner_param_.common.delay_response_time, peeking_offset, path); + first_conflicting_area, dummy_first_attention_area, dummy_first_attention_lane_centerline, + planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, + planner_param_.common.stop_line_margin, planner_param_.common.max_accel, + planner_param_.common.max_jerk, planner_param_.common.delay_response_time, + planner_param_.occlusion.peeking_offset, path); if (!intersection_stop_lines_opt) { return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"}; } const auto & intersection_stop_lines = intersection_stop_lines_opt.value(); const auto [closest_idx, stuck_stop_line_idx_opt, default_stop_line_idx_opt, - first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = - intersection_stop_lines; + first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, + default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stop_lines; // see the doc for struct PathLanelets const auto & conflicting_area = intersection_lanelets.conflicting_area(); @@ -1083,16 +1088,91 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( if (!default_stop_line_idx_opt) { return IntersectionModule::Indecisive{"default stop line is null"}; } + // occlusion stop line is generated from the intersection of ego footprint along the path with the + // attention area, so if this is null, eog has already passed the intersection + if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { + return IntersectionModule::Indecisive{"occlusion stop line is null"}; + } const auto default_stop_line_idx = default_stop_line_idx_opt.value(); + const bool is_over_default_stop_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); + const auto collision_stop_line_idx = + is_over_default_stop_line ? closest_idx : default_stop_line_idx; + const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); + const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); + + const auto & adjacent_lanelets = intersection_lanelets.adjacent(); + const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); + const auto & occlusion_attention_area = intersection_lanelets.occlusion_attention_area(); + debug_data_.attention_area = intersection_lanelets.attention_area(); + debug_data_.occlusion_attention_area = occlusion_attention_area; + debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); + + // check occlusion on detection lane + if (!occlusion_attention_divisions_) { + occlusion_attention_divisions_ = util::generateDetectionLaneDivisions( + occlusion_attention_lanelets, routing_graph_ptr, + planner_data_->occupancy_grid->info.resolution, + planner_param_.occlusion.attention_lane_crop_curvature_threshold, + planner_param_.occlusion.attention_lane_curvature_calculation_ds); + } + const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value(); + + // get intersection area + const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr); + // filter objects + auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); + + const double occlusion_dist_thr = std::fabs( + std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / + (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); + auto occlusion_status = + (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized) + ? getOcclusionStatus( + *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, + first_attention_area, interpolated_path_info, occlusion_attention_divisions, + target_objects, current_pose, occlusion_dist_thr) + : OcclusionType::NOT_OCCLUDED; + occlusion_stop_state_machine_.setStateWithMarginTime( + occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, + logger_.get_child("occlusion_stop"), *clock_); + const bool is_occlusion_cleared_with_margin = + (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); + // distinguish if ego detected occlusion or RTC detects occlusion + const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); + if (ext_occlusion_requested) { + occlusion_status = OcclusionType::RTC_OCCLUDED; + } + const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); + if (is_occlusion_state && occlusion_status == OcclusionType::NOT_OCCLUDED) { + occlusion_status = prev_occlusion_status_; + } else { + prev_occlusion_status_ = occlusion_status; + } // TODO(Mamoru Sobue): this part needs more formal handling - const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const size_t pass_judge_line_idx = [=]() { + if (enable_occlusion_detection_) { + // if occlusion detection is enabled, pass_judge position is beyond the boundary of first + // attention area + if (has_traffic_light_) { + return occlusion_stop_line_idx; + } else if (is_occlusion_state) { + // if there is no traffic light and occlusion is detected, pass_judge position is beyond + // the boundary of first attention area + return occlusion_wo_tl_pass_judge_line_idx; + } else { + // if there is no traffic light and occlusion is not detected, pass_judge position is + // default + return default_pass_judge_line_idx; + } + } + return default_pass_judge_line_idx; + }(); debug_data_.pass_judge_wall_pose = planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); const bool is_over_pass_judge_line = util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); - const bool is_over_default_stop_line = - util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); const double vel_norm = std::hypot( planner_data_->current_velocity->twist.linear.x, planner_data_->current_velocity->twist.linear.y); @@ -1113,28 +1193,6 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } - // occlusion stop line is generated from the intersection of ego footprint along the path with the - // attention area, so if this is null, eog has already passed the intersection - if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { - return IntersectionModule::Indecisive{"occlusion stop line is null"}; - } - const auto collision_stop_line_idx = - is_over_default_stop_line ? closest_idx : default_stop_line_idx; - const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); - const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); - - const auto & adjacent_lanelets = intersection_lanelets.adjacent(); - const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); - const auto & occlusion_attention_area = intersection_lanelets.occlusion_attention_area(); - debug_data_.attention_area = intersection_lanelets.attention_area(); - debug_data_.occlusion_attention_area = occlusion_attention_area; - debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); - - // get intersection area - const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr); - - auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); - // If there are any vehicles on the attention area when ego entered the intersection on green // light, do pseudo collision detection because the vehicles are very slow and no collisions may // be detected. check if ego vehicle entered assigned lanelet @@ -1196,43 +1254,6 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( has_collision_with_margin, closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; } - // check occlusion on detection lane - if (!occlusion_attention_divisions_) { - occlusion_attention_divisions_ = util::generateDetectionLaneDivisions( - occlusion_attention_lanelets, routing_graph_ptr, - planner_data_->occupancy_grid->info.resolution, - planner_param_.occlusion.attention_lane_crop_curvature_threshold, - planner_param_.occlusion.attention_lane_curvature_calculation_ds); - } - const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value(); - - const double occlusion_dist_thr = std::fabs( - std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / - (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); - auto occlusion_status = - (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized) - ? getOcclusionStatus( - *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, - first_attention_area, interpolated_path_info, occlusion_attention_divisions, - target_objects, current_pose, occlusion_dist_thr) - : OcclusionType::NOT_OCCLUDED; - occlusion_stop_state_machine_.setStateWithMarginTime( - occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, - logger_.get_child("occlusion_stop"), *clock_); - const bool is_occlusion_cleared_with_margin = - (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); - // distinguish if ego detected occlusion or RTC detects occlusion - const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); - if (ext_occlusion_requested) { - occlusion_status = OcclusionType::RTC_OCCLUDED; - } - const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); - if (is_occlusion_state && occlusion_status == OcclusionType::NOT_OCCLUDED) { - occlusion_status = prev_occlusion_status_; - } else { - prev_occlusion_status_ = occlusion_status; - } - // Safe if (!is_occlusion_state && !has_collision_with_margin) { return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; @@ -1257,14 +1278,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( temporal_stop_before_attention_state_machine_) : false; if (!has_traffic_light_) { - if (fromEgoDist(first_attention_stop_line_idx) <= -peeking_offset) { + if (fromEgoDist(occlusion_wo_tl_pass_judge_line_idx) < 0) { return IntersectionModule::Indecisive{ "already passed maximum peeking line in the absence of traffic light"}; } return IntersectionModule::OccludedAbsenceTrafficLight{ is_occlusion_cleared_with_margin, has_collision_with_margin, temporal_stop_before_attention_required, closest_idx, - first_attention_stop_line_idx, occlusion_stop_line_idx}; + first_attention_stop_line_idx, occlusion_wo_tl_pass_judge_line_idx}; } // following remaining block is "has_traffic_light_" // if ego is stuck by static occlusion in the presence of traffic light, start timeout count diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 698242da67528..f1b516d72726f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -96,7 +96,9 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR } auto & intersection_lanelets = intersection_lanelets_.value(); const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - intersection_lanelets.update(false, interpolated_path_info, local_footprint); + intersection_lanelets.update( + false, interpolated_path_info, local_footprint, + planner_data_->vehicle_info_.max_longitudinal_offset_m); const auto & first_conflicting_area = intersection_lanelets.first_conflicting_area(); if (!first_conflicting_area) { return false; diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index e6e6fa0a1da9a..093f90e4b3df7 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -215,13 +215,15 @@ static std::optional getStopLineIndexFromMap( static std::optional getFirstPointInsidePolygonByFootprint( const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); - + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); const auto area_2d = lanelet::utils::to2D(polygon).basicPolygon(); - for (auto i = lane_start; i <= lane_end; ++i) { + for (auto i = start; i <= lane_end; ++i) { const auto & base_pose = path_ip.points.at(i).point.pose; const auto path_footprint = tier4_autoware_utils::transformVector( footprint, tier4_autoware_utils::pose2transform(base_pose)); @@ -237,12 +239,15 @@ static std::optional & polygons, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); - for (size_t i = lane_start; i <= lane_end; ++i) { + for (size_t i = start; i <= lane_end; ++i) { const auto & pose = path_ip.points.at(i).point.pose; const auto path_footprint = tier4_autoware_utils::transformVector(footprint, tier4_autoware_utils::pose2transform(pose)); @@ -259,7 +264,8 @@ getFirstPointInsidePolygonsByFootprint( std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_detection_area, + const lanelet::CompoundPolygon3d & first_attention_area, + const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, const double stop_line_margin, const double max_accel, const double max_jerk, @@ -269,31 +275,39 @@ std::optional generateIntersectionStopLines( const auto & path_ip = interpolated_path_info.path; const double ds = interpolated_path_info.ds; const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); + const double baselink2front = planner_data->vehicle_info_.max_longitudinal_offset_m; const int stop_line_margin_idx_dist = std::ceil(stop_line_margin / ds); const int base2front_idx_dist = std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); - /* - // find the index of the first point that intersects with detection_areas - const auto first_inside_detection_idx_ip_opt = - getFirstPointInsidePolygon(path_ip, lane_interval_ip, first_detection_area); - // if path is not intersecting with detection_area, error - if (!first_inside_detection_idx_ip_opt) { - return std::nullopt; - } - const auto first_inside_detection_ip = first_inside_detection_idx_ip_opt.value(); - */ // find the index of the first point whose vehicle footprint on it intersects with detection_area const auto local_footprint = planner_data->vehicle_info_.createFootprint(0.0, 0.0); std::optional first_footprint_inside_detection_ip_opt = getFirstPointInsidePolygonByFootprint( - first_detection_area, interpolated_path_info, local_footprint); + first_attention_area, interpolated_path_info, local_footprint, baselink2front); if (!first_footprint_inside_detection_ip_opt) { return std::nullopt; } const auto first_footprint_inside_detection_ip = first_footprint_inside_detection_ip_opt.value(); + std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; + for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { + const auto & base_pose = path_ip.points.at(i).point.pose; + const auto path_footprint = tier4_autoware_utils::transformVector( + local_footprint, tier4_autoware_utils::pose2transform(base_pose)); + if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { + // TODO(Mamoru Sobue): maybe consideration of braking dist is necessary + first_footprint_attention_centerline_ip_opt = i; + break; + } + } + if (!first_footprint_attention_centerline_ip_opt) { + return std::nullopt; + } + const size_t first_footprint_attention_centerline_ip = + first_footprint_attention_centerline_ip_opt.value(); + // (1) default stop line position on interpolated path bool default_stop_line_valid = true; int stop_idx_ip_int = -1; @@ -318,24 +332,25 @@ std::optional generateIntersectionStopLines( // (3) occlusion peeking stop line position on interpolated path int occlusion_peeking_line_ip_int = static_cast(default_stop_line_ip); bool occlusion_peeking_line_valid = true; + // NOTE: if footprints[0] is already inside the detection area, invalid { - // NOTE: if footprints[0] is already inside the detection area, invalid const auto & base_pose0 = path_ip.points.at(default_stop_line_ip).point.pose; const auto path_footprint0 = tier4_autoware_utils::transformVector( local_footprint, tier4_autoware_utils::pose2transform(base_pose0)); if (bg::intersects( - path_footprint0, lanelet::utils::to2D(first_detection_area).basicPolygon())) { + path_footprint0, lanelet::utils::to2D(first_attention_area).basicPolygon())) { occlusion_peeking_line_valid = false; } } if (occlusion_peeking_line_valid) { - occlusion_peeking_line_ip_int = first_footprint_inside_detection_ip; + occlusion_peeking_line_ip_int = + first_footprint_inside_detection_ip + std::ceil(peeking_offset / ds); } - const auto first_attention_stop_line_ip = static_cast(occlusion_peeking_line_ip_int); - const bool first_attention_stop_line_valid = occlusion_peeking_line_valid; - occlusion_peeking_line_ip_int += std::ceil(peeking_offset / ds); + const auto occlusion_peeking_line_ip = static_cast( std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + const auto first_attention_stop_line_ip = first_footprint_inside_detection_ip; + const bool first_attention_stop_line_valid = true; // (4) pass judge line position on interpolated path const double velocity = planner_data->current_velocity->twist.linear.x; @@ -346,6 +361,9 @@ std::optional generateIntersectionStopLines( static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); const auto pass_judge_line_ip = static_cast( std::clamp(pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + // TODO(Mamoru Sobue): maybe braking dist should be considered + const auto occlusion_wo_tl_pass_judge_line_ip = + static_cast(first_footprint_attention_centerline_ip); // (5) stuck vehicle stop line int stuck_stop_line_ip_int = 0; @@ -354,7 +372,7 @@ std::optional generateIntersectionStopLines( // NOTE: when ego vehicle is approaching detection area and already passed // first_conflicting_area, this could be null. const auto stuck_stop_line_idx_ip_opt = getFirstPointInsidePolygonByFootprint( - first_conflicting_area, interpolated_path_info, local_footprint); + first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); if (!stuck_stop_line_idx_ip_opt) { stuck_stop_line_valid = false; stuck_stop_line_ip_int = 0; @@ -378,6 +396,7 @@ std::optional generateIntersectionStopLines( size_t first_attention_stop_line{0}; size_t occlusion_peeking_stop_line{0}; size_t pass_judge_line{0}; + size_t occlusion_wo_tl_pass_judge_line{0}; }; IntersectionStopLinesTemp intersection_stop_lines_temp; @@ -388,7 +407,8 @@ std::optional generateIntersectionStopLines( {&first_attention_stop_line_ip, &intersection_stop_lines_temp.first_attention_stop_line}, {&occlusion_peeking_line_ip, &intersection_stop_lines_temp.occlusion_peeking_stop_line}, {&pass_judge_line_ip, &intersection_stop_lines_temp.pass_judge_line}, - }; + {&occlusion_wo_tl_pass_judge_line_ip, + &intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line}}; stop_lines.sort( [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); for (const auto & [stop_idx_ip, stop_idx] : stop_lines) { @@ -407,12 +427,6 @@ std::optional generateIntersectionStopLines( intersection_stop_lines_temp.occlusion_peeking_stop_line = intersection_stop_lines_temp.default_stop_line; } - if ( - intersection_stop_lines_temp.occlusion_peeking_stop_line > - intersection_stop_lines_temp.pass_judge_line) { - intersection_stop_lines_temp.pass_judge_line = - intersection_stop_lines_temp.occlusion_peeking_stop_line; - } IntersectionStopLines intersection_stop_lines; intersection_stop_lines.closest_idx = intersection_stop_lines_temp.closest_idx; @@ -431,6 +445,8 @@ std::optional generateIntersectionStopLines( intersection_stop_lines_temp.occlusion_peeking_stop_line; } intersection_stop_lines.pass_judge_line = intersection_stop_lines_temp.pass_judge_line; + intersection_stop_lines.occlusion_wo_tl_pass_judge_line = + intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line; return intersection_stop_lines; } @@ -1457,13 +1473,13 @@ double calcDistanceUntilIntersectionLanelet( void IntersectionLanelets::update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { is_prioritized_ = is_prioritized; // find the first conflicting/detection area polygon intersecting the path if (!first_conflicting_area_) { - auto first = - getFirstPointInsidePolygonsByFootprint(conflicting_area_, interpolated_path_info, footprint); + auto first = getFirstPointInsidePolygonsByFootprint( + conflicting_area_, interpolated_path_info, footprint, vehicle_length); if (first) { first_conflicting_lane_ = conflicting_.at(first.value().second); first_conflicting_area_ = conflicting_area_.at(first.value().second); @@ -1471,7 +1487,7 @@ void IntersectionLanelets::update( } if (!first_attention_area_) { auto first = getFirstPointInsidePolygonsByFootprint( - attention_non_preceding_area_, interpolated_path_info, footprint); + attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length); if (first) { first_attention_lane_ = attention_non_preceding_.at(first.value().second); first_attention_area_ = attention_non_preceding_area_.at(first.value().second); diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 2f204f06aac7c..0ff35ab5c0c23 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -69,7 +69,8 @@ std::optional generateStuckStopLine( std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_detection_area, + const lanelet::CompoundPolygon3d & first_attention_area, + const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, const double stop_line_margin, const double max_accel, const double max_jerk, diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 73e60aea6471a..d1ee4c2f79410 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -74,7 +74,7 @@ struct IntersectionLanelets public: void update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint); + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); const lanelet::ConstLanelets & attention() const { return is_prioritized_ ? attention_non_preceding_ : attention_; @@ -160,6 +160,7 @@ struct IntersectionStopLines std::optional occlusion_peeking_stop_line{std::nullopt}; // if the value is calculated negative, its value is 0 size_t pass_judge_line{0}; + size_t occlusion_wo_tl_pass_judge_line{0}; }; struct PathLanelets From cd06205ae63be9b8e311ccef9e08adb0edb0128f Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Mon, 13 Nov 2023 12:48:27 +0900 Subject: [PATCH 094/223] fix: scan ground filter document (#5552) Signed-off-by: Shunsuke Miura --- .../docs/scan-ground-filter.md | 39 ++++++++++--------- 1 file changed, 20 insertions(+), 19 deletions(-) diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index bc44544fa298c..21df6fa6ea1b9 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -30,25 +30,26 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref #### Core Parameters ![scan_ground_parameter](./image/scan_ground_filter_parameters.drawio.svg) -| Name | Type | Default Value | Description | -| --------------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `input_frame` | string | "base_link" | frame id of input pointcloud | -| `output_frame` | string | "base_link" | frame id of output pointcloud | -| `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | -| `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | -| `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | -| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to distinguish far and near [m] | -| `split_height_distance` | double | 0.2 | The height threshold to distinguish ground and non-ground pointcloud when comparing with adjacent points [m].
A small threshold improves classification of non-ground point, especially for high elevation resolution pointcloud lidar. However, it might cause false positive for small step-like road surface or misaligned multiple lidar configuration. | -| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | -| `detection_range_z_max` | float | 2.5 | Maximum height of detection range [m], applied only for elevation_grid_mode | -| `center_pcl_shift` | float | 0.0 | The x-axis offset of addition LiDARs from vehicle center of mass [m],
recommended to use only for additional LiDARs in elevation_grid_mode | -| `non_ground_height_threshold` | float | 0.2 | Height threshold of non ground objects [m] as `split_height_distance` and applied only for elevation_grid_mode | -| `grid_mode_switch_radius` | float | 20.0 | The distance where grid division mode change from by distance to by vertical angle [m],
applied only for elevation_grid_mode | -| `grid_size_m` | float | 0.5 | The first grid size [m], applied only for elevation_grid_mode.
A large value enhances the prediction stability for ground surface. suitable for rough surface or multiple lidar configuration. | -| `gnd_grid_buffer_size` | uint16 | 4 | Number of grids using to estimate local ground slope,
applied only for elevation_grid_mode | -| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | -| `elevation_grid_mode` | bool | true | Elevation grid scan mode option | -| `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | + +| Name | Type | Default Value | Description | +| --------------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `input_frame` | string | "base_link" | frame id of input pointcloud | +| `output_frame` | string | "base_link" | frame id of output pointcloud | +| `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | +| `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | +| `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | +| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to distinguish far and near [m] | +| `split_height_distance` | double | 0.2 | The height threshold to distinguish ground and non-ground pointcloud when comparing with adjacent points [m].
A small threshold improves classification of non-ground point, especially for high elevation resolution pointcloud lidar. However, it might cause false positive for small step-like road surface or misaligned multiple lidar configuration. | +| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | +| `detection_range_z_max` | float | 2.5 | Maximum height of detection range [m], applied only for elevation_grid_mode | +| `center_pcl_shift` | float | 0.0 | The x-axis offset of addition LiDARs from vehicle center of mass [m],
recommended to use only for additional LiDARs in elevation_grid_mode | +| `non_ground_height_threshold` | float | 0.2 | Height threshold of non ground objects [m] as `split_height_distance` and applied only for elevation_grid_mode | +| `grid_mode_switch_radius` | float | 20.0 | The distance where grid division mode change from by distance to by vertical angle [m],
applied only for elevation_grid_mode | +| `grid_size_m` | float | 0.5 | The first grid size [m], applied only for elevation_grid_mode.
A large value enhances the prediction stability for ground surface. suitable for rough surface or multiple lidar configuration. | +| `gnd_grid_buffer_size` | uint16 | 4 | Number of grids using to estimate local ground slope,
applied only for elevation_grid_mode | +| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | +| `elevation_grid_mode` | bool | true | Elevation grid scan mode option | +| `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | ## Assumptions / Known limits From 1f861e88e227865b2938682ca7656341345ce5a5 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 13 Nov 2023 13:14:55 +0900 Subject: [PATCH 095/223] feat(geo_pose_projector): use geo_pose_projector in eagleye (#5513) * feat(tier4_geo_pose_projector): use tier4_geo_pose_projector in eagleye Signed-off-by: kminoda * style(pre-commit): autofix * fix(eagleye): split fix2pose Signed-off-by: kminoda * style(pre-commit): autofix * fix name: fuser -> fusion Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * update readme Signed-off-by: kminoda * style(pre-commit): autofix * add #include Signed-off-by: kminoda * add rclcpp in dependency Signed-off-by: kminoda * style(pre-commit): autofix * add limitation in readme Signed-off-by: kminoda * style(pre-commit): autofix * update tier4_localization_launch Signed-off-by: kminoda * update tier4_localization_launch Signed-off-by: kminoda * rename package Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../eagleye/eagleye_rt.launch.xml | 10 +- .../eagleye/geo_pose_converter.launch.xml | 23 ---- launch/tier4_localization_launch/package.xml | 2 +- .../geo_pose_projector/CMakeLists.txt | 17 +++ localization/geo_pose_projector/README.md | 28 +++++ .../config/geo_pose_projector.param.yaml | 5 + .../launch/geo_pose_projector.launch.xml | 13 +++ localization/geo_pose_projector/package.xml | 30 +++++ .../schema/geo_pose_projector.schema.json | 43 ++++++++ .../src/geo_pose_projector.cpp | 103 ++++++++++++++++++ .../src/geo_pose_projector.hpp | 58 ++++++++++ .../src/geo_pose_projector_node.cpp | 29 +++++ 12 files changed, 334 insertions(+), 27 deletions(-) delete mode 100644 launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml create mode 100644 localization/geo_pose_projector/CMakeLists.txt create mode 100644 localization/geo_pose_projector/README.md create mode 100644 localization/geo_pose_projector/config/geo_pose_projector.param.yaml create mode 100644 localization/geo_pose_projector/launch/geo_pose_projector.launch.xml create mode 100644 localization/geo_pose_projector/package.xml create mode 100644 localization/geo_pose_projector/schema/geo_pose_projector.schema.json create mode 100644 localization/geo_pose_projector/src/geo_pose_projector.cpp create mode 100644 localization/geo_pose_projector/src/geo_pose_projector.hpp create mode 100644 localization/geo_pose_projector/src/geo_pose_projector_node.cpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml index 12d84f374f7c7..6cf8d390f919b 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml @@ -145,9 +145,13 @@ - - - + + + + + + + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml deleted file mode 100644 index d4f82e72a297b..0000000000000 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 9a137032e1277..1126914d58c5a 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -16,11 +16,11 @@ ar_tag_based_localizer automatic_pose_initializer - eagleye_geo_pose_converter eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt ekf_localizer + geo_pose_projector gyro_odometer ndt_scan_matcher pointcloud_preprocessor diff --git a/localization/geo_pose_projector/CMakeLists.txt b/localization/geo_pose_projector/CMakeLists.txt new file mode 100644 index 0000000000000..6e2cdf32fb6c5 --- /dev/null +++ b/localization/geo_pose_projector/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.14) +project(geo_pose_projector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(geo_pose_projector + src/geo_pose_projector_node.cpp + src/geo_pose_projector.cpp +) +ament_target_dependencies(geo_pose_projector) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/geo_pose_projector/README.md b/localization/geo_pose_projector/README.md new file mode 100644 index 0000000000000..a3363336da1a7 --- /dev/null +++ b/localization/geo_pose_projector/README.md @@ -0,0 +1,28 @@ +# geo_pose_projector + +## Overview + +This node is a simple node that subscribes to the geo-referenced pose topic and publishes the pose in the map frame. + +## Subscribed Topics + +| Name | Type | Description | +| ------------------------- | ---------------------------------------------------- | ------------------- | +| `input_geo_pose` | `geographic_msgs::msg::GeoPoseWithCovarianceStamped` | geo-referenced pose | +| `/map/map_projector_info` | `tier4_map_msgs::msg::MapProjectedObjectInfo` | map projector info | + +## Published Topics + +| Name | Type | Description | +| ------------- | ----------------------------------------------- | ------------------------------------- | +| `output_pose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | pose in map frame | +| `/tf` | `tf2_msgs::msg::TFMessage` | tf from parent link to the child link | + +## Parameters + +{{ json_to_markdown("localization/geo_pose_projector/schema/geo_pose_projector.schema.json") }} + +## Limitations + +The covariance conversion may be incorrect depending on the projection type you are using. The covariance of input topic is expressed in (Latitude, Longitude, Altitude) as a diagonal matrix. +Currently, we assume that the x axis is the east direction and the y axis is the north direction. Thus, the conversion may be incorrect when this assumption breaks, especially when the covariance of latitude and longitude is different. diff --git a/localization/geo_pose_projector/config/geo_pose_projector.param.yaml b/localization/geo_pose_projector/config/geo_pose_projector.param.yaml new file mode 100644 index 0000000000000..704d9dce8a4ee --- /dev/null +++ b/localization/geo_pose_projector/config/geo_pose_projector.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + publish_tf: true + parent_frame: "map" + child_frame: "pose_estimator_base_link" diff --git a/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml new file mode 100644 index 0000000000000..d840add1ed1c7 --- /dev/null +++ b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/localization/geo_pose_projector/package.xml b/localization/geo_pose_projector/package.xml new file mode 100644 index 0000000000000..d424ff14b9c99 --- /dev/null +++ b/localization/geo_pose_projector/package.xml @@ -0,0 +1,30 @@ + + + + geo_pose_projector + 0.1.0 + The geo_pose_projector package + Yamato Ando + Koji Minoda + Apache License 2.0 + Koji Minoda + + ament_cmake_auto + autoware_cmake + + component_interface_specs + component_interface_utils + geographic_msgs + geography_utils + geometry_msgs + rclcpp + tf2_geometry_msgs + tf2_ros + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/localization/geo_pose_projector/schema/geo_pose_projector.schema.json b/localization/geo_pose_projector/schema/geo_pose_projector.schema.json new file mode 100644 index 0000000000000..9daafb27f4320 --- /dev/null +++ b/localization/geo_pose_projector/schema/geo_pose_projector.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for geo_pose_projector", + "type": "object", + "definitions": { + "geo_pose_projector": { + "type": "object", + "properties": { + "publish_tf": { + "type": "boolean", + "description": "whether to publish tf", + "default": true + }, + "parent_frame": { + "type": "string", + "description": "parent frame for published tf", + "default": "map" + }, + "child_frame": { + "type": "string", + "description": "child frame for published tf", + "default": "pose_estimator_base_link" + } + }, + "required": ["publish_tf", "parent_frame", "child_frame"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/geo_pose_projector" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/geo_pose_projector/src/geo_pose_projector.cpp b/localization/geo_pose_projector/src/geo_pose_projector.cpp new file mode 100644 index 0000000000000..6d5308b929b25 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector.cpp @@ -0,0 +1,103 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "geo_pose_projector.hpp" + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +GeoPoseProjector::GeoPoseProjector() +: Node("geo_pose_projector"), publish_tf_(declare_parameter("publish_tf")) +{ + // Subscribe to map_projector_info topic + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_sub( + sub_map_projector_info_, + [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { projector_info_ = *msg; }); + + // Subscribe to geo_pose topic + geo_pose_sub_ = create_subscription( + "input_geo_pose", 10, [this](const GeoPoseWithCovariance::SharedPtr msg) { on_geo_pose(msg); }); + + // Publish pose topic + pose_pub_ = create_publisher("output_pose", 10); + + // Publish tf + if (publish_tf_) { + tf_broadcaster_ = std::make_unique(this); + parent_frame_ = declare_parameter("parent_frame"); + child_frame_ = declare_parameter("child_frame"); + } +} + +void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg) +{ + if (!projector_info_) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 1000 /* ms */, "map_projector_info is not received yet."); + return; + } + + // get position + geographic_msgs::msg::GeoPoint gps_point; + gps_point.latitude = msg->pose.pose.position.latitude; + gps_point.longitude = msg->pose.pose.position.longitude; + gps_point.altitude = msg->pose.pose.position.altitude; + geometry_msgs::msg::Point position = + geography_utils::project_forward(gps_point, projector_info_.value()); + position.z = geography_utils::convert_height( + position.z, gps_point.latitude, gps_point.longitude, MapProjectorInfo::Message::WGS84, + projector_info_.value().vertical_datum); + + // Convert geo_pose to pose + PoseWithCovariance projected_pose; + projected_pose.header = msg->header; + projected_pose.pose.pose.position = position; + projected_pose.pose.pose.orientation = msg->pose.pose.orientation; + projected_pose.pose.covariance = msg->pose.covariance; + + // Covariance in GeoPoseWithCovariance is in Lat/Lon/Alt coordinate. + // TODO(TIER IV): This swap may be invalid when using other projector type. + projected_pose.pose.covariance[0] = msg->pose.covariance[7]; + projected_pose.pose.covariance[7] = msg->pose.covariance[0]; + + pose_pub_->publish(projected_pose); + + // Publish tf + if (publish_tf_) { + tf2::Transform transform; + transform.setOrigin(tf2::Vector3( + projected_pose.pose.pose.position.x, projected_pose.pose.pose.position.y, + projected_pose.pose.pose.position.z)); + const auto localization_quat = tf2::Quaternion( + projected_pose.pose.pose.orientation.x, projected_pose.pose.pose.orientation.y, + projected_pose.pose.pose.orientation.z, projected_pose.pose.pose.orientation.w); + transform.setRotation(localization_quat); + + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.header = msg->header; + transform_stamped.header.frame_id = parent_frame_; + transform_stamped.child_frame_id = child_frame_; + transform_stamped.transform = tf2::toMsg(transform); + tf_broadcaster_->sendTransform(transform_stamped); + } +} diff --git a/localization/geo_pose_projector/src/geo_pose_projector.hpp b/localization/geo_pose_projector/src/geo_pose_projector.hpp new file mode 100644 index 0000000000000..b24b976b1eb61 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector.hpp @@ -0,0 +1,58 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef GEO_POSE_PROJECTOR_HPP_ +#define GEO_POSE_PROJECTOR_HPP_ + +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include + +class GeoPoseProjector : public rclcpp::Node +{ +private: + using GeoPoseWithCovariance = geographic_msgs::msg::GeoPoseWithCovarianceStamped; + using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; + using MapProjectorInfo = map_interface::MapProjectorInfo; + +public: + GeoPoseProjector(); + +private: + void on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg); + + component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; + rclcpp::Subscription::SharedPtr geo_pose_sub_; + rclcpp::Publisher::SharedPtr pose_pub_; + + std::unique_ptr tf_broadcaster_; + + std::optional projector_info_ = std::nullopt; + + const bool publish_tf_; + + std::string parent_frame_; + std::string child_frame_; +}; + +#endif // GEO_POSE_PROJECTOR_HPP_ diff --git a/localization/geo_pose_projector/src/geo_pose_projector_node.cpp b/localization/geo_pose_projector/src/geo_pose_projector_node.cpp new file mode 100644 index 0000000000000..97367d6b9f774 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector_node.cpp @@ -0,0 +1,29 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "geo_pose_projector.hpp" + +#include + +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + + return 0; +} From c8b60f85dc29947446b72c85cb58c90dcb1019da Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 13 Nov 2023 13:23:03 +0900 Subject: [PATCH 096/223] feat(simple_planning_simulator): add acceleration and steer command scaling factor for debug (#5534) * feat(simple_planning_simulator): add acceleration and steer command scaling factor Signed-off-by: kosuke55 * update params as debug Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- simulator/simple_planning_simulator/README.md | 28 ++++++++++--------- .../sim_model_delay_steer_acc.hpp | 21 ++++++++------ .../sim_model_delay_steer_acc_geared.hpp | 21 ++++++++------ .../simple_planning_simulator_core.cpp | 8 ++++-- .../sim_model_delay_steer_acc.cpp | 13 ++++++--- .../sim_model_delay_steer_acc_geared.cpp | 14 ++++++---- 6 files changed, 65 insertions(+), 40 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 75f77489daada..0c5441c1ad9c8 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -67,19 +67,21 @@ The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves base The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | Default value | unit | -| :------------------ | :----- | :--------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | Default value | unit | +| :------------------------- | :----- | :--------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | 1.0 | [-] | diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp index 289c607a18d90..92129541ff891 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp @@ -40,11 +40,14 @@ class SimModelDelaySteerAcc : public SimModelInterface * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics * @param [in] steer_dead_band dead band for steering angle [rad] + * @param [in] debug_acc_scaling_factor scaling factor for accel command + * @param [in] debug_steer_scaling_factor scaling factor for steering command */ SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band); + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor); /** * @brief default destructor @@ -74,13 +77,15 @@ class SimModelDelaySteerAcc : public SimModelInterface const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] const double wheelbase_; //!< @brief vehicle wheelbase length [m] - std::deque acc_input_queue_; //!< @brief buffer for accel command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double acc_delay_; //!< @brief time delay for accel command [s] - const double acc_time_constant_; //!< @brief time constant for accel dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command + const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp index 3bda878f8cd76..376ee55f1aa5e 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp @@ -40,11 +40,14 @@ class SimModelDelaySteerAccGeared : public SimModelInterface * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics * @param [in] steer_dead_band dead band for steering angle [rad] + * @param [in] debug_acc_scaling_factor scaling factor for accel command + * @param [in] debug_steer_scaling_factor scaling factor for steering command */ SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band); + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor); /** * @brief default destructor @@ -74,13 +77,15 @@ class SimModelDelaySteerAccGeared : public SimModelInterface const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] const double wheelbase_; //!< @brief vehicle wheelbase length [m] - std::deque acc_input_queue_; //!< @brief buffer for accel command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double acc_delay_; //!< @brief time delay for accel command [s] - const double acc_time_constant_; //!< @brief time constant for accel dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command + const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index f2629a0586045..07a5d34f63c39 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -230,6 +230,8 @@ void SimplePlanningSimulator::initialize_vehicle_model() const double steer_time_delay = declare_parameter("steer_time_delay", 0.24); const double steer_time_constant = declare_parameter("steer_time_constant", 0.27); const double steer_dead_band = declare_parameter("steer_dead_band", 0.0); + const double debug_acc_scaling_factor = declare_parameter("debug_acc_scaling_factor", 1.0); + const double debug_steer_scaling_factor = declare_parameter("debug_steer_scaling_factor", 1.0); const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; @@ -251,12 +253,14 @@ void SimplePlanningSimulator::initialize_vehicle_model() vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, + debug_acc_scaling_factor, debug_steer_scaling_factor); } else if (vehicle_model_type_str == "DELAY_STEER_ACC_GEARED") { vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC_GEARED; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, + debug_acc_scaling_factor, debug_steer_scaling_factor); } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp index 964157cdeb64c..670671165de60 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp @@ -19,7 +19,8 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band) + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -31,7 +32,9 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_dead_band_(steer_dead_band) + steer_dead_band_(steer_dead_band), + debug_acc_scaling_factor_(std::max(debug_acc_scaling_factor, 0.0)), + debug_steer_scaling_factor_(std::max(debug_steer_scaling_factor, 0.0)) { initializeInputQueue(dt); } @@ -104,8 +107,10 @@ Eigen::VectorXd SimModelDelaySteerAcc::calcModel( const double acc = sat(state(IDX::ACCX), vx_rate_lim_, -vx_rate_lim_); const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); - const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); + const double acc_des = + sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_) * debug_acc_scaling_factor_; + const double steer_des = + sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_) * debug_steer_scaling_factor_; const double steer_diff = steer - steer_des; const double steer_diff_with_dead_band = std::invoke([&]() { if (steer_diff > steer_dead_band_) { diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 76669c9490fc6..d72b8bf116d77 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -21,7 +21,8 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band) + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -33,8 +34,9 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_dead_band_(steer_dead_band) - + steer_dead_band_(steer_dead_band), + debug_acc_scaling_factor_(std::max(debug_acc_scaling_factor, 0.0)), + debug_steer_scaling_factor_(std::max(debug_steer_scaling_factor, 0.0)) { initializeInputQueue(dt); } @@ -113,8 +115,10 @@ Eigen::VectorXd SimModelDelaySteerAccGeared::calcModel( const double acc = sat(state(IDX::ACCX), vx_rate_lim_, -vx_rate_lim_); const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); - const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); + const double acc_des = + sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_) * debug_acc_scaling_factor_; + const double steer_des = + sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_) * debug_steer_scaling_factor_; const double steer_diff = steer - steer_des; const double steer_diff_with_dead_band = std::invoke([&]() { if (steer_diff > steer_dead_band_) { From dcbff101ea0548d25fed24c89356b86148d8f538 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Mon, 13 Nov 2023 17:44:07 +0900 Subject: [PATCH 097/223] fix(ndt_scan_matcher): make regularization process thread safe (#5550) * use mutex rather than main_callback_group Signed-off-by: Kento Yabuuchi * subscribe reg_pose only when regularization is enabled Signed-off-by: Kento Yabuuchi * add some comments to describe Signed-off-by: Kento Yabuuchi * use initial_pose_callback_group Signed-off-by: Kento Yabuuchi * fix typo (pauses->poses) Signed-off-by: Kento Yabuuchi Co-authored-by: Yamato Ando --------- Signed-off-by: Kento Yabuuchi Co-authored-by: Yamato Ando --- .../ndt_scan_matcher_core.hpp | 5 +- .../src/ndt_scan_matcher_core.cpp | 51 ++++++++++++++----- 2 files changed, 40 insertions(+), 16 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index f0d90fdfa0e08..6f9420f5bc71a 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -204,9 +204,10 @@ class NDTScanMatcher : public rclcpp::Node std::mutex initial_pose_array_mtx_; // variables for regularization - const bool regularization_enabled_; + const bool regularization_enabled_; // whether to use longitudinal regularization std::deque - regularization_pose_msg_ptr_array_; + regularization_pose_msg_ptr_array_; // queue for storing regularization base poses + std::mutex regularization_mutex_; // mutex for regularization_pose_msg_ptr_array_ bool is_activated_; std::shared_ptr tf2_listener_module_; diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index a2e89540a172f..1317b8bacf47f 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -219,10 +219,20 @@ NDTScanMatcher::NDTScanMatcher() sensor_points_sub_ = this->create_subscription( "points_raw", rclcpp::SensorDataQoS().keep_last(points_queue_size), std::bind(&NDTScanMatcher::callback_sensor_points, this, std::placeholders::_1), main_sub_opt); - regularization_pose_sub_ = - this->create_subscription( - "regularization_pose_with_covariance", 100, - std::bind(&NDTScanMatcher::callback_regularization_pose, this, std::placeholders::_1)); + + // Only if regularization is enabled, subscribe to the regularization base pose + if (regularization_enabled_) { + // NOTE: The reason that the regularization subscriber does not belong to the + // main_callback_group is to ensure that the regularization callback is called even if + // sensor_callback takes long time to process. + // Both callback_initial_pose and callback_regularization_pose must not miss receiving data for + // proper interpolation. + regularization_pose_sub_ = + this->create_subscription( + "regularization_pose_with_covariance", 10, + std::bind(&NDTScanMatcher::callback_regularization_pose, this, std::placeholders::_1), + initial_pose_sub_opt); + } sensor_aligned_pose_pub_ = this->create_publisher("points_aligned", 10); @@ -397,7 +407,10 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr) { + // Get lock for regularization_pose_msg_ptr_array_ + std::lock_guard lock(regularization_mutex_); regularization_pose_msg_ptr_array_.push_back(pose_conv_msg_ptr); + // Release lock for regularization_pose_msg_ptr_array_ } void NDTScanMatcher::callback_sensor_points( @@ -459,7 +472,9 @@ void NDTScanMatcher::callback_sensor_points( initial_pose_array_lock.unlock(); // if regularization is enabled and available, set pose to NDT for regularization - if (regularization_enabled_) add_regularization_pose(sensor_ros_time); + if (regularization_enabled_) { + add_regularization_pose(sensor_ros_time); + } if (ndt_ptr_->getInputTarget() == nullptr) { RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No MAP!"); @@ -816,21 +831,29 @@ std::array NDTScanMatcher::estimate_covariance( std::optional NDTScanMatcher::interpolate_regularization_pose( const rclcpp::Time & sensor_ros_time) { - if (regularization_pose_msg_ptr_array_.empty()) { - return std::nullopt; - } + std::shared_ptr interpolator = nullptr; + { + // Get lock for regularization_pose_msg_ptr_array_ + std::lock_guard lock(regularization_mutex_); - // synchronization - PoseArrayInterpolator interpolator(this, sensor_ros_time, regularization_pose_msg_ptr_array_); + if (regularization_pose_msg_ptr_array_.empty()) { + return std::nullopt; + } + + interpolator = std::make_shared( + this, sensor_ros_time, regularization_pose_msg_ptr_array_); - pop_old_pose(regularization_pose_msg_ptr_array_, sensor_ros_time); + // Remove old poses to make next interpolation more efficient + pop_old_pose(regularization_pose_msg_ptr_array_, sensor_ros_time); + + // Release lock for regularization_pose_msg_ptr_array_ + } - // if the interpolate_pose fails, 0.0 is stored in the stamp - if (rclcpp::Time(interpolator.get_current_pose().header.stamp).seconds() == 0.0) { + if (!interpolator || !interpolator->is_success()) { return std::nullopt; } - return pose_to_matrix4f(interpolator.get_current_pose().pose.pose); + return pose_to_matrix4f(interpolator->get_current_pose().pose.pose); } void NDTScanMatcher::add_regularization_pose(const rclcpp::Time & sensor_ros_time) From 54ff23ab1bf21f2cd433502395037f3f48c40972 Mon Sep 17 00:00:00 2001 From: Bupesh Rethinam Veeraiah <93628947+bupeshr@users.noreply.github.com> Date: Mon, 13 Nov 2023 17:53:46 +0900 Subject: [PATCH 098/223] test(obstacle_velocity_limiter): added test cases for particle model and approximation method (#5342) Co-authored-by: Maxime CLEMENT --- .../test/test_collision_distance.cpp | 215 +++++++++++++++++- 1 file changed, 212 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp index e9cf8d9ad4dd6..c5e69e5fd8fb9 100644 --- a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp +++ b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp @@ -34,7 +34,7 @@ const auto point_in_polygon = [](const auto x, const auto y, const auto & polygo }) != polygon.outer().end(); }; -TEST(TestCollisionDistance, distanceToClosestCollision) +TEST(TestCollisionDistance, distanceToClosestCollisionParticleModel) { using obstacle_velocity_limiter::CollisionChecker; using obstacle_velocity_limiter::distanceToClosestCollision; @@ -76,11 +76,11 @@ TEST(TestCollisionDistance, distanceToClosestCollision) ASSERT_TRUE(result.has_value()); EXPECT_DOUBLE_EQ(*result, 3.0); - obstacles.points.emplace_back(2.5, -0.75); + obstacles.points.emplace_back(2.75, -0.75); result = distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); ASSERT_TRUE(result.has_value()); - EXPECT_DOUBLE_EQ(*result, 2.5); + EXPECT_DOUBLE_EQ(*result, 2.75); // Change vector and footprint vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; @@ -95,6 +95,7 @@ TEST(TestCollisionDistance, distanceToClosestCollision) ASSERT_FALSE(result.has_value()); obstacles.points.emplace_back(4.0, 4.0); + result = distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); ASSERT_TRUE(result.has_value()); @@ -151,6 +152,214 @@ TEST(TestCollisionDistance, distanceToClosestCollision) EXPECT_NEAR(*result, 2.121, 1e-3); } +TEST(TestCollisionDistance, distanceToClosestCollisionApproximation) +{ + using obstacle_velocity_limiter::CollisionChecker; + using obstacle_velocity_limiter::distanceToClosestCollision; + using obstacle_velocity_limiter::linestring_t; + using obstacle_velocity_limiter::polygon_t; + + obstacle_velocity_limiter::ProjectionParameters params; + params.distance_method = obstacle_velocity_limiter::ProjectionParameters::APPROXIMATION; + params.heading = 0.0; + linestring_t vector = {{0.0, 0.0}, {5.0, 0.0}}; + polygon_t footprint; + footprint.outer() = {{0.0, 1.0}, {5.0, 1.0}, {5.0, -1.0}, {0.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacle_velocity_limiter::Obstacles obstacles; + + auto EPS = 1e-2; + + std::optional result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + // Non Value obstacles + obstacles.points.emplace_back(-1.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + // inside the polygon + obstacles.points.emplace_back(4.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_DOUBLE_EQ(*result, 4.0); + + obstacles.points.emplace_back(3.0, 0.5); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 3.04, EPS); + + obstacles.points.emplace_back(2.5, -0.75); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.61, EPS); + + obstacles.points.emplace_back(2.0, -1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); + + // Change vector and footprint + vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; + params.heading = M_PI_4; + footprint.outer() = {{-1.0, 1.0}, {4.0, 6.0}, {6.0, 4.0}, {1.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacles.points.clear(); + obstacles.lines.clear(); + + // auto EPS = 1e-3; + obstacles.points.emplace_back(5.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 4.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 5.65, EPS); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); + + // Change vector (opposite direction) + params.heading = -3 * M_PI_4; + vector = linestring_t{{5.0, 5.0}, {0.0, 0.0}}; + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(1.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 5.65, EPS); + + obstacles.points.emplace_back(4.0, 3.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); +} + +TEST(TestCollisionDistance, distanceToClosestCollisionBicycleModel) +{ + using obstacle_velocity_limiter::CollisionChecker; + using obstacle_velocity_limiter::distanceToClosestCollision; + using obstacle_velocity_limiter::linestring_t; + using obstacle_velocity_limiter::polygon_t; + + obstacle_velocity_limiter::ProjectionParameters params; + params.model = obstacle_velocity_limiter::ProjectionParameters::BICYCLE; + params.heading = 0.0; + linestring_t vector = {{0.0, 0.0}, {5.0, 0.0}}; + polygon_t footprint; + footprint.outer() = {{0.0, 1.0}, {5.0, 1.0}, {5.0, -1.0}, {0.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacle_velocity_limiter::Obstacles obstacles; + + auto EPS = 1e-2; + + std::optional result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(-1.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(3.0, 0.5); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 3.05, EPS); + + obstacles.points.emplace_back(2.5, -0.75); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.64, EPS); + + // Change vector and footprint + vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; + params.heading = M_PI_2; + footprint.outer() = {{-1.0, 1.0}, {4.0, 6.0}, {6.0, 4.0}, {1.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacles.points.clear(); + obstacles.lines.clear(); + + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 4.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 6.28, EPS); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.31, EPS); + + // Change vector (opposite direction) + params.heading = -M_PI; + vector = linestring_t{{5.0, 5.0}, {0.0, 0.0}}; + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(1.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 6.28, EPS); + + obstacles.points.emplace_back(4.0, 3.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.76, EPS); + + // change vector and footprint + params.heading = M_PI_2; + vector = linestring_t{{3.0, 3.0}, {0.0, 3.0}}; + footprint.outer() = {{1.0, -1.0}, {-4.0, 6.0}, {-5.0, -4.0}, {1.0, -4.0}}; + boost::geometry::correct(footprint); + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(-2.0, -1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 7.34, EPS); +} + TEST(TestCollisionDistance, arcDistance) { using obstacle_velocity_limiter::arcDistance; From 387cb24426a69a83dc54a6a27cd3cb576b6c36d2 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Nov 2023 17:58:19 +0900 Subject: [PATCH 099/223] fix(sampling_based_planner): fix runtime error (#5490) Signed-off-by: satoshi-ota --- .../include/bezier_sampler/bezier_sampling.hpp | 1 + planning/sampling_based_planner/path_sampler/src/node.cpp | 5 +++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp index 624cd585b0a72..18df9dcb796d8 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp +++ b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/path_sampler/src/node.cpp index aa037755bbedd..e61f635de67c4 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/path_sampler/src/node.cpp @@ -298,7 +298,8 @@ PlannerData PathSampler::createPlannerData(const Path & path) const return planner_data; } -void copyZ(const std::vector & from_traj, std::vector & to_traj) +void PathSampler::copyZ( + const std::vector & from_traj, std::vector & to_traj) { if (from_traj.empty() || to_traj.empty()) return; to_traj.front().pose.position.z = from_traj.front().pose.position.z; @@ -320,7 +321,7 @@ void copyZ(const std::vector & from_traj, std::vectorpose.position.z; } -void copyVelocity( +void PathSampler::copyVelocity( const std::vector & from_traj, std::vector & to_traj, const geometry_msgs::msg::Pose & ego_pose) { From cbbc7b7257c4fb65770d952966c0e372b31181d8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 13 Nov 2023 19:23:36 +0900 Subject: [PATCH 100/223] docs(lane_change): stopping position when an object exists ahead (#5523) * docs(lane_change): Stopping position when an object exists ahead Signed-off-by: kosuke55 * add stuck params Signed-off-by: kosuke55 * add backward_length_buffer_for_blocking_object Signed-off-by: kosuke55 * add stop for lane change Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- ...ehavior_path_planner_lane_change_design.md | 159 +++++++++++++----- .../lane_change-stop_at_terminal.drawio.svg | 94 +++++++++++ ...hange-stop_at_terminal_no_block.drawio.svg | 76 +++++++++ ...hange-stop_far_from_target_lane.drawio.svg | 85 ++++++++++ ...ane_change-stop_not_at_terminal.drawio.svg | 70 ++++++++ ..._at_terminal_no_blocking_object.drawio.svg | 76 +++++++++ 6 files changed, 518 insertions(+), 42 deletions(-) create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md index 2e5e486afc7c3..ee74f700c4d42 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md @@ -186,6 +186,46 @@ The following figure illustrates when the lane is blocked in multiple lane chang ![multiple-lane-changes](../image/lane_change/lane_change-when_cannot_change_lanes.png) +#### Stopping position when an object exists ahead + +When an obstacle is in front of the ego vehicle, stop with keeping a distance for lane change. +The position to be stopped depends on the situation, such as when the lane change is blocked by the target lane obstacle, or when the lane change is not needed immediately.The following shows the division in that case. + +##### When the ego vehicle is near the end of the lane change + +Regardless of the presence or absence of objects in the lane change target lane, stop by keeping the distance necessary for lane change to the object ahead. + +![stop_at_terminal_no_block](../image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg) + +![stop_at_terminal](../image/lane_change/lane_change-stop_at_terminal.drawio.svg) + +##### When the ego vehicle is not near the end of the lane change + +If there are NO objects in the lane change section of the target lane, stop by keeping the distance necessary for lane change to the object ahead. + +![stop_not_at_terminal_no_blocking_object](../image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) + +If there are objects in the lane change section of the target lane, stop WITHOUT keeping the distance necessary for lane change to the object ahead. + +![stop_not_at_terminal](../image/lane_change/lane_change-stop_not_at_terminal.drawio.svg) + +##### When the target lane is far away + +When the target lane for lane change is far away and not next to the current lane, do not keep the distance necessary for lane change to the object ahead. + +![stop_far_from_target_lane](../image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg) + +### Lane Change When Stuck + +The ego vehicle is considered stuck if it is stopped and meets any of the following conditions: + +- There is an obstacle in front of the current lane +- The ego vehicle is at the end of the current lane + +In this case, the safety check for lane change is relaxed compared to normal times. +Please refer to the 'stuck' section under the 'Collision checks during lane change' for more details. +The function to stop by keeping a margin against forward obstacle in the previous section is being performed to achieve this feature. + ### Lane change regulations If you want to regulate lane change on crosswalks or intersections, the lane change module finds a lane change path excluding it includes crosswalks or intersections. @@ -272,35 +312,36 @@ The last behavior will also occur if the ego vehicle has departed from the curre The following parameters are configurable in `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :------------------------------------------ | ------ | ------- | --------------------------------------------------------------------------------------------------------------- | ------------------ | -| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | -| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 2.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | -| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | -| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | -| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | -| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | -| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | -| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | -| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | -| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | -| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | -| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | -| `target_object.car` | [-] | boolean | Include car objects for safety check | true | -| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | -| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | -| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | -| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | -| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | -| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | -| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | +| Name | Unit | Type | Description | Default value | +| :------------------------------------------- | ------ | ------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | +| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | +| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | +| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | +| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | +| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | +| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | +| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | +| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | +| `target_object.car` | [-] | boolean | Include car objects for safety check | true | +| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | +| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | +| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | +| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | +| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | +| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | +| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | ### Lane change regulations @@ -320,19 +361,53 @@ The following parameters are configurable in `lane_change.param.yaml`. The following parameters are configurable in `behavior_path_planner.param.yaml` and `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :----------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +#### execution + +| Name | Unit | Type | Description | Default value | +| :---------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | +| `safety_check.execution.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | +| `safety_check.execution.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `safety_check.execution.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | +| `safety_check.execution.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | +| `safety_check.execution.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | + +##### cancel + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.5 | +| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.5 | +| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.5 | +| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.5 | +| `safety_check.cancel.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | +| `safety_check.cancel.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.2 | +| `safety_check.cancel.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | false | +| `safety_check.cancel.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | false | +| `safety_check.cancel.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | false | + +##### stuck + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------------ | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | +| `safety_check.stuck.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | +| `safety_check.stuck.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `safety_check.stuck.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | +| `safety_check.stuck.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | +| `safety_check.stuck.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | (\*1) the value must be negative. diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg new file mode 100644 index 0000000000000..f8aab60d0991d --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg @@ -0,0 +1,94 @@ + + + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg new file mode 100644 index 0000000000000..0de2c5fa0a550 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg new file mode 100644 index 0000000000000..dedcc13b6ef6a --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg new file mode 100644 index 0000000000000..938b7b7d4b371 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg @@ -0,0 +1,70 @@ + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg new file mode 100644 index 0000000000000..e07a8dcbe0354 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
From db962b3f13806d83ae01029800faa7930cc59989 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Mon, 13 Nov 2023 20:17:03 +0900 Subject: [PATCH 101/223] fix(detection_by_tracker): add ignore option for each label (#5473) * fix(detection_by_tracker): add ignore for each class Signed-off-by: badai-nguyen * fix: launch Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...ra_lidar_fusion_based_detection.launch.xml | 1 + ...ar_radar_fusion_based_detection.launch.xml | 1 + .../detection/detection.launch.xml | 3 ++ .../lidar_based_detection.launch.xml | 1 + .../launch/perception.launch.xml | 2 ++ .../detection_by_tracker/CMakeLists.txt | 2 ++ .../config/detection_by_tracker.param.yaml | 11 ++++++ .../detection_by_tracker_core.hpp | 5 +-- .../include/utils/utils.hpp | 36 +++++++++++++++++++ .../launch/detection_by_tracker.launch.xml | 3 +- .../src/detection_by_tracker_core.cpp | 14 ++++++-- perception/detection_by_tracker/src/utils.cpp | 30 ++++++++++++++++ 12 files changed, 103 insertions(+), 6 deletions(-) create mode 100644 perception/detection_by_tracker/config/detection_by_tracker.param.yaml create mode 100644 perception/detection_by_tracker/include/utils/utils.hpp create mode 100644 perception/detection_by_tracker/src/utils.cpp diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 59fe3f13f1231..b3e9e9148ee60 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -195,6 +195,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 11deaad5d06cc..20b1b5a4d0b27 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -220,6 +220,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 1fcf29606891b..33994934949ac 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -73,6 +73,7 @@ + @@ -104,6 +105,7 @@ + @@ -133,6 +135,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 822c251ddad33..ac521934265d7 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -61,6 +61,7 @@ + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 347606d91759f..8b241db9774b3 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -18,6 +18,7 @@ + @@ -174,6 +175,7 @@ + diff --git a/perception/detection_by_tracker/CMakeLists.txt b/perception/detection_by_tracker/CMakeLists.txt index 236268438f852..51839027e0e41 100644 --- a/perception/detection_by_tracker/CMakeLists.txt +++ b/perception/detection_by_tracker/CMakeLists.txt @@ -27,6 +27,7 @@ include_directories( # Generate exe file set(DETECTION_BY_TRACKER_SRC src/detection_by_tracker_core.cpp + src/utils.cpp ) ament_auto_add_library(detection_by_tracker_node SHARED @@ -45,4 +46,5 @@ rclcpp_components_register_node(detection_by_tracker_node ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/perception/detection_by_tracker/config/detection_by_tracker.param.yaml b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml new file mode 100644 index 0000000000000..695704050697d --- /dev/null +++ b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + tracker_ignore_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false diff --git a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp index 0eacfa527750b..10affd0b94ffd 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp @@ -39,6 +39,8 @@ #include #endif +#include "utils/utils.hpp" + #include #include @@ -46,7 +48,6 @@ #include #include #include - class TrackerHandler { private: @@ -81,7 +82,7 @@ class DetectionByTracker : public rclcpp::Node std::map max_search_distance_for_merger_; std::map max_search_distance_for_divider_; - bool ignore_unknown_tracker_; + utils::TrackerIgnoreLabel tracker_ignore_; void setMaxSearchRange(); diff --git a/perception/detection_by_tracker/include/utils/utils.hpp b/perception/detection_by_tracker/include/utils/utils.hpp new file mode 100644 index 0000000000000..3f39125b95e03 --- /dev/null +++ b/perception/detection_by_tracker/include/utils/utils.hpp @@ -0,0 +1,36 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef UTILS__UTILS_HPP_ +#define UTILS__UTILS_HPP_ + +#include + +namespace utils +{ +struct TrackerIgnoreLabel +{ + bool UNKNOWN; + bool CAR; + bool TRUCK; + bool BUS; + bool TRAILER; + bool MOTORCYCLE; + bool BICYCLE; + bool PEDESTRIAN; + bool isIgnore(const uint8_t label) const; +}; // struct TrackerIgnoreLabel +} // namespace utils + +#endif // UTILS__UTILS_HPP_ diff --git a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml index 79e1b642cc53c..95e7cbf16b388 100644 --- a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml +++ b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml @@ -3,10 +3,11 @@ - + + diff --git a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp index 7b436e1edd64c..2595315e1f9b2 100644 --- a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp +++ b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp @@ -160,7 +160,15 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options) objects_pub_ = create_publisher( "~/output", rclcpp::QoS{1}); - ignore_unknown_tracker_ = declare_parameter("ignore_unknown_tracker", true); + // Set parameters + tracker_ignore_.UNKNOWN = declare_parameter("tracker_ignore_label.UNKNOWN"); + tracker_ignore_.CAR = declare_parameter("tracker_ignore_label.CAR"); + tracker_ignore_.TRUCK = declare_parameter("tracker_ignore_label.TRUCK"); + tracker_ignore_.BUS = declare_parameter("tracker_ignore_label.BUS"); + tracker_ignore_.TRAILER = declare_parameter("tracker_ignore_label.TRAILER"); + tracker_ignore_.MOTORCYCLE = declare_parameter("tracker_ignore_label.MOTORCYCLE"); + tracker_ignore_.BICYCLE = declare_parameter("tracker_ignore_label.BICYCLE"); + tracker_ignore_.PEDESTRIAN = declare_parameter("tracker_ignore_label.PEDESTRIAN"); // set maximum search setting for merger/divider setMaxSearchRange(); @@ -259,7 +267,7 @@ void DetectionByTracker::divideUnderSegmentedObjects( for (const auto & tracked_object : tracked_objects.objects) { const auto & label = tracked_object.classification.front().label; - if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + if (tracker_ignore_.isIgnore(label)) continue; // change search range according to label type const float max_search_range = max_search_distance_for_divider_[label]; @@ -395,7 +403,7 @@ void DetectionByTracker::mergeOverSegmentedObjects( for (const auto & tracked_object : tracked_objects.objects) { const auto & label = tracked_object.classification.front().label; - if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + if (tracker_ignore_.isIgnore(label)) continue; // change search range according to label type const float max_search_range = max_search_distance_for_merger_[label]; diff --git a/perception/detection_by_tracker/src/utils.cpp b/perception/detection_by_tracker/src/utils.cpp new file mode 100644 index 0000000000000..29a500a24cf32 --- /dev/null +++ b/perception/detection_by_tracker/src/utils.cpp @@ -0,0 +1,30 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "utils/utils.hpp" + +#include + +namespace utils +{ +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +bool TrackerIgnoreLabel::isIgnore(const uint8_t label) const +{ + return (label == Label::UNKNOWN && UNKNOWN) || (label == Label::CAR && CAR) || + (label == Label::TRUCK && TRUCK) || (label == Label::BUS && BUS) || + (label == Label::TRAILER && TRAILER) || (label == Label::MOTORCYCLE && MOTORCYCLE) || + (label == Label::BICYCLE && BICYCLE) || (label == Label::PEDESTRIAN && PEDESTRIAN); +} +} // namespace utils From d3ab218b6e76d53eaf2cef7d46f4486224a7a3ef Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 13 Nov 2023 20:32:22 +0900 Subject: [PATCH 102/223] feat(image_projection_based_fusion): enable to show iou value in roi_cluster_fusion debug image (#5541) * enable to show debug iou value in roi_cluster_fusion Signed-off-by: yoshiri * refactor iou draw settings Signed-off-by: yoshiri * add backgroud color to iou Signed-off-by: yoshiri * prevent object copying when debugger is not enabled Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../debugger.hpp | 1 + .../src/debugger.cpp | 56 ++++++++++++++++--- .../src/fusion_node.cpp | 1 + .../src/roi_cluster_fusion/node.cpp | 18 +++--- 4 files changed, 58 insertions(+), 18 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index 8a6ac7672b3a8..e4b1913effed5 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -50,6 +50,7 @@ class Debugger std::vector image_rois_; std::vector obstacle_rois_; std::vector obstacle_points_; + std::vector max_iou_for_image_rois_; private: void imageCallback( diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index 3f52a0de1f09d..a51c23a77aac6 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -77,6 +77,7 @@ void Debugger::clear() image_rois_.clear(); obstacle_rois_.clear(); obstacle_points_.clear(); + max_iou_for_image_rois_.clear(); } void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & stamp) @@ -84,6 +85,8 @@ void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & sta const boost::circular_buffer & image_buffer = image_buffers_.at(image_id); const image_transport::Publisher & image_pub = image_pubs_.at(image_id); + const bool draw_iou_score = + max_iou_for_image_rois_.size() > 0 && max_iou_for_image_rois_.size() == image_rois_.size(); for (std::size_t i = 0; i < image_buffer.size(); ++i) { if (image_buffer.at(i)->header.stamp != stamp) { @@ -91,22 +94,59 @@ void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & sta } auto cv_ptr = cv_bridge::toCvCopy(image_buffer.at(i), image_buffer.at(i)->encoding); - + // draw obstacle points for (const auto & point : obstacle_points_) { cv::circle( cv_ptr->image, cv::Point(static_cast(point.x()), static_cast(point.y())), 2, cv::Scalar(255, 255, 255), 3, 4); } + + // draw rois + const int img_height = static_cast(image_buffer.at(i)->height); + const int img_width = static_cast(image_buffer.at(i)->width); for (const auto & roi : obstacle_rois_) { - drawRoiOnImage( - cv_ptr->image, roi, image_buffer.at(i)->width, image_buffer.at(i)->height, - cv::Scalar(255, 0, 0)); + drawRoiOnImage(cv_ptr->image, roi, img_width, img_height, cv::Scalar(255, 0, 0)); // blue } - // TODO(yukke42): show iou_score on image for (const auto & roi : image_rois_) { - drawRoiOnImage( - cv_ptr->image, roi, image_buffer.at(i)->width, image_buffer.at(i)->height, - cv::Scalar(0, 0, 255)); + drawRoiOnImage(cv_ptr->image, roi, img_width, img_height, cv::Scalar(0, 0, 255)); // red + } + + // show iou_score on image + if (draw_iou_score) { + for (auto roi_index = 0; roi_index < static_cast(image_rois_.size()); ++roi_index) { + std::stringstream stream; + stream << std::fixed << std::setprecision(2) << max_iou_for_image_rois_.at(roi_index); + std::string iou_score = stream.str(); + + // set text position + int baseline = 3; + cv::Size textSize = cv::getTextSize(iou_score, cv::FONT_HERSHEY_SIMPLEX, 0.5, 1, &baseline); + const int text_height = static_cast(textSize.height); + const int text_width = static_cast(textSize.width); + int x = image_rois_.at(roi_index).x_offset; + int y = image_rois_.at(roi_index).y_offset; // offset for text + if (y < 0 + text_height) + y = text_height; // if roi is on the top of image, put text on lower left of roi + if (y > img_height - text_height) + y = img_height - + text_height; // if roi is on the bottom of image, put text on upper left of roi + if (x > img_width - text_width) + x = img_width - text_width; // if roi is on the right of image, put text on left of roi + if (x < 0) x = 0; // if roi is on the left of image, put text on right of roi + + // choice color by iou score + // cv::Scalar color = max_iou_for_image_rois_.at(i) > 0.5 ? cv::Scalar(0, 255, 0) : + // cv::Scalar(0, 0, 255); + cv::Scalar color = cv::Scalar(0, 0, 255); // red + + cv::rectangle( + cv_ptr->image, cv::Point(x, y - textSize.height - baseline), + cv::Point(x + textSize.width, y), cv::Scalar(255, 255, 255), + cv::FILLED); // white background + cv::putText( + cv_ptr->image, iou_score, cv::Point(x, y), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1, + cv::LINE_AA); // text + } } image_pub.publish(cv_ptr->toImageMsg()); diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index a540688f7e751..df797369208fe 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -203,6 +203,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ (*output_msg).header.stamp.sec * (int64_t)1e9 + (*output_msg).header.stamp.nanosec; // if matching rois exist, fuseOnSingle + // please ask maintainers before parallelize this loop because debugger is not thread safe for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { RCLCPP_WARN_THROTTLE( diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 4a46c8aace696..9da9df7eff6ca 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -84,10 +84,6 @@ void RoiClusterFusionNode::fuseOnSingleImage( const DetectedObjectsWithFeature & input_roi_msg, const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjectsWithFeature & output_cluster_msg) { - std::vector debug_image_rois; - std::vector debug_pointcloud_rois; - std::vector debug_image_points; - Eigen::Matrix4d projection; projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), @@ -100,6 +96,9 @@ void RoiClusterFusionNode::fuseOnSingleImage( tf_buffer_, /*target*/ camera_info.header.frame_id, /*source*/ input_cluster_msg.header.frame_id, camera_info.header.stamp); if (!transform_stamped_optional) { + RCLCPP_WARN_STREAM( + get_logger(), "Failed to get transform from " << input_cluster_msg.header.frame_id << " to " + << camera_info.header.frame_id); return; } transform_stamped = transform_stamped_optional.value(); @@ -151,7 +150,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( max_x = std::max(static_cast(normalized_projected_point.x()), max_x); max_y = std::max(static_cast(normalized_projected_point.y()), max_y); projected_points.push_back(normalized_projected_point); - debug_image_points.push_back(normalized_projected_point); + if (debugger_) debugger_->obstacle_points_.push_back(normalized_projected_point); } } if (projected_points.empty()) { @@ -165,7 +164,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( roi.width = max_x - min_x; roi.height = max_y - min_y; m_cluster_roi.insert(std::make_pair(i, roi)); - debug_pointcloud_rois.push_back(roi); + if (debugger_) debugger_->obstacle_rois_.push_back(roi); } for (const auto & feature_obj : input_roi_msg.feature_objects) { @@ -231,13 +230,12 @@ void RoiClusterFusionNode::fuseOnSingleImage( } } } - debug_image_rois.push_back(feature_obj.feature.roi); + if (debugger_) debugger_->image_rois_.push_back(feature_obj.feature.roi); + if (debugger_) debugger_->max_iou_for_image_rois_.push_back(max_iou); } + // note: debug objects are safely cleared in fusion_node.cpp if (debugger_) { - debugger_->image_rois_ = debug_image_rois; - debugger_->obstacle_rois_ = debug_pointcloud_rois; - debugger_->obstacle_points_ = debug_image_points; debugger_->publishImage(image_id, input_roi_msg.header.stamp); } } From 8eb858a1267a02d96b9bb7be9ffe9d0172ed55ce Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 14 Nov 2023 08:49:29 +0900 Subject: [PATCH 103/223] refactor(landmark_parser): refactored landmark manager (#5511) * Refactored landmark_parser Signed-off-by: Shintaro Sakoda * Renamed landmark_parser to landmark_manager Signed-off-by: Shintaro Sakoda * Fixed tag_id Signed-off-by: Shintaro Sakoda * Refactored ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Added [[nodiscard]] Signed-off-by: Shintaro Sakoda * Refactored landmark parsing and conversion Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Added namespace Signed-off-by: Shintaro Sakoda * Fixed include Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../landmark_based_localizer/README.md | 6 ++--- .../ar_tag_based_localizer/package.xml | 2 +- .../src/ar_tag_based_localizer.cpp | 9 +++++-- .../src/ar_tag_based_localizer.hpp | 2 +- .../CMakeLists.txt | 6 ++--- .../landmark_manager/landmark_manager.hpp} | 26 ++++++++++++++----- .../package.xml | 5 ++-- .../src/landmark_manager.cpp} | 22 ++++++++++------ 8 files changed, 51 insertions(+), 27 deletions(-) rename localization/landmark_based_localizer/{landmark_parser => landmark_manager}/CMakeLists.txt (79%) rename localization/landmark_based_localizer/{landmark_parser/include/landmark_parser/landmark_parser_core.hpp => landmark_manager/include/landmark_manager/landmark_manager.hpp} (64%) rename localization/landmark_based_localizer/{landmark_parser => landmark_manager}/package.xml (88%) rename localization/landmark_based_localizer/{landmark_parser/src/landmark_parser_core.cpp => landmark_manager/src/landmark_manager.cpp} (92%) diff --git a/localization/landmark_based_localizer/README.md b/localization/landmark_based_localizer/README.md index 35d8d78e7015c..e4c79b7941b12 100644 --- a/localization/landmark_based_localizer/README.md +++ b/localization/landmark_based_localizer/README.md @@ -23,11 +23,11 @@ This calculated ego pose is passed to the EKF, where it is fused with the twist ![node diagram](./doc_image/node_diagram.drawio.svg) -### `landmark_parser` +### `landmark_manager` The definitions of the landmarks written to the map are introduced in the next section. See `Map Specifications`. -The `landmark_parser` is a utility package to load landmarks from the map. +The `landmark_manager` is a utility package to load landmarks from the map. - Translation : The center of the four vertices of the landmark - Rotation : Let the vertex numbers be 1, 2, 3, 4 counterclockwise as shown in the next section. Direction is defined as the cross product of the vector from 1 to 2 and the vector from 2 to 3. @@ -43,7 +43,7 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc ## Map specifications -For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_parser` can interpret. +For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_manager` can interpret. The four vertices of a landmark are defined counterclockwise. diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index a22e7b1acf6dc..24b737c309016 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -17,7 +17,7 @@ cv_bridge diagnostic_msgs image_transport - landmark_parser + landmark_manager lanelet2_extension localization_util rclcpp diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index bc40fb1532297..a66277c699a00 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -148,8 +148,13 @@ bool ArTagBasedLocalizer::setup() void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { - landmark_map_ = parse_landmark(msg, "apriltag_16h5", this->get_logger()); - const MarkerArray marker_msg = convert_to_marker_array_msg(landmark_map_); + const std::vector landmarks = + landmark_manager::parse_landmarks(msg, "apriltag_16h5", this->get_logger()); + for (const landmark_manager::Landmark & landmark : landmarks) { + landmark_map_[landmark.id] = landmark.pose; + } + + const MarkerArray marker_msg = landmark_manager::convert_landmarks_to_marker_array_msg(landmarks); marker_pub_->publish(marker_msg); } diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index fe33a64b995a3..889e76eb78ad2 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -45,7 +45,7 @@ #ifndef AR_TAG_BASED_LOCALIZER_HPP_ #define AR_TAG_BASED_LOCALIZER_HPP_ -#include "landmark_parser/landmark_parser_core.hpp" +#include "landmark_manager/landmark_manager.hpp" #include #include diff --git a/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt b/localization/landmark_based_localizer/landmark_manager/CMakeLists.txt similarity index 79% rename from localization/landmark_based_localizer/landmark_parser/CMakeLists.txt rename to localization/landmark_based_localizer/landmark_manager/CMakeLists.txt index 41f7c00d61383..1b6126c892d2e 100644 --- a/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt +++ b/localization/landmark_based_localizer/landmark_manager/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(landmark_parser) +project(landmark_manager) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,8 +12,8 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(landmark_parser - src/landmark_parser_core.cpp +ament_auto_add_library(landmark_manager + src/landmark_manager.cpp ) ament_auto_package( diff --git a/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp similarity index 64% rename from localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp rename to localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp index edf45c2a2997a..9a22ee13f60ae 100644 --- a/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp +++ b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp @@ -12,23 +12,35 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ -#define LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ +#ifndef LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ +#define LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ #include #include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" #include +#include #include -#include #include +#include -std::map parse_landmark( +namespace landmark_manager +{ + +struct Landmark +{ + std::string id; + geometry_msgs::msg::Pose pose; +}; + +std::vector parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger); -visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( - const std::map & landmarks); +visualization_msgs::msg::MarkerArray convert_landmarks_to_marker_array_msg( + const std::vector & landmarks); + +} // namespace landmark_manager -#endif // LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ +#endif // LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ diff --git a/localization/landmark_based_localizer/landmark_parser/package.xml b/localization/landmark_based_localizer/landmark_manager/package.xml similarity index 88% rename from localization/landmark_based_localizer/landmark_parser/package.xml rename to localization/landmark_based_localizer/landmark_manager/package.xml index e3daa93f81220..1a35ae6a338d1 100644 --- a/localization/landmark_based_localizer/landmark_parser/package.xml +++ b/localization/landmark_based_localizer/landmark_manager/package.xml @@ -1,9 +1,9 @@ - landmark_parser + landmark_manager 0.0.0 - The landmark_parser package + The landmark_manager package Shintaro Sakoda Masahiro Sakamoto Yamato Ando @@ -19,6 +19,7 @@ geometry_msgs lanelet2_extension rclcpp + tf2_eigen ament_cmake diff --git a/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp similarity index 92% rename from localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp rename to localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index c86b35b6115b4..6d1698daf5eae 100644 --- a/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -12,16 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "landmark_parser/landmark_parser_core.hpp" +#include "landmark_manager/landmark_manager.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include +#include #include #include -std::map parse_landmark( +namespace landmark_manager +{ + +std::vector parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger) { @@ -32,7 +36,7 @@ std::map parse_landmark( lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); - std::map landmark_map; + std::vector landmarks; for (const auto & poly : lanelet_map_ptr->polygonLayer) { const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; @@ -93,8 +97,8 @@ std::map parse_landmark( pose.orientation.z = q.z(); pose.orientation.w = q.w(); - // Add to map - landmark_map[marker_id] = pose; + // Add + landmarks.push_back(Landmark{marker_id, pose}); RCLCPP_INFO_STREAM(logger, "id: " << marker_id); RCLCPP_INFO_STREAM( logger, @@ -104,11 +108,11 @@ std::map parse_landmark( << pose.orientation.z << ", " << pose.orientation.w); } - return landmark_map; + return landmarks; } -visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( - const std::map & landmarks) +visualization_msgs::msg::MarkerArray convert_landmarks_to_marker_array_msg( + const std::vector & landmarks) { int32_t id = 0; visualization_msgs::msg::MarkerArray marker_array; @@ -152,3 +156,5 @@ visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( } return marker_array; } + +} // namespace landmark_manager From 450f832924dd80d23964825c9e23b0a6bafe9a89 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 14 Nov 2023 11:03:49 +0900 Subject: [PATCH 104/223] feat(obstacle_cruise_planner): use obstacle velocity based obstacle parameters (#5510) * Add extra tag for moving obstacle type Signed-off-by: Daniel Sanchez * add static and moving as parameter postfixes Signed-off-by: Daniel Sanchez * set hysteresis-based obstacle moving classification Signed-off-by: Daniel Sanchez * update config params Signed-off-by: Daniel Sanchez * Use speed norm for object classification Signed-off-by: Daniel Sanchez * changed '_' for '.' to make the code more consistent Signed-off-by: Daniel Sanchez * update documentation Signed-off-by: Daniel Sanchez * move the obstacle moving check to generateSlowDownTrajectory Signed-off-by: Daniel Sanchez * remove unnecessary reference Signed-off-by: Daniel Sanchez * add const to certain variables Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Signed-off-by: Daniel Sanchez --- planning/obstacle_cruise_planner/README.md | 32 +++--- .../config/obstacle_cruise_planner.param.yaml | 31 ++++-- .../planner_interface.hpp | 104 +++++++++++------- .../src/planner_interface.cpp | 24 ++-- 4 files changed, 120 insertions(+), 71 deletions(-) diff --git a/planning/obstacle_cruise_planner/README.md b/planning/obstacle_cruise_planner/README.md index 260f302791079..532761b1f0cb7 100644 --- a/planning/obstacle_cruise_planner/README.md +++ b/planning/obstacle_cruise_planner/README.md @@ -230,19 +230,25 @@ $$ ### Slow down planning -| Parameter | Type | Description | -| ----------------------------------------------- | -------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `slow_down.labels` | vector(string) | A vector of labels for customizing obstacle-label-based slow down behavior. Each label represents an obstacle type that will be treated differently when applying slow down. The possible labels are ("default" (Mandatory), "unknown","car","truck","bus","trailer","motorcycle","bicycle" or "pedestrian") | -| `slow_down.default.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `(optional) slow_down."label".min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | - -The role of the slow down planning is inserting slow down velocity in the trajectory where the trajectory points are close to the obstacles. The parameters can be customized depending on the obstacle type (see `slow_down.labels`), making it possible to adjust the slow down behavior depending if the obstacle is a pedestrian, bicycle, car, etc. +| Parameter | Type | Description | +| ----------------------------------------------------------------- | -------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `slow_down.labels` | vector(string) | A vector of labels for customizing obstacle-label-based slow down behavior. Each label represents an obstacle type that will be treated differently when applying slow down. The possible labels are ("default" (Mandatory), "unknown","car","truck","bus","trailer","motorcycle","bicycle" or "pedestrian") | +| `slow_down.default.static.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.moving.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `(optional) slow_down."label".(static & moving).min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | + +The role of the slow down planning is inserting slow down velocity in the trajectory where the trajectory points are close to the obstacles. The parameters can be customized depending on the obstacle type (see `slow_down.labels`), making it possible to adjust the slow down behavior depending if the obstacle is a pedestrian, bicycle, car, etc. Each obstacle type has a `static` and a `moving` parameter set, so it is possible to customize the slow down response of the ego vehicle according to the obstacle type and if it is moving or not. If an obstacle is determined to be moving, the corresponding `moving` set of parameters will be used to compute the vehicle slow down, otherwise, the `static` parameters will be used. The `static` and `moving` separation is useful for customizing the ego vehicle slow down behavior to, for example, slow down more significantly when passing stopped vehicles that might cause occlusion or that might suddenly open its doors. + +An obstacle is classified as `static` if its total speed is less than the `moving_object_speed_threshold` parameter. Furthermore, a hysteresis based approach is used to avoid chattering, it uses the `moving_object_hysteresis_range` parameter range and the obstacle's previous state (`moving` or `static`) to determine if the obstacle is moving or not. In other words, if an obstacle was previously classified as `static`, it will not change its classification to `moving` unless its total speed is greater than `moving_object_speed_threshold` + `moving_object_hysteresis_range`. Likewise, an obstacle previously classified as `moving`, will only change to `static` if its speed is lower than `moving_object_speed_threshold` - `moving_object_hysteresis_range`. The closest point on the obstacle to the ego's trajectory is calculated. Then, the slow down velocity is calculated by linear interpolation with the distance between the point and trajectory as follows. diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 123d0dda93b7a..def2a2af78b37 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -183,15 +183,30 @@ - "default" - "pedestrian" default: - min_lat_margin: 0.2 - max_lat_margin: 1.0 - min_ego_velocity: 2.0 - max_ego_velocity: 8.0 + moving: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 0.5 + max_ego_velocity: 1.5 + static: + min_lat_margin: 0.2 + max_lat_margin: 1.0 + min_ego_velocity: 2.0 + max_ego_velocity: 8.0 pedestrian: - min_lat_margin: 0.5 - max_lat_margin: 1.5 - min_ego_velocity: 1.0 - max_ego_velocity: 2.0 + moving: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 0.5 + max_ego_velocity: 0.8 + static: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 1.0 + max_ego_velocity: 2.0 + + moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving" + moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold time_margin_on_target_velocity: 1.5 # [s] diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp index d8c31fb35df9b..2e1e165a78952 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -49,6 +49,11 @@ class PlannerInterface node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); stop_speed_exceeded_pub_ = node.create_publisher("~/output/stop_speed_exceeded", 1); + + moving_object_speed_threshold = + node.declare_parameter("slow_down.moving_object_speed_threshold"); + moving_object_hysteresis_range = + node.declare_parameter("slow_down.moving_object_hysteresis_range"); } PlannerInterface() = default; @@ -183,11 +188,12 @@ class PlannerInterface const std::string & arg_uuid, const std::vector & traj_points, const std::optional & start_idx, const std::optional & end_idx, const double arg_target_vel, const double arg_feasible_target_vel, - const double arg_precise_lat_dist) + const double arg_precise_lat_dist, const bool is_moving) : uuid(arg_uuid), target_vel(arg_target_vel), feasible_target_vel(arg_feasible_target_vel), - precise_lat_dist(arg_precise_lat_dist) + precise_lat_dist(arg_precise_lat_dist), + is_moving(is_moving) { if (start_idx) { start_point = traj_points.at(*start_idx).pose; @@ -203,15 +209,17 @@ class PlannerInterface double precise_lat_dist; std::optional start_point{std::nullopt}; std::optional end_point{std::nullopt}; + bool is_moving; }; double calculateMarginFromObstacleOnCurve( const PlannerData & planner_data, const StopObstacle & stop_obstacle) const; double calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output) const; + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const; std::optional> calculateDistanceToSlowDownWithConstraints( const PlannerData & planner_data, const std::vector & traj_points, const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego) const; + const double dist_to_ego, const bool is_obstacle_moving) const; struct SlowDownInfo { @@ -223,6 +231,7 @@ class PlannerInterface struct SlowDownParam { std::vector obstacle_labels{"default"}; + std::vector obstacle_moving_classification{"static", "moving"}; std::unordered_map types_map; struct ObstacleSpecificParams { @@ -233,28 +242,23 @@ class PlannerInterface }; explicit SlowDownParam(rclcpp::Node & node) { - types_map = {{ObjectClassification::UNKNOWN, "unknown"}, - {ObjectClassification::CAR, "car"}, - {ObjectClassification::TRUCK, "truck"}, - {ObjectClassification::BUS, "bus"}, - {ObjectClassification::TRAILER, "trailer"}, - {ObjectClassification::MOTORCYCLE, "motorcycle"}, - {ObjectClassification::BICYCLE, "bicycle"}, - {ObjectClassification::PEDESTRIAN, "pedestrian"}}; obstacle_labels = node.declare_parameter>("slow_down.labels", obstacle_labels); // obstacle label dependant parameters for (const auto & label : obstacle_labels) { - ObstacleSpecificParams params; - params.max_lat_margin = - node.declare_parameter("slow_down." + label + ".max_lat_margin"); - params.min_lat_margin = - node.declare_parameter("slow_down." + label + ".min_lat_margin"); - params.max_ego_velocity = - node.declare_parameter("slow_down." + label + ".max_ego_velocity"); - params.min_ego_velocity = - node.declare_parameter("slow_down." + label + ".min_ego_velocity"); - obstacle_to_param_struct_map.emplace(std::make_pair(label, params)); + for (const auto & movement_postfix : obstacle_moving_classification) { + ObstacleSpecificParams params; + params.max_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_lat_margin"); + params.min_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_lat_margin"); + params.max_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_ego_velocity"); + params.min_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_ego_velocity"); + obstacle_to_param_struct_map.emplace( + std::make_pair(label + "." + movement_postfix, params)); + } } // common parameters @@ -264,34 +268,49 @@ class PlannerInterface lpf_gain_lat_dist = node.declare_parameter("slow_down.lpf_gain_lat_dist"); lpf_gain_dist_to_slow_down = node.declare_parameter("slow_down.lpf_gain_dist_to_slow_down"); + + types_map = {{ObjectClassification::UNKNOWN, "unknown"}, + {ObjectClassification::CAR, "car"}, + {ObjectClassification::TRUCK, "truck"}, + {ObjectClassification::BUS, "bus"}, + {ObjectClassification::TRAILER, "trailer"}, + {ObjectClassification::MOTORCYCLE, "motorcycle"}, + {ObjectClassification::BICYCLE, "bicycle"}, + {ObjectClassification::PEDESTRIAN, "pedestrian"}}; } - ObstacleSpecificParams getObstacleParamByLabel(const ObjectClassification & label_id) const + ObstacleSpecificParams getObstacleParamByLabel( + const ObjectClassification & label_id, const bool is_obstacle_moving) const { - const std::string label = types_map.at(label_id.label); - if (obstacle_to_param_struct_map.count(label) > 0) { - return obstacle_to_param_struct_map.at(label); - } - return obstacle_to_param_struct_map.at("default"); + const std::string label = + (types_map.count(label_id.label) > 0) ? types_map.at(label_id.label) : "default"; + const std::string movement_postfix = (is_obstacle_moving) ? "moving" : "static"; + return (obstacle_to_param_struct_map.count(label + "." + movement_postfix) > 0) + ? obstacle_to_param_struct_map.at(label + "." + movement_postfix) + : obstacle_to_param_struct_map.at("default." + movement_postfix); } void onParam(const std::vector & parameters) { // obstacle type dependant parameters for (const auto & label : obstacle_labels) { - auto & param_by_obstacle_label = obstacle_to_param_struct_map[label]; - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".max_lat_margin", - param_by_obstacle_label.max_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".min_lat_margin", - param_by_obstacle_label.min_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".max_ego_velocity", - param_by_obstacle_label.max_ego_velocity); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".min_ego_velocity", - param_by_obstacle_label.min_ego_velocity); + for (const auto & movement_postfix : obstacle_moving_classification) { + if (obstacle_to_param_struct_map.count(label + "." + movement_postfix) < 1) continue; + auto & param_by_obstacle_label = + obstacle_to_param_struct_map.at(label + "." + movement_postfix); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_lat_margin", + param_by_obstacle_label.max_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_lat_margin", + param_by_obstacle_label.min_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_ego_velocity", + param_by_obstacle_label.max_ego_velocity); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_ego_velocity", + param_by_obstacle_label.min_ego_velocity); + } } // common parameters @@ -313,7 +332,8 @@ class PlannerInterface double lpf_gain_dist_to_slow_down; }; SlowDownParam slow_down_param_; - + double moving_object_speed_threshold; + double moving_object_hysteresis_range; std::vector prev_slow_down_output_; // previous trajectory and distance to stop // NOTE: Previous trajectory is memorized to deal with nearest index search for overlapping or diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 76469364cfb39..47f62016df53b 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -561,9 +561,17 @@ std::vector PlannerInterface::generateSlowDownTrajectory( const auto & obstacle = obstacles.at(i); const auto prev_output = getObjectFromUuid(prev_slow_down_output_, obstacle.uuid); + const bool is_obstacle_moving = [&]() -> bool { + const auto object_vel_norm = std::hypot(obstacle.velocity, obstacle.lat_velocity); + if (!prev_output) return object_vel_norm > moving_object_speed_threshold; + if (prev_output->is_moving) + return object_vel_norm > moving_object_speed_threshold - moving_object_hysteresis_range; + return object_vel_norm > moving_object_speed_threshold + moving_object_hysteresis_range; + }(); + // calculate slow down start distance, and insert slow down velocity const auto dist_vec_to_slow_down = calculateDistanceToSlowDownWithConstraints( - planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego); + planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego, is_obstacle_moving); if (!dist_vec_to_slow_down) { RCLCPP_INFO_EXPRESSION( rclcpp::get_logger("ObstacleCruisePlanner::PlannerInterface"), enable_debug_info_, @@ -648,7 +656,7 @@ std::vector PlannerInterface::generateSlowDownTrajectory( // update prev_slow_down_output_ new_prev_slow_down_output.push_back(SlowDownOutput{ obstacle.uuid, slow_down_traj_points, slow_down_start_idx, slow_down_end_idx, - stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist}); + stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist, is_obstacle_moving}); } // update prev_slow_down_output_ @@ -663,10 +671,11 @@ std::vector PlannerInterface::generateSlowDownTrajectory( } double PlannerInterface::calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output) const + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const { - const auto & p = slow_down_param_.getObstacleParamByLabel(obstacle.classification); - + const auto & p = + slow_down_param_.getObstacleParamByLabel(obstacle.classification, is_obstacle_moving); const double stable_precise_lat_dist = [&]() { if (prev_output) { return signal_processing::lowpassFilter( @@ -689,15 +698,14 @@ std::optional> PlannerInterface::calculateDistanceToSlowDownWithConstraints( const PlannerData & planner_data, const std::vector & traj_points, const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego) const + const double dist_to_ego, const bool is_obstacle_moving) const { const double abs_ego_offset = planner_data.is_driving_forward ? std::abs(vehicle_info_.max_longitudinal_offset_m) : std::abs(vehicle_info_.min_longitudinal_offset_m); const double obstacle_vel = obstacle.velocity; - // calculate slow down velocity - const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output); + const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output, is_obstacle_moving); // calculate distance to collision points const double dist_to_front_collision = From cadba461d609e1f9ca72f29ab199814c200fcfd0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 14 Nov 2023 11:31:36 +0900 Subject: [PATCH 105/223] refactor(side_shift): support new interface (#5556) Signed-off-by: satoshi-ota --- .../side_shift/side_shift_module.hpp | 26 ++----------------- .../side_shift/side_shift_module.cpp | 14 ++++------ 2 files changed, 7 insertions(+), 33 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index 7c04cab5c081f..fce31b6db7369 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -49,8 +49,6 @@ class SideShiftModule : public SceneModuleInterface bool isExecutionReady() const override; bool isReadyForNextRequest( const double & min_request_time_sec, bool override_requests = false) const noexcept; - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; void updateData() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; @@ -70,32 +68,12 @@ class SideShiftModule : public SceneModuleInterface { } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override - { - updateData(); - - if (!isWaitingApproval()) { - return plan(); - } - - // module is waiting approval. Check it. - if (isActivated()) { - RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); - return plan(); - } else { - RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); - return planWaitingApproval(); - } - } - private: - bool canTransitSuccessState() override { return false; } + bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } - rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; + bool canTransitIdleToRunningState() override { return true; } void initVariables(); diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 2232c6d750d55..46332e738f82f 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -40,8 +40,6 @@ SideShiftModule::SideShiftModule( const std::unordered_map > & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters} { - // If lateral offset is subscribed, it approves side shift module automatically - clearWaitingApproval(); } void SideShiftModule::initVariables() @@ -80,7 +78,7 @@ void SideShiftModule::setParameters(const std::shared_ptr & bool SideShiftModule::isExecutionRequested() const { - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } @@ -112,7 +110,7 @@ bool SideShiftModule::isReadyForNextRequest( return false; } -ModuleStatus SideShiftModule::updateState() +bool SideShiftModule::canTransitSuccessState() { // Never return the FAILURE. When the desired offset is zero and the vehicle is in the original // drivable area,this module can stop the computation and return SUCCESS. @@ -150,7 +148,7 @@ ModuleStatus SideShiftModule::updateState() no_shifted_plan); if (no_request && no_shifted_plan && no_offset_diff) { - return ModuleStatus::SUCCESS; + return true; } const auto & current_lanes = utils::getCurrentLanes(planner_data_); @@ -169,7 +167,7 @@ ModuleStatus SideShiftModule::updateState() } else { shift_status_ = SideShiftStatus::AFTER_SHIFT; } - return ModuleStatus::RUNNING; + return false; } void SideShiftModule::updateData() @@ -184,7 +182,7 @@ void SideShiftModule::updateData() } } - if (current_state_ != ModuleStatus::RUNNING && current_state_ != ModuleStatus::IDLE) { + if (getCurrentStatus() != ModuleStatus::RUNNING && getCurrentStatus() != ModuleStatus::IDLE) { return; } @@ -331,8 +329,6 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() prev_output_ = shifted_path; - waitApproval(); - return output; } From 9f43afc510143246982d9d3f9600913462796417 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 14 Nov 2023 12:46:44 +0900 Subject: [PATCH 106/223] refactor(goal_planner): add updateStatus and reduce variables (#5546) * refactor(goal_planner): add updateStatus and reduce variables Signed-off-by: kosuke55 refactor Signed-off-by: kosuke55 refactor Signed-off-by: kosuke55 * move to updatedata Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp Co-authored-by: Kyoichi Sugahara * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: Kyoichi Sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../goal_planner/goal_planner_module.hpp | 56 ++-- .../goal_planner/pull_over_planner_base.hpp | 1 + .../goal_planner/goal_planner_module.cpp | 272 +++++++++--------- 3 files changed, 152 insertions(+), 177 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index e4044d7191805..5149979ef082d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -93,50 +93,30 @@ class PullOverStatus void reset() { lane_parking_pull_over_path_ = nullptr; - current_path_idx_ = 0; - require_increment_ = true; prev_stop_path_ = nullptr; prev_stop_path_after_approval_ = nullptr; - current_lanes_.clear(); - pull_over_lanes_.clear(); - lanes_.clear(); - has_decided_path_ = false; - is_safe_dynamic_objects_ = false; + + is_safe_ = false; prev_found_path_ = false; - prev_is_safe_dynamic_objects_ = false; - has_decided_velocity_ = false; + prev_is_safe_ = false; } DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) - DEFINE_SETTER_GETTER(size_t, current_path_idx) - DEFINE_SETTER_GETTER(bool, require_increment) DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path) DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path_after_approval) - DEFINE_SETTER_GETTER(lanelet::ConstLanelets, current_lanes) - DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes) - DEFINE_SETTER_GETTER(std::vector, lanes) - DEFINE_SETTER_GETTER(bool, has_decided_path) - DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects) + DEFINE_SETTER_GETTER(bool, is_safe) DEFINE_SETTER_GETTER(bool, prev_found_path) - DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects) - DEFINE_SETTER_GETTER(bool, has_decided_velocity) + DEFINE_SETTER_GETTER(bool, prev_is_safe) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) private: std::shared_ptr lane_parking_pull_over_path_{nullptr}; - size_t current_path_idx_{0}; - bool require_increment_{true}; std::shared_ptr prev_stop_path_{nullptr}; std::shared_ptr prev_stop_path_after_approval_{nullptr}; - lanelet::ConstLanelets current_lanes_{}; - lanelet::ConstLanelets pull_over_lanes_{}; - std::vector lanes_{}; - bool has_decided_path_{false}; - bool is_safe_dynamic_objects_{false}; + bool is_safe_{false}; bool prev_found_path_{false}; - bool prev_is_safe_dynamic_objects_{false}; - bool has_decided_velocity_{false}; + bool prev_is_safe_{false}; Pose refined_goal_pose_{}; Pose closest_goal_candidate_pose_{}; @@ -177,6 +157,10 @@ class ThreadSafeData bool incrementPathIndex() { const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return false; + } + if (pull_over_path_->incrementPathIndex()) { last_path_idx_increment_time_ = clock_->now(); return true; @@ -393,10 +377,10 @@ class GoalPlannerModule : public SceneModuleInterface void decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const; void decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const; - PathWithLaneId generateStopPath(); - PathWithLaneId generateFeasibleStopPath(); + PathWithLaneId generateStopPath() const; + PathWithLaneId generateFeasibleStopPath() const; - void keepStoppedWithCurrentPath(PathWithLaneId & path); + void keepStoppedWithCurrentPath(PathWithLaneId & path) const; double calcSignedArcLengthFromEgo(const PathWithLaneId & path, const Pose & pose) const; // status @@ -411,6 +395,7 @@ class GoalPlannerModule : public SceneModuleInterface bool hasDecidedPath() const; void decideVelocity(); bool foundPullOverPath() const; + void updateStatus(const BehaviorModuleOutput & output); // validation bool hasEnoughDistance(const PullOverPath & pull_over_path) const; @@ -433,16 +418,13 @@ class GoalPlannerModule : public SceneModuleInterface const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; - // deal with pull over partial paths - void transitionToNextPathIfFinishingCurrentPath(); - // lanes and drivable area - void setLanes(); + std::vector generateDrivableLanes() const; void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // output setter - void setOutput(BehaviorModuleOutput & output); - void setStopPath(BehaviorModuleOutput & output); + void setOutput(BehaviorModuleOutput & output) const; + void setStopPath(BehaviorModuleOutput & output) const; /** * @brief Sets a stop path in the current path based on safety conditions and previous paths. @@ -453,7 +435,7 @@ class GoalPlannerModule : public SceneModuleInterface * * @param output BehaviorModuleOutput */ - void setStopPathFromCurrentPath(BehaviorModuleOutput & output); + void setStopPathFromCurrentPath(BehaviorModuleOutput & output) const; void setModifiedGoal(BehaviorModuleOutput & output) const; void setTurnSignalInfo(BehaviorModuleOutput & output) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index 4267261fdfe84..acb034a29d9e5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -53,6 +53,7 @@ struct PullOverPath Pose end_pose{}; std::vector debug_poses{}; size_t goal_id{}; + bool decided_velocity{false}; PathWithLaneId getFullPath() const { diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 0475cd92f1bec..202c19f1bf1db 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -255,10 +255,21 @@ void GoalPlannerModule::updateData() updateOccupancyGrid(); - // set current road lanes, pull over lanes, and drivable lane - setLanes(); - generateGoalCandidates(); + + if (!isActivated()) { + return; + } + + if (hasFinishedCurrentPath()) { + thread_safe_data_.incrementPathIndex(); + } + + if (!last_approval_data_) { + last_approval_data_ = + std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); + decideVelocity(); + } } void GoalPlannerModule::initializeOccupancyGridMap() @@ -524,9 +535,7 @@ void GoalPlannerModule::returnToLaneParking() return; } - status_.set_has_decided_path(false); thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - RCLCPP_INFO(getLogger(), "return to lane parking"); } @@ -549,9 +558,6 @@ void GoalPlannerModule::generateGoalCandidates() goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); thread_safe_data_.set_goal_candidates(goal_searcher_->search()); - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, false); status_.set_closest_goal_candidate_pose( goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()) .goal_pose); @@ -689,28 +695,25 @@ void GoalPlannerModule::selectSafePullOverPath() } } -void GoalPlannerModule::setLanes() +std::vector GoalPlannerModule::generateDrivableLanes() const { - const std::lock_guard lock(mutex_); - status_.set_current_lanes(utils::getExtendedCurrentLanes( + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, - /*forward_only_in_route*/ false)); - status_.set_pull_over_lanes(goal_planner_utils::getPullOverLanes( + /*forward_only_in_route*/ false); + const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes( *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length)); - status_.set_lanes(utils::generateDrivableLanesWithShoulderLanes( - status_.get_current_lanes(), status_.get_pull_over_lanes())); + parameters_->forward_goal_search_length); + return utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_over_lanes); } -void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) +void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const { if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); } else if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath() && - status_.get_has_decided_path() && isActivated()) { + parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -735,34 +738,22 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setModifiedGoal(output); // set hazard and turn signal - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { setTurnSignalInfo(output); } - - // for the next loop setOutput(). - // this is used to determine whether to generate a new stop path or keep the current stop path. - const std::lock_guard lock(mutex_); - status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); - status_.set_prev_is_safe_dynamic_objects( - parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); } -void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) +void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const { if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); - const std::lock_guard lock(mutex_); - status_.set_prev_stop_path(output.path); - // set stop path as pull over path - auto stop_pull_over_path = std::make_shared(); - stop_pull_over_path->partial_paths.push_back(*output.path); - thread_safe_data_.set_pull_over_path(stop_pull_over_path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path output.path = status_.get_prev_stop_path(); + // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); @@ -770,10 +761,10 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) output.reference_path = getPreviousModuleOutput().reference_path; } -void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) +void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path - if (status_.get_prev_is_safe_dynamic_objects() || !status_.get_prev_stop_path_after_approval()) { + if (status_.get_prev_is_safe() || !status_.get_prev_stop_path_after_approval()) { auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( @@ -781,7 +772,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output parameters_->maximum_jerk_for_stop); if (stop_path) { output.path = std::make_shared(*stop_path); - status_.set_prev_stop_path_after_approval(output.path); + // status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { output.path = @@ -794,6 +785,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path output.path = status_.get_prev_stop_path_after_approval(); + // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } @@ -808,7 +800,7 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); + *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -860,13 +852,10 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, SteeringFactor::GOAL_PLANNER, steering_factor_direction, type, ""); } +// NOTE: Once this function returns true, it will continue to return true thereafter. Because +// selectSafePullOverPath() will not select new path. bool GoalPlannerModule::hasDecidedPath() const { - // once decided, keep the decision - if (status_.get_has_decided_path()) { - return true; - } - // if path is not safe, not decided if (!thread_safe_data_.foundPullOverPath()) { return false; @@ -874,18 +863,15 @@ bool GoalPlannerModule::hasDecidedPath() const // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( - thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose, - std::numeric_limits::max(), M_PI_2); - if (!ego_segment_idx) { - return false; - } + const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex( + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position); + const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( thread_safe_data_.get_pull_over_path()->getCurrentPath().points, thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position, - *ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, + ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); return dist_to_parking_start_pose < parameters_->decide_path_distance; } @@ -894,16 +880,12 @@ void GoalPlannerModule::decideVelocity() { const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; - // decide velocity to guarantee turn signal lighting time - if (!status_.get_has_decided_velocity()) { - auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - const auto vel = - static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); - for (auto & p : first_path.points) { - p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, vel); - } + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); + const auto vel = + static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); + for (auto & p : first_path.points) { + p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, vel); } - status_.set_has_decided_velocity(true); } CandidateOutput GoalPlannerModule::planCandidate() const @@ -920,31 +902,15 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() return getPreviousModuleOutput(); } - constexpr double path_update_duration = 1.0; - resetPathCandidate(); resetPathReference(); - // Check if it needs to decide path - status_.set_has_decided_path(hasDecidedPath()); - - // Use decided path - if (status_.get_has_decided_path()) { - if (isActivated() && !last_approval_data_) { - last_approval_data_ = - std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); - decideVelocity(); - } - transitionToNextPathIfFinishingCurrentPath(); - } else if ( - !thread_safe_data_.get_pull_over_path_candidates().empty() && - needPathUpdate(path_update_duration)) { + if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_.get_pull_over_path() selectSafePullOverPath(); } - // else: stop path is generated and set by setOutput() // set output and status BehaviorModuleOutput output{}; @@ -969,7 +935,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() } const auto distance_to_path_change = calcDistanceToPathChange(); - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } // TODO(tkhmy) add handle status TRYING @@ -980,9 +946,41 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); + updateStatus(output); + return output; } +void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) +{ + if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { + status_.set_prev_stop_path(output.path); + } + + // for the next loop setOutput(). + // this is used to determine whether to generate a new stop path or keep the current stop path. + status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); + status_.set_prev_is_safe( + parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); + + if (!isActivated()) { + return; + } + + if ( + !parameters_->safety_check_params.enable_safety_check || isSafePath() || + (!status_.get_prev_is_safe() && status_.get_prev_stop_path_after_approval())) { + return; + } + status_.set_prev_is_safe(false); + const bool is_stop_path = std::any_of( + output.path->points.begin(), output.path->points.end(), + [](const auto & point) { return point.point.longitudinal_velocity_mps == 0.0; }); + if (is_stop_path) { + status_.set_prev_stop_path_after_approval(output.path); + } +} + BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { resetPathCandidate(); @@ -1019,7 +1017,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); + *out.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -1032,7 +1030,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( } const auto distance_to_path_change = calcDistanceToPathChange(); - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } updateSteeringFactor( @@ -1079,7 +1077,7 @@ void GoalPlannerModule::setParameters(const std::shared_ptrroute_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; @@ -1087,17 +1085,19 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; - if (status_.get_current_lanes().empty()) { + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + + if (current_lanes.empty()) { return PathWithLaneId{}; } // generate reference path - const auto s_current = - lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; - auto reference_path = - route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); + auto reference_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); // if not approved stop road lane. // stop point priority is @@ -1162,19 +1162,20 @@ PathWithLaneId GoalPlannerModule::generateStopPath() return reference_path; } -PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() +PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const { const auto & route_handler = planner_data_->route_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & common_parameters = planner_data_->parameters; // generate stop reference path - const auto s_current = - lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; - auto stop_path = - route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); + auto stop_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); // calc minimum stop distance under maximum deceleration const auto min_stop_distance = calcFeasibleDecelDistance( @@ -1193,40 +1194,6 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() return stop_path; } -void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() -{ - if (!isActivated() || !last_approval_data_) { - return; - } - - // if using arc_path and finishing current_path, get next path - // enough time for turn signal - const bool has_passed_enough_time_from_approval = - (clock_->now() - last_approval_data_->time).seconds() > - planner_data_->parameters.turn_signal_search_time; - if (!has_passed_enough_time_from_approval) { - return; - } - - // require increment only when the time passed is enough - // to prevent increment before driving - // when the end of the current path is close to the current pose - // this value should be `keep_stop_time` in keepStoppedWithCurrentPath - constexpr double keep_current_idx_time = 4.0; - const bool has_passed_enough_time_from_increment = - (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > - keep_current_idx_time; - if (!has_passed_enough_time_from_increment) { - return; - } - - if (!hasFinishedCurrentPath()) { - return; - } - - thread_safe_data_.incrementPathIndex(); -} - bool GoalPlannerModule::isStopped( std::deque & odometry_buffer, const double time) { @@ -1285,13 +1252,41 @@ bool GoalPlannerModule::isStuck() bool GoalPlannerModule::hasFinishedCurrentPath() { + if (!last_approval_data_) { + return false; + } + + if (!isStopped()) { + return false; + } + + // check if enough time has passed since last approval + // this is necessary to give turn signal for enough time + const bool has_passed_enough_time_from_approval = + (clock_->now() - last_approval_data_->time).seconds() > + planner_data_->parameters.turn_signal_search_time; + if (!has_passed_enough_time_from_approval) { + return false; + } + + // require increment only when the time passed is enough + // to prevent increment before driving + // when the end of the current path is close to the current pose + // this value should be `keep_stop_time` in keepStoppedWithCurrentPath + constexpr double keep_current_idx_time = 4.0; + const bool has_passed_enough_time_from_increment = + (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > + keep_current_idx_time; + if (!has_passed_enough_time_from_increment) { + return false; + } + + // check if self pose is near the end of current path const auto current_path_end = thread_safe_data_.get_pull_over_path()->getCurrentPath().points.back(); const auto & self_pose = planner_data_->self_odometry->pose.pose; - const bool is_near_target = tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < - parameters_->th_arrived_distance; - - return is_near_target && isStopped(); + return tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < + parameters_->th_arrived_distance; } bool GoalPlannerModule::isOnModifiedGoal() const @@ -1334,9 +1329,8 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const { // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds // before starting pull_over - turn_signal.desired_start_point = last_approval_data_ && status_.get_has_decided_path() - ? last_approval_data_->pose - : current_pose; + turn_signal.desired_start_point = + last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose; turn_signal.desired_end_point = end_pose; turn_signal.required_start_point = start_pose; turn_signal.required_end_point = end_pose; @@ -1440,7 +1434,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c return true; } -void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) +void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) const { constexpr double keep_stop_time = 2.0; if (!thread_safe_data_.get_last_path_idx_increment_time()) { @@ -1619,7 +1613,7 @@ bool GoalPlannerModule::isCrossingPossible( bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) const { - const lanelet::ConstLanelets lanes = utils::transformToLanelets(status_.get_lanes()); + const lanelet::ConstLanelets lanes = utils::transformToLanelets(generateDrivableLanes()); const Pose & start_pose = pull_over_path.start_pose; const Pose & end_pose = pull_over_path.end_pose; @@ -1655,11 +1649,10 @@ bool GoalPlannerModule::isSafePath() const const std::pair terminal_velocity_and_accel = utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, - status_.get_current_path_idx()); + thread_safe_data_.get_pull_over_path()->path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.get_current_path_idx()); utils::start_goal_planner_common::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly @@ -1680,7 +1673,7 @@ bool GoalPlannerModule::isSafePath() const pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = - status_.get_prev_is_safe_dynamic_objects() ? 1.0 : parameters_->hysteresis_factor_expand_rate; + status_.get_prev_is_safe() ? 1.0 : parameters_->hysteresis_factor_expand_rate; utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); @@ -1742,9 +1735,8 @@ void GoalPlannerModule::setDebugData() }; if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = status_.get_has_decided_path() - ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = status_.get_refined_goal_pose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); @@ -1834,7 +1826,7 @@ void GoalPlannerModule::setDebugData() marker.text = magic_enum::enum_name(thread_safe_data_.getPullOverPlannerType()); if (thread_safe_data_.foundPullOverPath()) { marker.text += - " " + std::to_string(status_.get_current_path_idx()) + "/" + + " " + std::to_string(thread_safe_data_.get_pull_over_path()->path_idx) + "/" + std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); } From b11496eaa9ffb7e3d55daa1011be71fb5d96f7b2 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 14 Nov 2023 15:47:59 +0900 Subject: [PATCH 107/223] fix(simple_planning_simulator): change default value of manual gear, DRIVE -> PARK (#5563) --- .../simple_planning_simulator_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 07a5d34f63c39..a3715a1efe8ab 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -210,7 +210,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt // control mode current_control_mode_.mode = ControlModeReport::AUTONOMOUS; - current_manual_gear_cmd_.command = GearCommand::DRIVE; + current_manual_gear_cmd_.command = GearCommand::PARK; } void SimplePlanningSimulator::initialize_vehicle_model() From 18867318a73a4561151c9d5d793bd40a4f803a48 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Nov 2023 16:33:19 +0900 Subject: [PATCH 108/223] fix(lane_change): fix object debug marker not having point (#5577) Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_planner/src/marker_utils/utils.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 031926f2d9d1d..f1f681fed06a0 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include #include #include @@ -45,6 +46,7 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) { CollisionCheckDebug debug; debug.current_obj_pose = obj.initial_pose.pose; + debug.extended_obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); debug.current_twist = obj.initial_twist.twist; return {tier4_autoware_utils::toHexString(obj.uuid), debug}; } From 7d7168707d303d368fc1ec67a5977a889cc1fdd7 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 14 Nov 2023 16:35:04 +0900 Subject: [PATCH 109/223] fix(avoidance): fix a bug regarding the nearest search (#5575) * fix a bug regarding nearest search --------- Signed-off-by: Yuki Takagi --- .../src/scene_module/avoidance/avoidance_module.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 2ad0928696a5c..2d85f8cbe3224 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -2025,13 +2025,16 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig planner_data_->parameters.backward_path_length, longest_dist_to_shift_point + extra_margin); const size_t orig_ego_idx = planner_data_->findEgoIndex(original_path.points); - const size_t prev_ego_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto prev_ego_idx = motion_utils::findNearestSegmentIndex( previous_path.points, getPose(original_path.points.at(orig_ego_idx)), std::numeric_limits::max(), planner_data_->parameters.ego_nearest_yaw_threshold); + if (!prev_ego_idx) { + return original_path; + } size_t clip_idx = 0; for (size_t i = 0; i < prev_ego_idx; ++i) { - if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, prev_ego_idx)) { + if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { break; } clip_idx = i; @@ -2041,7 +2044,7 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig { extended_path.points.insert( extended_path.points.end(), previous_path.points.begin() + clip_idx, - previous_path.points.begin() + prev_ego_idx); + previous_path.points.begin() + *prev_ego_idx); } // overwrite backward path velocity by latest one. From 5fe26c63254a273477b27723c925fa48ff4d6e35 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 14 Nov 2023 18:48:25 +0900 Subject: [PATCH 110/223] refactor(goal_planner): refactoring plan flow and add post process (#5554) * refactor(goal_planner): refactoring plan flow and add post process Signed-off-by: kosuke55 do not decel when searching Signed-off-by: kosuke55 rename planPullOver Signed-off-by: kosuke55 * add plan flow Signed-off-by: kosuke55 * add reason of early return Signed-off-by: kosuke55 * typo Signed-off-by: kosuke55 * fix path_candidate_ Signed-off-by: kosuke55 * pub path candidate after approval Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 31 +- .../goal_planner/goal_planner_module.cpp | 273 ++++++++---------- 2 files changed, 154 insertions(+), 150 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 5149979ef082d..2e95ca82735fb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -287,27 +287,47 @@ class GoalPlannerModule : public SceneModuleInterface } } - CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; void processOnExit() override; void updateData() override; + void postProcess() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } + CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: + /*  + * state transitions and plan function used in each state + * + * +--------------------------+ + * | RUNNING | + * | planPullOverAsCandidate()| + * +------------+-------------+ + * | hasDecidedPath() + * 2 v + * +--------------------------+ + * | WAITING_APPROVAL | + * | planPullOverAsCandidate()| + * +------------+-------------+ + * | isActivated() + * 3 v + * +--------------------------+ + * | RUNNING | + * | planPullOverAsOutput() | + * +--------------------------+ + */ + // The start_planner activates when it receives a new route, // so there is no need to terminate the goal planner. // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } - bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return true; } mutable StartGoalPlannerData goal_planner_data_; @@ -411,8 +431,9 @@ class GoalPlannerModule : public SceneModuleInterface void returnToLaneParking(); // plan pull over path - BehaviorModuleOutput planWithGoalModification(); - BehaviorModuleOutput planWaitingApprovalWithGoalModification(); + BehaviorModuleOutput planPullOver(); + BehaviorModuleOutput planPullOverAsOutput(); + BehaviorModuleOutput planPullOverAsCandidate(); void selectSafePullOverPath(); std::vector sortPullOverPathCandidatesByGoalPriority( const std::vector & pull_over_path_candidates, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 202c19f1bf1db..84b4032cde4ad 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -253,10 +253,17 @@ void GoalPlannerModule::updateData() initializeOccupancyGridMap(); } + resetPathCandidate(); + resetPathReference(); + path_reference_ = getPreviousModuleOutput().reference_path; + updateOccupancyGrid(); generateGoalCandidates(); + // Only after the path is decided, approval is allowed and the module is Activated. + // The path index is not incremented until after deciding the path. + // So return here, if (!isActivated()) { return; } @@ -541,16 +548,12 @@ void GoalPlannerModule::returnToLaneParking() void GoalPlannerModule::generateGoalCandidates() { - const auto & route_handler = planner_data_->route_handler; - - // with old architecture, module instance is not cleared when new route is received - // so need to reset status here. - // todo: move this check out of this function after old architecture is removed if (!thread_safe_data_.get_goal_candidates().empty()) { return; } // calculate goal candidates + const auto & route_handler = planner_data_->route_handler; const Pose goal_pose = route_handler->getOriginalGoalPose(); status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { @@ -574,17 +577,12 @@ void GoalPlannerModule::generateGoalCandidates() BehaviorModuleOutput GoalPlannerModule::plan() { - resetPathCandidate(); - resetPathReference(); - - path_reference_ = getPreviousModuleOutput().reference_path; - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planWithGoalModification(); - } else { - fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); - return fixed_goal_planner_->plan(planner_data_); + return planPullOver(); } + + fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); + return fixed_goal_planner_->plan(planner_data_); } std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( @@ -671,27 +669,26 @@ void GoalPlannerModule::selectSafePullOverPath() } // decelerate before the search area start - const auto search_start_offset_pose = calcLongitudinalOffsetPose( + const auto decel_pose = calcLongitudinalOffsetPose( thread_safe_data_.get_pull_over_path()->getFullPath().points, - status_.get_refined_goal_pose().position, - -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - - approximate_pull_over_distance_); + status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - if (search_start_offset_pose) { - decelerateBeforeSearchStart(*search_start_offset_pose, first_path); - } else { - // if already passed the search start offset pose, set pull_over_velocity to first_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - parameters_->pull_over_velocity); - for (auto & p : first_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = std::min( - p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, first_path); + return; + } + + // if already passed the search start offset pose, set pull_over_velocity to first_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + parameters_->pull_over_velocity); + for (auto & p : first_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; } + p.point.longitudinal_velocity_mps = std::min( + p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); } } @@ -709,11 +706,16 @@ std::vector GoalPlannerModule::generateDrivableLanes() const void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const { + output.reference_path = getPreviousModuleOutput().reference_path; + if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); - } else if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { + setDrivableAreaInfo(output); + return; + } + + if (parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -721,24 +723,18 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const } else { // situation : (safe against static and dynamic objects) or (safe against static objects and // before approval) don't stop - if (isActivated()) { - resetWallPoses(); - } // keep stop if not enough time passed, // because it takes time for the trajectory to be reflected auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); - output.path = std::make_shared(current_path); - output.reference_path = getPreviousModuleOutput().reference_path; } - setDrivableAreaInfo(output); - setModifiedGoal(output); + setDrivableAreaInfo(output); // set hazard and turn signal - if (hasDecidedPath()) { + if (hasDecidedPath() && isActivated()) { setTurnSignalInfo(output); } } @@ -758,7 +754,6 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } - output.reference_path = getPreviousModuleOutput().reference_path; } void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const @@ -789,7 +784,6 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } - output.reference_path = getPreviousModuleOutput().reference_path; } void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const @@ -888,22 +882,48 @@ void GoalPlannerModule::decideVelocity() } } -CandidateOutput GoalPlannerModule::planCandidate() const +BehaviorModuleOutput GoalPlannerModule::planPullOver() { - return CandidateOutput( - thread_safe_data_.get_pull_over_path() ? thread_safe_data_.get_pull_over_path()->getFullPath() - : PathWithLaneId()); + if (!hasDecidedPath()) { + return planPullOverAsCandidate(); + } + + return planPullOverAsOutput(); } -BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() +BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() { // if pull over path candidates generation is not finished, use previous module output if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } - resetPathCandidate(); - resetPathReference(); + BehaviorModuleOutput output{}; + const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); + output.modified_goal = pull_over_output.modified_goal; + output.path = std::make_shared(generateStopPath()); + + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + + DrivableAreaInfo current_drivable_area_info{}; + current_drivable_area_info.drivable_lanes = target_drivable_lanes; + output.drivable_area_info = utils::combineDrivableAreaInfo( + current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); + + if (!thread_safe_data_.foundPullOverPath()) { + return output; + } + + return output; +} + +BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() +{ + // if pull over path candidates generation is not finished, use previous module output + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { + return getPreviousModuleOutput(); + } if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, @@ -915,8 +935,6 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { @@ -934,21 +952,34 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() return output; } + path_candidate_ = + std::make_shared(thread_safe_data_.get_pull_over_path()->getFullPath()); + + updateStatus(output); + + return output; +} + +void GoalPlannerModule::postProcess() +{ + if (!thread_safe_data_.foundPullOverPath()) { + return; + } + + const bool has_decided_path = hasDecidedPath(); const auto distance_to_path_change = calcDistanceToPathChange(); - if (hasDecidedPath()) { + + if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } - // TODO(tkhmy) add handle status TRYING + updateSteeringFactor( {thread_safe_data_.get_pull_over_path()->start_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose}, - {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::TURNING); + {distance_to_path_change.first, distance_to_path_change.second}, + has_decided_path ? SteeringFactor::TURNING : SteeringFactor::APPROACHING); setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); - - updateStatus(output); - - return output; } void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) @@ -983,64 +1014,12 @@ void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { - resetPathCandidate(); - resetPathReference(); - - path_reference_ = getPreviousModuleOutput().reference_path; - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planWaitingApprovalWithGoalModification(); - } else { - fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); - return fixed_goal_planner_->plan(planner_data_); - } -} - -BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification() -{ - // if pull over path candidates generation is not finished, use previous module output - if (thread_safe_data_.get_pull_over_path_candidates().empty()) { - return getPreviousModuleOutput(); - } - - BehaviorModuleOutput out; - out.modified_goal = planWithGoalModification().modified_goal; // update status_ - out.path = std::make_shared(generateStopPath()); - out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; - - // generate drivable area info for new architecture - if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { - const double drivable_area_margin = planner_data_->parameters.vehicle_width; - out.drivable_area_info.drivable_margin = - planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; - } else { - const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); - - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = target_drivable_lanes; - out.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); - } - - if (!thread_safe_data_.foundPullOverPath()) { - return out; + return planPullOverAsCandidate(); } - const auto distance_to_path_change = calcDistanceToPathChange(); - if (hasDecidedPath()) { - updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); - } - updateSteeringFactor( - {thread_safe_data_.get_pull_over_path()->start_pose, - thread_safe_data_.get_modified_goal_pose()->goal_pose}, - {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); - - setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); - - return out; + fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); + return fixed_goal_planner_->plan(planner_data_); } std::pair GoalPlannerModule::calcDistanceToPathChange() const @@ -1099,6 +1078,13 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double s_end = s_current + common_parameters.forward_path_length; auto reference_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); + // calculate search start offset pose from the closest goal candidate pose with + // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible + // stop point is found, stop at this position. + const auto decel_pose = calcLongitudinalOffsetPose( + reference_path.points, status_.get_closest_goal_candidate_pose().position, + -approximate_pull_over_distance_); + // if not approved stop road lane. // stop point priority is // 1. actual start pose @@ -1107,27 +1093,24 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // (In the case of the curve lane, the position is not aligned due to the // difference between the outer and inner sides) // 4. feasible stop - const auto search_start_offset_pose = calcLongitudinalOffsetPose( - reference_path.points, status_.get_closest_goal_candidate_pose().position, - -approximate_pull_over_distance_); - if ( - !thread_safe_data_.foundPullOverPath() && !thread_safe_data_.get_closest_start_pose() && - !search_start_offset_pose) { - return generateFeasibleStopPath(); - } - - const Pose stop_pose = [&]() -> Pose { + const auto stop_pose = std::invoke([&]() -> boost::optional { if (thread_safe_data_.foundPullOverPath()) { return thread_safe_data_.get_pull_over_path()->start_pose; } if (thread_safe_data_.get_closest_start_pose()) { return thread_safe_data_.get_closest_start_pose().value(); } - return *search_start_offset_pose; - }(); + if (!decel_pose) { + return boost::optional{}; + } + return decel_pose.value(); + }); + if (!stop_pose) { + return generateFeasibleStopPath(); + } // if stop pose is closer than min_stop_distance, stop as soon as possible - const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, stop_pose); + const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, *stop_pose); const auto min_stop_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); const double eps_vel = 0.01; @@ -1138,27 +1121,27 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const } // slow down for turn signal, insert stop point to stop_pose - decelerateForTurnSignal(stop_pose, reference_path); - stop_pose_ = stop_pose; + decelerateForTurnSignal(*stop_pose, reference_path); + stop_pose_ = *stop_pose; // for debug wall marker // slow down before the search area. - if (search_start_offset_pose) { - decelerateBeforeSearchStart(*search_start_offset_pose, reference_path); - } else { - // if already passed the search start offset pose, set pull_over_velocity to reference_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - pull_over_velocity); - for (auto & p : reference_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(reference_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = - std::min(p.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); - } + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, reference_path); + return reference_path; } + // if already passed the decel pose, set pull_over_velocity to reference_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + pull_over_velocity); + for (auto & p : reference_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(reference_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; + } + p.point.longitudinal_velocity_mps = + std::min(p.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); + } return reference_path; } From 874c55977e2c470feaf66e44251026da656146fa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 14 Nov 2023 14:36:47 +0300 Subject: [PATCH 111/223] ci(labeler): rename simulator to simulation (#5580) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/labeler.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/labeler.yaml b/.github/labeler.yaml index c3efa2a1a2b15..47f8737ebbf39 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -31,7 +31,7 @@ - planning/**/* "component:sensing": - sensing/**/* -"component:simulator": +"component:simulation": - simulator/**/* "component:system": - system/**/* From 2a53348eadf259a302fbac960fabb1464a3df698 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 14 Nov 2023 21:37:23 +0900 Subject: [PATCH 112/223] feat(motion_velocity_smoother): add motion_velocity_smoother's virtual wall such as MRM (#5555) * feat: add motion_velocity_smoother's virtual wall Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/external_velocity_limit_selector_node.cpp | 1 + .../motion_velocity_smoother_node.hpp | 5 +++++ .../src/motion_velocity_smoother_node.cpp | 14 ++++++++++++++ 3 files changed, 20 insertions(+) diff --git a/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp b/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp index 2ba0a4c1d46f3..ccca5e97d2b38 100644 --- a/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp +++ b/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp @@ -46,6 +46,7 @@ VelocityLimit getHardestLimit( // find hardest max velocity if (max_velocity < hardest_max_velocity) { hardest_limit.stamp = limit.second.stamp; + hardest_limit.sender = limit.first; hardest_limit.max_velocity = max_velocity; hardest_max_velocity = max_velocity; } diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp index 347d19f631588..7be91d67cb945 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp @@ -42,6 +42,7 @@ #include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary +#include "visualization_msgs/msg/marker_array.hpp" #include #include @@ -63,6 +64,7 @@ using nav_msgs::msg::Odometry; using tier4_debug_msgs::msg::Float32Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary +using visualization_msgs::msg::MarkerArray; struct Motion { @@ -80,6 +82,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node private: rclcpp::Publisher::SharedPtr pub_trajectory_; + rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_over_stop_velocity_; rclcpp::Subscription::SharedPtr sub_current_odometry_; rclcpp::Subscription::SharedPtr sub_current_acceleration_; @@ -95,6 +98,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node double max_velocity_with_deceleration_; // maximum velocity with deceleration // for external velocity limit double wheelbase_; // wheelbase + double base_link2front_; // base_link to front TrajectoryPoints prev_output_; // previously published trajectory @@ -153,6 +157,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node { double velocity{0.0}; // current external_velocity_limit double dist{0.0}; // distance to set external velocity limit + std::string sender{""}; }; ExternalVelocityLimit external_velocity_limit_; // velocity and distance constraint of external velocity limit diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 6b5da01b9cb09..a27e02c15710f 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -14,6 +14,7 @@ #include "motion_velocity_smoother/motion_velocity_smoother_node.hpp" +#include "motion_utils/marker/marker_helper.hpp" #include "motion_velocity_smoother/smoother/jerk_filtered_smoother.hpp" #include "motion_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp" #include "motion_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp" @@ -41,6 +42,7 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions // set common params const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); wheelbase_ = vehicle_info.wheel_base_m; + base_link2front_ = vehicle_info.max_longitudinal_offset_m; initCommonParam(); over_stop_velocity_warn_thr_ = declare_parameter("over_stop_velocity_warn_thr"); @@ -49,6 +51,7 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions // publishers, subscribers pub_trajectory_ = create_publisher("~/output/trajectory", 1); + pub_virtual_wall_ = create_publisher("~/virtual_wall", 1); pub_velocity_limit_ = create_publisher( "~/output/current_velocity_limit_mps", rclcpp::QoS{1}.transient_local()); pub_dist_to_stopline_ = create_publisher("~/distance_to_stopline", 1); @@ -329,6 +332,9 @@ void MotionVelocitySmootherNode::calcExternalVelocityLimit() return; } + // sender + external_velocity_limit_.sender = external_velocity_limit_ptr_->sender; + // on the first time, apply directly if (prev_output_.empty() || !current_closest_point_from_prev_output_) { external_velocity_limit_.velocity = external_velocity_limit_ptr_->max_velocity; @@ -890,6 +896,14 @@ void MotionVelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & t trajectory_utils::applyMaximumVelocityLimit( *inserted_index, traj.size(), external_velocity_limit_.velocity, traj); + // create virtual wall + if (std::abs(external_velocity_limit_.velocity) < 1e-3) { + const auto virtual_wall_marker = motion_utils::createStopVirtualWallMarker( + traj.at(*inserted_index).pose, external_velocity_limit_.sender, this->now(), 0, + base_link2front_); + pub_virtual_wall_->publish(virtual_wall_marker); + } + RCLCPP_DEBUG( get_logger(), "externalVelocityLimit : limit_vel = %.3f", external_velocity_limit_.velocity); } From 4d79d98488a037b56169c5fa5fd977ddda07d026 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Wed, 15 Nov 2023 09:08:47 +0900 Subject: [PATCH 113/223] feat(localization): add `pose_instability_detector` (#5439) * Added pose_instability_detector Signed-off-by: Shintaro Sakoda * Renamed files Signed-off-by: Shintaro Sakoda * Fixed parameter name Signed-off-by: Shintaro Sakoda * Fixed to launch Signed-off-by: Shintaro Sakoda * Fixed to run normally Signed-off-by: Shintaro Sakoda * Fixed to publish diagnostics Signed-off-by: Shintaro Sakoda * Fixed a variable name Signed-off-by: Shintaro Sakoda * Fixed Copyright Signed-off-by: Shintaro Sakoda * Added test Signed-off-by: Shintaro Sakoda * Added maintainer Signed-off-by: Shintaro Sakoda * Added maintainer Signed-off-by: Shintaro Sakoda * Removed log output Signed-off-by: Shintaro Sakoda * Modified test Signed-off-by: Shintaro Sakoda * Fixed comment Signed-off-by: Shintaro Sakoda * Added a test case Signed-off-by: Shintaro Sakoda * Added set_first_odometry_ Signed-off-by: Shintaro Sakoda * Refactored test Signed-off-by: Shintaro Sakoda * Fixed test Signed-off-by: Shintaro Sakoda * Fixed topic name Signed-off-by: Shintaro Sakoda * Fixed position Signed-off-by: Shintaro Sakoda * Added twist message2 Signed-off-by: Shintaro Sakoda * Fixed launch Signed-off-by: Shintaro Sakoda * Updated README.md Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed as pointed out by clang-tidy Signed-off-by: Shintaro Sakoda * Renamed parameters Signed-off-by: Shintaro Sakoda * Fixed timer Signed-off-by: Shintaro Sakoda * Fixed README.md Signed-off-by: Shintaro Sakoda * Added debug publishers Signed-off-by: Shintaro Sakoda * Fixed parameters Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed tests Signed-off-by: Shintaro Sakoda * Changed the type of ekf_to_odom and add const Signed-off-by: Shintaro Sakoda * Fixed DiagnosticStatus Signed-off-by: Shintaro Sakoda * Changed odometry_data to std::optional Signed-off-by: Shintaro Sakoda * Refactored debug output in pose instability detector Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Remove warning message for negative time difference in PoseInstabilityDetector Signed-off-by: Shintaro Sakoda * Updated rqt_runtime_monitor.png Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_twist_fusion_filter.launch.xml | 8 + launch/tier4_localization_launch/package.xml | 1 + .../pose_instability_detector/CMakeLists.txt | 24 +++ .../pose_instability_detector/README.md | 37 ++++ .../pose_instability_detector.param.yaml | 9 + .../pose_instability_detector.launch.xml | 14 ++ .../media/rqt_runtime_monitor.png | Bin 0 -> 438840 bytes .../media/timeline.drawio.svg | 157 ++++++++++++++++ .../pose_instability_detector/package.xml | 34 ++++ .../pose_instability_detector.schema.json | 75 ++++++++ .../pose_instability_detector/src/main.cpp | 26 +++ .../src/pose_instability_detector.cpp | 176 ++++++++++++++++++ .../src/pose_instability_detector.hpp | 70 +++++++ .../pose_instability_detector/test/test.cpp | 168 +++++++++++++++++ .../test/test_message_helper_node.hpp | 80 ++++++++ 15 files changed, 879 insertions(+) create mode 100644 localization/pose_instability_detector/CMakeLists.txt create mode 100644 localization/pose_instability_detector/README.md create mode 100644 localization/pose_instability_detector/config/pose_instability_detector.param.yaml create mode 100644 localization/pose_instability_detector/launch/pose_instability_detector.launch.xml create mode 100644 localization/pose_instability_detector/media/rqt_runtime_monitor.png create mode 100644 localization/pose_instability_detector/media/timeline.drawio.svg create mode 100644 localization/pose_instability_detector/package.xml create mode 100644 localization/pose_instability_detector/schema/pose_instability_detector.schema.json create mode 100644 localization/pose_instability_detector/src/main.cpp create mode 100644 localization/pose_instability_detector/src/pose_instability_detector.cpp create mode 100644 localization/pose_instability_detector/src/pose_instability_detector.hpp create mode 100644 localization/pose_instability_detector/test/test.cpp create mode 100644 localization/pose_instability_detector/test/test_message_helper_node.hpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index 59fd5174fa38c..23a1201a84958 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -33,4 +33,12 @@ + + + + + + + + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 1126914d58c5a..c4de9c04dcaf2 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -25,6 +25,7 @@ ndt_scan_matcher pointcloud_preprocessor pose_initializer + pose_instability_detector topic_tools yabloc_common yabloc_image_processing diff --git a/localization/pose_instability_detector/CMakeLists.txt b/localization/pose_instability_detector/CMakeLists.txt new file mode 100644 index 0000000000000..5270df636d791 --- /dev/null +++ b/localization/pose_instability_detector/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 3.14) +project(pose_instability_detector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(pose_instability_detector + src/main.cpp + src/pose_instability_detector.cpp +) + +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_pose_instability_detector + test/test.cpp + src/pose_instability_detector.cpp + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/pose_instability_detector/README.md b/localization/pose_instability_detector/README.md new file mode 100644 index 0000000000000..89cf6ca3be684 --- /dev/null +++ b/localization/pose_instability_detector/README.md @@ -0,0 +1,37 @@ +# pose_instability_detector + +The `pose_instability_detector` package includes a node designed to monitor the stability of `/localization/kinematic_state`, which is an output topic of the Extended Kalman Filter (EKF). + +This node triggers periodic timer callbacks to compare two poses: + +- The pose obtained by integrating the twist values from the last received message on `/localization/kinematic_state` over a duration specified by `interval_sec`. +- The latest pose from `/localization/kinematic_state`. + +The results of this comparison are then output to the `/diagnostics` topic. + +If this node outputs WARN messages to `/diagnostics`, it means that the EKF output is significantly different from the integrated twist values. +This discrepancy suggests that there may be an issue with either the estimated pose or the input twist. + +The following diagram provides an overview of what the timeline of this process looks like: + +![timeline](./media/timeline.drawio.svg) + +## Parameters + +{{ json_to_markdown("localization/pose_instability_detector/schema/pose_instability_detector.schema.json") }} + +## Input + +| Name | Type | Description | +| ------------------ | ---------------------------------------------- | --------------------- | +| `~/input/odometry` | nav_msgs::msg::Odometry | Pose estimated by EKF | +| `~/input/twist` | geometry_msgs::msg::TwistWithCovarianceStamped | Twist | + +## Output + +| Name | Type | Description | +| ------------------- | ------------------------------------- | ----------- | +| `~/debug/diff_pose` | geometry_msgs::msg::PoseStamped | diff_pose | +| `/diagnostics` | diagnostic_msgs::msg::DiagnosticArray | Diagnostics | + +![rqt_runtime_monitor](./media/rqt_runtime_monitor.png) diff --git a/localization/pose_instability_detector/config/pose_instability_detector.param.yaml b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml new file mode 100644 index 0000000000000..29a25849d6b1c --- /dev/null +++ b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + interval_sec: 1.0 # [sec] + threshold_diff_position_x: 1.0 # [m] + threshold_diff_position_y: 1.0 # [m] + threshold_diff_position_z: 1.0 # [m] + threshold_diff_angle_x: 1.0 # [rad] + threshold_diff_angle_y: 1.0 # [rad] + threshold_diff_angle_z: 1.0 # [rad] diff --git a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml new file mode 100644 index 0000000000000..4a390ee2854d7 --- /dev/null +++ b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/localization/pose_instability_detector/media/rqt_runtime_monitor.png b/localization/pose_instability_detector/media/rqt_runtime_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..b3ad402e48ba7a154489ba02935817e050a39f62 GIT binary patch literal 438840 zcmX_n1yCG8w>9nrCmY<|o#5{75^Ry+?(Qra+}+)MaSJ54J6VDg-1X`oYtDUZW1mQrf$}b z4rH3v_7)$FP*5Cf9GrWdE$r<3IZ}>m)A)K6hQ4w4m2jxlsfI5p%P-IYY zl46=(Ij6baIfh!9_kGj+_ghtUXC=*vxm4yD!I*6g^%Dfh)u{0lQ5}d1P{mT_$@Ejv9jTI{1cITDgCSQ*Lx!8LDm6$J$V2*ox!v$QmNJuNalQz((hY|vKW zN%A+)yY#_cK6*cVkSN%xYn)nRb{<-jUcqW<*oS; zRDL-G-?RGm^2D>3^*UgY%VEc|1AxcpwLQvOprWY7YMuGn*v7sRk{UAf?Lhcg+_1}PQL~biF-KGkwh8Htz45{Ukx=JzB zm2~KE8K3wYnW8D= zOR+CdAT_~RGuT*P1qA5Rf4SQNDJeqk^XQ_#+t?JT(t+*HHjRx5`x3v|cSj|ACD>Nz z!4I*Obar;G11Q9CrHADdTlFWUOqBl@Q`z}ca^D>t&-e3ck=vy`=~WYQ8B^u!<=~16 z=yG#&H7D?JYZDA&ma8Y1>7G7%A2Dlu+aQT_&@~_$YiV!yB&@gGv?bcsH&8*MPn8D% zjcB-PTfu@T?6kDygdt=$vi4W2h=^q0UlH9B#tWuG*B zO_w=M7JyD(jTL~f8^>Z2Ol)K)Gf^~?89Ub!Vex;?lNWD8e`&ClgvA%XrdV@`ad`O9!2EW z-A_1NBZsIZ6jUro*Ain$Av<9gni1S>Y_(OJddzO#r6OW!+O??&QLyBuLp5|0e}kWW zYCP{{hA9G=p|LB&h&H)0RMfjWK5H+yeWRUwb)Wm!zS*wfv2L^Zul1-4on_MqE!tjJ zMR}@vx2L?hxtV3c2px#FXp=fMHMPtWTmn;T$Wr{hT{6z5bxkRVnA?>6bpF8FX0o^Hh5K|@)X zjcK|#lH>clUU;!OH76!-uFaXvUd+$vM6%=;-#4Z(`riE=-p2Kd zh_FX8pxE(8tRQM?aEV;9`jTpK*0=^{a{@}YdHn>#x@P(I*(ghZ92zfN_Gr8jFEO?# zEbwK;y>4R^AV-BQ7+&x@At%Wjj!xiFH5xH@(p4P?rysiLeZWpaK}rIr;jfIQf_zM5jb=Q;wNJe4Hb2&H248&{hx13F@qrN8Jg8! zLUmzDYV`X}LT)+;lLKZ^qAhtTN51%m&q9sALOKg|G{qpBq}I{l zp~-5K#m&hwhONC&Km-1+ZadNw7Ykco>cqG=y6mR%pGFAgIrPYSkS>hbIeS)g!mu|O z&I^rro!9x7l8EKw#3I!wBvwp3CYl1Gipv_}%)UfR7ESrehBUlu2hAv-JUNO>{UhuL z0Gvd}hdkH#EmOd;JGJ|)H?plMDFfR^Vl?*47L>O#GS;0)%iho$iD2VB*TqLrg)e^Q?MB2EB9c1FLG0SjV(o!HShOL4vY!rYo zbgfw^k_xmHg`K9k$-5Yl`(L$|JL|nhnR3@_6-TqNDV{18QEG92yhVlrJ~&$ZVUq<7 zq&cX=h8eg~h?Lr{+U`oS4IAIr_Syr)<@e9Vop%C;o|}PAo6Ehw+v{JyqUwM%qH)~$ z#NiScsM<23=`W*VK!Z@JKdMv`>gyd2(g*{8&Z|rpb0Ro0i2+<5$RpW2ZjfNIOT~v(7Q+_A?_A6FzN+%XpKQM?13G-I(`QR+xx+Y<;i3jHiQWxFHqYr zXMtDi&!h!4pP~kIpk*6|)kTL3oZ)9P=orXosMKOKkV1cec4;}B2ZK{!rfWssNH|Hn z*#xF3hV^Ht7LT{EeFq3f6yQ&QvS$6*wow`}(=`LV9@jw>Mi&fGD>r^OT3{b+CS(&k z@f{CSumtiY?!~a6fE9k9xsA|}GW3qPbdt7z8o%MrtiFze? z4UO+0YPaL8%zcX8^UN@bs!%3@Zz#l`IwoV(s;X-uY`IjR?3Yn$uqSi4mhA=?$Z~prc zC6WK%Kf2>gL@>eVKdyM{`u@l$<_qOFwHrF!$^Fh0O3p14S@wGa3SLESyDS$^Uw6Jg zv-|M!J9M1&>4J}`Cu}lZ78(tGM(}R12fhzh;W2hXU`Z`r4#^E&7t1sIOt7W}+rxIJ zzJ?+Oz9Q!3T+(HGw6WX0lcNy`hFRr#$G<+I@ARYx{s^T}qKaMjx=8%8;qiQKy{`2q zWxm|ykJN!06QCwTQvw9Rp^g%GoK1L-IZ|OQ>gfqBlt7#h6b;;;_Kq-ujl4R;c%_Vt zC5@o6An`lI3h*B5adXq=e?G0u30PV`#2Gbw&wn4tp{`zOtd09qjPaM0XIdV|^MdyRa=*u4I&&N9ip&j}n@;x$1_MBPjmk9slN{8JmrV`tox1hT#{*9e zt1YvLdv?E<{P)D&=>XdE?j6m#w^7d({Lc?h>2Kk*Wg>%)0gr@6D@}1`m9z(n0{QdG zBB@CUYC3y&>w&+{&$^P^jW6(7a(oC9gm^+>Kdp|WB$t0Irtz;0@9RUwof)~v`Pr?} zXf4Js{5FE5@27n;<$84O_J5|jN&eP}yd)Ns(jI`Xg}}EZKx9MlgZO`#I$jqlfsjLB zf{AQL%$Go)peoOrP4Jgy++Uaae3~P4?Fg~Y0EzY*{PoIOy_{6Oj zGT+(5Zs+0V=lQ;w;hfd!hO)V2*LdQXOLi5(H#(KyS-&o2hzG}nAB@iW-pSvbrb#PD zb2S@OZ`2mQI(63YAh+NQ9uL+>C_K$iR1IlUVnkD=PrY`kJzK| zCN?UlF#AVsXK=Yv_UI(<_V4q+_vfdtQ(sSNo_Llyf<0AKE0MnsdtA)?=C?bMUFid0N5F5nTp4^3 zu!N(;03>z+3F~B(uuIlPH~3XJ-ToF5c|4fYp#2*d z`5rEC4rjYRC%heroe>HpqHb|~8J;UwAypQ!C3wa-4sQJ9jyyspDyz#8C~PEDt|Ame zOX3$qEbx`z{@D9>UI44-#-s13a?bCj&V{-y0-mCMt@_2G6suNtmpDWTCH z0IaeGkDRdNXj0l_brioW@>^s`={1MFBncWUj4 z_VtNDz+ezoF`u0mbYq&tr_A9*86`_d2RYnQkXMd2DEU(wv)*rLN*PYGQ(cm-10w`< z!jUiKxuZ9T=ldTo8*^{u#&iFAr?c_a&za-A^u=zoDcJb+>eD9xPna`ow3~+}pVJ0( z%}Q750X~z(pM7f0uh>5AJoB?^(!cCqUdFZ$61@re_Lvx>j>b-?VTio*K&oN`=4mZQIz5cK< z=}dbUz^#dl#LzD*oRFt;|MW$JR8*F%(U-?xdN(f|Ra3iK>`NT~LaqUPH&7^QL707m ziIb1Mh=b18{knftuRhenW++aay(xI2pHLDcSl*{74RkJE4+%R#uKd-nuTDeIdS9QRjI;iuREuT z&?OwS1%q=x#DbB3C|@z9(*QnU7EpZ@seckwnB%{14Q_BF$v*n!Jzv&ndi`m?#z;jC zh|lDgr#%0gI{n*dKsbj&zHib&IumeNE;7jrz~zQ}pePiY&I2B?0LFQwBfRm2P?1y*k`$4Vp+vMj(V~+5x zp*E9Wj>WI^`BkiDr#G0k_V&xM$T!JDLE_xOG-lgMG{DqUJcCRQA84=(UC?bi*KWNf zj*^yidddDo7i>?v-sS*V4Zr^K^$Cup>w&n#p7nBd+HmB0niV+spawwZyZH(H!VSh? z{46+nt$?q=zvq<0&gUowS3Xnzt~&Mg+D(6hCg9=1v9VN}rRy)Y&$!3_WKVQzOuDMD z0|y+ubgWQR^Hfie*@kkIL=s0#o`3ZD`>D>UEJZ{dVC=K-^E6!6*TA@tcKA;scW}yr zZcN$fQ|99#)HzOn5c%(OcGUtge(?xK()I(L%`#jzK(QqJA#`;!LZ-bq-%Islu0CjMu@14u8Z`C3LhVTPfGOY>? z63kimx$xF~@BJdYmC}yB?R^Gja!h|tj*f&nZ4n({lEWD*r=8D{t|GD|X;hqAIIdlt zya8IR1VA~w$RMsiA_S@qqp3J3Ec=pINhjM-A&Lnonko24tXbupC6`rdTXA0ijf~$Y z&VE6)$3QY(!;CD4z03U@8yS~UkE8;+o_vZh+Vsch!s-t*a}D<6d9!jc6TYJqoYlaY zfMHWopWAhe>gY-<7Ze&-YXL0m@P3rS*5O8IcU%cE#jIHaI~xiv@zxD7Caol!R9W%{ zp14&?GBh-$aHy8F(?rWAA80~4X#wX&idcrTbEWG#f-V ziBCz|D;)FtIAk6Sm-E=h$?pJx>V3`UZTvn9GsXAMD<`rasctUQvdoe+H%Skm#e|I; zg#taL6Q$K?nn8m`t%ZgFgfUY}_D91nj`)d>1^Usij)upMiAxcyrHHuze`a=7 zPAk}_zauCPX%Oj>#g-dy0mseWWWG&%ORY|uo*)5m(Hp%SCf^!+Z+=h~qy&_*H$lc8 z>CTwZM=7;L_(US>YFO|d@Y(xc!usc4;hU-*u6j|$Zj2i&V&WCH;)NQNrE8YW; zZ39xqVfWbhjuQAlDe`jWe#4~K)}qDd1L4ccMp^Z;ZVLZlSqo~n-giyoYc_t@zOa9} zvJ$cQIa8=8@M<1$$Lw;V;%M>|Wy+M<9yXqwQ2HLwGZ54meXWK4xdhbWmfE}84Ad2c z6(rZjM)1(&>>*2rkCNDS)E_4f#f9 z++3!C$m zDO1NYc^Z>$|9-%0qB=%AzY9z+P$0D`vH_G>Jm&Pw&y~yF24})Xg*jGQ49qf^MP0Nc{o{}yA8f_q?E1Rna+L53 zPr=U&5Kia)QK{kkKU-^_hRrWDidl*p-<|cvxP$qazX9zT%w!Y=bEcI9DU$t?(%vgm zE0FBcT&cWnPkFuQBqGswK}Q$^cd5UP!Po~VUgA$T|C9zsU-r`szPR>G?b+cNAj8xy~O7b=0&NkNoaXr3-pxq3)WSU0P zAq0=J4ZZ0zVjepHEaInAOZb}3Y(fPvS5r4?`yG~Ltm$b-V~*g1xxT)>)0Feu<3aOB z!rj3g#&+rFn(z^g=sV)QxAIhWS{Cn$cOem@SfMB#a&SUpxc1iT8zbN8PYJ!I3;s6y z)sSd%a3D!jc&rhq+wSy{ihM!v(^F=vO?aALak!9v z&`}Ml(&5tMiVu%un4yZ{s$s~{;xCE5Dj$g=8 zf=9BW#2aZ7)xeEmrPxY^J5+Eu>ivI&h};g%x88&A)wbH=v>17=?qce9ims;zBM{h+ z2y&3g?TR|-Wm8j-kx;P0$#%kaRd#MTm8}-%MwoOv!YZtcx84&m=9@Lmw>H9wJQnEv z?&e7gHKC}AOy;pU@}R72LfWsc_Zd- zKnm%CvMaIFvpt<_S{T&3zD`O=W8xs8qA1Bj%C(@}Nyj<{03EeQL>5-u)A zaSmrY48ib9FxZ5DYQsB1sFgVtN16^Z#~#{k>knS@dm?aX6UroMA>@gcW__U_ZXxw7<%XyWf_eIzowAI*lPXm z@M4lD8yJzZW<>4K0AWn)J`b17*FqlA&E%2mBl117EFX3=EPw|J7o6j<>vAkhLm z3c)QxY+E@nr78x^uzU!4p^d(1_{zU+uJvkHc_L6r)B8R~t8vR1REN)@V_gixWmVUUbD!)z~UUV^~xI zyBD|~TbKOGe&eb7xpP+qwd1UNc}71P+3!n!SQM@tEUwvIE1%a#?P>Jyr{v9-5xL)W z-@1<>)ifnZRF$YhqwyrIB!j+;EIqz3a<$6FwIa@OPhXq<{uqUsHU%sR_?%918W>n9 z@hwG*@LIl~RgRked*9!;ETTJZOIvgGRy6sjz|78+3@C`6&cn2S525Sg;LAyPI2{DmyL)i#y;?& z-=rfoX5j;AL>05>U?Tt+!J-i7ObgY;lJHP+Jen=j5i3_D`4oLje>|1UDS1NP*FztV zHmx8ewNMS2QvJGi8yH!t9f|x`im_Y5=mbyl(OpG20NT;FcG{nJ`9smaus!Cc7^{%A z#i$iGck9rQw$?S-K(zKVxR558T8fZ)O{6dNeA%PJg(1A~XmV*`loiOAHc%=BM^)gm zGq0fjl0PW&K88eO!nMl>i$P(T%JN83Yz#+oRN`cH!jU7TMM{G=&Uj!9RXhC+13!Jq z4TD&QC7t;dRd%mIMIsvATRIk;z|H4iw?vPx&e%JPz}76Gnke*nRgp%3T8%b4RVF4g znY6lTP2L7(Ml&rzGA;P2OV`H6rfT`Ot=qxZgRV}CA-0-y?~iJ7kOQ@DR(7_vqhtLt zlwIuDx=?4aF4NM%iiZE-=7CKtagBCW{hBLZG(}D8t@xa;yy!Ud|8Vu-mM9m3j?^;c z2cP9;#Wko_A6IKNqt;43&MLsI*Jm8Kq}#tpn5{?mP4Kk%?(EQ?Sgj3em|m%T1GQ^s zGJZda39+!%@*d8meX~)M6Ywoz2BUSi^HUmBTHb**G4;7@d1-osq7mi#%zJdivuS*( zGTdq@eo$qQ4f;}3{6i~3P@FtXb}z(S)LbF6PPChpG+ZJtRglV+-7 zbNIf(wm7tMZI;PKsOqlwOTBhBz;oqg?s>fLJI%kHLTyCJ*pJbX;dA8Jq}d_!9ct)v zD{69gP5}omJ+6L&-ef9QFB!S90tv0RlL}TvkD;+FA z#cxn&4ssiW$MZYUSz2@aGD%do+FsmZ->Lrn#El^Ts6`uWLmYN3R%bhrevhxxHZ5rv z>E)RGLv3#K(5S`kSvr|VmaiQ#R2p9Ftx9F`jakbru+E^x%RbVnn1(YWP|*Dx+{#z& zv%PdGQTtYEWN>gMJG8s{ne7KY`k@O16m)N`AUH`?A8l^Nf~Q&3`oK!i#*A*lgYwNH zE46L`tvOQ5y;jC{y=>0npIYU4>!yeJ6HBUF&u!`{4U6rZrwa8KO|0?ZWH(UJXwO1x z{oJe~PuUV_y2En;KJ4;$ta+xkt3ASPe;O$Q>9D#+!uv#zZF_WW-toJ^U(31CHEU_s z?f#1&wD8>)qIZWVrtDu@}~n@(COF2-(Ryn zX!)i!t`m1*yKh|2=C>+QUemjS-^;qbGrq>G2%9Sd#f=Vs&Q8{F;?hQ?f0-ArchWf6 zrj6-)a5TtZ>1Ol(PfqK9;mBYE^AjM^s$Wa%ydYUvg&kq~dMlT7s`mZgiQf!09N}g= zw==%Z?u}887~I+0n^4^5;gmg5x3-VvJqKId*`5$h*aAnS>wiTe*Oumb3~qxa-r(vCCd?pEL77{_aVD(CH*oX7aVAsqs0*wJim0d5jK& zT{rF3$-#O0vP<5n933|bT`i&!SQu-CoBS3kaa6Ui2f3|lL>+DFyz}bu?0hph+%ZAB zFQWByQXcS9%32^Y_B$*2x_!9UNaK+^F?oKZ+CuJ3IpFo>wW z?5@_?&h2h%n*Mrr>B}s2t>3G0w-Blu3$E%%=doLPxEh(OFgK=e@Z0vL^mxk-2mAiY z4)qs`f4u#XJTDdS`WI~E;pu&b6X%#H^8T_`-f5xI)EKiVwbN_K+-JwUnmB#HPa3n-o$k z!|^;xE}0h|N-5ML+&T6j*&w0VVsd27-hVoL5z?r>ZEu&1*Khm|uZX#mLwOf{4UI=y z1QQHhO^gc*U$09D>9M6lcuyzy+6P&!v{+LLc=SZMA}?{N*`1C5m3ZcS2|{Z5QvE9C zgY)kAbK$?E>VsLTH5iL07BE`+RL6eZp-Q)tvm2xaq=O^xu1ce|5*a&o&!(fzt(ZJ(ry z0fnU!!=@!MJp-m~B|@9_95b=5Cbg!m3T2pBA2fD4K6=Y@S2tVORvoRHZ@2y}vs$@R z)DLd8X3cN8)`rCcf2jIF<4?Y4g^fu(EsjZ92V3T~NkkxBO~oau9^2eFVlhG;xutyt z8;OJeo2ki0?|GUCG~yf|naW$MbfzI*dsl$2gs%)DA&;ZwPJ?!U)9&;a{x>p&*o=O# zw@L%>fG6V9m+`2^NT=>3}1tb#9c=nHztTen{ZoS2_3?tjPyip8x3&kzr=<*;Qrfq{;g&_ac60D4E_=15 z7#%(PI|DwlDwBATNodP*v5r)%33aW;E_MQSe}#IAvZc^H6RShQ(Rz8R<@{7lX2M0G ziqQ}RKvRipsh%zQ{Zkt+3voW}^$|6=*5+2yJSsWsEw9yIrywnqBeI}tn zE(sp`F7AEevt+*|x8R9cr4@@6tE(xbj0a>6ZtUP2h&F*$sQCmGhuP^i?u&k8t+7}b zmizs%`+7sj7gSLRMF%PmFo{K1J)gHDr38e{M07lDhKQADa~uTj|NXCYDpXbXdeG+S z_DHO=D`t<;*yJ^0(r$fA+KRhS*Jc1I>N<+uZdLEkz!#PIVoz2cyXuQWVDsY`MsIF= zo*U8L9moB^=E7DPMt|Si{ssenz@$%#Lb{g*dr42L26RHR-}H+EJv_*9}~qOV6Lv28fqcmUyjr_qFsd>Req+iExyCII5-E)`iKjC8mt zPOLT=R4QhvCwEf|9NV4f~pmjt#(T@0ey0#@3Gn@Uk1R;>DdFEOv{ zwtZ*0-*%;)X3-yi043Ami`TF-89!n(8m$cOz>d0}u%27?7tEg8tPfP}G4cf-BiHyl z;{86%BN3ib_6n| z93kap=i*hh!+W3N1@{ztFC5<|+Iz3y5$=OXx7=`4Sak=xw_i!x{%t^Cvh==$t6V!8 zKM}CVJ^b;k+nX7RHyi#5%Xc1ftp_&a9>%NixOz+oOu`C9ye_S-GaWhRei`GfFI{T` z$(;2hE3NwC#v_Rad3!I> zzZym*({VccEcJDymADG@y*<{tX$ndct4#Z4_@4O(<>JxNnj~?2XhJe}l?8(-KZ)d! zz8=zgVVN246D|j&4wVy)9?lkbJp4O1nN2FygdHM1>r2n%B!yL4X>rCGBXMO){*?Dy zf|Eo7!XffBaL;#90Ly>f($02WSw4X4ZF(vA_DAU4^x*-N8(uiMG@{fdixZ1P9Ns8_ zFY`=hpD$mUS~s3|{FWS7!r8@L6>vZpD|7hG4)aSraDB*`<8-x0~B0@AtzuTjtZ50M$lK=LqU#b8)R@qJdk zpXX5jLIjbR<}jAn`SU3AYr+6rYwIDNwam5gkPnN}b{Xm#q;dLA5v{G`IJ``gI*sq8WApG9f|{K6-FhEdPabv-`i4Dw z-MRZZZ!H5{h7yi6y&$UxofpLCyJrFpRueykHy(EL8-%Q-lf#CQ@vMtH-=R0Wm(M%S zdjrM|1fb4eBj@$NcFd@0_9Y9|7>hQ9sZ+$hnd+hvlH{r~1Kv?M!;)0kvvRT_ zQe5unG2wJU)YFrt@6fv$S84Nf(o%yJ!x?H4{I3t7jfdv5P3d&eUj^P0zsL zAhBoHQ+7u&oP+`Of4K6K%#tHW=L|1z2O|3r)TzDPbpI6Ma53%87eb9@H`IuA*Oe=69sgK$Na){Z6tRU~Wc>qqm|q)R3INb*6*O#aWU zP43Suenq+mNNa6pWx5X!|v$Qf`k(|7!}jb#R^#D*!B%FNOi zmWhkqe53~HlvvbC>Dh3p3kf{c<;*^PJv8Zcn$%G{N3shRKQSp{B9y+g+uWL(xh&?l zTI1^V+-3HA73m!*7rsRHX~jkM$J22i1{JH)B~tAO;l_NB)=}E{pVHPGF`^o?m{0_a zWqC7y*r}|o@TlS#YesR4?IsZhMWYxk%s%7zQp-UR1+(*|TZ-A{;U)cVNPo>MzNCjf zX?Cj~Y`JiK^OAaVI3H;=iG^UXGV`j(=ZHm1>`T}8Iuwcw2$@_4r;%^1N+${C&=4)X#Q2`?|CD7?+#eWe~UMjntnDE-~ei%r1gO z8zuX;dUQE_X-BjU5iW^th#B0XFg80A+nDFO7qP#E)9E_adwZ&hVLXN@& zQl~48aq8rgDQZB_w{Uv{4|TfR;+eIC>AJhXkfY zauLtonWvfcf5whkHknNl&=5P*(Zn_&posa1YC!+r-i7OSapp%JXQ(ur*0@&II`hXl zsSW3K*2i&HlARn>)>4&ba!~-k9bal2^NpQ$d=6JI_C#zAsm}(qu zmk%$$y`l=f-q@wF=>1gUeb16&^t>8RFj6jIM@AmlO_(&7zokQ|1Bt?Xoe=PLTPpr2 z8iqOV$`lV*aEYaq3TMOYj>heQE6XneMee-=-m}*qF2>$LtVY-Fy>0%eN|Vfnca1SW z$V}4pW9xT5`~W|$%xa6vv4QeI?{q+7rPbyH^?7GhvNAu`E>JM7Dk7{`oDPAVT+VQm zps+|>3T_uY`IA7-yXRu6;p3uXQ^3%th%=F_le%}|(!x;k>h)&e*ry^h94%6(iOkO~ z!{Z0Db93Tg{{E=BURTCQ5`T{L9$QqM*I$v=j`eK+{+<5`)$v2BW)D`X^)`zcR)@i= zp_?iL(F;XGYi#qRvKqVMf&Pu?)IBkrKkh`XxP1t4A1%&{OH0EO{GYCg__|1Amf!(8 zblQw<$PFz3~n$Z=iT)CTr5r6|9}ki_8VoIus7g)uaz;a07Ety5YodFC$nX_mB*$uG?nh}$YI7AW@ zbtxCZdMEwLA`ZJHRe(&+E-eINE;xoRw8@HkVWA-USB97PDb^FP9fE~e2MZKjtoY)N zTv%;34DpAyLgB*!g2&{=Aro+OsOMseIoenFNVR53pBQjKN+1|53i@KB$}CH4m{?8B zWjVUZVTKASF6+!_uH+SLslMbY=mQ}o{Si6Y5t%6aBD&m;5;UHIV^~e%LT$PvRdjvl zHsoZtQ#B;{GyJJ>@1dFHnQQf?r1Sdp7yST#a2jy&XYc8G-(sWM-O&c_Uv%5E+X#mP zW1$JuYHih856m!fvurHNVGt~iN$t+JRMoJyTmb-w7n_j&b8{)v%W>QGeBXP(N1PaB zMql8sGnn*v&1do;tIYrAB>t7Ho>NE^`rKY0sK)@;D{q2k!Ab|ug;deSpai3h0|U$9 zyJT0Z$)H)yzUUIp#$+-C6JEB!Y%9f%^26g%R=}9fsELKhYk_tr1!}F zp)8j_mVl{Xw0z5+TESj>0S+Ko^rHeEr+nZCf%hwpFfTQ%H0c zygY>9BQ%m!v)z=^Y#NL`>M$y)tCM0Dj(O+I+MymcZ8+w*w$tC8wrcf-s^P8R1DEU> zt5)7)&e}}_+*$j0N|!9Z($XHp_1o%?_c`|U-W)I5Ce-V-*?rl1ZXxS=$;=;pY<=lk z)gkX?eKyeGzFiyJ`i%7;ozRm2Ry+7Z*qIynN++joad1bhxl2`R#q`O^y4DzdZXZ+o zI}84Yf2OHD{EVqX%v!VF|CF1XvYWBROdWA&UmBR7rZ+mC?VdA ztz4$`a27WST~IBnLXj^*ra(wg`TP&wR9l&)A_lS5@+^BL*Y|K#NJhLU9;UU6j8k@W9GpLuM-F@MK73MI+nEn217 z19O{NzdO+reSF-TQcWv~%5=6!3XN3QFQGnDz>|eG-_PasHtyWN7Tno;@#eX*?B7wJ zR@tYuC0lJiWh-@I)L2$6A#-PN2kbi9U7IYwgh9yp;er1PMHtbD{aBqd{X^B+vfLM6bkD>HY;7EQce9o9A_f45K9_*?_&{yrL-TebfsGHMh|^F0&k=lp7p zUSDl{c6K3N ztk#RC1HerVDzUArw4OaHlIMKR17PNtoh_k9W!MQPJW$!|S#b|SvF{hv?caN`0y8}IFn>9`Zp-RKh|+RwZ<*IuRcfZ75RkSG|6Z(W+!g$Uw4E}h+*ncJk@zMjZpQkTyfeUD(H;O?Hy%vJhn!D~%bb%+as zEZGbQQ|vV(*p=^FWG8gVKyd4c?&I)07h2}UuC-7di~m%Uu-!o=YmM1qomgn0vxLS3z6 zw|1@N!oO(2k-|j-oF=cJ+(ge_Cz>D|&&cWK#%u4g=>5$6lUqYmTKhuc(B2fKTOG`AC@Z0-Y$h-dWzj3r6J<{Cl9Rq2)_bfk=_f_ zAyO2iZdkLb$Kt5Q@0^I$SA>TzR;^{421SlIkOcQsC^n^qSr~0${=}znDO|_Rh@ayF zzkdaT1vNcb;MYCWZ!gsFRrx%4JqBGl~<=zE2QA?tl3>Z$5#)dD4EEyBD&0NT9~9084wlTB?-uhGickPkTg0A z2-pH=-DU^Ul+(dwng1Dt2S2~*ERjXdzmUjC8jw5Ji^9L*VXD~xu-sQ#)w%gWYXe`Q zBUWvSA#f@?*Zerb6$yod}yeU0sYWxx7! zo^at2F@Lvh2Ctc6fO+@5fPThYS7N_`QpYM9deTV-VPJ8hU$poPlVn9I|h+z3AiYP~!#*72SEWdz>*G4-uGQ&Ixbn6_n0{}OOH>MwU)C)hZJBjYwX zzbc2EO|)2Rqap(i4}*R!VLB5<5^3!#tl<9=K2+E=b7~2k$&jtIyQUknRA|S>P(3@t zwg}um9ZkcXZggxXVn#ln#!9OXd-ZMR&$5~;l6rLlCB7;SLEYKEhv#;C%yvF|dnv+} zA}g9UW+$TEPne3RV4}=(Jsg$aayf3LJUr-5;4MqZ#SQH~+ZGw`fn#p3u*+2#y#|a! zfe1*mA~1Tta51P~e14HJ z=qQ&hTH8OKMV8VDAy6|z_F(Af_ixjU%dDFEDL9En{4p2?PArCAJx#(uRWEy21P5CTNy|`lG(Pt)JX*}rVh$g2;&aK( z^%){*)AvgoTh_Nws_CK!8itgiW#iwLTaeb2FnNIcIo;O#Lv_^PzGu`W%Jr3A(;*@n z{gCID$NZ$<^JY5$t8-BVW{_t}hF;rWBt08(Tb2!zsU4AM+~_Yaju^6l$3IIQ={908 z-|_y16+E0?ixWAi@_UsgMrN7$zvI@NwJR=`gQ)t+#dEmD5fXkZZ1ks1W+>w$fMPp4>@YUZq^Jer#pEx?WLX+uz# z!i7uFm?gc`i>9ECXlka>6Cm_5vI>6QvRkrWi>0R)pT`{hyT5*Je%ZAsc(v2xWo8Bl zSeE@@!2KEIIv2+&2mC*Df))g2=`Ueit$L@IQSq;zp3ga->aqcBhthXM4B`ycy^!L^ z)0N&x9(!eppV$G0Yzb>|*~vdr!ab>`RfgZ_scFvdRt@N^#<{dCHi$g^W5Q)NAxxlP-Z{ zm~8(K$v`&0Y-UM7_wL=PQ>U&SbG9^9F5Ql@*RB3J_Ls=`mH$5SIM<`cJo;LBZv)Cy zwqvBEMy=ZP=+Ogoy_7OHx;zn8FGzx+qdfn@3(TLt!tPgv9TNm6;-#g&4G}8wV+2dL zLkNxZ^mMMd`WoVsk}SqrS+;6*>(!@6uU@!)J|;c$4Bve_4?~&9zK4pm_1OI|`l>az zic3P)6jJ6feWrlr%a-uq*fA6Z{88gl-a3mK3jrvD+`~H=H}*mH98u-2212?X$lOqLJ59qI8{{c7r%QsGes-jG2c7$h;h zO4w%4nt(dV^;ku=WabC&@!8ykC)>$242&TWOpI6r%&h0`Aa!;G?&yGjTka~1gABxftNyd zZQQ_fliz07fy12B`yvJmxQYaIly_dA%J<7QkXKMd-R5l>b?@C&i<3Z*Lx*;A^T6w< zT)zn~JvENEo_~yn?Rs(1h28KWK}k%*L=zes5>=AT8?U~>oQ12XQM)0-N8CZ}TIuL! z5gXTU;Dwjo;>giFF6!5xE3UYZ$q$cV+42>n)~?TO!|&#_MlOV=P|`$~#T?kX7k8zG z9NxQwaSx1P@4+kt3U}o?y#B^3tY18f*Is)YlXxz<{3K7xwN$dc6j` z^70h+?%PMrW{uH-JzLf=Y4TJu4rOtEpFUhQ=o-8#z=AJk@XpNnWFI|B)hg-Sa@W0_ z-n=TaKmM4lnL5L7>Q9VI2VoG(*~deVO=R_!10*K+xVYZ{&hOiU1QEoalgYEsOk~ZL zT{LOcfuTchBR$zm#+Hpd`P3x#9?9q2o)>f5O;_U)1-$;oyUhD$9@XkJX7HVN)1+29 z9%oO{?ciiOnEotw?%6{?Db{{BhgaTwkAvAoG^ksP;iK-SLG4ru5AWjfr(a{k*1a@o zQlE#%U585rm^|@uX3lt#%dhFrm6u<_bC2E6s-M=A-k>?R+%b}t^<(kqCL32SV9-^| zQ7$*v-*g)tI-h|I2HCo9EdgoAyj51JEG<~VFWY`0Bo%}TnKEe-(?9u$^SX8A;E^DM z2j5PMhN%RO>}S-NhZu7IcpBEOfy;h3i9*N#7y+id@)qBI{~gI`)i{__1iB6~#EM1V z^U7QA;5TErZtxJgc5RJNe)jCx&c%KEQlnl|UU~5aj_g{`%dfw~rX2_9*0VPQukTNs zE-A_0&vTQfv2^Wb>eNc-{-Kv6OA5I4>dUDVukr9B_i<{oMtu1GyL|T9m(;A+f?I|T zr)m8(c5Gh7YcIdb#vS`PwM|#XKR6nfvdt1u$2Cj%H{!T9f#t!vBjPP|X3w4+_<9cU z3iKaWfVAS^NvWYwgrtGb>)~K1M2jw+QCOb9mKB7KrpMB>c}to#Z%p2Rz6`j2951~5 zKDC4kDJ_c!sU+Wh@-eTxG?g*WOeVf0lSf{fZneSou2Fz#1{pY@Kiw|7npgoP_^44W z700aErR!)y5by^znMK&SLH+z5;kgIJ%}W&%a|9A5=0P=S98 ze#?AAAkf0W-3>ziJU)2qeR7Kxk3RMk7x(T$912trL@`sRyv&GEkCU2Sg(Ck?%=q|I zX3hDAN`+f^@!6?RqdG2K@#W{Al2|#7S}7^aoxhm4)EW%$-C1w3@e1+ol+KtSa`IME% z9f<)1LYBJZ@WDf*=Zh~GGGrJpPkWt&;6X;* zbq8H~U&-bD&mtwg8aj$z=XRmnxgGf6%f(E5?hRg@cr!{$G$m2W&-QKG@T9k;XPa7# zA9D{ye#N9IuaZqN?pQ&i2DKP{&s}WYafC-FOrT|_b{ImVcFih0^}-}XLJFFuvwibs znzuQX{Jb1S-ZPqJEzjh-UOjp8sR`^WFc>}LKYahqZ1PKD7(QYIpUwQ3(PJLv!`B}n zH!p|GEDh=Gf6647yN{L2mT>*3XDG?t$D@xvj>{9v1zj3)=UpSn$|>Q-TW;pnH{Rl| zyN2+>ixati&~;FY858dK$td=-s_5mt5GJ$!~wnb1%Nb>(2~D=sJZ(`P_8rH5@v$mus)Q zl(#F1w`OH2%}B(S8L!YpF)GZT34%jJw3eGi$LhgrF1J3<-k*t~(qADzJ9 z+lP^r8)DSR(R?OlihR!!jPXP+WAIStGb#*Z6Ei`MNK(xWerJTigGbsBPh$L2gR zY$zEyiW`TI1fvkQ&xgySbKjWpG)PaRPW2c*{9r0?zCVjGqwizE_e&Ud>#cnJ*;}kx zzn-dr4(Mbo5P0>lUop^WxF;k_+bf0vyLD`enN$ZiSr7C zu-X-$;G=4lM7D0-j>1ikzJ1ueVFf=eTf~ANmT;g*(6UKG^iYtD-5IoN*VZ<^)x-Hp zDo}w6{5zpgVb4cRnS=s)WMvm1JaN>lQ^%4Jng+@=QAREwfASS|T6Jg1+I4(5^+{4x z9v^%#lM+KGsOwxi>;b-;ql^`da!&urPg zlaHp)VEzpC?c1Nli@)N6Ztd8zdL@|!#RQdyl&Up( z`K>pY{r>aRN>AbWH{RvuftTS`*rxvysZ2Bi96q>{S@TzO@3ZgHt9N&vdwL{pS-`q& zJ6ZbuQtC8p&W*Rg$K{^tj=~ zdR+FNuK^|rm8)`k`#5+an%5A(j^NGOh#Yqzj_%UViu_ONvMYJwsbcU(FR8#Se2 z^;q`rUd@UP863(gVAYTFNf3TM|NJYq?abhp-A8$8+B@{>aW;K=b^(vX)I8K|+?+;@ zsuAld;M4ctVc_le(DB^!xa+q5#0GY=aQP~V^h#7pZ$y_aT{)|DQ``z$g?>EM_P-aU zWS$Nq=%`J~mk!!a=$b&QQ;U{EZ)S%F;%e0(;L<5piXaN<@se1(4o8xcIcMBB^y<~n zL`1=?kYs1==ds7earSxVapi#9Y0$U{H{N_XXLj#}@aJ%G_w$(W++=$9yOgxbv0U1_ z2j^dMHNx$}=hjJY)Qn)j&&&^J()Y6doY(PmhFo_gJ$qfi%dfwSRJNBJ5?8Fwx#xA{ zn>q6cnz1x*-I41r?ZzFqT+itHA7aprx00S(nWIMw*|IB#3;UiEopa=W4XNDCIvZ#RIOeQZ)_a3YE&i8?IJ5H2NQvTz|>r% zr&S}?qY(%x+&(vzlVU0M7h2jT1j;Z`O3}1YJv61r%P%4`^Dvs%N7ZUo(R?ndS4|@~ zI~UUkA(aa$eBkkro|=G11qlX&9LPKZnog0alU-24MHgR4@AJ+AE72u}=ECjONKW)1 z1AdBvU??jxtU@?uWENB;%BfOTb_7i*{6#sK%0-nL^{p_8Zj+>VAB81BGBY!Yi%S5P z%Muc(0v3Jo5#yhFh4ec0X;8l=I#z&wsbTA%tU$T~D-Gu_n|5&PEq8ItkejJnBb9=j z13Ylwc#h;0(el*hRF2m%O*_1dDbY2TC99E^ow_vqwL#%uc=OeL-KIc;W$)665XKv`D8b zi~TUAWs9f@HxkR!H7?GJX-GmMj(&sg;Q1#WWcIXIxbmV4IFwgRiOYvn2D&oQLfOoj zHJvA4`jDCpn^Uh|4RoW#wo%nEO>hYXnxcBuD&*%Cp_ITxq6>jr6G$US$PA%$Wm`*H z6GG{h2eA-v{yD7)J-jv*9xDMgbV{A41_Q#%FidMQf)eRI*$&W&t>G8N4R^) zU}Rx28jASD1PrijDU}3e$2b-e6)2=IFQ0^@N+2LM)=OfXheKIe1ce(zi$N+&9;;#6 zO6;mG@QiNal}0bhRh zDM6{>6()DwGm1Ozz6Ytr+7Yh6R0@{>;g031fj2VqhOw+)|1)h*Ys9rT-^{f)4?zkK zCg7roxyyc}O5-*(tyjm|5|k+AnqPqmRN&tSYg@MSVhDlTmqO28z4&<6cRY6AXmT*P74f z&u7QxEoe2X!NgJ;#Nf*+`XB+Kn%?q)x%}wE=2`G zgo+C|av+n0P%I0VucTF{E>vsK1g}}Z^0^D}ozavH%hys&EOpbX;x8(oSKmG~XmSew zx#dxEZ@r3UEt_$8|5i@9^jzE?56bPq?Y6gEp@Wk#!ZA5gDx8VJF<%f-f%yVOB{Xf+ zfF~b)nEnHI5gpMWy$dW9w zb8{#ESjROZ{)5+JY4%K|aA^j`{sM|a%5n*^r))yJ#=iZ#ID9k*kIO}sDpk4p zhJj3-^gKeVM$0y*q3Mn-oipnNv6WJ3dHSi${p=&!G^~am2vDM8ka`@g+n&zSX`fTK zPE`_f2#Jm|s)UB}#M1D>%c$MvOb+hYNq%M~LTDsbNux%y zrf4ZuY(r2HakUNW+kGfypbKe*WY9GGXEy-Slz26P5Z*}L0)$eyg$BZlK*J>z3Jvht zso^9ZEs~?y%JmmVa*Za8xMcvD`*&luZV_&ak_wlQAPdRKJHn*{uEYzGj3LpX^vm=J zPQM&;tpXLOz&{684o`~>5C~lKy0jn92SdE@`umK!^L7lp)NkB^wq4KT_Tj_GKXQQE z1`WiWP@RE8?q$$5mvC_HH)u-Xl7>Zl1nANPyqH2ms2~LWXv!q}@BwbVZZO3GxN`6a zF7A0Ql|6n&-@Ap0FTKmVQ(vKV#~$1__HNL5RAVRcXM)7hj=w+Z3cwXav!ej+6hvhmT>m4`IjVEsPyGg7_MzG56!wcyio5wCXvC zp|@R!2Mt}1;hc_bdF+Xo=-8t>4?i%1XC^$tw{vC?RBo;rd>btr)FD9v^j^cdni0x2}B@9fb<7zmlq?2o_Tr@bB~KY2g#9!F3i zIFPZMF{8(!g^rS5yCLHq9!-_1af}^t3zJ`XgsIQ#XfdhWG3sGzrN%SouiAyDl_HP2=9XhI8%O6`X%TFZx`54P)*d%b=_KQ!L%otkVK; zk(Qds`c?1J|LSE(<>kDK2JxSZx>K}k6Cr5@0`J(N9q+#T4&VQ#@uk-4ODN?iYb#Oa?1@DGv$S+ zCLMcTk6k_Yvt<e2-zL1>bwfH6oX^^$!S)sz9!0L>GYCKMRz2opd~9YY>kN? zkzhG$W-X##(=lv`iwlH-L`S0GQb7JYBtt3)dJ*}${rY#iFmA&`a z`UB}VPBWOyaakJ4zk0MjP58X**3LQ=CC0h=N!M?&Q)RbTk1DLmo&En4LX zmu)dsQF-5;=Y%IJE37L_o~(^BlHc4N-hw@jRisVp+~F>XWFHkop2jAFu1N1GOTwi9 zB^()xV`=5kd5aMYr=Sxa+w{y5D_9JuC|z#&X$>^1FI?gJqgrM6OEhJ+7$+TfxaCeq zM3oa}jWiH3DBTlQdPRCxBRX`5=G2c~N^_`}xmVZ*PYS{2jcZu+!%~c>e)9QZx$??> z#Kr1p(gaj4mx{s-+bZS-(AjqT6n)MwNpne*fKLUdgMzzbu0(*?`8hVgUhi&_$^qhAAqpDhmckPWy4_e z>{%?I@*+(W5=ay-l+-vZ6^n}U=rm#&je7P(cs${BE@efJ8ct|S5taAHA{^?ECoB9- z2&E9h3WzFIH1QQ-?XyCmNvD$pC>R3<$8H2Fb=TLY9rN{O!PWuN@>FBN9MqNE$5 z^jn3Gyb6@CoFyzV*Po|g{}`Eyis-a_RqFA?lTT75DUshCk>7kV75-B|jK`!(N(=!J zi>|v+5bG?&eaYk#F6Au4;YBWw}QEQywlQR=-S>%t^4A%Syy^yZu%UaHrsO{~|0 zFiJ>E^iYtJNJw}vgoY_};wz;ggQ{&gHcG$55y1dEjZ)? zQ78%IvuDo%7B1V%WtVj$)*Uw3uutldc7zNQmuA0%QNnj$&L*MmX`IrkDLy69|Azuh zR-gj^B>a{-SOFV0Y@|!)PPRH2z(h(*y{HL`E=VcSG@I2EV1!I`mliqvDbR#NzeKoj zB^>J`=SETP=6LcqOp6ILrGf4+7|M-lN`!75zojxPPhES%RyI59WQo$sWd=*XUzm$5 zqg<2Hs^6;Gp{)@;P^m{9n(rLAf8(u0sSke^(MnR=o}82A8epqa(QGeNqDoeT9Yn-` z!x5pZ2qyY^*?x~^7NawmMDEeT;}*h_nQFH1Br+SczxSwt3)hX1)-B z8N&Q!JL_J5l}5oJS)2Cb4F++UmVJb26q3DhGu5kBX31kuQnOA&v<7wUv^anW5egh) z%9LsB%*Y1KKq((ho3-S&TL&KROnp+Jl!AbtXC8foy6rBs5~xc*nFsdq!dtT$IA8#c zYga^0G6^Z29UUHTfmU;*|M?YK-#U<97V2UT5rFyw3*41`YwMJB6ej^MjiR5 z5v71u1D)6_2Cc?Rae=Rm( z8OEK?oD~a358m0u}g& zAhJnWQagh!8&{B=luEy=ZzQXr7*k1*MT{SDJ2h)HWd4#3NDWJ7qzubeP}qUxZA}7Y z@}*m!LWIN53;UWfBK3#wSAdC=i`a2hvC1*An7T3wUu6&#;mw95R8qtT)2DOl>1R;2 zS~V`Y_&@yo^LER`M})Zl-g|g+`Yc=siVAY*f6dhl8F4TEph@`IN*Gu>A-Kkr*E>KE%54c!9|2ujn zR$`x_==H-Qgx6)C94w<}nU~GHvpSOMN@BzErJR9dOJge?OoiK*!08>@)3!kk5DE=R zLC$V&yL~hn`wK`-NZ{EgM)JWYv-#}Xb;QIbbL-$sXy2+X4?Xrg8GH9)C>Oo{Gmx7G zoKN*04r9keaOG-=ipk1+7(9cA6>_3Y2eMtI_=T(u@0+O@S^3?U z+Nl7}CYc66xVG zqS4Zy$}>j$)$uyHIHpA>RXP_{Ryj=W|2KeZqiYu<5X3d)6n@e%@QsK|e!<&$dW(1+cj}mSWmV-Q) zUDycMQIfcn@eXu{`(8qg0J6Vf(I39(e3U+MiN`{*Ar%7$-@xIlgZOmaHi^(NLOQ15=b^E; z^JcX)1`fHCbI@4yC?CB)1EK4HhwPj@2;?$(;xkN~G7Vjm7-j-jTzM@IKXwP>?;XpGPiCQ~ zRVScgSu*DX=FEAYyT`wb%aeen!=zVUBc)wK?!5Iz4i`xL1;x~A+L9OEoJPk}s_^WD zhj{s|Pf3h{tOA{s+Ra$HXgUkO_?-JjkL74lG0IT1>ClylFTcdvAC@wG=1g9Es|^Xs zZji;~WbWgwnLjXL;?s2K&=wyC9nPqaD=v&au~XDFZ`1z;$PX;zh^%jzg6OQ-Su~4Y%B2l5jnIeMOs=Kx7>0I4H`7y zqKht~YuBz}kF{uVzW|gbs8+ikMIi&PG?{tMxxC-03-5L6!h4-NF|B6g1&&q*G8jTiE1zg=LN#7|?KPGz`htF!b?5dw?_$%Q zTrff;#CXx9NiY}!yN^n%Vk%I93jFOMu(cQpEAE{^R#pxkkB6Q;&gRECpEGmjJU*Mh zmRoMUp5%BBS(yjOJ-m~5-kQoe=U>S83l`Ah+|Io7_M5Ezc`Iwzt|zT>6{dgqA#2wD zNX;5)Y+SvJl9C{ko_~%tYk%V0Zk>sZi{a^y(5b?b(vX~#H;gslM-bne%WJ^m8B9xv&|CDhL^ra_*cy1B*FFDM~B zVB+@r*k2T&;{_L?Y^F*HJ6yEeg>=PHtzkV*Ii(4$o7E@QCBUWI4s^C%4FF_ugkyy;@aPtzL)ea*>r^jK>>8tk3(` zk5&aLP=UV$(bl|H;N>8Bd4)(_=lqK=qfWIr9(mva@{I&;y?GERaf;ldSri@3;>h76 zEc@{X2H!N4JqPx2diz$yB~)g_h+(89#nP|OrQ9*>5q9p+=IR@6rbpM-+%aS@{jR*8 zAD69S(cC$l->DmeZ@it)zWNraDGaIDy>~bHC0^QfI2+;C&}0Y^3{jGo%aJ38Ig*>r zu%UM{W9ApMX?GU!aq&oH(QG$nI38e9rDUYxr`TU;+W-oL<|03@5Rcbm8T<(sgQBG!HT4IDUt$}hkzCA#gr z5dsWNhxmA6o3)_EMSbn~dQq+u(nJP|*s^8|X4WAzCGcnlb{FqO)S)JF#rs ziHTfw-2k3?dOWGVAUk*LWJ6{lqgu8lFFzNTZpUX=2K#qzV%_E)R8Ox)d`cSo4(+oo z8{FVZ;LKB-v3~Vpip_y|bqx*6uv!TjHq6e>+|HsOR+3($9!r)jCgb2y+O}qNjqFKYLG*9nI=gw#I*4ytgV%${Pwrs#1 z{mY&;58OUCA*FL_n~q#L>Q=_xdk^;v9mb1qO(oW4<$I_=1uF3G#Bno* zluj8}&hG-W}&kkHF5@_1=RBEPFvKUd#$JI9ug}CZWfA2jK zQ>yUH#HXlTyE=P*`GwP3)I+ypbrlo`c>n#6$;m6AVdEy;cJ~NdC88mOj|+RB&5RG< zWBc9%G^tY)mvEuG6Y0{aEh$M>hy+6kR;*mbhG`#>UcEX~UwM({wc;qw-OUHHzu~rF zBk;N$w$Dir6zwwq2cew4j*h(b$4ZTs;QsMum2St$wtXyZGy3PEbp5;RGE4V+1^ya{ zaKuy%sdRGu28Qm#CdgIQmr>EQPIXnk5snx=XAbovZ#8hisu zG2rpU6RW$aTKg1kxc(a6p79>dKX{G&fE!=ch9sob<@y`0!Dc^tg1U;I|X_K>eL;?g= ztn~`~ckrvZgMS+e41?@#+sOF%V={hRLSDvROkI##w-$9ecBEFnepISeA2gR0S<(rT zsuWIgNrlaH;y4#8+igBN<&X&H5_F`A_7i9dE7Cm*h~%0qZN(V55^>cJq5_#bGX4ny zRapqN@^SPk)^^zg)*luf0OGIJdo+O{x8ox7lvfl>ihE?+~&zAQR*??#nM@fJl=pv(g1&0m6wO{Qn(GbqYG z!kRU!Ie0i9bRTu=*5%a3HCeOzCk|xhAaxH_YuBe;%VzBOc^TVx>?5GuR7y*y-5F;R zrw3WRd=dLH^H9P?Y+^E}p4OULX>lCgzl)t28Dt+h#F$53CC^u#yU%T9_4gCr(b=8QAikdhRS zCi7UkW)pFh>(Ho94ZzR7jD4)xl0oNA9jFu+^WPk*tf=I0;Ub+q!Py8kWv@5K z$xqp_740;55pL1R$!mMf{sF>#(&%0VDsTdb4i^0ImWT z5LP5>CgIG5rPj1UDH%D5Yw%mAt4Q*0=QhVHSvW;fPDN2rc5JQydHF@mU$~YF&OZ;2 z+jX2;Rn&h1X#`j>|7+@NjrY2Lw9s^s*})%|7eu$-;*N|EVVTLL~$y*jA;A~hwS$-fg3h#q;uy^ zC}nNNLbwTU&k{6epI0VI=tzZ~YuB(sVxggg+m4#zP$)~q>>PKav!+X|n58aZnVq0? zq|Ffs!vuMl%X;);#g=`P1Qq$ASjIf{BBO7)2zQybN9du66gnmr)z$3klnR1SC@Ii{ z$2N2Um#|_KN}(gsaYfCEQVi376=f&p$&t84m!w5~R%IMugmc1msw=yfl+w_sNG|3- zaypMxN(J4kz<&#+Glu+G2o2%(05Tjo9;}6hvQJ6EnbN;TPQ(dqaUzP(QueZrtWhVJ z&2KCwp`(Z)DJhOi`}RPpV=^d4!8sjTsgE?>%{e_Tz!VxzmZ;xV=ZV5@j#Y(2x=!%< zsE#%5fZ)1zViHBAq;(1w!VV}demk?w2{qDcpv6Bso92m^U)GF4Nr^ate4M{!2Ju%v zUw)bLq?ReL+NltKDjb?nR^WCa{w;~2qA8FIDXp}T0?lIVl%081SveDQN0KBpl%`v$ z*Rc9lN@ddph0rxLB~Zc&R<9=hoTDXza27Mf|Cj8!>}(Rp zx&G@YZ!Jc%mDUF{oEA?+)9&y-;t*d|x)23YsqnMmbN`98FkIm8p?kkOqgOf437c-8 zY}!f zOw><|U|I~r$tJYUhGbX=6y?R{!~YzlLP&*a+p%hYL?UQEBklI+5H0-r2SO1&7lqIf z!p_kl6%lO)go&DSudYX}dTabOJ>o_uu+|?+;t~R-Or+F7vlDPBK-26z<<9u(pe1v~ zz#&{NL@C3TaG4HcB1D8fI9WQ5Im~L7v!9ACM}a1y zMimTT1&)V5f6%je9VsHV4Z51M8qmlf;e8CCjt{?=JMDh_px^CE^B|anYR;y08|L2vU%sNsjS($4^7i;$C(p> zLaBVd`TTvxJpLm2Au!}IiK6}hghh4HK$#Tf?%~DBlgTSCIyMc}ufVzY%_*<&!{Q$Z zDn-Vg-4qoR+R~ff*Ks9&KYoA733FPXefAlzz4rRa%{FB<9Hsn(%zP$Je3|U5+&^9H z(IZ(*eClbkit`EmiE^gB_%ff)nnef|dG9~<{?QxbNht1w;iSY8Q56f6a1^b_#w>&i<}vHNX}mXmHaQ`q%p8wO$)$)8RlssMGwpf+rDL7p zT@cl}@Uzhf^S8G0Q#ftcu!3MoTRE*PMu_U=7!LQPRpQe0F> zNgz<_v1m;%QX+#vX1?wexr(CQM40aQVXa*wj@mtP3@^Y~`wJ4|}@eS)Us(EdFf z$~*$n#P9bLkS68{F@R8-?iu7B`GprIPo~%i9Ea{HLcsvV{*n_O5g`OpN(u@JPw>eK z{4e0-Nc%-Z?j^$Cqg)tDN!cB>YGkcT8RGlz7m}HkjS^8Dr9%i5C}~Z769ZF)A}3)P z;Fpc7`6Xi?QYhY<_6DDQIUmE$9qgQPEoF&)vR6(^1W?TOZR?r*>U)#~Lspxk@+n)D zo1mnXv)E~t46oP3_qn{ap^k#=rRg_8L!T=X3Wj^-k5Rfcq`b&Qkjvh7ci-<^#?gxI%x zE4%jXM*_M~AVaol(W=(K3~wFL*DW2BS!yKgx4}@R&8!;u3y<>M{O`#N1dmJXlscAO zaOm%b4XZhP^e~2L^4!Fy*|c>Nrm`|ot5W@K{aJk>t^SrF7JW5~&*ywciQWFv{TWrK zG6`pRRgx7e*RX2MM$2%l%s5(eKp|y_=3CKSpD@y)zN6ql3$ zW_VsX%x&5Ji0u23eBjo2NDA_ES-4<6hH1}D#{ntoUNf4(S74fvIVY6~nC#lQm7_-w z6H?ZCMgvor;fGYX;7B=2n$|j^42z*ml##>KDbFzUj=LE;{0@fRekV^(d^voNRqtN~ zfo0$?5W)lkES&QRBkvf&l69L2X;74($xF{X%DBg$rNDIfGi6EQq{W6wp)l>illHhP zVT(wGfieqteB5|G|Lkl0h8a1a2vAD1^PAiKY12s|ZBq=3SX#&1aK}lTpr|mZD)-fd zBKzPrMh(B6sqfAt5GZ2dS2GxS*B#tB{7(Llz4wl@s@V2@zg2UE&JEp7lY^k5 z=z0aWZ{A#Y^}33gYwCBi7*?%X%O|798$&C0y+pKBbS4?mYgAc2<3AY5>djjS0ou`? zC}OrFf#WFFEnmXHqesk|2T;b$-?MWok3RM^Ik{)qz2g_Q?b(k~iiux*#`Kx9a7s?_ z-diuT{orA=jBT~+4)E5@@6I-+&9;i_y`tPREMByPeB0HZ?mASS60nPzGkpSMznV^w zHn4&VvNd0@)QnurdN!Z$-?yLFN4!R1H!OeDfgu8BZOHoeryCjYzlHtuyyNhv@#3C62kSmDG&lJEZ4|W;FN+4 z021YZw)~On8s`5-fd~OOWe6*Xc5IM7a{?8nULgfaIS8$Bu&^wNR?5ZY$Y}m~Vc`gg zZHK@Lp)sLhPa(%%?}+RjXjHfuVfjs4l>#S(&>^JJ?l|s~KH+}R#5qt>;+TC6pAMsJ zjr0Xv@25mdW1|NICR`@`2pvK>+JNGvVOsPd5QG7r3z(NkT?zth;$jrB!Y9I@Z8xqM zhtfVX4$6$FqXiZrY~ja3Ae0T34+o9Z2G=G$0T2caL7$J2Z@-DOg4hBAI*h=F#&W#? z4p>&iaJRKYD4S!uf8}_fI$^*s1U_wpFqveOcFZ^m@CgSH=6oPDAxGlK;P2F<5o-vP zjj)1%HnJD);uE&(h4DvV5DpRx7pvsTJyfc3tRS{B<78%l&ovl~_xz81=t5w|UrX0W zF*my{LioHfu-v(%9e3Utd>igckwRff_i!Wxjus}ADHJ|!W1(G7h{h)@v<`z%D3@U_ z0z0tF5PqLAkkAn_B{PQ==pvT=G@Hy;*U+Ow3mgZM%Vi*x#}gXm3h?^s8TS95gO}Qq zpcmIGX4}T4d_MYf>U8K$<0kbfDLBoXucxr3tO9pG@-RtO7$E}YFrh$6%VgQm#UO)7 ze38}}=2Qoy#MS~w*=RIj8?=QPZ!NJAW?ktpj__llKsZRGxr_qFBk0Zxgjui3QTU|| zKA*d7y9hT|j|izK$vw;$pL{~cn-jSH>W(a%^9}EhnMHE>bV`Z~35COCTvDH@Uw=i1 zCiSo|Yfnq?Y2`v-!XScRS!ktkq;P$aCaPjP1{Pt-K!no)?Vxbk6WnmPkTy61Ap>Sk zxl%WH#~2m^6(TFE7hSsd!x9Qq7~x_VBRWinKnt|?8K0&l5aCjGZdyt5mF_ z2xD#)TL_d8SSo~+U@Hshs@KS&0T9^uqWXqm?AdA_(djoy19>%G& z`GkvedHSAVd^2|;`;Hu7$iVJ&>)w^_Sy^0v(=Dvuz6T|xA(lpfDrV&KPx0=U$!J~7 zvV}9bc0e}0d-vq=XNGe=uZS5_zGU!#o^IC{_^`vkA!My*;=ahv1$a!yozFRh~p+m#k z^vLQ#moDA7{f-AXcq$i73Exflgh5viBCBr}f4lQu*6-Sn6q>!iZsc$Mdz00@J40^1 zjbphbC@t~Xg?#e%%Upf!AhNT1@!%8BaX7Cqau$q0AB9HiB33V%$>3`T(k1&^?t0`| zutAj;G2*!w=$qA#tn48yUcVEx&CXv|Gwg-|^zWZd_pE_ToiP_jY4Xk-;pvC(rdM`< z`d)V%D_5;YBhgxO?(8uhy5m+}dh>U*-KZrw-+@Mn>}0BaMQH|>5>`O&9@%JTW}^_S@1zaPDN^x)&qCK0v*ARVSo7|k^UZ{vee zUt*V?=gZM=a^2wT7}%!|ci#6XhtB3xoPU}(UwMIUJ$ll2z(8isnUB&Izdt1lv@T%b z4^wE-qCMSu_M%g#&b;v2XbOr;35N=p{MpC!>z76MUcI>W?{~1{;4zf4S-<#u2K4Jo zpPv1==q-X*Lxg=bE4$E`P$m6gSStFL4G{u5{&V#A_Y+;rp34D6RppX@;_-nb2=ZMOZq zhJW0AGyQt?;qP}o#DSA%(14{woH%}vTZi7pjF~gZIe&&{pL&dIugRuIpT4~M!34_C zY*@8`K3&?8)vG&?KK3x1fBu=Px(#N}{-f>$#&`p*IO;a4Plpa|>E5|Dt(!OP*=PU& zAOJ~3K~z*HRCb7$hd)loZhh&UJ(xN37g6TT`wRWM|4GF&qr7d;4YaygIVmL;VSb!C zmYS8zla`)NohzF#dg5$Cb^)W`eU{p_tC5^ij;1ZzvS!0Zp1A)Zs%O-sa`lGnIdK}{ zFJblaWj(jJ9>onO&XJZ<1H*&xso>ZYmkPd|K}KK=TT-KRf8uD_XIb{|IBxr}~iIK8v3X5iIB z89in^jvZp#rsdpy+YJopKY)P)Z)D!mHI#r^!?6a2EM@MTSv>vtaFl(P58ix<4xPKv zqeoY|bkF9S?-vsem+-}ykLca48-uPM%!v2KQf39P5xhNO1cL?)vj6{%cfWFEIu0l1EsdZt}PpA-+2(H&le*+{H7}8omZac z?GL}e2|>>3Q#|+2=NLTTCO#cCnhwnxvg^coLKHD`!ut%l?P2ml4qAFflxx=MFgrG{ zV8}K7>5^BBd2rmAt*d`kQbkRf`J1D(>tp-FTFdK!mz}Wnnkm}WypYGy!-wb zLS;Ej82b^|Uwt(LdUxZtJ09g^P7$TWIea$eBl>3bBzr(M&yD;9EflAZ9^(3e{ki=g z_i-|(h{f}N;JU#B>DDWY>#w_+W$QNMVDsbm<7wWi6`lHC&y%mbOPL0QLSiHTAhPvW z`JY|>^Dc(`2Z|1t@af0zqY^7H`mJ}d>@x1S;~^|3jI@kr%+UfI8*PUP3yZ?CF!@Dc z#(X-7#2`%l;xnFo_7$dm_6m-cI6|X!7@@-E)LfF!dvAZhHFrEl_m1tcq@QxhiS)|O zrgP686qW_J{r;ypa&RB`gS5V?C-1)X9EpjLd-f;~JpL?izVj~4nl<2y@n0}w);H9u z{WxR3n#Y5WJVlFUb@}G2PxxxZiQo6n_3h;67E>C6313XWDl1^v(7RZ?Y8`zVRcF-b zPkHF|_i0h@3dW3`z^CthNYi&7XVk=r)M(a~H}1HOP|g9e2mK8T!HUJpSh#R0BR~F< zlz72?Prk{S$&~lUQ54dQ8T|?I@kyiv^Vz#; zDW&I5^4v>rQoU*e?z`*n{Jd;7i{~xm%`p=xmu&ISlW(%&m)*3vL{Vl7-W&5FRnyCp zB+3{!VH%e-XlVQ`DufftrCXWsmnN)=Lg{H1qT zx_kpIDi^V8!>_zM?laPo;&|zWkywPWA{=9$uTz5vbN0kx(rVRZ%qQ<+=bz@@`<~{+ zHEpqcFzx%*3?Dv{Dpish^U(+V^O;xp^sVQ4;kg&dy7eIj59~_rnUmb};JZktfY~#q zQ0T<-{>S4va`ZS)KKlwc49OxhsT>Jr0=gx{&R^CrZqj!Qf9pN!)~JZGe3YC!O=5B? z!$-bNYLdmXk37P}$=~wmZGCw7?t6Ib?Qyhg(~{{k=Q4TP_q4A!j4>a7Ox?CUc;)(R zgtRD^nvBHe;K5^j`uBSna>Gqz_v*;k6TTp?#NwlmCvf!0DIR-f1h?GQpTjvt#Fwke znDOKA`2^DP^X?nZQLS=@*%VzIi7qSR-4|bE$_H;E0&zU>$bIx^Rgr^7PI1SB&(ga? z1CkQs@kh4Q{|cW()U4Fu5FZbJj_G6Hg_1(H?K+IFc2$&?wCr#d6TbYE+?*nw8~zTT zkDEyU9u3*L`8UG8Og{R2IG0r^&yIBqd4KE_{&CM8^y$`=yNBM5(2^FdT5?GRAN#g! zU|+qO95{M}Wh<7^sBsgHoGfA3OV@El{VRC?lhK?ydxo)}&EcI9uXF9St=Ya~H%E`2 z=H(AQzmi*A%=N?WL`ok)jHgx;=6rqu^;&o5rDyKv-0_1v{@4S| zZG1W9gFe0(KZ}n(A4{bQiH!Sb3?F77{-p91RaV`ZT@!btgqi;zSY8zVIS45YM!)zT~@^^Jvwg0gjXm zy74CZ_U*&rtv_@9ZO_xTQ5BL=XlcBL$_|@LP}235S$+@}<)? zJFaSwz^Jcg^8P1dxvWYiO8PjqcPEu9SLXAH6G%u1Anan^{^(0?yZuf&wQs`gucz_S z@Yncm`b3T$IZQ^idW`-2BT{@8J`YDJAc|4_tNgo^{}v-KR93{kU3Ft~j*IgUK7`WlRw_{ENh$kVwh^_m6VcV`l487w) z;zTY2hrZYJ=g^V;6p=#xM$Jf1lT=Di!N;*b?4!hlC$uk-)btF>`2#e%yb5P?a`}1V zIRbIXG-}?83Q2Kv?a+qjpL~kqa|hXd_!y7B{4$lQB%%|GN%9#ghh@vwuzb~4I`!yA zA`Z%zMxU#PMS@oX?XuT|C@d}_r_iEZ`wnELl|$$d+CGOCaipeake-oF!z*gBe9kxI zoIJp`od=k=@&jHT{t`h|Oyx^zQjnL+^w~>z^w9^YR;`K&!`h`-D$L3yb7|PFKd-(u zlGMZ?t5>XH#oBFj$?8MUE+Z`B>C^XW(5c8kA}ML9R7g$2B8he#x<|cLQgJ@#BpbIM z<%tpf$*7QyEKVgc4iFkkLRmO$6sQL_)vnh!kVs@Bgn~%;pK}q?#l-Pz3&Yze(G##d5S~9uk3tU23VqLSCpqPNT6q3_3 zNXv+)O1S{V1;;slzJ!!YS5UWJ0}_KdWcO;z2gBZB*WP2CIh{k#f!B~;(IPDY;-p46 zMXXq{l&@EwWZL&X5~o7=d=@$9&QdX{oDr;N9cjh!LwiWCaVd41*CP$EwC2#+Q{YP= zy;4;&5=&{(pe9T99pd1@BOE+*p1U4=1iubpVbQ+Z0Gy(8?Ap7RKKDLLxe6HsHK4-S zWu=TB_Zc0p9>R4u4Z&ySvTD(fOkIAMA7;%b5H3UeEKZ*~fh~iGxN?+F%fON*P}sJ4 z{TK|B2HPR%3o!JyTj+9C8?-+_)oPg_4xtE=RK6-{X{q>P{D0zt4*%yDsWoTLoT9Ms zJR)35VVO-id^k>s1#^Go!KX(MP=1Pv3aQ$p8b!q=Na6@2SEWU}cGRn2v0(CtgmoMP z|2B+{^%BTP2%;Q|#JG5Rc5cF!wJQh&g5V3VdF@J8G-{1Vu1?R6t=Y6@1&`eGASJ~` zloTsU>>&B2WjF*t2C3hoH62>kVEf8B?Av#MjfaZ)Y5rmaB_wBF!P#?Xp>hJ=wY9Jf z4j~f?v<h^6c5U zizb()5(UE<2!ocMGz=s{TYmiUaik;!2?XQG>eqvBXZ^@^otv|M({^5eq74Y|;=DE& z@>H1fIcHe6^(ZgA)sKwKbV9kQ#05-$w{F?ar(gfT7vKFvz%C>#(l~SK1P%fbmrPuO zpLkWu$-TQ-uxKqmZN7=1I*+3hsaLx)`(%jP4O>ySaXm6Hq35H!ZIp~7rCfR9d_^4E zxtE+GNs|`ss8GRA=Z=jT{?Rl}oh<+*u@cfLmzF}g$V%|w2Y=xK|J}-eixFr^NQ?_| z^uTVkZVOTp(i$Z!QsNUKRE!-8Lt+r66+XwouL0Y}1z~aWY!2Wf;P-(JA(ahM;z)^* zkerf=W0z4n z_b{L=1j5`>*A}U%sTAd%Gw;WTMzDRwBDQYd$+*eiB2I1RiMJ+W`2@j09AzbC2HB|v znVHpS-n=m*KA%SAv;?#kB*zEYxZo?!o!x8Tb^jzfa>bK+zU2?@!hCZ`Yx#&P`k5o%Ygg%p;#G-dfHU%4VT-PMmL z@4lUQVQ^+CphJB!OUng8af5yVk;z0dBtG8aD0U%SWGl%HwwqBBM%Gh79e_vya|GJYlqe zl(Ynn@7{-y%4KA7-|Tr95C|N!CD4H&m1|yG%LpL zcFczD&h-cl$baazxAX=T0zrm-23o@ zqy)nhl=-QDNfi@-)EcCA@7y_PE$~S{LMbeuupp1`Cw;}{eaFcfl1;h91OnRN)ok26 zOiJNX%3#jW*kM6lZW$FX%Ooi=jx%RZ5V9RCpT*(hC-BF`WBJm!^TB87l(mCN<0o>@ zJrD81Yj2R4T8TH_c$IG5S|Xe-hYeC-{2$9FnSDNz?k5 zxtK{amkn-P5*HUFH8seYGpEqH4v2tpdH_kONeuhPT?~8VF;a9Xw)9gjsM)t}7UA4t zS2Pw0$;q^8*N#_4e??}{to_6Q%=>N>xu8KL3= z&}ro472pdd5Fd=gLuk5)Ll?8_8iD_X2d=-$e^2>u;R5v~CeiEKfsA?US-$;pJWE%s z;&fgZhw`LlR3Y9z!sH2KS-XALrs)^RumIUGB%movF}lo2E(lBt-H z!O5*FSTcVuKP}lzdX1KJXj+>w?>x`u-?p=Q!%j||Dy4GeYFt(|z^fykVePujY}<91 zvQVk%ln~zaDYH=tP{P4hVMC~^B{%{pBu!g2BQ;6##fR^+a?t|b{pd5g4H`;PdTsi3 zZp|zA4QATZDJ)yHk@KY{JTmy|-kdygkZE5|WB1NoY}m4m{BX!SAe$zjKv|?Dr&70O zD$hLePZq6M$4^Vvg0=`L<1Lh0qn!|?3X&>bLbuM%dFO?@S-D~*Yku9&`mKiv1QL1v z;hXqo{D;h#K8K~tx3h2OVL}9`SnYD&d-Hit?AgG$&!*6?Umwn#IKY(gpR;549@hW5 zje;`J+9K@UkQ3S_=kRvAw`<12H5*-Ok~or6EAzxZ1~K-HXPEWHVYd8E%iGbRTn{wvBHa;2t8mrc3 zq|ewE%Do^Evg2uRMLk6R9zJ>JHRjG)!5i;RW!UYvQonvxI(Kf(^AFw6!XFnif9VDa z6euf=YX{%LhB=d2GH)io?%d1foks{t3rj?ovjz~7E1I^V?A$(Hed3=iU$KgrKdq)% z3v6vJvc%)xEz zxn{^P_8mTf_UNSi8b_6|f7f0%uKSfWD>t)Y?awINM@UFyz%oX3Ne=f8y@3xWOedrS zySH!Uwi||#UsQ&63V8dKNBR3hk5lj;x=bu0P7dt>9vVx5Ki0R4kvw;T^y5+VHnnv1ThJw!~2)dUITYO@OMk>e0SU zGd3=p%X1Ij&V6^?!^~Op3C72x@PY7|SSA2|Py$PYDLB2C?j74wuU-r8esm;(inY1t z?qOuc`5E)ZbG-B3`vw!Jg~7$yMf|e*C+5%liH|@3n&sQhGi30M^lDv?a|br@#w)Kf zclJu|d-P>Gb#6&&yv>i_O(tBbseNffj-4$fkd(&FgF7%`%t%(R*~FTS``CBk-XOA7@{OLS$@*Ql)BLP?J+^~VQ%h&VJW5Y?UP?5In+9S2cb1O+ruf&1hwv%)0 zl(~@T6X1_0BQ=>tv*)s4lG2lW@!?2zZ{N91I+wPSamWrOQ069^3=cl5`J8`h`IBZP`O$y`V8nt z9Azy0;X9l_0!x>#p;O21JpR;UB*j@=R_AiIZrxAa+SMs>H0hP9)3|PJTD57--krPo zdfIf(CB$@Bh_kLLa$yusad58Nq!$+O`F1roI={Py^33|>(9P@ zd--<89QN-&LW>s7sZyyjZCW>H&)$Pfn)(ezB_a9@7(|Q44NbPk2uR65%5!sbIDYyh zeX_F&NQ)x}k5jQm9U9iVl(uc!uwunpe)wSy+1FgpEw@}poIgmTM)j#tDU<25=CE?j zdfImAN>=Ya)T~j7HmzE-VDUW;t?mb2*=vPq(ZrI<{?zUnpkIn#aaXzi>(I+FW^g9WJ@N zI+^9unEdrD)~(%0{kpXY#3w+Y96dU=qd%U3+w*Tj$O!Ubc!K=glQ#Yg)Bz zLC_K$JaU@$S6xL?AV67R9ve3POsmd4s8TT#DJ+DrXw|j_LFr@aH#6C|`B&Or)rqbh z+f$`dCKWR>nKWrCn>YVVla{UM*Yhe0P95O8`5W*By2IH3M)IO#Espn}6O+qh>AW(X}Jh zs#N6knRCpVISaqvPy6<*XxIKK*00;h%$eU&P*O(g_HC(JDU(*MTC#k}BIeAQOI%_q zgZgLFu3eGKcBke9MN-Tj<_1i}r0>QL|<(E~!$HnKNgyc*zRNr&pk5(}u>A z9l_U``Iwwqo{sIWV#AuX%$vV}g5omTw{69VV@K%Fr7Lk#a^mPooVXM^b!^Yo*?l;2 z>=fV4_?BIJ_RyqhQ)*PHO#S)|2o)DIdGZu?@7+)9)@{kp$)QTE+B9m?m>QX>EL*dQ z>uxRM$bQW2_*&6_q+`O*e7xS}@2xw-7# zwV#gNIuW!KyS8t|j!&n3yEb_DwS^Ekj>FlrXGu*>{X?a6`qXJ^)T)8&YvS0E6XX^daz=R)(GM2!aTnIZZ_Mt?xbO(22`tFnLteX zC65N|-1!2+wxm_FMjSeNn(CL-;nM0E6c-k-cmFh0`=82bIB|Xt^Vh=(@k|mhL27Zf*hd=FY{k1igB7rB$motXs8)IdkT4=6pU~ zx^<;;g><@h?8J&?%b34#5v2+S^yx*_ishL;a}K-qAE85sj&$qLlpWi*Gws_SXx_FH z5C8LC5&{ksVO$;0>F%b0Jclb%{0pVA;)Di#D<3*!kBhW^CD<6V=8m~?g?WtWH3 zFw8PK26AQ`_d+`;EzmB@z7(L9gOn0SIY?=_!6tu_2_()B`G+VtI9v)WBa6bq&o zfTPN=q{LAgDg34`Z!EN-DnMFpDk*LHuQk$bZ)A*I%#0-kN^3(2gEIV%F1R{E>*1y> z(=PbO(r)%njZ2;5X8dr|rD@koqX6mTv+}3!`P-A9vwGbUD#aO@Z~EB)03ZNKL_t)K ztJb&yIF~fnJ>f@HmXW+yG5{3<^l6N*QgYD*=1@W|P)?ZVUHTnI;b?{QGHGZB zOIne(YIpu<7sBA(@s-{j71HqGNg0)i5I87&?%G5e+UAHX9gXnPHi#$%l8i~U6$*ve zxpOBqYSiG5%5Ph?(xKy3-XujkrVWm8iJ!Hb7hTH;6a)oY3OuzUaZ|Bb!pK=`q_ofo zlyW_H;jp=!A>3>&4hWxR#!h?KJ7Gxn5m7L{Ys@J?I3O)U*lxyIBZV^hz#UJsCcG1Y z83&2EcqcJyTWLd26A&o z4(C}s^6V3olM)k9cUPD2m~!3uuHDBskerf2N=gcs)NRVzjav{%H;aHY zJYsI{VO;(#EzSF-D+gn+y4W2JLdwYEbJ~ z?~OI-;oNp>?U7t4mzE`3q?CXUO9tH2DiH$@AraCS86WA&(u&YHm{1ME7;h#VDct_J z#od@S4OU(C=gfzmybGK6Hhn%}95;hpQn0^|O8#xOhqeiN0p%G}y7!$%>FG6^^h9k#QGhMYwg=rC?^~4vMFBT4d93fFcy7Si^ zuZY|&wD2K?IjkbV=Na%siQRp|+x(@$**+TB=`h=S5Dp-B85AT-MJym0a&|w zSa`;a6o!XSSf*3T?TjwumcdyhBqWlUltf};3JHm+bjrGpkPv8W5XQKa!quJL0Y|!X zOG_+mMOg22^mrdxrwC&(SwfpRFD)DoEA1YXq^mC+H==XFdJqz0S}VXt3hnAtht;c= z(yo0+7H&Go?RVWpIm=@2uFW)S)QIGSWRemRNQh4&CA9*hCQe6Vx$E4>&u3Y#?)7M7 zw7WjMIcy;;Uv!ON5wJW|xG=g^n>Kpn1X{YRevwQt3Ms&nM!#qwBP8EGcW;oc&Xs=| zfd5w%p_KZaR{XEcF{mR-(JK;+GBAl6UGTE<%nZPgDx)Nh<(^P5grZt_p#$N1bUd%1 zd4v3uzG%2mN9QHCDhnelRY5;sPW_Q*orlRR2S zb2oe5$Y?7gipd*EFt{@BS@V!fg6a~)Y8=-nw4!6 zWjnGyz#Jsd#z-+&L@%azk9q}SKZ!~)GC|xAG#5>TnBsX)V&;n1ZBH)08^?&>E2eHM z@=k?e6Y%8k;9v>Mo!1wPHUObeh#fn2P_t&ui(iCB^V`;6>3CJA$d`4bg4j&Do_EO< z?}|p0*5o3QxZjW(v@n@#P%7fdH4jG(`p8_>o+k~2(nilko)O;Z&OOU`b;Z6l#(=*_ zqPQ4LGupn$Z*=7Me?+~l5R@34uZY9v9u}kX!4CL^;@6V`G7ca~ooS0=6=_5+rVdD}fs-wqm8=>RS_9H( z7iqkuVT!j-qLPlpEVV;S;yCx&n51CtcOpaUhQPEY<~xGeElbBPcz3O7*DGY+tRs!P zxaD5||Mx{l#OeLz9Xn!wZRUoj6I}9@$o##~t9F4g=$HVuPa4L6Xs=XcR>h{(jBSs= z+p?pL^XN*vdSq;FVJ_&(MN`IvZN)_!yhpJWJMz&!NHlRMEG)NEQPU)PEXG|U(SyD> zCegJQ(XpP=MSzGSIlU^?s@0%sm8w*&T8(N|s!}Z@1;6&JHu1ZDC|3*V$aVKvW7Z?a z@w8PGGwZb)Tm#T+qIBmXDxyEV|005ne9IT9M@KH-2z*-MQ%0X^8Ba!~8dR-Tiz?M? zQmslAYE;P}HR!vrI#22m=!l38UW~Q{Z_A3^8w3dN=C@a=JCZS>b#K@5b~H!&?*F?fZT#(d^3GMr6pl3>Bn=6D{UNwNE6`| z!YoXsquvWc3nHU=FVUbvoY=aaTW-9C!{>6%_HEl}+d*i9!%z`L6_fN`2tz=P0HR7; zyZ;8))L za6IP=!){p0#ELzIsZ}1Umo8-cp2K)9f`}_$nsBBMy?AHs?8`f9s?Z@>PUO}h^pWRJiNImICfARWcg zgWH(<(-KMmTS#>AX>J@mkR`wThL#d7%;xL`k8MYxwVOW6Yn^L&c^<}CgEeBiYw#cs zI`*@RwnZZ^3k#p|P)SKx+i2mB2{BqA!>n7oh81gn#V5gX_eiBZZYq6;GmGqBuMb)k>u4?JlC zEGrr^cR?@)ydvB`G2f3q0}(8+xY%fm{o{@);)2iru%8hF@M3e(!UM!e_+32$i4?v_ zv?8{p7dPmFcEx@k85?=g?@S05VW0p)`jFCuM=c>Dbs5qvuYKMpkr9gNzd&NS&&JBy zG~#zMx}e>z6x=q+2*l|3()8pdVrr8fO_Knhv|`#QkXAHQf8iK;;~Ry)TsSr!V90Ch z#e*PX|LGQ2rWei5SUH)7`oJR_^Tr~&L;qF&&C9>u*DEwq+Mr4i+6DoRi4S_BOG)kD9kj4!kLJB)#D?~heb}2YT2%+3Ft>JA;uUU;d@421w$%zOYET2O7 zP1sop3tPLm3>^Y(5>naPEIb#6&jpK2IcV+RSUwC^MY))iFz66kYS$No8~$|LCndf6 zWix0%Z&R1sA0aFp8N}8;cQXiso9EI2^KV_mr17KpZO1OkEU>kQxUrFFY)sx!V^V~$ zl;cJYHI~rW+HH?J45j&J8S&iX965ZDGQg1*QW$2a$Qe+UB2+PGlN(k@fw17_TW_X$ zv!<>m&YU7mwBABlzQ`tQynh<4{p9E8FnZJ&3JM%-Bw;L*r=1eO*tNF6V8L`4beYMe z?7{;~+l^P&M+jR8!mh348Sft6MQhMf<9Qzq_Q(d|U`t7h+nZsrhMiDo9m0hE%RreEf0^r15h4T_nj$3yVI-E2h9F$q zW{%@}7*!b(g`>e%5(uMonCRAEgEl!&y;`*p;1q)@L2FG|f|APo>_WPP^ifuNj?cz? z%(m^jPzY@8qe0VV488SwW9wT0rDz<&8bZ=N1n4k0B?fnfz>xxJ38V)0~{WmGmX z8}>!YCN*!}OmdvQDdsAbX5 zFK+vVhQlBA_y0+5;)2JbZ~3#H{JuxxPoB6Kz;JO-Vr%;2k@~ZCU;LIo{?ecK{^I)n ztd0LCHT}87{_H)`Z^Yn@fA>DGTzq7@@OyuifA8`yHv*+4L6{_IJv&F)2o%oMt1^<~S>LxgoPb7oDaP16>XPf4X|vo@?=zXPRV zgq*utKS@SmhFlYV+A!GowV%z!^v~Jpf{l`wCRWU!!o6Vi~Jx;i&fSaxz zNQKOFI(F>LFI%>vEq}y_)LQf7yt&Muw}d$0_~C=}?wd`uYL{^DgOB2bLs)1I@7_+E zrVYtVPv*v(Z{*nd0uW%A7INFo!^kXuDeu1j2_js|$M3#RojP@B+N>pumaRim#@SQ* zxjK6w6)IGsNB8bbo%|IwFKx(*3Fygo7I~d)i2@27hj{)y(OG? z_Bgi=9ZKaIb?Dx+58>QAN=rhttlyYQnYCH9b`?bhc|7~n(^RThiLTwV`EC0_Y@yh+ zW)0ojwj;B0CfDA0E#J(T!R>cGNnvprp`s$5dFTN~ef|YyM1vXtLWj8Lwi}uH-E>NU z)2H^)u2Xl`{k)5>KKqQ?m(-+M&04(o@i=2TyBI?$Bxg^Y=FtcL$(eI!kvM$$`KMf7 z_i|d-YsB(ZYmq)dxU7Ju9=V^4v^1JFZoz`3t5H?}A#CP;H=QcwYSF*%wUmTyMtwSt zqlb>**NUZ!7Sp168|u`)lu=_R;s`-O?g{>R|NUHA=W;4mtjMiH@8Eo1ab&KAp^`j?zwkUYt5v2)uRi>;W1rcZr5Dgrgo+D!`PpZvQ>zx8I(B2n&Vwi+*tBvn z-P*Mvy+S70*A8Rrjy?42)s2h_<;WT^h$AOX0wKaqm>aLVk<@Y(m^A$xe%-m3FTa`r z3X1Y`c>d{Us9dEoJ+gYU@8C(afU}48F|bz`Dp#vX<;v9={>oeAmfD;LbR3j0 z*r()_3|@WXZ8oo;PurFa7(Zb$nlg6mJw)T?Jz2eCC3oF;4MPX_deamXD`}=)d zGweYYE?z>N8nxKHXE%;VUW(_S(OgzLlO(^xFWdKkRBT+ohFT3C{=+%8wOHVZfnsZC-gcc?>-Wc+ znZ1wkDS4jvHNW?H&g}=`>@$1KnpI|9>t6SLU5i#MVch5g*s^*FgGP*D_NQO)v!7o~ zesKj4KKeADem0MT`j+v+i_g=nA?Z4#oL1_Z_Hge#4>9fB3wd|OYphu|m%mN_n7W2~ zetz)<6jTl1_37_%&t11-=jB2)%G;lP!m{OGFlIz=p84}bY_3(znmvazPnp1tS6xPJ zYct<&-i00Q!rwof$K7||$q|PhMBR=W>gyY5ji=dGQ_ImujSmj!P3sEKE=P|X!k0^y zlR~m-?OLqd0(uS^%=i;dX4ae!dFiP?^X^|CWyPkgBxJ|{L9MV|hje=@NXg7M-{px% zp5k|p{E5e&ew2!`0#a$P!v$P=`E@M*Y7y68ekzYW@i2#ygm3YMRvsC|>cRaF{)x{%`-uMidUMCGevOO9wexu3 z(WhCpW(8-QJPy)Lq*8HEE&S#2C)uzw$?I>u%h{8TW!ecxvZiJqO)br=UA2)XUU-Ff zUVWS|KYo`v^A};~6f%1B;S?3*{(vv1PV2Nz>$Lw}_JhmDX)o5vQZAL1JsCE97-NPF zV)OEqe6wOPmHkgc3567CQt<>Iyg!%u3+J-CNmEwU-()(<94fjGV8GD*sV)ff$o=~bH8?R4iZ(RdJx?_&j1W4sjR@s&Q`}b%69ufZh?BCh6Y7Gq= z=d<6?gE;5Hb14-rT`NnF+6f%v*;!Sgq7o*abTZ2puVBi^UVOc52^Zad7U&rB=gwi? zqUE&h-9RkbgShr{7(E}4HgR9O_tvp@Z!1qdbt7f@E~TLa55BSxL7aG7JukibD%;k7 z!;Za86xX()909_jv@A-Wo@I!}9eniu2b}xUyE$yk7z*?uteC%$Z&rTI@G;}aDXe7h z;6ap>qs>=P}F}oDOVw|ks`^Cog4Z5%cbmXZX;|vY}&XU^}+iL>Rv=`Q;Y|0xsi&ZJi}iv;WQocRb92BZkwjXBji!dX_I1EhQ~-D6Qm~mq$2)nG_yq0HP zd7b**`>5Mp%eI}h6m$qwH(o)P6mQO&%dr!uancDVVu_s$9@q!V*636VOBa2{^w}Q~ zZ`i_))NrFrk*tJ2jnD~*wKC(q_gL}uXEd}WDeGH`(^ki#1&g@y zo~IZ#;y^5sB9)9Y`=do%ebY^h9C09Ftq}2Tyz$assSWkzx*KkywWXcCO>M-Tw2@gv z(cZe7MGHP*YlG(YJMSdj+Q!Zud)c#d7fK1rx>PY>$UsU$VH#`q@cyjXELyRQZM)k% z2yUZXNw?~5bnjY$q!vr0O>TdxnI+4Xan7~B;m|{eaM+M4-g@rOeDe7Mjvv;WoZKk= z1`lL#mEy?5N3m^NBl#05xcS!G$P!3{EU#~;by}x&TBrT@?T6P6_7^s#(XJnYugH&v zaMDR^%f=QiLdSXeug@{}^KZH3j^DC)`5NZV{}SyQK}1a$VL>zuVVxwIPJ6_nUh;rW zk&_!D?V98f%eFi)=HhCPI@y*)LN+>;B9%^)Us#MK4N!Bv?BEP}Cc)pr&ST1HQ@Qn? zCz=0Q7ZNhe{sa2*-pkK0WBLrP`Srad_H5*_H|BadR}!Ip!fG!#-eZoH7=Aq=zz&BY z*~+=+ol52Y6S(E}U-R1Q@6h0au)~DIVGpVR$|dP2qIm_LD7nCrhHp#>3vGo>%%O4- zmJC9CMG$=jmUfZKWX1{+M%odQ2|pCy<@OtIqGoRcH{9|YR(<&y^H$b)LHve}rn$L^ zK?4SG&jSxoSQG`J36+$ybNwoWEeU%WaJUZAwh+oiYS+{kiQ{UdW#I_JR~E7a$wbmb zH98K;1M8=j)_uhR7OU2^Pma}BVR?fNn zGU|72=QnrU&e=b`iXr{_bL%gENivzDC?XAYM-Ve(;tCT^3OgrkIJ}g?LSkuH_0 z&&xrlxQqgXLyKcIcZ)zpC+;B5XSFC2@ay@f$O+Pt#I8Wu5!5P=Gz!Hq_0tLmN|6kR?X_U zb4aH(wvedwUY>pGPb^-(iJNb~laJ;t?F77v`*`^ zPWw;Tza%ll=ku?r+05!yYx!*cCw#Pc6$1y3AkR^xo9k%Wx08KMO;q$7Oi@`8r3GQa z!dE8%TX{gra!Cotkj0WV)FEERorCtWW<#V?9!-ZFTY^^ zyiZxXZap>I>ku+00B&Yk^HP&#F4etyQ4((F=HETe*vZrAQV^!8u9m89)l_$_rnD%J zh%jt%kx+;oJ9ZOyGzy87A*#BRQBjt|AOG|?Yu9aIN6lWGxPwZ$v^2KUd%puHDX*le zq8L;Pl%}|-n3c;`vUT%znp)c#GkzQ|J^xo$u2{*ZpDkeV+T9EqFodX^Kx)ThhEK75 z+gcuY=u!66H3vLdp`0kiMTLB|XaQ^2Ze?F>6OQAvUV(5O_B5pE(rXB%6EEM*sGZ=6C!S=@hRv*AzX5?wVQvodXT8h1 z^_yr13&0o01*mGdUMi*Be?(0D`*uZ4C*%skxUTEDP+Ka!4#Jk63#K|3QCD(?KunC9qu#iZpXljqsWAGtVlyspqCrU&s!Z~@AmgKVV(+^m` zb_2Wiw1UV*NDC{J&(Og`ng0BnY+Ap8>C@-2twC|v=!3B(9)UP`tk7tg#!a^J{7cWV ztG>|-!;qjg>%aMm*WY@ZB${+8&hyW|%z}kW(aI%OznvGJ|10~NnzKlqI<3<>tS~_gsx{4p4a{-rJegh}|=yZ-4Gl7bdZVc^T$xClcXW9jqvwPz=j6Y&5 z*WdUn3QEgB=b~H}OC~``k}^Wd3SlV+p#{>i4c&yyM-#@@8g1twfRNUt?E=sc#egB# zX~hb|p+}y;t-rX4dwzK}Q>UKEhAo?ov`!{hHlQm-*yQHraro#F)YUg~>W`)(MTk?+ zJ)cCZjpN6T+08b&IW&r9y6~F6N9)9pK>S~)a{g79}9lyPwSD$%| zGftnzyw4Y*WC&X)49&3>;?BEnVfD(d7&g%uI8n` zKFP7;j^$@p-bhnxjEd@BJn;L6S@z*frc5}2i!QsCR;PeVEfl4ES^G7Iju?m)Af&7_ zU1cFegej9wVDHX#j5us4#l;15>t4;I6UK4DkEe3f_~Tf!y`C;5r3@WBfCCRcfImL? zC@F0bH+u?BIb|}JUHlVnx$@^6KIUYWuirwK@&bk*HI8morTplG@tk??<)pPFYzc;q z9L@gwRWWVyNnC%+?WEEcX$)xTF=RLwUhrdnd;OK1dB%AR9X^7eUVaf;SlB8-4sp<$ zxC=_zSV|K@deVXb0ujpR*1PUy)AG+b`tYN;_J%tsDJ#LsDd*aoZYI8GEys>OnsYC? zl1;l>`Nc1PiHV#uC=bQ^zzqOvruDYI{#gb{KOl0!pQS%zcNGCY{Ec@69D8LMRKQRmf#Oy_j&KhAAgb=J!v$%!7Y@h2aDDLutck z7!m*>l$1n>qaD-9du-zm= zh7JE3AW2~9FnAC_YIFRQmeIhArBFx}M`@e16(OSHC@i!LW9bBr2&0kMx*a8Q&`LnM ziTZ{XBB30bVrkC3_!=&`@NCXG^F$C~lt&li>rn#Ww&Tb=v=D@J8c6~~4$8F=mIxFh zZJj`gFpet-lf<p1Vy3pxI{u?QW*tD>N2{RwyO%O}n{q zAZ7Yd=6F;rU@HfSOG-qrw8D~*LJ}g0z_hC?EF5fvg0N7a6CgvlgbcqT5Y`DV>eI#% z7Pf8!ZIhNcUjHW%Lg1<}+NTh6o6$1gknakko}h4XgiDw(K2;sUa9N@qEEGb7aFj(_ zLP(zLb6@yLQ8);2N}4_(mz4B1logg1XjhZACAQN7 z(k3l)iI75Jk@mRWER;u;(;_x<)xzFA%433i*i9(Lq-e)iLguthFmgbBJrf`|eZ($i-3pFxWV0zt?EO^&D2 z>eW3I2|^B~_kWGK-tfs`1j{@EU?hYvu}{j=TJ;&BGJIHp7@JpWB(os;Ynv6uu;SZT z!Ur4?kNnn;eatuI*`^(rE%=Q4?!FIMIf%gr9Dv3}i?Byys!SZ268NO2e*JBsy?9Im zWu@@?TMLj8kE+Fh1#N{*9}0nTHBu*-{_=CYH1i|6^c~J^x7o@qZ%P)pbz05nP|66q0)=YZ6P8di`IcnKNpV5Ef(=i|%q zSs2X^!%Hg&ArR76Ixv!7R!|RtmJve^jyBq|c=r&1FyeIxZQ97|3$VbJ2DI5xFV+u? zKU5IT&IJ(?L@1zc*Mzb}Cj?k|0hw?ogzL0U>$Fb$kL`!|1Ol2A0zp!T3;^*KlZ_6TyH`2s|skTy+;vV;(=L%0W4fo2Q&!R(~*#w3}j!oRAd%1?KO${hj({j zbZ31jDf29TB$N*cRR%m}>1t-$Re;Xuc}fqoWY%3@Q&O8Ul#6y0Ius$Tl~I`hI`~|I z%9@APLZgJ^m0*!AmxWK{EHbG#u6JjN;S#pB3)1y^*2V|9xJi&k0mD0_C#@Z%N0y9N z4HZ0__PnGL?SnuaG(o2GkVa)mfD*nwr~vGYycD2?3dT=Rd4UeH^`G32 zFqIjQ%D}BGPn3(Fq3)A#XEnFSshROmTS4pkN-0u%{hwXcpr2G`+zFo?Ju~-2 zke{0ktE>P7nmYK8pCu#bt6XS-D?C}gpzr-2^V`<%L;q(HJZB(Bi}Gsb5w{0fGg&Uv zpnbm|1a^7?JFU|?t!t8M7b%kQ7M6Uynpn!oa#d)2?JQrU zM+dOXi&gUeA3(JLL21w_6q*!v;L*z{rTR!fBBeAALoXIk0*>-QroXWJN1oaMO9D9K z-8Z8J>MLDt-?*Nw+jo%m7G+0}iLpW>h?9!fv-F$Q#L}*LTLu52f z%!=vD1bHz41y@T*FMC-B)i<^DYnUa=1T;4{ zv1q{p(n_Im5txJ_<$XbFh1BiTY~943rk2cz5k7<#MpY!(4B*u!fkxp7JAf|PJFUz( z)mZ>oppYmL_HN<>dPD4;0YP-=OR`$dw`@!rG=li<=XeO&lZX<+tB&?I19+PZa~RuE zNG#L8835>;cb%`HEBx82zf*B@C!wW(=|A+3UvB2pEENO48d(y9nMTgcn`{%%3GOkrwvh0UX49R|pd&gP^vS_q!Bi>reJ@-FGeRI26lFgetcUqnEJ#taWeYp&n{b6sj_gCa z?BzYPC>oID0VSbvv%!dyV9kmp>}ziEJWbz~jMp9z^}wF+q}I^fch_&2H}_-ThZG!} z8i?on@`TrvCdomk+gQGGHLYnfAWdiJo_#PWz39u}X@ut??a;&mA!VRLni*LVDXpxn zfDW>uO_N&qe1Hg8w`wK7zTyBHp73HfzcViYo=QT2*2JLu&IK^ z$R2zmm?Pk~o5=J<_T_lvUHi~Gqg1lDW*d9=?IZ1d?*BnsLFGipk}~CG%|V5W@ictdJHXih^@BeP{B{X$)v*%6l^x+*lC^CX`Pm_9~=bgz_XQkO$&UF zpo^9%5{aY-6dZ5y%sytyc-nMOnqP_!MErXJNbKBP%B#DgY#ZM@=ZmEWi;KUs3V+Eq zAS)YuWEN`|9i)9||7%&EJI||w0^yKK#Bd#j5Q5UOa;mDTgQzGUNVsl_eGP3M`LJI{ zZxPlCt!laV?wj~v@iJ1u(`D3vgVqcdS>IczJP?#w&IM`O>uNaX)RXvn)kZJDApo{rR?X74a9EsAiXD@PcA{hrX0E*`3 zCfXBDFk7TH{!ugb(tJMWb?*JcA87|1ZGjb`Yqwq$M5A77_;fE>b?Xp?k%8y7cLZyW z{j+qjv+84#hZI7ab`Lz1J{M)so<5{D-ci3z0;xTTcbsglH^55q)FTfw|BKH^(ot_Z z)BZYm27mT+@Vto*qZhI^BN}01K!pK`uFyv3+0${xo7LJwd5)U_i~hZoHh;c@{Iby_ z{)vHUm&|qlg6Nk{>$FbmwEy4Q51tqzwFcs>{CWv*&iaI=hGr_tDwuHkSsXa17#Bra z8CVi;YvpgxJ;(Zu+vwVRFlYYw9J-e0vU2%SX1(_z`|9f{s_f3RpPWy>9u;g~|1Iyl z^(Ncv+lk~9FzMtUama`RDaf@bDlP(P(YR{^FaGT{Ht%kxFq+4NDQ9x%A%h8vG&{C! z=G8aeX2+g-@`|fDZORme4;_H?&oTjoV%O$xdH%&$x%jHvs3^8sy?PysS8U|mGf(7& zXP)Mpb=#<{>dw@&rqQQIl_Aa58Z9)%1rqE6G%n3`+j#l4ne5!QmXOpaCDF>IvA%}K z|NIp7jjaqAb}&CW;|$6p3YBQ(<)@$Js}DbB%A~OzKXxRae7t~<=YK{hn$M|I&td3* zDq>B0dHKb6*sysk-MUpXX3P=1GHX6pU3ob@EAkO&Ea6~lhsXc;Ff-on$>kTHLnPh6 zn=?OVXG4t9V~*tPNk{X@Ll3fTXFYuf9LSGOpF-ElVu}h2u|g(8d3VhkUVnQg+xIjv zX3Wu?c+v#IB1yWfo|j*n$*MIq^ypU3nNvofQf=IO>upq(*!=Wo=hC}-H6PCTfKNYP zK$jl-aoQPY(Wh$>+c&Lc`dc&Dx@#|kh7MxHA&0SIs3-Su}*Ty+~m`gh|O=buDraXvb1BXxp}YuE6`J9B7jZ|CRdj2W}}`rFkc zlkN1~e-u;Cm`Z7W$eeI`v4sZMx(MO2X8BUyoIaD5lxE`ODRj#V@yVivoN>X$6o^Lt z_Uar)966C*g${4MGo2-?YpAU3#-t;MGv|XjTyV`zR25mQS-qMi%eQg%=@WSI`Da+Z zdJ{dm^2(5(yeKcCN8mt06xH1ql!b2xDH@$6S= zGkewte6eIL;c%2oFPuhomr|y`Gn-{!FQ(^!!Tf0IG`i#`dHT8688z-y4(QhvTWb&w zI@Q43d0+C;ysya1%i)Skr?GU!T2xL~ju|t8hF!b(+lw!7-c^@VyQ79#Z@tCNx)%Bk z8_798Ig>mvKv-lQ6Proe;hhtB|8yq^?6gknv`)*me*vk!M!PXSn)x^WKJQZwA3L61 zyLRxCv(IP!h8ohI=RyFskPPb6gDDe_Vd3JXJofC{Xi|JSZyw)%y^iC@9z)HBjhr%h zG7Yg5%NH-^?N?sn(8EU&u{Bp+bsZaPc9Lps-hG|Ruegq`-Fng5+R8;2 z|D2lbTd8l@%^R=3#i&C@bI|YuX=tqFFVDV0ePesz9Tn0X08cn+5@%g}IbFL}^Z5tw z@bx#}aKwaD=+(C$!b&r2NM9zNcsw7>{yTqp?r$U&Ecj$T+qP{Ym5g)e%{S9j-^?Kg zkK&$t?q&X0D{vAqZn^qWUVi0eMjUoH)m?iSH5B18W$LM%^WzKX)vbc}X1>Ai9)6UO zqYq>K`t|(c7gv%%v2ej6X1wthZXp(L<-Ipw!-^J=CfgUJ zLAo^U+`x=E9}ojJZ(Po6(`R58mQqrb!%4@Fqer*yTz&N~S+`@Cp&e2hr4+IHT3&kg zDO%gxS^m``F8s;a6qgj!xA%VR+EZ&(Hw5(R+JzHOIF?krjXQpQ4+$)Ul=Sb@i?h%B zDaV{J8B53c`|S7FRo6gU<329``DLVqP2WC!x#rp%`Eu!MT3dGW&_fSXTG^e0MvUMO zzk8UcpLvm_@{f;&=TkPaac%o*xafjQuKkdU*?dp6FF$)7}{sCaTm`&`wYDX9L$m9 zCX$~Q;!l6Lo44P2o8yl?hW9_1$K%hviAu$JZ`KU9?)5qU1h{GD&3uQOZ@iHq!wzEb zkfDS`3tul=$d{|Oqb0QLt7q1muhW`r=abJr#@ge40X)QH-AiF^>BXs@Dr5SiaFC~V!N^6uvH81 zNK}JeTE>{8j$-jw-!Oi77nUtu!bunW60Ib;#pP_T*~^GQU75LT8|_Nr;1K`=Xp@b+ zbJsprt=Y?qufIdDsyq%H(v$a>{tkqNvZB~IxwJIZGJ53xY}v9Mg^P@Y>9t=^#tiR; zY~9KAe|eeS)!5lQGD}`svok-Yx~hsC6{BwV3b6C(KYSzycF|brUA*%A z3!H!b?VK{{7{-nq&N*kC#{5OgXtfF{?=ysnQ%**ZBHq?QWvGFz+tyLpr5nw( z%|Ro& zldn_A_-3>ho4D|kFRAJ^lnbu9f~p*whWch6yyF(0eEc?2kzx)z?sN_t(go3!5Gu}V%*t^p@t>A_%ogn+QU!&;pW)B(}6EtEe!ZPwkjU zrgV(^Zo7rYo_U+5+9uL14G3j2IJFYsdGOMSIIRt>RQKwQD*#(jRbD_tV;yM>8=hJJ zER%tWN4|`gFrYP-M+;)=r9oOKk9SY#G%q~;BESFr6YQz2Bi^zXoP-y3DG)d`G&Ycw z`J~bz;)ygTOq#^mKblCgrJcNJ5oP6--V*G^PrA0}j&ab5CK{XSDJUsI1I2kcl;(xl zwQnEBA8LDW)g~H^aK!MQeE!M%tgor1sM|1dqmc~Pp!Sn=Bs~TU#7Q)>as76_TDFzR z6OJWTSI3>V+{J<~zoxCZfr!(Bt2D00(_PNQwrQcMZ)~A^_dZD50ykl_tbwhoS8&VC zx3g-~Zqlvw=u`~lg3^MdE4*k_FIQQcSi7CucT-eSiWLqcg`j)aD)#K!iY8@}gQQWo z>Djf6bTWpc%w|JiWl}-3!`Ag{DX*%)3R?)Ny?8tY3Z%9{NJB3pyhIXdnEJE;5zgi0 zv(9GqiluB=xrv6BIKu|_WzmNpbI-5tX3LJUB`>L(>NXl4mgBtjiVe7blE7^ zF)@b99L1)zxlb(CPD^VFCsaanOw(__KK$&Gvrq`6whZT=*Jnz(G&Z(VURgyN543r} z&2{~I3zXxa(g{O`qzwnBPnV>%A6Y9ALUj0}I{{#)by}x&+J9(2CYBV@^N{Ln}pN2|BwMeOB<62X)${2 zk$m$0EIyb$hoJ`_h?LS}m&;1s(Kh8>`Z9Xh0G|BaZ`j)4aKMlQiP!BS*3`(A*IvV! zKmG|_yZ1y$3#lE_$u^RX#?gQfSkh+rkbZo*;3Mkm>Pe*qv6M!+nvH9gQ&rWK^Dn-D z2~(z0QdEi*5Dw?i-c&~{mLQRIyc{M||NRdf!p?2$X{p^uthI$DE52p_kt30o$sjlJ z1{#Dy3k^be6hzrGC&b}L9LbJ#t7)#QC!S1`Oe-q7mebx^PyL=+k|`TUcN7J*ioUi83VgDh6Iq$+t8Gqu5gu`JZkdrT|uiZ&3ktFVD z%Da@2h&8cq*Dg{iiA%V{yz+aXu(X11J-XAcTRGFFp2q2?pU&~)MibVp)Ya~!EtU2X zLd^Gib}wVi@};C=F=BBCmwZYpy0CZ4N|Nz7v4o3be!1B&Gz)tJ5PV2Pqw;w(+1ha#;l*_jZKjDTeucfVS zJ9*s)Gv?@tlt&c>;S}$G^eJN}v7iV~001BWNkl80LU|>J~ z_~I;%IesFp2qA$kT`IZ!ic5L$-n;l)WhIGtf~u-Y@=HoM_reQ!@u|mHFsG7jyY?~U z$Wswkl(FN-@$l16vtaJ0Og#Q@F2C_se)F3LxcZWdiKjK)_CJDyh95y=!(K8p8A+Bc zp3B5@ZsYGC{hfmcb^|RDx%r%V?pZwX$3O7i`*XSQ%#(nS;l?u!%!L=6&EtQ4iEr0$ zBGJ@HNw5Bdga8N9DxdPwZk#c36t~`TH3bzt$c+~9t9$OGd!HU$`qQ8A>sxQ4qPjnM zIXT>U=QSL2lrlPvxqse#t|Bc!*zoKAXmvV!}CBFt|@|Rxe(P@Tg{d z8tj3?M$xsbD<98zhsR%=MkruS&hq$JQG^mqJ9#3?LhhJYk1*Jh~#jryUV%Xrm+(E1!Gry$i{1EG3Xy884nN)HPPH-7tM1&|v2=dD{7WvFui^zv8Eai>f&0xDz@1 zgkkJIq%XHzeKl2OIc(hCOm5Uu(9ve57=mj_QGNlVhV$@bH1$e%;knmlm>qTQj*iVeljh zEe%>}WPTC9y7LYmd+HSy%>4ir$>W@#oXgn#i@5aS%Q^qLKQQ^|1Msje=brZ??tb7g z7Jm5+d4(nX{1@kQ*pcIz^Zsr8?BYvEr$ab7rC8xYEEz&;2O(Spt$Z-^ZJwL8f+rup zmq@yvt1dgABc}d>i_ScemCNSyG$*lH#HQ zaN_LQvzz?N?ue8_yseG0E@eoaq`sk*aDFj)mP=hzD@A1$h-4cru@psR<=84sZCw-j z`32-gAs%ySY;Hj76qj9lFUK5r3_ri5v9T3Ui7 z6{%#Ly>+d0sjMVod)i|&iwlbLwZ@mQ%Cb&bs=QkrlmLV0B+VWH4Yocg9V;t3bqwkfZyK&8_()Yqec z(vlLQIU$;x8)$7y5DG^rE-fVzlC-tQh{cnXmzN-P3Mm|L9iDvZHRgZ$4S#;}5egy} zmUq~Wwu}c@n&cbh#M!&AmT++e#d*0{$|2U;Mq^tmt^#S<6qc8hYeP#z9Vro^BtMt> zeS0Xa?m@&(lWcFJu{lZFNn?d`C@w7{*HSb!wb0g{G#S>>T*@lS2)QYmnp$a&#R*3u zRF&sZ*U(IEVLAC>K_VWbv8ffMT%v^~6ciL-xiR+EwNhMKPL6Gnj5pKP-cE6OHQ-_k z%don89!gw?csx#1OB-pW$SW$Mv>-%07N@ZxhSmxhiBM8jMo6{N*qo%OqKlDZ(*P;j z+v{m)h03aGql4@wX>4qvEuKOMO(?g3;?ffAR0|D_EyPohS6E0{L4-ssMnh8!rCekr zhmz7VA|gS3V;lLUmE=f}I*nE?P0j7J#N%jTQC?a~UN}u%Lo3n33i87Sq#9bB1TD=e zT3X|1DJd;4B`0jr*4#pCYa0TKNKOs~<)tLr+HsOe%F4?SxWro8X-T`3loVr;q^W){ zp}Y$6a>J-(E42-2%FD}$gsgxazf&=!(>m?@?Yl5Q2!T=xDgOnzqn-AD-Le%!esB=z zIw>sC&hPKOgGIY?c;?C9QGgrx+l)UXlNl*dCP3a-81rhYGrCcDQEukHfb`6JiHi(n zZpN~H4?vo_y}Nko*}sur5M|Gv?R@yf8lHaq5uEmYG&Z&qR89*jx^`#q&_RSSf^z0u zIlCGCvR%(nWqCjQ^vW{$*;CBLm%q|{C-^?NuW_IFac2?{NX%v5Haik3BaP>gL2I8l z*e8Wk9v_`iip6g`)4-Y5@<8zR&1;$d_Up`=yMo_6ct86O>T6=P0*<&$EL(<;uH!S| zlR^7L(ZcJUtYiF4x`#rj7|RxY!NMiqGIQ=%+;iXk95|>Kt&O!TUAhd{BeO;bq-8U7 z#KDvm6$CDB@tx6~QQGjS<+8?+_F_H*Zb8dy2A}xb>R4F7u_uDI&x}R?m^3p+{gV7o zvpY=-g&@VIjq6yyX$O`S3dTt^TEJnW55*3sinJ$NXL<3PnLd&pDAxFO@@ZxuV37`L zV|7sM3H*=RECQL-imXOMcT@@SL26K_xloA=6?!0F=qHx=8NEUV<4lQ6Uu61B1&JRS zB^mE}1zKu+(L_VOEinJMDjgb&mP}U6u_3fAHgAVTC|PIO#{z zI4qq<1e39AUgf@snbBztUi`iSTGrxV7A%WQ%7>M;Q28J+i$m4}H~}Ec28vn`jplIZ z$YInswbHB4ew=mD74+*-#iGwvQCHhyg6%O2eyE^0z)L>yt+|J%-zt1GCe6a@ahYj+ z5?eoJ%)~YdzoNc0n)h>nExmg%)j71c$omVW56FUB zXV9eggVHXcP?(;*2XNQDr!%nsepntd7hc==$uqu=ia-Q3$o}1fKJ`Ft(4Qg$BZINx z)guzgqqov!M|E9ET1vcv;CX+0aY+fJJ2Kkq94# z$e;rLCmPuS>-cIa*{Wrk=Fjd#|1Uq`!@tT2%0(E;ZK)xdXrrm286`~nDFo4cmy|bp zEHB>AJ1EAhhNt@CKXag%jqoJkgs=D!^n=Q(oBx?WYk?MS(1ZT-X4)d7LSjD8>UDo0 zYmW~!7)aTz6Et2&nd@u-7<}$OQAXD}C_>`ZF+*maIYj^OTU%QjH8nLzOL_??86ccp z{y*-ZeUP86T9Sd&|7iaw_TYZ`9q;d#pBdlZcf0TX@c)wiTP-KP=d=G>*%`v|tcm&G zDEFUfoy@iW_I*44=HI&R-@5B}`}yCiS;h(S?~U8w4eZAd3qjYeT`4Xu{&&jmwEs!= z!+Qep6e2t)n8%5Wt2LJ8pi~ma2@?w02w|2sltqU*o%OoUS_;i|_;@Gtxxnzj2`M{# zv*S$2tVsShO)-9kMaCoHLzxVtVfK3GJ&=|dFPnp#N|C}Q6ps3EB6tevNv&xeB9&Bx zLN-!n0T>@Mp%6l%wTlq`-DL&@3hxPY*2K7-f zTh~<04LmMh=~=DeKV#avUnq0Trn8<8KzqtC!gz3W2F@USZC;t>h0_`z_8>AU(0)BK zfHMQaR95{0Anv+2ZWfXl?od?TuYYhvP$q>-De9`uzI< zfa{GjNe1{TG!BZ8w=Ggec}7d5$UK`!r*RdyAseJ18^EAYt7 z4n`P{VlbWkJ7*Q=*TL6v7JeTq836SEiYKt4p@BEvc!QSKW|B?bEN_!$Xs4vk+8F%@CbH&?)*00$DZET_p-|pS)#y!o z8*8aigv?7->r7(7I=<&x;m=pPjWi7K9 z`=9E}QLB*n2djZXvCdL*^%kUnwv6oKEW=;-=3k#dRQKk@Nt0Q>Yys^QFzS%ug#1O1 z7<+eY*-f;pD|wNyS&XvXj#keX_YxQQ3qZ&_>Nn3W09z}=@#wXYlTPu%6OYpCh+`Rb z=)r`v#`2EQgJWPH0J{Edv*tz?C=^1W-847d{2QiDJ)Kd99fH8}pD<`Ub9qNn=4?-w zX?BIyiiXAp3QG#GYzwV4Uw^q6N5jE~jlv4LC)+Ffo$d;}i)QpFL@+jk?Emldynp=e zA7W>(hndCkp8zfzlu}%O{qEP#(*yWt)jEqUu0(H|FMXx4zEbB zbnhs^f4_mB&7Hk5$u!hI1ML3UBSWSA@BqJnf2cGa`{$o4zhfExcHLhC{1XapAqgvftHOfcVZB@6arsvqJgn zq7MSa_x6duRWr8`-|6G` z@1o7|neyhD&YCD4)*gX(9Gm?M?@}Sm_r2G^?wT#sH#VcRV#VT5S+sN|akA#2O3~W5 zhcA|_BJP48L*>6NK%w0>9=`u>KK^2f;g|EjtkXfA@vhB|{qhe6eRW?y&a%C3Hy58X zm1V2flM2AJLioE&Z&CL>h^`R0o=fJ7kLR*s^Jb$joTYB-?{LYki`OrWjXSvZ#$U3d zK4#(?gNJv#e;W^=L2Jg_qH#^^TLb#)S-qA$&22$ncyDxbA1B7bd9(P#gO8B%>*&Uq z^ZsnM)i#n*0CqYKBX7_0-Tuk+nc1!j?-<`~k{nPPl}@p4)pB;%Hjjp2-mGlJR$OQ1Xd@0r3E zr0!754(}Kty)j|#=elNg2W=uuh>jHgZ1A>HuK!Aw!P=mO+hI=@xD|vM^Bvm3f58PO zKq80%HoyM9hs%^IzB?KG{`cG4=hp0`Qu<$MKe#8*;D!`U4ZGR3r;em6v2*h1+N~SK z`3|n@;HVHDfRAU`5#ZraQ4-HpUk8X1nzqjxV#a&m~bHnXE< zGci}-+F`nN?Mg*SAw|9WaK*L1ptK+lH_^(bZR?38B$gGSs#|x;N{WzZVr>m<-?58C zQlld|R9APQyr>XMc*z?8Xkx96Y}-~tw*mW85Khz5)J{`#lAb*(*}8QDjcsYHNR*yE zx>FoAeiflyY|CQOsizYYCFB5ZqKz#(cF^9kn>~AKNxK4}AeCrg)28jDT}8N{h(0~K z5!NpCJGZfB^=hihi|F39lI|5n)a~2NzI{!&Ru0|&Kla`{I*MxR`~RG(>h8=5At5A? z5avN<5m6LHK}8e>Q3;v@A|FxuKV2Qx1Q@+D=SlV)u}V?z0Y@lzqz@jB?Z6xB(;PZoVti(qjivj`wvkXbcm0OBPFqd!o&O6 zuyGxw$CGK?q!B4`K8_deqo}A1E2$Rs^72Ry_^2!|q44m2DnenBQj(~ZR)qLtz*S(VFbMe5U^G6>@UwVB&D<_#q099mk}EljRY#VW70bp#!@(SrWqX#Zfmm zkMzUo=2@lt7ETRPGyhKdIUEF-22WdV)iRM+iGUYS+o3PG)V)h|6VH zTvCp$9pX}Ik(--KJQ~xAMxRY$kxgAi@u?FO7M{Ycig2nV0?LPp5DFD@@L(a8A(L9^ z>15|*VX6q?2nP-vq`0gSGd_`q`3;CSt2lIEAH}CbB&K9gKQ9}@iy}ISy|XsRTS>u!KU@= zIaM4auR%V2uN^={Iamg0r;Ngb$0;re5ucJmUcGt*Oq0^$LJl7}Nid@D$H!BzK|ZzO z6=kQ7ao~86hK(AM;QLcz&VT1J72OndG;|U*{1p-ja=Nk#BR+}bfQ2J&GLEU-2&C4I z`+4Oa&8q0lwcYTHKA@tPy#Of?QlD*mS`Zihsu3`lsrrJPfcFaI}NZ zG|-VC<;BHFLTwTf;<0K3s{Wsf{OP+LrZNSm_J z95JOGa2(33DhY`}YI2fGFs~GbQ4{h3uCpEi)9<~v=g36G=e;058K$c_*X*6 ze`NXh8-V~+GUwB`nfd8bI-PqiCyyK;Eu#UGo*0c`RUa@`R#h;6?pGW+TExcPMf4jy zjNyYW;_J`n@Y$yeY0;)7d-m=nH@_jzO`FQ{9~U$6iN|T%ts7-UhcS~fd2-4Nq?H}z zv4@^z>KpHHXx9qvee`LXweLphp%kBtfZLFKl+$R@D#sq+R5GH zpQHB$dDx;^zG4HVCrjwvvpwa7CJ#LRGTGT#l$RD$JF5{-O}L9t@H8Vw+((NxXOWjz zhZfD7a?8Er`DyVFv~8LP-U1^6zbs!v!NF4uzwUB2{W6~!bAF&nyYslPb9)-}>c$td zKjCCq6+5=drLO?wZJmYmG)ox2$K%u8I@ zz7b!%_ZlD0TS;zS9vNxzjJ@YhzW)9@=FXc(UV{c~-LRXXw+`j1Yp(%O?oqcPEd1tc zzL>j+%zC-(+qIQG!^Y72qK-^__%V)49Ch+qFyf{gNpMc_$%h|MTB#{GT*Rcw&ykx| zi;(SO;ljma*4x8?YX|b(><=k(f;{@f6D*qhci#W-bF%9<;>6*-T-s+4!)_eN+>bxt z{dvo2-nuOZcW)r0X=na6czcZT)dk>~->wHQ|%W%vjY9$&dRZiLQB4)kuEtg$)9W9#W z5?7-Z|832x-RM>*ES#CaE& zKsbqMlOMuD+^O_`HF`DTlrU}bWOfIWdHa=#9#jXEp$MKj#Mm+SlhWcMCOmvMse%7X z9mPf|p~{O&`=jg-D9|=28)YbLF|d_^X)2fd5*x(CP(F{Bz>Q)W62Z0R;)saH;UIvH zxW>K;cxpS~S9m8}06rY$qRlO(Kq4L=sSoWbPAM&zhWi=!ZLEKy?f)wOD~kM^i>+JS9F(oE7r>C z9V=yEziVXI$r4$+WVYOL`v^H6iO8XXHPW$LFZp5RR{8FWSQy72nIX zHx8F0;fTC2{sEc!&N~vcLo)rT(elvLnX>u7e(BTwJXyPYj|3y9Wy`vS(!BFEvg=T( zXuDMGa7gT`BQooSNpjDVvm{h`M8=G`PTrjNqf|OtoZw-(ZNPmx}EKWzn2Z~8%$@g<>^rtY`uDj?juaM3 zq^eAw7>!e$!&a!&fZh7OA&t>3sL!`nEO4uovva*wM<>gn)`mNjL(BVTe@R~ky z@N}tEiHO!(M2q_s3Cr?t-jeHY8ZM=x<-5;kNxvIMNU;{NBS8sAf>L~}Q2O=gDc}6M zMiwt!Cf&Q7Cnu^ZWcQ|3(jd(z8xHM}36DM~w_HC+N-KjB3GSA=N8K)O&0Qf{wAhg< zv7IW}w*E)y+4lxHrnSufbh-?=?QS{hXbC$Z(ZO9Zu>Y0v!`jWVdeOHsXkdTYeX3Zh zDvRa*hsMj`n?^~|p>@*v{7YozhQkt$RLM(|o|mCRZ++~+D; zzWjFy*x;mQW}p8#iv0 z)2C1W!>?t_mc_0;apHu`m@z}N_U64rMC-6PPEZc5`9?C*lI4v#OJv>8Ur0uBk_>-f zsuZ8xBmJ-FDt^Q9mfr@SKvcdn8A`dKpb z!*9Inie&LOuS=4ZDNn!hp_~-)+EJhJ%<3BGfAHI%i?=3fEwLKL`pNr{9g)L3HcI3A zO=ZCKx66sDh*XIq%jUl;jZ+ilk*PDKw8p!+PYa8P9cvFqL_|m2`4DRZ?^-7$BDVWC zCnCCXzYM(mB02xcTclh>BJND8(Qc75?yYrLbZDPk+v9xceB~`t6|J{+MB5=bS@63w z%m_%&L1X1;P{h$91qB5%`MD{gV=oz!%927EIqU{`@VQr{Qba_DL?k3yLLxdO>wo)6 z&hOMl8Z>GwuYK^j1VzM_Dmi&*i}dZ?OLBAa<>{wil1dSAbd?0l3uW|(Tcl2A9l7J~ zadPZbsYtj=%1$4XhsTYTy7ls<|Ikr#q`XQT9g$FJkvuZ?PHB)=Uj|%%s~jt}y;iA` zna@v@yqvnyqi0XqvSX)I#@eDvL_)FF{Px>#<&Qu9_=i3HSNY#lv}X&fSg}I>{S+}? z#-L$XScZjZn)u?9xVT+&4j`m)|B7s^n;iCOI?L4RM<$j^)Gf z8`R56AtlbCqM{0|OtdmEOcS4BkzFT~U@(lTYogE|>dXb-i(!zOo=Iv_GQ~wjoGREy z>&~4BB>V7VV@kx$uoH1J!=ji&1mXe=8gc{kSFY#8`OP_W@Hn@%Y|O!(>zFv{S&mnM zS$33?xcV`a3*cp#xzcN;+Z8j4Uw6^9QMapUb>F)TkmL+IEfo1@1H$!^&OZN-6UVpsu`GDwRv&Nu=<440b6 zFx=w>Z6icbhJoKS@JW~r%NFwdE3*g^Px#a+Qk%4M5qXv%x|~D%cd}-~7KYt6ihy6C zw5HP~9XWlf0Lwr$zm!077EPMuV;ZKL>njn6Vu}C>ML2Na5Z5%yMNE_WIkm}3)oj|f z16vG4{P;~bn>s#D(Y0+IR;^x4$hWSgH7AEQ&AZr&T_&33bzgX7C1V@roBh#*s>D|0TV+T2sV}h zrwaG*^u&o26qOTKae~6r0S|8H_OfXx7sDqGN?gV1&71a+on4QVq(po^MTb_+`1OYu za3Vv%^5G~SmgT2o%Uph0{WF!?aSwtGFZ11tKK-$FHT4>vPar8CD_BK5HgRS-r;3Hm zTeouCjW-g}HnxWL-P&<*{}F;AO|#~WF-;T8@Nw!$0VStT@WkU!ks2^Doe0f4cEG~K zz{E5K(Uol8ww))R7*8N29_$D$8@I!(0udjUFAl?0V3+gGj8|E(^cM_YGW)g^(C*@k zUA1kc!8GuaE0KsM4mf$_C?|pz`Hfm&Dw}$_b#b)KkrPE|9K_Kw1t61gQhJR zIOIlp_vy{C!~58=>i`|QT*jDDH`1|PV-_s>f#QhC#HlZn)gYf{`8m~aSX}HTQo){` zTiL$r7!|<~aVe>^YTJR_dRYX3Q1CQs*KOi(;Yku|WzfFE*<{yFzz&!2`)?aKbmSy) zDJgV3yCW^yoz37I`g7^Uow4lGgv(Fz`|m4B@j0B|r5UX|pU-vIUq|Yepjp)#( z6$#?5iP+Hr6=ct@t!&=5kMdIosX&2cRp)JZ_&m2nDA=-s7bj0;>91S3qFFa0KpfGd zU7M2PlRP(hIzxuvNu&H+rcHU47H!+nE-#h4?-)sb+wP3H_fDR9>|x?^>T}OcJ$UJ< z$0;U-xpP0`%{SlXjdwn0{QcMR@kj5o{Xj8uzW9VsKKX(P_dm$=mnSgw#p!I=aftUm z{D4p2`H)A(j^_DSr?X+vH_ZS32j2YPBewmzkmskqz{FRlQ#a0!6^j7=6$SiHE&u-P zV8P`gi^22(3A3-Th}L<{QK3rwI)t*z`FhT`)N9#=`^VhOFTbqhvpEX^g{>vV185Mz zAmU-76(R=O%OI2}_}QaVh(eRA$*3KdkI>d6Bqwp;z!q2T3p|6;HCSVdw%}#4Ce!(X zZhZRLBg}l;BCAOUn&j2v-N`eEPfFv}X;UcLww#Htf8%|`Ky)k>1yCf#`@t^dP~kCB z8fCiIL_+9_(@c405`)K0W5_iZF#Cg#*;oXKU|K%HwhKn~`4dU0mCCMNdr&>k10w7@ zR!q~>+AeiXlsZLufPR(e;zvASyQy4F<48E<9wKp-}#feiTBxYx#urU07EJFyF zRbb=8YGLaS9PQRa(XIvIzCEGuT(Q9}E{*EhsDl&hOfuS?_(u@zVy4TX)1V zO^=JtB~noyuU_5UhO}&y!6$FdV8_7{`rmdAMMn?w%kn>Xe&!q0inADb(@>Pw7|KCA zRUj7P2qNG!;%Jann}Xe2sk99eO+S_qz!1fTmA_L`UdcO?g(+Z}imHkV zcVE}qr6Uq|`Oj}yho9E1A`}jz4cK3Jl&rj_7(O442Ce*P5llnl(m&LMI4KWHrO9iQ z$I1gIh=gt8l!YS@K~Xy~k=&e2UY_+PiAez$y5RFuw0kY4Asjt&l)Q{ufF`+CCJ712 z+&A_Oflx(=;(v1dRp06!P+N82R8soO3}JEN!FB1PGR3YX{rWK!md5Nj z3{^9CRJ-eh9YPT%g5Raci8?_Nc4xlwV-UdI1?f~03MYan%8O1i|C?{9-{wLZou5I(QLNv(hld||j0t0J!l|^WsMJh; z{v~o6G~&%>&8e4?9PMBXQHZYM&6lR|>g**10&cEEo3p#~&c~mSo8~b6*$GU0`x{Ej zEAaaRT-JXW)2H0W@_C;y`jP4Q5)w&BPG#ClFK|{`33I;vinDrLN866ch*r#={WU)= zSi}p@jiyzTT;_cBB^O?M70vQ8nE2pBeDv)Cf?yGuvxh~|Zt-$jqPl$ERh zVDPQu=+vbX@yh0g0oSr^WM6*#Z4(bX@+=o#*qmmy{0ts(I|WA$^U@o0xa7)#T-v=G z?HeVqXw0(|l~htUE&%fHg;)Gl{{L70$24IS!t!NHm^t$u#y>uR6`Qtm?)eu}Co!4e zi39A|xRLseTd{8KMt)xQGuyUp#xyh{9vGL1M-$`2!E!Nf%F74_P<}T$BN~+DW_1CM z8$Tjy-Wg(JmYMZ* zJdAjsLE~mk*|u{#KP~-%^_#c4d3mBpNlW49B}*tPsX!a$^&G`AJWvpDbg8c{f<1;lVKaHC<;oFaAGyBuO^ZVM(3?FqDAHO+^ z*I${%!w-#T?}>6cb-WOt<7PmMmwmVV*Ck}2%+2Ph$Dice`3rgfqt6M3 z!Zc}`Py6<*7(VnyKK}44-hJyswC$%sP9`r+e1P{q_>?^bM;JPM1n*3Lg)cw*jHf2Q zNLJ%ET+pdKmQ*1+?2)Dj7zSr|y@>MTC;4FJYjo<+;ta~0Xa=%~i7&o31N&XYjHyqM zSUZQD>>N@O0*DCTe*HDemoKNdqKtqE>8Z(-mY(Lv#Y@o2?~WsFa@WXP*t~89Pd)V{ z-+#G)9eWO9i6T3vJ_imSWXaD%}4LV)i zm6FmEOndQVX3d((oVnle;P|J&j6<}8q1;T_C^MhymFXI}eFn-(;Fdc^Q?PX%QzlK} z^RK>PYe6AGfU}x5BfDM}qeqWs&ez}Z?z`_&bo@9Cn>1m-zpm`ZRq8fNOUTK z6G5s%0c+N*W%VB` z@CW?7``)|!ylgQSbnA+t94{KG(2j#+#4+jlSJ<&@E!Xw$i{*qtYXWA34VzZ;#pm<5 z=h3Ixw|6`3o7Lm38E>&`-yzCNibzPw^hJ@7n$Fm< zBk_mI>DO-nhbtn?cxNVUTC`-;$dQb?^A76Pt&51sWxe~bdD|9VdFfe99JGS*lP0oq z*>_YH6|!K#uT)lrC^}L|!SzRE}qNJ-+#i|4V!ps@>CZ8u#l3HlYBFOK1C&E z?AW=TQFn}D>5}i5@Wcc7EQ5$+)3y7h96i3DVb}L#{#W0y=g48c{PGKyFI~$clU`)s z?u}$7YCe2-Hf7~59Xra#&=vf&Xd!FXZ{zikKV!|hRbi%l%Z+ayg8*Mr5rv~ zNLhtVMx8p?SftgeO{DA;*p-|vDJ3a01*IT2D~*5?qG10XN`ji)W-SrzP`7R}rc`jG zsF-a9r^%?>0HtjFiSFrJNl6X5r@xYd|D((QOm?txk4PKl)MkM?EBdwlur zcdS{rom$zA>D8?}hLymOn{FZ@Wf2GWZJ}ZA`CQVgAMe%5Vfl*HWal+w`l$QJtDi$j z@d>UUcqM^=AJF9G<#XRXcT+n(C6+~@;?kJ%>YL2|dI9Cf4`Kyc(DuBGY3L-90GP_; zfk*G>%Q;`Mb?a6vGlc=yUO}p5QWXCdBRcy{trEL!v<1-rJBl35o~3M(;%NmF0s zyM;fod+$zC)6y}Ma(R5h!_52oTZ&E;5me`JdGB^4CnWR7hHbR#d@j9vUqt|mbK0~f z)e3k~5(f-}T^AR|M53EwQlYWT=CTQJk=5rv>0?cryEZ`^$chC=tV-nA}y;f z6Q7yDk4sjudHWu&zWx^4p4E)p^aP%o{47=BDpE4Cx$FMNsGXcjo!t6-{MlzLT)ddI z+YWJM-)lIpV`J*q4)DlB53+j0Ru(^p zZYBw78BBX=8sC4vnDQ!{m!>^WmkzC{syNEXTZd3T%Z~}vZ`O)Ig9ejq0TMy502B96 zIfbP3MBaPjd45>Dl)VK7TsiPYI=5*{?OL^X{%^1F-QRzr@Zdh;l9Py!i$nQRd4Bp^ zeD&?u?A%>|u9bxusKvymC-Cs57V8tcS|N0wgST_?B6JLBPugsXl_X`%YX8l^u>Uuuy+O{RtAIH7-kK^0# ze&ERdeMq}@oZqc0Av=tv3`X8Hg8aty*}8on-3JckieA02MAN=&cPdpa{Ftb?y4-j7 zDC*bGBqQxCZoBmsQd5%<(O8xV%HrBVgQ(NAJ)#`4v+6M9hU-Z1#bKxjJ$qeAyO5uM zNiMP21WSu3F4ok_ZcbMH`q-5_u?#oj8#UFngL~>=1aPc445h(vFttV#k2ZbYh=o|F z$Z)e|l?5T&#vvYu1kP&Rf`-{CY}mYp%P(xssj_nVbnQ-3N`Nc6cjful7gKn$oFRAI z$U2qIt)_Qi?z%$npJ02|5Y%=-roE zwNhx;rYXN{{)1!3k0Qzd;t-{1*QOb%rbB6QIT0WpyzqenkC>-L^Tu>+ox_$z#q{fO zDYcTolG=+D5B zoGjRbQx#;^t26j0DTyXc^2x}oPyM`B+&TI-K6q<7pL{u&+wZ=YJBM~gOp}NTU>b@> z^|P?Tm6VhebNFxxVG%lZZkB=kZGY}_C#C8zN zRjM&flZ1o>d_Ex*3Zc-1!y&}5z_bYX{ouIIs0!OeL`X_X!7?FSS&1_IM8Xb&NqoRh zLY##isYEH$%^XLtYVQ1hMFRh$%fH$zRnvU?vp_7~EoU0Y0D21X(h!vrd-6kzx` zt3wxBcj)R-R0)Qa$Tj^3agCUWHt^D~h|kOCj@xfTw4y;yCXTYuqOjuA>D%X8`YO}S z3eyV9Fi5V~kUQ=e?H=D6E^)6Go7#19x$U-*IJSxD84KrKZ~^CCaFNT9FE)l~(o@nI zJfJU*2%;Qv^P2O}*w$_bL?fD}k2<-HxqHkQZ@~veGsL4dMp*$9NLKTZ24$=_C>U9cd`2_W_3OL_8;t0c{rN;9)1+<)uT!CHZ*C`HnvfV zfT@HYS6oGpEBb&ku(hW>;!oi6URQH@uf86!i)P@!8xZ9x)ii9>oV)I74$8z8{?jBT zW^n5*!(uFpja#&#Nvoy^VH62O$$g_y!YT|JH*Z6;7Og#oxoUmwTG2XD09A*7$ z_BLgZoRUUXn#s-sTiCOE4>@KcVKF^$oW$A|VNyA2-~gW)5jT)2#FnAEACLBK5GhxuR8WY|EqZrg>yE?999%1<38Tv0)#F9lciLgBKm+a3|StE%D{raONCd=_=Hvr)>R|KOXr?Uo@_ zR0#pUL84)E=eWlhG3ri+k9>ePXT8JCSGU42%vdEY1my^(kw|uS9TE)1hChDeoJJS( z>*_Vs$vzujyg|SZWv5S5Y9x|gHya~Z#FD=+WZ>oPsEjItdT;G0h4$(fQ{DECi(*9W zrgk?rUjq3Jn_-`Nhsw$z35LbaorPS~?P?mt zPC5meiuP^KR(SoGrTxG1784>#TOvOP|BKWeYgFVPF2( zcmVNdke6MD%Q`n=-}beH?S53AtU}vDM!E--_%A{Xf0h5V@;^cmqf~(UjoVU@9`Mei z9V|~yNm&Mtm%ia*@!UiRLwm;%HOM;!mry$5VTDAZ_&bf*3T1iHZk`H-)*59fH@U>N zQKp5h9V`>dD=PVU`AT+u@F|J4YVpQvf1^|T=8S*%K~`VyMHYPymAM84xbubnJ^63 zD2^(yD8Z9XR563fZEx-Ioq5zuT2N;6WkKmE_nA9t4W(mR9}L0};!WrgH?t)Sd!}g$tVXj#o{EvfV}(F)gn_f)Hy&k1p zUF+D$`sa#>Aoz((sn58_9^kHVPjO}UZp2FvtV|O9X3Y3iI)W%4T5Nne=t(*Ha0~-Q zII891HEUEVjo92%2zz&Ip>wBBgeyyF*rXk!Mhv5QmY>0cuja+Kzot=xe9VBKo_$Bq zsaDAVu8tHdTTvjG=ecpyF!P%`F@z?|RlT|mH!^I8{4jD*RqNY#ZD|zI;d+F4s1xpq#;mH{v5TBgFxJSnG z(wpyaV&^KBE?>onyBiy8r+n07*naRCo)vyRJA|qby%+M z-!b~#&=R#IqfO?um4j;z3a&PWs?k?o`-sGB8m&F!$*YXQ3!@Y52TuY}Tv)o{jTslx zAYKH{tWmq_F;hKYyzzKO`$dy=swLE-u}2-PpJxo#Y~PxOXY8#ds+i#E$vU1Ew4prA zuW~c5&Fc0xyt>uYK{&H--FNv%vS=bgBoblAjveIY=JJoqpS6Q$&z{Ylci!pV*{Nj9 z){X4iyPr^{CNV9GvpaPn)e5p`$#NQ>)qw^XK7L-lhOByxIJbQ(P^E0!wwF!2in#2` z%SrMnjM!1X*M6cw7jgHnVSKgX2#<}wkJ`18Y2LC8Et)sMkH!ub^T*nC96f#-e{wqQ zI-NsyS{&Qgu3%TeVKhF{>*mn0LkE136MX-}FSI)6Vp`_a<3Pb~)@|H^<0x9UYe`1! zG?x6hoU_kAm-^XtDLrz8HJjE_QeH_`b}r|1K9_h^#pZRZ*m}5}3%hn9#V`DQ;V-o5 z)QJZ9xmXTZMwA0js3iI_E6@`0aO2R9W=w-jxKOxJR^w zM_9XY8>cF&NK8uM+zzcs2so@VwvdPYCNXvHZNeL**Po3cRRU1jl%%V%jvp9Ni7aKS4qO80U zUm%{w&05f^StBe%Q?UPVOg1h?!t4ZD^T!|Pq$DT1A_jk&N%Q8-BPS>4FYVy}?=HH;SBs9j_CvK~RP;zjbdajBpaMw*yaW-?4)7`vMSDcI^fQfu zsJg27wD?e_g%Za#>Zqx+ES_epQT<4-p6>rV!{bly^5@}E z!<_MsCu?5d3F#^Y;;?7?Zr*{G}a5s-LJPg->bL=4D2#8q3#X&d%+VZ0elYolObBP(LqD!fW#9{j4iBoO_Q+dh= zUZ6HQ%+GKJ9IY{p|C-bG-)96y-!s}{9wJp!O(L({C}q?IGPD3;K%os+L89`+0q!3) zgkLuA#~}`vpxb2l&HY%vbvM6nEM@Mz_h_D*b%qjzp#aB53}3abwzyf^uA+pAX+}qS z1QCT+7AClnZ~@y} zW5v5`k}|mIj77nJ4pp8Jx^|CRefD~+^ zQh?$yJ$voz9mAS2r^y}5QPn(C+lc8o7dW6ni;0+?TO&4tf!3}g6+I;}#0@amo-~}H z-To705xYpcDBXesht4np-4YdvbY%t&T+b)AmTJ$bHLciavOJkT)R_w7;O%V!qRbjD zIPS5$(x82wbg8%YyD9bV=|(j5(Od4&4tUTasCGc3YfW@E{bdCHXOx;o;J-aP*j-TE z)m>>Xk|NRQl1jal(1s!4QhP4zNJdESm%y@Mg(_fkC@}3c0 zxA;K*CKoAL05Nhx5QgIIUB^)c<&+uDDa`fnaHmqF6m-Bx{s{o>WAl2HyT4@|~jb3#7 zB02)auH^PxhOu(hy6VV5bbBAxQKdGCeQ6yVB>?}>0Q^@Mt+ktI&>Dlnp5Kg!|xh$0){V+_UHDXM~|!M*|R5?_3Xi=Juanj^LF&O{3?bF zx{9=%P;Felg16PqW8o?usk{+5YhO| zs7d0EJyC|6M1ew#INYpTw+>eHR7hMVf|y&bqU(@~%@oHGv^LOMs^=xHktH6GSHy7P zC8p;PY60a#DHFpmVn(jpXUc^hc|D2YM+{$VZB?GJFNXCGCDvSMhT-Zy7>JrB=5AE)LJpf}>2&xY02@ znd>KNOey1+9~aOuHJ^@cT9AlBY1@n9x%G=EHz~pWd%%5$7tygjzu8@;93th%`Qn4u zXnXkp8a2)%&TCDH9#;!Q{ZA#9n~0z+Of>gB@-XpqWToM9)OiM^t0}4w2b3vpA1QD_;?)MAYk;^>V^Nk@M`C@W#2Zpd z5F8W{G;!FD!f!Z49Ko`z*u4bTCNz|yVUtG8{^Bz->t(zBYeW#Sy&#YK{(dDW$409t zC6S3zih`YM`DMjk`rb4MzkuQQGkNkPQtRYl5Jq93J#3ryHVAhdR!3ngy###4HOo~4(;H_ zrN8prtl2cqNhBpsc=Cy-2&86UXpN!7ySs9u?#f4cMiwu=Fon$8nXF#=8T0oj_Q$8qrayr@#t@rp)CO?MP2Rqbv>4QCgl>HchZ z|Bp+} zHlV9DXw6uSVm0vW7b6M{P$tA@@Yv+(vB-ZE4|ztr0m?99^*6i_cnxwD6dF_2pwU+b z;yuS}QTL?hjIfxCn^odYB4r4ssfeBYMC~l^Lxx8jUTy6Nc#-Cqqf=w}MB569foWoG zVi?u!j)y&uItVq#V61Ib)VPZ}qpG@NY83NNiCi_|60!JUG?M4Fk7c_1MGVxd6w$_t zMg>*P22l#5`fgah>eH@h2m@TQb>S}~@ISHq+l@e53zn+n)Awic#Pe@sqDW6mX5h&C z89t~xrs>DfZnaLIJjx??-Nw2NJ4noJ#>3A{=F+npGXKjjdEvR4oT?}#E~PH_j(e1A zuj|RWpXT%MefM$7v52?Q=zqh_jJoGGjN=D+VBE7zdE|e*IG52xkWSFFY$$(q# z1kjr8s}^(Z4a4~8$KPq!FopSF z&1e1(o0;+aSRS}{G)q=*At5=N2cCSAD=+Paa(pO9Ftp~AnJ-fm-<${Tzk^+?f8v2h zrf~B3VQOb)AUX}husM2QGed`srs%|J>NPowNiR;LT>~HClH)va=U84ytHXWw+{~ap z7xDZvFR}2aB^Ze*jJWGTuJ3mNl_w8#+t4u-94e$m>n8LY(4Si$dWoe!E}~=8Y}e;j z8nK0uLxvKclF6*UJwv2$6XU1MqF5(0aKJ#G9y^4g*9~CXz9Q1=x8TXiPjT+qt$6OK ziCoybH&Ex@&!ZRQKM4$M1UI^FBx4@K_ha z%nn^$VO7_vweEGV9GbMen&-znOPN%~&JDlt^ypXFc_5p5HLEgt%tJW&r@5^|8`4ul zOnHASRmzrR!q^G?`s)fxRjkLuPdv%>*EV70PxEu>78sAmVEy@#&Wno|e%b6wlEe6t~wYNcWF_%TeM`y&}4mt*POmpb}rr{E|1{ z`;3CTY&zU{H^YVvCJ;W!Bac4A+D$va%_F03VI&Q%fd{8NsiM7xKpIuX8dxkIP$L&kG~|!O0`LczF0!KAJL#I#ny014%5G zCk8#jeNVm2)pbj8>uq3xfsu?G|2hHXvVZ$3uD+rzHR@L3+nH~& zd&f@3k9m#EojWL3yAdypf0;{bRPnEJ`A5u&{!wG?rKdv^m^rC1~XbBl%cfiMwUvHHcrI2W}|pb`~!OIL6wg zm3S_9RYbAV9{So-g1p0^Ih`7usP?Sm3F<=6+UNzoSz_+tdIw}1W98Gz9Cl6rU9Yby zuJ|Zzq*yC(lp#JhZ80ufKf2cT+_UDm?RevsXuoGWMvG|^*x1U&^1L?^Zwr8nCB8zd zz3Y9en(|-{o@LiN5*zEe#umZW%1acWJ8C@R&CoL?_14 zx8xS}S_$3(PsCVFJy{Hg!~e!A`MdnTQ2ufy&{hg@qZ~c3oBEfxVBDDJICWqbBcFen z`c;!?aB)M#HbDI1B}(wZxUncZ#K*Ij@Z}eC>Dc&D4jws0(>7fgG`KHom;J_LgYKtE z+YKB!c9yharFd`JXXKwe!jsR8q3!k8(6E?`gGMVw!TB>(s(uk~e)bBdcdz5I5pU6{ zU_1PM#k11YYfy`tRm-w|%Qh~n*@V@rR&q)6 z4g^xuczV=785T(8r$s+AYt|gDZr2K|03u$5nsU)tWSu$7*cV^n#vVQC(y=ugR{zG6 z6XqhyrflVkd@yY)3YW1HCNuNv1zhszb)*+B&eJbH&W+bzOPN3cua9|}%wrLze*Ogo z=g;x%s4+CCnM&F6r6D9gLVRGCy_u^8iDNTG7s67elkd+{~n-+qUtS2dwhisG}^ z=FqflM+OcZPU%n*b`nf{>m9I)@%fjt`0}gST+*lkN-2UW%-M5CnLPC~9vL*0YSnA< z{EMUc;EQ?O*`)>leENAh^|+UpI&>xwDz3i~YNHF@5GN{`vAas+LOQ`4?W}y*J;ZPw%VQw(kg|C%nrgHPd0XNAkv-lc`a)DkGmA&v)~eaNYGC zcxd2#lrCKYv0RkIKw>77jIxo!d_qa7y#M)R(wwsl88wMj8~0E%B|z!2Rruh8SyU-u zQzkW=pl6lTkvwwp!;F9PEiNjX%!ubFF?ZIt^tz!QS~ObOxDHgQQ=boKe@8~p!PYsv z`^FnwbHmNNIPPWM`rva$j~>soDHBMx{h$gwMc&)bir}w)9}x8K7T*$>kx>>b4+ClR zsJJWLH^luK_^=S|Tkv!OUgBYG zeXKhYNXUvmFJ4r90*mbh4aPCGngl$^LgA1gl=5x8UYo@?fEo$gvSkZ@m;YYnFINHu zOz6J|DJ3dUzFIZvRW48Gra!QA%NFW2x(XGrQ94H6`5c}bJ(2Ghd`-TaPLq~hKp;kl z)KVE#tyYZ^TuxHt6vt0y;izPSDJ7{`wK~PBBvGSMNsecoqkg)Dp+Yeyy5zJB%2%yK z%@Q#(N~UpW-!9JWTtS1T?P+#RTS_C8DG|cbQE%BO|1bpzDkYijx8B00H5+kSUCfp( zTN!lsKqAo?lU{#^*3nZ(L@ZntB)M2RWlN{RsUxiU?N_=DpF*t$^+^|p)(va0Yv*Q) zSG*pTUV#eLs#2;%ItmzYZ*4BHl86upS|k@MLAg?Cgra!}Lb0;dsaPq4lG-7ff0mKY zzQ~V1EhW_sbH#N%32U=~DL04x`!boka5eLPyql0!fD;XKb)Y!SF0MjhI6#lP`;wL% zBt_?ub!;mxDWsRqphO7=EB^@VmMy3Mn5k5(S%b>OLwqsiC04KBK*UNTP^=tPs#nLt z#f|23Q8|k}yEam(#-&Jl70Q<_W%8I78CS%m?&TM;cgA80!@}lunRM*fj$lCeZRskW zd+}w?Wu4&sxopm!Jx@t*I1JX%0p;R4Q5OERmUf+Pq4AYXu$%)_uap4@+7UkaWIFFp z{Rqj;LRY$yh>M}0NiIRLQmGWzVN}>VwJTV?d?i)uG~lwUno=epbh-9w-gN_D7JGmYNYx8u!Er&H*-Bn1Klm2Z6lu&@YWC6}gTnUbU@=Xn+y2g~v{-jtG* zuU3PKp>kYSyAr2Q><87rxTwTfBLb<#C{?By>145K`A_WFb&Q*C>4WX&pkgjn>r|mw zMrCfhsWNy7QXkxoHWBa^LNK`)MODVsnO%-ur+YDb4&J zeqr^x&3yaADo_!FIRj7-3Fqcugo2LW{yCh;nU%2^J4?1}H0pZ3j?V zumT|p3(uJ*D#7(!Hd6GVCIB`nSc3Lly0Y-;SNLXbIZ}$3pBGtZ@$nx0O$FpR5R6c#xJd8C#|$FhC09b?4_C?j`{FJ>rAG^BXeqJRg_6Nm@< zn7LKrCLZY85Ckjb; zAH0Zd-vVPAW2`Hd6(D4VNYXZf##MrAA{p?(@W%L}4X2?}ph6@iC*#JlKtQ{uf3{^o zG-_CZY%`A4>eOZIbMJCRU6Yqu2$CK!2whi4v8`Zy1JueYVna(fzW(bWBp2?IrsfEi zn9L;!+HotMDZ>B$AJG%}zyDWsn+tR+Pw_~|zW^@EvqWj7imdCz-CYOlfQmB?U0|{L zFR9IcRE4q0{;$@dl(GD25$yj{wZY$)3x+abG5sHnt#1QPNQXyuec`0Xf9VUZ{FiBt z7sFTS6K5y*t^7kkobT~Juu}dm|96)7%>Pw@P|N2I19og$$*(^zWyY*o%v-*hOD}Ih zMo8gi@8$T>V}$J#v=hd46;U^Uwu2rThWNopl!I-1W_rs)D+>z)*f+=+FKj|P5_)_7TfhtYpKEeYkcK+5-ZE=QdOpNHP^GRi;8(l%X%Z#&x&d zPwCVUL0t&37?Hv-Q9?KpG{nRqi_P11ksHROH$$jcA%hy#OEY}%qpVr6mW^BYBii!F ztQ~YDpGZt_lu6x$6{K9*3|1^y$hr+X*?T;jYrA#hlgX1<{^MdknKpxEna8>0(k29) za016H5i&O|=axGjVE5rO-l0?xNKL0)xpFN2?puCcy_LO(j-!-~vJ+=gJC+BL9Kz8k z5==wcNuFz5h^aKHRIf$p1qDgrv{xmED^=PVkxZO5KX zoB8~`sa(;dp;2Oe+4Y4>0;Hr>qFd)Sj2rnF`N5J@uThr}Q3ARUH_-1M*qM5if|q^&%R5OOr0*G7Df}2`+eJV`N2ZgCnz*A=pM6g~}E~0peJKwnCJvSc$!B zm#|^=I#zDT>&B*ye<(|GQmqbZC;AaauDhCRU#%Qq6kW#x)xJT+tlxnbvD zf)@T)im${<9Lpu>!jmjtzLW#U&SUb#3NgSD7l;5cToIyxBLWgeFt2?zoVZK(-za85 z#9OBSW#iVM!)S4c{mZ3-;9v(5mL%8L>Eo6E871L*{C7&M@H{IP&1K=wD=6^Rh9AB9 z`@O2@`|;2Jg6-`0fg$nYTZ4TUvS{xoVaoG)HT@MO+9Wm5V#xLdaDUIxpg=6+j`lNb zncI0vrgvZ0^#besFkp?rA9@T~Xz?(ie%&sAm;b)y0wwUz4-xmw+hR=8k-|boj(nC^ zCQV|<$bZtTMQe(u73aG4E%<)X&)jqW!vrP5jW^uP#EFxrU9&0{sT4~uPU#X!2Gh!mIa|SGRl-83BXDwBclYVDM1=F zX~}zUO<>l?@AAapM>v;Pi0g;$BMHBX0+9eIDJAK6{k2rCQIpPHI$eMFHQa}JlQYc-l0%Kl$hOJxHb7!w!j2l0J zyn-;r%VhA@l*vf60Qx`$zmNy+xtHgjdx=6Pz~h4-V%egvd3fN%Y|1>u{rw;2$_6#K zr`PTLylge&-h7`jY3YfQoypD4qVZ)Hc?yc}rt@Xi0+mdc z>#nD2h2mV(u@%MAQ>j$BDt#X4%cv0}x%Kv5^Y_wjHmGe~I@$_>ddB-%Vj8M$M{axx9I6+O%#?zk7Sr|KX=7lTn(W1x;GCrAvpa z88VEOBw=j6W*_ryyh#L-(x_NA4ci7~rC=u&r)q^Vgp?3SEJ=-ZiOZd}QI_uR`X<0g`Q<}A@jA;*rL z!igE2n^{Y#WRx#QTF6FQsbrKXPl}}w6{1wBViYeH!cHzh<#Odn21BwPC`Orb6)Bb! zLXkx2vgJt*7>h)S;>9RYDjgL{r+oR+glwVyWlb6M$Uhh}YB(>B9!sH4;h9m-Q92p= z-qV|5&pg9{V@I$QWSu_4fdfa4Ql>S>4j(2ruK+=lpO?eogNOcu&oSlE<#^~Z9cJ&g z)pWU`J3p@2$l<-2Tz1LjO#O5YNIpw`m`|gIjVN8F0*?)Piu2jojCg7Yr83G;tKJo? zT(jM?#v9Aszoo6j7evC*D*h`mLUU~Udah`A37>qq05_V?=JgxcbL1?B@Fz;RW&Fq@;t4sq=0QO=&vFY)Xn4ZZwyZ$B%F( zw-86WAQ8@=%i{3i0~|ehf~e!*htnW2@^W)Idi(?@&z!-sJtx07~xk%R-m9D zFNed24{-R&C>@t~es1#T7@ih&WQ1e_GaWTqFAq?3A@@ev!+XwUyc5{U9+N z6}QNkXf5Jub1$u9B90@j_nvkmqO~Jhv^cISjuwe&@!m5RyKY2W(-RSK#r4KSw20$q z5$%YpBc@eaB6)mpT;>H~Bo-yyYNMT-%?BBUVZti-!Ec)d)3G1kc8#VXy`Vn!bp5eRf29W2VK-uRpe~>xipeudgE7 zjf(5U#Pwf$GiJu$5v^lI+UNJvm6&LWiZ-L8JxS2+1@|>W;??Re1+7Kvuy>^+j?R~u ze^>uLuBp?=d{nd(Hm|jaBU+;3diRP;ponAo?YRCOy~^CMXo*QoM07MJ+HvCZ>}oCA z6%i*QTATSdZH$T*$9zW$#SvFx{uqiY+6{|%y?1;Oa~#pG_WJJ)Le$7sR79fjHLk^R z{aG~ExUM$$bi$&wj?YD6-D-(MBC>h&X35UZ{==W8OP9vKo0XL%Z@u+a;`!soMBIpo zn-jUwfddC*%$PAn-q9iw71248xp9f~x~;49>C;zk>)u1= zEnX()y^#?ul9!Vu<32@}Y#aBihZDUl-4o!H+#8|9EVeOq}wu#9T*oEML|w zTOfUU+#nYmDIUtbw;|NYYYwr*0s=4JBDioN1LZs*ROD{I%T{gX%U z@AAL9_|H{(g^f z$L)7=ZL7xgyQ4d`Yt*1d_3G5DUXvO%>hSR3;fCHo1wdJGvQA}%P+l%x+cN38Y-Mn5 z%4@%}g2Yd*Vu(fk6RvG3P&P`L?^p^#mKCSOKzVsly&#u(f?}mmw#TzC{`(FnkDtr3 z{h>2$AYk&Gdg<p3IkDfxj5FQhS=+Smq0fZn*yt&3( zr^-asD&M+g*`Uo>CDu6DaoQH!Bge(89XsgB@`Wg;3%K_F2Ss^&apKJl;vj`589j6$ zS2VhUK94*{o@;wi@-g=8+C_drl$@+HoH=!xgZnah`;FJg%*mUC}k*RB$mxrA5P$!)-9=5w;oq_x`8>1*H9>+B}~q#-3%Gnmn$x5#0}l= zW!F$=0PaP z)~&k;JH`#TYvU4n-h3Sm8#ZFV;E|jz1Xm&~`s#gdyzUwEE{(O2O%4M|kns zXDCrN4ac^<$C=Qm)zyr9<8@wrZ6epTznWXRb)jXGnt$p@{ayagE`ND+uobjHk{B}L zMG7TUWW(_uxXR;h63fFC5ns)Q27(KMpo&H}T|kog2j&0&6GinJwfKJiLT|(J_8*Dy z;pfxAO2bb}Ckh-Nxa?sJq3DK_P+E(EbraEeMadv8Y?LmF1LlH|hs5`kzr7_Q0TT`) zl^7c_bPM9Ou4o8_`8+Xj;#XV5-BPq2el$t@&Ry7;*_o)F;%)X9&PBq3>DQ%-3`Zir ziecV2-?T_%PA;k>;knGjb$NKmP#zpQ5?6WX7p=LXSu=L-%LFUg8&88}bW|b&vuJi( zZ-nC`76-nnZDf-G{z~Dg) z7(5K|jwc{Ecr0w%8%5;{loz{Rv^wR_sCnTZK8m(CK^I~2QW%9x5_5Lp6kO0fEfJIz z#MNRBZd~{|o+9c~im1dL;$xFg9sgjgii}DTjoG7GDSD&dUw7eL|52^~&H*=(6w<|w z z$SI)0BtV4N;~{MZ_)O?&y6N8C7dCYyNz`{$>_)H+=6o%`KFbOem?4oSc(<@$FAMF=`a40mZ*qgZ?i6 zZOUIh_gZ@#Q93}f^6*b_R{AKhNG{*ZTSR_-)PRBE!U+4gqVfk1{UTpB?C075V08>F z`a-aDQ82;if0 zwWqL|?>H3Xo#p!lOUTI!7g1ik1}bBT6EtpIX)2OOSBmm<`FpwLZNNSg|L?Ig4$6Cw zneh`(K`E+K`j{n8@w7r<2fdU}9OhgXPh`N?aMTyqE)D4@u}E z3hX4Xg4oJSNagXjsX#iYWbd9v;kD2NwTWxhc!osZqT|V(pP|DQms2N?^X2EC6Vo1I zS~S}74;ucQ$Jn@j9lH;m`h901u6p|E_`GQs$FuI?39P>08h-;dWd9~Big_al5<*-_ zD4a^6v`Z4M7a-(~i^q#59zm_vjyI-$B%-=-x|KO(BtG|N-SRBL{wYQOPNBoss4LAx`--`#z+`{1h!vp@He>MT zmnb<|2UxgpIW-$L=l$uknfk`_6bopBxm89!mF-2y1k!1H-EF-0?qoV&*M>CLCB1lc zUV3c`FOL~Ttx9E0Ab=7>NUSxu8doJ#q4s6G`p(--dv83Ik|Rw0@Dn!g+|8P`yXbu9 zKlozKbjFPsz~Oy+SifNdB`a3OwUZH2xb5a{TzN?Y&@n`Vr4`z75S7mDcR$2??~J2W zvql6Q2TNQ+ z_cPhL_c&Il1hH6{WGP_oH{VkD`^cF8Xc3fh%z9ETt5z=IuDkD~*FE>Lh$%WR~XWwiVoY$L$H4N?`u}9T8nmKy!zrWM!xV0 zVZd>{O;#0fc+YyC8aa-v^AVqT-rL~4Q>Q*p=9W$DK9)r!p}Co&{eTbOzT#7KD735b z4Lym?S&&#BD}I{K!Bg2@#HovxL~^IN66RTpT=6mj#0q$<|NYFK_YDPr5^WS)rEtCc z!T_#YRPk|%MbEHw`6^DH^GI3as-{tF#3wfu5(>3axXMpv=D8XXZ%A}pX%OYliG`(H z6I1KB1`6QO{Af>2Hc^I}faS7h=MLU{?R5&m5i&Qfq;A!+Y}vCfuFQdp#Ln>Hhwrg$ z%N}B4-gCWZPdqC?*2%prTf2cmyr|&9W88Z4_58eMlaZk!LMjL`Cl()Ke*wmG8z|fJ zz-vz-(%348pT7T+9``)VnVbSMr{48uFV?F4WLp)CuvCZGi+0c_#?@g8^764&8Wk#3B`IiAEG>xEnu5YY?4X6%3b7Ss%a$Zb zITYmQB5=Vm0#PVslN<;T3!lf)LNw+Q444#WwQAL-PMx|W2aEH_19y;r>=0AldWZA* z7S~+chC}OrWWYnuP@vMeyU(4JD-}Sri^jlS0+uH$whaLrM>H|<;0t1rbut?(m_p@? zE~egPm(%yb2N-z&U8EKxH00r6*@P5t_pF?7fi3?BRljW4NB*|Z>q1vy|@gu^jH zp(L!J@lu#afkPzsG(CDfMp~)rJkq~6DFMZSy?a@(U>So3+)KsM)%fb0pLy=d7udOd z4Ih2-DeZ52m=|7tjj6AVVb+xAIDG67g(`{U)MAt^SB5K^HY5<#965Q$xWl!^(hg`p z65p&ACnuMWKmMG~H+Ci^CG@uy@V|Na%jaLTHuxQh0vfRmle?o8O1UV@K@%{_fyA(t zYw|Q=K_H01FGUR}mr6vpiP9huP!UwXGVm_TSj5+)ItSx^GlBCOgA4L+B*ua!4%)U12cVa<)?5_@%OnVL1Y_oM3(?}BEk&z#ZMo*! z_6QKLeQTS8*g;|{$vdq@J(b0vw?q^;1-v<7EbBIGinm$&oQO){icbmZVi5x!1yNXb z&>N>jDk=fOIaxgNkNeoYXAcp;Q2~@P*&+PQyNDTUS3p}fE(Uwpz56X(T)zPUG=kxw z)8dVzQi#&nw#m`#WvAkN_HkZ(VHD@`3UQRln(QJdj2sy19*mN&Vj%fwiF*8bmifNV ztg0NeZF`vx{FyQnj{;o&q8+zb;wCN0Z+HotO(G2Cjnu zj4(U8{2~m!~n-qhR(zSq!3qJTuinBOKBrpVww67V?9JJu+kfC(m_cC<;ju8 zB8G)n0Yn@Ewu_P|Hi|GNmq8#Ym9976OoNN-6Z2YR*&a=X0?mAW>N@P@{Me8fsxotUbjDMaP^A=MeihvEcE@*SG!S(X<`f`fN24U8y zfBY)y!4SmKU}=;tBq!?-Uwtv1*WUh^T_`2)5d zhha}W#`<3uGUfG8IezpY{U3OM`}+^#bWVf@ty|LQvTFP=?^`lz)}U4UHiQeZ2~bEz zsgk&a5IY4|D}uI7a!M*2SFd5s=1gkUtBd5H0UI}v$~9eXqD%_poH$73 z3Kb|`x-!jMwIcYZ0-Y3y<#Em`N|mWVlP1k*)ubg=%9f`~yGH!7@Ei6YIL;4?H&CxZ zL&_$*Y*?{`rEAwy7>n@c#IdB8EWy2fdXt-Tj$k6CPv&-Z?p#Bc>pJk{ zh+)*NSC?=kpX{@TICb(A=W}z>fn*$&%H3J(HTeYE6 zr!IUwcL6aSpfKk0+wzsDSd2q^x6!B1T{Laen(Mn>&%7UgHXF5$lDTyYcinXlEn2nV z<{rIS^2>6s)d@eP;IebW3VL?y!hw^g5sZ6mvl+{cdHyAdmd zPx`BY%w4<5+_i@g!s%oC81P^}I<)V|b1#lVdzQ%K2Y1o4`;D|}(UhUXN04>C5bOZ4 z{Bw*LGK{O6U&F_re2j7nm_BV9*LAv%?zi?}#hOikLw43t20i>JEnBqap8M|O+wbSn zvCFOO*?&B4^-tV@sr-cjpT7(?>lJLyafXW zJi&oOC(tU1O&hjw`uI@-IPA^b%D{dPa80`oy!rYRA|klrkaOk;!-o!`ZM#nNx&I%; za_F~S0}wftJW>KuWx^L?>P*>=Jjj1zjrU%wr;@_Pdv)P zMT>a)+41Cuqr}2tCX9KW8FS_lHL4BqoCg|Sc={>6U-$zKinCcq>2==&Y}~n@uV#Hl zrw;9CcTIbyefk-$VcrAp>fGEs=FXW%ettd>W8Ul;bh*AWw{^XlHS0EFSrCgxnK*U~ zty;99=WRV%wrV3-sn`mZ{_q2Bn{;I0fX9hAuyXY}&SxIDq_Y43AOJ~3K~$e7Ai~;J z%jkJq4?1=1#OGhmAqo`aW-<1~(R8}5Ggr51!;mLOarS(~bAkF)+5U!Wb2j@NYgesA zyI~g2o5_tgbftN-X581eKU;SnB&J=I8{>zC-*RP>D|z_Q$BAjp)(z{pulHTFZ+|Tx ze>#Ig$K_o18OA<0jCO6?a^uZ6Fn#6>Zom6MPG#oJiU8f!{_h6!Ale0r9$=ERLm%bh_Pvh zh+(ojXaW*8im4SOYFVJd9uUIML7uP-8?=CnB|`3*6HJ`&3R6Cs!|nZ^=+t1sLsY;e`eUQQ9L*94H`FZNspVaBj%V~#mbFPvO*Oe z>VFSA*Dhl4pke&HY%@_i%|Hos8g(ve$k=g1Ik{&YqhAkd5B?+)h8`i%bl9wMSrs9m!rB}$aw&fa&ClXH$$D>icX zef{X&y%RG&`k2WdeM7DK7g45CW$HF;%sZ1_;Pk;A41N3w#=bm>oqG=b3Dh?i2nC{4 zk)S?huqUpC5TMunw-e4g!;Lrg;Fop#dGwKgknB1vm@}QPzyFa_=g+fr=^BL@XOtm5*``>U!VaW!U!Okg+V~rtJGA4ekuPxfz@gNv zb`cNU-Glm7Qn|fn4_`V%aNI%OqDj5 zH;^Sum&wOdUXfV z#St?4&Cev}II?cd3fZ(_oxJeWLvsH^gXEm!$SWg;$lD)HlRP&nZ@loR3?KJ~9M8#? z2k*X7dfwYtep)hLUK;VR)VlOq*>m)~gmccwZ_5_T`eolpmup+dOK*QHvBIM=@ZN4R z=Ka~SZqH#kmwiw^nLJt=Ue#V^&YLfeA z-+qt|U3$o_{U_oSBau_Pq;ZXs^8QzgWaGY5QgA*?-XHUX+;LAoS+s7iY}(;3J1uwKew)1U<{R?c&x_^8Yud_;A6H6N zPL}lT*-?7-eL%kdWu^SMaGsnx^s8Lm@j98e;-Ku>dq5%uhveNiUzF=^zFn3sT`Dh( zd{(-2x=FI~bL8VsKbH2bTFcVqzsSaIt7XrDOzC*zZF2C~3CTWlTJG-FMb>8Sl0wm< zB`o3-leiK2Wa3B}^2~FRCtB7l{Ysj4=qd;EMfUH_ly&Qt%U3f$mn$!AC|eF5m!FsX zB3CzVB4-KsBG+EiMkc=h zxqLhKD{0!MqkJ)Uv79`zS*~o}Qr@06TNW<(R$4S~D^HJnNeW%UWHd49+M>G$|3S+VjrdHnG~a%Z21MC%;+{FAA2d(S?yckg~Vc67hwoIN33 zI(L%~-v3yBUc5*;wQD0wH*AxgyLU;pxlZj~O zth_z?AJY552jz$5t7Y`FBcx>IOJwb~9a5NoL~ibKlMH?88CkykH@WAQuJY{5Z%9r! zEYA$MUuG{{DBBP0mm52@lezPMka_dwNb9DT%Y^s7l4#*+>CvH~44*JXHtatw**OJL zlticKpNZEOlC4CeQQ5L(%m0ufMnvTF>C^JoTW^`Fw4pQ+9roxRf)UY&(2H zV&3;7BI4?ph+Amx<7$cd^gV9OP^IVut&Afg;ugl~d?XeY9rMRY#MO?tZdAneXs$%Z z`{X!oQ8F449X0pSuA!3>SH#VeJ-au`w(Z+x>-HV8b^8w4vOQA{o<1WHEgr3tPc7vM zu_Q=t424Qm#G{gO;PfKzdSnFfVec4#HduY8m(G4p;L=XII;IQ>({NN z-OV@Rps>V2J1*OI?`6xD)nsMm6U{csw6z_ga?J)bZ*diM%BM2z-8b2L=onfhQKD2i z8aHji)y=E0VDT>;J9(P=l@*p2&snI+s8EGQjW4BX?IfnnUdFC1+c~#;F*WKpV$hIB z$*?sws#L%@Ed8SJqhtfc)4Bfo>sY;d3)eTU!P>R!=ryD}mX2_E?=IGE*~z(+$2pRl zOraLUoXY@{)?ER|PM+rQ(X&jM{Tby;3KdIQyuWZaN;yO$Ijq~bjZ+7=lAMypv6H!I zY_wQZs91`IwX2}c9cJ#V**x&*NUpn~GwIGX?A?;d`pv6o)T|Z7%U0#e#*HaiA_+@r z7Jkw9pwZaYtDOaH^b!wI+#mz;bse4gFnp|0n;%KDc47;{(W&6(kxUqbW96LdQ z>l(nZ6ms2q=wHm`k-{uy5}+ zDpaaL)GkS_s#QFPq`{RLD5pcCW|uMJ)vw5j3R^eq;OdsGD3$DTIQujU7cSz=sWU_h z3dr1hgpvk=hr-1c6Sm?=gwJQrr&E_+^y+mxA&${_{&Fk@mRrctBL`W!Y(3|W@8Q_- zLLypFT9J}koEkOLDXD{~f^(j$2-f_(oEkOj(zDksR0svwxBn#Xy*ie5AHRrBD#oQ( zwWDSIlH?pc$&ByjlM{^+N;a8U{OD^CY)jC#jo1zJFr*hY0Bi*R{Ba zt(%u|Nt26Nci=S7+}VI&ERS6~cCl^SYEGR#N4^sVFG^ma2qvfS%riqh%%dk=Ue<#u zbuQ+L7FW@}aYI&b*u%1gU*R;V!_H%8nfTrl)T)?*{ZMb7d}Sv059|jbIF7eQ?GRVB zYDL*Jm+h;6WcjL94CvJsaiL^JX{y!8AYF`8I-b`X_&rqC$G~0?W&b}}e0Q+Hrz-GL z>7o3dDlZjY(4(&rV--|>K4H)#8Em14l{|Mgi$M7(V|ny3wcb2i%CE0zq`6ll5j*wQmIPfF9>YXY$G_j#c;;S}6n{7VyQt|> znUsjOFXO)FLjA5@Wqa27-`@}XQ7*d4t0IH_w=4MX0{)U`eSI|0ij zEhU5#bwLLcp!GN?9fF}CX~7`6AfJN#JStSKL@0=f)^nXAE7MW-{+FLIdGZH5^7Kd|XDV~xyS0daS-c2Ji^<3kNFgOT8H+G>z;K;O zB%A*I?u4?JGq~R!6h`L|_PGB7b|Ajt#-dU3@(Rc(SI$(cH5tW|C@jn;tN}adMT7c} z1_z5kkq3>SU5zUSs?Pt%-g$>fQLJtMSKU1`n={KUEU;`KEICRN5LC>FS=#~=T6 zDM?9Q#*e>(xa_u6mu|)5OCl{LB@%asFl@J%=5X#=7LCn*;u7PL0utlBB*tqTI$Td! zX#~xvE7a@tF|uC~UwpiXUL(&UtFRXdJ|Bj|+ZS6Mpnd0J2sg4}%??(tFXOz+ucH3o zLGHX|A}5}A5km(JX6>p~giVF=I0+chR)Qv}YYNh-V_Q2($O_wWfJ(7_?Mm*OF@x); z-cMqvh&6jZjPRMc{Csv+YxMU+HT5JXCgIf$gwRM&Nuud+1y(2kngR(kkr*wQc%>9i!Zy3 z1fSyKE3YKIO-HP{Lui^|C+{c?P187c%mAKy`#p*V45d*^rb9s<@4fac^A;^*%B1Va z*tUn|D>p>KA_Nu^TY-cXc!ayY>^j#9-A;Y*dT5)SL8!To+PcGtxOfthQ$U3AC3*>% zCjPKf$;z}hJWbb8LL%{#k>;gkXA`CrXqrGshka0)POPi$BoW)IS~_uSIua#>!?WhZ z4gQ-|L}EDxU2+{Fdc>(FqTKk%Uq&B7Kw4%tufO#^Qfj!Hx{}y2(uP4mD&jp}q;x@< zw7E9jcx2&53Oi8)e?xh5Q|fYd{bZ~r1JI3pRlCOz$tLj zTfAPI4^@wb^8804Vw>VB?jwO7f=Ca3{@wqEDBO7WqtNQ8{J$l?I|!6EoJPEId_P@#52i~=FY4<;tov~@9t?D06C6v4P28(H z#JPqSB{U4D7ON1p1rQ}|3J2_cz|b6mXQiVX_L;b_QzvH6f0lLYHd2t8O4Xr8I%z&4 zic{byJ_V$Z->HODS5Gmv~TkJc8=#YQmOH zMWSm4Ijz!3O@vq8c!SeV9709KVF;TL3bA)j8E2nyJ^7uBDJp8ux`P4GG?G%1*t2sN zRh1B~C{7tp6u8)Q=z-)`N_<*B!I9)NYIr@b@hI}{%$LyMvf#iB>{xO z8>f?;634bJTj|sx7nNvXDTNf8lhtgpqqK_dy$4g$tvjl|lGUZvHeAvLVG&1Rm!5dE zFtzoSv@hz56$p@%ok~);6`Iw^g16sg)QI7DLw=IHaU{k0So`hQWDY8%Rf3@Jz(K5B z`Yl6>+q3bfAF1|x7}UQv-!5B;t_wV_Le~WSj~m9k8z!@}S~7IZnV@SCcpD9~@{p32 z$0@`6^7!-{NX+g+L2)60!w12e$;in@C*7aoXtq zEO`B|j2b(ff-H+>e+U#*?5!j(znE_QdK22eiNrYjIGvE1%-;Q_l$ReQ(`%8JYMW*R zFmOnJ-v06%)^FNIL8``*Wy={o_9Ap&62decf@c?m{w=eia4CpPiLP{n((r0_;*NbJ%eNU-^v2hI%^m=td|MASW%Es@g*in36V8IFfeV zJJIrNEf3v(FJsQXgyfV2%F4?r>OGi}o_%NzTKu$X3kVOIE~q+KiWTa`j~h1QO-QCs z*J2_IOj=Zyl~K93oV_)>_;S?-jz4WOz58__UVnq7Uwy{#0o_=!^anZ>6_AktLTDI< zt&XIVhovjwkjY3iuR%tu9CmHlMCE~FN!CN8BzpL2`FeWv?n}GY>C_zD!{%N4={0Z& z$(qTk)oV#<)t0V>9RPun7M5x9uSiu@m0bo;X%6s+X3$5WpooApTUWRdY0f)UvEQ(D zfJ@aQoGfrR87&a`mJ2rBL!@#Jb?)C?tA6w+cl@JkBKCkIh|mtW7Dhzm8NV)$%}qHe zL;|D;+pIv!rnyorEd(4$92=q;3sTj;0Kml&BOF~3$~|A<9^UM$k33~Zp8iii@86N; z=4O;qR8>_u{j~f3&vQ|VU;Zu9dN3Jdy>n4ZCuY4`BxQ!lXS)hB2Q zh8cU&4G59QX=j|tZ8K)^@%&e~`tl37?$$fG@1Z$deaRm|=$!M1KhdwxKq?L#Ko?lBw90A6voAbFZeBZXyK5Tv&7R8( zbLWzskX-OwDTkmfU(KZAmz0-k#E1+MwSSb~5q73ZCIHg#3yOuGJZq(4YdOXA$r1bX)y zLj2;7xa7hMh%^0ovhwk2f|5SR&?fyuE<5i6diO5jsfQ*KRyJEAOPP}sc(Pt1A*%QCTWsd@msq_-}j zYp-Ki{>r$V)7l2Fm~)>!oo-2enSyjB7+AH}A5VHBJaFet%z5H}nDsy%C0$CmW%5+wC4`ki znHF9Fx<>;mjM6+wdMCfr`d-JVaee*qBwDKFyIqM|OKYcV)?wH2?56&d-_yKHL zw}zR|zRnZR_rl`~GxwQi={@vh2L%3mvfzycwzop+NC8rl2uy_1Y?>X-$(L0Eg<(?{ zIvY4j!>xI1!!HN6Nej#2c{HTM;pPBA-K9!$66A!EXi`OZMO_?V6F1r4v9s!(KS~=G zDj}WhUE6jjG0>GnQ>LA9?NoTt9Ntp*77zt&_WwrYFfEWs%_hXsAX3Rlh=_C9P0@1h zCnERzmq4Jyaq24HSdi<2KucPYXGj;^67}|oNNJ+Km4BrzzurcH-|uI^f(4QL#a8M0 z=j2GMp}ohro+rz;hC9`3Y!Lsy2m+NtN{MNjv}xPsf9*L(<^Mhr>bF=C|AHuh@F5<* zZz?MfB=PKXvq=O(*oahD60880ZpXoBW+Or*V(Esh&Qusp*!07i0;~{d5YoID%27<3 zLWS#4o&-#Mc*2b+&5Nn|@S1)s-HWN|_^cpO_hKrAZZ!}H1~G(=-|}$YCD(KAxKp|O zkK@pUCnn&?#Etq9Rue%j5h*mhQlhIC(7c#ZL)Q($*veX00W9IeRN%7$g!MR-0D~5U zWg)aA+l?h`H=9lnTXAbxcnK?r6QHReNQp(fortJ{=!8(xi>dptX+=Y52rOk2EJFxX zh%iZZb|PT!6anXNafI=r34v}kVd;s4(eR-lP>=8>fHZ7yEfk?}h^w!@p0odOJ|~SC zjh7Jiw&RNwr1xOjG&M*RahPt2GZjV?f{-#$8u*YP1NN9PP~nh1akUW{{AP zih)GO1f?*A7ZZphfQe1!ZeUZ>Si(mbgE#_M7=$sLHbW>FV9VBRbm;KQpm4*64IF#y zu>jQ6)Ua^jLaw>ynkbmTg%zfKN2P&qVUO)vRn9@twyM}=7zJ)6BnNCMB33=uff{l1 zy6QLO_8*YAJrSx4o+ zFUl#p@ZERc{r;9f0Vp8|Svt}IE&yKVgon^Tk8^+k2t66l(3KnT8x4X*;BW`pl}Dn7 zKY{S1B5+)0Mj`@XZosLI~$Lq!mX&Mj@2n=0wz>wRVI2#NKzySt!9GegHs6w+}h6XkS zv-|CQ&-T7}5t@qpE`%5GAaoIVk#>)rXSpLI3_M3@8n>-B(2h(3EfGy=_=KZ$;!p&MbmAH%T5RyT5Dw9|4ZDN@q^%fiE4coGDHEOeQO7BT5gpW zR}?5|TcA)VY2wv94mr3T7i{Bt8&Jd<9(!~RuM=jk;U*F22xr`Vk>Yv+9Ynk{)dsx;u1jr1926kawehel+&=J!mz0!o#|ml=aKseXU<4>n4Nn{CsI*!_xR|j90>v< z^&4fxW1Znqs~ z#we~6kzf9C5{`2E6a&##B4v zjDaq(Sc2+KzUUmgB5l~n{ zBQqlda9n4xqjQ91g_s=zJBPzba%ZHKhTrY?k={-l9!fKW#)54*`) zbgbQWDCNur+rR^McB^HD@EG36UZ!n0*r)&iAOJ~3K~#&MZD6kG@%-_++pvrzd=7qy z00!X}^b-yrsPp}p5)}4(H=`e_sB6$}bLsv zdQ9bW#|?|JJ1sG5uk*^lI|}OUDxdDOzz=30?uMAdXYK#OZKS0D^?WCVThS(Y9?aUXT8(_lQUo1N`dK zz%ET^xmKOXw%~5h8itWfPEJy!)~u%4r`?Rq)^@;pj7tV*@&7Wga-Zo~6oA^w3M`M0 z^vn!Av8UF^W)Q**huB-uNZZ^Tyt?+YTRGKMh3=5H{sxLdxt4+0cK^Cq3gVMeX`7r1 zN;y>oe&u`aKIJ|J74g_aH;{j>2TB;Erne$B-Tj_pnMz2eU1Cb)K1wMpDbY2}jzRi| zN?+k`Zf5_1eRM4990`+;x?ezGfoh?qrU5-6gY?Asm_9gk7|NYbE~u6u>_7l30@?qb zIG`Viz#uiPH7Ti%g(s3QV&ZSEXWyYFI^?y%tBJq4gI$wa|Ji2ef>!slsP!STzgh}( z;keVW-NV>bJ*p~e2pfsCX_bLtctF|pa)tJH##R_4rRE@F%$~x59LlL8{Wp*}_D31! zaLoZ~gK^}w%e5_<{08&=Kaf~j4S|Kfb`OuteVvh~UcjJE*{s>Po!tClI^?9$SXag7 zZQE%GSY)+nN7tePD$BOBySxJBNuWp19%LjZII({=;)xDtbbd>>w4wy1Dcj}vi+V1a zkf2bQ%~h=4u${c39^_>v6AXqig@<^rK*uD|aG13l_tL&gS5h-loG=p=W0`Z}+N83R z>8uz#qEIMlw?+GV>;Gq?7x~H21yQXN1}SL@X?Wv&HvLUR@400Ig?%Ux76H@1Qj!F( z$I&hBBo?tK@Mlj}5%_3t6~E0)asj=&{Rrh80Niu2!&+cpXX^^f0qge8Vq!UVY#kdo zM)k4wU!Ctq<^M1F-SgQaLCk>Ag>#B^kFo)p>MNLj_hZ!7HbzfVV6SuGS^|Ey3C8+e zelAK;QMR2~vu07(*c5R;+m1Lpw$EL=if9d5=aG?&MYqVkQ&E^`!Ma}(d#MYdfs}kO zZyq0iwuBbT;@w3Hc;n4?BZbcFwI5{P?k(JK>vXDXo9&p!Bl=(i#mWQwsH|`N4H(`P zSbj=(Y^0{q??klyo$laRK^%?u;?vKu>ibnk1cCq3BVvD%;U;$M+)az=xVV01Px!@K z2oPG#5m`ld2_ald5fRIW;bsgA*Y@%&)51pHY~HYrDHCs|F%+b%Y!5eGe;wr&)tK%z z%C6b`($i0|eAN~Jzd%60EXOhyORgbQn5L#0c9oVB!m&UG8+r86huOHZEb@-U&pPS` zkw<}^yFJ)zLK87tjI3kFh85iVm#1k8{8DzS9b377e>t^Hfk-FaEhzc~C!oPDqHJFl z3+MzWT_LnE$~?pyFF(z~556R%oVEx%hA=wlzbvr;kjN(Z^G(`WLoonI07{1W@U7Q* z@bQ;va=s~l_RZg0l(J{5R1z>bynhpq&3=sS<&~6g`H}O-oyDBz7t+#L#iRG%#Tloa z&e`Xm%abp>$mVUEx%>|oF>dUsTz>7XtlhKEVG4CU98T@+h)=+twbBLinp-E@X@jE( zl~f36p{cO_Hz$jH>knUW_8Dh0@2w?N9xUaWtFPvhuYSN(AZ37c-!0|LQ^)bv;;$lf zH^Pl+#jdUG6s@s8(KOKPcx8lgsC$TLL9nYWDJ3zF$bvpnBF|EmGoCss9N>`|w{i27 z=~UL#+jCP{M5Aq8y=1Xr^$PxY$(4NY@fS#?P%a&zl5VMY9PAqN#Apxg$*qpuQ~qsn z0G~Ss$^seWK-n%HedHl78$X^~Cf~*vOTQ!J)NS6pc>}Ybo`*jeLYYCn{`@m;nmn0` z!?kvsmBKC_=@yVYDo5q_k>4EzYOeZlHWqn=YL^HkhYr`-MdE)o8|q(KBnm8xs;Vl& zj%6+uOh}?Z+L5hIz>ynQg#H0Xm-J<+YUv@ z-^9++QUX?Nww{X~BudpYQh}6zx9XR0EG6y*O1Q=MV&2seW+E5LyMO() z_9+mOK+w;jLp4|^%y5YE(%mRaMgf}wgvGuC2dHTZAY&-oB8`$EmVUT^yC0ZIv#{A1 z5l~rKNjMyGJMs@k$%@?AzN>Wl=~xF;m~e9)HT8{HzhvQ5CT7b49=P`&zWjbWrik9l zR1R&2jE;<3^E7%2an5Ct4OjqS8fze2u4`H0Bo-+J(gY=u z%FQtaq=i%xX-bem>S_;CTVEG>wOaJf(Q*GhMM{uO$WSBx<{*uY3d?b`x9L>Ojgu#F z(FNynV9yrbeSZmqMvY_do_#!Z|DAll6GjG77)3^vl#(o91jh(GLb5(-Hu)QG>imOwCwr3Bpu4B)1T*KqQf zL8!(GK6>wMc9&JqzAsc*36U%HS5NO07 zXraEvPm5&|M&JCP(gyhI{f|?{J{XtAsZA`lyBv|_ugc8St(6^Kh35^ z$O_~4H)BeP3^&u#c$gM5Yy;A80KdP5mKHzZaM;mBf5%wxFNzJy9r9+)qWR!1&OP^B zzTa_>lgEvtRlLQY#-70AFU}{dLR44mX8E^ku!7BOUcZJr?|Xs^FT0ZTjC99aB4Yj> zm80_e$?xtCRtSXjQ@Udd->lk9LsJXsDX9z`Hj;vNakc`I76=FgoA~n6kJ)#il8l`8 z3?Dt3tP~HWyLR%!%C*!rG?0*<#mLbo(l$GV>iv6I@y#-->iu}U2@D!Clun(BNY6}U z_=uqxJ|Fefd-?L~WgI-zL}HwezC%aSskj3^735HLHD7(bf|}X}d`W2x8#;u-{JdyJ zt)3O*b`Z#j4G9y`Ix(2;_ z6jN_xW1;ZZRq^GrZ>g#%Bh=D@r93F9XsWB?{l%Zq*wje7{9*To453E8`0!Ke z%l9yBP;dJ7>B`zQ8(Ft*9fmJ~!NW(BpO-LoKh|TNQarVi_V_5ZkvvM6ZjX}C~FJZ*MuDti|dsH3rlbxH-u;D|< zN=;_K;A69;Nn-x?ZYNSJcI|@2=VMl2d zqecuOPK5Yw+1L15=hMAg7km!j5yA$QOP72`>w;p6iVF!hRq)Qo-!bC2(KH_1&We?* zKu@Aq-vRXQ-4!$qQ-ZGPWM!r?_ViPTOG!lFXZwatEdOy0K58kitfdzM%?hz%`7$(Z7E`FD)ii0F)WHV&+N#teN$w{VkDM*f7$C{F~G#}!NC10?wqL!St?HPXD z2vU<1A=tq8-~Ys>t)(O+Cv(PGr;?y4)~x!Tbz8S#B&0L$^fO5C1X=y#IyP=X||Sy)(h*0kBonzftRuwerpUpzxbjiFuZ%wJYqF>Q>x9RI^jRapr9to?2& zw@#hGs`Wd_PPAwVYA91tTUo_pkNkz8FNbl1GYEz)KKkejI(F#D-IK4x3`0$0h+#uV zke6S~yw_f$f0shsSUB5?DTA6(8oy_y5YYhvu?n z+iqIr4PWJ9UNM`GH%zo@~x@R@>&_gpxY(Idr`Xr*sFn3M7 zm02^UF=zHIbSrAZ{r5jWPPZ=PWDe!IxpR1A&QsJiw9vhz2iM{LwkQ^X_7#9!Ixc!&vn4gJ?*0@7%%2!N=2~eL9QYoXd^Z-@uw5)}d)$ z`W!o!ryjo>9fcLLxaW@PJUsnQ9((3_!ZoE#y5SZc|LY=7=-ZAy{RVONga?>)`(;eN zaRP6BvI?O*oN?BfJoNB%k`p|(HBkIEwhy5MC<~T1o-@;4|se2 zA~Xey-~Wg|{OJm6{b7DszLZ%H+)c;~uzt-dZn$|eyY^KOI9$QY&%a20v!BwlRS^UYDPBtXOMuGUuMrJ-Rou9Vt zLeavfpS;hP-)%%G3$yt!iHSZw{P2AqoBKRLWhb9#3WSs_`{X@7Ub37(FvydS-p^ki zeTWvnpP$xk#0+CU!D_+`HeskRci(qE3qJY^DGW4BGSV{1%;`u%VjSOmzL;ySoj}>X z{Ve}>ITLQ2%Kn4C#X!m`Q|I;Jo+doLCEye9Bk(Cxvz1!z7cumZbjRerDV;nd-VaHg8zN zRhRvV9Xob#sOm5~_w2P};ZzvQUrT~VXVuD;-2KpOT7-_!bdnN1WaSo-oYfXAKQBM` z9HsjX(o$Q+;EV6U)WDLYXQh*!(~hJBovj_<2wTW- z6SAd&)Wk$yedRS?c>NuM(&D{0Ugpj_?x40gKy_^c5M=QOi@0sdRB9V+i)PSLeEa1G zJoM0gSVHI1k3V7Zw1)|59&kc1bQNOxlDC+6^9?jM)UkBgGA7?Wi^Gk_sW~iI^d`66at#Y!dV$y8{)j!LyZOsK zkI*9Hc>jZU7~Hdf*|X;I)0(xs_4a%YRyFX_tMi$^U_O2O_d-d#>WUJYZHd)%ZkT!- zUwruvC!RPGLIFIwj<8zTv3VUcAAXDxC!NjPi{3;J)-Y+}RLb@qpla`K{2?!Mo_vyr zr%&Rew?5#y(18peI)J8{ zeaxT#CVd7D8twDiGUtDu;l1}h;M%J%<*Toj z^1)|c+hpllJQHr7%-1Wv;q((n;~-}U0YI>0DFq=~nh*2-*J~L%VhpMAKATQQH#m0m@uX`yHKnB}X|nperA)Z- zHm<&DGAEok94|KIl5lfKV#5TE%2D~9H?IqXbJi0&}{&hUvmXXS6{{ze;Chq zE0!_rq%l~+=1uX%CD8BKku=oRQX5QS>8c+=jmB>Zy7fPv%dfhclSU5Yn4!nAt#mJq z0fUUJ4qS2NmBe$Hv(CGgZF~2Vn`_|4A1NzLn~q(%2st0rGdAG26%_f@me8HhW z0Htp5IchF^385J&GJBdDvd zCruCY(&F#&TXuG-a(~|(GD?b||@Y)tB1OrBl;MhTZNH?1ZwlveD-*H@a*;%Bb5aC*m89Iul z7Ks-2^Yw;}G?^w+fv)P=e_#hcZr#V!yDld+HJ)wjf8@3K?~?k*llXYaa$bDzW7@ZC zhsO+a_`oW3Pa307JDXm)3N2K@yl0-{+^Z*X$+(jkw|fg0oqrDBt+|L=D}h$|UAg+Y zKVzvN{-y>}R0Vqv?8cv-MQu2dzTHcR!?6ImR$38e$g#b7c;1(o61HyIO|Jp{$jFEz ztGFB9lr|I;H}cizAG2}W9#WiaXuDRcL!7HZJoEA*ih2%b#y$7o(QDXNb{JhKG~uIb z&px!ut0yZxk%wRSke~vDMs{8?W5*s#nzAsOciUDw1glnj5AiA7aOZ7gCqP(QJTh$x zPyNrGG@EgZJ?}~ec5h9Jk-(BA?{oei$CB>x;ElMmh2uI@NMTnBiBCwR|FEGn`x_Zn z-N5<{+c|G^0T^)%9CiX{99M+bs^s$X##7K^C<8}~qI35Kra$-?)r}R@DM4H_*_0 zCX3$voVy?S3j+oZ#fLD8|XnTdiMraetn z<&9uT;&czHxsiEK%w@=^QyDyRB>jgT!-Ofb*>_++*@tl~_mSGV16{gy#;~d}!WQT$bnf1h zoD@%F!&h!*nWg{}p=D%#q_8zF=^a6qdk*g|UdH9)$8+wb*K+-YKa(JplU1vbDvUyq)xJH&oeDAJA*zG{7R2iz zwrp8Xb&JmUn{Q!2aVEzO@6YO2zGGKeIS7FsmrVQOdFtP+3(&5QqB69ePbi zXvqv8c`PR$+nMJVujh)X*HT=ZgHOUEGiQScION!G1j%k6hhC$n7+KBC#&|CtEDz|sT=iBP6fnaW))ZYYP7B&L}t zLy*kdKFE6KT`ORcx_0a znWU%269|QgPJD+Jav#M#`q)P^X<=ZYtPpN)nVT$v5D0G^ zXPtLGuPNsn zBu-E$i@Z(+_#5A*bWb%utl7zFCy$}Au9n$%-%D7<(<(WRrkZk0(?S_IV8OQ53Z)^H zG7B%0Vx$F?OOB6*R_PCiG|03f37oAv$Hi-7)`eD>dP=)isdap*0p@D0_`n>_1Emn>f%AB+(2p{*ntw@L8bggiMJ)7^3D-Gxep_ zy#2w~cw{5zoH2%0=_xTzGvUVkM=6G!F^F!f|A`2^@d>0Q3975hs6KdrR2(a*W+!!6 z%0f!ZiGvh`OzGqeC=8*YX+D%@>pX9yZH}!{$_T{@W(yu=Qh&IPhQKy-FfVVd3^uvDrU}pmTSjfNykM` z;PrS32U-ZWG=ofL>F1yFFufwCR6FDPNo!?*L?)3bT__9;9(doGz7i4K|hQ8(~W z`R~Z@9~0sCB5cLtrh6f$+%{T$r|3SCD9LkPf^ltyMw zHk;S}$eAY%MM=e$^8NHVX&Ac1A-u)rs*@osEgmVf$P4#+JqRSh#(L)+cx<35EH^)q zS6_aC5vPpf$_Y2K=F1Ow^6e#fluaEWg@@K{I*^r~%C*;ANls2{bReuj`R4Wbn;Y0y zUQSU#KEm)Id?|Q50;}OLs&yJ#LK2zT+0^W-zyS8wHL}0HnNCGTY+Sn|vW06xM`(g! zqXskmfjLw+#M7luUxd&RQaYS$P6C32oHqIN?$VBzo|wsj%0{m2(UZpNGWPB*3O+#2Fm_d|gU`gB3>(M=QDs0Q9bw3aaS@=A0ge?h{#fBfhAtgPFsdwK) z^WL?rzJ0Du!{_l5Y;Ld*8A3aPrKPxYCq7!f9Mj)|Owie~vyA*sB?t!;TS7x1@dyiD zS&^g^+o`8Hq}m1u9ghlNgz9+rowqpq&(rwB>BsQOYj3l4PYXi#V(5x+Q!Ppg@Fr2v ztrxzIotb>wB$9QTl)|G`LUO9VzUl-NNUxNKV3SGnl3Bn<(r%h5>y)vAG!l03ZNKL_t(~aQiJ2S^U*%l6;C_OS2743}1xi$d{f& ze!I5JnlXii&(37>t$(6l&u(@ilon5~o?YqRvlBO8dJ(s$q~bqR!>IGGqen?0pDNAa zMO4nA+d^PEWJXTg1t7u%T56d&>q)evw!Hn?6a4AQTe)`pRlM-fE!=qHjf63{=YiX~ z@#dT8&?<|)d-frXJcJQXzX3ydd**ALJZcO{K8uOho`WR>cTKyS%!ClZKr>2cbnf1V z^hCw%2dDAe3y*W-&67E6=s*&^f*DgL^2GfHbuAK2hS<7sBV$iHk<{Eg4sI_av!D-# zvfHgYho%2iq;NHq523>Y58TO^aThV+h7jkSbt*g8E@$SWk8$fGFVMcAfc<-RVJVG- z)Ku=6I*DnwPU6CguVCS#`J{Wm=kN*sR!5hka#a3V`Q1UFJ=JaI{ME~rFn!8hG*%y= z+Vn7N#HqCMdGMOGeDlrs^dET=&%E$g%=%LHRyCk>Jp#xgS&X{w#8}(ei%K}0S78fX z=vZN}l!0`Lb4lHU5-!b#ljWv)7;)lQ=D+(jH(&NA+PCk>l5aPV-+cfsopjXYXjj`v zO-Z3=aW)UlTf%#vE+N4qIbqZg?wk264?p+-)E~lBwnME=hg{};@FB;KIn}{IMn+l{qbw~^cRIKa!G!Toskg}H29 zyN+S~in(^uWNyEEHn&ymqQ1EavhwNIcL>e(wdl%@m_zzmx$I+3zIZC1E%}Q6o!cXn zLXS`2)KgF9=~=V*=9?cl^TcCNh6hZ`v1nLIIb&b?jRFjmDis87~EF*=s z+4-DsOfk1!e=UXG1|WpN^;0L%p*Wv&&p(yxuO3gI{>NhIitBHOfG2^<6=`&~$ zr=2~Tt8coQCmwr-(v9D+Yi}h3Pr8U+oeSByZUaIyW8RRUd+%dN_a^e*>#s8Bwb!vd z^TH{4<xVF!UV3n_FD2=r?O?&0gg-b(z&oR&%M5Y*$+H|5vrlt??+dH zf=)fCuUx=wx6YujeQR#Gc!Xo|RP-5q3^{KvV8$(zNJ~y+{hn%O&76s#8lgf!5Ja3^ zOIGQTY8XPE4T%7B8jptTSkzn-TLq?Da5ka9^HZ@E%q5O;qpNh!&qiazZ>8UO1MA z@1922zQajMO6HpDF5>(P$MM9hyI8w)07hynuDtXjF1Yv{W<2yH8@BEtF5aM|_pzKm zb~uHdy7E5@UuEOw^O~ESsZa3YyeG*`hP!UQ ziK@gdJU(kOhbwk7`n0S0%fkIHyuvDhY=M88!FSZn57^LO4 zW!R`=@#%_F#+}cA?)k(ClgFN(M~{K8vSITMa@%#}qRXzNeRe9th8{<=N~Sp&=IqP* z^QVi?B`#RS>F1tHVaK+lW)(8?v01$G#yhlxbP5Z)k(t$wb1oc9`!?C+Wal#X#bC&e^X9Uy8$x0_F#bE3?XHcA{h}Rf4rD|_kSNaSr`@cc)ju42<+V zHf$-URqM8#I_{7765Fuy`_+UM^ckJch+~J)szWChfAA)+&3}u!kU?Q#0foH=vhbsY zys_wW>gpRwYn{uOlSYu4p3DUoo==*rHHw_VUu36%1Z znAe&4Z@tB9Z@j@fZ~m3E%xqp+^bsS5kH8}uXqB78al?8NZ|Hcv$xOU+DwX#?&4$&h z88)yFN{<$XI|=}g%I_&h)DAx4r2oGp781>@VfKvM`D&YD!i4d}VUpjeguI+AG&8`C z?K=>LkM{W;*|KR1hia-39v?Yv+tRhT4drDAF~c4Ti`rrZ8(6vWdy4xE#%yY);^2O| z_vwv?Cbn$eO$mQqOP3Ow4(%tPB~Z{I4-sr+%Z}Yt)*M39bW*b0(yb^T*;3EO%{yso zX+rnLk(Xag$GlVmE%j{JxQF`Y5XA)@$ZwxRS=oNd%lD#rycBlrM(gxM0xiw#*l~c8 zZk_Px7WK7NtlCsczrOuRON_H!QOZwaeI4sImJ*au(xnK?e~2a-PkzUId`hCi4XoR+ znL~9gcy$lC?c0*yu|3ycc|9kO8_OxDjv-WE!`2<89Ip41n3zbfVFjH^I+2y0PU)^)?A^bQ#FPv=cP$|$(Z|7x3aY9O)4OLk zgtVzNloep^lk@oUyR|&~(leyRd+bwv#L{bTOhSPbs^f=MKhnCOC+*tgV5k6<`}eYa z_ddd=#OsTrbC2GnCm8J9x``n16t-{2+Mia@d(dE#e1gMOm2BO$k3e%Xi79Cmb}1n< z5q9p}&E5kw2rQB^TGOj{4?Jd&9XoeZexQo9v{d?bFJ$B9?c^19CNnXf+Cx=r*|7`L zv}luGMEmw_Ay~)i^*ia*wFeoA9_p(qC_hk1r(V7A3gK{`xxgU=n$AyaHqok88X4)S zY~H+$hWdImUmP6@I#JLzi{{2gHf`EQlRrrNf)3<&$m3vHIeW_X5|q%ceFusg4=dz%WM;Qkz4`X<}^zPe}c#oiL*Dm%Rr~!|UKD~O9;xj2L zub^~)1xhK}b*9S7)I z(uH_KvUA%O{6;EWJ9R(>n^?7WJDrM)X_b*0(QV;ym~Gp(@qgHR?>H%nuKoL49cDJ? zUBZ%sWI+T$L69UEFaUxeC?*g@5kW8`N>BtuMZ|!jC<2DtoFigFB!htD95<&4UG@G^ z-7~X*cY5@Gf6sGUevoCSr>nZEy6V(*&bh9dHEW)7ZSu5(l~Uy8<*{V(5=M+15mhk} z9x7`@XqrqyXsp!0R3ROkCNzR8R1k!PgQ*pNiVre>&J5Q6b^u8nO4)!-&u*>x=;KdV zzNwJ+-d)IPHL7@2(o7ia1)wPh)6J`5kpL^ISTdLYvHM?2<3nzqxw%x)JVBug8##Nn;Uu1a z<`EJj+<~rJPXUG*Ny-qM!a$9Y6jCwQo$3{elDl~Mjc!biGTi`ehvSD2@Wxy3kdu?i z?wvb$V!=BsdF3VQRnMY45OD9Hox}dbB(gHnBk^{pd`34O4~U-pEBT}~Bfdup>xoK< zh`^<%LV+tO=Pj0=I_jwxi%1ox{PYypo$$l&GU_YEk%PPV>dQ}=_uN~|dSWImTQ-ll z3jbb1POd9DUa=|`-uIO7#!7+=v2*ig)@|CtqjMKBedbKsw`xQnP{i?L`6y*XZ)ynA zvNA~U$GIsDvCb6{TScWfw@UFiu^+^?Q^kxUQI5Nldn@)r>27*%*n%gQcgpYR>kIPp zC@d<$FfF|KX4yWfR;hxQ0CCEDsAzj*-v{G_M~lo!wCi7Qx`uXT{>}?jT2f4YegV>v zIut;HWm{xrXXCRi94RAf#vg%XDEB{si}a%0KJ?-w|MeRFEhBKr5=M*|q2qYv?|Tuw zE|yYa7$U0R5u-t@grxM?ZpPj?jIVy#N)Q86==i*$*A5`Rw2U>s9%lY?vuIE~`}dzi z>Ka9?1dsRQDb^!>PSWEerK?pGv%bf!s~#Q@A@BF@4;sNN-AA`>UD8=6`I)5q1f z-_4!34k1wm(R$|p_pz+qyLYpA@nXi0AOEKVC;!Rvml62iQDTii3#erD{n-;*Cr2c3 z&UrnlQRW8s0}6LT5+=eGWRDG%J*i!>IAdvv3p8(Bm$#R^#Fm{001HjM;LzywHuSmtVy%08%6Q(W0q8xOC)^%2N=%}9t~y3Y zR63!?Y;^*S0z|6%{ipqBNAKi=r)RB28(!JyhQgv!_U=2%9rxZ% zYj9QGS3Kh96Q0`(HHug?A@=Ow&6XW|nLK3@ty?uhpg4SZH!r`u6zS;9ZzW6&pPzwO z52kKzuA2vV>Z8HQ?Fi$M8k^oH!n-m$z|p%HfYioQr4UR;D3 z8D`_UpZWZopNVSCN>VbbGJM2v5=^hvr?`*H<=u_!+{_wl6Y!m+W%Dfdtqc=99W$n^w{g(e|mzhcR*D zmwxvlO+-R9zFe`{MfXe{vVb6@w2rQlIzjEP@>lt*{O>8kaUA8zSN$j4!5SS2gA*cb zCTerYlcI<)zr_LI$S{`i$Am3P6|0aH&EAY`w#ucDiE5f?fpCxi0XKm_f8D`x1IDf2#d#Hu6UH<(k{=S93PrjHb78p?K_3dFJ0V2GIcXq;>v2%Z<(5OcM3ul7dG!=hsL0xJB3iABJK3mAcpQt~ zYhrpA(GxCi>Y?jG&kvzA!YYJIT@_J+IYoUjhPV{kK`WGU(R1Y5-?_$c_M?rr|5nes;#sU$)OHg4L8X_z`2RDn>!T?eFVoN8@YA*4pelsB_ujX+m> z7m1-f1X-W*Obj>N!$BDiN@+K%5-0a;O!PJ)c7DVl?n*jt{Q_YaCxl=q_dwvq$qDx` z$L|6F`oL$P!y2@9I?9dRi%>JUhY4adk56j*pE6T){eR-V^?U6O27@?`!`7`^|LwN? zt9|lk-djpNmdB1ABR4nqA6)%c`M*@G{|x#UEsk_B3;~XV!a(OU=xI0B7>GG_Diw1&kGfk7&KbYTTicq;OwQL_sqHX$2u-;nAQ~m-VRjy7r0ZO=U?FX~ccDwqo-U)EhoE|W<@GOakbDIt zg$I~4^;t&WF_l_5aZz_|OgmLf`}FUl2%&=@_FobAU<7g{<{6{vE|tgEn>_+USmYlo zVAGlnC}DDF-xlt<<922*{fH*Day4ax3Zi5Yt5*Jq%xXd>Kp4@P03bw&)jxgC=PPzI zdi)sTQ4lO(-cxh9a?D+{Yu*Sy(ls8U@0o~EZjpFKv%9ehjkqE8UxtUsRQBrXjCgmv z!ct%v4xvCXt5$8GydsDY5{1^e)kc(qFv@uA%{Q?!n{n9%=VDRHu5GJ%=&`q$_v8$c zvdzfcCo<}lHmu{#q;^KHi>|gRW_0v>=U~Q+on9q02kXg@^4}k|N)PpSuktRfY#hhF-@jL9 z^k0=%i4(thVoU%2U3Txt4@-n`oDiXqz)^~zF!1?Avg5-cxA8c9?Lea{5TplbcbOrP-xA|V+=hN%da zAf=6ifzL0nO%nr!lobR66-bqUW7t@hiQg1jDI^l3B#=%8fj|W^K8*z7;DjBVuz@d5 z5~wI8B;!z~NxaYJqMZsuSzwr4bK?jqtP}(wWd)&72qzRG7_c-6vrtG`OrSy{jW~ja zMY7Mpq=Ky*SCLe&6~$%cB-l1_wjvx35DFaQ=kdX8fHY^f-K75AY&PkKN zHn9Qalo1Gp2`LL@`H8b_OhOnkNHFN&NDIR-2?R=5xAqtE3yR51QpCmi@CivMSVTBv zBP~C+&!^qtvVvem1(G;~sW9z0${mMf+lQgT1OtVH>{Lw4!mnJ^!!@FU6~!2K9KtjZ z;R;HFCVtz82p1DlCKbv;_-qnwZAJ?TLK)OMtqC7~`6c0mOe_&5TwYAbRRJhf7RnMB zN)o8ZCoKI)!^ZFP;WH(9hj+4d<2p*p%2B34qLs{yCuUO-pMrtZ@`phP3lm}6_ze?F zg$aejI8xvs!LTuXK73MPnj&IhX->8z~xL|bUeO@K1o1FYwg^<2pU&rcsQrX$8^41;$} z0-5*Jo;$fx%2mX&(AS2QzF#B;Hu{7_;&FvOlnD2zE3t^8?Ow0A$$TQlbc`7X6;rj8 z`UAtP++N2CMfgAgFX5l)%_`s55nK|IRFn?Qa$Hb0qZ1Jsv5&=IcYh>9!zt3{JR@dvK86 z*qwm%>K{c+9U}5VRBozgcE+ zsf$y5gt{%xW%A?)@KqdT_EXQW{QI9th>K_Y?n8{abtKme?q3N9LrL~+UPbRdS2FMI zuQ;o54sR}go#kr}GHc3hOrQP;zi!@1QDG5%hg{F#0av&PkU%KO+}Sh8w`w!?_UrlN zouy2lyO1hrK4hQ_R3cIs96xf9d+(h@NpUGhiULe{=n=Y}nMHZ9oO$zJ=A(B%Wk~<7 zv^cE>4?H-BqOxMj!xfx)PFKdst^ z+1({(KmHV1i{54Y=xf=(_G@N7|2nC;r_rn1c?=(P5qFOt&z{2tl$3-SG5QuR=-G`s zZ@-;R7j~!DMHlhf3orBeS6>qdhw;b9^U(A;MCoy73=|QU1Zb0)h8go{MPCWJW z>&%}!lVrbS?1+(cxZ)Zv?R{Znp;k&FRDh{>jUlt~ncOgZ1c!HSrq5M(^5QFtIQZ)~ zytd?Z@=JnbrnMM1vM)og9mRVfRzL zS`F&e$!6@B;XL!)Lbhz(LP&-&;;S)Z>Nt{oGR7!SJn`rwtod~l`||_z?Q<y-j(Y%)j#V}8KsHrv;WgIDyCFM zja-H}QNhlghe*t-PIj^nOpCBIumzw(7=|llX6nPEse&jKbqkv(B6vceVo=a%eNn9S zBtC!`P{}hLb^8KHWfK-A+KI1RBh!6HPzYh8fRF}kV@zq+C?&RMJxtw02$fr}Mz%$y zZLX27g!gg8j`BcD!?j{PTr?agX8+#Zh@`6IR?UhSmm=C2A`B3o9VlGm3x($;ifyeS z6v$GJ9xJ4BT0N;!7m07WW^I<>0n zaX$I<t}I--KU~CCBpeY1gqQ_ug|8n}7bEzI_MLdtiSK7nG8mQH7_Tdj_*~ z57%CM2kW-%q+MnJfh3F|P<))4^%^nx@uw);^D_fSOk>Ta?S%F%XW<*4vFP=s)Xq#~ z-0kBi$U7Q&SpoOu4pXCEH5%5h!N0$ZNemryBLjMLCfPa0U89HN%WlmR_l`nT6f*Lr@vJ_(9yMy#Brc^EPt19Q zv=keuBp-d;in?{H6OFO6Py%iqJB|)#w;|i8VBIG#aOQbExo!MdvMjLuFlp+;2;t-7 zH{ay5&p+erZk9o5F&Nmk zVI8@(YErXaHmB9-!MR<#Q*iVsH{Ez6t2S)bOlNM!q~U~#QxYWv3toDKL&u7k`}_-} zii3=u@F+?`ob6}m(CfM8nxSl3x15QyUgw5eM&NrKN1t%TWnGYw3@E|K+r}Y8 z87tTR#_XrxW@!Jmgbg2kuepxfuI`0jK~{CXSEp=%e;>eP*rf>Oqg9L-M~ek02t zqO{!Mxw-R56om}G>MGuN=M(N4b^#Ob9M5@I-^tJ`E@0(PD_OAMoya~FW9yt?km(mP z>Z<&Mt-qKeh(YiOacui4F7G#z3Df7%_4KOTe)mK48*&qucRQ2K8`tr`q^ayUl24Cb z7c&0V5&Z4d=Xv3kH;GHjWy&Lua7NR*Iu_7<5*dAhNYVC>8M)?^{=rCKpyy^*WEUINDAqcW(+jj1_YZ@c(7|&VlT2a})kkNJs&m?h?N)Lk4 zO^qHj6c|FHT+G_D_$q@=VNf9oi=nu@oGMk*F;T4k=_|&J8qWnI@8PzahLCu2$4CBF zG5;2>VsMn*!9xT!m!MKb+&5t?heBDr{>mI|SDv?$>JuW0REjWA%EY_wN#w=NkX1UAJ!hK6CdTT@?TXV z??pJQGbR7b0AA2AHikl&3M)Q=#FP|rYt^OWnGM*zXB%P5hY}%#C}r=CjodQoR=S^m zF_We|%CV#QKnPQq#KotQoSaOHCbdcQm2<4107V?8kw|iK3RS9SP_t$>g(YP=uAOjX zF*WQ2{7H$_tW}$|q(ll2?q}ELUpb@gIn=6Gourf`t@b1(GU^Qi;qv;$*<9ZLGS>XO zhNAsP*t+#MTDE9N;gKEOJ@yv5_Pmh0?w-hzqlNmcDy+y!P~qUH0LKeUC=dJTcvfpN z(^JXL%)+w3a*A2?&4=_KIFJjvU&7M2-lx1I4A=-|5^q~1#rX)82HCuE8{IGLNk(Qi z)vMK_{b@DXw|fUcD-PjLATcqK#Kd%xQ!;4TtO@aPK6lYKP)dN|!}ceV;J2|%6NG^s zpF~1Z0`Y!>y_;5X>#*zS-n~1sX3Ze4u$Zt?gmEw_XV3OceD~cC4CsF~UAy+;({FyF zthj)E2aaLHXL4?bwxp*fla`)}fxQnBM$A~OJ05j zYu0W6>Od90;o?hsU^!(heeo$Sx%e`!7;p`%H*Ds3Nr(^{*)R;zyb zm0ERcQMYC;8Clioc;=a`{q|GBfeIYkkCl{4dRi7;&Thr=qq`{&hg^MDZxb*;3QV7k zvV0^YCyt6lCH#6N9>E(Ig zqolNuJqPzu7zlIZ$R1Yx^aDSx_?f)J+Zl7)SU&mc7yNbtnF&5tF8_`R<0n%RR9Fe| zC?m$f?EYXV2SbL@@^=d9I1%H_Lu{nd-@28< zTUXG$VSN_9^R>JBh1s)X6DwBy#HQc2yHDpO$bs-O;Jtd4+eRe_DHA13O-}8JC#lGl zZl1lR@1xv@6Iz2BS;mjc-lay(20T1>f$QQ|loc1Sch5eG%F6YemmbO}L1^_S52-Vh za`m&7d-!v;ja?%Z*Cf)O*8oQj9^i0ZnQo`yW}=1N2U1R?E^TCKKGK3CN60TO)A*PQ zV=9R-41(ol>_51hqlFcCB8r-*TSVYRDTDmB;U_M+s0(*Yew;G5AB56|m~?`C_5Mv+MLbw8FMLjB#sKPam6xv^*o=`TeW4x=({*jP=XWz4(!^%)q{r6qInAj4jsm( zT?YX;yk{Gut{X~=7R~5A;9A!2*pEbVeD4-+zN#;0v}(-m@Q#gD59C_P>gOZczyUt1#XV2>>N&n~gyxiTDx1jrvaRzkztRj`D@G!%j$ zufFmsNmU!Nbow;D`+hBNzWohg;Yh=ka}w^NAdyII*eI85I%dysguwAORROrCBn-`Q zCPNPK@d+F`vXig`!%#?Ugb|Y|soehwKqPZ+m+rj%;bdN1;wPnALr$w%gEyXfh=3z_ zW$BybZ(YUo`S0r-L1CbkHvwUyFp2Z~5KaY0j~yd9H&q`Z!w#~vh&#sI&V|D!aZSJO zEME8;Tk-)VF%3Z|Ad!HbV3Uv<&z^mIaMal-9QNfEQ9m&mA;XcABf`-qP%AES;uk1P z3rrKjfuI|>@3@Bd*E-S^r50*`QViNgz1pt(k1t_UdRLRa_ zSJ6JCVMSt^OiR+CV@qCoYbhNya2+83i$4SYqfnoVU znMh?KaqtnwAdC~UCJQf%T}Z+zjA6SD9MdKtHI*hU+VbL}rKI>IO4uaE1*j-Fq*Wur z#k{fP4fYp>ng8li3i9%Kc-pfd3{1l!TprNLIi`)YG|h>^M~#{dIIT)N@4fpe>vrWa zrb8RbwthpSrVW_(!V(%(%LYt*@d>ANA{7;tv1rMAJn-ODYS*m7onvkz94tqX6nXC> zFO-1zgm_F_P*_-ipc;k($94M}Lbx7S z@-{!L`4w4qh_bL2_^XzY#Ayv1(W2Ga96Nf5Jv+9MkyVA}O&ZapaRb(@TSaL_kfx0q zQ?1@cv>B5HEam76cH-n{nr+;Z{sgq zb!B&Q>(-@F!xq#(tuc;rIJ9d6i{E^geMgFDetH`&?>~TKUx`Si5EmJ`tdP%>)di zf@L4S&usJ807RbPG{hN zOE|Q18%y4JgMxBJ+m1cy)x9H0{tABl;!8gGav4RAk8?Y9?{r)+)o|Tiup_eWfT|W^X&Yk+^FqY9nNCXJ@@j|^RMv0t^Jtx(7jY`(3UqQ-Oa*x8AysrAyyp${k~P`Q;~={Md7ZlIrl`lQcekF4Yp^Tza-Y{H^(`{4Xk%vV;E~eMm9TkeZ#gLI|v^>h!SB03V%`@Km4?UJ_85fC>x;+YUEbs^wS$M z;L0nw_l{dBJg^7lgt2WONhz7E+3*|ZwP{LmQ3*=MgJDs%S{2@Z^BroWrcx!bi2m1H z#pp>>NRJmB-o1qtzwPF>)?)}eAwaqdQIH?LU&eqN?&iY}KcH!Ys@gG-oJ3BwY!)wg ziHedEn%7J~8Wx5V?VHT(TsCdm#*Ur4IDF&?mfH<796~A|wQ4jXHObHP8Pgef)nEz_ z9ir>S7t*+XE$URy;@TnCa@*~9B8v{ur9)FP(h`|F<3ajd(uLC-<5vaqPz^B;ccyM#FH?Q!oXAxNjX)xp!dbh zocb_{W3T1YPrs(9EC~4V*?yLP`4N3CZp+#qzUGe6V|nX?kEvfHjY$*lr$}Tl<^J&; z+qat$BW~fLnUB)ESu<@oq9QJ_|JjNbMyOJro;8L0CeEQEE&(%CLP(`yDw9B2DQkaT zMf=`IXj8>cSSgO=PNp%TF*YdFSI_c=P2)d2hjV?!5OgYBg#> zz?Vv^vpZ5Hy^vpiT1k)nhv<--4$@)chP50#bcoKKnv!5;v+}3a96fx9yyNNIcH_;w z`}Ggli3xR+s;r>S!l9rM{QArs~-u;d@-+zS`4eQ|7gYBYdVSIK4 z@4opaM`R}FOum-CEnUh>i{Iz$3(sT5V~=A5N||`iFr*5wXUA4bi}GpF@qA88v9N?- z#dpj2<)@zr2ZQX%FXx`&-MN4Kt*qXzh)c+z=aB=nZdH@Z&%c0j$HMU?@XRxBF#DND z>C>|{Hw?Lo0+B>~ji!X{3@+(X9|MPjyEgOM!d>JSDBk|)JC=X7gmqtk#-Pgvb3BaB zsDJteX3Tqr8~QXs3CG(}So!@oTtDPS_7oQ3^BEMCdCU=jx6gPH0#1lC&uT}jGv;yo zZDV3w_}&Uu%C4Q8sj#bZcIPf+CI&dCOs3D7(jkem@5ViCMPAt=o|Yo@r7?W zaA{k<{Cqjn-*}J)4I6Oz#od`U^%<1Yhm~vBbH(Tfso$Ux11{*q8*`_#al;CJ{Ph4+ zAAO#NjglBWa%a<+Vx19%=_uO30XxWyuxC}C~-ThjY(6k2u3Zh$Pyy??`TT26lWp zojP_R(Y8p-uEp7BwINOjEGvO-ozJ0qZVvUEoyiAF=A#Ps^65vPl8~B;<+F7xp$u>$ zW^UQ>^cgsi8;1|2<2h|WI`r;;C4Dcsm?bYf&)Z+FpmWzQ#2F?R^}U4Z*=ZCUI!wdU z+t9jc1LFM&+&TFXhF#r{k3RT-?^bQ$rs0E0%c;sU3tp#os>PE}Jj1@DrS$B2Hl~@v zHP;WLdCde~Tkssa4wZ26fE$@R{XSNF^92WwlrV4JQ`D>5i1d_fI(0e|(>9SvGPASj z)#E&p6a9Fh+`^Z_ocS-4n{M#w2XAq_G(^27t!UA>9&vzaSUfQ0KH9cx!E^JT=9^WU z>Dr|`>4u4kfnoSah>PQ~+0$rLGn>UPKF`WEYY96FUuqR*Kf8#_x}C>6i(lruU)B(` zvzU1Ac#_O~{`TGn>@S4A1BP(R^?g{h@Fjdn={)xIToMeEMs;e@v3*-WxEY0Uq-8at z_oV}=o}J2BEgKW(xk{t9lIy{;>2Pi*hFmj{!B<{PQoNrU)$4NK19!4|<#L{W?nRoM zc`hv))S-2Yrrdh_ZERY<5r0w|7hT?$w1h-jv^s;=UtdDe;r%=@e<`OmZ$+!7wQ1V! zEJhB$j=#P90t;XNgf3k=6KBI2?K^YVxRHGM&O&}%xdvrtaCWEj$Vy8hCA%I^J~^BG zz3chvn-xr+I)%>Xw!w~1p;z~F$xZ=N2-0)w(4k`|k}OlZ2ECvmB|s#RmR*~3&umVT zDZq%QR{d6d^1%`^5<|SQ@FlkG*oNbn#HVC3>7H9TR8T^XO9wN&{{<|0;UyNm{w`fE z?2Z|iM$d~bq-V#|c;%(%*t&BcDH+wcpnE40<84q5ZMt-2=ylgH>ZTj8mB5J0V*U&B zsh@4K@WuJ8S-+96a*bElT`Lecjv_TVfd?PFo9&x7@Z_B5soLOln$)jDc3KAKb?b>` z7$E#KZrO%*EgE8(@l3e?LHhJ)!;)8D<=~-0eDP@*Ru)$dx{9hvL5>{RM^1JQJ-YP3 zpOB0r44O4-LbJw=FoZ#TQWEEM>_Bo#3el{}FgiChdXNAwdhYL+*n_Z8L5hy;V)5e7 zsnYN)zFWVQ6<@zast<%=fngvGg_0pR)+&ihufBy%o7XUW*g&jc3CUIJvV8R#mVNp* zXVkBS-%u`jw8T&Xq#~?rYBxQXAJ?qqo6ibj1vo zVu~Op`K(?0Bg=pOm02&m!QS25xw2P#zJC8RHg4KUFyxS4y)mzU@Bv@Hw~&GZ+gZPH z7Xe}sFl{s?WM|W^Z7aTi|4nx7+QG_g`#Ga$Ke}~2pXt*k^2B3Psh3*=WD-}89LuI( zS93%E^RZ<)6-sgEgELwE)2C$G<*Zw?kw7^FD@=O!xq*ELx3cubS$z1)JPsE+Tr=!u zrap8(eyf-tmM`OQkwK~S)3w)S%z6A_Cf$8AwjCyfpAOxw;P8QMj2|(GZL5D^=gtkh z_WFAqsW4dj)pu;!^c^|=Vm^BJW6A^I2m>W6Fr8w)|KeK?Q{vfwa6kFQ75IFqB>8+8 z${{5)i*Qhpf3yG$L2`034i*UsDFn+(zzI?sC?_t_j}nlYk^~MMI-EyEFhoX9DhfzU zPb1z4QCeKg!J|barlq5V#7;`VGW}GPd(qUf^lN{9IM`q1|Gi@AxQ}S;g;Waj&m`Y; zU6eve8Z>Us%-N5SB8Z3*NW)^t^*5s247Ra%jK@)7q_8!brz98j>IuRmEEQHt7LPqM zU%T>Z*QVpy?KO&|lDJ{`NE|FI73Q{E$Dj-Yqsi%9*Q_-Xf$h)WuJLyu2~k>jh@ygH zTsQP;cJDpJhu=Ixi>58GL=fQr};NidVMxM|o3)G!l?jYMEdNUht1sZ*x9E^9ZyS3&h!jhH-n zGLE#|gIkzOF1eiEz58jleg#4~FwNRL#odi6@^VEc{5Nu!Uma;2{hga-EwtqaUmDIqm7#uDy0I6Qc0& zes&)?&bMo~a^tAmsh*mINtt&2i?~QclY>Ai3o9vy*>j%3!RIc-7M;5G;@mF1bZi;| zM}eur+<5b?NW+Je4zuSyjWBHtrD%CpM_RV;1VU3pfWj1E23>svgRUNdRC?1e0Mnn! z)kAM&$koGf3=@MOqeqX!!9qz%vu3TBF|!qjIBnZ0MM_!@lP2Bcl1(@?Z_|$EZQGz# zSfasg3UElEPNO!AZ**47S;VGUlg3PaXd=qZIyKyl>C!8%L>U_W9)8nEhTm)v_5#JF zA}Kwdad+JfhL+p|nD&4sWR_BqTdN6=Or8X$meCU;nd-F~bN~I5w9%s!h%kl_>Bf`uU!z)X zQ-X$|VUs4zobd<_0z)ZU&6-Kr5*Rr2yK*QF7N&rV^epbW=bosDp#YCeJfbk7R3yRS zUt8T2!9akLqH>a}*C#zQlh9EE(@;93z|e_SrfKQW3)3cyt>es)_@u&6eq;cQ1TZ61 zFc6Uy5)#KyC{xF-)vZ;Hn%U`W-?5kc;!=vs%W2S}CH^Fvv(9WzMaA13DVAJ+^91q= z1hXC(&x_C0W8&1AoKr!f$(zGVA^) zNsde4^2;vAR2BUAJY^~~XFbBzpMJ!kp*J&i!sVDo98%aALQ*{|4J#0! zurQw^d4r&|;euyRk3hnwfOrhx)x=Mhl1SlVd1XH5xmp-Jc2_k@>SA5U)*Iq;C z?&otx%hs5}0^!pej?jH=11O~zJ7J=vbctj^DFcO#g{I@y!ev^LO#s40m2@j5G8{%I zhnHVmz_r(2Pv;)z)3BEtXcmn2p^7PxP9c( z^ePL_Fc6^CT7-pErk;O>iDBCAd=WZe(vu4mU7A3fN;VH zVk6)5JP{}iCAEgHVWV6U5<`G8Y!HUq=N=8Q1%~AY_!~G5~YW zxLZH1AwrZD9-&>!=G3cGpSrbcQ@3sd>NjY{lg}(5tSp2Xhf*LNi3t(+nQ|mfSh)SD zAROZBFPAZF*eC`L9E|NV7=FX$`Vn11G$fWrs(vu@3A>^fM;8E3SnYSkPvGt>Fv{Wtk- z(+*x-@(wAPspRBTp`x^$akt;f8?Qaj_TM)1^|vbtVc-Zu8$fm(i9Xo$(=rb1KSWV} zDIxTncd)5fuO2B$l7-LD=GTo|_+j;ClG0MCQ@gr0hTJ5TpcBN965G)83NJ(xmo?Bx zqHE`KsGX6>teJC3$;svX^IH%oKFS04-p9m=Q}D+nV%kCW{kD$Z_Uz(7VHpyiJ6;Ou z#E3~s2dSKh`UzGXwHls=Nr?7s&fuZRQ@DH56t3uV8CJNMcJ15n!3Te%ZOdl7_wJ{Z zmIRTmiRmES_d{UDWzg`n1~?VR_~N~{SoZagY}kH~nssVo`~1ZFOpYJi$$|U;HBW1b z6DnZQ%g?d*a6aWOdA*3dd#5S_Wq7GJ`e}|I&8Muwq;}m#$fCU*KYV~=M@m?`VL#ov zccXso9Ar43mA|Z{q(t%7yI)eTNdt20*5kB#b=kCL6%}PAtXjK{j9Rr2aj7(@TZ`XT zt)il&lpj`YCb>pKnl(RzI=N|l^Zp_#0zp3gem(y5TpHw7*JTg*4SndWWBf-0_ zU=yZkM(+)Hfnt{7QK7ooc7_o(0$hF(VVWpukXz?;mj3MnmrEb|$^g(I@Y$Xw9j53DdJ-f%fr6R5>!-X?U%hqia0Q%%7D#-u{jUL1l zaYCSPR5_*6*P{1v{T4z95V15B(j|2jkv5#y;}TY`y9AF*OvVK8NBdnH>7Pa=~zq=lV#`O3Q=)qUAG~CIBuEnAh+E45T1sNz~syh=d)$!F5L$rx-?67ju>uV zh2iOSEq2Oa&LEblVVnuu@=J zu_U(&gyr(>nT#4efl;?jh-@OlMR=pl_MRd7ES^Sev;thzoQR4|r=GLX`C-|W846WQ9e-5O?}Q(JQdK5SzKaL$pUN%QT!|BMNJy(gTB09e zXkuugLK^BrVaTA{RW{P}X(bR-D-7A__Y6QePDIs1I3f1#*u-VM`w$37+IQ;1_19iO zolLelC?-eGKl8~Lwm4j|1At`~d0AVT&VG}~)m;%fUhFm>}ed|~8;B6x* zQ#P$TT+DUDt|2Zyjougc=G!SxF?Qn9JbceEu37OTug;#v)00av{V7zhp5?MexP5Ta zgt3sq2aeS5fD`7H5jS($HAA@gg05WJ<1Fr(Fd8EvhosELT-oPBvf~2WG-@cbrc5I( zy$VGo6-<0|2zFv3cir~@Q=fQ-wcmZr!Td7DOqhr?(ik}4avpx@5pMb60}hv%jD2Jd z8JTss`=-G>c>e=z_+=UUj|I4S^hByBCvw}UL5v@FFC#{crl{aJeFqIDJ0UTKr0B2m z-&}-}N}C`5DXu_Qn#|iEJ)1=eg`k}Bk|JJs>0<^D>PK37l54wfSA?S=aoPPDIu9vS_t(YYFx-O`sjF+&k$c#LWVc$X>!dv|PS>5|0^8+!-I zmW_cRpoiT>G{dNHK3^_dO=_*CoYAmG)D`Axu1cveU9Lg>3TcTyY4{0@mb2F}7f2j8G^c zHD8&d2w8q`+kKLRt?-UJvGm5eJyA`a%7b6I_fOt-l!KPIGqf<774s#{VBxrKHi1SY zPrX(}-_?^ZQA!aCh1jxX3pH!jJmvS-uV2r(=bj5dUS1wcmMme!h?~$_#-)^$l~Y&} zCLC0lK0jHR>6oH|14jx-OUod^4s-Ze5oTg4)zXr{DWbTvoPtuwtyT>~g%L6UR$@%M zB&eg@G;}DRuPfq(7v@s0N;XL;sU##P;!|N%sGPjKQYyk>r0pX;{r_X{y~Cs`wzltI z?cF^&&yYcKmMnq+k)Q-oOd#g0m=zP~V>*gQF()vf2#5-pP*L!Jh$03Qkc>phLl}l( zQg`pF_5M+NcQ@#HUr+FS&-Xmmb@j}2&+gh)t7=!Ry4Std$|p0dC@_*A<-voL9;`qMWaVU&o|;1O&V3ZrEF?WWgswVBNog5T0$ju`sD-%bAE!%9`xI6B+Be8c%l>H_9(V-0TbF*=^uy_AHGBUGBO;1Bds@PXj zN>mHE`FUh#X5iwXy=wOCs~{TlNYBb9Cojj2d!(BE6$dFVFDE^_fb6_{!j8r@9tTPf zaItE$<5u!_`hnB0PVLg6ruzkeo2 zb^P$d52;tL9$mV0`ORnK&+)^Kha~Otkc6H1>-?c4??6{k{(h@`^7Y15%XnbSi;RBqIqDYV#j8_T^P@Py zJKK(+T@sM}RDi&l#KtM&Z^((8+vx5AYT;ih!s3MsNN?7b4&9FB$tV8GLCNHfJ8w-& zj}&3=u8ll1ZajSk^rJ90)v9Un>J7vWFlWx!a1&c+k>sw4%@Z>Qgf zK(zpcsXV~s$rCub|5-F`c!Y15No0kUgjPdPc~I4DH{QrG{rYg~X=hlaJ{VVZ*rp#> zIATPq_A>p0d7L!pTx#VcP`JcpHnh(nir!&!G5KmMa)~2e!5Ao&NS+jk#41EWJQuS+ zb9QXq!p9%X;L=-0uyVy}&L1*_DWA@!Ws}Be5zF6lD|!F@sdOH28SR_bPa1NIl{w+7gz9rBPJ zG8)P%x4y@+liWuRpNEH6WuI+hK$$3uzMV%^MoqeO>4YoE#}pscR8FGaq$&=78(i@l zdf-1)g1CpaLI=W`WaMO$of`@+@YjxP8q~|SM->O^*2}_Gu9aOVo1ENCa&jHCK-vC% zTyxb$eD(cm5C^3U9>Vok45eDqaYIq+)T%|jdNqBMu|gcEz5z~`TSLRlon(5pt$twUSV08|DwYNW*vOm2EE zb?W9Fg80`vBGW$eqNr8Bk-t<4b?P=u42A(wDWqhCsg;o%%m{3B2Z!2qvVxT$z6{l> zRo{M9$H>XANlw1PpmA`?$gfRCp20IwT-TaKjR_G>O{I379Pm7hr%B5!q)t}yc-yHU zCei*wv#q3%S6GYSEQml+QBm-9oYZt`*G~7}1PKvCIBpiTYi0TCpTWfg<)G5CC``+s zu&|bOkaK*3l#@noZW?(7ht2R%8u^8F$X7O{svDf5+;p;YGsw;bjK-)S$IL&+UXM(}7`^ z3Y1IjdiA;S<{QY)$@CRNL7OC#Q(}F@#YHLK8NjiGbR)($xy9qiBVw?RnMJEaIevUT z7Zu-R1&nKzQgLt{hcnJPi%Mn9Mxg!c720UDa(y$jw!AYZk|9>HkLMqKhzHxBK!b)ykb?3d8QXR(hL9+~ zufAfa1f_(_uDOc*nzj7R$H#606PN$f@%v`5{Ktc3TX=2KWR5)H9Ex&WZ2GMv1rUYj z6ZajAMSPS(j7B-uxxg;^wip$tGyXL3_d!Q#{N!HoHfRGb24e)r4g1a+es~$raylC} zs>d@gJVo8wwQz&>i}95lH-TLH*r_tg0+hVwhM%>VQqOrzsz)wvTXKuAnn$;Y1+qQF6;#Z6>@NWhPY z4K0p#|MMk?m=IKMd3{M2_&jO_hZqH1<;MSS|B=9>)3UO-^4jY-_3UyhF<)_O)uJhV zy%=YeR8TiR*CO+W85)#(*!%d8LmLpZQK=-H)(ukCafn!wm9fNqlBop&ZNq9mZbk;T z-aV3o<%fQ+PVL&9e)<`trl!;V*yG7h3uq9;sSt;q;}7XcknP3g?_A`n_$d5Z2!|aG z54*&16R}>Mq&uJ-LT+lJ4Nly?4dKwQ?L11w&!oyp91_IekL)E$H+MJ$Bshe{p%f$~ zT#VPNER!`pq2m=LGfI3a$={3U63{M^)tpm9Qd9>(o9MeCZLrf`9!RBmVE54dd`({V5 zc3Uw*6|-i3z{OYHiWfP+1?QYXK~WK1j_$!1-z_EPI2dKU{v6SK^!CfV{q84dJa%nf z%)o&sQ>Ru#uDoUxnlv0>=Z2MZIkF`+@-jH{>~q;rd=OEoRF&@KnzPTRR$gNsd-fT; z*nXb)%R@A-SC4ibJ1}F;0-{t>x@QxE`}C$}em=c=9K)NF$CKZnJxkW_@=bXL(UrKO z8QiBYHS?PA$>(1(_oGQ1*}g4VwVHC{$iHB!OE{@VCkl!R>2dO4mapG}hr{^ipJTzd z3(%rj`Tds+=+l!r^_z0@$Ooy^8i=ub>uQFaJ%k#yo6@saKdSfd$1C5%F)bTYSabyQ zzgWlJhC;-TefHN+aFSmV5EZYzxtTtj_pb9qIx{|@KYS9_K1}J z!kMS^A+JUwIvqcd?-qW`CFc%d>+XH*+PsSX#~n${x;3d)vo`nsVBc5W=%Kh9y1yDI@P2gQ$bNHE|s6kL*N?Ce4^Q?R~0^Fmc=%hF^CRW%${L zk^ohm`14;b!G>;(L2LaFy^JybOZ=C?h{g?tIicrC3_a%@h73K6p+nDN$dDnlYu}O1 zU5;kJNxex;O+BoRfBq%LD*q<=^$*vhFvj(fs8j|FJd2@2hH}n1=fq#f_vpcCgHNY# z-@fGLWMPcKi~Z~E|07<9j+OCWzh^8DeFa5p9e4II`rp+~`Pb|CJL7$5JLM3W{HX-~ z?<~K{|Ne)YgB=&qF*f|Xg0@|b<$-(e;+IuRd1~}S)XBSpCQX~5{Zm;^ZU#?1{TM2o z!mDq8#>5HJ>HgQ@Y}~w!qmS>$#2YW>t9hSu^?9f9*`goWyloe0X<7Vj-ZXY^UCV=G z#?qlnXIiC35DYOC6?=D4w?Px0nlyuLE5BvbBhPYdk7F@=7IVdQcW~>dQFQIxj{myn z5jL;?8Iis?Dlj}NjM21d--6mT^I5!n6)o$x=ZEjVp?$Yw38iK7(8CY$U^ttZAI;*` ziPP!Wr9I+=kRZvoXfzHb`%8IX)ID_W)}2QmeVFgR{))ejp99KJvu;h^nl=Sj!Tpas z$E2z6anJC6Waa1a_$%Y+-={aVG9!$8;$dblT*u^h-)H~c-8?} zW_?a>emb#Oj4LkLM?p?HL52<+07&|L9v*v!mcMHGgzFV*5)oGJiy``A! zg1Ri2JdM<>6x?tc6DNGY-hKPD_+rr#2A_Kl>({Ix zzh+HZb!bWJI*Jqep3Ii*CEPLUetMsJ8d1l!rYJ{Q?{x9dN;7rp`@Hh%R9<;$JhgHR zx83(Vo`z5;#E4sO<%SV=vhb^~c;(dzoOJT>ILhJV(@x{=F)vaOhP3cbT*tvE#m>#Y z@XYh$_^-b{!VyLJ{AKjB6lJGz_MkQ_S-Fv?#!aDF{TxP*eun2BAHzcr-$R-!zH5~7 zX$BsnAGn9Qja%`>*jI_hs>#jCMr(%)FF2RmMn6PGdMaPd{gg>lKH%k-$5T}u<^0R8 zqE?f}G{`LDjuAI=_X97`xPEQ!y#G<=e$|Ek%~Oa*qP+9TC)CQ%BfGK~Wo&-a%F;4+ zZQajX)88Z8@wn%KG0a_XJZE)p%tH@6K=0GfV$2Iq@XSk7SiNjDiqi-3Q0g{eII+*7!zIZS$O5--2@7GoZ~9mfeV>i!29a>;Ot(nBo%;v+ts z@g6U|_7c$pd-==rljwTV$uw)*iBLfqDI@`Y%6A^)FjVMYD1q61+O%nhZ2JFfQA%5? zi3;Ha)Dk6V4UP)3^cY;%B^He(9GiZlUB9bb?VeV?B4%M37kHxA6`;!6MtSOQ^3H= z+!#YuRn_0+%>G&aXO>Vf8U8blA=Ys~`FybK8VzXPwlzn!YRsB%eqhzorPOcL#`ky? zs>=2=>8kH_x2h3&g{6LZo@%`T)xt2T6O znZuMfa@o0eKdl>v6Wl}Pl37rPBU&`1SuLpX(o{CCUPbA;uV~)!L{2?-82QRjzaWDY z6G<3aeU6$^3bHad_4HF&vgjwyKBh5CmMmfT;EVC1hW9`Cm`~@^jY zHFI!EH!^?L-#F)%C+T=hH?lB%GkYehRxReJp8W{tH=s%LmgMDTfaCD^gB|P$_=~g{ z8_O`Wpoj*wvdQocfDvlcX+qPcb;uP>^x$4zpEQ+k7X5%JujGhMCsHj2r9y;sHNR|H z&#W((uxfKLsbS5I?Yl7f^=RLuh_VXJb+?WnH!F)YQ^CGn%R!}6RIfg@YkGt#HZ%XT z*~VM4W8uHt#~m7Fi5G^Hg4a?_J70 zkC5xwyrqF>l2PS^XOQXVE_O2?n@=yZe zl9HN6qb4nBT3c~^*S74~zK>m-VpOXT{mvUklY&$l)GnZSSJV&n6i=#U&9_D&T9I3$ z5iMIDK`t@M_wC@#H>dLX{CSuI`zdNazy=^zE@`<%)T)t5j*jx|J2Uw9`<1M{#ITqsPe;ljUh))#=Jf8nmJup}gPdxF&_-2{RI}4VC*hNWDCJ`43TvEbeJRP%( zV=Rh_9boe0*Z6Vceja`5S(Ywd!<_kx5oM!4fqn2((?Wz@FfoJDc9LrZLPBbKDxMK+ znmRuTpfBFaIW1aAkF%{eX(uA4#s!Dn#qL*tk`w-z{Q zv~Sjk8E?J8{4c-d{)e9=vf)R@y}uC00fn}nyb40fpp0kpq8bO!vnk$`@(qDi`?>n^ zq15So2G2Zy74N?D4!>v@RG5%)keCp5K#TUx)IoS0Cr$gb`7s z<<(@{+T}JTV?0N*{h4K}_r?0=@jW?%p=YtQEd0-QFKmP%qU_)8>{c!LJ zVV4Q&8M~PVW6G zuT6ayNpXlBj3Hv@ZHy3S3^|Y6ZXS-KB1E-EQSExX^}6u+V}nt~2AOt*)YMc&8)9C}nqgJYe(Tw9M=umGj1t?of&>brney_h ztlPMgr(c}FsxRJS#*cd}lQ85`9f|tiajA&F;4{wTsypr?OIH)ap>Cu4gvH8E1jGsM zo22|Dp5Q}yvPrAW?OZlX zxHnf2c|e7ew7+2YPHy`@rZgm}n1}WKuzDovcd#b7ffDEETNfuO6jMAb_a9PzyQPW# z$NxHPI7I~?`AVvPFibdw9mY@m7fK`&0fE}JYyamWYy3mycWC~af_8%Z!Tu5u*Fqdz0hD8vIRHP3KH(JF z9o3Ch-_2#tj89m$d_j^W;&AZOl4{eaU%x(u;R^10_$f|4^FoTUGN{_WgS_kv za}sE&k);z`V^4!+k=mtH5b;=Av7 zchVblJh~mO6ClcoWnUyrW>#GWpL`6D-ghGh$fa@97C5mgGD9A9>lBfim5q~{4x-6O zfrQ_^^q3|dSrh~jMYmP;)dY*8*V^rhjp8_(Bz03Y+AFDpO&s-@rna(#_V0DDOW#woeWi)hykUnC#kQTi!ljZ z&p#9y|6pdr0R_uOB6^~KCL^&y2LZU9xE3pc))rrrg+!>N?DVLRBI-5(E^BUvwxG_HQaG@UTtZJB{BI1i@f1{wm=20Z9bFPD1Le zFns=I{P__Q??_x6jGzC%I8#9qj99^+lcF)&i+|OAF7bMd*q6lH@+T+oe`E1Oi~T1D zKUnNE+qZ7w{PQm0>g%rKoGY*9_~TEeFe{&qZ5lH9?P;8M`EZIit>vgrUAW$hZFkrWX@-^S-E^IF_lhA$R$57hld{<&E6ebIl1p3uDbqC+O=y1 z9y^{7-+7z%?Yi>Bb1%}MZcUV%&N&xe!Z&~Wl;gVhVfu_YTzlI{PVCx_VS@*8$Edrx z_Kv&g*zqV*wF7u~{>HF-`xYinoJL7$Wqb^rj2s^P>lmg@8qX;M2lK_(-`g+@%H{}h zl*^b$|H|4`%jnpl6W8B%FL{N9gp|U#Av`C8!rWRs_+K~i?$kHw-tAbfyXGcJ%gV^F zRmih1Jj2Q#zoU1Lo?L#_4IGT6GW_bxc;)E_=|6A~^B1k=#+&aXKkRXQ_oH}u@>K45 z;w5Sq6cQ$eNHmcGEEJ|ev$h;_Y%hLUw}#FgTg4Yg72iticq*06;DPvQHAr*gsh!{~NQ57utpLCxGuIvv@HqmJ&xZIXz)Nr z-F71*Zy!a+PJQ`#(=XJnnMbD{$J4ZNefsr0kwK>o!x%$YpmW#b>D0D4gZuU8=3DO~ zB4Lc<;)4tO znaXiJPN46A)9Bs%Bzhfx4CkDEI{CTjoP1J$?tf@3C-myaP1jz?9e3Qy3BCIA;OH?_ zM?IRhJCc`P8po?Ij^mi_-MIa(yV<#?1dlWX2Ul4iWltPDW7}=S!Kjc;W~fp@xhNAM zGrtBSZ@-PVUmZ)o-o5#J{z9~qnY48!nc`F!oD3Xn))0(h*hLqze(h?yw(ra>x7|;T zf*OPzhXJP#;o#mKoP1(0UU>O6j_%Wo%P+f#TW`FP9zA;S>*u=w0MI~GO^ zx^fRQXU<^NhHXFuQBWlcr3?_U!J&iQS=nb%w802Obug}hN*KWP&aV}yq#}p?ZD0O@ zH~u99D(c5v#2zS&5b*+~AZp_jdbS<0c)h+dby%Qzdoy2dhqNqEWe?Zz4sT&nb%%qR z{%<+-t-a6)k*YF2cxwW0OnsLK#1)la3rBoK&{u*2J9ymmn~?LrTNONulf9n*TOyi&mOs2`twls6`29y0W3-sqPI>&k%Vo$lw@9goXc5syL>nU_ zM#N~*MvE2^@r;NO@r;qE5i!9v+W24eL_|we>@`M2v^F9pD#qB)wTVg0coGv4qa&h? zC!UCi7ZWi?w2n!nx>Po9+#tJ)cgTjdE2aC1XUH2Ld?pczNgx^j&Jr_5Vmd0uRErMk z6%p~OM2si4*;+g?5;G#AV`9XJ7$ZhU#1kW0w1}w^5l_VLlV@z-jfwfPG7^hMMf-BI zvJo*_#E20S+}Rk3d7kK?9Y!Rkjl=?3c|m>l|DM=(h>6(#n_z4rqQzLT>X?XVF*iDt{v;;_EC4reGiY3YHj?^7!lE;C6I6Mu_t0;zMTDr8PAuU3B+jI zWMZ}&v3=CO+{I`+$BdP0EcjeUMYI;tIw5cEiD*x>vC~y_RE%i*xA8=DRJ1Xojj{7i zM2tivsK6d1+&Onbv6NoRE_I6Gr=DnT!G5KZDOlf{ZLwV-)nNm@@ zM_zm7CHeZNbrKUT#_W?--+UsC8?=_!-kT$3@!8{vNX*Wf;6_Qa(DR?N#4HPDTr55Z zgE=Sh`l5%lJGdrTCqyUu5nq_%H#4$l#~SI?u92K|*$CP1_d6l5_*3nF6tQ#M=wM|{ zYRex}HgDc6k38~-zaJ$vO|-;|)2<%+psZWx_G-pDUR#YpOJUm;)k*kKiZPm+`&FE#pXBm`80(5 zL$+A-5oNDaX|@Y0IImh;jEZxK6d^x#903o?uhaG*6c?%MI6<-!!1(bO1JipbZbq@p zBn?i8I7cRam<;L0)5j*<5f z@p(Y53K34pVxys7W4Py0)*kEdYOh!@ZxFUq{@ku{Erp-L^k6ArzJ7WIx zB^W|zaq&zFS$PHY?>C5cEnBl|>(9J6?ltN(?!fc+j-+nATFjp_n-4$xjwfGvof?gr z(yUp1A3L)=T|4(QNCez8Y{q7rIVGN(TD1S{DztL^xn)qqKnw;OS5WSfL^q0 zUXKIC8yR`$EsT6}GM(Eu#Z@Wf*Qv|EfrDt&pq_7xw&p@33Zoo9cBer}1e*>p1yICr z2#N7?Hv@5xQv)W3R;g&EY<_oLjS9JVe!gj&gF1qz(lJ1a0;Q`FH-(ruq*96PQ7WE; zwd5#+V>HGjvO~qhC8RXURAU?)T-h;E8#B*j&XUKm5J`XgDM zf0qB&d-E%V()efK1X||lL;o*_)oGGW);>-UM{(>~ zHzr~#M5J1@j#)H9EHWnMfZyKW^reJu$ys zO&kI+{_D_Mk}kFoo<*iiQp*y@asQK8yyrUp*Wr}~xRdxtc27iCi9{>nh@IB{`QL{p z4zK0V+LDV-uH8r2yf~_ukcttbD@AmrM0}($B4SVc(J~QT<)eL`7;RCcO8**j*gXz! zgf`kD&xa32@<9F87ftdP64J9cT^y!4wBF#o5q~avN%e_{HhxQEB2s0MM5E)VtbJO3 zOODBvSllnD-AmxD$s+yL*AmZw{lFxDFOEPMUzA2fS4uGZjWH4xk*E<7eL%#->^Cg9 zD-k175!7$=uiFs++agiPf;&uX{>%2xB(U@(^xGWLpTykt`)NFhR9DHepH|5Jl79pV z^u$P&9N4{1EY1po_e7*W-A9?i>=y>#ijD2L3G-^~&(!wEW)}p06|N2xZ zi)k@BBAb5tTFx5OUvhGC4c4TMyWbRk;%hHb| zKPyAVPI_NC&mat>Rbogq0zMRMmu&qzsmwOu~~q+enprdpOS_*il?Gv(Py z?@7$7l+pK$lyt|H2~#FW-$8?9z`%Yo`oY^IoK_^Sy!EkY6O~cdTqez$x0Yp_x5)z| zuaSmDX_B3tD`#GKm8{)SEXBLl$%*Y6%HWG`k^RwXx&D%&l2xOb{Iq(F%zS6Oq~|t} z*QQJt;~kW_Gp0-D_H8A%s7TJg;%eErYu_R0)*n%R6A2Vgj8`ewUwFQ}^zsC$G)Crs zG)elOajxt&0eWv_?~e6ycAukV{<0Mk(Pc9JnR}#r|BGZ_l_!7uXrf$u^#yYN#n;NU zH~+4{&ySaLFCH%2sw1K$DlyMmTTE<^JaF&BGVqj(#q+A=`M=yD zS6?_x%3_{)6+7hA!KcZ$Yd6T0XC9GJBkz#CF;8}F`$3NDHAuc%8;PUSeaLy83AqLe1!yeL?NPZaV>XBX_RAI6YMplgRfr30xb<>HEmV?6)!j6--U3PV_oe?GR2wTJyLi?tIJvV?GIE`MiV6Bz_ZN&D)1my_=F#P7INaAL6mwGU^{+@ z>wt$66rX%8j!%2`iPr%V85c#I2IDiPeG+m) zRN|wi%C_541fG&6&H_&bC!G`^ECFXup+cF6O7X|qW-@V=kgA1n62m6mCv|AUMBqTl ze&&8QhnO)wQlx#Nye~`9AQi0pc{$sPO9*mUBzdfmz^aIkX7YSH1dQ~riHCjxA5v64 z8W%!K80`laS3a^366|vlc%B~i3aIo7*Uo2clel@<&?#{#95OEt<8b+Mx6V|`Cyd*? zv^atMlzmRbN4!mpFoG*$Ik*8=%m=zdBBUF!sEl&rP7m?tGXA%Vjg0u~D0Tq~r0__v z`5bJ<>*UyTJ_Ae)jvu<(Am{*ekNa-B@pk^6;t)eumvGlDH}T15Uvu7-*V5~xeztAK zppc=EfUtAT@e`8?L{d6{}YB;&V^3@W*A0 zxP2toUVAl1G-`nBfN~wQ8%9hFqa6AT8Opj6dEv?D_;T@TDpBaTqlJCS8n$de+g43^ z_x%qzSh|xX%hypwIM4bh0MHcx^(SKRz?P2eLja>#oPJh(|NS-)Rm&be2(pL zA|poJ&h=MZ&X+SkV){q3sUi)7gX<_<9l?#1f~4SS2%9Jn#tA8Y*|40OZn=$??K*P% ztvB=I7qfX_^fOe-p)>s7Uy`0d@rXtvR7Vd|UR}nLjr(ZWxEblhs8z29B_;dVSB_o( zFzi22LAg%l$d*lTRFrN&a`stS`J6Pdw zKDK$rK+GpwD;20O4%*+bMVYuc+i2^RWyGK`6t7&w^~0}YOUVHniX>1@M9?Nd!WZ$) zw~j&ud3wY_C6e#}p}0BL7|$wNzYgl?4eM_C+co?%E|@ zDLXbS<(5&SDLznTRR{qkzT1P+KslR!Udb=T`|N(5v{`z_phX8XaX&JA&<5)*h;j&0 zyV-k|^V6dFY~NpMY5UsvUXBSea&WaM@I)gHcsj=YBS-S-tl30-6Mi6f(FWramW}p_ z=Ei`DVq*JQvg9ZBR|Kkt<9oXK-}Upz8c#63`OD886Q7;dT&}J1paavUpV~?#Gz=vQ z?Z;>Inb+~(#)wT{<~XcfwT4GVKTK6D%KDW*(z9C!)@<446XxyWE?x=aUmVMVrE7@d zo2vbgH+Fnul$C5_@rpH6VZ)_J)gFdlehFVMU+we#b=EN|-?X2~yNK ze*bK`viMja7-NqRdv=+Kgb{@pg*JXJX>AbEY+k#R zlaBAos!iJv<)R4rah3e=K?rD#crh@7a(z02qY!aX%CXN}vX`b~JdoLXmt2`kD zC$~T;)Dnbzw*57LXEbqV6G^0D3rPP-x^+@9!a-+R`vb1)Xues|Jn+vymtyZ&lAb?Jno4e410Tyg1DTzUTa)X&RL zGSvrO!~)__P_r2q4w<*Zw`4kJQlc0Goke*q8QH-eOCC0n*^BNEIh@RezY^z1Bp z9NU?d^FCq4vX!h{yNv-uFQIko4orCERbG8@JSX<(Mc3weY+dpdvuDj?&0bB{*A*~XmDKIi3e zFSBL)EkE-bJAL4(!Smob_D5~PqkEYPFd2?E}?ZWhrKc~Ffkm{y@GK5@%@jPN) zJkvSaxP((O2ssXjM<~U?=qS;c=dXDh#1M8|8%j(${?e^M#c-9zQ8vY?ZBC5Qe;rGc zR!1`If`N!qG-}!sKgW-E_4_%rl5mG;Z907A;y>;VS`&*-cUl2P!?ZC>%T=-Lkn^ zwIfKZl*b>wp9PB+6Ls)|Pg`D4$N|A6DmF%-qqOxJ^L1#~QFsA><(KLM#awpYS*%&R zjwoQ8rQMoCw@G+ zeS5ZY=bd-3x74OaGblg4oZVI=;5&s}93?1;T27#qG#*&xNIVo#B;=A%Srbs36S7=B z$8|6gK_fnJ>VdM^LB!8@YqUqCstOHc=Va5fXAe>`(yfAGqJRO%r7~iu@GQR!(N@_F z5D|&7;IkP#`|MM;oyH=xojP|QJ2wX}-Z~q0MGH8tix9I&jrJ@G?kHmZ*d#)G1TeVW z6qFxiF*gjZi0%gf`Qv!NaoXag7zB?c`*RDuvMF%%w-W0gO(IVV7m$m;a_~d zpn?!U*gV`iIBJOvljHeFj&l4kDoHX)jCMi^w1~Gq;gb}}!$4Sm?aBK8Dhf9gCLDH& zRaaA89VHw}0Y99FU@*qBYm*8gxEK{MU`-;(vT_NIy|%IOsFIezraS`0(1sUEw9!$D z%8E*2QO$v}GL)l8Nlj8u^2l0$h8Hs^%a6>6RVj4meq=ywL;^B$-7K{K<1#k(a-*DSzU<%(o#|puZqgDGE_Jd@$8|(bsfT?R8BknOzyew0iJs1 zIUacMUQ$#3fg%29i`ee7l(^ARJv>Dt5 zMOu0qN>@@+Qh|`d_H8@K$jBr&D-#tzfXQwy&65Z@ifZsoZqS z)ue@79PKgsuTRjv}1*6O%&9s$K@B^30Z!8LSguaLc9MH#nQH`S@PYNy#D44N)N`UQL`39FFcPfN7jieWdP;n<-Gj- z6a2J#GxeLd=aS1Vr%ByRmi@Sh>C--9>(1Te*RIR(;n&iuY= z&K@?5-aU>*r=@c+Qcf75c*|;Deq{pdx9%f5Gm9bTU&^t^9);^@Hn01c@vptc)}6)V z)vC|A=bXdQo!b)_jd85GY4e(8jD2}LH{SCw_430k`)MU#f47<|FFJ!4UU-JZE7noF zZX+(g>IzykIs&7t6NV^7OlyP~X<{hZy^U91n_0rP=Kug807*naRLG`vtH{a9MQe?# z6uWnB;qk|wV(>I4uu#Wl->T+`5lX(4|kGX5qNE+8ILWzKmLd@{UeWNL=djz+S zxQ6stF>g%$fNjN<^y=N0ONaL1q0tYqZu4H6x9-d(mtH`fT6sic9-=)`5w`xajyEPx zW7C$MoY1!~Lx-GA7$H)+m+=!PvUueN8q}@Lbr+qC7mG0By6ecxbGd!g%`|OTpAX-e z%G}Stq23Wqx#Y?#XjH!@8`iGk%}JBkuwyUnI<%*I_a1z=cn#NFejcernL1@6*^S!L zr+07C2u?BzjNzrR&(g9>SB^R6SgK05Gy2I1Tz1)&?B1}HsZ-x4N-C$Gc{ZmE=!=L& zj76*?(f-nd*lpZn{+wC7`@u(~sVbKLyq8Xc93&QD@}%*6{^fV%71iRrORwOlBb(tk znkC2=ivo< z)#H>wC-BURQ@Q@i;nYqmr&42;WFOU3V!(s}g)6amSYip{|M>(5jUp6GR{%#)VhJKU zx31&vyGBsHetk9J2M!AEbuPIUJcmi_oG^%^&!ee0G?eCZ_?ui8wV z8o4-BaqvI|TDfSYFt~)X@~BxOpUE#g!Pb>uFyxG$6y{{39TzX0LFZO2Y1br=dv3gn zDQ#Qv-Q0z=?9!hWEt~NLArw&*f+37?XmO|1Ih?Ys8FqW^q*4ZsfTh?@gUVrJKv?r<_d7 z#`SpUfrq(x*dWHg@+POAI+Wa8KO~t1Vek`lAFFRF-?_~?bBU?o!x`_eYVCUNd*Wuw z%F2lxET?v@98yxVSo!ltR<2lySF)L^ssp5_y2PTIZJXBf)AFB~{Q5M`Kj%W~=KaTg zX#On!jf!I*<$ztIY*5ZW5F1tqqAU60(;57*dK+h-e<5M1=Hd%3WA*Cw7}r6gh#3gE zX&irC4{o~ld^T@f$&0T|LQ5r|&;N$aTPwKy(n|?dmU8BRzU;4zvUKqZ=FFPIS?8Zk z+lE=(ee2Dv*tiW{QN`B_zNRt~qj>!qzWsg~LoT_VX7zHp`r4b>bHHQghUJ`m>M%-T z=?uHzLRS5>imw)YO-urBxP$?=ettS%eEK2F)^0#_6<>ZnhvF&+70#k-_Y)X?&2VBR zn|R{MrzqDt&P8;^uxZ8jEL**f^6E++9CbT0=Y7p7XPk*Em565--OP*(`VH*Q<>wCK z{kJAC{_T&@62?u<;N&3}FygMeIH6k`W=@^JwYNP;*AseElo#gOtFK|prgfB*7W3h! zUvS2mLm1eippw#5ClhAv-Xh7uj8hXchRCz5ew&j#M-UCmMU zPD&;{d-mbFt1f5Fck_64!fPDF<;TT8uyyNt4px_O*X{QaBg`3t2k_cc5Ayl*bqge z2uSZFl#q~+`Xo;~XYcoqbIz0CIQL#>oVoYC*Tv@vDbI7xKD(^7_S(PoTV}X|B}+ad z4(!>!g-^d)MJTTwdHEfWKJ@+inJhL#V z_AMDlVL48!UCZ3rQ&_pHlyTSJ%#eP^5cK)5g^vM)2Qp>q9gMwv44c-k)XO%;d|}n~2nw@!?-SWW)ty8FBh>{8l52 z|MV8MjS&v*+s%tlzraZ&MseoxeVBjG6uw!#9@`2t?T)E@UmWJjYsOI@Zea2I9}$no z_-4gQcJJBeL|Qc+C8NCX_=C)O^m#^&Ih)D@TNroaog{oAPCQ`<3m$xot!pL2DnZTgIkZnj|B z1M`?V?G|=!TE~ZO4O9^ULIBrlAEg2?lix3~VhxAjL0w&e@{~X^@hdMj#L%BQ->7N(zCTHe7Pecv`j2XZqwD3Hki=8F~iu zW>075rq#^5e?BQKav0FF6S*x~aMNuQ2xSC0c<>OHT{n>_w_V4UjcZxGVJicM_M=0G zuCy-b#qa;{3^`eT-h1b5R)4pN#+nHJW?JFr7vVxSoYN5{3_Lgy7@RZqD)QU3WYmb$ z*wjeX-hEigM|O5=PCW5sMxWA)6{|N>Tv|@Y0;hDB1HX~v7j)u;69+J? zXC`ldyort9ZKiJT654br;@)|)$kG+>zV&B>ooJ@)!1Dz4%ru4%Kb18rH*k92d{(di zmUC`64IyGE8E5OZJ+#Wr;;XHPX^;}>0qb2XkQ8v>P&vEy9ORFS7L%Xjqg%TcytDE_ zl!_trIN@lF{pI`V(Y-sRhiZ_PKTj%J+x%BClN16-cX;Jp=+riG=r5tnY36vD?BQrCbH{Mu8tFdF)v+p3k zf9F#QT4&+28>l?A30rBj@6wH~ZETFlA>MxFHO5bz!SFLqVPKy^eskdktXRF4I04$W zFXZG?hGU2XRwPVbN}RnVJIHC3M}$-g3)o$)a%u-R7CXis!K$UpXy36D*N(rM+<@fJ!7#tOe+Dl+ zcQ;x}27``2o#T6C5Ur|Z@n=h^kB`UjnF!4}Jkn5Tx=zdNY{Y>wV$m9o8+IaopNW(@ z8JRg0b?Zhz)Ux>XC1mHeqqeRVEn$(Cmd>hG-?1f9L1Q?AX$tn1SCEq4g3X(EGbA^U z?7Y?tI<7ArvofgIvd%fOQV`JmWTb=`di;rW&9T|={WiAkJWT%_NqJ>8b02z&Zn)p?L918mcI}_U^=1I))u*?S}8LJ?yRYGjYn@ z+;rD{&X3U=zFfM5(jyUv*2Mt{P}D7(sF6v#4n6qm`>)ZdAdk3m2%v-xS*^S9;;XNs zFx>PQFp*4~J)dc_A9C=tnoF`Jvp85*=2TZwiZK^o&X|iYLux)8`X9l8gS)UaXTA?S z?qt6D@^qx;Z%Uj~I(N@}fIDZI=t7~%C?%yOU`JT|=U1t3ln%MMJIC`{=d*A3X8yGJ zYdZHjmeWoiiccj-$!W*Ci{Ew10&0%#ynfQ1Tz|_{61od}5I(NIE3Fn!Kkq-HwTbVq2=iKp?|7pFT3heEi}oueSo{}OTLK{Lv4 z;b2iiX*tY!@KI*YdlaR)^HwFeXZAcS5kMdaWashfTd$)uBT3|(JP6h_?!9*gsG~_+ zq=I21&*J#e=VA#BAA)(0Jj1*N&*9BeC7c+%t|BaW;z<@f@d9zBAq413QP8<7%U7+z zbNjSpve_@GA^%s!Kr|t1yoxkGrf7dQNhXA7SkjrW=mwqgvZ$-6MwtPWoj?;&K6v{r z{fW6yHdwotrIyE%i!X( zh9h(XW!YdD2%$MUKnW@#sjUl>-=RIOIU+ABop3{hMtoSB-;JEeBu>k7Xq|sH4kvw6 zX0;Fow(aH*D~p8-=JWZt-*M(eS7HYISdqA+G^9XaQB_rj?(>u1rai%+!ByjLC%a=; z8pDS%f~jQZWVqKApgTk#E~LJqjC=2zOkw}y zY2UU3LiZ7k+obulWEngMQ|92{%B#a1+q)mS4pzo{_%Zjn>gu|nz8Aw~uAuAIZsl%2w7AA(9 zb*vB|LR@v@t+f5-+*tEFOOBS-STf z!jjjXBQrHb+x$ENhTyjoZlOo-zKHlvY~@7Wl^5~GiSkHWL*R2QX@a!O3=)>4vZ{_y zS~|gC5U|j(5tc)As2fft3Qc$BSv(OX(imYt#{%*Ty3($7dmbKgCT;Sv5r(8qZiqbx z_F<;yU_z_Y%xKnq$yjfzxq&#l+9yF8w(F^&?PK4Ju4eYKnxIr+?c z@?pAkXzlPzD(~phO;pni2MZ~{l(@K44X?FMGLVBfluCf`W8m<@I>|l`23u=3vX+z> zn$J;lI5=uMkw7<&uJ-iviepK0 z%D>3}QSsI)Ha42jJoMYYP#jdcP!J6_P+MJ1w4s8P+YfNwWuq_?QGBuytFfB(>o?Hz zgfkd@?zyCYwVeI?%TX>VvZ*w@^&||#QNFs4tvjT}PG+1$mmqD0ra4ZdM4$|(mZ{P} zHyylQL5Hqvd1n!&rDfP5gZjnRMJGh=UTO_(N2dRuXGyAfW4X?$M2pKl+#x26QJJt7qM=a)zEY z96xackWgUB7_n%Wt;IDIcIiU8-$bDB`3zEmJ`No`KwVuIOw&e6&+!5wZ9ZSVp8hAC z#+Y+{&4x@r`#<{HIX*Qs6hS()>rQ%5r%Pc0UAuROM1oLeI%Ruf*pW(>e)A23`}HL# zBWRjV$Y-#3^Jek`tw}c|g+05nX~Skt>RZIl?Zq6b)#=~6E2~$o$3`ZzTZIq|IB_U% zPPw0bngJB7dnyzA@c(Z z?alROF0KGgH=5exL01H5y0bnE(ab4wFK3uqv(I=`N6uB7-_mm&MQR(q-&+a7Y`Vx% zE%UZx&Hw5;>Pbq5rZ#9vdZnfuZqMn~lO*)QbzYs%cpvvZVQ5WwZBG~IK8KLJ`I!H_ z1rVGL7SeXf$h~1|_S6D*j;LhAh0v29_W+j8x@y*6!rffZY}lJc3X|gn&HBR`FQ3so z8%9t5-S|OB)cLU~$|!`xSO7nLo%|yI|BK;FCU4i=?AY^PCCOc^WaIjk+;G!m?AlT~ zbv=gTj~_vHnn`XteE64-IsKfAx&Of@7`OIwYQr(w6%;v&RnxF!#GT!;SENN z8c7^KLMgIZwqpFm2|WDt?|AD)lSo4Yty|}jnw8D-8y6@I8 z`m&q({L|0q*R?$;9WAvbmtS)OFFd}0_ug5|jaOZSt@#j%sIxB@I@e!+4G%xLkhR}` zk6m9!+aCQ10wQ4}?Ety0I&krYXLH~5>G)EzNKen?fk)=hwp~XiOqj?Mb7%2VY7SZH zY0R26i8Du>%KW=;=Cuy3x%sBcxqjlU%$xTF*M9K<30vc$tH;x$QwP3Zxe_U(jzLs_ zFzDWQD4jZV;H%F+F5|DbhF;wZxqs@_PCP?Ox(*t`fC1k!{r1WD zWt7yMcHBGbUWBN?z`_(U6zSN)#FiR{bcr{V=fF4_=dZo^JYTNdfUx4UY1f&)-3m$T zn8gQ+-(mc<*HGBC7n5(ehRy5NGvV56@CP%=X_?FXhvqQo)Kj_S@=KXL?M}=qP5S*LmpUQ2w+{xKj-Nv~W zoI!o~2roYW0)6hdlzSRcK_oJgc8lDuw0(bq=P1!MHzpQ zpId(D%=|}V_#ZhwfA4eQa2QPpcJ12rk2Uarm`EvIinL$mb8AM|^lo*Ci zz~@7^t7%O55Jmu>-9StWqMHUjJAxI7Ve0{65-@erO%N(dJgy<7z!Dm!Y2w!nkP+hX zIC0yD;WzQ=7Ag_PiUXR@p};Y~RyOgt!sqj02pcIaYGM+K}0Utq4V#R8(Y(G->qx(z(B(SB8ZR_~`K9Cj;H=xGv zpM8PlE7$Pov(LIE)I>6Nprnfh(iK8Qh(;n?a2px=+FqQnz1=XlKs z5Hu4+6AEdj5Y#l3<&2vWKBQ^lHw+9FrY@?XnL$!?fwF88i5ObQk1q*AaF0k;j6^g- z0zV0Kbi*KI>S$IYG212~4dR+Xy5EFY9r37*G((_km_9$Ih=WWJk4tQ+qjVjg;lm_C z%u)zn2tx=oJ5Hpb7LnQlQ%VwzQS_7)OscUgfzmVa88*_25>MD9Y?wCZS<+gx=Dx|7 z5RF?X-Na`YPBaUNz#<+AV_6Dm1hEa16b-Cs7=r2ev^dI^#4Q7(W-F(keF<}3c!zEs z+7s{@Xr@U(fU+AWTyI)+MM#o|N_KdGjPu;av|aYQHuO$dkbpn2E`$IvGd3AS(F zPC>zsQ(|n~xRGJQh5=AfQNf}`i>RomNJavGnz*M1Nwwz@Be{^2f1pI?e-@?rXASsI zi2^k*Gx}4n`;WBqzv8H=AN1)DfBr}0?|oJ&g=JZ2nwFd&|7a4@{{(3s4IDjsGy?_< z_-}5}FY>Px&*5LOVub^;@S@g2=*>_F{~~ci;SvMg--2K;Kq?$nzt$JZ#&o&CL?DO~ z;Kz%M=$Jl%&y8IoLimF|m$=nL8E(Z`BLzPW-U&U004`wGmqNhh=Mo}-&(si_qVnJ# zo_zKtbYBXGD{BZh*qnUg34Hna2OKJINOBH>qHX)m3>|tbhOY$~qFFd!58=~we5PZ7 zk{r@{Iw9SO2xvx%1H{Be=q7q<0HrhnILFu?-AN#zV@W|!YZm_3`~(6f0St%y7lG#Y zWBOdBCjcD$QNZt!2kQu-lM(c6qLZYe(9!*=1eC&$!!4$1Y3QPf|4aC?@B_Ypj=*Bq zwspMu`Xct##p&FmyTfH@1PSPl!SnE3j$7u#AMz*1JOSuh0G|Q=$hP<6P3&%RhjLiv-J zPhl7g8$O)8tW1Kz0JhLvUgsc&=EE>`5Z=8NC<9+04bwd?F^p8FxynG-4T3=}iG6ag zI$-)jm`V^3O@}iI$MNy`3~Z?o!XW5(nZ9HKT{8%V0$$A0CFS;$8gzLkk!YrlZW?Ua zw2JRH7P}6vbGQ~v&*F@cXAsnd<6z^AGe!Wvq2WVIW<%<}3=E%e$(_B}zKPH@0s%nj zNEbW~LHs&RAbZ^)nBKxY8a6P}(%h4;3`~cU0y|pEAD(-GgVhnDjg9QyUCpd{*J2BU zfZsjF!mB<4pkW3xoSM?f-zfByG#s`?4NWr%`aqgG!Z6W&LDEx0&T&1iGpq;k2ff2s zAHIMO)ARE*AN~}dOENB+ornJ8;?*plK7IN>ah0PTh@_7D88~d3KVH(&{4Y9NKjx_X zR7dHbi5mS>N9iAF+s`F`@7^UPCA|Ln>)dh29m%=!zd;r+Ui{zPgkR*}EQYsSG>

zX8=?GN1_0X6wbf=CWgoT1aMAoo8S{p3Wr0C>qg*kvY0#*;-OE3`+k&;hn;c`(;P&Z z1JYJU86So7Ugv2IoSIgWl+0Yt96g4*a2V4JFtJk+ZF5_&Ib1=)swG(_1V~Rybul2` zeLauQp!tv9Be~FMJk#4`Al)hvLLrp!TvH?l8UkH3m2Pw1=M|fh&5rL?lKj}~8OQyw zQ7+@0aT` zO1mp3DaAV`^RQ6@Z>T-E0B**wNp8n(oM5)(k}C_zZJmxQWf=+F7-L;U6^CHmPach#JGk=wvovE6&{h!xk-dy&sBt6~Jygj06gp=## z$NUh{?3<)R=%VO;P~Oj3&#t~`R^3y&eWGa6G0D+P-q?k&c)AE&ZQ#uzk^KGNZR>v~ zO$_->EogR~q-t*F?;fRhyeXwM;Sm2eox3?m$tx+S9resV-n4(6{rW|Ik^gOCI8h0= z{1))9bO6D@9%x#S4xM|_PP&_7&C>@q(zdBJ(tvNu<7?v>pCy<9QRi9O1_ zauunC!oWsHbB&KD!i_ElQ?eL1XfO)frRMM>fc^uHb<2sk4OPOe!r(O|ECFoR6aU(=|jiP&8y5QGBR3n>ZxZSo3&G7xmmT|xFlnKBptYB zk7ijG;c%F=tPC`q5`dOl7BJ}usTh%H0?Z%*_n0$z$7El5W8*%HvT-sjMKfPSCfm^5 zrASU5Cwxt(&OPbexo4C0RPNKb*A>F63GIP41V>};CDM*i+mOJYnu%X)R)Iu_A8bXM zoCwe95GZU6oQ;x~s^DH-XeeP))cY8^yT463$;lOWv^b9*B^*hh2Q%<#&1)ifn<)40 zz6=Ho9Gc9GY;s+7w~S)5!TTHe;nO4^`tN<WP!P#}d{G|9bqa(Vyg^SE=S*@Fvj!vC$`oh&(kUgqN7-9D!>BCuzp%lBV`4@4Fv%j`Mp#)5fN0 zbMT+Y-^`bvXHI~-_M6RKFJt|vOk3~%KUP*$;O%mowddz+-!Jlu{8z)}<*){w(z5dP?qeo2l>W(qi6v z<2C9V8@*Pz|9iwNu7jimLg^ToN$1Ha4=0m$8ezL7-IAA2?#i87$2NG*odT3((eIz( zgAYCc1ws10#FmP$mww8pOTQ%H8gl0XF-nWKGXA#dlvg(%z0-9a2%#cWRhCj+-{6$F zqp6N6o`F=jkvu0Zif0Z~Qwc(^ZB~qf2TF-V-SJUgc`>^wH?Wxl?Wsep`L15Wsn;n0 zU2hr_S9CY>Q;DEytJmD*Xefl$$fDO? za(Kj~&Ee8RRM$5qM-`lX!co0&)I{~>q{ElyBvd6xR3G5JS+m$zQ{%el%8m5lj+ZlL zx@MwjhBJSaPPnR?KRmaP{iRMndI8)YebGE>)YRU8R=iDG(=NxRrg$qi-f#n-ui8jm zZ8-}UE@b1D-Jm3;`*ySN$;X&I_W}O=(Z@vMF_wS1g!vCXz{8I}$<70Zlk>}4$6i$t zr+l1r9dM^}6$;BmY&UmvoA-3`!IdO@q?D(hdXn$A?g13x`a0^vF}I#@j3X5#JpI%{ zcI`Rf-rsvQX*_piA^DDGzw+K7o9_9;&6`rn-LSdIFz#?@!dqBQ!xc6OJ3(1hn3!zl zJxQD$pYm!pIS2TKM({QNv~)iThiKAeA8X>G zlFFsy!3{n}sXMZl$&;s1QsolO3c$7;!-sM=BJQ}@(p8?aY0kKIQb!=9mNbygC`c#1 zcGQmBOK_41rJ4+;+iOBVV?!MW_7!7G2-i38!TTRj-xx-^{pCa_671NygUYIUk|xF5 zFbTkp@y(LO%zNl@qQc#qD8<*yzT)r^$LX<^aQNT6D4>o*!6ICW79o=kj&Mg$B`e4_ zH_q;y64HrCDRs2Ha3Kqccmw+n9K_b$KP#u&hEq;Vy0g=ZlDkK>3Y3(rSoQ^bcJGGB z5pKF}ET64fk3*U6xgk#9=qNXO>ioW0$^)Joqr7#Q2(xYTW~_wm>KGRia8%=6_=h{L zQrJWy4Sey*5~^zI9G~C^PXE#J!+hYQfBHwo@g*FCu9OqK3?DA#!*}23KzSXzwr%E~ zyYA+Nm*1qJdJlI@n#9CO_pso1kF$K)5;m+~!OCXhaYoj=Ng6`e;luU@U^>{h_hz- zXWV|n}Izct{ zsZnVfg&b(ECXl29u7nWl>f1TmI<@(#WF4dst-{{>q!li94vF>+?j(SDR` z6TH{Yy*Uur2#;@7McKV!4cA_E89jUS=CspB@y@$ThzbE(n6=-0!cCKA(in}QtOgdn z`T_$_9?i}}^$sUuvkEo8L;`=2f2SBfB#Qi3<0*ua2y80K%GkbVKhbE6P%ub`?mfuO z(y@`)%H27|V{F{8j;h*5QZw@??B0XSpib4{a(3+6OEeb42&7TeyEiS;Lxigiv17+J zY8xen>7z?wS6b)hlHEF&u~%J5C=?=IU&-bz+o^7d6EF?h6&BGpFB@IN30K#$b^C7W z8lw38DHL|?Om53;n($-*HsR_rHg4HL&w(e9=7%Fkswh2NOYg3o*|cdLhpTD`rDW2r zsEDkzAW}NT=Fv1pj69V(JsVKOBQ1uGh6%jVr2si`3)Jw!p< z0=DitK>z;z$V~C083wwHQ-9P6rb#BAzH7lrV zh?Aa~M`2Mn(n1CoTyzm>IjvDj60Wac`;NWTg=6IB7tpz|6Pl*5qV;UqzL&Bi^<<=) zbZVujtSDpImtV0zS1_=DFVa&}*t2~%2M!z{l$JxM9zDrQ4bV_m#jc$@sj3T;)he5o zx%pI7)=|{8GXWiTZ{32HmQCAst=)qyk=*%j-?WbOR;|g&&4XAKYrfx2QBf}()Kk(xRY4 z7xLS+MI^%P+Eq;X;R>XkAiY&vx^?SL$n=h^n_`$UQOk-I-_p6)P+DfCkcc+0ZA%Hg zdUYY%7-8#fVF2v>-b+uBBsPPf}BZ z#2RW@wq^?hdlxa`)>~-PKEH`s>R+mzeq4mmQ1M!J?%GRfc@^P(yNO8+DWOwgdoI25 zO3wcEMU)-b&W7*TaqRIYF=fhabn8;UUq5)CiX*i={?ya7?bMNuT{_^oHoC4kXAvq! zX~|xS_gB&wi{T5U)48x4xver0M3J#Nwr$x%MNODMYC478dyt*#L&n2w*|d|2BXx*S zDn&gC>D|8%mtTGX!%jH`VV6_3Z#V1Lu4PFpAHBNgFl5*XTr=*soHYCdq>_Yd%Gk1f z8x2uKR!$qb6crKF5>%D$WADC0G(_S^%^<&XA?@<>nvU}|&)c$Ts3~XF+U<1d)t`b^ z8I%j1l*ReC*+GUWaKf=L1JJ_&(Enj?|O_yGM2*exNwRJn4j~PJAG{LHG zSJARv5#2lHa`-?AyNk<+NkPl}wsh*;!A;Kd;;H|*IQxAM18ae@*t>BfH(WoF6GooR zWmjKE$==<}y7w;DZ{NdRxBi+$tcLQcYV25?PnLYZYk&HHXMg`Z`E4>#9@D(?HqF1t zFY@mbiG6*PmwL+g~&M)ZrBG+<_Iy=8*?(!EZDzgm^5%x)sYPuW8_$ z4F@=F)CEi!dj=o8`zDJPEusJ5V_Cm_Hz}DpEPUc&R(!sMS+k~d+*ub>QCd!8LSz0z z^T`VD=l)r9nfLsQlx_K%>C@-aYuH&-lx*XOmCCaVA14?&z@3xsq9G3L3%l{rr>nSX z+*p1)?oxCGS~9EDCSFy-O;=yW?-qT|alKmc!TW#W`{D=>-7}u=SANNX%0|9hyPbZ= zpUkZjuW=(Z5}|Aszy3U>W>0RLbQP~I{2i~n_ZcS)8N~j*#mKmYArr*HhgtUdUx~#m zmVC92iPP@myi?mDWrBkx`&l2#At%F6ZP`|)&iEaLU5lu$twn^gnSb9zWJ3j0Cf&v{ z#}1{SeJ*7O_cM0l{e1SxU+CAhwKEEu#8Q$SJ9iKhDRk}Bk@X+F%lDks-N^ZuU&57_p3k$7J;rgTk7UH?Q9SX;Yz`c*BQ>)v8#eCXzK0jk zvwaI*ec}<`{%8d~2A)KE$YA`XCt%A6TQ{wvt}KNfUE8o>?YAsg@GQN06|rMq8Ev~1 zF=yr-eEr3zJUVAC$Bz6Jow|3TsF!5s?B{v$x%p%oiUqUp<+O2=$Zgl!!2n8Ei3*Dk zUU?qbx{&K`naH7C-!XpD{VaNWF-LZ8WYvnbl$1x$XU$~Xw7Fz=ZOP23lc|#-GBbi~*?X7==RH6{MvU8Un@F1u-N{T1@X6O3 zxb^nix#ZU)+<2kx+65bxsAk4pH*wZ=bGhM)Q55gl#_V~|@zOK*GVlJ`91iS@b+6T5;EOX z1?3(gswlsI`bpk-|0DVi8A{E;ErjDXntRk3#)(|o+ z8bk<97lf-0@y=_nkl*Ea+71n3+cs;~uHo8ozvYhG#uII5q#+vR&M9}&reiOjeeo&s zx^{3bE}f%(>{_0GkJ}3Z@w@4F@%(FlCSq%3<+S1I$#--6xU>25A0A`ILw_WuBz2JlgHJk_ zCl)?Tj}CcGFfs`-NKjY4jVpe08JA3)&74W+@zjF(Jo(Hkyt3$J?w$20Qc50qa4NIz znZeHDy%-s}oHpiio}D!wVJXV?ZDs1@skCdG!`rXSW$Kh$*|1>`bx}pzu0wg{4-YwO z+-_je%P;W3`>!+SiRZ9OHZpm_WFCF%BS!Xa!6j#(&985n$J~kMaLd>W`Fc}1{*2a~ z_^VOOoj;vWz~{uQe};N;-ocN+Mp}(byZZr#oO~t|r%WZyXP}+jpTWm;W9*Idxa91C zSV)v?xvZ{m*c7po)8anqo zmT9wRkR}scdC_I8T>dFTPB|IjoOlpQP3O|9$0LC*pMTHW?=5A**psM@*bEqUCNuAy zz@DwE8GPLF?3i*pM;at8a@sOu#!OOGHD{kcj;(w5aeOP`g5w3zs7>3#W4LF=okR~8 zGy1}bY+AdCXz4P(-d4uv%f6yzKvG$LBhkj{<_XGp8KEuOwV_v^9;{ink)b_LVfDA) zaO{|C5klv}E3U$}bhdoIjycc&nR;m>F%Zhhg4Lu15|kb~%%9);oM&Hpov!V3*u8NL zqsBgfRD#UxJZ_yl1!+aeZ1n~!R&Hd>NgXkK>5Mw}EG`;xDrU5jD=)o`ekWbXv?(_e zvg2HF$z`lvyPS4~T?w`B#+19Jk(rSKx}b8*g^tltfN;t(*&3X4*<}nH+>eYzn6JZ? z3_AW)CQZAUbY-DgRa|}J4cOApfKNW--KF0$=7KQ@eE9VURaN^~wSF&;KK?WT4UgeC#;ZZrM&60$V!A#Xf1_mvIy} zPrtB;)SS*d`PgIV<`ItEJPU-vGy{zJ^@UirVCRA=yEb`)1zHBlq6JgL5ZwxZY;U4O2O;D4$LbE#Q+sy~~uD#g1Wi#KeU(X{izD?`Qbf!P>I3Itq zg3CvCM!6W!O{>3T`FGoR`>&sq?YCI+r$6$$C+9Hqq+^-+z_au}?hJ08d<#BJV8lu> zR03T|kO_2ufV0jU&8X9dks7Jui?>?w#@ip#Z|c=7`|?YM3>`sgz(^hhJE4pQ%J=Qy z{-@vMnHOJU_;Fo`mv7?yYwtn`#al1GM&I83xq89`O84*Lk{hN|QxE-mcjo=Se#(f` zj$_qVpL6ONCz6#NqA7Fwzbi@-BU*oe2j@Ob0~vh2@(c9C>p1DGaU`q+ShnNH`E;Z( zut?#eao6$OgSVmEhgop{0y1+uvu5*ZT4o0EYHcVtTVJ@F%Zln+TDI%MM<2ey&b3Rq z;)-i|df`wm89j)npIStV&iz>a<_kPB{dS&z^;Iq&J&2D#|BMDb#G7v~rf2Ui=(uzdbVs@$BQq&%e8mRWWqHUFz$kL_}%PB zIQP`SR8&?%dM=CKTu5#4R?Z(glZ{(;(78h%DQ-5ma`CMhZQ9VkPj42#@g|clKY=w{ z572ec2u>M(I(v2>!mli3Z8>Wh@s178EHq`Ldy4{?A&26OmOq8+_7!>vFL#q^x zin9GARGj6XeaNy;m-5%oKB7nOPDda7ddYSF4I7PSS+HQW{Yp6i}px{6uPNDBo91zd?Ez z<~aiC8N@0MpyzgTLEi#RB`7H=X5Hok+&N_?K|O|&HhqQ-q`s<}l#~|ackJj|JR2n? zQW;L6dlg5;8Yta&kes|c1dx}VPV4j_+xPAwrt3tL8H|d6VKTH=8&)p=nC|_CliIo$ zS!rpQ$p|2BR-PcgM>pzfKIC9&6>Ha)aQ29iB zIF#(%M_%i8=z$<;3A%Ub#3%2)jfyuowQfZKQ1t3jz-P-pCu-TGnoTaCljM`iIp_U` zcdnnsp*?$f|1Y01`kE<}6mMtimIK^*_bk%1ILIK!4?NcM^wAX5RF=`YeHY9WXI>9I zrjQ5gt0}LlX2aIKoOSN6-E0pVG=&mQ$u&)A7)nPED z+&O8aV}xxBT{oN!o)T179wv@Sey45@*|&_LyK8C7)}0)vsAkoUVgf2o&n|7zWi5kG z7|g=SkFsk|IUBZ?F#ewTXv#)m{{RT+;zT6~&CLLJ@n22i9aXvjwSP(!;o4eiYa+DF z>q%~YI}(kX(Urn9O*a_~Y-u}sh5!-ebCR5B#MEpwJ&301?xw|YR?t970k%VjrIbSH z0i+Q0>eYoVZCbH@-Fi+NT1ahun6rkDB0W3Em@`k}(La90zOpb^Tz3l_cizLVN1np* zr~QiCrcNWzmRJ@jDL^w3dI0<>SSUA^#QhOGivO3=S=cTx;RU0s8l9Ocvj7n%mbMbnEXbCCKjBjj`je=A}O@Z4H%UjQtNZaw=@ z*rfwAr{BTU>Gv_9Uy*YSDKY*RaSi?=|9^>=1lLOSpS<Ppnw*&(k$t+3fWFBa?%VMT%7kKZyM+plXj)TZhtL&<4z^{HnvubQ-P;fr2%%$ZCQ5S+yJ+I&a%wWBFm%{SM9OyZ5R zzVH}2wQ0qNZ@orV%Um9O{0S!AIhoA#6a)(0Xv&5Jfe;31p&(YYp3;4L0I;P)i;<|W z;IRkqXY@svG5_f&x%A?TKuH(Gtss#=0m0N3Was3vedBr;`7GE|T26MWR%lY9*{)p_ zHbPiV!hoCYpy>j`(9sddh?g;KqNLUo6;|;0<4@7I-yj};>E!0-Iz49wu_6tQldn6WV3rV%F6eXh&xWxhMgt&Qc}rEPosU? zZ2lj6=N%0^Kb@um1Rdx5EZ@9sG-}PPhS~JsAUE!oU=Q%q(d*_ZVDDeV2 z+_dsaf$7Jm3~YCNh)Sea|6|EY2=naIFOXQjF>PBma{a?h7mFD{BAHnQB&Z0#Z1~32 zeER`ECW_*cV)_l}%|o+iGy9Pzc=W-0Db35KRof2ar~7zf&g0n0MYL<#lmz8cieNgl zD%#_kv_W}+M9TRe!NS>O#z5fTFHSVQ0(>N=WKl08h5fsKV%wIVv9u2hXWl>=4*2x~ zM|=UaVW5?O&(TmTWnhSk#z8x=xVHN)0-`arg-8fQ*t_olyUPzzTH1hm>1m`UCG*v1 zE2uhB%g3v}Br!3Wtn7T6G;PkyFV5wO2WRl%;x~Ee)wi+n;qw_NBY=?*#59F%TQ<2d zL_Wf<{z+p{P*g;Msrh8dJ5(O7Wc?32@CE&3=hnkC3@2Dw`4H0p+X)U+fE@+kfZ@mR zWiV(^AM%q;ZomC*tY9)jhxfw{*YM2Tr+DhQ=Lw|N=k7bF^2RHV5u}=%Z<)#V12y;( z{Di9yP;ulig3Xtotzz>}JDK(HQ`|7=I)XtzwrCO)lQ4}4hxhD8+XfLMnZ(pA3}Dyx zUx;85HUUEs#$?>YtNHMq`83YU;{I8Wuw`#K5s71D_(#SDxNMpV2#}DN!Kk6f@adAp z9I32|zDuvY@fzVkB1I)-DD9(uQDg4B<0j5Lr7t&Kdp$e%IZO`@#g>i*di@)Nga71M z{Ld4g$NVntj`|NB1P=Z}#Ni-Y`^oz}a$gAtw{KzXwhG4d9zs?^B9W?HtX=ypjazl$ zg$3{MYM#l@zwX2K1+kRhRcnRa2utU_F1B-jG>RBco47#(F|(EXo++QRSepU*3_6jA zpL&ByS6)H0mM!`4({E|eq9fuN5L`2=lX5MIdg&Q7D@x(+XXmqE(c2`Ons%+q_~6lJ zdF8cN2p!x>#D)Y>WM`%E=7&o;{^VgU9Rw5<w-e#*-au``rR z`*uAE)mGxguOU@@wtNZ4pLG)-eDon5o8+VLVWg(hu1kBKc<2E(Zr(=!j*XlZ$_vpI zgYMnh@$ssqWasCxZ|hbhAqlM%7y)WYp|GHo_GKwtKj|uZ4j4jpjm@ZYMpD+SA$|L` zXY6^SIO*ik5DGDB)Cn{zuFrjw#?ZHaKaLsLm9x%2k2!PhCA9Nr)~ww?UYld+*19df zZuk+?h>@2o!=Qb){#bWC#*0tP;r^$e#WX=_L6o4qDOn}pGwU((#6g^N$|#P%cpCK! z3a}2;k{qbz$+?fvpty|fhr(c*H&OeQdM~~pfN!Qc5 zNeLUb?4?hFkHWkHc5M5RH(q}YvuYoq8conp6f|ta_Dzp*{~fa_D$eHYA#Jb>hh?u@ z->%s6=5XIF)5y=v;O(WKGHdpID0K+5V~%z<7%CdI>y6MT8=5#EcW}Rsj2?Fvm)>wI zh3Sbj?9!ShO>&rd^CWup>rL49GwSrek`PEGNi;7$`5fn+)1L-;3z&HEnY3-+o~K`2 z#D$k!MoCr{QzndJ(&Sq?Tw6uG>^ugv&v$g5h9JHmow{}9)#v81cYh_Vo0l@US8Jw@ z8^!tKXE1KsLj?V9)M|W&4kJizgO*%*_E7G&gB;lXT#dh znKv^~gQ%b4XUF=_xPRvD)T$td z4({aMnfDS5CUKymmIiGGkd~Uo$tMnB`P7Fvp?80Ri3v=fegRo&37mJva8i?l*hT`0 zNm(>+(}vECGnhMb3UeQRfbmnNGve5RG%79R{wY`U&}{})ksv|8$&O9yIOVv(NNOJY z58Jfs+J|5;7~LBDQ!-+S<8>?IWUHER<7J$G;iZhf_&hpv>%_KSw(;(JpD^XF`^YcK zX3I}DwqX)TsK+NohX)2ObO9`2E5UKkuh?n>O_5+y>KGiCsc_ zXZkk$e)5YO(6&=ojvdsWfC&v6HzlW_nEeM1k(`vwph1IZR9Z@DX$ir^6iQ1Pke!oF zNu#Ee6c*66a~H}QH>aYqn)J*ph7BJ^%Vv$}H(($MiD?`%A|F>wsh^< zgCvkfeY$s|q_mhuO`5WQe>pxg zfnx>^q(#%lQwVVgi8fpg9~mv*gN z;x~L`XXn$tO*7JxoLta_C8acL+6`$ zNJ>uUNJS;Nxp_2e+LZLvG@3MRNhnlJhmM^X(6286zaPZUh%-ksbja}p4I#fck9O@l zQdwC;z)&=8(uCsDX0&e8fr7j|I&|nvLV}-2q=x2A%E-^IM}xdHmaYDp^DeuT!mM9spN^fnQe9nxflyXfMuVb!OcX`M zg_JgK%7DQG$V^SaFoevUJleKxM`~gMS@rAFzDp1Cvoi_!{M64Ypjq?A1pEO~($ZEeM** z2_%T-X?I*h&>`M@a}nE)_!xi9cupNMgt3=jPP^tM1OtA$^yp59&K>C9qc5k8IFn1q zUPwW`RC06kXxg?j-Fx@ryz|fFgcAmml9Wh6gA#gl??Q254xKu6p-r21^zGM|UcGxz zSWrY^aS=Uwbfd5!kKVny)3$AU`VJVx+2>!t`R9xz$>;cEw`kvyZk^hbkyekK`~rIS z>Ox`tESHW6L^*XaFu}0+@rNH-`TbtTT{nR?jT?}jl1#(0<_tdWFZAfqgBGpY(ymh% zP8~LktF9bFaZV=f+IFN}yY_VI)R_}cJdq(M4WU<$-n44jl8#-was2S14DQ#Rk_Lqg z7%+eqt=iImz(9KR?m?@T%^7@bFWR>2MDIR*8FtzTjvqXLqTDn}8#km)r=FZ}^2wZk z{#i6C$|vAv_4#KkZ-);b=DY8{rB|Noixojh{g8o}KY4 zMZlj(K|wK18_-WIw9l?YYit=;G$x4s%&PrT%ntz9E-n^OA)Km%z3jU3y_*4EB zqLgCCjvXj*?ZHuv;2#YFwGC3i-P0zqYFCgaAHSDW;#l;FQd7CQECKDA9w6$}5#oykqwzrbZ;f;e&g5>)mCPmKO8V=I^-n=0|yT{)_bP)|$AdI#r0) zMWSTJUYVl`kveBaJxBnDwAkU*^Z0ojrhi<&GA|oMjHnjZENDa%ayi#K6R{Fkf28Vi z>Fa3AfO0b#h?_{yh=L18gAoN%Q4U0xV-LYgTXp2nF4lgrhDp;N;J*9srcB>s;^+YxLf_>2G^gJm>%NPJx&E?Y|Mczj*JYg%{2X}4jN zH$H6lTz3qr-{U9~bR%>C*>*^73-#&!5kjOD=U@K_9M5iH(7Qtp$|n`hR&1FVT+C0ER=CV~aB; zD-Z1E`U#h@a@_`p*-|T%1UYx)NqoIw6U)EZ&!V@UrD;KSbOvx7dR<~+oTzaxb(}MH zV>NX`&^$J8H*1X+Y|;2kNB?EJxvYQF&+Z`e-V0kCbF~?D8@I8m_A+ePaJKEQb>0ml zf>xStU3;WMok#I*eGd2#E zal}TQ7u!IA*qEOAU3orE%3XksDDaKlBc|2xrVf2nO^$-hQPJ^JiI{O0NQ~!7B-)k^ zsPJlF#sHez?mz$Z6EDB~3Kw5-8SUD&bru}KDYpVaW%JfT`&|~+j>afO%Qk{@hKj422PD--E*Oi)3u+ zHhezz{j!zWv*(bKm(O*R#*&_(*t_!=?zrO~cJDvv0#w292RQSBi}*{w-oy{aC`|YK z_@X97A?kDMz9rEVgI>qrG{5$ax;eX*NL>)-wr`AL{2$Y*h`8E+p9@-0F7On`auR>{ z_y-vd7VuJD`f$y@K1ET35?Y1**j_EgPext|oig%BFWg63Qi8*kjExqbJ7?eqnt1fy zDoP%$l!{V{dyvp6kKvLyD-6SQP0-@xq$WPySzIn{_qUF=oI_Y1zsYRew2b6>5vOj- zX`j-DW%L?+GMSm#Tzc7+)K4~}N$cY0C<7G(e(^(Dd1DYfa(e>Tei4XO01H7W zaT5;4=JkJyx%yA}Q~sBtL`0l?zQ!M~1;hoL*dR8xk>E@+Q4kl?e?-q?dZJH zcwj90827u_+8v)3C_eA6lRiq-nJ{8kiHbo#Z+9DAX54m)&&BEejRF?;dCusiXL60f98ENH05;$Tm=JLEeen-cUTVE)jbg2$Z4AS7PnDz2iD?3z!&Y=bLt7|! zH;>_qW@Qavfvy1pIMLwV9UXnANldfsfL%9}fZMmAFpg3RME{jKIO{k6#F|>w{VIwv zb!@VaJHdn24$P5gR$fnUAY!;nRm52k#ZA4Y#MRfu76(UIC>Vube)*Y~UwWB|*G`NA>!Z+K z?C{L$1@mNRqK^9&t*2`w9DQb&hj zB)CAyo8p}s2EaY;0iNG3HNTl)B~G&^#FP?p)Jcjcg#AsFVcfj$X@F35HvrC|2v)d; zN1t5486$>MFDuRMOK;o+a9M<%M@n60v!ip-3ldf2MXiwnh6-cb7M29?`+eB9<>cj! zsfwt(<51B$Sdl93x%Uw|bn4CEfqkR=LJCjArO?Wct&C_umM2Es(1{1wp5DyUR(kF7 z!*}2F##?W5@ih}j@|zBQ$?r5={5A1)@Y0;A|E_=k0eR=0cjEG$|L^2~+(>ITjha#@ zQ(<{XHF6)1lNZ@Z(7W^v{68v2vCMX+J#GOC9wM3#+TZX%r zbhu*`S_>a7S^9U^?ceMD7ZX9EIgD#-YyaKF`BVPI;sc_S+`sBY6{~{9ue`)=qmVO3 zp6o)cSki5AcgCg?z>fNr#eAR~HT*+&-$|nm?HD>@Bmwt@^_Gihj!V1+$jy`L`nNe6 z5))I7u;BUUNhof|iO2LJU_dO}q%#=^0#*&P?zxLLeNLf&pKdPcYn&!79?0NoRg?!m z9iBjE5j5lcR8(yD=dH=Oc1)#kw1e*T?tQ%dJb=Px_tx*ZamE~Od+=d)e7TgZ`)e68 zY#2ee9RG3zWG0fCd(!>T*_ozLq|x`4K#Qtk=h}-FK`NjVPe{t-i$5 zS*SX@`zUDlB<6rtr;Qv~>fAG42XeH=LZbDLU2eE#a=6v1si`@{!q?wr=t(C+dJ2YN zq9ms0lBk~1)6#l3cL1L#53sp9LT$vfvI-m%a3yaoc$q_HAtV2KGJeC`aKs>bY!l-A z(SV^WY`dD3YrdwSv@>;`jp$hO)yah%(|F>JD=$)3@x%HJEPU;C z&Kh?W0lyjDcGYS7=zHO|PYkdA;mc@ZV&Xq{vG$N~^nbz8ti}5&|MP2AXTw^jIR66( zjBZ%f?;ii(%KsI>^ScrqXMSfBc2pnK(FD43=mtV!)dM1oJ^G< zP5{Rz&~nol1r%V1-Br-%oQJ3BihvyfGm(fmj^-fb<>zqsUAK~y6lC?Lula6kCC3jN zMhHm2a$C&6(cgKHBIGXU324Eg;y{r=Ok1fiFq8#$4HyALe1w$)JOfheKmaia8Hxl2 z%8HFa|*b=Q+v;_^|{6%8xPy5vxwb zoW_WPSqC^fWW=ZdS{Z}|{AdiT8vH>l9KR}4+0JuqL6d+s4NPp54uO$~r$;s<;%@Z= zF?UGMZxlx>XXprG)uQ}~M8t=7``r{lQR|ci6H7ya0Z!15lbJ+-unJ-siCE%jg6g11 zx4*F~0S#uFbDn@nwL7ANgav%cz|=J$HV#p`-yL}dVux7w*+(2qZO72zCu10(B!bc! zF@sJIXhpzq+s{nI7TiDpL5mMt5@K;naqFT9*j5O`XFKCZC1NW@5RI~H!ANmA4+Wo& zpzQ$K^{DV+IJ}i;AOXXlfGvWlY-iYu!cuVo4hqoKu7=bXbZVa%M9+0<>(;Go+_;gxef$1@)mK$jRsZfH{3-upiGsj?tvH&t7oM5N@{hmd#FP4S z^`*m^HTx+Rzq1@9Oz-1{GVaQYk*aN+K6(s?D#8RzgW`sbx%P%hv}@Ud88=O#Y3ELy zan3nxSo=Bm+&7yaw(X-~<7Pbk&|Rb_C)e>aLTTQazkvJZJVB-S7;@b4j30XvqAebn z`4BJ9o6i{|PvorOCo=ZZE7`Ya7b@W6nkjd1T-Q5+4J*e&NyQfmHsSjsiJA4rif+m>(=$uYtWSGcil&; zlKOoA?RVUI+nwy*y@QmLEG`>&4aW@X$Fha5G5waQL;}h9O+Uj&ox}MTokPXWos7Hj zKIY7Q4%3F0UV4RhS8nE*zMYsn{vzhT_$<%8`ZiWgHJy4L!<7>zP?WB@_s;uR@b(H4 zg2_y{{u)j^en4!}blb}gRWSRZhk5<&WoYf^;!8(y{9pQV@7)ivYQ-wF3NYlxX zcl=C?4*j_2p1UzCw=wpLoA`0Z9xVGH#RZK>Pfus-FFz9rX(mm*g=3HH&#Gn1xMSws z?60*mOg5}q#^gI6W&fdH$*h-6MNJkl zRzQhqh%5`+KEV6$eZT{Ap5x$=3XU6mEK?^>;)Qw7GxvoTsjP|6xqT-l-ZX{u1kJ72 zUd5_)KNGPuscGrlc;^H3ZC@W#gqNRvnNL6djAI9OVAQZNiK09ZQ8C-Cr(YFM?-?RgbC6lH9%bZToxR^1stydc@xD&cnM4o@<6EP=-R={}>VZpYo^t zUlPY0teh>ix6Aos#W5jiWpL`~^O$)3IO_RAtoh(YK3}(i`{zDIuy!w3Ot_tSX=w~Q zsSWFX-p_OMUZO=|5({5^mWO8D%U$=+LgB;lEDZDLL$m4LcQ8{=8bUy6(t?Rm02psR zedXmB89wY(hK@QLi9|?9sDVHt=Z?FI3r7#7UQiM6Y3{yf7D}borq9VRl)AP`*~vV z8`M|7a{dKZa{j~_4C&FBDbw#`$vqH6a>uAY1!y-yrMz6e?jLP~-1ankS+jJfe9a($W&E8geXXI|vSS&z~@ z*W`{n=P>`3x4G)vzHItsCl_6P8z=Q|NlH=>zi5c2f>Iz6mcRQZA1z(MZTCMwVOAEI z$+bNHL zlW)JB-aR{#8wl~@>P58geH@ofoJei}KK<}@-uvJq?z(?A*$I{0H2pyqEc}4ek81+r zq_c||=iLrf8nF)Y*sR;wu*=V*Pd`Jt-zG89$CPPzlU&e@xzlgs;MQ*$H|Z9#%bJl> zeTe$mxlDif32L@}#)N5em~#JYii1^Le$5?x{>6H_l)=U=yP0(%*m?bnlzJ^C?sUR!Fz!VMFr^UeAnXy2lg-Fpr&^ZwZs<|J{?Et8n} z(Bs@S@j@m|ypFCTE@Ra20qouOGuKRcIgSI+iC}crX`8COTbT3YbDTZ?dU~~KMxv@> z$CmGz`{J8Sm~;zGOS5@+=5+3PG%uLtZ z>za3!8!svfY(b=g*Pnl!cUOGJeGflLZbk~h#1vM&`zFD}WFC3>S*m_o$C#_8GUb7} zv@P**)wQ?t&4z6xms-qu{3*s>e+%7P7V`G|S9#|7mk9WRjKBISveMI|25Ye@nSJLp zb{J&IL=GQe*RGvT1ge;bI8(A# z3R?`!gdiF9vS{4ADNP%dk&>A~PJS+}nl|OYFWad&w3l7`4>07clgVjN!r&7IP%p*L z_Zxpks{nzdBy#feX#o2`1i#s~5qb48IC9u=;?=I1QN&L|Fi2)vki^6w?|$?tja#&( zOXp4$l@!shUvIu%@iC%pPzlt}EhZ-?lhouON;`A~-kK`P;EhGgY1h6hZCW*_q%fP* zpuysWuh4h!F*I#jM$48B>Dnfb6>C1H1`~X#U?J#w-$sF$9~qQ%Q;*P#>b+cc-FSrfYV?8c`bEpaj_VaD;}#c5Q;pyo(5 zYu9|uX=k5JQR9Xbm6V_(2ids!C(ass0}V*#vgt`5yY2}L}qplOf&}`DcRuWV(0l zL}`N({(AheeDT4X{JOs!TbbyH<+^W}vGvHOAQEEfyNl^Da3GCaHlwI8kNTNuSXwX= zQpn3IrbFj;WM-w2l$lOZgKQc%$mYPly;SVmM=+R3x4xYyDlDc!K_RBCF_e!!eR|Qp zZ7Z~BG=6HUYFM-SGyZzU8I(3Gp|r4wjHE>T#C({jLoeb6xM_|34{B>X_n4T*QDbWh zQ!KW9`w@Q`JcuQ$zUJ2-zNAO59z6Z(`yfa7?2|=wY}1sK^m?3oHo8K=iXWlR3yvBSa8oq3wvmahzhKT;Q32yaU&pH!be*yJW2$| z*V@}2cqa+Ajvxryw!JtrYz>wckO^EmOillW-u_e2bcXa@{y9Y(YjHM`>i zVIjiG4`1Po(?_x7%k_A^CJGCskMQ*DnH)Fh7}ox<9m{Y6LZbAiF1Mnk!M17$)f}Wc zVnrQZAcE*x(A8*NL2Yd%RW&u#Shl-1*@#_3sJeoRswxggB3Nidhk*#;P$kvX)l`PV zguJOwB7{RnsI02wNNt#iJ3f&x;ZOxNl@(Ofh6zVa-ytHQBh*w^QXL8ra@)gUYVe}2 zy?g(wt%85bzguD~9nlEUKX^yrZlVlBQC(ewXE;qyOXkqQ!+=96vUh(uDe3jmTA{?* zDQgr}71d6jSfA-=Eww^fHbEmoxTey1;ni;`3!D!oLr0ycW)j-6AafZ zg=@7F!0>}*Th6qs407scP;q!ak#HD*BUP0oBq!rI<~#XUW4n5f3MLk4k(nB#s_KZ7 z+Ds`hePm{3bLij^BH}DgNa{72|H;)0Hb3a%_JT z5f|_qXhS1dC=sl%MPiblgrLd(y?X&0Ln)ND9MEle1h+T~lW7u6OQxo#2FtRXcT+2p zQ!@!wR$;k)S#=~tQc^Oe(ulhNM~SW#h*BgZ1TnNk@1eBcS@caX3{5a43CoHQj#$_N z<%bUAPst!LB?+Garssp2U?M0LL8%C0 z#E8}Z5ph7E25mXM!DtL+6Hz{@2@($1kd~B8MP&_pwr}R9>u#jl@-ybLF`PK4J4@et zpZgwqnv;j0!37tcM_ztr-3MsL-&d(x3}s=6#x(sz3}-$mzM-G#knn}otI7WV#c-!$e-o1q|5HTEH*?_LXKw+7RFrdUjNeGnJPC+8B7q>*&V;qlj6O9TVWa)bg89eA% zrrhzU%g*VJeFc^k=D8=IuQ7s`x*(fdAoQ)FFwE1A~8* zSmLPP8C@B?0b`9)q|^Z{p_b1^=jiCtUC8?P?l z<7La4FzGfLHE&71v^11xLXD+K&e#NFuKeFztFGw^%+3r4Hd5rcB@vk9Zic7vKUTmx{M zn>1wV_;Gyl@h9AJ+XJZN`gHHq4xb2y7;fyW<7ID%lQqGqr;uJhgEgx^X62{fu9y3AU+aRiEzQ$r?Gm)QeJ%d4OV~t zC7U;G;p_`9XYp&V@y^1xm_PpwKKphD1N-*CublB=v$#B#JA$|DQ+JY@|s8#lwUYItPU-5uDvU~-$g!uU5C5)SR z16piCRR_3k{21oUeb&{+{A1#n1S3f85$?L>X8QH*&sEpmOjt~mKM}t_$o_r%2>MNq z9N5RNyUN+KuZkrfzE9PzZ`t|Nx9qFXtX}gapRHPfRa0A+Lr;U)HN5id!<;hoBzpGj z#qht5;Ju|Q328woo67R-+%)NW`t|F_xffi@w?FPgD@CaCAlFTpK=T@=QT!-K9fFu`Z0LWUwHC`H>s$#9e2Pws!5^hNI7Q=Kb0<>JJF?6XS#Ok z&t0>gWZ63lIq{^SeD&S;VA<4GRB-&j6FBSaOPq}?A$D!s%-}%-8TQvRS@YFqG_Yaq zYQ|l1HvRhdrT=lKvUc4Dst)XB(sdIVFrYu@UT_H;w(Y}K!lAuex#*$`=-syuBSxLW z*Xw@(e}I~*3T~M+nSuR};qC_>;Ydvg#A4UBpSgU@MfC2|o6E;dWaqvL=RL*a>r(^} zw*S15%P+Z<{{2tj`T1{PDIZ?se^hfOhO3ngv;4!?dHtoQNKH;ft3-DL;>EfPhxV8A z+UrZWY1$n;@$mf|{^fh-zws_Rckf}=z4tR_!VS!Q;sF|@n>_T`^F%^b+^pRbM<0Fyiy(6zdz_ocpU;cWKgXV$8W#k{Hf(>&f2Kq^eMKZ@V)+9_p;1N> zBhJ2rV|%pZ_Nh0p=))DX?%bEj*ImK058la>&%Vm7x8K3wV|ro`A;D05xoQnlrc9@P z<91wo{SBlVJ_?Eo$*z}+AqL|nO{8&YE>o|Y!0ZPfVc)?cQ4_946Tu>6*Rp!$$BZ3w z4bx`K=8`KerKC|SPCtDVg~3{`A2*I=tG{RL#A%e}C34lJm-6^CZ*crEy$J>a+%#nx z8FH9uH%#Qywd*4 zR%!wXDOogW+>ivrpmV=|^zYf8=@Twx!Jk@_@*Bir3 zptz)n^kjEBQx0I&N+WK01%rZiotbgVO}zKglT4g&4J*F>iT=l*#?9B9!;=rr#8JK}| z8a8Z5vfo6R0ZK}W$gZD?;ZLDuvqoejIZ&pcsDOgPTxXM%mP>KN7NqdUqi? zHQCXuDZmg61GH8oXEfxVd+y-Kj<31?+6l~C@D65b9{1lnjjvaI%+zUjFz~c6 z#pkbpj{K`P7AWfRLA}uKa#7998%+f>CST8;x8Fxa*kH$wN-RsGty<7w_V3xl;UhJOZ6e|)m{UxH(gxJ8mq930 z1A!puN*m4&XpIO!>mW< zVTCQ0EqaBsM_$A)zx>RsyKd&e$LCQmuLw~FHI_|HbuGJh@1e5FWlJy{Hz=%6X?_N~cl^TUpSDvkzX9K`|AueYe#@FKzQ<=M@CC_e zP(uCO94De$KtiLJoMCDnigl^QxUg^T`Rn*Vf*$isN{w;Y21w5ybRj6EoSlJx7qy5F2Y7KeR_2z zyM79%5B&=pzx|$HH*e+ZuQ$=TXLr&wv+35o8^8Xz4hdJXY4eY??bCyl%xwC1ZcF*b zFW9(#9pC*@&fvdZKzddN!;bGxb@^6){B;knzQ2wR-3O4DlS<=Oc_=Hy!2{uF8GnyL z@=y5>5;;n=)<+-ur;66Lh_*y@M6`~GEg}&S(RN70t`@N)qD92gBBHBg=TFNeue6nX z{nG)lMIl5-qkwMC=;Tx>jtlB`o3`(^VpNt=L*iSVSzbMRZ6+TViXGkl13|5s`4Mh;55# zEm}mvTEx~`w6??&E!wUXZAT>HR6?{^VmYlN+6s%me-19{&twrpxh_=MiUcc5##Cfua zHv)86L`TGS%kH$fC1N>0TGu*#XWP;75!PC2B`mhCcCHtvEY9zUXt$rjI#w6255x|O z*0D0!Vmo8g4vS@L326~q+s@b$%PFTF7F%nnv9*ZQMxQCRQwv*;Y6B}Q5$!x*yKSPi zEn)49W36jN>?)@%#fq!D7F%jXq(-#uwwv46B4M$jBVD5Jk}cw1T`Lh0iD-A6>5z!+ zbiCGK3Aw#2+8qqq644>i+IbH{;*3?XYDHTWV(Ch^ZN$BYQ=eKbV(VJ5?TAFQH@37> zUa>@^T5O3(t%zGA%NY+M&Tl&;T3gX}6A6jd&U2jqy`Hp1bd87(i>=+NSeA&kB;vNK zH;>q&Me7<7UE`Fg&b*@~6bi|@b?fBd!Gpj1vwZpT==uBi@0Z!LXN%}cIk4wz>CvKz zbnMVee%!TBe*FAx$w*6+M;9!S?dz9GQEq|U_Q>n9{_}UFSy@v#=h}OvR)GYoWzIZ>DEjqkYE-=mv z{ep3Fr23#dJ8POGr8kzBUVBv@dSH^|WTnfcmyeT0%RiU$h{*P@7E5+&iahxIyRvKj zGRdu%CNrO1A|YFg*yXb6v&E8~m?!gJUmyz>z95-NnKJk7_vJvvKDl(nagv_hTvmL! zMy6jqQgRDh%f~BM$Ty!ZmbBzznKS#P=lh@}xB>DM`hhe z?`_veetMQX|L#&bEF$aIE|ab$xzeyvQ@MD|SZUv}jbsd$Q4@-6RVYy?{<&vI~ zCeOU}o-BTOmefnHFHbI7CKY?uNm*f*Tr_cpgd+##&Pi8El1h-bR&S6>cTW3d>o&Rl zu9;%T&o`kRGXDG_GJeLxa!9;6!4i>QW%)<1$gs1nlS37?qHFib<9Cgho+q9uZ+y5+ zj_KV`j?~nM=-skz`F!c|mow$dPnJl#k}Uc7`yVAFmVEQoDj70puvnGf%PA)fl0{#y zml|!$zRh1r=lW^#*1~6{-GE{8{a?;aDOGzUoC5^1~T&}uuvSU6~3d6QA#iisk0${qC8nlhV2Sx(6Er{4CYz$0L zNzN`<3D~w1Y@!0743r9E>KZ;;{03zW8jzNnN^(jXDan~MZq}AnU#!Jaj_;EapPLE7 z@h-G%jnX!re;~?_G7JKM-}QZWvbQ-JI!hc)lcQ4zU}8GX@+2TC0XuBt_qee!T_U9D=ggU5$T>^SNf0n0=70(+n6n6&U@>C`b3lw3RzyU_ zRYBCnfEmO@5ET@aoYOE&I-$Gj{iCY;oN@Qwyy3@1kRl9uBxu^)Gs_wpiDNS z&NBJV+i6f-kD{X56c!g#qp&93d+kSAMxjK^^p8+D+Q-oW+A#5%I2(*1QCoA7Mw!^k z09^?lABF@l;!H7Tl5gQB7$ zii_%U!RRZf%xJR0i`=_{Fh87brvIrjbP@iHwcNi5fB7f8}TJgHnmNn2~>b96=i$N@QKs1O1c3_UR!t0GMoE0BXiz6cfk>mW3be_34YWf7$fin2rK+e?yO?-U5eFZ3 zBgta7MZFNl=8vxD6OobUc&~|D2Socra2(Hm14}%sp_yl`c|f0&QHuzV>m2XPX?@_St7z5?&dPGvnn~ z2~|phsD5Dy>lMBb+ib1zWY`j;%`6=edNn~nOuCSNM=PQcx)^h$#a8J;n|G(Rz_9`P z(gC3bj_cXM6W~Y@jSV+UwlbX*O}Y_hj%37{7ujn}{7|k52C##nZ*n|ytq8}m0M`xG zt96vPVQyef4z2~kt}E>`e82$mun$bmha{)pZTek!5-AF};_8W9di6ahVGb=q+wD(; z5^*L28Eq0sH3ApMf^X3HxNbaZzvntp8^Zaa?feN5k`(zufM!&OgHl*-7$Jm7Tp{{Z z^f~ZPq`Hbxt8NPh^zF>t`JXfO(Z^`wm5@;qDPksR%w}e4;%K4q9ARdna8Y)?2hxnP zSe|@Jcwj+E9Ie?~vWa*8I-BzC8(6Vv7Zb)EL;IFZY1gtL^Jc$DkCrugW9GBeYt)1; z?K<-1CktuTt|PbJFqX@%p2ROd|3c8E6Iw!`6^Y_T)G18z&g>UxRa8#5E{({Vj2|kM zL(kq_X;wF2%B>SP`p^TI_rcdRY2BW7ZQJrS4odq3+DAGL0)^w{#)o--5{V{Nv6;#D zKET?oRh&L{0E<5Rn08GYvHh1Xx$mhrx#rsIsMnxAy7F^gnlY0;Z5wdtf%`;80CZrc z7n(o?INGrX8Pib>8aAax>t-z7xSNjcI#a850eJOj(XavY-f91>I@aD+qM<}GR0rWw;7nnW%CG@kv-d}4K5(xY=Xyp3g$N%8r|3pu&} zN%ZK^i5H%JkPeL%->lj|T6zTG*m5kdp)&EpA`JbJuF)}fY<#c^_^qpwox9VgO(R}?>OPu}8_C?iyhnrP zUFp=U2^XAv5TAbf4hJ83Fl(2tBvDXAz1nfR2mQ7(v452R{l&m0ozo8dt+Rs#MnVmg zp-%aA*%@y2y+x7J7+>&{7UuVpyQCxN1&2;bCgX51L zgz%CCC|nUxT)#CJTyP%WEO>*9F1m>MAAU?qc_>$)M4UElyK&Q`8~E|-MO-=VI*J;% zDO%^CSCU@CfqcUpvq+GyV6H!hqQL_fw=ZT#4!E_vpY0s)}9+C z-b$DD&A4{_WsJONBy;D?p`yH;8PCt;!t>AL!AGB9(4mKN^xy#~>7faT3m=@A(Ps9m zXxO9!x7>0wPIf1kjr|k5Q-TK{ew^N&+R&~4AdWunNaoLbgP@=eH{W(E?VHr#(vg=i z_w5g8)1@PgY86JyYWV7MMSyk*@bH34=QfuDodyKP~=@5htI;(iIyx=bSS^ z)MmtKXHl|wC8wWy8t;Gh6*t{`FU2(*a@7^1*uCXPPCxZ@-dV7Wt8TcRT17>icJ3L} zty{>sXP(CWQ(xwyk)vo-SYVP2wQu+1-`)W9NBQ4bgi=cX?y@&QCEqV!#@4C=4j9;r zc=&n#I28ZJWV1j3-)F-3@pS03FQ=SyHi?jgROH{Ny1nREyC=TZxK#4pH{atY>(jMe zYozv(PDt7rUa!&qUOxTkV~U%0r%T6Hc*3{0G+W=VZ4%WUrE~jbbrR6rRr*)ghaW~3 zo9HtO0?`OEto!LZ#$9(Ok397p*&S=yvDc?dpYFs(-bO7$(lJ@>5n6}&Zh6nnmsheK zDt^^(Q9X2q4Xb}(_}OE5@S&;f*SiDAAnKFqu*JCcf^?c2t{+dAeg`pp#0XphW5tcs zDRN*>gP~EW)$ zxD(CiQm1(Ap@;cs>1v*S;t`5tPTrUcEt0ajwJfZ5K9(gPFzLMZL!{6V0q{IfmBYIB z>qZW*V*56h{;-~I{rgiG^Kc@-tIQ!FvOJqZMK!>it9cIK2|$e+{> zNhC3pYg8WI6nXC&OA}MAzV@>B=e^Cf*I&yUpMFfe8pXKLp&`Ge%66*+k#DW|dz;li zUca=~WV2a*{P9PcH*fxTzw_<4-*VuA2LiBb*Dhwwn#HKmV*rraWPBrB&=TJ!Hn^lw zIHYh%k|Dq)BP1~tj;cb-I0_f7z|kr8?A%P1@~{GWD6J_qJWG5 zML>a0Ap(a07wx(z4W7sv<^^F_W z1=7&Bm_Qzlt18gaMUlXviXf2qPMkOzNP~fhWVJMXhQd)9w1}C{q{bm-vYZ|h%Cn+ExO`&bS?LMs#I*UUFL=s;(WbFHO$bd4^oW73Z3yD_R ztlvVJcP|oTggKy_`R4;^v@XCG5+$sJDH#Y12W*v+xGs3%=LCR92G_R19@e9c$;`32 zbLY~uX;b?2>GKcg)F0*lZV3&3ixw@y4gZnv3jVD@p$@8eW%{G+Degs|fxV0^MEiy; zRSPreBdbJU{B5@4AvvexIUIk=$<(M@-^2;Y3}!IL&`MOpe>nzx4JvCE2rZE!K&w4W zd-@^j^&CRGwyjAz#vdpQ(G>_~_{aR++;i)Aj=K16+H`7VvKN()kg*6L`1TPlzqY7q zAV35GIG)uCwN6j#`ZAixfaOy|Is{g;QlKrLmo%v0&tz2t;NZ&uTVx|K)7gO7LNRAfdBzAM(u`m z89VM0TD5Fs`btZb5Rtlv)`6{rgRcSC*5eQD|^P2*|V<<4Ba!Na+#;!fXJ6 z4_@5F7m_!mBg`0B;N-Gv<4-*P=;Pee^I2js4@nTkn1yC-ZGk&7h6&N@vH?iD&~N2xaB2a_2p?7PuAuyesN5LN^TZ8gcUu5$tHy0mBfbyreUkOZ`y z52mgXLso3gIoA3d5V<&AnHz|arnEUN@LQBf!$H`XVdI9t4d;UP5JC_Wps_Kd;gvFp zX@Lf*DBHfCvFD$~dtdyBZ^0zeVdRBpQ0CS`$SgugJo40W>^w8iH$cFwk1=rE$ZqP| zB~QCW2*A@C(^)YP+FDgzkRA}=;UK~|XO{?&xhKg`B$fytgU<&+KE;5Xr(Z6S&xDIf%&od7{K=;}At>Mb6E~itEzMOp8NcL1z7*bK}ULq8TEUUj;#E_#8qfO@?Tz}hrRHZ5r znLXTd{q=Ne+k;#0xtndW@bM&!%vvQ+#D~Gm~uqgI!SjqV(A3^6%?djgDCzB>k6x8_z1E*^Vnp%wCTpBV<%9VDr5PVpK|o!$I`QVZ>IkFc`AH`@9$ySQ;*PZ;6Zfk z)|Xjx=8+YquS`CPMw4aRFH0CU88b7|J-bzUttIXh=6EBKQtCw@c;C^)I(uwmgy@qYOD-k-)o!5_Jzn-1x z)TI-bj=PGjC8hY8a;85ri2?ol(xGD)&OG}+e1`gPt z_U+nm(kZ92^yiIa(D<23o_zcv(Zdl9oKR-d%ui&q9{=$(5 z4xoFdjtn~FP(JwVOMD?gSMkxj*&KB6A#~}~juTHgo6V(Z1MmsiH;Jsqzu8h1&R~0p z`kUR-N^UxN6y&+Dg;r|~%BQeybME`|t9cd9i|(b(N{9~*#Xq&dyzZ|K{@RDcjnhCv~r``ro8&NjwP zN(0KJ0D*%@)MM6PKjEt-U-9*l&sn_qOO}4Mh)d5KVZe(;BVlx_s8%OUe%OW*=CBz0 z3=9`%jsTzV9#Lo7ZwiT)!g?w4V3|F)VqrJJFsdqHD2GfkM;MZm3yUyybR!~uvj)0^ zWbt7!;M;=Ke>0K7q`T!T?KV3vgl{VEexdgPX@FqFnrbh#VM!tA6k6wr#O2cJ{a=sx7|Q#X*uQPB}fF5?|P8( zy(y+X@i>kwARadcazVI|8+QE%?!KM<4?2*Ek6wiEGsHZBl!8mH9?$U8PNRMeMa_5> z6K=SkWI-VhPJNndZoGq8k6nil4r3=w;Dn*WX;P?p@tKEMxL`5&Pkw+e7A|1uh_hMv z@jRNu^Iebg!TU=%^Qf-eHfbUo zc2+WF%0tY5_dU)yX$UXQd7W=p{DcycY0p2)Pv0(O%H;d#(!DbUnG_|vc9YSD0Qr>D zPUoEQw@|mJ2HV&Fz$KSo#@VB;q(j>#OuFweYSwMYu*2K3;PcNo<*bW1?BM=1YTU?J z?L@TH0-9Z$Hc^$$N##tIBa?mZzV3f|jk?bK}H^NQoG(hRTvXlvSpvtV;2~O*gZ%G~mHU9^jpK z=5hMz=kmr&Q~2@Q#dyg&Jp23|tX%#z58gM0K3&_ij-6#F?eod}ztVs3 zQJgaL2wr;eWgdCx86Lg&QeJ-H1zvgk6DB|O5G5P8as71@D66WXFkTRW7h~=6DKFX1 z>+?Qf;=PZuPpbwrsO9nCgAcRp$IU$O(8GN3=^{=z;vnAq_(Mv|((K;3+hiGvN_Owq zN@?0h#y$G&H-O9Tno7e4ji?(d??4O9;$_RIQ@0WKOn!t^o#>N7L03m$Pu2oCHu5os&wZ!9E3#3~_ zQOyt(X|z@ZfsgCB6vsWP%1TH}GYbQoA{AQCasVk@(d?WJ|6=EaLZGY#+E`=_z|v8I zjrFwHu2Mo7IAD{WOxsMGt?fGM%|t;>;yRmWK{9fL<-2ziY7pnuju6HuVL}9?jXO{_ ziO+-{SP=Lt2(7KQt#o$u`-OkOg{c#f8#iy^P?MD+hK*$H8in?&9> zs>LQN5yf|;QdMZJDJd!WJNssMZ^Kb*0%2q>=A!!7h+Z5zvi61Ru+F8P+b_#%H>f_^ z^XG(!ga8cxYxwrH9Z^;}*?I#0S!q;%l>d9h{XLRFsu%ODKnoJJ8`7d_F*S9Dw?AFT zz(Gec=;$LT4g!`g{hn85JWcnT#*mT4wCmBIKCNrep`m2dm3OnVbT1hN(#cYlsbule z&D=ftE;@DV96crcQF+g8+p#Mjezln9UHUTQu)#QL3&Ja;ut8l~HLFdbPE%D@$%3WJ zS^fPoc5hwJ#&iSHS%Fe6#kK0tx@i%y@;xm3coBO_(meX)6Qs*Z*tK~JtJiFxdGEHS zso^PD2(<8U3gWcy-j_DD)4VXfGp&2}rr&-YIb{DnY+CgbCB2h;^Ya>RdtxTN8rP&> z=f-^S#w->s{f3lNi^2vi=&^4v_UqY@x88l9?In9@=^59JgQ4{(tlONXE$UNCE1r1r z4O+G9%*kh+M(y}sMyx%C_uhJoVTWCUa+9>{-k+Y`Iz(qmv&2|;jdl@1oLcqj(Y{kh zx;E0h_1+@-9CRQ}+!ES9KaVvlR?@D21Eh8kO46onTb`b?kWUwU$cUjs@I056t=seJ zD{s@|n`Im`iX^ z-(SS)4O`KrJK45*1EmU5@!GWM)RTUFdNBOhfy`O_J>~jjw1}}!mtOSk*By2Gv7C9$ zbCg#p6akJS5jwzE(6CJhy7%o(VZvkLt&gEod-(K|PdRzy7zQ3RkgdzVqgKppve8Tn z7k6ze6_rj6+V$y2?|qVFN`GeYl5e@_hP&9m`#$X7y(MqXe2n=EKQ}QwS{PDpWx@p{ z8Wl+5MRjP_yb(={ldS!65ubm$l&YeZtl#uA8#ivDG*gHlKZm>Sn}R~(5Exlt1%a$Z zt2RC8)4MP28Yh{5#*KXO#Scg&kss4&B0qjN+?uUS zq|kW@OBOT;BgtoIvaIV}I4B&WM@?YsXRb2R(gCmk8#&u!%H*!GyRckP`)BiHZL_>!IV30VfL5XnKJPzRxkU2`{pc1 zD-#o@kSJv=DCx2^=Uz01F8u~ltWr$WlGZJn{!JFLP#USssn=9RQKP7cz%DRJPf}U7 zmmn~~PenBnARwObD2lsOrcyR5+QjV$0R@QyQoc4sf|$+3aUttlx0DVjD=(q2FoEZq zXqjX(NmVKZLJ$a#tc>TK)kCmsO;p;5x`+KIUE_>MX^rDZ5^xK`3G=PCjb)n=J6l~zI$5JL$=-=b9&%C97uj3ETLahIZGoQldyq{tHJ z6u!=yXeezci=-zBgu>S*3pX1#vV14%%c*V&ab+g#~6% zP~Z`Z#i*!CfshEtL-=VPxn~k{zuL^?o3CQ^(goZ(XPI?11^6l;K;p$bJfT4cC*0N`Sqfm-a3Q>uidpKk?3PDFcIF8gJZNHf{;J32}X`Ks@5qb00 z#8~QFV!d@;hhW)!9x@IXm#L1h|9=e>{pafa_W{&8n;0^B^yq&WPap2DCiXR7;U;Hk zHJp|qObz43wY8xBt-kMnrpf+UAlB*#xpb6 zvZIvkJIiTUzad*zu4Kd7Eo|Jhm6F}t*{^SJTC{FS?FP*dN+8?>Et)rH?RU#rw|)!T z_Uxr|pU%8HZw?|=g6BC1N8rW`Nc?qC2$LA0OyWln_$Z|T2O$kHYjN$yG_O~SIZsb# z&6?G`_WDO`OL_F}(h)CILKSB7Q-N<53TfON0Z>#k$@(=b*|cFBYq#uX@Zf{^dF4{R zT)2=mzij2*_ZQN4{{a|TE~A@k`D3G=QXxT!P-qq42*Za*khOLMY+{AP@l3d~76DoY zY~HvQ*OT0E%gxlNQIoH}Sj3i18>!d05fdifN<})w+Km;KKTuG&PHh@Dtj&x+Kgqf^ z8+hf_ci5Xs)3$R5gwRM~qjIz%1y?G-{Tu!_Z8pTJa(-I2oV9D#Fk|-n6gBNc+ZHXU z6U(r3%UX7nR#CQh5Bv7$LgR*wsNJvyDJ2jXV(#z+E~N)bSyv2J-bxerS%lU|8OGQc zKwzvp+6J9FI5LKClXUCSfsba-W#ig){Jdr(-HHKy`_jE*b5^ff&f>2YvvqShWht}iCyNW%Te6)^t2eT4{Z1OR zY)^}JP55fTd&FIh5-!PvhxALBJNsqUY~6{nKuQRWqsrK@dIf9Ot>yg>zoM+NlHR>L z;l>hd+p?KGyY{kY*Dm_>>P_R8EvVVJDPiD}bX}yS7(#9NF{tX+}Z)aC&m3iBKiuvz<#DYaj08O@RE3dus0_(Q# z08)JW?KjMO@6+mY|G!Ye^-yaw7DB6y0nOGeEM1%6Wr&`&jStjXRr@pi2^oKExEF+g z!2U$CWDq47N&Ax*9B2D2+|-&zu-P*Dy|F5d6AHvojqH0=@9|4yzS zqGl>%88aW-xnrrZL|AW;Z(aNS%demP@6{!=Ea!hm2od!~eg_$vGTR@7->H7xf3M=z z?;{W<{_|J$`=k786d6vW-|OWop%JdfNh8iAyJs^epD>(zraVgDL4z24U_Zv3a}Fa% zj%M&t$8p-3XCPI8t5Q5NdS=;Id&+2o-vD4&%224 zzWRjYjy#SDx7J|_=5m6@-;#_6L*(ztFR7oK${Lx-Ni^cP+u z5GI*91P6AtCy;S`=^EpJ69?(x1co#j>5$I)6xM3YwO5U0<$}L5?D!!(`urU3dUP6H zS~W$=04*&~A~A$k#H0o%P8i?Pt#5x+x}1}bJCVEZf0RzWdNJ~%bGiBY>o{fD+0?Du zm{W$Ih!7r55D*VixB$RFKfm@=sH4+%7zw2DwM62WOhYGT!jS_&#O($T3eSMGpn|vO zzQVD`4&&4_FQRSdE*yS9UuL~9lOv8ekqgF*XW#(?=+H8WattYKag7>Wb@e#D`1k`x z3>(3W>96wOV^e6^wgnnNTxU!crZ(?Tiodg6*%P$NRPppol!f zlMzD>Va0b#S+e{mCf$A`e|g~k0`n zhNDvm4Zikltd)y$<0c*qjTDYGd3c<2-npoqYZ*4=IBvQ99!gRwM@k-6-3(5&7IReH2*$pHuUj}p z-J}IQI(6it)6Ze-_?y_1b$I55=UDdn#|%61ILWc*4<3ymv`UW~-W!B`QqDr+Z=hth(W(j0l*;q2R| z8y8=EA)`l*Va>YD=J1nE@%+ped42ACXf)|P+nI9z-K<)-9`O0(e=+Bb(5tVbDR zy^3FZui9-}{MT>i?bn^Pjc9{xkRKYWES<+xbWN z*D6BWBX2%c%x^gml(wn+Dua*-l(r(=+6ScB)9nH(b&5^DET-q-qxtK*@6)GU{TzoG zfeqA^WP^;M8V~|4T+4+e5JDPd5hpx*YZPe=g@qTn6pWaHLdP7G4v=ICi5{{lYvjLB z2tNaEA~MTZm0PP4;Na6$t4S|q2WUc$y1AJ2_>4DZLOBJIr z?w~McMg$p@4rcV zccwWTLZHyn#Yf>%iKYNQaPXWA8qc^Pg-=#HHiOhWUnvZ=1R~0L3*)|p(x9>^$209x zM%pSw&Vdw`=-FftO0ZNl0$=+$B4+9q#ssP~WhFmw!I(*mz4KxEwrYeU>{!Oo$7shT zK;RG{0%^yM0VX~gN7#HnmBmBh3lCoi;tG@$Xk~H*v%*2>07odYB8C(G9hWeJ&%`Tc zNvEnvr?NP%WYMC<+&uAaUVZ0H>L%lOK$zhyEn#aA#88fvxWh-Qy zr3n!?N-8rA`~jU7jeZoL_C;RSd~ z<4EkB^vRMip%N-1o zM!_e*LFh{M?ky!AOR#0r3dT)%oSUXhrDqev!KO4wEf8c)?45QHB7@0eHt^C|zic@C zf0-w6lwEHO02HcTA;t&9CINA+XhWl*_`pVn=q zR+HA$uUUx7nmOq?0tm>YtN3N@CK@$qPVM5N=t>beseikY4}e4X8K$4)b{q}5f@KT8 z;JLTH~97%|r)CXH%G7$}R?szrn6#Egqg1vri(lP=|f`=_vZ>n@v3W;mt# z4%na5PaQ@$S&TxPu#dN!xDXgVC&Q)ZTCf5V+yuEa6B9EAI&$*}?X&W`<;<8qlZtfO zDw)KnQCQ4Hqc5ao^Co!0Y>oyr8D2fJyeUGt5^XJCA(x1*psbizYGeuJ$Gc-y+4nSB3aWVLHz zu>jZAoPO%jWZeX4VSti-cM<`PhXBitZ(q6wth7@o3n#&Hs2M5-15(U09BHx(9W;h| zBF8p{c5p?2p?MHsrS-mC_zBNG`#fo-D9<`veCeh5CEK{|jwjetS`lsbu9x8C)6QVv zzCA1e6lfhL7Z}*@m@cuFB-iNm=4}UtJ1+(zuw%i_Fi-DoUf$%&QYSy#9vdDH?SU28?Nnzi3~&B7IOH>qZvDKG8Z4;j~gf5 z&!CgeXUM_5a7eM_^N%>;l#7`3;6t2shM{(m)y$K554WS##H5AV=3$N8{E84R$s+u> zHj~*TpBe&WggIskyM`MBfXS{l-*eIUpek7S=?Bbs;cYIsVifhGUNO>!XmgmAvKoGl z=7`8|!f#ZB7NA1HWrfP_W%jFc_7MSe2c-yo{n*<$&&ABvrk7(8GZ_N>eaT| zOt}&ENBP$*?yrMde``yi19panSy3WdWW!mTd%jD{eLAyZ`2xIH2*APdN zz)iPYYqnw;GZOMbkch_-!enylyoZWV4M79i1P&|m7qO7gGjFwv_F+-&UQu(Zy*}Gl z_2D_p?q9`B#;rZjqV|ZUD)mUz50Vhh~uIqB?9=Cq97vo&2JBe z`zvSQ(0M=Mdos&<HBf#ZX!q>Jvg+O0I{DuTt7~8$p+9 zgsbFj_bU3#6e+5ox zV){Ylnrr7#{=ffOtC&Qfvz5kL?Kmjy;RljH$7#{J1(#ob1qUBzu*$D!)FTj;1oJDISCU#S67byk4b}WDos=Zh9-hHFdYZb{AAf*7ELW?*78dvyK z`Yv%#BUB0@lQxDiKq~_0|df&EQA4vj;IDv zf4ibJM!GZL%~{X$=+x<)eaWAgI`whNQ)w=|;0yvFE}k(3o{!#u_%iqKV{+=-b8jQs&LN)onu>gS>$$|nxb*|{JDu^=aqLZi1 z4iuu0L{V*$HHt|l6Xwr?BndATT_52M0uTW?4lO|>Ae>)Q9T4a&Qn)z6F&V;yr%z?- z<4YWwq##+FWMMIhWFf`LB*lpW;!#3_2y;>GGsCv3Y8EidEM@yf*uId_h8$)Yiae+y zG1;mSj1nPpe-53A5KIuBm_0nFfMlYOf@A^7WRhe-f@C}%^?-=rQh0AuA4!gDERqM) zL>j%Ch~*69JPgD2!x*Npt=JXP*_kvvY>!u(*E6baHUab2s5;m2)A3S`VpxETQ-fsGt6_aY0^X?4tDj3u z+-2UkjVzxAoxu;P_~D12$YitjQi*hmh$rh(m@J}ZJWin_bL+(KScKM~vaI^%Gfp`C zU}_fE=CGk>Q|7xkPK?s+TbOdsy?pfXr)07jsRujO`Emkx|^o3yTbI%M{mty(1HD_RjVFt zJN9PE^f^>km9gUM_c&xgZyGje$UfZ$^4dpVvT5yl?!NtQK3lZRoOgm0H;*}=#tnP$ z!mQW%am^a;xqULrmi&N9Rq(=I(K6(coTkS*L+O;UC zS(kG!y_xm9%P`LWJcuPS?A`u72kzUJy0r@_D2U@G8Zmz2gFN@d{WNOch9_qHg`*Dc zPw#_|V0R|N=O4a-SJ04&lkQ>JXYbLzO>64atwZDHEx7xk=cq~x6Z@<|hz!fWnoqkX z^||);N7%7rBM0{CK)*r9Q(9iZ>hC`0)S*YytU-NRx9-Zlk3L65*8go4r|r8lHu^NF z$}QY@-!v|~{6@|>?Ia$Zcrgn;ewRJjtg*OjO*Rv-V%1OFGVvC=c5XvpfvO4u7A*Xf zDvFn`E8F9D2<0#B>#z zy_4Pngf3R40-%cRo7b~p$8MW{n|~@YRu2UTm0`=zKd@ojE-ROn z0|#N2p5sUxe<31Eghb;gWhA(w4LsU`O&)=UAY{9@@o*tLQaTSPYK;nfV_CD=bK5tp z4?2jfVrF3t z0i@mX1!4FKI?$0d5X=IH4keVFsEt}17iACxIajv`uL-NJ`TFCxnf&nMRDhu{&|yZd zAW#9C04X#QiOgfv4_&AslnVe~Wzg*9lTY90`4{IzM+~7=l&zaj)EfS%5LAT>9X7a8 z>(CdKV*czIJo(IYs%#%AZMfP3;h5liZN`8Z+9Apft?r>q2E+NM6*?$m{V!`NPi63x zX^qxSwV^2xMjkOl-dd3@-^s1lT*2EPeGzG$hC@MNEJ%?BG6?(KN2xSxe%Z*LlD*M) zqQe$>ha#=29Vq1mgndhFSN4xsmJMli2f472XXFS6Xn|5&TV^ewR>4)gwy#pRuv+hX8#0qPd zi^pHjYjdV?*r5j?vjMJW%^T((yc>VUYPz8o44*X2SBY* zfsYepDA3A;HwY8VA}AnRzL&8VjpUb2J9%>2Q(S!Ja2~n;VSd`QgG%`AjtqjF3twn< z?b^=z?P;2~?g~OsuYQus(w$TWHe>;ac^+q;cL4_;HW32=KMQ$NV5n=B7rG4YzNt&|09S;quZVH^3tr4x2rv z5a39(uHv5CZ{XF}-^PzBnFag3&~l=)6^uOV6yBcy0T~P0gbdvQI$9WnbP2VN&6734 z31ez9D3v9!3xH5QU`SDwBMktv-_vN)8hn8TmOerRmd+$}X&MkKgs~jWd;LYGJ^L&f zh$NW=85|K9@4FP%^{OJWWg#2_AxWc=jvIjz!_AdN5}>qsM}d~n=jbc}DvT5Yw29Hd zuKkK%gD8@N68DkI+7jV_ZC;lON@qQ?RKlo(_sQ zNU2TT15IEi7M`O(+BjCNjOMhpDhd&%76nMh0&$^8`IU^hcoZwX{SG07O(L-^*P#tp z5cnB9$Gm?bLPIj2FzbtKKmWO8K)1WO`{sT{q}s;ZQ8{8jaxZx z_}LtD{9%k6bviq@ZsmtxHZu5xlgO$xSB@LU!jC?~l`-p9wuc1apuHkmb?DB30X?Z- zuLhn{1VI*ua(-O7oGm-EjJbLe#|=4(BM$7wj!j!wwQ4mAft#p9w_ZINdB!jjekI$s z?IKP1K0+Yq;CMCY+^H*X&7Q-aO3fX2+)C$GO*r(ZA-pzwCj0N#i~a}gPfTT)`{FDX ze!hZw?b^`2XBR&H@LkTk_%bdWc?Dm8wus7#6q!sF*=!m|I0(l>Ix!UBEARuWE)u}@ z%^UgVn++`c{%6iP`vN9EG?{eSF1Bph`rB`8c>_@e8tEiZxM(erjtha2{!{hr9yqsJeF8EEF?Wy@%&spQa+gE@3aKVE)yG4+it2_R^`igyW`8BRf&2eAi|^`e-?IEkPU! zsT?(FG6Q>;;7LfNU$1VYY8qN3z}Krj=T7dYPw$@0JZ>CyReM~H7liq#%apd@Mq$guz-mHji`JQdO z_s$Yp0|ur2hj8@KlOWj0M<0L2)}0mjgCV;0>dTa4CX?#c*!11ktp4H)8d`&-<`iSMlH`#t`Uke8p&aVMNgda?_QFh6bD$fuvJroOeEqORSU zdhF5UWTeue6kv@Q%mBgmMxK81Zxj_|GIQFIxSe5^e)t8A&F%E<(~B`f2k_o|@36n2 zje;)SnLhJm5?v{D?Qsyf*(o^1q`9_&r5`P)x~7r70}f{F`0=E;Oxl{O`EdCsY};K! z*B)J%Jn?V>zGj|({#ia;`7u*xp2WcJomsj312$~lNm6z`Q>RR!Fe{m++P%EH^h3() zTFLL)ovsD>G}hH{!imSD6JYuK?~|C_m0(Ld&E94vPCbrfhXZ8MT@%t&x$RHsh z0gubY-km!M`NC}9x*dl{!;zfMsL_L2`quM&@W#8`d;3io&J@m>kQZwMx{juxzOLH3 zwhdV@bt}r6k(!Q6gRPr4(zmETRdr2hPL0&GBpbVIl}Kq04TotG2?eZ8o@wB)3#^nW zm_{S-z48jLzVbd7Tz4ObPZ)(}LQQo!-)!8;p`%ALeB`0@E=*?e^NVN;2DxOxLK3Bk z`)^->O3dbkCm-j-H(utgRh6K0oNhNEzn^xWiOZFQ=5kS1whdtdAyJ^2BqpWe@<6xF z{h2?19)(${1cD9*AJpBB7XEf-L4ZsU7ui`we$+9 zWpz5Jxa{#0&3-B9D1ouY%7(AjF=F&svUA;-5<&|`=vth^s*hgh>-T;9^utdy`Cg<~ z@hK!GCa~+r?-`gofU-UN!I4N-W(H}Ua(H9e`*@q1c;jzRvSv>`DIRxh`2J!4-KPEC z+(1$45tJgYq!$Mtb`%48mr}O#J1)BP3R=wsBJC}lfA$=lYO(N?jA8?L>M zJ@u`$Ha79*;@9zo!)Qt;ze{HZA9^JH`u4+Ys%6f(bJ$YWNT(Ey>#w<-uh;!VDAd5B zMSo*grI*suzGS7P+bL)j1rdU2a{pa-vuxQi`VQ<*qQ`|(wXx@?Z#n+zCp`)WKh0--Tcj-j8{6y|q za0g$1z7B6wHMigS06uY(ot4Hd*Wb*u&%aDa!3Xay;p?y0P+U^XPhWh%J@-6}4~?JJ zujkWMYX}7byuRoeD)+aNUtGYe&pyKZ1rHLEFuOOc<n&R*JHd`O9^evuwp`#AxBs2kzl-uYW?0bd zE)RYC4`A%*krbpS@a)qsaQ#j9keHIfx|JVr+1!h$ZVR&Y`whJG;wz+gDJ3U6pZ2;c z?!5VG8vQ|xU^`DeypXMxwS4l~mn?aEDMr|ewu<;z_r)hX`t)n$7I&qowt_k5%;BeP zJMf!=X$H}-_#-{;LZ!`R7dgo^ZyOz z`2ga4ErFEmuAF(=bgH*)VETkZIsW9?v>Q&#l~Z90o)A)q9SOqFtW>=T4#Ti0tAGem zNQDJHu#_^a`_Lss+152oJ!UeKrkz1~o0D_SKAQnOdocQt?tHxXX@(9S#+A1`Ot)Tr z7&)*H_szeOOXpm{iZ9mVkLdU!0d!4A#EP0FWLZ*}kKS=L!w#9ib1%J%&z(RR2VpIX z!GlIKd|+p;J%1*{hmGTvW#4k}*fI3$+XF+QsvU};VW4y!r_-vwmROm;0wT0El(TT* z!_@o2y!X!Q969AwZhPPfUVr9qoOSY9{O#3`NX_le#pg_;uBsMiMk(i=I)iklPIiii z`ih+_T=+06)@}l&gO*4^aUs&Wo3l@wgF7jYlHz=pzw}p*8h;eu?c4{NPDXwqXPhyU znl0s6F;^CK*p$ctY4hJjG~y5Yf69KBBC21SHDMNXEoI!e{$!W|UVZ2V z1`HX&rB_`n*Ca#OpHi~+=2pn_b8>Xuozvc(R3%JJ-c$`5hF;FAmLy; z{RbXQYhwjt4jawOpZ0Hp zPd<#pmCXDb=8>E1$7g7~wfId&_Bjp1)R{EpB&Lk(VeL<2crhEFi4YEj$V^Y6XK4wY zOMBur>sWa2-He)WELU86HHmr%Oq1&_oJ-fPJ?Yi653ZiYe6VUGdn;?vB4K*=IfyA! zkLQRX#hiHl0_vI#I;ARl_U%V)RVBkm4&%k!-k`;6VunMM^c%#CS(8aKgM9hcW;9(9 z2!~nv!6(eS@n(*iFqXDy;}|gVbUyv`OHP3E|<$V^3s6&kUR);j^z+amHCE z6EUFQfFYbR>r_Vc$z$$~iwKE@6BL{lgduD&e)4e~F?KL{i9yc&^XvTO>hpQ(uMaS2 z}2Chxzs1kDs8D4V{;9;c>N=;3fDGI&HEM)oMc6{#iSZ>O|RKTer7m1Gqr z;A^6^=RveJ*D+{tUzUHmin(WwM;Q@JrSth0pR;rOPR_jgFQmJ}j2tzbZ@>M4WBaG^ z$%;?8{)smj*RMCq^x+Tt(cDQ48ZwlzqX*Hje>X3^_BJ=&^%#>U^hG~yGLug@m$e(W zkgqu@F6qMb8B@vic<_~P<(7b#wcq{3!Ntk!+EdQJ0RuRD##A($HO8_C0l$~5;_l3x zbqeXu891(-$7i3dWa>$?&~+UV1DC@|w~`)|l~vGxz(77&zLF+i0C!pfy0SPPP1WIo z#4IjIsOTt;dR#M;8&am-=IJjRo9IpM09y^8}U2;fD zO=skxqv_wX5T$gKBbCCgJvd@?3(1<`!r~ycQiC>zP$^Ij!az!9CMDf_pedahr<}>5 zhx8;#g}DETXXyOsGpyUVm2s1%ao#1DQIelQpWXx6ytkQvIJx558O%9r7OwU^j5&N9 zMLB7trss0kJ$LZrqQ!W9E>hF;NJ`D&uyLcw%gUyppoqUd{U{GTyokLuEu4D#dCZx6 z8Hvsy#XScy_D~lYX~}p}oQxVbk}kPPq+($TJ6Nj}NHT>z`r|1)2uux=Fbabq!$&fC zdLu`S8;z#9Ir;Rn_+-s?1|Bw(PKhpbN#*{>o+baG=h(h$4~0ctnKb+evNLn&I%Nj) zudiimO@wY;yKu*Ycai(>Q&dzpGw6`f3_0{Dk`hyyf6t>7_Z-4UpRT0QuQ6zFKim$B zi2OIT7);xuJNwi5=im(*Jo3n63_WxL7o2+*iJDMUkWWfVl3hfoz>&g$!NVv>ONny= z9q4*0{rmMHC(!~WnT8;ygN*#{4C>blH#QnuCE#!>lomn~v+3KX54oAiI5a1-&p#I@ z1~0$zGKY*ljLR>(6psTo{kVw-A9{*@BS-Q6$9I$8Da#^LvLE6f!NC7+``w*Dv9~&+ zlr78-7*Jo=Oi@v(6@=1tx^*e!>(4(VY=qIAZcL>i%A~Ms4&jg=Unopig)vo-h-uOq zaFLy!i5q*TDs<#z?UamC4lcg*5?)*UIu~6yo3Z1ka@pDAts)CkvpDL^An&}oh{qPM zVB)yZR8`avG7SX5j2L!g0}Kh#*wl=cSjpzCS?Fej>#n_uf}AvTM?3{aN900DR31r4 zN=hOWj-YUmAfrfF+L>qI1O+13S338pDDdHv+%W+Mox z=~;9x%%!%v98(RmC;aH5Z#{nl(~bu@NK4PcEn)orHVg$2CLC_%@kbW2Wmgrw`jk>t z-%Mdq2-Ad!=|J!xN~bhGgXQgwgbV}IuAMb7@pyEcnn^emjX>HuyqXK;v|tFiow6{3 z?L>k;%FFiBW6~6Ki^T}1sadHsF>%wA>7)9d|4%K3Yvn-xBh=^`)e9 zVMm6`DnIa;p@ahv@CWgSBQ|E# zKs1M)L5ou6*zHyl1L0c^;=d0SrlEl|gK4K<%(T{hdKR)J-D^2m< zl9yxc@7`ww5B_xoC>sbOpyB4U^DpC1=Uc?>3SsfvFN4v>UAJ9FeM=Zj-QMPEj2btY z=igjvCyx~o)8g>cOp_5uPPH8!!I@pc3ya^h=wwX6R7n){ID`it9)^Waj?R{Xh{07i z+(J}NuIG^PJpRmh6jtG%8Rc$N>6|h9a!$M8Qc!mM@7HuY|E*@F?=^cQn4+V*J8{t! zH!|mP-BO3NBWl;&as%iZhS-Q74( zcoGQsd|;YHeC>Sx>2i*lemZl`na-L|ma+Ptw?NlONpKTru^cs*?jbun8)sn;&OQGe zJod}$)b$web2QMdL_@cAMq`zrK-jRRVwbMaBuqkb8V)7w*}k8m!THpdH&9*EN|%B> zD)yCGm=Gl>w-duIUWi6J1aK#~2>MzO!^-In=u^n*XI9hP;w357VEc|8)Phz3v+Jez%%OU;744R|L(d$AHCP zD~gEWK+`qyQ{C*^zLP$Edf~0AV0&3PMcsQ?4aI4tSCnRZ9abrWX+*#XvcGXZAx|oa ziD|eD6GzC8-(Sx+-)~~>jSn&6pj;YT77`AGtl}9v&8RSO=@$2yuE0>1iiZOS$~3Ja zRs)b|v4_HlR*71GDZ++Yu9qd`B!k%k;7TMNU?kAF8kebqLiX*=K@+=TbMZY1bTGN#{rfO zbki0j5~i}MmhO4kDBS3xlj4G4dkcnWq@?7KlakDLt3RgOiDS{4160>Fke8c|+TUi8 zhYPrr0(T;_FT0pC=iJDq4Y^F2brC6UCuTT+VS?`V*wwHG5Jn?_8H!*yBmB6lhT?(! zaUp1tc1*+1j=kk1=ah2o{2Qs=vzJdlcn@o{5x^htqPw$kXd%o{5Wh+w$>~B#gitVm zxDwEHoenDP|NG_5j8;IKb|H}Fh&fL2$xzW8(L4iDa&PM$*J6&9hQf$M2>E@yzvO*Z zeEnl=qo#la*K8!I6A1}^6kwW`MzwA+n8(`G@oL%(1eyj~v{=iME{t+u>Nbip{@@Pe zX_Ro^D(o?pbP!O*Fco6^BOQFK;`j5~3(vECpVw-;0Jtzy3Yj$J2un6l1czqdoo4Ak zTe|^`4l-|BB`SLUxG-+)PvyW+9e1GF1od_|caWb07D2hy*E(WxxJTcq-^3JX7T!|R ztm^#;I+|va-N$IX6r$VQ2yxuEQKEIx?cc>=0^=_c9c)Te$LDre30N|sL?4+2L{~96 z&p7&V72PZesE8F&{{_O<8uNe1#{Ku%e;^%fq8uK^j-SL!*WS$)b763wQf5t^!m_pZ zaP5Vc;WFCr1$8dG_#*UB8DVb=cinb7g&8`VH*e2cCb0Jv+BEc4!}FoPHMbZhMHGyLOV6;-PHn{2S=rZ!nL(cpLLCzk$97b?2NDj^)#DzGdE3mywm^ zq^91-^*7#XO_It)QvqwiQBmGEYobvCnlgCy$;a8bYbWi7ldQ~ix|SZq!B<|-W!K%! zRTrI4cBgC(A2*S+FT99ruDXg#F1(1GtZcgV?8TX9oJs@-3I{GAq}-rP+?vqu;93I`=HDyKFAqO1hEY_Hf?0 z=h3^QfRj%cO_!-592cQ(4F;r99+x=}w=b6qbCmlL^O6LX0qX-0)|1l~?h|-<~8T z!BYBgIUQ`?_&rx$a}DlrGfiy~P8&aoG?yYZNoUbZi#cxUbZYBf;EF3QLq&w3D3Y8y zd$(_9+T$Ou6pP(;93plrJ3y6j=Rn0s@kC1(WS;^=s$k$ zuf{*txCpRyrfAqcN{VGWZ*j+Hzj&th2hy=Ih&I&_iK%57#&627_=o*JXff^J-_J}i zLzv+Zdn)$P(r)0%$e?FY4&KIU_EpuPv;?yA3(3h!qGtD33_JWh9)0R%I_G(Cr=(C^ zSVWQz)iwLj-5xTsv(Umms;X*eYG}ccm`c~u5R}aZ!wp=|ap9H5EIk zuWupjOd&P96UBMCxK)7qx=L#Hw_=K$?EC`qvr=eos->!`nTTPMl9@$eVLpMDW?Fqd zvI+`u8V&3$Yow@i2?_Y9s;Z``Ie>veOH8IuNf8azyJ*wWC@d%-fe39)HPp8m

+o z6A4gVT~2+27f)g;d0o1a8#TpkD26?+K=A>wdToS#Q#qQGL zIawINM#}cJP}Hpl{`xAs5k+234t3>aBy`FmE!ji3-OIMJ2731@B|-O7SGSManr2K= zx%Rp{xc9Cb>D#x5t&?p}*~((WY-??ztgH+J7sZ7+ghGB=O*h5)xwvR26!21Bu^(T1 z1Wk96nw3pqisHDVj^LCVALE3h$D;e{Dc@I1n=gXqNu;=QXHq>1Bh*S|Wi8&8AdaLo zx|MWAf-RJlRS+_Catn*dNl&JxayR>1gD7VL-MSQ$;&Id7Tti)R8+lzyaj7s4<$y?t z*PnTWwPitWxa|g##bAGBErD>DyspKT7)$JN>}Ovx>(3WQv*}e!4w-$XJ9I;qFou53XG;HB9RbomxEBi zD)2C)^g^Op^dkyuv9``?|1B{IMNMo@No69+u;3?_n}&(gem?}=w8of#^*gb(mX(Qt z6V0wJjun82vLi}j>33_kF1y`ty3L$#m?lbhS@06E6?vl3Q8PLxLewF(+GfVNrB+PU zN=lfBX4q-x4o@iRj9a|0x|QZu5uyq}Vk=@R4s@LVt)?IxiLiS0=Zrt%2#6BL+wG4d zNJ2A}{p2(#cWjjjX`_12dWIf(DNC2HrhjRw{c>9*zhFtVSudR#3x6Ai!L}Wn3Hl@U zZ*&YaGP1HLDJrlcbLyALf~fF_ZVKofWWF(S=NR#^eWa~XB+8PL)0LvRc|YalO+zE9#1Ivew>iY3q}bSG!m*TrVC5loTZYXf%Ic><+{>>} zMC=qmR1G)!xq&IVb&N8ot*)Y`x(;mlHWP)@oj|{yrFJ!&Gj0O1j*qH-2q30m$wb-L zh$cfY4C^>eL$jCziAG1_Qy|tfXH{>TO0)aLdd^}?Vp(#7257py1e%2X?d;jLlVI2$ zTY#oCa#MmFanyJgJiCI4hYrIN{R}}x`M5MU7FkSmGL2hc?EceY|BsGQBQ`#xt&aW~ zKk?gje?+xX6n@HgZQ`xBm(eM=fHfPoQ`ICqaLW}m*6cwXiGXGox++S#my({GWTnz# z*RlwFtnm=9yrMu1e9e_S_2eR+f8#@*ePandy5!*|`kq*vnbvp;p^Jdw1WiMz4jUor;Z^J zqFUva6V^d1ZrDzsvOCGNm1vx%VL4-1vWP^VgB|-dZEjE9?09Em(Z;ysMbyNW*#wD; zsM+6*5z3pGG398(`dAs(wQwOe_E$G`8)s%y)2Qf(r{g`Bc-kUtiOl$DRNQA#IEfq> zm&86MdhWPS;-0P84v}U%tA_F<0+iFYD@ex-lE2|~n((A?Ba zR#vwC{@Ze^_PQ2*9#)Sy?H;h^&8V(X2YNfI^Anvfe%W%fV}+n&MT&Qh0X|IaPn3H;sD!IrqZX~_abu_zKvZ|DbRGnA9m ztP=im(>w~Z+;M}rBlNCfQ;A)%rWBEgj~_N{q@ke&u(W~=%}I}g`chI{7<(b2;vUh7 zEt)D31@n^?1EJ;9)1--O_Hr_d=UhlIogdx6s9 zrmLuP7VDtcUBN<#6=`H2>**S>&U$ir|105V?5%KC0H`SRE zBR%%D``NJm2bx;FRw~039J-s)qX#hW&-c==vbt@ng?}KPWVMy(H~SaYi1*G8aC(0BuLDzYKRf@geEZ*P(U(Tzco>D~ zmf4CB*<)P&$@ZbCcpvS5 zwCLSfl5D0W8FqkU+R@n^-4~5ab=cp%o*ek^C^erh9apg^Ff0`fP5rWm#2yp6Zbd<& zuY5Fqf8aAPK|%;lOm(1h`mek_|C>l)U0oe-zWF9|=FGA0@jypKz>WgOD2RPallHb28k^g! zB-B5=q*Vde0fe?f>>|Q<-+jlPy?Zc;O7lbqwMBgr1teQ{X|w46>{?2NY4^6!;_kW{Nm^5 z=LBeOZejr8KpwxpB*&6Tv z4+~mh5|IvGP*V&LBlgZ%{cbtV5vA-j_P;TD6@6uGUQ|P(#Kg*~2p7=BKqCS~P~sq> zoEVyJ^A!GP96)P>Z@~b}=p1C4v3DMObBcsegl!2z6*nIKckjr*+cZr(U=Gy8w4G}U zDHJiK!^y>xkTY$^R!k%I*i2K917`!^Ukl9qGwb=!KaUkd{bB!A_Mds`5ic)3c^^-_ z_%;Fl!D0&bgkY;FNJm1(G!2$7UBxd?n4v3Q3*0Bh7$o0fN69X~4JoEU2EdAtj z!f|N`rR->+JsC-)nH#UZfDcxEMVR>HkcQH9l;-%^ZZ!U`O#X+v{9jr8gwedeo>yLc zm2e=;>i6H^xtA8>k6tZG0R4|FD#Bn-PF4k*<>hQx{V5MFypQHcIHo;oo%X;TPD3+#PB7>&{Kh+A#gLOe*!URXxLAETgZMctu$6{ zWzKn*^7Rip2!LIhp?<%Rga`#&*;QFX2y6Uk z_NJf%pZWiSMNnc(>nUY9*(e|c1TmE&2t*`;!eT*)02VAN`Xqi!rISDG5BsJ4?wG(x z#6*`c)q6IvM;Yv{*hi;?1oE;H@wEqOZfyr3DJ_GfBoCU=PGh5&K+tkb+{r1VrKRF@ zx|w~+T(kr?1_ll@Kx0cAUY~)}>84YsEL&glhUIJm0Ae-MW|fy}II zoVp_DYo)oRiBLqL={ji{nIt86$nBiRpKrT~gcJ{L&HLH8y_WKdN;)MblADo8Bp9Tj z$%kPWq@<;jl$?xCfHtp>7HETX-LdiHSfMpSP8k_7I37Eh7U@q6b~V z_T4oxF z&LAxf``EpsiM{0&coN)XXQ$HI=*903B1(~!(+Rf@&5e!tf)QMvL^3imaB2!ogOCxy zj5&buuB4!d5cK(IYH25EKw4TVX^9&9>l+D%Kof(clvDzt5aDnDJu!vM%uL)EU<7Gs zY{DN1pc)&9m>QZ=w70YnHihK$bX@9}JJ+8FnE!6-SR@u?`rmKK3_IIk(C*#O)~%aq zZV6Ibv5ODhUV@(0mk~Xaxa{J&e6@Zn-Fo$)xuu@3)_%p@%dRCQGnNTJ` z&Td0kB8H!*9(sVAZukqYtXjjU;e&8!%8pj*L{-ccChbkNoHpwe*6#AMVdEw;6BI5L z0cA(O3ELQRhed#H7sZIu<4V{dN|p2P^0GSm#e_(JFTYsL-S^zjk6U+>o{`BJ=bXc= zKmCd96yb{%pYX_YAM^BM_o6ur9{KCzJhONyOW%E)qTCF-fa^aLk^RH|tL=Ap0(FN5 zroySik6(Yz!h76|8$FO?#&l=Fg8Qj$F)+;tW>Ow^-g*s*;YyC3egVZL2jOx;eM^|R zS6s@(aU;0r)?4X$$Pi|pHj9j5J!|i;&{1fVH>p6VvKqikF$bEO;MSE+I9lL8e{;av2J7WkEjIjK@ z57@J#o@vJ(N@-4jzuff%sVO-$*45Hw$PwId-6fg{LlPEfP3?ZMF z*5+1I}tTRq#?3khGLJZHPFmN~xHvRA;k38@w#hrUH`}nb( zeai8;O9qjgRl*%N&13VI%XsgjPpEEEWagCczymk2cgHp^zi2iuzrU1*`Wo)KVLm}u z7Tz|Kl=Mt)x%(De;TmqaZXQ)$C!Vy-_ctv; zc#JlldGrxJ{c;WN^iKHNd|Y|O94c$-dFTDFdHlhf+4;jdF23LjUie@Ixrq_Zo_Q=& zFZnZv4(P_6^Df1aT}oX;3q@UfaP!SKu=c&zcwpf|3I~p%d#{7J>WT|+$2mM=1Q3F} z@ycRedihP#atley>B66{y@VytJ;bt=Ye~(>Wq)HU=U;ve$BgUE-Pd2pH`{!4?wn6q zRV~N=={(M#HH-vhuwm_L?z^XjJ_naFW!fapo_Q9T={cn2WOB)sbNOlQ*Szt{Yb0hD zvcKNX$)}#e%$dg!CX7-plpVXUA~Fh;iINchwkGada2K2RR->onG3D4POc~mVGiIGl zX4gZAv{us+2$I*iD`v2T-Sr0dKDdx!UDH_l`U^bu>`SEQ7UBwcY4$}h1)hBPA@((U zx%tioI2?`+H%atZR5l(;rp3K?_F%T6*Mb%HKG1jlg~dm>E$oaSAs-)p@BtgQY{zKc zOTf_4H79w6T^KfU6k|pVqpoTWET`OVbUZz=cQu! zn|Sx#Lp2eGlf4VZ#~J zzc(&SYASZ|{zogQZfK=v?>-zoX)?(!gY7@A=d&-qqrSNrU3W6fY&vLw!hatm8(7VvXd!Mam%CzaEYF?Ipu!8FSZDi+UbMh$@&{PO9 zgctty9AA9#1(#lUKDE0yuzdMvw6sSk=u*Nl(~c)e6rQkwzonJCZ@-sbJqtN?#u2=> zcqu_gBIo^SGRxmv#?~Fx%sBIGG94k7zPp6IHD2_TG)|a$3?)VRaZ&ewgQF#aiHWHU zbR)!9A1~qd`=8*1b1&l7{=I3~x0S~peVmOutGVyi3(++b4JTS8#50Q)v0=+T-hAgB zI^|?o!_jt@EhpA?^8W)4;U8qt|Ai*Mx0xblpj!SiccxrC|8ChIibyD8$kOK?mUGTM zTPnS6Qrl1`Gfq51Zn}QHlx(tK_x?cgjgKj+5H`b<*w+O3+s?FD{%X6OTV#ssmvOM*Q;4@|R@Fv}sb_ z)GW=dO>*PB>t)u-r$}?iD<{vKDGTqtU%WoA`2G9kmRlFdrB~l7hUt?9x8EXXpEFxR zrYWWwdkEH0@KwnL$B&YQi{6m>kRjo4MBe?|eR9DC=SY>;EA{pJWcu+Z$}KltD|@yq zm$c3UWLsH{Z2$H{$?ZN$c2_q_#kMsvWcZQt&4$h5_czP)k1dc{XPheE?$|BIPM;>N zZM$X3TTe+*PLV8H@}>N+Ws8jHQzARdHp>k+Tq!qRbA@=@TBV_;Tn-sNN+^}X-7DXJzfO)EGfsAwl}mfu zetG4&zse!wj+dI6-E!7(L**~`KPFy(v#eV6flNE;Eb)5F8ft!&{s#|~SKnJMt==Z7+qOz39(AOAUsWs3&CSx#&>+FsQ#7of z*mE`PKSd(;Puxc$A`%f({K0_yxbX*RYHF0Grlw!~tX{o3*4_2>_44SWkBVuAMT|E2 z+x>r*?Bookdo38dHT_t z+$GQ_|$j zt8N!>uubl|{ycHHJ(8K8EJ-e1N)9?yzS^`$0wQ9>=2JsN0^+UTA=4)glY_eENI_bn zXpT;D%Y!e={kL8#9#6X5a^ItJhm;zP<9;y*EgPu1j{8-qLf# zM5%1_%4;t?B&9`Z(m6j{k`t2T^s5#~O~XE!dBiZ$64Iqp_mMJv)|pbXcb$wGIZ6hP zKVJNy8oB7yW2HDJSH9e|Rj$4C9LY>ck-}aFOKy*0^4ZrL>=7azYr?;1d-v>>JMUT` zhS@5iP>qZkIZE!m_hIpeqqBaq?BBOp4jC~)zW?EK`Eu3kGULS4<%%nBlF7%;l3f*b z5->%=hAD;_iH+fZQ}h0>ZOM`)vTohF|8Oh*u;1ED(;8`Cef5?62QYy)$CpxwBLUr^ zqZ<)+Z{JDJzJqWjCy}0!#^^%^v3=tPBx0bPDL6dIBqz8SG5jC`ZB4ZL{WfP@grJ0| zYG|i>&pvn(TqL+%@%31i**m~LoqHZ{yzwH}Ty-@Yf834{5dnLs-McG!@Uf?vbleGCe92t;cFspd0%*SiwN!v8 zh3AXIvQj|?SOqDrL|jfCj|S`4ZlJWZFZl(9BqzD(*QX~twrvN8PDFGx zcPa@9E=!5RjG&azQ6U21h=zd!-QmEYY3RC@9@SiK5pz zz~OM<)S#+t7d?6p;Qz39-tkow>;Hex?4FX|APFf1LMWjZ6%kMnu^}q<-o4jeQLi2B z_lj5%yLhGB5G;raC@O-|q)6`xB?QuwlXG_G_s8s>a}v;NLGSne%=3DoC+FP5D+KuAhb1)2>p()Y=ETML z@Oh>70D63wJ|D>`vG`+R35Zx?;$q2emO}N;ZS35>g^~)Ju7?gJE;fdw1Rs7=(~HF= zC6StviWedb3sJF|u2D^+@HKQ7>r7I|2q+Y`_;t~5f*{ppMZEdOTQtkb=j+8wm^*t0 zu^wHjVRF}-xc~ql07*naR2WFZ!1VY~p%BUzoOQv)tX{jC%l>u+re%|s(UN)JEadY~ zr_-^Zm9DSbe-cnZ3|rBowJ%+7Y)-$+&58j{hF00pXAsDD3xmgbHee@w8z4s`Snkfdj~Wbu-3 zczfc@2vMscu569;DQz1QNzj%Q?<^uMIhhe7{=u9tKjP5CyNBJ{2QA>v8F&JVs_F_> zZ{0(F+d}+?i%_9ROK(oI_!#!?+=-=ZzW(|vULQA(tFF14<}I4x5nu@0VQh*-i8e`- z{FxGV2dh5`B1Q+62!u2VRPMtgKzKYfOHXIXj$(~>XW48iDke2O17Vt2^))(wOnBJ0 zw;E}B@ffCF^reYV5}%={tkk%GLbw@Zj+@Bw4N0Nsf7}Ul=+TL<=6%n-_dm*O&)$yD zYa;ES-YkN(OnCVv^4j(0&Koah@$8Se`-M+Y9s}tysjscnxqYUW(3xRg>0~gYVPis;jmH;@DHY|r%OIf{6=k)Ql+}=wlt?Wa z+Bm4dYuR{YB#>G-kPse^K`>Ab=z#B*c{wcpaTaxTwZz35>?z$xYHF&pNoa6Z7Z4cd zt}yMB0KeY@RtRC+n)Sd11C#;!JYK9|tsa!NNn%neyLT?p5W=?2`mII8 zCN;z7kHNymMx*R2<)KH{wq(Qwm^kiDYJy(69o`MsW3}JPsv^XG*cQ#wnz3@%4xKt- z!{+TfNNL^zY4{LU0D(=&@Sq3+inR0$f^`+tRFxy*J(TaOB`z_Q^yFB2b}V4Zgb&!V zubN9Pzl>Y2yO~+Q;2~$@F=I(eNM_(M$MW!lcQ^{BBqk=7jo-}1BL$|DaT}hFLTGp# zVH1~_OrWxy+I^LX=5c_RgoH$@D@v)W3lQh?Qna%aX-HyYb+nf)!N$~3E5ZOg#QOc% zff8q)=*}^OKu873A}&6TU~M^-rB%pu4`utxsH_VR9~*;D*aU1VLT=!WZzNcf^yV2< ztk?*lAjbpTA}Fz zZ5JKDcA$ME!tkNY82v1}9>Z4H#GnjMl!EF)|2pfGgnG+Di5QfKrES}Ma?=x7yM7h> zD!WrzQ^S$n4<$CvL*GNXQ&&BmlJZ(EzUBssO9I?^%MD}~bm#5|N76G@Lt+`W#4t^S zl-SbLDN@Qt1r=T)@CIwyyQ6}D9m^2|jv+BAo^}Pf%v!LJy?giQN(nzmN&B`fNi-~K zD(i4lmh}26oP(C6X#IMwzv^bZ>20{@zB`DQkXqP@8w$H(*g^h&%_Z!qc%CaSJe#hE z4B*9AMqmrC!ziuesAaH<2X4NNIm@@w=jg#yR8>*$t;MdlQCQR~iES%{sz;bYE4-GI zH7vZ?c(J92JMX!d$45TM-M8LKUfbS`eC%!pAKv{xh5`I436~@B`(sHfx0>>YXih5B~lZpq;rqMIdxDUo_g$lg!vH15AKU8j4&xd7`Rsa7i=?4@|TrA z9U{g8kRIB!Z^xG(OyQlkX7k>Rx%3`%6bt8k%;Xne$ZNO>vjSjgvZP3EHyzvR;|zau6&g~eaa<;SHf*t&Z!m=a|`k3+ig z(OXk_``x+Boxhx;jvdIDQ6ri9<~Tl^{RPuL`ARE5KfBWC6w2tUlz@6$kk-5n1A2F5 z_yt3m_V(LcHT(%uTJ`3Lo?S7iMPX|e5@|V`puSlu3j;-q>~!XRI-QR{n#Tuo7IN&+ z!R*##k~LCM~r`OHsy5+ zTN#8bg~Cs4Y%Eqq2}{0Rz?$_%l+-AK0zyJ7g33%{$gzF-^!=9@{p6F(`C=LWp8OFQ zFD8Pv-FO zlM^}pv@=NbNcs=x$C#Ji0#7=J_3TOC4(Tjj@HxGX?1te_=k${X@%|f+^WqDy@cG;& zy#MhR1h6oK2}1L#gdm(9sdWpj#&qb|i=M4Bxb^&D%y@qWuS}guW=<;-Jr!L0w@aBc zc{+c; z#~g0Ea42uRGnF&`b{~0N`_ZXY9yw`}AC@koXkR4`3X{`|0%0c6x8DHvtoVX|Jv5SO zGr!=|c}qZe5X!a9Yb94Iv{g|GLWY+Xx$U`l$dTNC&3R0n@)jS={DwLeizy^eJ^Bzg z-+l-CLLuisC#b0^=b|%CV#cglgzO+Q-}yH!+xKSOjv8z%?z-t}9(d?Jsw|xyEtSR= z{ngeMVUU>GjF!#4lx$wg@}HlFOv=13KcWP1x6sX|CJHIGC%AU8U5Hx$^(OV5qv`&C zXY;q~hO?%)nsyz!GhynRygv3(e)x74Q$Lu4@Fn6E^=w(Ol-k-__SMz#7zYp{FW3bq%OQW-R;6ADXM#3Z#~%&RXm z?!{3o`sN!x`tS>CEl1J%4Jknf7VXWlgdd+7&(&ui!_4WE*tT~s3JBHL^77ahP_ap5 z=eI}Lio|9uxaf+@xc|=U89DrFR&Cr(Eku$*!eEXEtBy_5B>!2A`|rPh1pFTBU$jF; zM7|OY4_*y2%!H(U`;K_Lu`FM?f|S%m1|Hdm?mZ4+(f5m}sjg-C9d~eOw*qSSZRdqI z-lyB4eJI+to^m3fhvL-GUxHy5jT2v2fvHs;eqF?9gt+_&pjr z!?hj&ix(|s?w1SLU0TK!mtRizE`_u!XiHsPh$TxFliebVv(G*ckbL+3ckHXI=GYTX zC?M6d&??WyLJt^IoS*ydLkVqOg5|w$g>$uB{RwOA)XI zeftj}!RMv2DnR>AU1-rPm71D*GBR4wzHMuI_UJ}Zd>o6H{6L4!JsB}_1kDot1Z!(a zPEDa(x9*q{DywWdckV`Vd<;Qb(z8cTax&71Pe|dr`3s1TkD>Qrhj7fGV_3arBbzpE zwj;Ayd?Wlq$J!?ZF-eIuOV4D{q9q^%-Me>DT{I)@~?b^_sObZ=Oo` z?w!fb&Y(}9zO4LlBdgb}CO5kU{rmSLHz$vkD^_57O^zNkkiLEUv3AXmlyCoek_ zQz%lKH=|p(UMya`j6hu-xBcS|x_9kBa(p7~3p!9yS&VP#M%T`TSb=&{nl+cDQ+L|tu>pL`u9#K|w1@D{9Hl?@05Mc--TR zKw#T~*!V;aKjaWLZr;lBm8;0i%%DTNHdF^}diCr@j7L%%u<72d2T3sob+vV5WoOa3 zOIMCM>PVV3OJ%|0rR>;U%5f(SrAN2U*nt|Fw`f6OVWIO*K`EQ+swz5l?MX(nG(v$o z@FsB7QGJQ?3TmsX$Z6Gv{DO9Pg-&3xESu8OQj(IAqgJMf?B2bbyu3UBYHMp*xpF0k z9@-nj6GMLMR?PqYd!8Tr0^?pEhc6+M)6O`P+(dZg-%~kkz_GMznZl$g(lSpZv&3PAJLaQ_%FTOI7 zqfb1Y-aWgpdCL~YzcG&I$Gk#vN&;CqIgEevZHAmajJ}8WCRAO)xN)!X)U(fn@Nx5< z_i+5cUVQV}CoEX8g)`1NmE<@dV_zE2fD=!kTepsQ6b|E%c86B%+RAOW-%Ihn8fJYq zljoj&h2q`236>S}?3mZdZPkWXpLv4YZ@-J_AI%{%s}8-bTWBepmuU$=ctM*)Z(fRmPIbY3Nzzbtv=i`~5bLk})A#BAr^XBl> z=;v6sVGCKUS~2X*VcdJmE!=(caHdcHfQ+nGTz=_=bZ+0;!Lp3(1;0ni%gR`>VkLe1 z_Qxlk{{VA>Y6#%~I4 zz2jbvI%)vvX{kt;r@6tuKVR0aT}whj0$EvE|CQ%A$)6`e2)1wEevr6>8x*0nKjkuX zxR*Hpv;{ypr_5-#ZG?T*yD@BC;5^-^u)8u0qAbF#Qo@Ne(E&18(&0Z)wvHck zq@EBS$8n;Zw(2%UzKQD0NI(9hIB=;-->-y<^sUPRAzXJc4Hmt~^AGT32Uk$JZeJ03 z8_}ru(f7Fk6PncAqPTbiQ>M;h)~DYyZTfgjsW4o!_n&BIq`U+AZuLLqUh61Gj>}Xj zg>8o@+WI4N=6u1lSxb5Gg=a`li9-=`z>9U6ma@YqZRyZxMS8?lW^`)-hgK_6rKp5X z2aNl`ET8+gL_}Pf+T<2B?nSs{r5wf$haWlID@tkh6X~j4ve7ddK5hRo7S)fq^f^(u zjr$F`#`D=JOQ5aM4l7Axo{ykqVMvJ-4GN2DpEFNI1m@S}v~Jv@hHcsZ^MQUnzzPz+ zLMcVCzMeH}*N~grk^_m$7y?jQTFR6uQ@G};Yn%dt?ApDZlF~9lL4gqyM@~*IaiWGF zH*6z0Gne!@#rjRfBqui`w?#ULDt7PQM^Q-~?F!oyV}MXWgl%F8fi1M_TG+d}{*uf1 z@cUApfBtbYo2Sw&Ba`&>=6IFDs;y-Eu3{=H>%bRBW^OL2euI+Yjg;)IMByPOE|Kh< z7MQ`k{J3r#&02OKGdYopvfXSiE=DO2nOV(=i}kZ%?KZMowZ35jA6Mtoka}tldCe&_Wts0tk{* zQ^`zFY%VS*uVo%pd$+K!EJzR!$!Te{%+5mEL3R~wr=+ZkdecKe>(-coGPZ9oA`k+@ z^b(htLT*kL)R(bkb1_u`8zVNBf;O!Y^)(c2T~Bp|0vf50-AVdGltbOqs%Mx8JV0d6i9|wv3`}Td1y+2-8P;i%e2elQ5~Hy0V&` zrM2YcW@8u-3RJOn-8Qnavq?!#*74Z;=ePgqGGoRJva+(87(@O)7j^KtgQJ&e%TXR8 z%949UcyW%}B*cDYME_-C_!H^WA&+>k%jZfIyh2o?&4KOT#kkT8j1Z69S`&&bhnnD0}m>I%WYQN1*E0-b+xUaDIa?VU1y6;iS zt7`RqLXwo$oTr}}MVG?1Na=0V_QsR_7fgN?#iJU=4U4GUx-JI}fNA(-z3{y9%FB!$ z`yxsSOewH!Nz1%8y#4MZTz+P;Ul|7~Su$zj6h8lQ5qFOGr^8kte&VJBz4`y#_OJrz z{9g*#x2Kq!hu?)Sp&9=i^$2MxaoC{{ciehCbHDsn$GtiC3?6y{_uqRjF{ZD6qO^6_yw=C!43$LWQ($ZV4VPY$I^vTf-KC)jF zBXr|3qyIYa=sM8#|MB-IrA;UhvW|~tyvK+Uqj5XdMiP^l%G>X}O-5SMPt-`!xL)c2 z*ZtHt|LNDC?uAG@e)HxkO)@fa$!MO9B|I8nq;+XO;)yz?IcvlnC5gyO4sqKF21L2BfJR|wCki1 zehj^dNw1GK`5nRZHdv$M^4p*+8(|pOj@9xH^RPN>NjcWFp5j9d>oYw!20@x&fO*uH0K+wjT>N>uD_Z__PehxkU1Vn6X z^Des`y)m&T#rKZ zh8^8cKUJ7*+Y!nj=RMg-N16X=l6JSZ^&@O_FWcC7!tYBquG6n=Ya>fwbP4($DulAJ z5rl-^4D~zK@k%=P$q2viu$7O77m0?xruo>;fj@7jPFJNTMx)I>UEAP3)&$PSm~>QX!-WIq{?h8c;YgAK+)E zwVQb!^}F4`68Oi7QYy?HoSU0_z-t;?0w+(N%(YivtABLX2<4O|T+e}2`^}K(6;->g z_2*!18J~POoo&0zuraiyS=e;z-kGYp5W7lhIO(KgNQsZp%C?}I1vvZ$~ zj=ys)=~B4bP(#bDR?s3d4&9v^UBHme!m6Bn35R7T+@FnNJ4M6;1S--8G#=ImN5R^% zWebxhPv-X9Z+9N=D*igzOYK*`$gy14%~^qdB`5G7CAMuNgkZ*u8BN^5e*tM=2@ES| zzi}XjJ&rak{b(j1-2VV7#w0NznGOR7p=89Bcrzmw0C%fYV1r>a%nNiCK>?ckR{)li_hxvoQ5Z;_0Vr`67pJ_aW2HuVS6Ir; zzBD51j8ncBg)I!%5qEIKvQZ7{7k>0F(*l*y0MX&Dvz>a|VOL$W^YW*~NhopOlDj5~ zu&#QL&$q6-&&g2~F5iM<-xLCgm*{i0{{Mk(Q2#eXtFX!$yGpoV%=(|pz3``73Zh=1 z4s$TVO1ToY9@j!ORA~RlMLEzsmTh5}&RXIeG8~mEJii*KWA5@GBAdIrw0dKc8G7bL zG|Wy`sIcW&hChj@H6;8&IqQu+b%u|*Lg^!n?LHqgU2%BHa%nfEKGcek6W*dZdu8)Nsg>aG7En zDS*HIr2M-j+=hc>6KazG9Wj6ZDMU})`sx}MzyB@+dv&Fxtdu41zfXswjz*xc%?Oo{ zX}BARo&*Z@6MUl)I-`g?GTM^hEQ;ZUHhPjr4P*t|w{B+Z?h-op>P3ucgq1+oE+mx8 z6KuQuLRe1OQlQDc!`DQ|mV|&R=FMBc*1eMRhYi*fUAjOJ+9vt$7hj-z-y_NI)R9=x zIFjl&irZXMqY^4*6J4@uWZU}ra-tVT8P<*?>eJ6f4Mg87KnawL2Eq8x>f>(`5j7@6 z$oaCNg{v_Xh-(KsP@VR-7W`Q&vC`v?C_Z6=Xl2l`1pdYi?7*_W)#sPhQQxGM(g@9& zPy)j_e7V`eKW(XWwaNbt5km0x+izjI5K4|>VM~FH?W`S|+D<6pWUAZR+NN~Ou8u8s z4r)pwZGk1~bx$a%VP()fxVmRF+Mydm8sU>wL{Jc2J91P^vd{{-UXPvJU15W;9IH48 zTOT8AVWFgRs8%LYMIw83GcCPtV`?Q(=p(V^tg%vQ4O6e93aPBHWiWhHR}v*mXKq?f zxemsp(gz$NEF@q#Y#BmnvN+r62i?L@M3ED^bmg>9Dm^=taM+lYBusTDwC&tI?AyYb zVM;_DZhyzvaFn^JQ>QjEpg18gO5-V7(srJ!BJUh@o!#&RC3JgTtzFotKY5@QX~+D(asevRVWJWhu%REMUvJHJp0i-BeXp@WSIybL!G1_zO;h#{(d#7?rB?TW+y4D*|2USZ%qE2yKcV@zb|6diI^p{>j0q@ zA=kvNFLAbfAy~6&1)qMskak_WhLynRG8`>R|Lq(>r5mfEG{%`Bg@fzo;Hf$0ed?+h z`}|mjT{#><9V-?u;;AvO5wI;Tx%ztg_U=WDub!9R7|(-`KYDPc_5og%h-ht5%G)p5 z=^NEZMDG4&)rk79^T>wddtoX#bZpT1r=S4V%dzY@6r?a@Y=pKn(b z2Xpk54L(LcGupc6D&37TgaNrvCMi;s~g^z=5j@Qyn^1WaoUPq7VTPQH43c?5+{TaQ4pdIB~i_G#C@^ z^-&am&f!ETGcsh{*C7axnfdeQ|B7B{lK&sX{Iyz1W6yyA>_C7Qhu=oG!w=)uQKLyt zN}yMVc07IUHQfHyY^3RNZV-<0BmkSV7{%-JzUG9BFC#flGU@ekyf=L|uT7amyr-Ha z-_2+Hu4-({W=HWB0+xXbKrwN+*8E3YABOX3of@k^+zD5E~4@OV6=q@?1H z@z8Hzf4cSQi_h<)zOtNM`%1BeiQ(~+l#)uU&p@hrYO8B0tE?nsgYx*vNJ++L3d&1M zsR;y;hCy;tGh+NELRcUyzW#hZfjY&Jy?aqtR?Izj-N6yZo=HlQ$=&ykVCuV5IAUNQ zo*DlDo3;e#n&;D95#@$&5R>;?Wj`hUmo90)ZyWxpyZ3k8{}E4de={0f(Rd4u{_B9s z-a)R>FS+8U>)|L_2e|&ADb&CFz5|cdUtao8y`ld*;$o&26ttnS)*s2?6yZfs+u)RT z1u9U|RqGnLThURo`h6-6P9|ss^D?XzsA$a~8V?}si2T_x6;Xs$7*t%^3atVQbf}L0 zU6<@A8R1yR1Me04|Ka=@b!G~GR1Gf-8~LNpS7C+MsTYQ}Mk?oq=x%BF#1du2e*gd= z07*naR0ay^uYCiCVIrkLet!ObE?sSzlr+rZS7D7S9G|RQM27>_(Ye!hJuCX>aEXmi z7LD$6$6lCWM>vYI6?LGI4GlX2Sg~Touk48?`Ck{)RyrV5XUG0$g~VO5T-TbREEY_e zNL~3}4j*(3pVZV6lM=^KJq}^a=W|#x<3oB4J0mh!qbyCW3tLfEwvW1+TIy683+H{x z(&cMew0aZ$yCm_$lBHzj_oaMqF;6{qFMDcztlm_`o%amqxPjey_320X^vi{$wC>E{ z6HaFLnw3m{Ya*>Xb!OYv9UL)mFt-f9iRE)XW8CzQc=+k(nefD;%$@%YNx7}qvtu8p zpMNbZ-EPfF+fD=sC)C}-~1%b4}aLM|FwNM240zW8Vc-LF2w>4r!w z$?sMGo1{sawx3Tn5p zG$Tq@_#Ns}LPW3*iTdT&*0iCT>nh&nepe~ntnNtctZ;s8sN6PG-rW;~b}19NDM|r9 zP`yNWhZZ0svD3IA1I~j52e2PB$zMvOd*aiyLcdHQQRr+U0|*pt=exHiQg}pfns@I) zTuL(WiD_gVemL#>9Ky19-X&P7QPdkIp;`FT67YCTc9qnzV@nazZ*cCF7xBsLd03WW z>9WPN?T|xyRyrdedyFy9J;$&Uj^?wupHgcZ?A%q!si$AS=%=4%=!r*DvagIThxF(9 zv16F<+(^EhIgJfPJFzX{1W!X*StTc(aynz5dzR}j9m?BpO{LzpnfdlqimL>pUmeFY z&yFU+l+^6o!^#!QDB4@a{f|7#KSw=8VcYERq^S>9vv|#RTD9wep)A&{T2E4HD&CkF ze10!2nm1?7vL7)#iF7E)W##v?8`^xtAJ5RzBu&yJzel1sc|cjHni4+w_+wUW+6}56 zjSB!enynUO9Tv93uVEpmz$Qcp2!IpiCL#;s?-bjy!zpE>>{^z6_Z?$inMh@Qy~9BB z>-dr(vNlP_S|uIb#Ih}1@3>N6TNbum#kUI<^3j~dzu`&yOT;-|PuZ4LeDc9`iuRO6 z%HGfE;VR??V6kEOd|rR;Mb;JXBIKqBV}n)B#?`BsG;tc`fshla7_poEx=KdOAxddZ zZp*e@2;7K~(h)lp3Ol`(0t*XUC=d#vtf+D|G)}}4>xL!S(V8O4*5Lt~y3n~*Y06b) zS&m*ToeXXwu5qd3P$QVBjVjtCe>sui$?hgI*ax1*jZa~Qln{jFpUt6i%NCBi{Bo?M z1lo6OM}C_EtfWMSTy-Ve7B6DMg82w#han5Fb zbxXfz_2N|&@7_g+b~((PHJ9_xzmk(r9m=~CUdFDkq8_kC45mMk7@rTH83HM>r4OIq zL-U*@65~v&YHKm1p)-ILAUybD67c(dWM?H)S6f3>O^9uqw$gXdiTD!Z@%h1TD5Nsz zJK$K_w#(#t(sgb5Utl@kIGieRvg>e?#&aj_t!UJR5QGHzjq>hX9?Y+(}P_fT71 z{)fHDCTWr;`6I=RZ40q=%~H-e`vSgRw378}R?wk+N1lImDk@mTTazYH(58^2lr(O= z`F2Wn?Btp&uOg*c8u^7in7`=9hAz#6SUYX`3Gn7?uko)Z#%Kz;gHduA)(cPp7JfO4 zN$-A0os&w`-X$^Dd ze8Ix+m$0v@7Np@Ma%n~M&rU>XlK(rRvxB3o%D>Dq<-{t~*7MmbZ_v9>Us4JSsqlKJ zs;R_Ol3Kr?W?j0{y+?PZJ@o{43_1$wkBypjCLVtp-8#4Biw`FwWh_@+eIadgT96Y{ z&zs}lA}OO4nQ1<*Ip+Z`yX-Q~Jo_|e{Cfh+i+4B}SB5?{0n)Z1WaBfvPOybQn3|Hztl9TQ}l$7W$A9gz%A&mdQ(FNAcr|CERo0!)&d#xc7#? zVG8h>UNX~SDBHUY+wM;1uI-sH`y1-2Yp68?>@3;A&|^*m6<|+UC25&?f6!}ek|t@A zKTHImLfX>j9-0jU3zOJ55B>V}qeXTuJGQQ5^r)vu$>_jiqpqi*bvAQ9`;>Ry{)~~2 zJVsWl0t(t>N0gkfV&!C83zw1CMRRl@tCUW%a4lro9cya~l5mj-Btn2Rz?2YD5?dHR z2&pW<2M*rkfq~AQrz(XK+P$ss6DTPV%0eNjF5An$?zxLiWHNZz5PU*FunuVjFijb? z#%i~&n`DBJSdN=gYG*92bJPyEC&DbG!In)83xkS+lW~d@TDfw|35WP88xaa2kXS-u z2#|*EM};C}3k**z7L66;-)5E7NtKeiKrL^)_!Q4Q`!dH~dBss0$L+*rkxYM(*PeZXX|orRU(kUiOIGmcb7Se>BabgXpTW~(-lBbn z4lMq016SWPoMFcv%EE8v@#v$EQ`n^|OV<^1?u8d};c0{T;h!IMrXqPoO?2IVse9A z6&ol0oBFa++73Gt<@10P>@42Hu97kk9`MD|_N0@j+_srb@4XWadC)eqE~mm z|7->uOKK_TbQm(E7|<<`7vGpd-xDt&BQb?GSqUuqdJaFXT*vm38kCuUDI_7=MjATi z#l!=aa1w$w42^U$qOcT(^f&iIg;YKyvhNwBUC15lQM=}n`5_pbc7XdwY%(7I0_OuL5H#yrc*FOFy1j#7>p z*b6(bmmk+|;gF+-929p+lQc<_{5hf=tA4OzJ2zf>0RBJ$zYfjQ(iw8jHI&!;keJw2 zRebj0$86YKM0I5qm3#NGXu&+rKI06gfA}FAwr{1RqLf>&zm8jPyn`*pyCXIicR^HD zd^2+r?OJ6M8|&w=BL_44`xPi^`1Jkp9NxVPDG3Q=X6EzQ=+~*VZ7fyGrloT^y5C{M z`24hJ)tNgVdWm42g{^d)o)rQasAT%Mr|Hr@pJwT~+&OYIrL`786>(WAw54p@`laNh z$8y$%=d!c9nx`JTkId|RR&3b8Etj9mF+%e$%&ct9W;zJJ1VeDgOcJcoH$@0sj01baP&AT>MfM2V&PXG(7#t9$qC7v zdC@HtR|K(zi8Lg(qdyC~j<09E%ORaQk(1q-cR%`q0Gfx}KH)|Dd}{p3?Te(R--AM+?%_f#-?%tW#ax-$By$9VSPYnb)%`;^qw zpsqOI4Y`r8Hk_{P84{@OS$&dTBB zgjlw}_6k3ad!5kA<>VVC@4WC5gzRwoKT4sLplx9{uDJRtZoU2@(vnOB9(o>g5;xv* zBWDde8B_XrZtTl+?%IX--hPXEJIL|J9F0c^`VKgXc5MqVl!X$KBl;aq-~NYzZ6G{p z9CyMgWThpOk>84e0|pXf81(MfpY|O(pp+mrvw%~E9!G*l(r3V6-Wc~9ZvY$)1;>21ctk3E45hA1l! z@YEBdNR2UBw_-W9!4Ulh^=&e`H%XKH4~Zm5sBRy3-h3C6-usecPd$g8J-cGKmMAwH z7y(KW5+1tt8OVqS?&FvNhvHH7#H3_$ShHd=*Is`cyS8rS>Ps&p zfRC$gzKP?997}3a4AKq}6BElR!%pVNL-KiQ)FXVmVgqYeF6M7n-Aurr!TIN%%KXpX zz&b)(MX@W{S+o&vQVYzOIJ_~?rEL!1%$vvN9VK`Z(`nnL9YWM`{GcP)w!Mh0 zo3~T6V-NZ5J0PT&g8bH$Zr^~iswmoBLRMi*LO{p%t*9^E#foLi*s-UEUPlf_QO}{> zTSI**n|AErldo3NzT;tdgiUO+AE82&>)xNi zp6AC>Z)>nqLkMT!TN-HDkW?#0&*M(O1rpYoQ4&QEUqTvpjCdGjIlwW(q-C4#JaB(E zov4B!Jv*OU?zl?_$6{jHU`sgpv|&!Bm5n7OC!IP(!xJbQeChoC+FP)cjoBidf-c<& zDalEvof?h-$!XPv8?WzzQWiUk_h3snA?@;;@j#c}&a-u}ZJ5#t zXx+6nU3zq6#>d~#{%@yI(7rqOkLc+H-U64T1H;s;XL@n(*)Ol!UrFJP2)H+B_vA5(Y4QU+f5Fuzc)ma@L6hPNk7 zVo;$#)n3b6AJ1dex-A5q-9;(I`elpQu(gb5CQah30WApZx{s|zi=5<)|3v@z3q|O- zLuo5yFodve$35-D+o>Rd+6qjsM<-?|3%|!l`MzRm>VpW=gGU%h8~kxGSSmziZ7r4( z`2Btq9!$f7U0)5#B4`CLWAr}jF}0>yT~Uh_vhl}z!3<&~c(JG_7!0tttd_XAB!rY0 z9uGoF>grsVoJj;wrb+&avY!(8b1{J~$fW>;G&z0jEAVtcA3H4z4CxGffiO(Xqv!<2 zVtB!0BHa_P4MO;|>jE6!UXZ4A0+FRNfmEb;)5Nwkl#NCn6xfypLSZ-nwl;Q{22BVs zgf35^FbxQ*5K5yGNm*EU{#`B^q>*-2i0A=BP{llJ+|b&QD(7%o_<6VIXm zB*IAJ+Usv+!t6pr_!lg5B&V`9H~vxBu#RVMMg3`@kWuoh`}2niEg#&GnovuT@` zgs^I9*{%<<20B?zYP*$Q^%cR|8g>-##v7Bwo|4^Elvfc<@*<>xL}Ex2g&v?P zf2v7Q@owV%@nmN-C&pt?R$7W6i^`e`dEr>vw3Q^DT76$F(*%e-9T{02pv zx6&yii+y`4QN++JF^P_?GuX9rE0%)#sv0aCViOGKAmZ{IH>rSsRS7GBVSw_VV-Hb8 zOke_pN21J_FnFNloURc1E4}Esg*PnI7= zPi#g8`EA?s?Xq?3*;gL6wYuILp+G5v!k&lFrbQfg{_Pz4bT44~>}3>o?@On)d2DWx zLHXW&OquclkKb|{UD~HJdc@7F{;C&WFIz>uPzXb_Of?4b{(WObAO2m-nhFJYvk{Dzd~EyzysH(>p0lE1EmSEyf-6x@)|NNFpX z{zP?MfJYyHmb1>gf^*KjipT!-yk_2Tp;_E}B83sA(s47zTxJ~y#L`7#a$t{emrXm2 zdE}bhMWg4?U}8sqEr|xwRN)i3jTi7}!gwN_4g1H9h^S>wpaC}p%CTtT#M#Jj*Xq-# z5KU99Nt)z;O%x`061neR4{^(N=koQek9lL_2jsQwL~eFEC=(kSQw33YP|Cuqs`c!b zenP^7Ab@FEnha1A=i&y$pum@!!)xOwAnNvU@4XMOXw^pAbu2(C10@Zl2;j3q2u#P- z37vZN?w(p5^md zv#G2oM+glE<|?8JSi0l~?tb_gjy?G-Ey5}T)S_08AP zHYc7pUVe^Qv*&|IKq>Ipb%2R2v~|g_O)NZENKBysgS^6CyzuJN3Cs+=X?eaRz_KgF`uTe$r1*D&bFepr}j=3<2N<`+{wUV1T~BgmE1n(uEG<(_o`300w(Z$R|D%r}-sf>RQxD=` z5gtOqi$O44_N<(TZu~L!$e4Bum=;vcWe|S2w(`$qv{g zP4eFnr4+$nkTq-8kei!(z-yK-Urzu2{Q)Q~EoI7-DO`Q^)eZ%&Mt(zRmJr)H3>qrr zuxd!83ZWcNfq`=F(NHb60_v+-`u#k1@2f!x6Odp_a`Fo(?AQ*kXlO??2{{U*p<~yS z19c@Ob!A0NoA^30*#+z^F5-^+M{(W_BlzcCf5$KM`eg~n{j4ms3q=4Hfw~G7E%=VI z@>(!F*uo|#JhaMhN4NH^2@~Ea73K_xH104WkIdzukh#S57g@gtm{r0H+G6YIt36En4uyq`~!=Wrx2$xwU;;gcr*r*7Ds|w$1JMT?7 z?RE_#F1WP7c8m>r%hccN@fhW;a^4qCZ$zH4zs#61gRHD9diCn{>pP`M{%6GX_|Bg{ z-{B5+ELA_39eh9$f}OicSh;#Fmt1-waj`xE!2tE4deU2@Gwh5r`EuSI^0J!KEHw#j zCX2X!B?d}bdUDvB>d1D?e+Gh3po(#0pW^VdF5{?vN8k|$p!u;YS^Dh)UYPbhkKKP8 zUXQIIVoX!hc)J$3@akHNCH+VY7SEf>yfu5c;UBk?MD$wFC{VVM^4Z8R*!Y|Mu4+>K znxskomqmc^H26E>LNOy@9?oZ@(LGKs92I-_^6iAjD3YwMJ0I5I0heo3YVRG5*{fW#Ur{N(V^cK)s=g=|K2-U z@coYC*KWeiu}bO&8V-0Ex!S}}=kXXJCFUD17@pJz0xvv6DDh~X$UjoT{S(|^OT znFeJy?%znM4V>S|(r>v@q_@q?! z?A=GR)MUcLQ%CQD3Q|*5$+*{E=id`1vwPn@vT|~{^X~f?aP*Ow!l0^RAC{#YgPXQI zhEH)Qf@OOde)A2S^^d19yfEsa`aQJ$rEfGj}p*=!G2KDYGeNuSuGuN&XNq1f-;A^4_O&!0-{hk-L#}@JrVpL5qS8 z%>Q8}w(tWcwn9T!!GB<*lcY9p!KYt*4NknCEu2i*MpqupaJeRFk|z1TDW*QGXe;2R zO`E8ztHUr1Y}-akNlHoz&6_v>Nd>V!7(#d@wRJ&^SO-mCnAFu*Q}h4WJMTCts;uvS zZ&ioMIVYGIa?T2pBn!x5LNR9q6%`N=6%&dgi)+|*4VVKcMkI&<5mCVef&|Gk!!S9g z?yjo){!vxkJ%n|4pU3dL&iQ->y1J`woqOumy}x^+&xg+d&9Fe6KdKfGK78I%9$xe) z+xJ&;-=ZaCB*(C8$M-zG=pGv7d`1mA)r_E%8d_5$ufO#+8Ere#zh5tF3YC2I%}z?H zbjFStg0G>L*!U!#dG2{U)%nc4<6(LaAHnE;-BD#d8`r+W^Upm`NJJ8i!a;gQ7e);3 z&ujl&LXW>KBvh5CRwa@aYM~bT^OCfpf%os2y)mpwQ5u<4`pkJRWKrG|DRK@#&HVj}M^+g`t}sh=8QNtc1_L*v!J` zUZPiSE8GTj>e!yfl0!WI{41O`s6XH!j5^*~xr+B!ZRFXf{(`By)R9I#Uw^xkLBr1{ zDKZQPZmya#4G_qNG@>FSa42RV$j%)<^Z4IiV&UDhn6daR3GDDJ(xXY#+X0rtE(dvmUOMo<(2;yljLMyIh;}ht?h2lpPLY^;3X9+)V~xpY0U$ zKLvunHn8|L!O_2Jr>?G!<;$1qmd)U zWwhyVikXW_nn^mV%8FU^&=T5rKZSmsIv_nIta$THu9|)u(OJo;W>P79x+F6>7THu! zZEYjTQBjs3M$2xfg<9y(Oom|~gy6P0bNxUm*gSf&IZ^n5-m%|X!45%AStbZH)4v2R zwvDn%Gbeugn&1!3s|lNbhM}10WQ0UY1u4w5GK!-3HIB_@H%U-iX8uBxH(~L0e98q= z4h8}5vtZ345R^pA7KQ*nFZOkT02J$!uu{PMAJ~QGAI{_TK0Ylsb1DcZS{_uhGnZ+GPpt<>|~mP5>)a}WP~cs8oyK!l#aEx`t1TS_JK=ZjWcw{PF` z_$B*T@TXYcSl~ew7*YwEYyFw~f=tgrOxYi#!vv2UtN%0n0>A#5pIam`Zk zgT+7^GaEFkw&5P(*ASm*oeJciJeFVU=i@Guc990&m}=^Argq2KT00hxROZ;7-a;?L=s}VBg++=FOc!Ty%6$6d8e+1wmL+D)G@_eEiOO z+FX4WiZIYT^(=e)Q%0XLfk+h;Rb}?Pxvc#73zjTc#AAP7j8jo?BT$u4Qj?O{|MPYb z6OmdaFFy4oWkv#vW?xT;(}4jbWp`)A+bcm)XeiuHN&V|wJ8e2KG2!gqR*rDGiHr>M z*F`?wMY@GrsD=L2Bnd3UQb*GaRENu4G>B2zOqb_rxt2q?D%7y_x- zpu}b&ptbb-Fj@fCuzd_Mt2pTzI2|^?wZLew>MFQvC!#+J0JKP2@;1SCX?}x9lz|XZ{@QP@fOZH?-F9u+Hv8evrr`Xth`WjZ@H2B(tMUY`cJ&NHIXTy z^y|@{E$iQ-s!pS>ypE@y{3qq5g*M%X54%;>$mKnp{j@#Z@jXodSzxk5qo_U(*UVekaB{e}aB1n6_F=P-B5`JZp zl(wcQh!I3kg(tgCt?6HgUdi$omU88k*)(YZBP3G#=V1HzSidnpII(Z%zo&v7fMRPQ z%|Mc1Fc|>9cH)0CCu=QFKfZ(;XD_6t-UC)CJ;j!;jiIo+X_++z=u%<`g3PIZ5c2b6 zaVs@Iv%r@`x3C(*@XJ_{5(Uj~52a{x@?x{>&?{zDk$j=aOU` z;)bcyIDguF9=PdD?wvc6S5~Y+Muc&}l~afgb#nbh7qhRRn51_7$n4UCw4_-4MrOZt zG?36)3R^cL&1yr^Jkl+bvyc*D=m=Fspra#@LN#?cdL>)G|B6pG9i~ZxPzMO<1)*9# zf>`%B)-I@9JUFeO6^X;}Vc|v*!K2RR=2azgk}yA!Tu+7E)1JLrGp4KA|EMCt2A!Tz&1;jF~u|!n}Qa z_QkjK8aS2*AH0jq)JWcVZ5fA(>v(zjyQJo3k(JZhZ{CFfsH&^0Brop>nkI0EMUaw_ zPIRb?+VWzK7M0PYgDw;jQ&LDujK`%ac?tNn=?)M~iF8ZP$tF;ymhof|S%$ z^7rl{CNZ7Vv_xtuirJfAPDWY+!dFFUStGi15D^(kdS(V8hJi~p!ID#WC@n6du(*b{ zT{_~cuO$D_K_ZfKNlT8yq1TglxPY2k53cY?(las$4GA&%`yC$pzamrTXCUw*bsx_@ z{ump-+QOXM=dH4h@XN#}wc(a)$6+A2^6IPc$|h#adz^&$45nUrE+DC{DCUm2^Vt65UOJyT5FZfo zJIkO`?Xr<9;7(%QAUOtrj_2-WoCL51FfhSFm)3Wt8%Dqk;_rDgU>i)w{BY9qnv)%GCw1L2#W%mmKVjQ?eqlgRi6HY| ztE7-r{n}S?Y$MHFLhOzPIg+0Q2M7F}jli??Ut@89oaWfDl*P)wRiC<9AMNXrrY0lk zyyN;5#G}2)n$KMEo4?FHW7+r`f40=?Xky!)+GiK9mQ`B40t%%Z%T7Mg?-19le8=Z_Ve-c z9q=KOmSN0)&wum1`k#=gh4b>+>i3v4?;ds^IZCvu;qkf=NNOs|cxmZUA~L%(v2PS! zU9$1Z?>Teac;?T#0#Bolss;~NTzw6hxw$NT{%Mli_U#{n}tFA}$`VgUU z+&JfMZoTe2K6vYOZoA_lDttP+F6n#9X*~Yiv$Tno+&||QmaX0ddOa0&Ue204m47}w z)jtm?ikJNTyO?+DJl1Xg7U?r++om%Q{o_ea>DdvNlqi1LDl|1UvFM&#*qL9$KVMwN z!g=$kXl&&5H(uhVDOa)ea4oOB@-jDFIEkd5BYFMhzwydbe`EH8ukykx|K$6Rmhsw( z5Aim636D);{*ouTXk1rQ11NNmHN5%UQ_NlXGT$HC#{Mmza`ohExqRM2=Fhl{*Pnfq z1&_T>ZDkp%D~xMzxr>``xRg+biY5(|UwU_cLlT(2mPn1J`YIlO_ATyx@FB*H98T*9 zjrmJn;*zOTh;S<)8#r2!Pjyo$Q?8v(QWX63#afmweUYorAIE_MM|t{hFOi$-LMz+P zE34KqabPFjc;gLjd3+gzhIdCQPM&!B1H^UbaNUhFKseC6hgtXePZU*DB2@=t#*arD zO_Y|FkevP=(&;iazIrvUy}q1weNHDSy(1v0xTl~9#VY$IOmHUv#js2nHlJ=#Lg?5wix8*T zmI*kma}*UJOr9hHLmEiT#Wx{6o5c8N+|7HziB}eRf=_{C+3frOY-N(R6OIL%71b{7 zZTlfv-3okTeQ6Nvs(mbnlH-0j@o_Vqz{!{lXkTp@5deVASL0@~kb!Uh-H~-tfX4}B zeS${KbO+KO+1adR`7ihgYS_=V_5U$0@xPqLLfTKry07(x|H=F-K7xi|Kzt`U`$Vw# zUo$4{@gsxJ4jxy*?HSGQD-8_5ur>h_Vb2;{KJ+kU^*+|D-^iP9zJ%KeSQ}hLfaXw;iU7sM8s?uw_fMdbszG|vK6fVXe~Q` z{DGyft)@w{r)9h9u8XMXL>_tUKJ=PG#*P}#SKsF|=k|L@j*4aC#Bp49=_Pb*mrmav z9rRB@NThI4ux}UhXWmPnfy3DL;|?aDb3V^J^9JRW4S>Y)2XfO9m`jx+1w!i7RF#om z<|8e$J&M$bjtjxt*g&II=}PKNlok~d5}iS)D;z~J$jV6IryqAwSXP50B$m{K7z9mp z>fDZs@=6L0=TqBQPkdT3Iw2&)C(=+=ijHY2M{lG!uY@1BZ|9Or&ca^Gm)vs?o!j;# zAwGc%E*g(ebc%Lw=euvVGGWprTrLHN<$DOSPr*}V*VlpXib>$Q%-Y1lJ=FVb*0s=l-7}* z&%m&*Gccpy6#pwD{I@p{K?`VeFi5kblf7QHj!_!*96ofA`X=M}cBBDPL!g_^(n_EJ zyFDodK&t^5zkUU=>Fvx=1n!fvm58~*!RxgqR)Wha(E z^XD4S+F8q!F#Bm2nYZ$dGkhuEvtaAqF@b)Sq;RA2#Fyy z)Qu{AxHJQU2tuNw2y?ql?GgCLnl8ccG_vHbJLuNEHXxKumWo@okJ&=KBx_U}JPrN`jLY1ebXWml7y z-H!0EPz=ouS_sleN{C5FW#YJzRFxj4ZSTHx@7W!s!Nu3y%)Gfb6B*{B&!8Uos!MqF z#h2N+=LmlpKOUE-jGHgNnyx*1Gvn5~@HF|*d_Iie@rerq7eZQdv!#zRaIkm(0qPrd z)~;H?kYU4F_2I{)CdZ;H5}jsgum2DvgkgzlV?@Q_Qt%mG z49nY7^9kH8Ck|CblM06J1nENen3cNRZpE~8={{7f_0OSNN&zoFeEkL2&tAfmsWWJo z9%ELzl1`@0x|5GSS&Q4K<-XfyQd3jRl~ZpeDmAuZ8|V z^qcF~gEfxA&`ofoG+U8^5S9R8nk?+qSfE;pCwt*EQ@RKQx*oWP*_PFY1F9;k*t2^- zs-+nefG`ZxaS(x7oZU)`1L(SjAtk!~`!PEt6O$VFYOC1&(~mT1KK~@8TM>Pxf=^g4 zKF77;j~o*q@KRfGn1v56Ca;c>TVKwBLkFoxV)`eYXhc}x zN1CR7!vORq^7rrLU}0GhP%tN5P4k){O-h93C2!v@3M%UG36oD-Go>iOV-0lOPLClm zPNMaeNV8&t^dayfrG_TJD+$z*F|4HIQX`P~){?ibo8U&8f4Z)jVzUyl8isB)A*@Y` zG{?UHqpp^pckaX^4bz}6h53A?rTr4ZEWarAAemd62YXi|CDOi^mA0a(p^WW2f2JuI znHjnn32(hthMljDzz_{2vsKMN0dGAo{NrI(e)cU*-bNPApU0+eb|3{PmR78`qJp2c z|AZazs#*Q@gYF;`sQpPZ3=^PA18CsuuQssc(PsjDU_M99kZ8I@S}(b@w*bGk=0XVE z;i1IExhO9_#Nqq`ywVkL-7qxEx}ac4(@RYEcU7WDP*s=T0-*$Upn&=A*Oiv?&wsp3 zul_@M@zs|(W5h6|p&=9}Is%_C<4O_sCP*bEDG|jm*th#|?|6W$F`-m>Rda>)<^?bQy zGmQc^eDnb;-d=@AaWQ1{7?PuOmOk|qhwD_PU3(=5cmBwypM1kP7hcZNm!2guG8`1s z+ek&nQ&)vo55W}`gQ{0?XzxA@H4KkX&=m&>2?+=R?K^kpnde_(`P*;u$m5Ghh>pO_ zKKRE<+htm(0O2AwA)PiUVHE7$j#S)~meddx6HSCeK^Ov|M3b17ji@EI5j;t8D)E2a?m%NNb%*a$*ce4&|ZXrQk>b5s8^NfL*(Ga@PZY zW7^F(GyaUzaSI7T1JyxjbUZ!!_2b;L#`FF6-%;a(ORu?!-hBq(Yih*j_2BXN5JK_K z9p-XssStjn5_m22$D!ZB$-*9X28wD9I{!vd8h{UJXh><`^XZ@)V0aL!hG7|^456Cf zOaMmnV0Tquf=0{*O_u^qYhvxH_j%;OhcGmAI`Qcegb!h9l6-(>VD7%82i4&~QB;Jg zqDcY5hZ)LmEk43rz_x7on7OlVq1NNYXYt?=5_A(JXa?9-NKXEKnVJ?Iox-we8VoF5 zn}*a4yqeiVZ+$KI&!5BkjT`X-s47A?0hy_Xz+5QN0UtsLf64(<9=aKoC(LtoX={Nr zbDxkcQ9Hj9|9qt*_4stYJ6YgZwKZCp z34m>_cQ6nXmdxwxYk1ZK*CWK;Gh+YN5-qaWfpL&t>TW^w@}yAgq>GRs1nfp@)wF~ArG&Ad>dFn z0O%kz{FMWQK%%p2>qchGxP=Cv`6@}>Y!fsTOFJkP+x?9egV)ozMgn1CE z#86z;Cd+&;gwRbup*m584@3822w|q;_?62`NSs6^wBouOuA!#5km3CYFlfYIX!5Bz z@FIk%3DUGCgd+?g6jZ6B80M(Oseo)mvGckq!L=RCa@uC|*~g!7@uUm+c-@DD zI5jXNK0_cBa3IY42!T_=8E1^6Q^y3JSa=uhayzr@=R7NVIE3srt*I|R#Q1YBVaUj_ zWMpPAf8HEUJ*6L~o!Xb}Tff2O07bF2&*qr$c^jEEYd-Gi)+~SfExP2!v3Sw_)HeB8 zaL--bFnt!q)e2eJow(?%QB+lw(eLyLbn1{sa&iJu@o_x=!b@Co`L$FxHsM4EL#0>m zKIHA$#-&%^K&Re)NlA-h!pLEqckz{!HF|J4pi8eloO8i2wtn>`BZi+&uYRZS#N$sO zbRD(1S>g{x5(f@7~m##2k5XZC%6Wyr8$L^vE=I%zU1SAI-tdJb*UBe{G2 zJRW=MIeyrGlFxifF!iN8O`BTv1|`R9%&Dn6F0ubam6|9Fa*o_(H& zmpsOpF{3~>^3IAkNXg1Y^EUFyC+pd?=}T&BDtT_{v%L2Da-Mo-DGMKdgkdAc5+9$& z`Ik)QqAM=tqRTF)cb`7=?c0aMgjj4p+hA$|fqy=7{MHZMG*g-y!0*1>%IBYN!Y5($ z*l~2u&Ed-pAMx#X-xD62$k;O{l98N9T~!e)-g}25#kHueFoq5vNv|H=QKgT9g2Q~U zdL0$j_4Mi2pTPtA@$uSs`Ekc?!ef#dcjg3gGsAEgP3+sbodpXPkkPgclP{c1@xh;2 zv+i@sYCN1WXdtJZ(g#mn6`y_h9y|6Fp$R9Qx^-pbn9+nOUcUV7Bfi+O2gMP>pwmyM zPtUFhsdH%WAr?RQSHj{GxpmsL7NPd4I>m2;7Dn(b?Xm&y8d%CRL(o+Y+5Bp zvw8E^eDU@7M8zdCdfY@>rzha8tK_Y>-zUGY6dx*Gd-P@Gut9`4bm}Wh`S8Pa>^oRU zR-5*mHEtxkwr*j=rmyfA4hD}LL%*KgPz@iuw{B(0{eLAZJDbUqCK3}77CagNgNpJZ z-dgc4Mb!(Z68hxfv1cv-u06{SVR3>th2r*_Nc-FH7A|41q6ty(kT+(|@YfX~A_ zufD{#Z@=NJ@neWmnmABW!RaGM;;TQ(tIJk1dh}S*5<*zB_9M3MK7czsii<9oMBbr8 z96WfC^Cq2VDNKFT*A;Q=tb52Wsb#_9N61P~;pov~vNO}ref50(piT zLk(dY#uD$$1JmrUZf6d1nDXgYb*KUj+GYYq&^Uc>^uyNB? z8k)Q$XJ#;R^cb>I+$1C?k<&&q6UX}+`Qo!r`DW`j)W}3Gyyzmd@&kOZW z8bb#5M^ThtaX0HiN(bj(GKKW)j%@yJ2lY*j#HD00ux}TlLYugG)=YYx(v^hdXs(}r zJ?U+`S*mC^JqHbDRzxde!d$5SG%S`$+tSvmkx9Jp#!6PM{)F=K3Y_k6+IH=Z>Ik7< z|3S=~8%AQ7lgQi-%$Rd4JqGq8HYt_Y-hQ9WKkTKUG@p6*JxXL`3?32AxtCo@XhH_{ zN;CrokKm2>Ugy)#zNDh2iO{H6dUxr7Vi;zoe}9;rN?BziT?U@X#r+46m7K(q#rN~x zM_*AE3q$ zpqkH!*q^2gaZTn7i9Nc!- z0!ED-feXwHn57u$f7&3F@CbkABfq=MA4|Y3^c&K@Um5*>i3AGhReZhSV=kEX0GD5J z1sREMgi+73<;%G5uKSpN^HjEf^Eu03dzBYfyieWXgZ%T!=eX#Gnbha+V(#48JoECa zB*+SGnK_rxj7|*g(-Fn#LKA|Jut++0%3sT0p}?%2Ty5klKGIqcv0 zBiCPbDX+f&AyNq^HZGQ)15YD9Di*b|npp_Kf0S6=iI~G+ioXLc(`ZIeAI{T#+-E?syh;d1E(vLHaWTE@BNW`Zoh*^pLrJ4P-4?l=se_fS|`QgcDs%l z4H`aQ1JkD7N^E>Gqb7{OClypQbfJ^kz6-qvk0K{G9z$qE#YEFBB7#?6Sjx{ws+o7= z`RESF?cR%?eNH1aDW0D`d7F=ZDy09&5$N^RJoD^pbnbKt`@Y}G%)1|F_8oWQ@>Qca z6~6iI2iC0qkh3P8hawGB!^_SezUI>}x3hfpdOBuC;s83e>xe+|^@l6DW5FWMy7)5o z@7ToZb)WIlYp<|-`$m?&{5qFhJ&k?aKWEaUOZj;1N;+nRF#Fc|%qed?qcu-x6(dYVc|XVX;dHO{89aIIo)(>m&3u`TbXzJoh*C%EmI}w3a8hgQKW=6 z;&#;Xz~V(5sc|x9cu$^s;t4c8l5;2YM+hBF*FbR-5gAXHjuE{5`b+G|FJ-~JDJZH7 zMOgmBii+($t6-SsYT+O;HHCitPbDEW1HHbQyXMXzzfooM@F6_1a30_7I>hbMC-cG+ zk5DAjnK*VRYgfL*XP<56$;aojcmDy_to)p_Mi1cqx8LI7$6w@<%g)0Q5{knxxPQSS zqEj;IJ9rdMMMeG9*Dfo-$PvcCp`#f%bc|{GwaloB)VO8FObiqp=uDq}J+^1DaKv)j z&@<>i)bxF8D$C=+yJqv%PkHFLKnfIRC}YpPgsIm}X3F&)P2&cZ_8OgjrwyU+z|&2C z&gf3em^&YU(!*Ohcfv$`k?~Yld8za`=yzH#LR2TNxHK-hZ4rI#2k|Q$yo8`@9RS z5v5u(FzJs4QOsoBrYns=5e|eJ#<&URFm{6NzijsGoXHnpN4%%DYRfg(wZ}k3$LgC< z36D|e|T(Ls(qoH2F+XN;ZTuhxRi zhXC7gXyEBXO=|_gc^Cg!(ruyNmi!>FnOW>t)D9Zb08b-tyzmU?UwS3C%$ZJvQAa~f zG56iKhI<};j&sMIidtX5U(UIhk2Y&abN1LFi28jEiM&y~D19dBhtoV&ak* zH25@9LPOa3^?J5{{~b3x@ONS(bjF`KmQO$1%*7X+M|_AWZd1}ay57LUiyvds1($LC z4cAaxyo>eQico|k#3jhd$)U8gnC{&>^7@AFXt2zG9XfSm*pM#7NCW9BCp$ZfvWgn| z^zO-~ANQg;UCe)A33k~kfkYbBtX;F3iIcBl=1o^4kT|55f86&TmruEl3ogD0y=n*} z&Ya4sci&}5pF}(|l(7@eqjOdm6^D!2vGogjoSMtWo3`=z6OYlkOFL8vs%#`VEr~jx zPHeQ`y$wHcq^z0*LlB>w!hnIjNeOY|_Ad>>|Gy#xjWv~Y>d>C9T{@7Om4);aBZNZR zcG(OY+LcJ@LHAV9wtagl%S!3qqa!QUf6mMsF93&1`)*wrae8;6(AXnASh{9Y#zMiT zIPhvdLfsB>Tcy&o<4{5)LYXq<8m3LT1`Ts^l~Ph!R7gx>I?0)le)m*?4?}BW$zxA5 z>7uK+>YB@_FF%D#uDO@ZTXx_wnutlw;+%`mC8S{xt3JAf@4niIvo3)*RojnAj)>?|k?X2Mdl8rGyZl6wja`{YeZBW9Oz%_;KrxOkX^exG>3> zF(cTpej}F+YmXuX!^e%{^d70yH#G6XH@lfUvJWX~X*BqJNTUYt`kyE+Z^F0Ey46!sn7k5_S`;Ka~sS+!;@H_p3{3&syH$BX7c>K-yulj+i_ zEvf102-VW4{puEtKv^vjd?Xy$VGf}B1GG#Ny%Vh8q;4REilRp1a)nzC7*_C-qWIk& z?DmCyPfJ^)Kv0cZ1D89LVWWn!Bd>~9xe44n>P#-YU_4G?ny@9RKkUus1F&3f3{-~$ zoGzR~MO6%3iVL@*Sehfl3La8|fPypdtc3t83OOK^fIgwQ;a2#63shlt{mb(L=l=02 zP--;LJJtV51b2|&@euspn3~}eTpQG8pqb_y>E`ki{`QYOLj)Z*mvjsL*~tOT0pPDq zs!(WZY@)KfnvvbRngd@^@p|g1tg0cqb8kR`OOT$NL|J()A~p^c#d5~gi4F@z^XinA zR+5yQ>Ys>Iy^dW!ZsqO;i|N+84;A$q4NVRBa3FD5{(=CK!n}jjHr2Ch?*Ss6(0|AX zdUfw%#xg1{%lA+xJvp8o`x+@Yu$MVkT}*D@p|nbhrqO5M(XDt^p_&n?Ky6(WhV+ql za4$!kDv>FTfgC-2 zgeIS1!6vhKyAx0hAM01Y%QLUOPq$NtQhM+ZUM&F~vu>#X3_w3L3Q zoP{AJPNAVooucY`PESw5K;n*wAUPq9(t>NytQl@H&4Hw zE~ky-_NnLKR2&FHn)lEeS^MTPo_p_e`ki_z1qDaZr3+n`py~c#2&864McO{0LZS&B zO>r=2#2Ds#;DyH@;UAj99SiQIQ%)vGPz`Ib6bhk{(bU&e&{zjV*!*hv3=ap2DmX7C z8Ab6D8XiVWbPV|i50jIqU^ra(PzZBIk{lb2ueO}xqfKb4oA~53R0%>#^7rmx%9U5r ze&Fe3C5GYk`7jJ~MA+}4L{d>%fiB_jfxQ$6gXGrj=sm0lPKW6aYgmvWCMFuaxSGbw zLhhV%D=}$pNRHB}sH_2mrM*-9=AYWqV(O~u*?%aX+L}6&GFs8EeJA{pjzaR~nz#7J zD=X>U?=*@IAI0O7{-iMG(=*M%%`*Qw0oInsJp0|vTd$#mccP>4=#%L9+SXg)WongLM? zX3&x~$DL5iBb-FUwqnuWpEG0f9D(}AQW{plG5?KPsD)bS|8sI2nrAxjCU))5XW&K2sKP+%5=A%58VQFRp$Jk^ z6F7WeEncq==@96$k)M9rK|)SXZkl-;2lnn^*Y<6oOTsYlmLD-wBM61uPCbZ^+Q|9m zpG{_3GD1oWhf4AO1L%f8RTZ-syOf~&*tugD1%-t?f7iW4iCR8bxdv%yxZMg3^))or zH{fxoM8_o{kqkd$939%{;FKU01*gCQCsrbDR9ucQPU+m5o!h^o{+uypeMoC>`Q10$ z=sWZbuAO!r-+uT8Uq7}AMF<>1p}wXXUDwft;ImIQa@x>gTzTDezFqek|6H*J6)?OW zbfKUK7cQZK5<*5wGCytJfE;rwnow{EXq6hl&-?e&fADbX%S+f-Sj5GhE<-2^imF(Z z2SAZtbg7V0B9Gy}fh{5|8(p3J24|H8*B zo@euO8*vDgP=`uQRV6-M$B+VdY%KYCKj71JROvJgmWqNaG?Kqex`YW6#xwJ#sr>!v z=UBMlcEWUn5Zg>`sN{C+j?<{+%@>z4<=RV$P!uz6MTw+mhfEIryoW~b2MeDy*@l1A5AV7DJh8vJd8MFA|2Xf;5KxG>Oxc=zz_~=i8pXM1P*-Em*i1dRn47C zW)Y!Q^4a#I=+eODa?@B_hp$P)8=@1Jo<&%so8hB}F|=QAG^wMgP8`w<9C4_U?>7Iy z;NfR-<+WGv#p-2je0&v(KZ0DMBQS)(>(l*pW(7W?ToS#pk~&W#;cgcxF-g=FAEc_b zfw&0xaocXxkTBvB5tV|2?g17lFg z?S3k^ck9mnL&aQq{Q@o+KaB9yg#Z0{N=gjFVEy{_&B|#0A{lnXb^v}!Bo0evx^S2! z(a;gnj5$}W)Jr;MppX=1{y~9la;3si{l&3$|yYFS|<`1c;D5rD3 zA)J0{Z%Vg)ixjFgSY0Rz7+M`|d-kJqn~hAn_$qR;l4z5i%;2HJc;U^3+KhyJ z>Yxxp&+eUh{i%O2?Yis8>DZ3zr%ho%pHH}b&J2>$(us~tVCF41U|2Od6=@(0fq@gD z*VCj^Re*mJE)W4-1ERa zXi~+YM03`;lem5U{aiQYS|VbSm@sY(=Us9scQ1aD9Xo%fuB3p0g9k8t#6YU^zCjob zsM3ejLr|QdXoiajM>JPldM=9=-b+&JcBCezam_g+NJ>d&{vCIa9q-^sNf{1RC8NXba&%=0hc-Y4Fs zq^OWnyXDYxzyO|n{dsn5|AwOne)F?hXShNAT6s6iyyj& z#g9C}<}cTgoR~6`33e2D6TJw%0s;dZ*{(5*MmzVIv~`n985zk#e+wv3^t_9Qng287_$f&F>%>1UXJ z(~YF2=W_dv*E4$j5T;x)nN}HD96E5AxpQtLIXMD{qVWE^?^BY0fQqAsXxFPR*%{d! z$@?0iXb2^oOE0^ag%3Z*_nY3w84|)Z*IdoV@4ZQBNg);W8tpr_AtE9aL-(Pm&J#^H z|NT5=X_xEj>To*$gSM@3bVEpgPC)as9kFf7*p9FV1x138CP>tTnZr>P(x0M9O6jlp zYo_8<@n>0-!mLkgfk0^`#g~GUq+~MNkyiWWEdn}2i(_oBF}uD0DgBz@;`fMXt*fiU zFbtZSJoqEMf8~lB|4BdpTRsX33P?{+|F5oXq5qpCq%~S>jo`0Nre`q*8f7H~l$2D{ zs41joq>&aAK}qouN=vKILnFw{%pxW%6mNA61;xdr=j0G7YRN0CAT&0Gq;MB?HDweO z9HmiL36F`UReBnw`3I<|szX;?xFaKJo820R)<|K&LCPu{35kj&J0}}oZ81j*3TW`D zghWJ>+o~0Y*T<2(0@B;&;Gltu(jv;6+_cF|p|Z4)qT*6?si1^Jkd>85bf}Z!{QVSF z)nSB0(Jng+x7I-Z(GqIvJm7GWl9felL^uw^OkpE!mpDTr6c1&k#S|4);MKtu8BJ#E z)`ZD=@(c2)uJM7Q5)~CoW>z|~se*%tOr8^xlSqqJ$U9O6 zscgg@7EN|mCZR6Vq1jx-bacZ*-l4-(SJfk(p~R=AlO7+9)T%jfu!wq(K}>u+>2YrI z3ks;IsYg1)36D)6J3SfMRL%Ya1vD5638|@M#Ya~`7K;%a~}Q{R*p6;fPLLxTn(A>pK@XAmE%P*Pe*aY+>p zcLZtaS;RzyQd?0#VYQd^>}*1$hr{~{h>3|MJ|Pax+eBX8A*vg^DB+Q`%}k}XypWQz zI&>*fL&M0(%pxXK<>-+k94)U!hKA9xRR&J!BmZy#bqyX=my7hQR>Zh{{Jdu`DY;#U zbVFrT4fTzZ%(OVlOA9F~sz8?l5fVmLZX04$owAZb3Jc4SA>riYw#J3V(foX>Ydt8g z5Hho~i3)X_nkPd;_g0gCw2YdXCKN>w5*0^wMk=1#G7c10l9`@@Vltw zBPBkck3D<#keQiz!gIE7-_D>xW*|gaSsBZgEn~`*DHaHn&9rO6KbIXdxmmz3P`qoyYqm>d!N;J!f-`<@E8;wmT0L$;o0&j*0B#XDRU_MLKuc2e~+D%6<|+u^MsX% zS15Mv2ox&`v9u;f1-oXdFt3+ZEeT;pP$__rI(ALn;3NoUb%{XRDn3kCccr<1lb@`l z}d?Frn^h0UMIvyQMF=L6T7362{%xc@K>4Ncbkt0RRVIXR8=)MT(@#YA8-_WR}p zMbMcOwBAf+_IbzV)E8D?gD0Ng`mzDp*s+KKx!4smq_qf`8U<--GMe90T79+`G_#Z# zmJgcGulX?aCJyaCNNrt{snu1$XGmg_Qpn9nML`DjGdO0@;@tvh=F@ceM~;1kUAILA ztdwjRiVum3VrgE2WvQTVdxjwy$=fSGwO z&59>Ze~ZDR(jH}jjDvyt9SVkpCW4pEz}ON&*Vx~i=Ld~Xr2ieUpI^WXXqo%{Z9_0f zXjUiN;#67@p22mr1IeJRchi!E@Q)RNznY2Akwz&~CtpnJpo^G!!xe;MkHEm#w(rL= zdf42zMQF3&04(Dst_Si(4~ed6$F8zAcQr!EWwT`{GrT4NkQwZ<62u!6l5Ypx8)A@H26MErJz8X+ydY-6vj zp;VhARjaH=^R~c#w``#4hc5np+w-t#;y#nOw2^s-bHV)!{lGuu4*tq&b@zQK#*vIz%S5TI~#o69|RJ< z|Ni@=r>D1o!2i!F7zFzB1pZdh!Tx(-O+*Aw0s=cyDgfN1|7}u&0GWR`D{LSV-1xEW z+D8_c^Dm^oHPH5 zE{+^6#t^3eoNh?E^yp1)dI|_}Lhb_mD@dIF<@VUPxn>b}!kmNyW9WFE?F9vaAAp+c zTHtve*Pr7+k##RKm9Lf5!UBLn&@uQ~m`^`=%VGP72Kw7N+JX!Ri z|J>u+4er^$9#eKp$HK?sqZ|qPWWCE$B8cSttELm0(#8siI@wr00iWX7Cx2p2|M$q; z(FAl;5>=~V$IgSqrR0+K|JXb4I4O$lZ$H)DGqZWwU3SSCiITH`C@6?X6cdVqf&oQD zMFc@WxqyI56a-NL0~k>em8e$~^{QkAlpt{lo5Q5;s`roX2}>}%*KqyG@iXo)U0pex zI_aD4MhZ8UGH?ljz(fdz6fP_WmBCPc6fT=NR-iligyH*e8168np~DnLtwGx^Pa}k^ zZdWG??IYY1MI79FlwAjMX@7BRV%!1^oser!c$G!nLr#})M%2G0Z5wTIV~DGXVjywQ zObp?K^Vh;_NkpZ!liLiVZn&e$i)0^aMHmT5i~6O6Gg9P2``7pqmqZhfX6~c_6}Ij^ zOWn@K?}Z(D{;Kwzr++FLr`rzv9U_K@q0LlCLKrP8J2Q2JLR*N9<{|Oe5+Q8-%HMbC z2^>5JVq)Uxd-XLSL>O5%w9XA>~MZ(XY#|0Skws=hRFL3eSbEoNeTO@5NzRTY+*^o(BFToe-(u~K@t<|L+#%LgBP=Zj&?1a&Waf*=om-T=tVH-TLA2gk0LUQzpvk_22dQ4G z7A~P2JZvqp1OSi->7yt&ho7<}buOsv$dxI{)0Ma)MXV?z5fsnH2>u1@=#0(*ge0W4 zmkx%zP7oWv$4$g-M`1bg|Hv+-qW=Cv_J#BGmy;coz=6>EJ1~IYEO}*NnSOF|@{xq> z%+5~sq732rD!@-xb|w!z_$Vh%9^v~vTNyiH1_i}|-?^U7_9ZklU3Wr2gf=osL?Rig zr^&}3f5O-?kD*l5hW&RV5#fJ?5GWbI3KnoGCz~+HpU|Ao**yjNylKq!t~~21}(e+L1At#T2ONI*l|u} z?qc};_jCAUfIhwYa!Jeje70`4?)p3c03ZNKL_t&)Q>V_QMY~R1+2bnGQW8r@-jtLG z8AKz9hP0hTgzYw>l(g}tLvu&UsEexYSYj!g*$65PDeXQs13`R2>98UyqC!_13LQ)6 zNHoX!#bF|qva!^W_61qVFr#W(_Fg3&`J_@74!;Umn1N%Azke8QT3*Sq>^w|_gGX&) zDGSrVO}3Qa(BALqdT|GajeL{><;(!-;Ce?{v{+8tZKoG76?VOaZ8l?XFoyH_Yu1o$ z`eKJOGJQvRVg6M5^ty`6I(ML3*DDx4d^Ecb9LB=Or|aJ1+Wx~REb>us>M#>V-bcSd z!#J8#~D@8g3urCI|O?$+YQDQmB+8&pVSMM~x%CS73YP z1=+RhN2H}FD#~Z?{zI6i{C(Z~m9TALqSPG9kwJ!3V~S|TL$ZJW0k&-3`nMX7Um_uc z?B4PzQ=ghiF@!A&!461!u1(L9HmH5}$xQYgJc^}kJleBSgq=_z^Eq*3H;+x4NnSzm z+3TbPf+BW&y@7|uKS@CVG~>6*f-R6<4(;8>qmPWDcds7YK5ziGc!4Q^dvqlWcM3tzd}*S zp0C$&>kZe^t!o#C41buddyfJ^zTLQndj}1qSC8&od&2-;Td|HJ6c%2NAK1#M2kzsl ztFGeuTkhof*VZDX%a)l5+XfG-h_5%i$DscGx#s%*JiqL%@EX*F6RHLiM1WJ7`?;xS zHzrMy=}=|;~UeVH_MK7|1jg^o)pHh;dB-dEkgoabKQ$88(Ay3aLy z^5t%hAKb$ocihdx6Q&WAe)jMD5BCkanV!9`=GNikIdCH1nKmUa(0@KT7a1*xz{@+Y zzR8M}YZ>61M=g@) zc{)#jA{n-%Mmgaj{w%UUnG_a!$uB5I0;N(?iTAiD$j_#r*l))POHIM!(viUeva)mV znHrifh)*mM`@-^q`MkCNtcQL%I)zM?|%i%bGaQMyzziE%E9i;Bq0F92bX zkdj71jBQvgB`9Sflx?48Xn+~OA1o#(&xfTHiAhPsC&Z(IK60~8;xh%p{bXO5*btlbc(JL?@wC3W>1>xp}z=J(g05 zZiPgz6L0QOzT5pH`+hn?MuJYc zvKb&PaPrmwo+`FeEroHrawKKf6bgvT6(I}zx;DJL4~6(3mJO-?>Agv zqNJDU6CPvo^aYfzRt*)*!IA=@34-1N_8&OFsjOU7&3Kd$h`2Zc0WX-v2oyoXjaN#1 zmPM3BpHqMUB`GeWK(-hO8#?|i(T z=9OJ^x~L`DDuYHB*5<<%ZxaY6aC6T_*p6xzx+>>0olioaN@{8PI_IeUHd3nQX1D?UKgop1Omlm`%MDU zqA2SpHf;EmUbhxfJvqqdAAe5i3xnhoo@7w}>-k}S9@X1);K1hXpu72BV3s1P`2f-^ zV(OF6(SOKLnzn933?{CO1g1=&olq;6lgamFLFo*;#z{K&7kW{t;`T1ThY|xAc zM%+i?4_|Zh?L#QnuoZ#ad`gw8$>aYTkI-YtJh+d!PcNoo*;MYmxf7GejAZ)>owRb* z8F+m+YL|=Qk#SQ%bKx@~wPG#Cj~Z;pSrY=3752B&fP(xJ%$+)k{U>}Bm>_kH$QHO^{j-Y%JESx=;^`Cx2N_sNe_8cW9AqAm=e7^Pr=FOW&Lbhb2YEO^b#Mg+el18JO@sij2ksQ51$QI*ITY7&jh0V6~D7UG<0|m&>`iXbm`Lbb}yKxZ>IR`>& zpv4fMUYQ=(T+i_n$2n2(Z}#rljU-?Pe~!su`Kop7`Qiiax$Q1Ceene+wij~jgy4Z$ z6M68au5@bG5zF!+4Cz>(S-8zCR)6>*CkuRBb6t1hJwfK}{hrS^e#0$&dJyAM2w{Y6 z*mO;D{q5KB@s}I9@Af;W-sn;W-+dR!E{!QOW{~aED4!OGW+>9iRpOefyVK*!PJka% zCJ>WYiI?7amkO!zxJ@s$8aAdwuAifsr^q?+KA(T}6+JGiO8{uru@A4l_8b|SpRMbc zAvA?Blzr(GE`${5noewd3b9Fo&RsgwqjxVVq{U#ft(q;({|ih46(EJZ>k9;hMFkwo zHz`-CI_{8trij54=b>!8hd@>~Znt3j)-TBQ>r9+HiR4%}Qi0H1Af!%s5CRqSvuM^+#FVMYq$!V*q)V*g6AXLk3EKC#gWGTEMlk0mdSBh2<{d7fnl4F7 zDZ|7`Q%TZt7(8SwyZ2{OR@13ks~(R}8A*x;vE~s@oj5_?n@4ipRaX#i6*6)3Fk;ec zGHLQyT>fJ2x#Mm={dg5^F1-X9^ZNT6Xi_$w zfT=U-sp-VVCz0T>A+m&UHgzSDrk~sbAH8oH!p&EAWcA9AcxdEEZn(A;)91ZJQiaAm zG5HZJ|8WN2`7obs+D5M?8Lawn4P$1^r*8F1EPnANRY4%sFU6=boVtvt!>ey7lhP#?^N+{QmJA z%=YojjJwD=v6l~4z0dfkpQA#Vbf(XGfoap{u=s`PtY7^u8EK_$M+qS)I+e}LNl()C z=Am43T^~FuKz8OHW$z5iorMD&lNY{&9!}dQE=)cw+tLY zw|39#mk30H5=aYW`7wiDa`W>DYHsqCflCwIdFP$fZ{5n)VmS7=x)P4V zj)4)Qk(QE-ufU7$jwdc58HJ=llO~wBK}sH*K9zCf9%I~nckKQLs_y`xhpDqGcq~ux@pB?a!o2tqg<_gC{ngWLG|=OC^w- z=cSBWqI3h@rQuRRgy~00Fx)Z3#<-BVMI70`m-d4O5tEomQi7Ydjp}f4-yWKGyaeS0 zl#|L1T#WGX!-1dpXyayf_w0kNy!e9>w=j`P!_s5%#K)89apP8$kV>Hx!mSffE|ez) zJtl^F)hZzJj*^p|$*uz@x%>9v#3#lhVq7$>SChRz9_K_x08dO3spZOJ#Kz$92wciX zZq{KAW}afg)OpN!dMa+|r$U7qXlAg)CZPlNGgq?Agg zZ_mrQdf+3Bo;r*4^i+;-{hV*N?%;-j!-y3{C@H8_|3VCRJeA5NI%-P$V9UwQA^T)5 z?K)k7D=wBe1qXAFp}XU#)2udet{`>mlqJa>E)Ab0ZH=|& zMsw+CmWioQaTmWQ^-DY5a9}W8AHUS*RtoVFsRY8 z9kK6jVCe04adr0|^zG3Kzu_h*VlZ@r1UD4q9bnQE^VzcHTcq@pb-a*3aS)4YzT$jNWuBr+>x*dJ?qW85vx9;Y*d`%T z*?guD2wgbNRtB}})+JWASh;K&>4j}Le5!~Glt4)r3Gp5ZP95a)Z}(HJP9x%6?~#`1 z;;JjJBH;B?vteV5P?UlY?w_>P-k+@egm+eNWYEyNS@FgjEM2mM2Z!ImyonR|;Y5JP zCXOQ~w}1ynJxJy1Ynk)h+w3}UjP#5|r1uzW-g}44x>cxNBAPXC&ATbD z02&E#@uVijvu)?stoi73>Q+c0E;XG}2?p=HynwjwttjyNNl`(9fjqWu+sZA2ZY8mF zX=XqFG2d?AMXN^D!Y)_#=iGM1e-sHqF=7ogcOoP28_d$zm(!?4eQH*#MsdL@=FWVE z3bkufrS=8v{x%!UlS1qE7qej2B!)fw1o6o!bh)e*iMkfK)c>iiI8WyZjL_-zr(p*x zaK*%un3TZ2J>Q|z7JH1q&BFgCosDNp=s468SO!lAxb5*MFDxysd; z^4xRO%<$L~LDPuWEZc)n5S9eS#>F8F!I7W#Q>9WGU=S0VM9}Y}AiJ1yW!>Zz6jA68 zkerwh4h`Y#l1NND#IO-d&~GzKn(hLj;nHkXnyw%&&P9yJ;Mn1VRIiYX&mZ7qZULU8 z6#U*igbdhzi^9P6jC4XnYc3MYROacKQ`!05E}owLJi5rHRr@w}Xa*%g`q=vQXT0*} zD&BniZOW&5=ylCd6gryAji!Q_riqAi6PKJ!TyiPq&YMTgj97F{AvA+{PmE)Uq=#h3 z=t;?3(dBYJ+wd{hb?Zn{Tnqpk)@-EEXHlbaS;YQBl&e&o@iU+1o#&rn!pMhtYT*l% zP4(cxKIH#YbKLXvn@9>5MqC-jKQR$)%wtS_bR>lZUec;vNP1cVmX&X-^<)sVIHa<0 zQ-mfoFg%z-L&L}88hlewD{>xm`=M(%Qo{PHlL36z8HD#j7 zAW~`s5$H(TUv>#or;K31vb9Wm@;{vP!UdWKp(WG#imtr-(MG1sT*{K!kCS(3AB&bP z;`w>ANiJQ1*^3r&LB$M55*dkea(MqwJpAxf+H~s8*oouGh{@-Q^gAFej5I zCr#nIT|W}^#L(f2Yq_|6%P2eAP~HE022eOmzCs6~(d+uY6nG1Ha^g6Oy#W+1YF*fr z@sHh2a!Nc>)0}&CEDc+}Dv2hvKTQ&7 zNejahN6%}oW8l!SqKlG%9VYU4-pB<}zIL?sp@%-1#8o5+#L&K30CUhh_KP zLx$UfFY^H3Zr@GS>Qy-M!&Y|eIYq-Jt(Y@yDvypC#buZE;`s3_`rOnDB_tX_bm_=% zv`~N$Ct`tv_yHEW3KF{0N!++%(;0BhWsDqh4;hIjM~)n1)AoG~9(f_jRpO~!p)`-* zH=LUXT*o(Cc2g*lD3wu%-d#E{b>v_Q9~@77N_mo!Jap^ahVU*SaBlQ53>_q!#zy(3xBBxr@aw zE~j#Xi)mT6Hal0YK-V3_3dd&0G9f9W97p$WXZhmglq;Rie%iB{ZQFN{nqGr| z((x+~WlE=0bYwGcyt0%smCKTtkc2lsi%lCoqCvw31WU09R$!3(nOHJ&@qp3$Ji;jgv}@h zg8`)J+$4pCR2rI*!r+IV;EsnTBZP)j5LDpOg4{V`40nzgPf#ctSM0%wynI{g7|5pc zl|ATt$4D~w|3KTzdXrYBESBz}&1F6LW_wS(ni~U)N2kr=(di3tVpJiOmtdd}pVA4% z0R=|b%D>Z+t!pF{zg+8;h@!j@-hlZenUa$_4pJ9-18sEp+bA0G{T{YPU6E2Yphjhc1p z(Yj@8wr$Uvl}Sezf~qy^(5z`wwr$;tL}$dP(KN1K z8@J&iH7%WDQ_`w=bK*QYCOR#fH=_MTEjV=K1Uq+pM_jCj=FJ-;l!a~>w7a+ihOURz zr6Coi{Z~<3Y*DppHL8>^jWjKMQqiu{Ql&CK9XLqKmMyucT|0!7eEaQYii?YB z*}M^n@g4$}PMeEblbRH3OT08e>x(WTExjyTw`}2LRu)Z~x8SNPI^)tLTek0{)kT-` z!2S1=lHeieD<(A~gSz$VA^@*n(X?q3DwRp6Ld8mK`r-?$K#=B58WFIdUc)AoO-(}+ zk`}F6Q#zv@o4?&mm8#VlHEJZ~Gg2vAwj5?qQYtltisj2X>TnxjK_SV_&EkU(H?Vcb z54332nm)aHk&=`^%_^1oX7e@*d;u=Iyek*CZOhK>+t{{!CoNjGq|+tssamBX)v8os z%a(2UgBC4XwWfFXZYXK;?Y14{n)<0efwdiW?Q=^0cgR~F-}OU;g(_H))j z5&N=`0_p#E&4xm4gy!>a%O_NWbHC-JP);4gF46q#Tfa96A+RiqtgI}OlatSy=ER8; zRH;%0fa2m}cJACsi{{PIG=UHXI8q-QgTwBBO^Zbc-5x2;KnO5|v~AloHwYaeK$DQ4 zeS+I=yp|CUJ;KacGnqAW22VXTi#)GMhf6L-SD}5xi54duCQS%5B?+NV2q8Ik=qE1e zcm@BOI-NxeU!>Xv7jpM~_fV@!IW#l}mB+H>)|#8}h9LsvWF6%CYx**3^cZH$n!}74 z&oE=wLj0D&B^_GZ?2Th;p&@W1kZ2gfsev$@a6iIMr$EyLXtowc6T&ffu=`6X+k#gQ z!)h3I|DZ4g2;oKvBNDGxh0vgM(6sQ>F|Yvwv@mMSU&8Enrl7MtScLL?p$TJy7z9RgV2pG!#+Lvd}ewg@sF;9ym3+ zKThxSvmM=Mn6C3{#_HTDqVqdj`DYueGwW}UmOv`gmRdUiZ3;W6EGP`&;6E!ITTkiW zr=FdWD%r;+%RM_obgupiQPle(^8f)(*k9-EkQ(r`K0YIxfb+$5_KJt|j^I9@UWZ?# za0NmEg6(>p73S(^@~{zmq9OXkXoS@2R1OvtVbYLIFJ`<#i^wOotC|edok7x$gd-qdV6a?W$ zDIFm+GRl;pLisXho1te?)EGziNu)nyR6-H;`M*Iw{qz&dmM!Czzz=o_@~AS{JC;Yd!{1Nw(t*O)8*ZjTI>pFzD8ArU>(PCKmB;$wMfon{7kcs0V>|Klm79Vsj-{Ecsx9On=zW#bB$En69cJM=3kffSHm zSZL4RpXHUJ=d(rm@|92_#0(|y`HK1F`Cv0=6)IFkDO>ucoXd%63W^JhenlR?hE&ww z|62?oKpikx<)j9JIfx|2N zmaLQ@s2Lc_LI~Xn`vHXHhDt*T%lWrq+bRkL(O!Q@M;&mkLhW3Y6bOx^NNazikS+S#&s|EQ1Z2+CkXX)TOh4fb3tmYo6=uNx8?rTbq4}$#8XuB> zhIm5ZI2(o9Y_9{&QI&gNQ{|0VqvNnlo17O%egDsi!~C>d!-n5A*ltI}au1)(dV z<#dBV2n|SuE|St_dKH>;N3r45q_E*Eb*KB3IM+IkY>1)#!alUMaJZMqA+8+gNlK&# zg|6FU6FT_qEOiHdGb9DH!q?!l)+XF1T2!Ba6w%Cn=zGL-`j4RBbapBDEjT0R%3BCQ zW@aWC85t$B{|!u3zLL)4tEyelSxNj2haqwU!Uw!o> zy?b{-*U!Sqho3H)u0*YC5B z9XfP~H{N)I0Rsm7F8Te{6k-Ziu3Y(7SLHnY$y6d(^q+gsM^qaT2%hL8H}u^?1yAwv z(v`I6+>`1R%7pMDqS8ikivEq$(w*@}IGL?pQRK7f^G|4*UX#`h!6QV896&m^^vK3$ z3j_oLqvVDdRl10N9}__lyZ3z0s`o#mZ{IE`$HVT7{s{-7HLwo~8|PCwcoQnD%9B4+ zX32gyn=NJJTUaKA0@kkn2nAf;xeH#ImDq-7yA4XH)<$l2O$_gU1NKoM`f zxr*wI+tH|I6`Nr?XWOIm^b-tb^TzA%(WlRKXY`hBG`WgFgRdn9g%*~1pKA|@8W-#}5b&O2+1u;6sB>?smkx!{ zv1d6rM*jE_s(_UrtfoTMRy3$n0hb8HNQ{Qd5|Q;I&Ne5014I9dE%+5_o%ngWuA{k5 zUz|Tzlc*Kod<|>IBTt-^=ZY2i%cAG-%u~+TM~(Bj_P-DrXZ!*oa~GoQZ9}`ke|IYU z_G{Fc@BjB>AD!3lL7Ju^rNl6dh!p&H%KNV(r4)u?{Bpwc^nZ$+karG)pwu646QHmU zMHK}6fW!&a9RAJTj{Kl}fQ||l@%HOWIhB(|09*Zu41n^3w2*)ulqCq#3(AU;H3UJK zC~24DS70g2&fD^Xl9&jB0K#UkWaQ)rB6nn^EEEAC5H3UF{_6(5V9D}D#CUTvHQo2&ISoq z5lY$5?a0l3=b4?Cr2?Re0g2`0z4raL`SRauky7FVOe9D@Sa!@l3&$}-nf7=9UhMD| z$dJoHsFR98d4XU!KCRtTc0B^he%HbT6;Y#Eq2p7TnAjfN3J}tdP<}KSQojL0Qe1eF zw_bmVyuzYzJA#h%6{l{&&{R|*rB`TTT1clKG|fT^K>#}qmKQL?{c9H*K$%5I8N_m0 zVoHfJi&*{68~k+Wu&uzC_6VX(Ea}V-r9c*g=>_S`f1x1>I#Q&wNrDtg7P0odH`%s* zJAP%iPYUe5RY7~s0VXC;Y>%^&D5u>L&^<8>zVAM|_vqxz$$-5U!li^hmJ{bOG>G9@ zfD{_O;ym7cZ5g@QMfMsLU<%NbJ!&RkDFZ2etpDIW_8mNG_qDQ6n9l0QVPd3X)?mkV zbY`hDRsp2bqI2#}DyrVmT#PD_1Sx(dk0{c09ifScx-=>;W%^Ol4BG=M%R)TE(?+gR zc3VSxlT=nXl^Is?+k0Yk1455NW>a<=XZ1>nloHFb?0Tq3?}c*wtF=An>8~LzBms>6 z{GlWO>Bm=eipR%K;KGItXxh9bZ@#;MysQ&+Xx4yd7cC~>D`v{1NsN1ZI+hvW&`&?o z^NMS!U!y7O*RSW);k^tRa2t*4*XN4MujHGZ2e2$3uPt6ky#_5QSH2#TCQjn@#q(*@ zpea>r)TCjPM!fpQ`yiY@Q4J~lxVDw6S#V2@b z=F`+`+?x9Jo3ZBOHGKW`m$YkhG1aP6q)F2Y8990c?K)h{1vP7N|L{@d`GP26vg7NG zT-K!C%bnHEU9(N+kx|aw|tp6)=Csll19vCAr=JN;7$M%vk0>|0Y?P z$9d@f`>9*M9$hZ$%9r16BPcZ%%zm1Bb?Z^NWBWDTuG|1Y;i> zLA7eNsa3l^>(_nAiQ`8YI_yDe*S>%&y7gr9&RrnAEPZhyjq5d~YSpS-+^#L-$B(0V ztCrNdpeECwnu*VpC>7wf#fxa#ycrGa*JI|)`FM*ZLIw!;oqOGC+Eab zhTr!fwJ)f}WtVm3KbvfIpw(#}9Mp-~qC7a*;w&n3u(o z1BW<#B$EPf&@t@*;b6~3q<6O5t)$F7>W~k85vR%fR774UWD#rEtYqxOY51%Nb7x;P z9ma(y$z+Lsa`I58%M_#Lf((G=BM`Kia-k`tmCwre-sSao*Vq@5NHv{2PnS$abLNrj zZ^<^>Y}B5un^?T~c@Actz!VXlI(l|S%Zim%#LCweGyRDt$;`^b5(4FTFa?W`vwG!9 z=05u}0aGHw40;K!^jA@sX^w8Kvf=tH6$$bb(izz{

3a2&`(S5*bVKnXo;ePC;T zf}jZJsR_+y^i?rR*etJ!bI}xGaSBRkPKgR-1?>=#N})6zB{U~IjpFptIZyvQGNKKP z|BRb}1cc0I>D(vydQUD(mcLHs{@pw_?HL-^pUi?67xM6!8Thh~vVP-#n6=;q^w=WO zD^zC0!uhnUU4v9Bi=np;pk{}w8TrU4K3MS<)1I2o3r`Pc&+a{3+UrK{8gwHWt^!_J z_!JfDw&az`53_6Y=R7)X9<7@;p>DNgo|^L<9wVQZmc7lASKguN*c-6UVb5nv1QhF6 zyul}%w(|6IFHk8lhVtcN`25o?RIS;ZSKoM*)gQjYwCS^$yLc&y%E!R|1Ni95?sROF z!H~NK(QD8sx_7L{dn;D+^>+bu71}HnVXsi(XZx3Hnfu&JJTi4A^(v;36ffAcaRYCx z*~Bx8m!SJ{89QnuT1r_uH?7Y1J9aU9*-9#>3LYCZmL;#Pp#S9^cy;+w_8&b?sY)L9 z{kVrN*A8Uf-1)fTl3BUx13vrkb*4W(m-&lkb71cw2HZ7_&OLikCNYj#+rDAo?RPR{ z#Dm1dyV&;SMy5XTBok*YASEuqz4zQpjfSmhRWX5_yaHZ$^9?c*5=heA+B*eud zk!YG9zb}h#cI;=|v=?dLxFQuwn@oFh8t&98e6(&2@4o*&Gp9dE%jYJr|L|ctU2!!- z@4kU03!Y`!;+I+U=IfYQdl^1zJZ&!TLc+;CELr+8k3BVua`9dspR$lj)oRhHSv<-U z&$9R5rCwQ`w8Ubj{c9R}LIqZ@Uc(0;uIA~d=F;TFxwthADHVFiD_&WAv2G>vm%PQJ zPtW0kGKrK*cC-4!_xa%Soh)4XDl-2RBOZ7Nk(9#4wKCYTa}UpcxRDC+K^}i}B5$u+ z$KCx}5TBaL6ALEL<)S8}#}u&Qr58x9P?v?vpCCmPviY->%zb`26J|e4MhuL4coHtH zfEx$)L>YPsX-kA`>4?V@&#*D$7}&2D>9NIpx_UVePkxq}Gv`pYl$&XfPh~~9Qe1b_ zO&rbg^7O2k)T~~X7v|67-Ul9K$+J&j1oN?k#?ixv7<&64I`kXDgsHO-0WWc}F;QjO zmm;$`m!w(zIG4sfjUoTn3L%d4fq=fLGsM&r7eq zPWvXeVi_JDpFNM>9UGDwo6YARufr0tnCN)W&`b+W74q@t|3-K!u;J6$SkfdTEd{ey z9s2Y!F!Tt^9_k$t5{(HF_3zNbl3&H?&wmv~?}-wHpUi#V^3X%0nX;%p@xg<1yXFpV z8ul2Y2X|!tlhc{?%nRh2(EFyrJao?>#@ux)>of?G?Pb;YWr(I0Bb$TjPc1lkK7*K{+;h zj-<0>xSxSb#8j{lz&v|MoXjY0{1gWizmm^F&yFdb&zmSYDo= zJ%a-U9xlJ3KWS;nc8o<4q#*YwPd+(|1BFTS8+ap$#{Vx)ZzNE3Xuu>O{e`^0@_k~` zt8z()_81{NU}cAiI(F~?D?eCGcA=LJmt9Wt#tqT2@aCW7t+zko(D59awrWj>4()I& z6Dv@}yQ|*k`|tKqzfp58>DZAtkAV#O_+DBd_wHAbKrGl;~R2#vD{^`FsoAyZ5ANi$j8@*FsHgq>OeIoXBuxVAUdQxr{_9B1pUuN}!K z5b_j8f{^V0b{kEbwBh28?MRk>bdkl<#b3~*V^5m5Y>sZ`az&^1y!+l7E@^ZpxHQUE zsY=}{v0UA)Gany5N!hAhsZymnJ9i%-!&eFw^inn>fw$j!i{p8Dyz<7I$l^S#_(}wd zZCjy=RjX6EN;wixNC9yPNu;NzwcJ1Z%TW>{LMI6u0qs@;8Xj-;D@remk zs#2M%sj0Xv#eh2pI^*py(3*~>#Zs+CeX3PYgn~V+dTSX!7Nqd*@)s#AD8ikPh&Sj* z>26XoDp09<4LW!1$ZN}9p<1mPr0YqPPfy@PPBtr7e9VOn+i*#{cEpJ+F70qJAHB1J zPA&Q)j5v~0N>e&bq7`KE&Kt|wmzT_{*OyUPRE&sEA>cRh#2Dxyt%(Mh0d{@6g$|eZ z;Gzy~Nx_Ff7XSIr7qstw0}Y!rBhJdE`{iv|v*r_8*X)O`8&s-Pk$ROpbiTALKO8=Z z1Wc(&NQ$Lm=|qH8gp___OQlk|YDLlw9~+iG%SD%TqDA}Gq^cmp2J~goYcFu+ja{+O zog2S>$c4SM9q(GpRKzF7Q?7I}9@EFhHEU?su_x^>ZBHV8Zn?T6Z-2Ro?l<;Fk4dCb zrK;4bUzO`_>_gW9Q#h653x|XFVc!8P;b!o_{v^i55gln#prbhloF_hs7HwMc#M2XT z=^A(3dJFiy1kp%MODChW2RB}d3$j@-e*tUOzE8H-MUA>GK-V!`9uiBXl3F^67*%M) zV@cuswcQbvD~=0lR%QN{X-uCYxbuPGSZ+5p>NTZmohArPkBT0n9B*S=g()oyG!0D% zJAy#y0G83}KbwjEZ9844Kp!X@uR4g1sp$yaL%9m647~Lg+Fsn6Bm2K+=_{{Or$t9* z&zVkAVgj!(Th70~-OY-1pO8_dDoJUnVHKPvKu87BXR9%_B!sY4)&T`>ArZ<1dSZ-k^^AzNSN2Lhlahgm;e6{AEf z7CMG3#?oT(`vR6osq+a^1_PMR7fzHG8=hVG zA|I^(luthUg5}F!piFu)0?XbzLN+Maw@?d#&@^Ini54he{OE@{o?FE8FD>K#2Oh-G zU7$=966M&lX{W_a6ozdl6bSg8JD>&lu#^ld?{oy3Qdk0%uyE-X(hA^l8R$SD5VQ{` z&A?JJgfky0L)cCbnjw&ubR-xWC_9)&FzB(*`HlZ{{S?|-kQRJ?7kC>Py`4d z5qL0MF50%ai1$~2$VclxW$X6uxo^m=cnk;zt*|;tX%Zz&tdMu4gC#75j^%`uK-Wnw zmCS_6Q}}4@dOqFs1s|_pN37d}P#QtgkxLl10k*B=kmy2TSrSi741rK0Vc-u2k-A}@ z^Ol7&P1{q`&`3@z&A*tP1`w)2j(@cDdbA@qc>H>JcdbX&zFE!-|01F)n$rb@Tt!D)6g@VH#~e12O1Boy92 z0Jq1D$IuYMLaNZ%i_^mN2;4Cq1mKr|&~O=Uf`K4X*=nGGDbZcF&$vLMyWA*Kg0v+P zn!^m(W1}#Ge#cfQqQZ(UPe-8XvD`U)G%HuW$@iPT;<`S)@cO+-T}K5?JKT&2vh;-o ze1Gr+&%W?7GNgVLi`;uHIF(^Im)Hwcb}O+O%oM7qdU2R@GGcUEhxt zYd53CuuuexwwVPq=0IN%C0Le;%#UHZp?EQq#r8;*E zxtjw8MMNUUnf31Lv}@Cz?5r%ZtJY@3=m&82nDoLL`GsX{qgpVEPkzg$XGV!ZIgL|Qg(L~8j=>gKfLx8Hwf&a4k< z)20$w-PW8VQvqEYtk-9wKqJ*ieHn-O>2 zL+;T+qQysfYx?UnX_`Z3W(9ioyn@whHxU)vSkkp|;gRBeo|yO`wQAI(O^det@Z(Q^ zeFXXsE`7@He-@r^eTC&etfX>QCf&PqLOY>Si>(+Xbl;wxY~5SHy%Qhi?%_i?wMi|e zz4;ECwrpqNw?FXAbI)_v$XmF5U?1Lk?_-YVAK|&Do}~Za!Q6Q3EsPm6g1NJ2A>J{* zoHLg}!zVCs;H``rGKd+^J<6V)zwypzUo-svr?~z0J9zey(af3k7Ta?VFzLxx>Dv7g z?i?|UNe_T?b=D$ zitzSpuXEU|!uzkk#MYH_`EvgE5Kbp8DVZO?U(L_!e#281Ic;)yYsLrc*}ae41A8gR z-;Zq@p9l+Ixl$IIkZ(XySXvRrLn)6)aS4RdQQ;8bBty!sl#OMCLdIgGlIeIxTehs6!;DYArrU+rk)E7Juk*SvckUc^?b^qoydxAJKa4`~ zltw8x&d=GRQ61L&w1S`3tl@`sztZOP_H6xqBVW$@hQmjXvSZ6;k|YMMi=!Mv>x8gn z^Do?g@4Xxf-W>+f@RkISf%mQI*rwr<@-OeY2jKwtx@lAX=!AC|Fx{YEx#-9h&Y zE@H|2&-rTBY!-d@9j|@xHSIfeBrJs#AI)RYqJ^woyMZ^Sf54e%b|kZW*yLAPG-+I) zl#uY)V^8w)x(zH_wv1vQ2saQBk60wenxB6qDI=5KmtV%-?Z0v4coF3?Qu*}lH~4Ag z8V>B)O~mzZ(kfzwlLVY0cq1+nE2&H>}^hg@Z?q z6HVp001BWNkletA|##g~5 z=szxvnl-Jlw)SN*_|qC&p?b}2O*JOQR-D5J%yPP`_CYQ{Q`qn{Vr9 z<}PK?rtPV`@Z2LLg%m^YxSQPL`K(*LhNJlrCOq&64@|s|!o$0HXv_o}HfzC)Q=X$J ze?Nbj@G#qd-_GRwAEaF68a(yvbKH67a4J=-NGRk`p<*WYOc=wUt9tSF8?W>8#-04S zdO7!we}E>ZpTlF1J;a_Z8yI@aZR|RfkEbkLJVFXqFaCz7o|#I|t8U_nWvuzIta}QIeZf#tWs8+icNAk8I(WC4= zaFFZd8vX*`MB{V&w3mT8sO|wznA$~t_fQ74eQLn)%IF=^0VhG29 zgZZw{Wpq;h-Ng!&zCR@}#6MY4PCEUEk7LmFmviTBgXq=c0zUlUb9Vl=m&uPk!@!&S z(x^ov#*7`qtdBk>;-+%*ErWRTsr%`D`4z0$x{sIMm_c@$%T*Wmg8Mxa{()SUBrF zj^^i+crfOhvN-RGYq+t`MU1+oAD3KsIdi{Vg-S^wIW=ZdIVm`yR8qBtZKdK`X{1r9-+YIIn^)4k%XvIJ=_wjFtPz}S`Iad2u9zF5b%*o0Z|t2sKXE+W&%c1@U;T*o z9lLT{zdj7T=|+YOAH#s*t^-2;mV7-`0_q1T(le!g_WF+Wtk%swC2j|ZlGLpGM9Jn!E3Khr+J(9 zy!OVceDKQioZr0%WAA%}{DLC9q!g0V(+F#ikhmPlJ;c)Qmg7bQPe5?MN+mh$kfKTu z6-GJLxOLdwG_97zHJ9|_%05@IWcex}1IM-qr9_S5?t}=19UReUD;@2mlMLjvYtN{= zhVjtIpdjtjb;PFh9{Mhw20k6wM8%dY6lqE)*XI(!^0>QtcbCB3-vlFM2A z{g2p+c(|d1GRm11rbE|@x$o}Vd1m}bdYyj((`L-0YmW=)cU3oTy1p-W{bdrPCqB=G z=XSzYnowFQVaEc(C?}cZkf7`;T-CQ9OJ~1N*BUK${hb$$((xTdE7r{ zC=>6#gPU&~N$>0WGGO2>q}iF=b9+DLe(^DR$Bvn!L;px!Sq{p{xQBB(bY$@GQDkOUL)jI$y3b{7TRo4S=UvFVA1|bO ztrpxp_&V+#Ih^iYdvc@%s+6z5s_z$Y$z>OFO2_jlpH+o(Iy7egzHO{pwG!72z-P?y z@5Z%j*}Qct8pV+#NBL^bH{|CZLu=Ua`*zl?S&I&$^5YZGKNticF^=Z#X3hGY)NR^< zemCFDg+0z7#r8nEShm^tn5bqKrIM-Duq78>cpmke)W(q*q2zLO?{NX=pK}(K)6>ln zxL9U`=pzoST=+FZZy&*+A$PN8-9~cr@({}+=2}RoBAt3(%q5qdPkPv9>y|C7T)CEl zh~m<#ucJqgv&l*~8zgKCPh315A$oidD}G!-UU7tn@4uhnca0^clG(F+ACZ_FhpsUS zONekv7X7cil&$MlvTf@w7Jk2hZe6<(PO=z3=_%fP`8l$Zj5#}0KAWDsy3($76JvR| zLR76?hpVr=kdCeDb8OF64jwMR^TMPir_=4+o?LrrHxBIhm2JEBG4q3ux$(xESiflp zhYlSiqBW({eC-{r0c zp5n%SH*!&z*6jIhJzI7j#*-uhgwCbke}|o1i5qXdgBJp&@lrtDM z{(D{RiMUbmw0WM^u83D8;zs;_p~aP`L?Zdp`=U$amvujjt4$r3Xiq#H@!Q(uMaN1^ zTkDvJj*06<{BdH&n(Jxt#1qj)B5qV-!FxTwPkSW^J)lIyJsz*S5)tu4i`Eg*5=-c} zK_4>(ceR*)EJbD{`fVN+5s`>^;+58WP`^4NuGaoIGW8e<`hgquGw4q{T1%v)Sk|ps zE&2I}B|ks^uYMLSS`<&8mzO6~rc4p>3gp;Hdk$}tF?Zc0>6Vgl4^5Prvp<*j zXMHYnR&SL8FBq3vf@wi}5!tu?YiUuZqV&AvD#@zaO5XYWTPYS#Hm+YSKdf3ShjRDG zm0eDghNqq-dm?7eJa%xkoZ0SFIj`?9i4^aYVK-bU>B$vj#g2_K@S5JzD7%3y`DK?B zOR+5a@^z_~ktCO1akYH#>1>(#*_ZP6oMn=K?2yEAH_AKHUy`%WK3ghe)s@e`TOs3z zTrKtMG?aO(f01oJ&yh+MOuf&3_gTp(S3#zKy+V#2-zV2!aiLVLT3zPDPjc2N zEo9riL*lxJKmF$t5`}LI>pDh+w z$7JQAdD60Gw*0d8J2~h4i)7|EDUQD3_j$<6BHEpMJ~pvdNd@D{P--zf!J!YDk#N{mmXU|3K@P?m)w8c%zM<5ejv&%?GIP_{8v zC=byt4h|ZH)()0!-fw9!ZDiv|8wTWGRw=EmXt2cC+e8Q{-~Ut@M|RN`SSGU3^Z^GE zP2i5HF}{(Gtx(Dw?S~Y&p2D${2%;Np6?7+MI8jC6D3dj%EU=S(Z$}dy`Q7}l7(H$R zQP)`5G$HIznAhHZlNJqXgB1etZ~|M2O7;B&1xrkuh$v#NhZ8bK!CGs=wh!U0Ou1|o z1ji)d;GspZm2D^kRT!m|aUS=B^gIm~A!0@O3?Fg}Kd#$`rwq@A!sFbFd-LGE<4|G% zAj06kAlaO3nVg{TaK*y2lkij$Camxg@2_G?sOChk0AD|_kX;bn2MU{nPnTS^{+5|FK25ZiY zi4fvhDBG~TSU@!95(<^JyYkz>w0k)2&!WXLffgdB@7N)8UHhy)zCZDQ%;xh)Q&ouc z%xtdceI8>Un!;5VUqZFC5(*+3TVg=6-{(C)<546OpXbn8Y|COq-LI6iu@JX?3{C99PJv8hox zlOub6W9VHEaLom0lkv)XyfghR7R|50@q%Macb`I<;#uYv~*=KL1j>oZgZNBd_#fSQJ7M8Vi&O zjf`0g%AG;EqfPSbiU{B{9*_U%Wa5xQM|6_Z!vD*1yp(F z6^0M$Pve>uSo7;1Dm7?@ML=1Yc-r&-E6R)+|5=_FW8A1Qbic4CZBJ`MMyQb2UYkne z`t@1-<0c-TK8Z%v!qll(g?lI5$K^fGX3`TcGT@#kDW6@D-q&2kTdz)|hMmt#&%aEE zE`71W<>}n9J+D9aC{`Y1p&{7oOdY=kC9gaO_TAed#q?wCPIy?COlT z`3nAW--9%3-JBo3nL~{_^{HGwrIe~NSddQ2zoo<>V*WIs$N=eB0)@S^b$YT z3V2*?6?eBP&8v1fT8j%7#Olg@bDYU4jEmeIVGijN5s zYGTK0-BPBnmG%P_A2OC7)r&HHAm|aw3ZP4j`jixM{76~}h7>`FaN^vcEPvNgrq7l3 zf3b`YsQ8N6e|EML9F&v6?W0GLUb!kCeKwE0LwQ`*yALfI*ToJUr+Ld9s#HuNIkf^! zTQsF^)eICC%1NhU)ofZduSbeQg?=R{)fQ#xt~wfY>&nl=5`wb`H}%_?mNj zb)kCI3=}1_Iinq!4Kr3xw3Y|xfhUVW8^CQjzS;o}S*(T7o^?j|!;xPS6w zio%nqTDd%x>*es~j2S%s#1wYy+(+B?9XR{k9wb=-%uLx?;{QvmB&yYEM5szdk}z|P zcpgewRLCgLedEV*@5D*WoA)iZjGn-$jk2+c^7IQYF#g_0dGeVTxpDXe23>bK4lxGb zHJbc~Co*>21Dx0E3i{q~As(q*am}^l=H_w#y^}b#!#RwYcpkLG*!Apu!pq&Pq)gRN;C3n$P8GP%lreG>yXYj4Qm_RH`qKLAHDVvZ)@l+U3lsS!%2w6R`16qH%GE(k^ps^zBogLVQJSK{JU)EuL-riV!*j$?&jGb+RcFI5YgxH!BU|?s z@YOeSsavBWVKlaQc)`gEF_Z>vg%NE&d&N$ znIXI5iR3?=XAIC_dtX=yH+4UQfSuO+H zpX5}Tg(PtSNu7@#g9`OKI;jkXu|r*YkEEG_=7J;+U>0%+b6@b?B$ zy-NPNE=#S3_zT)m)~@@J_ugN`OH&{9>myh=`QzdFH#Ay>%eUVy;QQ}?rd!uD|LWaF z*;A09zMuddr650_wZG@m=G4}tI7T5hc`(YKCBgrRv`>I5Y^C`o`z_xD+7|Cm2Icv9KEQ>sXo zj_KgeL@Qt7bN=gdoH6bu`9UTgo|NENA6a$TH|vA}!c#OEg)qsV$Hgd>`xMThxi!%`Nl z%f(L4WWeA%xOKplIF`cG7Pf_<1H>`;1Q0=~2(iLE-h6oq%YOcqnBOc)LFdjLSo8CG zGHNvAg&7}FuX;rs!9W}-18!|F2t&9!hUL52V1=**LYPer$^&t6RLJyhWvB!#WfRdB zj-6znll-Z}5f^L+NFt^^EOE^Vhw=|?#b82uI5;YBJy3|R`~?b~iN&=+D=bS9!bNKZ zmP5>S35617GYK{?|9xwp78|83EKg(E7M_dW4!*&_H-6X_SmNS|!nPcgGTiXECP>7f zDVXvpWf^OtZQM6BF3JiS>%TTGKDO;+WlG3*)rtAr6cf0jtg!D^rBM>YQl;C}V7B>Z zJAj>(e_i>L8AE*Bc~J(}3lK5LbY>m%{N0@mxMsL&fx>Ovd(Q|)On#X&S~T^2ImEa6 zSaDrLdlBR3XS|mDZvrL7ELxszVPTowD)`ngGwF(U@pKH&?7;~8)uDZbQz@I^*crs% zqnaZxEiMW(I7NI5W?WZPD9b3W;s@qyEtGi1;^QP3;w;~SVxkSfKf^Ru9r4hZs4)r9 zW-(x}mWbIoD>E$$2C&$%ED&X&OHiN;Bdo=7R)0T-2WKqjy*H_qVfD`&Q=;lIIc;E=dyF_ZwwyPpAT28 zrbgw;Bx`f*7^n3T(`QZJboum+=NR?q8@%+x65G_m=%mmCZ{+;y^Jj zRpx@PPna+M@MG{6RrdQ6^K-(J%On4y?w?bTa?>juk>M7Jb1S>j$Gl*=9VJ&#uoGOIDb9B5-%1bQ^42pu$c($7O0- z8D&iQWvf)@6h8lc6R1#pArBUF<&RrSh09i~Qa}j{R{I(O)#{ahh z_Y235-iA=fiC2YLFaCShy2R&LzAJ9MFy!ghK>^pdrtNQeyN&QS-eRCGM2lA*=r7C@g zj-Yef9Kx~VjJ@-2HvP7ZdM(;A^v=7eTQ$iHDiv5>N|h0XBm1^6<)yb-{L^nVZ`FeP$J{}3IL54*AMweoFG$O(!_X0T)3Sag zlvr3|`8&g-d_MDIKKN__;j~PK47-DtIgJU+aaJr{&I_--&yk~1Ztvd{OGj9}bP-ov zdpC1$OSwrRybEapSdp$Oy&w=*?I8{EKfmToh%{paHB}znx|| zr*P$^UHoGeA%x3@pO?`0nj0x+y9^pSn$GQ85>_RwS-zZ?UVV+jg_>*n520uGj(CMf zdHMNAS+L|MD%WYw&=I3))vy9TEMCal(?4MEzWrQzNf%O5(^&AuEH2sn3vF6d<+cHr z5Q`jP@LF`MaAU*gm0Q>fmoE!}&bOS1BhM0E*;NA~detDn&7 zlumpy{cYM$9*b6XT(v+&iA0aHYuhf4?cK`6C!c5Vn0u*TtvrjC>n0@A001BWNkllT~tav%7QQ7WZRyDj2}0S`Cos|9mB@* z`ON9mudL{ESua9KsZ4xf2G76p0h7jD{MWlTlWRZNL0J0T*NhuKk%5CpQKLq6YSzeN z?aDPA*nfR5s&d#aA!0WH3YV(c^zxz(!d3O#+ zij{BeOIR*_tJ9nhX0Y+s&5V6;60vA8jum0S?9Z6~<_yN&b1!oiuH=q8NAu;(H}I4X z6fH46|L|iTdH50To%}Sb*KXjpp||tS2k((m@H@lr9Lm)`rbTI)seOY$iSOB=sBCrdiEQ zdUQF9?!9_4?St=l;GswP@U?L)S~#C*L>M>rFVwCQV%d+YXnSTS{xW(Lbt-w39N&)T zxzw*;k26l`!IY<`5-llW{DixC=jEyVv~DvK?j6qyFTKqDlV9NJNn^>blEtv0w{on= zWz4wysL`kuZE7ZyVhi_Ae1M8o>QkXy8vFO|CbfEfzctK(tmr7SXU!rtyE$XW+{xhU zd-L0E{mH49L8&imF$Dz&*|cFR>1h|RZOdjhY}-kLDh>H=(YJ)tGWm7wPdqyLA%>26 zh`rl?Naf31R>C`uVCU`a^{HEPuOpU%!n`4i<&_X*UNg)S&y_RLSnuHS?o z)~q8|Qbo;;FFCXkAYPV=crw)yA+&sSh%p<#QOWL2^j*h1{VE%UlIJk2g zwJX$MNB&WEZ2yr86_VM%Z!fO){=gjW8_z93Vl4e;0lja$i7Wf}B^?ikeAX#VX3gfb zY2T5Qq+}M(oy)lwT}ahXgc&bA&M&`ip^`q#?>lmN;H?QXsgaC!9cIi}PAG`p4J?6T z6sii9t8zT@3p=-Mq~}>3NJ)wE*{3tHGioz$;R=o&$YaaTKe7GbexgcYJ24`WgM2va z8!~I0%Bs~rBW@u_4j*9ij-9Ojau%m|I+yGE-9Y(p2s?Iw9h-h8oL+_Ijp|S_T*Rku ze@Nxp%^7juy=2-Rby9_iQ>W6q?=`q7)oI$gJsmopfn^EPUOWYfAIt-m##Ij0>bB(U zE*Vv^%o{=)HtiE+f5SRhl-bP5ICfc5L23C@qWLeFt(%-4vQtaTxRP^Xxx1 znD;+fK!YZY`EvH>SY8237B8VV2G}7sZ2XlYhYnCNDaxw#zmQY2Jy;fX8aJj!W)+e} zxc9NAF+ne$ADyfzEGS{lSBn@jWIQdK)u3~Smc04)CpV-HQ!&Ft+<8`M?4r1)X&3O8$7kK~qr5 zpG&DxA)O>Vl#UUL7L#A-(z<;&&g|S8O)(vNTu4sShRk_kD_M2xVL84NvZb+X@GKJ# zEILNf@ne+BstO?xE!4}-A{H&7$n|iQW6~;(B|gLm5a5BC08WL4!PZN%73EUG#3IGy z9z00Zx=rcOsT(QYQMz_Jhn$wRSiX2Zlb(8u!MFA!9NNvsb*n+ea4oQ`kPiW48E1Df z5tC>WWvVS3&v#PFD3?r3N+@tW3cV1go^~dUa+-4XIp=VFa(V3I$GCUgJ%qCx(5uVo ztXw>gXv{@y8&4_2v+Vax@o_3G6e2E46|rgK&n#KClCPIuLD+$UV@Ijcw3s^vUPOu& zEc-TKn_vq&l}=}N6Cp^ zPRdC+DJSKBL@e?7f-TGXQ_R{95Kb>oqgIXCxb_E{*2|(<^Bfv9YCy&G6jm--!s@NL z%y?@WAHDrD%YXV6k~2VD4(!@R-r)k$DpsLN^{V9V+D@~E^=Y2dl6np5kd&P4D^X$q zMwRUYI2(|JnClX@6v}g1yK*I`wK;_jojcR&)HZ}uQc!jhh@#-oQDT5jgrHCg@Mzq$ z5liRIC2#j0^78U2I3B@OVdGw_z;cYMcgPAEKRrKkvvKp5B!!b$Hh&)ZdHEbU9wFkG zAPOCK3^XEc3^y7jr&%MOefmj~(lc4Jc_*#fwxuY47fl=1qFJj`Xx!oyGLq9twPF+= z%SAgCXx_9T+c*74y?S-X$!SO9MlGnA9;Qc^Gg$xA3U+SU%ArF?DL5{qSE^3z$UgFR z?KRL)AF#c6G*pVN}`@~Px*-%R5M4e8YJOmbSb#!gByk$=IF znOHyyX=xQGIkcT42ljI?_Xw_5*j_Qm4;^4%ZXTa~wS=tf`ebFK(5y*Kii?lYta)=9 zHElsovqnhlIEDFnTy@nooYwJds?=$WrxoEO8_R*;H*IEL?qQ0fF28M9%dR~KaO1%T zg)CaMkUj&4vUt%#<}aAXlI6>&S4r{nPd^fK(jbygQBg55D-{dGU16= zY1;Y>vdX2?qIC}Wc?W1vqY^neEos!aAvLO$|EG<$lk(pwzCBM|#63c8?jDX6l>ku$ z?FU0?6eTDk1RGEj==fqS-Jdk3J9y!d`oqLIBK_}dw zSd7HGgH(UN2BhrM$~?>G$xXsX!N0G}b&cSat>4l+%KQ#cJBgb+5|hh`7veu!blG?RD^~7F z`BTLlM*hj>Y!ynP{~bfAUcqAUzN@M~`B+m{>q4PyRxE6`R7T5KFYz8EaDXOo2T znH4OQc2S`eZW%J1)r-F2hHLxr@RQGynqic{)7p1n<~#3FP#iJCR}u!T61rV+F_{@* zh7P!yf&B;Z)q-Wj>?9xpp5Tg0M7e~NLU|UJm4u^&DmCje>5<8N{??n^c=Z6Dc;-ba zR;v=!2q4CvNK6Fdl5b{l%Z>dRbn_iJ<*HD-X*+J{+n3Ps9o#gaFMa#n%#07dz#~MP zQ=74O&o(~!Vi7}!44`saF}K`&6W8^$THZo2w19=hvx1`HU$(g4puFu$z_88TutRg!Fj=I66r6c-+1 z;>1UIf971`*lo%|>=fcL+1mIBYAZ~a^Df|`E~hZ=?&0*gwjU2Z`8);3g%0h{pkUu- zZo1(*9(eF!tZ*7g7+ZrQ9=5GeRvN83bS6EP%T3o`$HR|2Ml=SEs#WBHQMc1?K!4`` zxQ&|!-$hok!-(PiS^d*uuD{_1ZW?$Si?P+(?b=YE-LU zl|ENr&i!M@aocSp*!0_Wrat*NU(K0stfPPw6|iXO3Oe>UkJ|O?QNMm8nlx(2WnEe_ zfBt+@%2lIEMVpzQ%_3%{#jz_ZR;oa^?w$DP>!ox*{~}Usp+ooXB;9Q)+guTe`Qheh0_1Wi*jiDYOe3wmjz4Ka^%2n#*Q7!;uY%vk8QuLXY8mE^zT1_ zX|KOcEK>jgeK&~?C%VkzPgD&5mfDwiRTB1(8l-?XUY^R$L;pfS z%=1w{eLTlM&?MtX1W0Kf{>E#Av}MxA3!shClb{hP(MaSFcMiFUN1mQWH0C9!Fr^A= z@T@=3Pye7U{^zB%di*%^pkhxjqKNohC!+i$o?@ud8N^3P?c`(x3%L_{Ao zytFzhI$*K%qK4;IL_E)M;6?+^T#1PmEiq5T^E?rWio^{2VJzStjYdR!p3i41KL2Y( z3=?ny$D`|s_6(D!7FS#m|2;APJ$^bdtdhZx77@=Y7SAp5%aKr~_If^}>)i>Zg4tRTg?qCTxW?fST zE#i415my^_Tkm+BXV=q)e>Ubu%5tpgfT7mUh9q#cicjO~2E4U~J6H$z>6nNY^>gT% zHui$zmL%4W&$X)!U#;kPIxQleE)wm3F!#nxy@?l)>&A1WwU(&3eyas}F&wy_c;b0l zN<5L6r+pr1H{PZtA`;VHyl1$<{hlkLwcjM3h%ONA78wpBM zB=7|Xr8j)TV)Ezb`=tEyMQbgQNJQ4IUHgZ;!GDW8I6freKT+AX;%%u=zMQ=L(Gpp; z=u62eUruhj`vEy};8(fi+|J^J(xhhH1~O*s82Ns|JgHitf|Re6B~4H7EQ{A|Fx=OY z(C6aMj+LEMf|)0Q-d6k9gE^^eA!DMWyX3B02TJ7zo#a4N`}3MVFK9RZ41WaqPt&EN z{)F--ruEs^{W<2ue0gRT*QJ+5N5nh2QQ9=9A{Y0)Q}Rnn=XzJ%_!tP@5ohq#!Ql7* z>ckoNUqcLc@FV_Q6_t{syJg6LYo&bE8gl8iH_O(&2Mss3Ut`)UmY=?#EuGr8kt(&D z$YU?QD2apG80w(^e;ZG&B98!v27VS-aVI}wc8vQR4QAJrJtFG~gdqXxh3 z#~&8+l;bm-_>@OJHkv`qH``{VOpOJQR3W8| z9n^CCpcBK(D{{h$1v3+Zne7Bh5n8)xDBgn4bm})hu$L(3ZH#SHSdv|PQ-gnD6UaYBD zttK7LI+Hq;QrNR?3qLGh%c1oIj!2zx@{|xEaRGEhLu85%)Z^*m^EuLE!%bAw9{L0 zV9U>ZxnMaxF1(CAzpfy!#NxE}XE6V>52@es49+;MCA)rI$DBp0=+yaiV#oHeX2Uk3 zo=vrywK=ED*;KF{l&wKr!V+QK%9SkpX$x1}a3#kNY-i!zZ)wz~BkkMf5IcH+Zx$?N zU+!UQ)NMffGdoc!HQDDB`qz@u!{8{|i!ky2M~O(7ufCYcM{mEuOD|1f^n`mTXIns& zV@D41_)}9Ec^2ctjh4gchI48FYdW_0{4s?!wcE98Q%Y5Hf`C# z7&^K4qbgHzAHm?#j7TI|_(hza*SKw9}UMvi-$ zXPq|*?>AeQli z3pv+)@l!UxD+n%>roMM9eb7yBqkZSaBS*z|YUrae#YAe0ngT z%O?QI`PyIEV-0gxBEW2^l4_c+Or8-#E)OWn0Ck(VB*$+T53CSnE7Cu9v4X=B^PS_f z8I+PCmBQx+u(t+*-v{0G3t$C}abmZRABzc|?Vt#Fi~}%UlS~JP#@h0Ea!r{N59kB~ zsvQTqRl(J=D)dSD*A#^Zx`g*%d!DiPJi(!uCP_*tcGI!MrRc~ZzMVUdCY>&$=^5$7 zw8!r|e&^|@o+SCMn<*|Sq%h_(?TuHdR;LAR&*(_qisk**H%E0sA-gyI#Q1y0QsO!s zca!LU``tV<{yG+X@gbweK1NB{p(Luvs#ceeW`9afHJbrfUBvgR_L5ntJlhT&<$^2v z(Qe9c)8j3LgUhD1%ebxIZTzxpKc1aVa&iVwO?#OudKh*gk$@hs1S@u!`$mtZ`_(t| zOzVlv`FIB7pZ<`}7hcCh6DF``e-WR~`jlzUJ%iL<#_W$@;^Vho;Qp8A^UixyS^UWh zy!+WAiXt{%EX24cp61T0+Z+FEOHewWC0~EZn8_c~x%b8F-mr=X?jFh2V<(f-uqwl@ zxs0uYw*@P?~!)xWgN^a;pw5nsG8|A^42SPdgfvV z^}UMQhK)yA77{r?gSu7l@Ng8=tXY>k$3DoSSs%0MSP3@ZgfqDIhC$fG5U-F%wXz}R z;)+B0?0VR40o#9F&xc=r%S*3LB`Yb6Bbd$UN%^;yQcIw}rpliL8B<0H^k0{Vv1J9$ zIASba@s(Jc!6zzE_QbdFX+zH=%3Py#F&4LwqsK}}E?0pRr<66(Li-AiBF^860?VRm zt)^71B^WZKQma?Y|39!yNuX4fnWFx>{(^S~lzD*#tZMa!RIP6L7OzspMw1vd>|6Tc zYzG0mWKhaL*$FsWRhcZ9kG_A(AK0D*i5uC1at11t^6SZbHp-R~0`d>@8P9*a?LR#s z5g8Ytc5`Lg&1{@+*Jih_#c)Ts*`7f;%6~EtC zP?gWko1luC8uhSIWhnndJn|3k#VJ=ACn<#_5}7j;#?PjNXe>%Wfk(v(m9SL6_FRhB zAGBH^aRnXizdb0|KWogD_NkNdUl55>cw`T+O#28st0s$Pe?fBYS~{I~z0blEFw<&8 zX~asS_l>tO?eUS=dOy!jdYVer8nS5R_teZRM<^H?!JMbTQmHgO?X3UD-h0PMQS9sg z@9LhJoz0PjU0}&M=b$7pfLRnXqQ{6?FrgyhfPfN21Qak3R4`yXMnF+O(vs7XVOhfF zyc4>+et%T=%-}iq`@6|-@8$D)@nUzjr@O1Vy6UOt6CPHq_?)7%r}+Ey1+4#h1Ex8Y zni`XUmdwiRHSAvVHII*Yif_ML#jzAWKmNFfd&bXT!V@odB-Bi$83la$ z$w%zmcYrDL7LlG7%dNwP^X1n+GPwT*#Jeq|Ed&QKq}OlFmHpbWb^9+Al$P@Ss`Yf} z+KXD5aXj|)^PDR4(Vzic;t@D z@y11m-uS=7NS1&USQ_-{FSnt(xQC4acSs!6q;^O zt5!1KtvN(-c@5sUR1#yoXq3>PK^D~&+0^&~h*&oPUnSpsvYL~HJ|4WV695URwMa~c z=x7&ISePNtjl?o4`QfWiIgww;b1%QDHu0tb!5ZFO_y*lC>QBq|&6OIK3^(Vz{ol0+ z#VYZK1cf@xktQQ_Q7wrj!g)?oI2lZKCY=b&B876wB$!q>>nfCCYg2uppj`}nRe4OA z@)Eg)#UUspun77~S@_mceqO&LbbnHs_L`|7afL`d=Q?3168=p@fRGT1Iyd55waa!f z8a0(1J9-4a)G#$SWyQtJnf@{dbI%ZT&TN?>U06#hu&Llnn7Nb@eIbwpYKl0Pdy;@a z$?b((g=LwFIkjw~m@YhTR4=R>e7y?iP_j z?E(wz!0Zr*;8g8(zH1+^p`WYyEFn-?!R(hNvh%NNK55{YF0JJ za&|It+I-4u0-?t(Y=&B5f?3L`+~ZXGf;L;J$_hE)(2{n>UgS_gjpu*seUzpFG6<$} zLmQ}n(iwNAs&^U00#p#WCC|y?%HDMO0Ruz05xN30q4&m_u7r-PENAqik8=I(_woL+k0?BK9McHcRT~6`)X_Z& z)T>>G1h>7)0r=@LpVK z#Ky&8`KwjnjwJ|G`ib$z<8^BUeHHkOAW~{nSJmKld2zd37{MAAzq^>_->qT7w5c?$ zSI73+D36V1xkA&tL?VM_e7)jhKKNoS)22SNk3k*}~{-PKsfq{jFX)lbH1(s!mSQAUrKv-xPxP)Qr zWD10)hpX_5$o15~G)g&oB!?O!h#AHSSf-zyyY_RopvnezCPG-4(o!Wtu;bvQfn}G0 z_*bQ*g+ohP0i>y3E-4&$kJ7r8Hb^uj{JQ3QMm{!z5?>7lVETRR&fZLEO;9Z-(n4su znkYeO>;fVrl`c_HleUn$J(*^&{hkREC*cFE2tT#JLerwuuHTLU6e8?eR{L=mM#NOB zu4kbMOKGRtESDnJOvQpqh0!(PLc@hFOe`Z9a@`BfWH?G&oo46$;~1s_Zz?`fgjigJsRon{nx#{M!v?;gYnkd8CG%!$j|$M7 zR5^QBVwozwGyl|SDt#7M0djV4CaLnjN=_0MiDs)unkn z|I{ds`myW(0l zZQg?=L7I|T6DBZw&a3#OK}~f9_doCe!~QmcvYG&4H{^NycbU+MO-!S9dLn0Y_jCB* zek_+4LnxJVAuNPu$LC66#|k)ak>kYFk(L7p&N(>%mHec1Bme*)07*naR0Vl_`}w!@ z>N|kh^XD<}qP_?#2&NyUer+O69bM>(u?8|T>S9?YJ2!8ktgxKYYD=+gdK5yJ_$rI3 z@N3l0Y($hMxPIt$toZa3KKS4x9=LlLUXPB@)CM*reQ0Sk>(PT&jWQVf^hl(;Ha&aw zz$*lM?+BB z8`mHerTG|!m)PWVFpAi}dnbnGAs{rQ?xAk|`Us$N*Ul_?|9#&7@MFe}e~OrBFHQ#W zUj_&YHLnS&0bY`7WzxJ}G6#2MBTdPf6U8JYClIgeVCe`FsoSVIzLH~(>29yIzB+S38NSsv@$pbLic(CA)U- z=HQ89e3nk19-XP57Dx7$o#f`_laN-6wq3iBnh=XSg3)qZa>CS*zG^o7vYs5bpkDn3 zbnDs$w>Oa+hF(pb%q$Gc&yHW$aXdE(tQHhE4@7o8L z*Q4B?(wW#T5JAdHirA99n}YIc8Z>Q2=Qb^f5*hB+^I8OPkMs*(SV~z_OoO60W^0E?K*d%enxE-xhL)N z5W)yQDGA4NcJk?`g5+o~oxAm*c8Z&ZEn9L$Oar_wjr=nw*zoHX0@9*!vzD}J(;Bzt zx^(Z}4PA3#+6%hN6U7zRTu*Ff3tT{DSuwwE*hFR7X-dm|SXK~CS`?f)%7#tZ z)c7nKG;c+Rwk;7@_$tfz>K{L_H>(yG^z2B3+DUBRx`jhWbMYpo(6wtzmK=3&BSuWG3}Mf#6`Ou$N2B}g8wfwi3e{&CeMz2jM2|d;@SZ{ z@M=0{bZw%eV?Yb2olq!S2{akF{j4nEs^wP6iH{Snv zC0F14DD$Vjz}BDFGIjLBjDPxJw5SB$T)dR)F7Fo#-Ox~*Mya`oP0L{L<%3x}c@CZW z4xwesX1I)MK798rwww|Sx#K>vYB%B0d#>lHNpEu5(A#NTFNwtJrgZ7lj<;q`X2s$K zlmwzkN=inLj_0~-1~cpJuXtrn4~AaRp9?y-;Et;=#^s5@rN@w*lt#Y+JsCdi5|(}O z9xax=jS-c^qhqG<{3ExhWWB#!3YCQ}Es$s)9Q0Nkih6WZ=$w0z#YSH;>Bl2(X?qBvN!Ky@@uaV zMLAO@jlqa-!J@Yop$VOq?Yc2!@CEkPLdA+(mVquMW=#=qFaCr&S?&1li%(gpxk#&1 zmm7v&O_H~YL&px0)uuDL+lje9KL?yQWiFLK5iS%hv_F6iG^^Q}{WE`ibTWPVUO;Mc zG&APB&73Ju@cPRWxcq)M4-LPZ1ABMy#{7@y*5)auOqf7yvpzI!(15D)vn=`iZQlCu z7cL#ppY7Y;qkfxSjCHnSFd#K-T?W%ZYfnYCyYS6p#5THY!8_UeHa<-rb8vFkqh z@s*$D!3SR?sa7pAGSis<#zH2KABju&89iYhgD<-bkE@WX&K<$hFfB=$FGx(Bi<;tM zUK;ZZQz{Yit7kKoEnmjPmt4(=d#_{JM<227 zm%a49s55CvUiRc1X7lcobZ*lMZ?p~~2u3k4j(LGnGoE(M68ZMW9o#ki3A~lNShMF8 z(`HVk{M137d}a)9FId3ZPu^tZ{sMaRy^Okbia2|yiczCR)4WSB0;MNexOf@!7A__; zUf3*V*g21MA#t(x*KDFZ9**qT!17O5@#@P@uzUM9=6m6$B*EzILpGf z-(~D8vuKf2!}tjkXx9BIQe&fO)}j>ZBqN=SXbDIQv-l{JCyZtKqK{~vX7ScrZ_}vL zCDf~v!0{7#R95>~zH}ichd;tKmkm&NCP5f}-k$vmZ7+YE`n3{xapWT$C<@TOdkeN_ zZ^m*pM+m4YFXP0CBLqr|Sorp0o}V(4t_@unQllc^p`t2?2$Zt&^RJow))!pZt2+mC z4zlLQwM-iO5L-5`XXf<9Tztg<-1s?h^e8jm{)pvE-yuFa4Wy*z>{(u)J)g&>zr!_` z55OxVy}NcKGtR@J_urxSzzeaYiNCarQ6rxw)|<==<6k5#AxgP0LxH!y|7-rg!laHM zivE}0#Ioj{IgxjoU{J#omqd$}t%%nvShDN`>NROiodk`Aix!fYUQfvhYN=d%+g-Hn zcRjV@Txd>xH!Ui}z?f(dTZg~Td!Ji!4pLQB11=9~buw|eQn>Pl;WX=XDUH$-$%?&@ zrJsFDoklH4OpN3C2@|-d+D%E`5pKPABuS}hSXvB&hTO*It$X6vqv_PHC36=o;?VJv zRQm!%MMu-TWmDW{5QGbaV%IeQ%S32VB-E~taK|$2_UlNEbE8YiOS9)w9&}MVUPoxL z414%VTJ*V+`Yk%(Mo_m&J7&GRh{MND6EF-kcN7^78WR(pz!NV_<&q%}Qah_D^)l0# zzj!G}bMr7PL3C^aSxuW0ml(}UbCz)HzQdH3RU_P9vYIx>E1VQ6XG{NAFo_gWc^srt zFzPjM5UKT=lUGpA&36o=Ws4?6Y4FU8FOrs-Npw^k4?O-9yZ7f%6%aIT(www-H=48< z{?Oxe8gQ8M3O`Rg@)!-9G(a;ddGf`VDfhWTYE`u|)6}wKQ_8)sx|X(q0129g?v7=| zlTTAnScW;n4+<$dy+Q!4fflZnvGczoe<`V9QcL?RFf}?*#;vI}k*miY0Hn z&IOlT$N0ZLg61#gyOrCJZWp)Sehc5M-^M*d2eNC+X0n>J#O>D5gwA!h3}ImBw$$Y9 zP_=!SwKMB8dh}zo$xNeNv(Fek<^`^} zt|wA+qvJwHaM=}CQdM0@w+p*7@TO-umV1gL2XjbCOXlVquOTBf375+$SE5=ZgaGO1 z*I&M8{pKC4_~J8C6C@Qy<^1}~8fs;v5FMAykQ;_juTDCeOXs+BQKxQQZn^yyYRAM- zoqH6Q6~vSRzu&~|ishk)A11c?EPeY7^+>AT^Hi#t4g5v!wdw(g0H53rSXx*Tz0eyG}iMa?JC%YEE+JJ!4tE^b4LCakV`lRB0K- zq-aR#;=bz%PVRw^z@=~fKG;Pq31>(}3o)|K?Ruoj_6SrJeDMlGq| zNHK#I1*aMH(1WbovJXS(n3{6T54(E=&p$ho9=*~duBraj&1z0&R&({pyczVlC<7rS zd55>tyVn2=cOt>+N<>U5125`|%jLoomqMqmDWOepTHQvZ)op|n76Lz|g?ZdO|H-J?y{P+qJEQBPFZ<7?MtA?)}m9lG#gk+i#XNZd4P*yQ}Xf8PG3xl|aH2xSGEmi%3b zcPStk@R6Ti%thC9Q;80iv==ltSKn|eAAdKF!s91cw{{c#Z+Q^itzlZ>u&9JEt zt5pkKSOfwlei_B^`yQoY);ykn;t{f%wc-9p9;9wsvg$b1B9JDz$Bt0#FJ;dBdBnI3 zG@@wSwj2HXbSFQzgt1ROK}O@&j2Ll0x^Q8cCQ@L_+c{Z!w$n)H2qAFCx=D(Up{lA1 zEQ8d9Sk440kiLBW{`?D^tA3RFG z0sZiL)E_O=i7(aJd+aow`n5sRbiCeZvNAI`v}Y%lbrqVX*uU_^WTGL_g-fXqyQ8U> z7EMj*8T8m_gtXAjN@h--#Lj~iG)j+R+nz&o9wbT0YROGE4B_?h6Y!>HaOeH^(xFW= zJVJrLP`s8qo(nJR&(^h@sc+UJE+LM(sd23NdIfL4_X#QW8gMFSE7a{~7k{xA9;qog zJk8*AQ3-J=8Kfn}0EjBWfZ!+yg2%Kri^=@Mww~2&=8sv5qsVp^zSh#)MOGWV--$!gQpb`DFV23@*#3W2`xnlD3H<>I%iw}6Dy+Dx1}mAtc+ z=-yb`bnHx@3ogJd!(buw4T)U`Mt$muj^eT_uAoiFo=8oz=N?Ie1{rj0+YxVaI#=Fs zBe5=ffk4=RR|~gIS_mOS`R(DmRsbcmZ^4eyjhK&Bms+6~EBI^&isO9joYfJmG*Fcq z{wm{EAcegs*=-NE$gzk_FPzE&8je$6IO9j!ail^qjD#XT?HF{2a3CTvP>2u+6{tG9 zp>C5A$PsLh%lYWP^Y*XJWm&3Tn#2C-`tQ3{FtPANd5BAhX2-7WTz5@xJi>)3bb=y= zzTw7;ukvG2$UQtGxOEiML^6~rSfw*C4mL6OAd8ME*eo#fM1cOxu~TD9u);)Itd z&O6KvLvN*4(^lL+YzQtQ7gL?u^%{UXijhx0L!;WN4wzd5U6?%j^plhp9W-OYpJY2Oan^>R4EF>#O?B+3608vv+Uk`fGKY-B{RX` z$fM&iEdyN_RF{|8g^e{5(~`mPQ=DIb-XN1xMTPji@uVds5@mxf%aRCuV1cDYhq4wW z2KBO1C@w3Zrn&~aDu~=bBO$piS6zGo^Ja`Cvsn{{+<7VtH_Yjt4 z;`94Bdg>%y`d$l~9YGa2)O3lQWBpR}hm@8_QRYTet|6mGZ?GUo+{A zkGY_21~p@+BQ?;X;<#z}eOz((&siczR#ZgGrO7bM{m- zI`-^GdW@Sn|M-%N23^L`+wNlJ@;CWp!$}ZoadPQVwhKlDVrQnMP*HT2yt5_5){n)d zxxmy2mX`3vC!h1;8y_>Edjlqne+`ML-Yd(*2$<-aBq1rDCJogwvXap^ZOZd@*jzP3a+p&jR?Z%C1+PEI8zyFo?t(z0Cn-HjC;_DyNxOEpY zlM>J^Nu$=Cc;TUknLBAb&prJdZ@e>~6t`M1Ecu(hKX3nJj#orlc4Cxc_WJ77gOs=; zmRHS*J%G?MuYT2pPIP=4!|r_;gbT;X>7+bFf`{KaKL5EeiXc9@4#Vz#7*!}fJQGD8 z83KYfFc5Zu{+QU>{O!JnLU-+yOtPzX+Qp0PVp8FW^xTsR)!uL!rid1wlU;VMJ2(8@ zf7M#&GY3#QW#yfg{Z$67N_11g0O9)z{Upvk_P3^mi;>yK|MT;8KKp-4gwHvcZa6@5H z5gGNVflznNF~Y} z%{y-|rb(KM{QP{}!X&j`Lwu!YnehBHn$=5Y_)Qma>#*UxIc)}ey0>BNhArH9*F7Z1 zrlL!UGz~Oe?G)dbHH!^<^O-$!D)F{EwQbLC#4T9L-^YxhUHw>oTECtKod*$=f~zm@ z!|O99QxcWNb4?l}WDrxj&_fHG$xXN3$fM6pV9KPI2$bd#L~`40*AXtAtX5N%!KUGj zP2ig^mT~&nPB#9$iq;)^(7JsWcC1|mK|fKkiL_|hiY1E{ajb1!4jwv8`-=o;@(X!? z(L&Yyl$%kHPG<77nLPaL6pkO=O5^%z?A)@6vt=$` z8}kq`9u28!7{Y_s8_(m9Kg6R?OyH@$iWMt}a;rGwaOrVH zyExhD;vAq8W`-ParP(ZvWtXl}bBE3I$^YQo`>zsY|BX{fp*BGZi`lhB1z5rgl`B%| z!FCP5|4@mrF!Lwu^C-emxo(}mMkoRN$IdMYW%-A)g5|%#Wc>-aMF@dmn0)!=SE}5K zW4~7d^Y7e7%Ti_8s;a8U%*_0KFLvJkQYK8(lz-$7z(RuMLs&KJ+OvnlhY#T=iiy)d zV$qw^=+Y*glSg-O-Cbju@akJ!+$jsUSOR;g%*=po;8m*&IDtKtfU~ z-MaT6B|gTUkW>Knum}k6=i4GxN$25DWAzBL@$#W6vQ1L6fNXWG?8_mz1agdw1<& z-=RF>Qc~&LyF0@4u`PQGr%o4=R<8k_x^^WYO0sMB0ixXTv~1ZBA*(oeAcy>NLHADW zak~I1k!BgE&lIqI#~vyx%XsI*)!cITC~h0v9?d9V%&0L`*Xqc)(GL{w> zos@Wu{Jaw!$g8Ah=hhURInI{tyQ!}7;fYJ8TlbzMcwybzpDC>j5SyGz_pV(@OG-e= z!P#{jh0Rk~K6dZe%Aw)_{rmSPK{u%>JHw_edpLEv2ycv=dd*wWsZC1?au2X^`w{wG zcmap@ZYH)~OPVyOi>NMP^XBd3=NBVfF6y;tMW>bxDLIqN=B<0EuB^r#mq@#=J!z7W z$l22;*tl^kHI|1S-8)b}BZ(c`c5?K{Nn#Vy=+dnRwNj!vk(bBW{0cgEYKJcToXkDO z?t`bfuvahQydFT+UIc@aCl0b}Zw?jJK@yYG=-9a%DM<;qrAf}N?U+$9G;G<57);LQ z9cR;~ZS=b6Qc@G+|4%xFq?81ML2`0(s9(SSzdUBwu3hx$(+7Zpf&!K=UrygXeQnhu z2q_TR^3<($H?TaE;w9TP1S2z1Im{ay@L7<$=7^h2zl?c&B^{*?Ps z;lF<`f(fT-s0?SjP&S}R-3GR{yVU6k@$YS?#HpucIRG;>SN!Ym{~7F6QBe`=*RSWQ ztF8)t_Iuaa{XN@hSt{0Q+xBg=ZQGVEUAp{k*E(;1zB%E4zyA6wLjDmIq9e@2LbrVE z*|L^>M^2HDlER8FzhmF=088ioo$6CNSn>5L4pq3BI(-sJfD0274MRCJ(4{jGn^;1} zLPNvC3RV*E`vDJVZY9bj1o2)kLP#{UaCC$X3{0C&*PP9qP!eYbswAgwmwqtpHHlT&#X`~}TheVTpYJ3$~rj8U*I4%>@ z<0i`O#v^4&E=fIKQ?VhoETI+ho|tOH*$bre3_}8dcIbh6hNj)?s^((YMQ3M0OBFU? z35jy5+hYVm&)}S>AF1MvY%LQUl@&{Zrb&ZzyxSGiEX{PIgOGc(VF!2jhI2?AZ`Od5ZHWSow2S6S{@cI`Prb zS(4*pLV>%QjJzLtPVkJHAT8W>9E#;EveHCguq}H#AAI;J0aKwHX<4MD*X54;?jgEP zIxagqEW9i`Kr7N^6jtjCyG30QP89op`&nrAoeEV(+m4mdal+E|2xt;+7ldTyRK@Fv z$yo~lHFY)3zB5N*!|o3~mNUiGtl#<_@iFntm^zWH+6jE}{dNujIm492oI6Y5J2kaRj)qDf%~*Xxm2vxDKo4ywqtPDs0u zcZ7UQ_|6?kKxaI=)K7v?pQ)HFLXwB7-7e*N3=dGnN=bnfo=~r-J`bwjg$vMBDH!22 zN?la}!t;LM|B6X_1FE}Rq4)H!X3yDa5dZ)n07*naR6>Zq=$)On^LF0;Y9^#5Whl$& zkI)R35>>oIq9OzVX<`aZ#l8s*goYKtR)pLsA{>0|xLg#DP^^i{bk#yju(VXU8wZS7 zG92t2x%jHs7z2shhHegkQ^zS*O^I%4O86&&)sqOzc3o(W`vuj8&>1Yd4FV~`GIL6Q z*9yUfNH>eqQU%c>r*!F*oed>mgzv;*-kj%X+H9ob4$>mdBG0*=4E1QhzM>o5QW?jl z6u6we&_ert=R_(yRyg#TiPI{}zAs_-qO>_J&6Eh;0Y;{+5#vIoV*ECy$~lt)Md6;X z`%Mbl6%}rE=-CSsq+)9=O)+|!4e}kARU{!JL%V}8PvVRRVW$>3M)43e)~a)Mf#_^aR93`hMn^Zzx{meXh<1mWyA4b7NPjB&^r+E zAVVhpjZY#!JNMh?ej{=o`D@UQ|0O2SQJ}$g$NMY!Y25}IG;2fStlC)iSO{ys=nmvo zn^b9n&@l-oT!_elhxn)8|KE-Iw+^v@06VtrVf&sV+;;m=TVM=A51hzh7Re#26Gy&B z&ZWY~igW)E+DL{y8|N^eBJvE5DHR{fRym4n?QauHoXxZPTjYI3-shh)z9N}GM}0`W zpAtv56rB5aG|Tmf^-6hO!0Cg(#(Q#}3H-ldkxZb5_+!AIV?qct%g3khzs2O&-o+1~ z>58n z`o#u54!n$<6cyxi08IENf#Yx!LMZt$3xsJ>Q&omPXxP)2&1%`T@B}jCArY9iyU;mO zAVd1L=VlCs=4(`(jAm=!iqHfju%yX9zWJ7Ua~IghDwnGaT}1&>^*zVQC_rimDeSXU zv2*8ECQg};)KsY&mxDWm<05xJyqz4UDF#g10MOyebTo9kuQW8fzbw#oOdK5q4IMq~ zHjMzQs{J}hi!&$oF#5%*oUL*kZ(0c92pcX68KD`i2`nMVJGh^RAH0XW@-pS^btt?@ zAD#WkRjCEl|B*2CUje0X4y8TaYX-_it;Wo;W5<~_b56tsbg;Kukvi0oFwZ_w#PcHJ zpVLa5eFYc>)isqiEOjX@Q_BXRk*5^cAYE5LFk*XhE~q^V*s74poZ_mh|uPgbk0tlpYqzdaTflAxvD87VC#PickUEx^{{ zj<_HD*;uxopbF>*Q%a-^B8@zjESSx66J}HDmr6>|R_Bp6NRbjulZa>HY|JxA2s4;Xfp z1V;@;+Iv0$=ZqaoVr!o}Z)fBi@&}u6<_4wzjkNGpR&wNE4m-AQW8eP$yDQBc{^`^u!RX72Tc9m15tvs{N(J(CgNHINF@jVR%B9ieOS?#DX0%C(cYUh*CIl zG7flC;6g}Yw>!v|&70W1b5}T#PCDRI3%A3GRdnv%t~G}Z&B{v3ICAJz#8hjAlWb+E zH4(S!01F4G*w8NoWCcPx*H_cMCLKrRZwkT6NWdfP$uUS#!D;^S-H%k6oNM;j31Pbk zCQ$&TMFnJU-a^2z&Vg{Dz^HIo;kk=#=*dTHGD3`v%U8^0EZ?s3z$OM5CIUX@~0&g=O*nw z$1>3D{I`e&^j3SCr$IDy~+OKCn!r35HbqC^@^gaMx|a`1G?c2%=^j zm&>rPqk&n2&`eD18AbX*D$REjwXy&6v67wGV@dlxF)%9fnK z7ZBTIpsfMxJP$C?Z5NLA8yGAiSZS5eV@j|zkG;z`K?XykD+~-#RZC{W9uzYI7N&_JS_S16uCm0&f0H&>fD+pj| zTExam0@ci)JA;wWJVWg|=`?HHm^bIl<(8Z8ps2V4Gib8%+kbH8)DeP#DyB|(iJYUk zbnMBcGB5)1~B zMh#zo^darrwkNA`OU6&0K|m5JO{caA0x(&>`WrIS(wI1T1_9IJ`_GnAKeH~Y*KOtL zM<3*>AvaQKn5_PCIUU-zCZ$e8ZW?wEGEjpI2B@s4q)pQ%T+r`g0z&faBlpuVJ(aAi zEXGfqK}|qlSSF@rF>TUIWTrG@`HC;uy7n9D*UjSduYcjh(S3C3+>>jD-i6Os&WFpE z(4k#xGU{b<-HmrqToDZ4y#0j!jFBaRH!jCqj5R42G8Tb^Y$m0%PEQqe+&?`G!3D< z05=|wD(SL)^D3rJf0MGRYD~?;j5+gZRZDW?)mM=()6wyhoY9D9$N!zqO;g#wZ6mX0 z&L+RSoC+(E`yYOiA(!^R1NJr|$^3>n1z$IbQnCEz7c4Njo{Rp``eqd*@i)Wr6N$~VOdS7-g zOP4I7adH(`-*6XE37I4$CGy&9W7)Pbn`KLuQ{(qx#bq#V;zT+$u8Ui9*h)=dIjT9G zcbEy|UgcQs8MJ6Gqn>{b%Q9KF@@uXcd=*6%HC!`vDEB>Z7tv-RGpD`EhV91))YQ*%;V3JoxP9f)KnfG{X7HvbVmZZ%A!CBKiR84X4JS@=<%7DRfY7t zKbU@ZwSvkb`w8+`2jD#yNdT0FQ8$1A^;v;11pFS5}j%$j(wgD+54&R zNrn!;i#u)`%DUxmF>UVK$hc%QS;N)0JjlIw4kcKT&%8NvS@-KkYJwKYjXN=E{Ae1a zC5Oi|D#KVBC2U-?hL>M|o2ozsRRIr%6_05eoIbXn=~E_iqNswRDvc|yx`7ApznLZT zUghlt^GV96hb7%yeC0LVea~GaYn8k+=S{x(aWhqc8ZN%>RshgIFTWmr@J@dIbO~c; zyoDCukc;~Fr+<@JvNvXP`;9k}n$eUO@4JV)ZyCaSzx+(Y^e9%mF_*7)SMcWaQGE8+ z9A>}&Bc6m*uD^C5*I(L$sncF3@8nsk{LpLgtvr7BASOKhAjRHRy!!HZ5?p{KIk9Ui zOP8(Sm3NkNQP=i(2y*k#tGQ$7oviriWA41~PJ%`a)rGlCp8Nx6eM!uk@gk{S7rOkH z6!-ra6C#KiEath9BU$|3w_G^*Dzu6`wjJGpumZR=K`>xoSvueW;h|B-4qVZ%J>7bA zVbg|eJaIAHaL3KmuUC&c$;lCsxdPperA*@bKe&@!e{g5A97segRLE-QanN5}dX^6uLU={xvF zF28I5KYYKAF^@e?|IMqZ6(5amzf77g!1VFuCm-<5ue(^hPeclY{|6gQ+VgS75weSL6nyJnX_;a(NP-9-hGGX$4=(MC38uwQ;%0?&j8C} z+MGpv`{PGAaL-ksFIS>|biCteuKMg99wOBbBk`Yl50b}XCUcHNp( z*Oah7x0Elx`Iu&P<1nfY^Zv5MJU(_RjWaTsGGhU+yfT}Gb0?#TNLRN+8r965_A)h| zbY6RR5(yp`(XnoR`O2bWx8BTnZ5H{5cX9v7(Oh!*r5xYz9mftGVdkuv1S*Spe9WsH zJzdS=AHE^?R3Y;gyh}n<6bbQuHm==_=__IU#5ojJ`Wg4))0CGSW9fSzaL>pwv~J#j zsWTTaeezTm%zloY`;K$RJ&$npkW28!#)b+thf0x{22~ZMG;Q6Hv6Els^!^Rpa{mN| z-f%VE>H~~=VJ7b^`G9sUGWq6{Wh{7O1`TJ<;ar@Xy!}ZA59q-KeFrhKd2iAZW9`Mw#Brbt0L$Xx#~oujz!%8U4Q-FgXOMYCnf!gT}Xw#;d9m=i|pPa{6_}7DMj=moa7Pqj=<5Hm%!0bV4cjLL7cmK`+;aV; z%>Q&9xp}8pxpFIg`wk>F&c*oYv+!9iQsdmDCMIAUIgJtUG5FfQfv_-z8&7NsV<%1~ zBhih=ETOWhl6^-{Q&dup-&e`ry+=v!+!zDFl~-KNGov3Qksv!(XCnldb|$~HG)yfD zSA0CRQe!BoC_~p=48MDX3ayP;rGA^p@&^qHgtXA4@`BX(tI02|Avrl6w;iV~1h~B} zV!a*$Rn=HR<8*#L)#c?}*tajH=CT=K^~}N{8j^q3emQUF?e{a6qqF;mxPl$CUB6OD zOv_^Jk82n=?F}kVAET_agr>c(MxqlmB{7Lfq}NWQbGv5jIi8PEUBtG{TUq?YZk~Vc zMZCcvE>ASR>ME@GX!MZ#NgyqQeYhvG;T8Ey5G;XVk6UPtp{hF<8%D#^% zR}BHvN3W}gfzYwEXi{p`CM{NS+x3H4`0-c@3W_K!JH#_Dyu_I!`>2v`1`ZpAv;WPBJm{7mr@~>lchv%I1cL;$c#_gGsg))B|4!tDJjVa(}%Eij6-eJ-AD^u(Fw$* zB+|NdW0K-yID0aenv>f|sMDNwJ-SlM<7d#oj(ocE9~9R3IFwh$qrLi&k`hbp)L7iQ z#Ps{vyCa8BzuCn1KW)cjR3TjH6qlBe)}uYOGMyMx+llG~3nK7U`*NlCPA*$7{ikFs(<`*votd3z3h2VRR#71H!lGkBm11doUp1SmRr zjI#wLbnM-a=2QnIpyT!?lb9SwyrJC1rf}npi6P$W#)pA4 zgM_Nk2|>^>KuQc;xDr!HNsdP^FXX`P{d~0PG++GVCp=~)o`i;!mRHifQ@4=zwnA|h zX24QOK0+gC+VN-@xV!=(OvNKm zFrk4NRIzxW_DHOd?yH7B7~brTX>3{&w$OcfWhD zkFUX*?g}TL=RD!_2_a^{3)hH0S8#!*Bd3pX$Bow!tk9B2AHJ7q@6F>>SiAI*V&G_l zC;^g^0;HOXNVu4YVPhx=CMToqFiLC>NZbvOP)-Ex2>FE(PzD{&y^x9(O3|f959+qK zkYLbFxDsW6a&wzS1-SW^UcCJ7Ox}3qRdyUI=B|r66GBKTU6!aeD3zAX#Fw9E+{7uo z`@#DxS+tA|U%o@s455?|jz&=u<(rkCFl^X(ZtK^Nh7Id7;+dh~7=C^{C6TZ@Mn$8n zAO;SRNFkz9Kv{^g$gWhK&p!Kv=Z22v{b{f8&fI0JUb%#()yu@%J#IPsR}QYk2wRKv zv`iY;%3|-%t=MuAmNHNh<ql~GI{hEK6T|XJ zC?i0*tO~sJ%=2_^Uk_7jw1QG)Gf^TQO1+ID09uogk;(Uacj4~!CK0W` zvPe!#p?>qGygKm(s#GoumV*kVl7IXtN;`pC&x zo%h)rRv;Ei8SywWLlX#q6OF{YV1bZH-sw{qC~OrZYPfI_0W*k!30kAXz*GTh)@{o3 zZ!M;JsvCcoloTQ(7>E7v0VskgDWqj2apdSel$_&2;HUtO3V8538iFP&5I`w|vK6!F z*{d6mjhsMgD1cy+nU=w(50f}`;v}x;&%jhcw3Wg+9nYgqt!yTY8ph}e<1tgxsZqB+ z!(W|8-SQ^Nv9S!BP|!vkg<%BT+-EC*pyOG%Xpkb59l`LT`2rZ2MgSZkH7%8*!jnWJ zVN?)ua*MEn$s}1ODM5qW(rhZsv$j{*>H8q3gt=jYE`?JZg zN)S<`rX-VW#8Of40#-@Q%)~GZ&YV7lK^4TYu*Ja8K{85}=aDCF;?8TYAb^cBHAxvk zmd`37;>XKLfSkNSDyIb5{Pk+S->{i!Gv^V?+ry)y-o`XQJA$D?ZpNXZF_LUhQIvL* z27)04D$1GMd{p^NYz2W}2xSB?tpM5s)DBufl2Vemt?%6oc=#_Q+l62yQ7X-4fYvck zX?J6~=z`X~Gyg;O?%q$ihILUYNB3zmLM>rR)EY#0QSO40w(yT~ahUE@L+h!y=#XRxoeQY@`2uz7051^!5foCvA11qPUhs09Sw8r;33|dF`q_FThLPcL-kCr z4Sh?$_1FFO2aBMvm5Ej%3{x2ODTWL(oHuaSiIQf_z3w^{**snEIccqb{tI8L^~S8{NsqF z6bfZpgi_MjvUVdUPxi(%;o$CFoNQQ&+^|71V3>lVeV7$@Q`d$?QhHS`IR9K;8}%sZ zk3EG7Ws+X5Ea#NZ#6^{J-(sRrR)}7`d-LLzw=i{LHO@cxTz)y6OW8(Es8XR8b+b&S zyfT&>?&wF}nIhVDXp45D6rVoE+f%2|sBuFkjh#sQju%t8YBoX3;NZT!oH&uknGy%X z5R{Sxyf}rKnod@Qa?E+_Rg!`!RL@GMLY+o@`^pd&yx)w{sTKu=whN`9d|WX=8I-Ty zfNEJ8yzumc+;#UooXB%%*`fvMX)$mRH(5ahGc}njd-vqIF+(YzWKgj}7NxT)U=zZO zVeokyl`^>P_M5or`s-M@U?DAAwB}3%I-TE=4i}xvBToz`yL=^T)u~MB@~IT7R7z)8 zV(9bF^3-Eb@al^%^5mdCRIOZ|7l#huo_p^kr!Y#pw#`V5_0VsZEkCWmL@5(Lsatua zvJ8_bNnCt!H_8rwnTgLn#$}gZ!Ndu#aqgv^shpZZkBgf!ZuGMl>RI;h*+W5*#;}sO zpz~$idf$`OuU?rJO`C8iC(PAXv}ft!1-vqEJyTwIo~mWiKolv-iZl87?AUpb^pp@e zCysOE$YIQI5n-)74DEP$yx=m?I97o3FYC(4DKmI`$`~%~(wW1ji@DcbDQY3m+x>?Dk|s$6_tM@EevPL*__QjG?j%soNx?&lM73R(Zv zIu&TCSogzrZtY*4)SRspiwSEFDbdh4Ml_b!U880;hxYB{^Q9|E z3TDu?eO;>8smz4o!+4lTk>}`G&sfRnbn4cPdj^lCL5&L3uTzKI5`%6R zG-AY)Pmz~gpJyKLPr7A*GO5|N9i6+J&%nO7GGM?!LP?6L)24AMSMf~GYY1svOIa|J zuH8G6Yz67}@IcCzewPb6Gy?=v{ij+uEX+_DhCV-*P)a6m&7490nN!qm)ShbDnJB9S zOgEF3Kq{gH(=K%FIZh^8Q*QtOAOJ~3K~%uy)7B-V83q9_&CH1fC};$mzm9a5&1`1&jFl`z<7utxo?(AEs4iT@V#~T!On?1F z>eXw;iqAghrkk!}`kT{;Mx#`!P?>6#vZ+zMCjB0~o591zGimf#(n3Rd?5-<$?9l-{ zIb;}j1bq{(uW@ozs2!mN16Qk+l+hpEe5Urg3@Kn z(XnM?%uot#&b@$gX~`&pWLKy}eWC~f?!5Ot%s?9Nygdy&kj71S+yT^zsbW5muTmlE zHgC_;g$sD;)z?|GYBl96)}ndywgin3W5x{Um1#2=_xwmIRH{L<77Ym)5Db{?*|(cD z>(+DerQNx&{~(f*N_b<&Tt>X`4v#-EgtW}kTzyj~3@e4E&0A8jRGLeI7D(aQ(Gz)Q z^eenQWg>U=>BE(sE@9B4dCXbxA>pXaHNCE&dgW{aB~dzE(2BH>MzBarugIw9pJ(dS zH+f;)SklW^r%9vwD3umJA$l=9%1Gwsdj=3HU6ZK3@3@e4!EgMrIE0eU+mH2e=M~r`A60g1X8lA7`$sKpzO0ofc?!TYZ%xuQL z_!5?a8+%_#sWgMm-LGM~Rhsu_&SUw~Pift;6LNWb(lSa>t#Vcj*HDx}l_o9dd*40m z-L{Q>*Imc{!^fF0ejG`b%{d(|AuTCHh3eG^mN*1agi^}WzFl+DgAUajw_@>!^O*d~ zn@kuto@#X))2U+{NDKXTM5C-s9(!&KZ@=+2FHV|(1TyG)#bt<@MDOcwBw(1#{Advc z(U0kL=_Q~vhB62Qf_yM@HUTq*apNb@q<(FJkz{VV^#)#^Gy&6z(x&yfq??LzRclbs zEG7gfWl+9uBOZFVKl9#ykMb32a&g-MjGr=<(G%a~`7sko%}D2}8?PZ?B~i0(W9%|n zuFb>{DxGhRFNd3v=>(4wxJ4SFz|_IsncLFAI+Oj zakQ9o&%Ka7clReNGZjmqdF$4c$}ESW0(8FoG6oGe%_oZ%(yCcq(vp)C#=?J|C>0>B zbT%Vin8b)lFX0kdy39Z(CG0(P09yqJQNp$zTU}L8G^jKN4IR!S&x~=E`0yEi-M*1i z`5K=FQ4FY1u_|4zxs$Ee+=jv;tX<&w05<&wKE}O|JVjI~8dtrX<2lE%jU?HoR zhzv+ZsT58fKg!zgekD|@A`jeiE2*YJ5#;sv=U{uZmY;m_6&OiGMWGc0G*qcxletS4 zBaVqOld(nd^3*B3JoR;=Vqhvi!(DUh0}pfS0|SZTX3tw_ZtL5R+xp%IMi9@3LQtZ7 zw{bICTzH!}mvG`}`uB_}pREcJFoP&7#QB$A&Zn1j0hNSpxZWW{1SMh4>(qq~m-KMs zy3sUi-G+mEx4MU7CyIZfRDZRG{waUTA1g|`NS85G{J2Z_j~t4w?iR!kGLDi2YMDCMB0y=^5Ij& z#5XvhZ7{5uJIMo;`KyIch%D8JVv z-fq}vuZ|`P<&=P7g0j5eJU8gs@qnP+$ST{bpYr075rr_%JsXQLj8^tc?^7N^3W<0@F(X@!l^!&#&8pu64(~ z&l2${Zam=c7~90zQG}uk81mS&M77DN31ecGUN`bD;$7!+E4y<<5yj=3HauIB&t+qH zC5dy)_@g3br}l6F-S$ponTex5s#xE~UFq(y@jvr#llXv$|Ickr5$`Zyc>Upz{(p7c z*4gs+Foyi}(@>-g!WrG35UH@5hHHckNGZK!e}9i1ys<%46qn``ra8khA92nd3X@ zcgu|||8^_3vb=V;==0!Xj2b@JRqjcQa`WTFd}l3qDB&F6wV7+WcIVflXRxgdI(F*D zkde>PqFz-OB_UyTh_eGJly=BHv4b0~y^U|SY)3q%CQPAS$98DoK-p%E0+eJJ`uciOeOq|Ye7qx4{?SK?=pM@LR{)YTuZ&1F&1TS`!LhZ$@R7XFDo}j>%UR(D2{R*x2=3MJ->3!t$r$o~L(bw3K06HN z_XhDlS6pSu|Ic4c;+t3;H%-MRI=D#@DyCfd;4}@g{JkNFb)#`n~DWOu7AOdYhy6#)uyVAzppsbclYqg4@UO z0CdwEM;fKHS8EG@)W!}XzH05Yjndwji23#7>V;2>=#MG!88%|$|35k7(IpK8pXkf~ z6o|3iMDf>@7=mOBv0Z~0WMtLhgU{A^Q_<}?H$K{h-!w>6s3mrRe~ayfYPuuFK@-Kqz!4W{`Yd9%vj(ph zo*=k~SHtn1?=lR<24igD^bTk$@o?fZLnY1-_uANuSN@UCFH8KWZFp_^?;2Ao2Evbr zaSJYftzU6}q{J0rCB$%0jaVH#^Izc;sV?%qM(8}1Q8UbxZ9AU6t445<1@PA1#8F3gd5g$5^# zySM}pOWdqHE(h<~eqFp0 zipJ*{^<(@LZlHc_|Bs1(t=H1NGUnF}#)hTezka>MZyU!OgDz0DiEqS= z+hruS@g`*XqHu&bT{L)B+k_2GY0uUgXI1f!4gT-?H=i1~>kmp?1=>5U#-Ijc{T}O8 zPuWT+%-@iI)Dn2|!{(? zL)_D&KmUA1(OZQ4qnSSzILpe4ODj10~uL&KjqF0!o|_Jzl@WvbxVVz}pYJ zl1sc6Dxnw%61&A{U1@ja&mH6ykrTt-f~N9rpsBR z$qDsK$c{hT=BE=kAHSGq|NSo#A1ipnh7DA%T=`E+;Qw+t%Mu8mU${sVHupgn(z?Q1~0D&8F|x zV*Dg15|y|e__Z;;_KSCt0uMVd-lMVchPR8wHk`!$!&AzM zlACjsC7*AiN3ULF1pFk9L<=&$N|4YpUdg?fBA;)>cU^n-#^1Qa&vwGaKE}1Yp$s=} zR#c4Y&+=TXZh2k$I0wMdDAPX@By47ImeS%|@|6EpfBgAMvTxr^jN}J*905vcR(SCndPqyc^uNDM5+tDZ~LB&juJ95-7BGFbsu~D58SyHQL5dQ8WP@WyO?U zg|7g5j5LBbz7s4^vG@BS3TKD(#}#{ir`(?6=QmPpeevgOme<+UQy3A+Hn1NE3 zJA*y+0awWo3;~e-NC)o<65gs1y%%ikpHNP@x?6R?ijcS?7vlmzfXMsjvKxZ z^(I1M$V{TRVM2bAof1JC0+=Xm#@ZZjj2hw|#~g3^8RA-6wKpdJuJS2`X_`c%5oXVx z<(1iA*W%7@_uu#^m-xs0=GT9_IF2``M5tW3^1r({f6Bj5tk~#HoVkDG=u`@^i&(vM zAv?lVxT<$g(o}o{SKc*o^~{K`ChE5ZjXReUZ8yH%Bd&t^^jHRqX3eK!{U+3E(wrdi z{X;7-6E+k7v?!iy%kX1bAbxs}ol^Y?u8?S$rAt1dYRikLU9&1l7%l}^ten2f?W{(L zJuklKD$jxwcPpH2N%GqX@ZuyzgvE=NaQt{KU3+x<%^Tv@2j3atQ@$zj*gX)Si2eI_ zux9lJZoQ><+@bAjZVLQ3N4FLUyvqq(wef||?-3hcW$=}*m|@c2486_YRjzcrb0p0E zJ=+-b;#4|Z-ix$=c0s|F8E+Bq#zdm>fEMK{b&ez>YQo!e#c+s*k8t1p!?^aIr@7>uI`J-2fN%Lye$Pun zef;_A2SE5XZTCB^3psJ(B&SZD!L|*OGD=aoLPb(T7CM^4?)|68u2PeXkiv=Nv2)Kp z(#upQyIh%A63ZVUgC2b}Zo%`$j8BEc! zkKdFvcIfeAP{Ghf>@<~lc2eT@ll!&r!QgkF`(Mfa{rj0cdo}|H4*ZQW{+}sYyL-># z#f$&lMfp?y#S%AY!GHhg_78{{zBNUNI|6WiiK7w*oKF-CN_v0&*I?1T)0-h5>KIkh(BiWC z+OY*+63t}p>ZQY8zgcK8FboTAN6-inR80MKH!+v^-DmrCVmnqCmoM2(A`!#F@vI6; zY_NUfK@@Zt5#`n2S5+O*F2`^L(@(h}ZifU#35qa|*H&Q<-w_ee1)w5m1z{lS#w8Hr z?GkdcweLl5*Pt897P5dIQCBjQ4QXzgvh5=Chn!~!ffZTf~6Cr_f##_eYmE(fwZ zrhKMm(XQ1MDM3p#L8W%Z58JerKUU&jx|@#ntRxyoS!gQ-2g?PrmI$K5UTwk9Zn%Vl zo2cZrsYa<(F6nYP*Wb{SfO1ee4BE!=#vO*q)-7N2^5lsWMnMz6G*jr)w-5E|WP2r! z0ui*1r%j+VE@!tp?xQGdKYmL)h-k0fU6-%cB`jaEfIIK)$LJR)GiAz)4C>dH7hjl6 zPEnYG{F6NT*yH@P?-aIuhM99e;_e5ZX7`?hC=}xOi7x*{#qDc78Q`S`6MJu?k_loUZL+sk$ zeP-h0f9HGuGq+7Vm$w2XCL#*0<#(_D$9{YpfEzYsV4y|0inB8Q#y#SBjtmS;Z>=B} zhN|$gbhSH99A(A~4dTs-f3%!_{r>y){D14mFyd|Sr~Ka%BW7>|MCMvbUYE{ogl=*!^~XArxD z;ZHn9^;(UoRHYG%7Jh`X9j@)!i;87x^5I9HFze0N82;4#7uXeC}mqbGtJE2s;3amo~G)T&3V zx(!+OxqK=>=`HXvRD2-~? zB|EDMvp)L7Q^?~%;1K1fbzgAqx$P;PU4h2U8nbBm3Ze*xggJWX5Iwqfqk8q4Jo@-k zC~@K#QhLY2KtM%RXO^Ml*lj2Xw#c z296#-9c!q75`NsYjXG6pQ>}J0_U+%#sHYyGa5j>}U}O5AEmXTW+Reg$mqy+dZ7gcVjOX&Y4BKR?VqUu{;C&-^1N^ z-^+qUt5LxIoxADKrVZQn?BJ|fsX&mY7uU|{Y4jrgotp>wJPQ*QC*i4`L z3e6ifpj`Q~oOj-Ne7kWI5lmhjJC>)P9zu!Z=8G#8CGXTxCXRoZ2M0dIzS<0qjim%z;FG1xdHJn5yfyPf+P7)$DmZ3hy2d|G5;w)TWeN-u5%-|2EboB&JC`Q>DA6d#HyWt3J?&znR2W+vqK1#vDER0B z|Gi?${|YN0{Cx+5KjnX?#DjqZHzDK?9s{l`&_;>I42IAsnzwGtthpbuWZrxH@Z~4W zTKF+`q>!I~+QO)prt#^b4>-KsH)+ZEuRBel}t( za0sM`)t}5}z>tXy89j-2-+hDf<V&s^~*m8E98VW=gGIinzW-MC8&BvcCBJcDmMhqW`;}o;(iw)d*_du3^ zzLZPPZy!_t{G2{?gp-H%P^o4UmahJWCkOQ9vB!t9_h=qR4s54W*V{O^^L5OdGZTIM z029ZJ<#g2Mh4C*EOfJo5%fI06yKW^Zq)0NOES@`!m!~gc!qhhz{@g$YKJqwQw;iBz zhi_+-?0Ac&q)soU$0%y)8i+w@Uz9VXK54I4>zopV^ccrmrgXL94!Jvm-n!dE~1Ox*^p z_t(rIIo3A&ZM6+%CHcFMvqE^-F@f0TIS#$Ln7SDNu$?wc##7nR9>Xa8r z2|_^UQ+#?q_YZiIUN`h%<>xCn^vgz;tyoUSOS`jiCW<%pEG^RaNd3UU4H!a1R9eX&Dyc*$BlfvWEKR9i5BPMU~qKbk32JCEVn%L z6tiZ&&-dS~<=J6lDAEpVe%MOKOS-XgdNYn99$NEM&{K z-(Zz(O8XXVNVft6tPm;X(zv3_MJ!+VG0L=1kuxluGm}YEmoVwYSEy7jgryP^ivB?H z4d!S8r-Y*8J9*;qL9G3LGbJS_`E=Q*>^^i9jl=2FhgtgRLT1iiz`E}@5Q&zsb<4Lb zm_L`riZTy@L=oyYvy?{W8ok5N!!$G-cgD1+i!aSMxziHh>D5~D1i zJ&h614d+nqnOMTw-!AFjAxZ%ewr^R_z`;XVu>5PB|Ki>_$dt|2&1>m%*Zq9((Q;Qw z_q`1gVfWVc3>-9=UB`-J-VxVV;`QvQOtBhQfQVLN49LM!32Lq*O*q|AWs|47y^$RwB`xS>zh52l;!|uJu zIDRI=Mqoo9;3@TKpPOBEJXkDiiAIw|G z!Q;nSHE#i1f7#C1v115?PqS^;Q4Z}t#`j-urhE5ZT-N0RGSOI^VE4~I^X-}ye6{u) z-gx&d8rH4MiEUrh;jgk8V<3dc4O4Wx7X{e8&}3R%g081U>EPUaV}?uUJh966L$ z%^MNYhe@6J4R&#u@4onolgAJ9{FsRtb`d!_x%|3oFV}YOM5_*$o(1EfwZaM}Q>jt~ z%BCg}J(iE5pi$E{G-+6$bSKQQJx7@F?mPUvV<#u}ALPK16ZjB7Nr5n%Hhssh+xIhR z(j*Kg%;6KceD}i-mT`tE7`f68T4VbL`*|9(r~h z4J($VYN-(I+I3{h_FaTk3gxn@(7bUAltehEb(j?&KTmPdO>Et@k8>`(h9onHi67pi z+>oka_e1~yAOJ~3K~#mP!=`V(=jxm8r1KS>DW!|4U#ljjl(2d8*R20xGhsr^pFNYq z`*xD`V^i+$cNsHYdx!kfd)V^JHmWshPik@s%5ktT5ec(@|9;+ne=a#E_i#KXhdl@O zk#1Os5uj4#OtQ=nI=mMUl!9G9|3vw$iuAm$C)uXS!}sLT|M5ZG+y5@YBvCoLGR>Mc zq<;4GEWc+cX9^1G)~h#Y?H)KKia5pOo<2o#Mp;ZN;AMom4Atl;wqyxSm#bK57v#ykrt_ z=Zeo3<#@1CW-Pqaai9IgI);v)&bYUxP`h$@Oe4yog)>>bBTA3^?2Q#V@?$58#pRAe`VP$gt*J3yFlK`t-9G>w#+Ex7&0 zo}?t^g6Sx`c5LE>DQ|J~beP-kxSKAWI}(sE1;-CDdcvD*-?NtU8S|G?xmq0_9QYTiRLUZN54$C?J^z1;W%Ez@`^7pt9#H+^ zmO#&ph1L$*wkbM!jJ~(rM8_U?F{JNvj2<(}O?nhJ(+mtSAQ%i_I4+U^|*nO33|G6qYhPKGP_*Yu91uu;FA?$imPjfy``l?h((E zV4mNj*TdTs4`sl1A=8J0+xk#yvd{;L}{Xt z;+UgaD^QjXePg-xG)%;fP_tGIhK!#?>14nRVI_qKnP+3(c|l0nVVl&{G_STE+Mt-2 zX2{)SOijR2h!zTq3h8p$Mcg}hC?O(kRmF35@xZQ%&jDplq{ZV{g> zT}sR5brBINRmkSaaT6(DDu5kTq$F9GmJ7vWJ9d20_x_C~V8mjDT$he%nS?A8B2l8@ z2!TMz%}Q4g2nGI8xEYp?LL4DlY;(hP*U|gdJ|rPT%oHk>OYw62jI%6f zfq;S5Q5czf(`40c#ITWLcyG$fM54CqN;4FZl0vi-<&sM}^Uz}t zVBDnXZve97H*BFQ8~75=AKkG2Af{2$?9uMjQtbMZgNVV_ZVi zt5c0sImOrOzGTbx{akm$eR14zj22#5D=W9W0kx#^xqXjG>({RU6K zktoV^H(3`nzzqb|UcV}>2nK=#yjZTJfQ3ZEUhI~I6$kow;pDm+ujp~#wSI$*{1W+2SHHHY0l44Hf<>J^HGn7htnKGmrnnuT2RU)ExiYrEz=H{>yDHCjxq((u&7f8m%@nyaqt#?wy?#z-p7 z&Ar<3_RAAlv348x-F*iyOqq^Vsu~0OT*mylvw45cLIyrMkT<5!XY9xcj2Zqguf8^w z>CV#2oXw2<>f|5K+>>?~9N}2*o{3;nZT2N+)4i|Od%TGV%i)E|WvvUuJj-J9M znX1(qkeQyw#!WwB6ChktLg{3Mp`(P0&hXXRuh{y_cHVmXU24>>Np^N=^73-2UZ)-z zWiu#WwiK2Mpp-|7>nYJjFi0ppjrCuxXX~%~IdtR%S=Fnu@rU*N^utf=+kcSak|G?5 zpbgMIW}mhxon4uvP#Wvju0te3xbP&UfL|i>S9WFR_Fvhxf3FLy5iKEPLaTO-`Si1oS-*Y@yLRs4$k9{S zflR8_XvpUuy~6GvzvBIQi%G9gg^Y6L`DWcZoJa}b@EJ1Ff&@%3brj2pBVZ*mc@WF; zRdI_43TzvNLG!llDLB55Pv6yWClGC5 z1(Imlp*@Q}S;pbR`w?A2N$w%igHg8q`~z>j{{d%;irrTWlq!=-QE?udH*VsGpSDpH zRTyRxhW4CD${@E;s8Y2KWlEK%T&Yw-rmJw-qA)_GY0|g_zi!*iuDyE^!z3?1myDzU z=d^7?PVOP*FZhU^yAQB)#~v~=GRZl9gpJ?*#4kH`kW{KHrOK9P@%+!&xpOzuK3Gio z+RbTHr#cp4S8)Wip-3;2Lf5MKflub>>#CEqx@v=0^ExiB6 z48Gg+Gd-{Ci83riB~#*9-1pFZT;25|`rdp!n}6L+RFtP|{xRb2kx|xv`58UCbf!s@ zrd)H|0~Fd8h7~05+scy<^yQpZ&1uo9EmvKA zE9=*WVFpAimOL?Sud zc;)3>(e)}e{&En@OyR(`pXh#J7g{!JP5;M7P@rM^rgdD`qZqFI@0=rp8T}y1g0`jP7aetJW1mQjp@|+ zMwWfG8IcH^*RSM;YkJbCSz}tZZpTAUJkQBO4|3f*lp{7v7kohH3(loMqZT~!?0CZZ zpLV_y9kwFqjeD^&Tx4D4vrP1GGM^t+}8VYy0ov#tFKRE>yG{W zylp=t#*gEsTe>mqvA)b(_!&7zb9w)rS=@I2qg>X#2Tu-qkndN13ifGMt@(yq9vQ(E z-LK-w2kv0S?3dZOYa{c%_<=`9zfJFJuHlvE?&teeAF}Jn2}Zs&lgoSE!gal`1N%?;zacRt&@lfs*+C|N3UOJFYdN^Wf(ZoFt5Du zJUx2d$kqdeyfkqHnOWr+HE9YTzV|xkw!fHHr_G{LRw+Q5`Nf@T_2)M^&4me!!#h6LH{A6X;ZHX_uP0r-MV&X&D!;#6poJInrec8MG#HL zE?v0(`l}c+@IfxPvd93;Kr_Fp zRGR^Rd62hW9K*33n;}Dnu=>OI=y6$R`t<3`j=g(9f*2AdV7NKm+KG5hmc+gYp{+Db zOA`dN4iGS0H&OLEP55xutGxHdIJ))d&hET00|pHy%{1u$=z}=nQ*^!TQts|QlzZ?!GrO{P96_ zzNib2KQ)T{qA<0aH0AyG-)G(%uhRLVPCWVSc&gQJ&()pUa^HW{Jm?WN zu9#1c%e%1VyN$d*cLCX@G6Li+gYC#gK>k(dFVU96Oam`DzU*Td6)Tjv2})^Jj2=$MYC4;291dIf*Efb2?o? zZdlW@c|&SdD2G9isO^@aQndzj>vAFeZoG<1I(22=fqkTArqi(bx%9fM19#ta6?fnB z5RpQMsNvdMD%Wq!U+%w?=N}uuHP_xia+xfie)d_COhrIxbTkTLfl3AimT1=ua3AM) zXvxUY<0&XCbm{s2AW?*g6dY#Mh)EncC4BJVXH0u#EXk(p&2Z}>E_;hIQGs->yzO2# zY+BFVclRbmN+?~vHp|zp=i|k5Xj-e9=koS9UmImww7TFDzFf7El}qN*s74j$&He~& zM<_g9NM5dD{*q-p^ThppzhWLsmVUv?<;!?+;&eK8y_Pj!d`g|{RE{1y?j>~rL@=FP z7Jf93cjqkTg=z0Ff9|_{|IO#TJ9Dv{a0c;MN3lpst-zu$*RXWy0vgt;M5USy>E8QB z+O%xWmEF3~s$ngHwh#8tX};g zP3l&`5EId<40_^m7Q8o!gFkI%@w~YdL`xVsbTkKY48Hu~7oK|fcILk~jd$lPb~Cn> z1}UKA^g#v>8bM0A`m9>_9mAjOPbfw^`p*#8+hG_c&0C&Bx2t-Qnihy1>|D`cggJU( z4@v3eNlr<^3M#5qD$Aw~8#r_-7nM<#3fbi_h|sioJx=DHRNmMLf zg~AhukZ?Z7Po1J%wF*Rm8dbB=XA0Q8eK)!J4t1KhMk`I-`js*C8IGJj$%d^5s9L=t zmK7kmbTXEq$<47n2g9Ecg8%0w8ns1h5fKrswRpe&VWLGuoDvaTD2`}x#1YXYBH9)$ zB2f{Eh$D^^ik2cN5fLq6(K_OlO^Zm8h%OY-+PhvvbXY_j(IVn_SNY#*De?Y_f97c0 zeTGvaVmlJmA|)cSd&e(w%_Zl{>AVxMyKK>-#TJpUh_*$vBaZ)UCnAovrO3NZbg^4L zr&uDQrAR~^DG_nbh)7f%+mRA25*0^87fIB8YP{r5iHI&1M{6n4B4N=YPDI3siq^Jh zomfXL5-k*MN5potguOD^+OKJ@Xekz3L_{K@b)jfoEMc*wMBM8|q9RVQ+x}Wh#IKhY zaU2otL`8H|Y!Pwni2FWmyX~U2h?KbFMvG`|i%5ZJUF5cz)?#ash^@uZVF`l1^L`rN&v~9b6roB6DN5Vw~^5d2*(zWaLa_Gbvv9&GY6pGkU z(T+&OE2HB?+_yVn5wEW9C@vPQBVvn4REucs*Tr^6k>mEAt)rqvi`I^aT_i>M2W9WR zALa5ZZjhBPXnDW5jFIutao3+}b!^kA}t8j+A&~IVw^2nYM^H zQ4z@(N5XEu+ELMtEsozkTHJQmMP5Hd#qr)9aYS^~Z5yrKw$oaBf0uau{`ZO2TEgM5 zY}v9!a&mHh_h!oF_+S0CLcR5rLmA#ujlFW=!^4h#r za^UAxQZ=iBjC^f@{Je3Q)T`T2ZW#Q6M4S@Q(cSXWut%j_)i$#8OtBP-NK|ZZEpfck zhed~v$%`Wf$^XaRdB;gnrR)EDs;avu=NX1!fB^={h+tOCi6D!ZGiF6y1Bf}GAc_HV z)-@}bGln&RIiZLMiog&Dm>j#i>b$={PE~gg;=Sv=t9SReynaSzx+|VKbo%2g9jl1{~?^3V(KNUQeWAE5SO zdR10PW$#|{;=3QptXWUVz{(y{+M`m=y!2XGxps}b_T+7nnO-i_?|N7oR(>VrnI&@c ziKol*hAQb@k}k)eHc4tcE%QHnK`JWx$f2j4FR#tMOR}=N$h5m2lI08ElOiWmPB`OI z*%SFMogGiI3f(;}ih(b1K1?#cVhxzlf#`d~we zi`J{U(K2IKPFtcQ8=m3Q&P?1zG$efx3dU(cp z8V7|^Hm)5e>e-}guoVa{C>t$dECf%xDCLVnDI#^W2v#Ayf1vJqUAQrK9C)>yV}yfDh-Fey6(;-JM>-t{y% zVLb7$m4i|?uf6yzPtAVK=L$4z{^@yz+;HP`ax)ZZn0zHu<{&<0T^MDXqJR+iG}abE zBtb77h{=J;?L?&++8pf>wrsRkh~@Z4PMY>CEZgM&g-!N7;2@$gIq()DMp)1Ys>FHg zl_$CDfyWuJ%UCjV(lHWTX#^^(A^%0ufEI;iIf!`JiG+TmMQmx$FIez(U&Rnz80}w$ zrR)UVIbMt_FS>-ER&V5hamTUkc7t)W$7A>3%{%YU!^JYH6XMXlaw{&qbTZjtzY1C@ zLKqn^lYpOL3R^6b&t}XJ9gzqGb zH1LGT?^F8vADTsaMh-by4%IbPtXf$`p@a=*AS&rZ>A>pk|1K7SgH|R*CGmbH{N$!h zS~sj>=8ZSgZ@0s_b@~NNn|dAdSH%$Va3zK-8Y~CL3H$k(itL* z{2$8Bq^;ov+-Mta$Yt5`YKCmL4_ylLX|LbFsU8asW{3uFCEG#CB-IthA}m3S^<$aSr7q6;Lpv22u>YZ3p)5}$P>PuSrhRYpp~o}&uoG}`Qfi#7l#Ru|Mki=(lN;LMNd)~Y_}fnO zpVZgO^6!IC7Bg;t5K%UP28%**?5SsP?5Pt7)KO&9v!q;7hsB<4 z8Gs^*{ZoJNL(#$Sn69gW%-fDAEGYPJ{I*t(xx+-ureGgG9W$}JW!Zj_Vvv&J7cHdB z(5c`_{gE;uDW+AJtip26oNz1?&c2GhwjE4X1X|o2LRJW@7@)9R^S*eVV2LRNLTqet zK@0`Cq?XM3ARA?qo|R8Uc_E*?_Zp|1@-s_U*U_ox5P$G+2&uFLNxH2B+p-xkas>Bv zxtyCWJBOPu)kJY99c+P0qkFef+Se^-)S(l(cJkSDec)NHoqP_rWM|M4Rows7^Yrc2 zB~gg$SsF{)Xs%wtgtIQDy20VDTdw8)yQXr;A!8{m?!pDiVr!jJ`?dhDSIefoe z$?HCl`|iGnI2kAvGw-Br#x}>c@hp{Kfv~VpX@wkp#9>@H<6cJZvpb>8GJ0(_fcIXz zmvc`$ow@ISj84m>rAd(+$w0Jg^3=sM3smvYUYLlL%U{nqlL>#llpe*!xX~!NT?R1W zv{PvMjNW~R^6r=Gd1A_O^vv@ZI^YFK>I4^uGFWiI;aA6_(rJ?&pH5>skZrL%O-&M+t(HV z03ZNKL_t($lXlsBFIPVBu~Gowe|6md?q`#IQt?&dXW|dVQnvo>oqo4zt*NQ0AvZU7v)`{@zn<>hy93bH z*2cnx3mLZUcA#tq3>nDw+YX^q=kE0CGmw#E#BYwVa(1|Sz6-i_7eGVWuzktk~dF9z z+M_~dPCk3>yF2MNhzhaGF1s>xNFNR!u@8N>-j?Az59R9xKT^?e2M+nmzEo~iN$1Yx z3>>;MhmIS=zI*OSm+~(3?!6WJ?|%S$>^_{*!aM?vCG&zR+S=pP)W;Y!WC*=0E9l*; zf^D`Q%6|LoM}B@jqehQntIA3S^{=F;q!U{Y+n(XO>_Ud^(4|KuJM6rJiQG8p?791H zt$jm8Xs{w;J=7jN_ zdeYHouN^C#$?)BFq-WQ18k^&6yTc9)9z1}7{rWI?&>#v6OW5at(Offi3cb1)Q`V`3 z{sRWmrJ|DI!*^lCetR--U@tm#E~EdTp^O=K2)pk*jLb;j>PU{Kzo%z4G&J!2_usS2 zF1rxSpGt(L<|q}Fed$+OfumiTnp){QXlu&L%NRDKA4^xPVfFfY&N+7?gZh@^*s$Af zyU^4eW%-J=oO;IDj2f{wVN2*cU?8DTm@mKlnvtUp6A4A=(W3_?h53B)+2`!M z+n$_s>aj#@he7?fqI2g?e79%`yX`xI2@_5uGX(i1`Sj>n$tR!Br+420oOb$2G0Tt_CI;Ww%EUsDWzDoY86VmV(5;<2P=PcOjrcbHQYMwa+b7q zX2x|_kjbV)y8&bnP$>la23PO-UM^o$TzlMh^~K~5*pY+A{e`FQyA?OBi18K|_X-6S0tJEw|qBFx~s^z_?Mv6Q{TQdq5dqr4@X!DTwu5 zEVJ#@8i5v4k3a@#4IIk z%ZxW79+t8JkH-3Hrd@X2M%U6&cp^Tq2s~lhm(ep5j`rdS&%AMp22mjMHhZpzV_SGiOq4`CQ*eVyc(y&y zHARdbVEJ5!N}-gM(7#nFW03YdY%6fv*=UX7s3dhh@H#BL{t>IHs^aOVpXP!KE=W2} z#Pg4<{CQ5y{VIhgacqpVpomHUP^AFR1KTly7JrgS%n?EAiPi~kdE#%|-^vd`2aA(|*M#MuY2Ukqk-BO@kA==WOAXd>@;VF+-pMQ}jpL~XC zcic@*ehFFW%J*sp0M@+RP0g*e8=^Wtq-O5R3w(SU<6ZPcM1#T46ATRl7;R)r&^k&> zTQgb&@u0k{jLeL%xlbh~M+`rFY<9%LOaMwH6A856$q>&c1{Uz!%WM^;VdFX;d+2XG z_1x<;G`7;UTThOea6TjV-<7;@h-dDd$!9B?xbnKGsQOwiz2bW6o1@IU=^Ao#a}wdl zEw;t}*`~Gj-)jI1Nlf&<3WcAW7kp;0kKw6v4E!=L} zWwD{Ao^}-J%A`LiC4`bJ&4BjP9s9okccu1#AMci zpA4g%fI=V9?W|d`jFnYYXdmQ>ozBMEM&cU6etvOcF{d<$X#)XlJA}eZdXh}yG>%Fc zn@|a`6*NLLIH(|{Csk$YAD{cgC#~)RD$SveAM;$|-icZ+X`0@KiJoWsGG`7QmBge4o zuu2|&^dY`qvYgJHD>(efqv%oI84nxRa|tOZ$WEgzBbTbGmCU~PUTPZah)al!++r@i z>>TEQ{uyt+{2Ep`%pM1fWuM))F^TYP^;~nw#gyb&OuhI-va>Tu%gV%3n!5FCcxLts z{Ia}?t%mNv!G|A0wiD;0_uk^&zkf(mt4n@SXAVE+D7u!H^2_{>`DFf54ms{P(rvJC zQ4;0n@4w~Qm)@eTT^Kof47=_)3=y+BbR@>IWy^T%;m0^-!f`D9X%RZ+^1?IEQ8{=R zg9rBUOALZXB!FkMg%ybM*tm8Tvz~gEH5=>bzwIs@IA$c-jz;1Qy!Of*-urwZ*@Y#X zaP(N(>(}z=Q_m5L2|MgKoDri(nxYjSnky$xPHqm$ad`XnS9$C8Ik;kjoz4LV9>D&4 z@5Z+u&*QZ@bBH+^j5+iuwi(ca+O^AhVfJi(UQtc=9^Du-W-PN_c#ETsI+)HSxh8)y zR>uv~r?Rpk%*@;FB0oQer9Um^+H0rK)^s+??g0c$keRwuvIf?A)R9{x=HKq950gK%H&OG+ivxwMeWs+b# zY&=YXk z3gx3Fdy}L6{t6>WQJ3jB1_i$dQf(HJxXw+^lK^@;<$9CAG59{nT(@sB|-A0aN*iPG#nOlezQuOQ9mEQdZ@yMgIm~q>^+;aU@xK2J zYui{Bv^3Ol+2vQU#~%AqT3kvr9;IKOo}6&}@z~j=0C;HMee3^NX0Wk==DL-fe){QT z<#u7uz4v6=l&kq=>Cap=@eF1^_#pQ^^f)I@yaFqdL&$LmMTDJq8b(8H3zH{bjLI%z z)SzqbXl*o)PxmT=L97jfE|XR>6~MkZZw zIWNEXAm4vKpXX;i&AFFMAtNh;jWxB*dhRv$8?i5?B?Ul?`sGV__0{*8@zl%oA3TsO z+oiI1IgzII+%o$a4mfBOPRPNDwQ$ZEXOodx%=ObRA}cG+_m-MMgJ9VFgV!!w>_5zc zNq+9!xqc`%2=yhW=_Jvz<=2gaq_t^0Q2o%yS2M!+_?V;-204Pa$vP&sTEpUruVnz~x9xpO)>mPKA}9#vIU z{=?o&L3M&`ct8qrW^vhq5C+e9WU zy!F9H3@FPZ-qy&~Q?8}5?;wsn;b?3X$5R>Pl=fu1q1*Vv>}EBYcuxK=wm{f}B@4fx zK{C1Rp@%4S;tVXya8}M&^od*+v(e@oS&Ah zB0gv^t^~O@{wfinv`YmUA{#+Z8fcS zJ_TI{vH$2%X5h!>i@7iR&mR!Qy0sfgi=s75$}4lI zYES2}r=KDtJz^++6p1{oEsnq~_D7gf3fs2XSX)EPb5WuUs8Ml~(jcbzDFJYlLW!50 zSjG3>s30J#{eS)Hdu86MO-s4VKdGL_l+XO|bW)8cHOJToX@1I#R@(O}1_f7M0>Ih< za7*z*DgT}cJX|TqCvp7b*^>EY_@56gA}Bd z+{X{C{-&plz!L~b&uZ$u{R7L#-^e#BDIi&0%&opMh9_z6O4lg*gOycS8h6U%25 zFyUw|UV`*I=~=W02(!#yR$^b1QsW{i;qRdJjD)EH>z3ftYvG6U75E_Chxi?Cbk(X= ziQ=d&_Mc%+Kx3h-|KdgXr<&<_!Ryf09;KnFm9mPSW;JOkN(-}SYFNvLnl|!_N^mUO zC~_$H;O)1VdH192IpRQ~_0`yJyE&|Ywp@SxYd)~?So-64oO1C^Ou7CB`gSg$X59iV zx%7I>R)D6X#wp`jpXL$5ek8LP}#iic(tE-Oqy*+{RkYKIIgg zF8$bNXiuzIJ=#n4b|gK+7NDaoJoe}_)Y%10J@+Is!>ue|x(prZNlOgUY>TreoJMJW z4y(n_VedZ(^rm{ctvEfsP@LEw;t}_ZH-QjTtj0L8+94IR5X+q`6=(|KIL);bOzckpKB&i^jQ@YgMGAa)SAcYb3ZMaSp7 z*+c!0o@;Q_mtTJQckH#r{(mqh2z&flxm6|{Y$KLUJlalHW;We=bmxnY-(!#M`{TB^ z@WZNVMt2>9likEOPkl&J-9boJCYDls@$p=SY(0qMPdu3w-+jn;_dIXbOO{JC+J^R5 z;Fj`mo13_4>NIvAF^=8#+!^9+G}Nx6p|Ob>=buT$t>x+07NC_yI6ap%%cXYhTH4Zc z30Wqo+p)uB<>wM_s%PW!4P=+)^5IttA-#Yur6nfgLn#x&u??M!Ev8VVzO{|K!a~9V zs0e-g4I=ZsWsDlJ2l)jB#L?trr1Sl{Dl)UOxapqTIsJlbc;SU19C^@wcq+7+7ThE! zL|Gsn(e^g-i#t=dZUuF#YstzB^Tyn-NiQs=U*%Tx>z>E_&);Xzz%GboQNMaM-+lQd zcTc^Op*{2Ye*QviOH8u67UFRiRM-@QC|LQ^0$zXf9j4wli`_u*N78*!Tvr#&RR>2B2PCOQ4eO()c1^J{o4v0l*p8@pgSIHZ%yv2a7rRcClTWdX6 z-SQAS?m3dYj5NX_oAiQWPCnsaI#~^zb?ON`{PeR7>RoPtU}DbO;u73q|6B{GZ)|0v z3juADBs@E2kz^JleqZ-Bl2L+I4vD&ez!IQH`}4W-`|a=OyZ&sQnCK-qe=6gfxwZg` z*ocvaOHeH&!^FQjb8wBpx0@7u1VtFXU5)Qo@ry#N0acil(mww4 z6r=;4RRY_YW=U?3opQgw_F!(_0xz-g_@;u*q(4}jM;*{{sbsPO+Jw$UVIph3S6V4M zQC+>o{{VAQm3NdKt_B?joGkpEck6d=uRa`m!PR^e&pVqcGeRkZNz5{n> zK)jAm=e)}~r=LPvQCD`~Z8!Ga{{W`WxSdJooKL*51}~#C3fQV|Pi~*}GW+at0G?Qc zB*qU5f8wKg^BJ^T374LCDOqW7{@F*;y=x~fIQ>j=vTdrXH;|E$NpWcbBX--Gt1dX3 zZsp}%Jo#u`m4+n_ox1kn(1S*D`B|rtS6aZjx)>KsyPa-@g@i4^(|!W5KNe>I@4xme zkG$|EcRunc#g0O$Oor{U2SZ+ekMsU|DrtpXDK4vE+LagJDTv}wR@s;7mrdmC)6S+- z@k3}Uj2n+{W{n?=DHa)7MRY4GW9Ibf+%o+<#vZUY7oRqsoT38O*0yuzq-*I~+=+W` zp3KZ!?_}=RpOBv0g;NgQi_w1>&5SEArJ}TmufF+_BX=A_B)fnfJ$m!%%Wt#G z3!29sdWh;ZYq(>^G{PZ^J@(p#(MO%Y{O>R1+zF=;$?HPj!NZtz*6~v|r%|8@p#Rbd7lCx@%AxrQ5VypuCdn@1$<(9qCG_n~`n^aRD3I;1=6r|0MInwK}oB2w;jvMVnak%W85vb)~!@ z3s;NpzcKu!0n56!Y%B@#zl`FGhr$Ua{|+i6|M+$N+Wdh>0Nuu_)wL{NTf??H3?<|P zMr9>=JAX6A`8#a$FeMn7%$K4yb=50bvUCOIeFo5_xG=F*5(xfTiAeukGjnBXQAH{U zH-#suyr+IR2z;s*571h06ex@mj`(5vMAdo9NN+4alSU{(L?OyCK@Q{q4MKhq;9(vIi4tgUG!KRcbQOo#f0cAA=+&L+H9c!nywwA)ud@OCTVcj~?a|+N}5Z5CwFCQZ$l3XvF@x?==m4^B# z&8;q_owLz#p{}lpc-$o;E1TThJS^pbZl%7ViRM;~wj4?da!?Ybwyqh^GoFjQ!UA&A z!!*{{(WWg*^D?QfsU;(?h*&PuAB0U@lgj4?gya-$DPq+UuPv9A+`()>V*F{tP!#s8#bs|^Y_6YkA z$mOK-F5{>P7jwiu+pyrvd0cVT)hw#2 zBxp|*c+$?JGp}XFZI3bS;U^fi=gx#ldMHyt;J@2DT(x2~Pd`1I$rql7(HsGDXAZ6e ztb5wI0TG=n=<#zlx9|l1XIMv`z)e2tqtQEk$~_9vw3;1ky6YWMt)ZBzhK)%-lRObMnll8VYhFex9^oIbljVbuvh721*L4F~5`QYj(P9#K0X%>(=7Tc}Wo zw6M`M))K}EE4p+_Pw!mZ=|`giT1eb z>*{)lWfpnn{k8q``}MJ6`GpNZ=J>yA@0Jcft5+=Jf(tKZ`O4LFDeb})S6@Tl0sZ}= z3>UP=tIs^kt#{o^yEyE*?;qvS5rm4P#K?4VI<@M9)T%3oFHS+cR zg`6{S3S$mBh>OlY4TWOCw+lG($YaRL$w%2~>^J&AuDW0Xvz~a2C!c(p>iQN+dJN*a zYp8gKPkv!{uDa$bhHg6uCsEV>uiD02?9Z?S2vmM<${#KmqCqLw zyzJPZoTOL@;M1jJE0d37NSJ*fph01we7XWG4=sjN+Ok5R6k20S|5J!u3Boy|{Uq;A zNQMQog2F6(6R8%0uh``?%SGcLPOGb|2(?U~&`1oJp+UfM)B&_4wIF0Z&z8 z$dlwcS^42u&uwPohBde9eBw&Mhh|fQjq;?L}g_GN> z6wWD26#gyxO=Y;uf^?X~)FgJoaiDx++n|at!4DQhixQ;OJ{(G!kyM9pNN`ad_8xpxkzlM;T+Lqz{e{05zBk>j)sE;ZlIYnfrJLE*1WFOM_&o;(SKg{QjyC0*zp@puM{W)^{ zc=}fq^4(XTGJE!mtXp4$la|Mb0}o=<$lbAYoZ3}Y-1Eqz{Iql#k(?s-+Iv3^J)pno zdCEdr8s)|K>hsTe;@KBzYV+7@-;o@6;3(28Ot?@5V_}?VTP^3GdlAh|QCw_LA@gJMOvbVV10FV(Qe%WQfaaFTKJWfB%4tydn-h z{BXA2W)LCkx4e%3$0i!12IJznEnIQw)%57upXoDh=JnYR^1vexbNRK?$#uXcMompM z4?p@W7hW-qZe>MWb>Sr5dT%F&5AMp;tFGqYQ!i%E?fWqOk_))$p2wMX$pk)m>lL1O zb`CABLz@m`wC+7(?J)-R>C2rD{tZz!p>P;%iyd~`gB^F@6YaHg%3r53d)5nFIr%iY z_3qDgH_aq1Ba?^ke2f=fdX+xg^e4wQWZeI9ZM(((RO}ZV_YeR=3rZ^)7u>{_w z;QWXIdcM{NN+na2t(47z88+c4O!+;Pl0p3Zo+Qu;h#wSzN`~1pMl9x`C5=cp$;|~F z2RTVxuOb^4Px%I^2>7Xpy8XH-(@CVkcS%>r} z#6?lt8e`#)KT@}D2)3t*X`3a>R?rfMczd+Na1=b`4I8U@W6oqX>Mxep@*N~#d-4>R%)^T&fD-yOD045SMb%hFR^-UGY9S0ACq|) zBQ2!);^Vm-KJF+QL+NDMnn&-ypBo>2o|BIpO`7is3KlRTu=J;&Xx_MyWh+;)p)H+$ zgDQFJwJPqq<2Jf>%_l1@n@8@upQBGZhP1X?WlBgBIRe)`y+!kJV?pd7DtvPt)U_SluLq7evo~cvL;-UK(Vza9B$QHE_(!BexJrzra{8d?+wjr$7)krs|S<_NBQ=u?_nHG7R7$L=G? za@etxu(juVLE^NvG?E?)(a_LDL0Ku`a0E}ebnn^;*NgMx_dl|F?M8;}uoGBNSXxAG zK|1SKZ{*WOzp(F^(L^kJ%lNRxfE3&l6o>rLW(tzxJoVrmOugw|;$So;%|-ZgsPT?@ z0V49rKDCeP3~;cJ1oOM%i3jfGwYT3Psy)8`^h4%-HJ?}_Mi@+~{<2cMl?0D7#D)-E<@p!M4U;m07gp6Mrdcns-;|Y^-Nk? z+KtSlwtNk$lv@w>^`D3Ki%zg2h%&1|&l7Cb&Wa^pam)#4Qd3vY>J>ln@|<^RiMk0u zVXiF*BL*tr4p8$v& znjK%0$lo>qIFh)>)Th+Z43IYP(FBLIBzet(cIyCll>aQm44NWd0O=x|hxR5o zPtrqYo`WBDL(r}Vx}62{KjHPi&m-n(YB#KmRx9vSK)K^Lu+}8y7Jt=ZTkM}`ia1TRD|zvyx9K%-DD%Ghig(_6j?9Rl zwTJE4h-hplglG-g;-JHh=Buy1;J6cy#qxxrqOQF8_xE}2F-A-`{?n z!F{@e69LOXi(qLNX{%+<>#wr0u8CuhK8BM{IML8-&HIM7m`?QffVMh4Bbzzzyu>ZH z-bhAP0sH@DEXSR262~5UB2Pa41Vuh6dJpKwv}-Qm z$it82)i>vwbO1ZdoEKhT%H>liFUch@7hENP#pfS=%7qt9rm?n)Ze5Cq2U^tsca6Bk z{za@qrM_iZe|%wxvJf3-?ed>kRbA(&)O!Ap`Cj{;DjPH5C8W_TWpp3?q5{D}`(BW> zE0(dLrUtD&zWeljKKW`PvEU9MuiL!FpLXH}LDjS*tKCKo${`3=m zSi0V1uSguF<0e-T&?UYl!ioi7&u7jXuhW*O?$w|n8qf`h28m-r>!w|emb*$2RS3!up9bDU zi34%}{uJUfJzGknl=gF=0(UPyLn9!r&*~2z7H*)&DlshWCbXYjd_9K_U00)&0kT?q z21F@*EoXDD0nKcnA>aX?@7+_PvBVr%lqu^m$=U5J`u0;^dg}wC?Jb;t)=B(*?x*G+ zOaq~GJOT0&8nI}UcG)zoJ~*ESA9Tl9^!<07eByX^-f0JpI_3!8oA(iMKX3E14?g6$ zBafh_xeh_|!TTRF{^YZ$t!qTIHk!}De_Ja3{`V#xv6gz;T7~qiVzLVg2uBolK;Dc| z$yFzKQmL^E|GkwsE%mFp=IU$6DDKIOnKLNsR7zHEDdWZ+LQzRMUCYbZbyz><%zm1e zU;cn@19xHgHWmEs&YPGt@p4vG*OQhOLQ4x;8*TEynGGI}qw!pS(WD%-)@Zk#`lfnx zIK<+genC0u9DV$WRQ9S!DIVGUGV%Y$l)sQPQK^iaJRIc`ZD|0liMPeD9UI3V+XaV= z%xv7YX0teTg{Fp93i9*GOm}c&t+=j6VN+XIOUSVag+rJU4nsn2X6`z)#^30 zx(>yi%jjAVVfoKXX=)Xm^bER{cO@$$ge97|r}1ouk%u2ii=9h*YYQuuE+XEpaBT-7 z5&HM3prv*l>(;CTJCmZ)GCCJ#Ah9N@e*S^)=6_3VQJ4W+m2%{fM_^~>p`@Mm_6Am0 zt)V_@k&{6!GX=uT_>TB_Hs#kDdhDlMZt-@&$Q zL@bmFv(=!jnON4J+zeqw)e;&SqNa^4hfZC)(K$bzpO-A6wH-p4*>vmLm8_6r-HM-B z@XZ&HkwvF2UD;>kD0bL=S0YXbPg+^Grka|XR!GaBTX{LT=??K|6DwD)p{X^F$!z z|LpU)Z0hYCG-5}hjdd*jVF7V3%7U+dWZJarIq%AA$;!*Y^3@Z(EhGCs&y+(>Q7Qd< z74rVq-!SKuS1C(tq&291Ncx!**j_82Gtie|Ls`ij&wy`Gkxsrb7QyDVT6iu~j`D)1; zy7%6SEXSsM_ud?O=ongCo9WV{KM`Buc^YMdjf*0R=e2Xk)SLMDn`KPB=P_FA*Rx)= z(Na^xl~ZSO>IIV+zD*^&@3SLMPP~!tmbY@rwKouPqAXwbGb*cuBgdb_D^EPkoA11j zXdx{lop>zDlAo5sj>9P~&S$|FAMnF>1E_0iLVF%r*@g7z){TXWs@QGMy%;vAKP~Mp zJ-6=fKZHO}`CrFxWoZjb+dw)wIi1;MNDsdJ=uNg6SjHD${y=G2XVPtlmCLIr%1@)B zXCGAK8kR3xMyG--<}X;m*rU#3t8OKPq>1-GoX7BOdh*gMuhW0vHe_amfjCM+#@S(k z;GwKI4UH{`I3Vq`$D_n`9LtN*)Z9wQaS$tlWm!aHZMfQFW6fGZmSq;*;^Dd)SH$FM zLJ|o6>oo5c`xEU?27$qv(|GojKnRcdpMS_z*WX2_PDRw$)>2V9l#4Gs1Keh&Typ~( z8|ul*@5KHGjHdH$gL&<>*IBh@Bg+;oWRC+6A=<;$!W*x@Mdy6zedfX3 zdfUAW+Fq_dmvKZ+}Xcic+eo)^gO*M{&rZBf0J7JNWXeZ>b!#4NHIgfnE0- z!I@{D#fR_A;mH@@=JtmkCN1nkBL%i4KpX4UY~ZRZt|y9xg-2Ukl&fyOgI=W>y!6BX ztw2)01Kd0NZF=_XOI}Vk=be8RUw!%spUiug)isU$vR3oxJ=1XGt{-Z3S^WLCOq%f| zvmU*h&pw{Z4?q4w{kj^Sd;L9T{_PPC+Ghuzne{XcjjjB!U@=FXd@2VYGLAME=Fa<+ zW$Wu1G3qZY`Qj7a{owE1_xO{1{^=*&c++i^bnQXS>eUS0c`yEY&S@-P_$B8~o=(rf zJJC}6GaH&M?zr##K19|wq`*`Ea zmGs@JlKpla$jYA<@V8e!Vd!={vD4PQ$lQGhmtHjkFOrYd-a?C)!Sv}@(zVED{0V1J zP*_S?w=#}BH5Oz?w1a!z_-D3Z^rA9-95aEncF28m<&6i!n zh3A}s*V;&7NpDK>GeN}=C0JeyV&$XpNb_2-1+YWJ9EA||-+L1IoaRJ;2wBBlIQ^W{ zx%1&y7`6XsV&bsfZX=C0Fvj~FL8Fv|i^BFicG-O&F1+Y09)EcrS6uV~4UH{W;S987 zu=~Dy^Xwb*xbm{8Ja+fZto?ZfPds!tx8HUnnK`-K_rTxie!w0klHtc(5R01C>$vN| zr)g}pm^k4iY+Oz{?kM)!eGlf&`-l~~F?8pB$;>Y0 z>~sH0eM2h~C!B`sYWfZw%ww~jrnsUU--Z9@c7p%TeCij$!479}-Stzs;;Jcp`q@Xs zy*Lvuy`1cjV#3799C7>+j2StSgAUw_D=(ag6;7vnMSl(%xer+pkH1bjkC``3=h1K) zX`u+0Uw8}|K`sbkQ-G*E#IjL%y!iZV-gx^xVy&&XRu)%WehHS_#zXhq!8hOiK)dG= zjcLv~?|kwy(z*Y>+xX(s&vCU)tUb_6DVH_!7#L_}*Xf1GI% ziHVM`mg_D)L5@4;8fk5-m&5iOCYRlCyEMkzB-&ml<3^5?dGEg_FTXlV4m)mwY-nnc z##mh9o)#Tz6whrJH`*#+zx|vXHU4zjsI^R;JW(Eae3rDh?Q+ZIC(ETb-z^(OBNYHtUH2a=bLM?5KQH*Zbn3OWEZX2n+-nopT`ZF( zpDz!*__3_`@e?^--i0ekBCE6$4rpM#^v(F12@QNXH1sXcwAzQ)pGJ-Bjn7> zX2{B_#nQh#Tb_M)uC%(YxUMT&$Hntn#f?@=b90sS8M>#u@bXJCf8Gnyd+7eMdi{Et zKksGPYwRhqz9A}Fw@6#VDj9#+VRG7pNm3j4L?kY*+aR9TChyFCLe4tpeAyU_%PHf> z%e(KqEpg8iPrLt*z4MNA-(sq*?Rjq^ZfppbMD#?%sRuoS8XO zo_WgWBmeK_-^tliPLzh0Ei!iGXu0c8_ej>u$;Op)KQ zlZ=^ooILp8Uu4nSPssQqPM0;?lHz%u_U1yzFv9dmHhQPcI=SbZo928t|TMbY?CCDO_E3?q%E12jPHxdwMt8}Ra$d7 z@%?6LO}0oXlNIqj5z``>Y>PA|Q<65}v+%|9jpTe0&kyHHPJAyVskUZmYipC8ZAnRF zvSPeO$)$HnvMnLLG2&%fCDFW9TGLtab1kxc)m%v@T4l|`+0v!9R?htH_0r~f;`>dK zPHmS|I&EiRu2oXWR%uNnq%oC}jOUAISHk?-OM2X-W7-e3OxMx=j-4v>0Q=&$US^ zv0V~vEz+7yNivhQtA)u(Hrpu4wkAom+5XLXMtqU{{P;Ah8unlM^FZNw*~>mGf+W=UOF|Y?4GvizIV7`&;9QF-b`!c1j|VuwzF=f`Y~P zzGN~P$!2rGoqfq=+a%G}D2ZfJ5}AyoeG%iQB$IBIM6ykq5=m*xWF%>P@gyVJY=b0| z+oh$oMVeD-$rvNP81W@5zGTJN6+}ctrcIkBbLPzX1bcG7{3|5X^WJ#l4e4MB6eAz6 z*+3MC6C^I!NV(RQR<>>2&S_)Df)gX6VQ75?t=rf0!TJX3`VA*mR79}@T6|V7p2KxF z{FdgN#_ZgTS3L{_A|jxyW5cKjQ74Xzp>^kWF8JOrm~z^e88f&S$>z1(a`PXU^WI{# zBw4m}JLyywN=-gN#nB3rwQ*IRmnPAiCR$QTQKvZCfw9B-K(?9n+Z!=%3CfA!I8a$z zN<8Y4%z20tp-4IH+@s(cW2t(4!^&0b=skQAG1o=K97c^8#Ps>gS-ZB8R0f8O8isKk z9FwKBaWgmk@)i~>UQDbw#+Gf{NM};GZduTuK^CJHaw3Rlc=W#e*_w5@^=H>n;uz+? z`YgY`<@Y2hCbNATo%U-C*Y5fdZQ`VI(0*;2B z^<7D|wvfwt7;LPjC&1tr6YURX(CgQp-#pN{|Fr+8j*DWL0dpw?UKxrIp z>s}mdZ{QGgRPeMzYipLes<0u3WHO70A|8$7;ZjrEi31Ov$dA5%2|vB|8pe$nNRjFY z@1)wj_RB{h5hAXG>k1eLw2cE)P7$T99ehfaP*M~yKNvwwoT#gD9cyVxY~R4Q&pm^g z^OxZ(7lH(((=WJ~tFHWCN{VAdj7PC!=^_=SxQ@n+Y0LT+DW=$ofpXZsb~#5Mb~sy8 zLdL|X?>meyPB|9Gu`bG3yaXc-h@f>5@wgLMi9MQjtmNFY&*Qy?tMG9UW$>Ib&i~f; zx%$%ci3p$!p0enGh@!YCP8hK(Dnhh8Mu<6}0h}T`uH#WG=Q(JxR>o+|wfLcca*Bu* z#R9gC_7+!{NTdSSF^IBIQ}U^fX>A{;Xp`=u(FhWa5DT;S1!5%;kbt$%Eh6S%+n$e8 zcTmKM7sqXgX%I(fZ(&ec5s5^|)6t=E+$hCv3{<=A+eC;)qC{0la2Uj&ipFtEh`5#p z)%TTUHgpJ}!t&r<`{ln>IzYsPFfkvSC~TsKV;3jS_lXz9DeF|q%2lgzkC+G|tZhtj zOl23kCWQ}{tOnmh92fAJ{^;XWb*<;RE3RVWd$YK4>Pt4vTKgD6$YYxon#-p79d z%R^7U!Bs!|Io&%&aY=FGjkhsk+`)Y9I~Otcg{OIN<~$4#RUVmKHdv6fRiurksI-i# za+l2;R>6b;q%%31(@9DzijlNUU@=&w%?;YDMB9V}RahS5rR9`XMET6=r*rPPXXE1I zXqQrFJNTC4GEAKiF@-Ez@u{uu#FF)!0Kv~CSh03J)pfmal!F`KJ%(a}ryoLIEA3)X zWQ~oGv(Sh(=}0?KVyh*I~3lvdujH!W(oQb`XR5^km7Z4~TcF@lJ9=&@7(96-F z42z3u=VW24FD}H9*1I20K8GyKj}H$Q1%)R-KMj~v!VFjqDxOy; zbntx$p_QLADr|R<4i)m41&(Q>op$J@pXNi11r9HS4is{}bwR_+pG+-KMHt%{EPDB% zc$Gi!wLi*+$%7%oQeHv@x*g&I+R5YXT4>v_HkPCy6dm$8+d-Ni-xhN0W8VMw%coLy zV+{G&vx6NMe2408y_kRBTWr{JF5kH5yIg+b9TewUShwSzAxfnsR<~{WXj`upgg4cDP-z{2bl- z4rOrvdM-Zi8=U;vBf0yodpY@xuhOr+79|-RH=M98zOl=}6A%BDhaY>MKi+c}(TDdE;_ESh9vAjyZux{^w$D{EdsG61?{Aa(;LJ4fN?-!6~Po$kji%jI+)-i%!ur zeR_1p0FOQVI0p>qK{}B{i9>05CnULpg>&Absyqhbf#1f@uDc3VR>ihW8=19z4TA^w zr{AEV%zoz`2EO_V>z6Dg>S|(2(WgfpQ}6yWTUwF~=+%d;C^EQ|mUiX(tA5DsH~)&p z#!W1KdluDQx-hh71*^Afv}>1ltu(&L*$qd+7(XR_001BWNkl8;G3GoQac zcn^+>B9g^%!#JyO3C@Q)+fYe2O2i5H51a@JLj;93*z9nkjG8!^p*O0RMH+IRPgFZ79CF4%YlG`J7#yO?vdB!FG>K;(dxB!8h`wDS9Cym+`N6e6 zVdu8>Y*@K~9W6-?Kkft?w=4#g!H7)|TE2V%U-{|}_{Fb(&!H2CgHpuHEBW3PKjsVP zTtxHEZ5)2kXqGIP!?Uj}D?)?+xMMW6j z$90^J@sa!G9}*EEl}zHeVaikf8w#6sA%C@SoY`IM7Va|ifC&_oo7Z0; zcTITL@Gd^0iWxHUpx~1r+04u0dwT*73TqJFH_q?_#uLubu>J~*W0?O%hlYfdWd*Lr zuKDO3w zn57-YMep+45codCW3@_Ipy-K^hl^_en_b3R;d5v|LJEHeV?vx=t}nz3w||Dd`Fri% zFaODsR|2)xfA6}FOgsaQF5{##zD6e6k8HA)&rSI<n#IE)xQ38!m^EINS53*_9D#`~B$8}xu zpp*M0F9lU+-#R8d6hH9b1Gu`Q;!%JWA_z+eHc}jGCkw4R!PQ0u)qPRndm7)mb%N~x@epO{+U>+H zxRCOb8G|1Y8R8x;>_(x7ZCl5#>&9J?$P97QT0FJw0{oqv9a z1m%Xc4;|_n^1$E(V@C&l-~m|+yscuv>ZpQW<`7&Q6pj>v1yJqVCj?xEbOeyLpBv=_ zo26J6U$FW4N)?_#ev=M+HV3$Qt4{b#eVqI~6&}Vq(c6tbY+WR4$869SVa*GSC++Pr zwxtr3MZTQf9^!wgnEbz)Oq!+3R?@RaPxjO~3l}bA^5n??G&D5u;DZlx<{4)O?$E-Z z2}{&@52*ytB(PNleIG($b)W_e;jucf-n3tWceOa~`q}Q%{?`FZFv{4`NPE30xKPx- z4UN#wUbt56enEaLN}z~Pm}j&bi-Dp?py>FjgI)3Ow5Yv&dIt2y^&5F|`ZO-Q@SAyq zpKWU}DB4vuRNwN}Q6>0RMGWEl2?6O*9aaN&E#>cj)_%McM%S)~pZuP=3!5pxi!Z)N z@7}!`GiJ<(>W}^M?JW_WTziiO@$g**Z>SBY~+oWCy{Z+nrSX4hZJK zDR-al5vpLJBOz4K3Ziy3%LhkWE#!Zr+I?PN?+DHI!GiT6y5+;F)*r?TzqhhGFuCQg z37IfDF6Fxx5q6Q00)@QEw|&oJB2;b#Xx!Pr4cGmQl}pwkM8NpySP3Vdb0(*pe5{2$ zkkE!wuv+A4tM;}162z_s|7nCj-+2d5J@OO~2W6o&;eqcoPWk9=%0PP zrBy-gCT}_{sD*L^XAbSh|!YIqr z5*`sD7&rL`)G=x1V{1mB2(*`I^ixUFw_iR+aj$>meE^IvIF7c+_iAsGc~7#p4X?ne z8nR&IvRR^TG_Z_#Xgow*jEW%Iw+CubHpn#uRc){Fw0|EiA`&j7*+3c8HoGkEc5wox z2ioo3)-|I7v%M&VGAi%>KtgwiwT+p)CGpd}qZW9Or5!b#b<-GJBnT*0Qc#(LAGQl$ z34@b^6REUQ)b?-^4f!qvq4T737<*_O-!q7KxC%CiaMR=O;fiOiAAw~pw6Lns&h>w4 z!QuBBF&dPID9>)ToyRfm8xzn5d|k-Symk5lY)p(jecR1EOg`E7?KfQ9ZT)>vez4g) zfP)G%kyWtOwO`LWr0lA^ksvsR*mo+M=gJN(jdosXODUKC+fv@`mwlCj>ryX7vfzH*3}46gCWMoRHT6VkB#tEIhS+%Y??pxA`hIFiQISv;cnDjFye zR=I8Owh8PP_{PJDS~|UW#37sUZ2yJC!0kjSLtT9hRYftDEM7v^iD6U}6^-C3Aui2i zl_pwL%%s7+c=NqwB(j=fJd!Ak6U9+3o-rR{`3qN4>sr$&RLo&y|2np{-9qoyp1q3pQCiR@YLWI;&e8&kgEB7UH+eg@l+wE^YvG_3ZC&@` z<2c}Z9!kXnlbztYmiyJq`9va7%PyuAN-I3y1et>SF8?io-g`=Dli={D#Y0@k=As{7 zi4IM)p_m*dxtS-PnN7cuhcU8WCsID>NQ|gs5WkJA=aZ8-I8ove2QRymjB$Y?oLH2& z)_Dcu!`UUY(XmUA-#KL$!jc+U^rBXpQv9WX68j0O}aDZR}@5r9V z@_yMbAD3vsNAN)h%AYD&cmDBL$1)11UW4&Hz))9LMtw~Mu6Sr|gO!aI3-zLXL>ol= z`Il+`xAOCr7av0=m!!HssDn6_#bJIbIngz$Y=HiNqot zHK9LcPS)npYt4j1MlfV>Ukks2bg0j#?`86Onkc~!T#TKoI`Ns$9!?}0u?n#Y6l296 z$_VLnga*-!7&+(vK!5A*DH_eN=47wPB^|nMCX-7*LC^a7mlE|t~+`uDA;zA}m;yU*=JSDHs3%P+f( zjcZnO_Lt6~TlZcJ9eoh*%vI;A;sO#{qm?)kfovwaj>aI)D7b9Zdb} z11ws$f}D0hr`fb|8PB}*8rguWe)0Qrxbwb;*wL1;7Su47@ZZ)nx?lcXMO$S`F!=Tr zTD#<*eC5xd9S5}-KXA1Qcp30bfESm>l?0AS;z$xj&br;m;7Afj5@<;y$^(_dkpzyk zp(Tw{IYd0GV2ZG0(K_CHXPyn3_cJ(>B4XNbO>5xF$)Y5UBMDqTjca_0<8j9Juc4D9 zaQrmN_jrHKVpcC-iSay?$>K=L*3Tr-lEy}fWzmwdbu?{gQV`V9-p3Nb+n8V0X}w`Jw>ZHVF#AxF3BQuG3)tP*|B9iN&*+K2e-pQ0`=jcnMrTi#8tGq;X9G$0YL4z>du%u1TOJi6Vn0W5+2u z?9A|~?^4bejvB$R`fAGY8Q!NWr+nrB>O03#zEAJ26&yUI3yz0_b4q;^MKkjnN09k9%A+XG%sj8{ql+#XS^tcIZTKhhC z-f<@bh9AUhGhgMh|NSN}&v=$uv)<+2dmrYp#~)z+c?%GW@oL{^1G9txIS`u=XM!3Q z?)fwr)OYDvu4G7?wtA~|2T@v_p=D>5S#K_2LyKX| zh=GhB)dhzXcu{7)^*)Q%?4+(o7siYj!1L2zq16;)T!&6&E~g$fj;b<)mvdOYVmq(S zUqwqcM{So1jvqgU>Q0Kr7Kc|~pUdio43*WL`NF~ds3;d!Z_M$+E6d2L9FrytWk`=w zToGP>XD#!WZziK1LelnpP!8u&4_*_3^?~l-dmUE={J{h@PxsP>{W~y&D-y-=ellCAiAt@Iwc4 z$RYihx3Z0z9_7q^Z5>NCY$0A=!r8}-;jtO>*_^QMQ-uz!jY2f)bJ(~64DVTvpeQjh zJ}@4x<1oB$6%&T{B2o++R_^4rxgSuZgz7TIMduvJhNR~1>GP?sEM@ZO!BkfYZB0JU zy)=i0oT5wT5{{fWoa#!Uv03r*%r}V(e09nw+A@a6XS`2CBE=CC$I`dfC6V%Z6!C5?&wLp@XRbWwb{)u?syzByf4d_ZD#hn%kXuKoZ7%K z69+SKXg4;zx(?+F%CvwFj3BE{95b^e81cICxXM$^oG=23od&5bNtv6g6gJzqKR zLVkJKsR*83c|9SM*vkF4-@=V|+($z~_`<1Y@uRCRr$=>p04beU<;b*dW!%t%*tnyW z)|^jHqI~C)Z}Pd%9>>?eb_qA#dLyHT_2UQM`W7=^dyCSp1G)K@TRF661j)4UlMBw| zhKsxK+uvP5zux7Xch0xjwxfyqL8JKT4Zq@xNA)5qN!BfXoyxK@CLDGQf0=q07oBtr zeno#Cnsz^T|NO^X`m1|*XTc)Ornk7{k}H|}{st<#^yIFGA7J7E{fPTMTH847ea&?K zC`EzANF|F>S;S=d<#o3ZFYd-KZo8eD@=_En+;{)|+(wq%mkt5&gn&0;!5H76W4 zk)BnhtoQBd?x81MV{IzR&YX*wN+Ob_G_E*!%pjJ{pUiMaWBoIkIqA)C5)dih=WHCX6}1) zIDXQ2RxV!83u`vgqeneQjvvg!vleo|h#@qsU&)Mli^#-lNu_)a8b6TgnBn)ioS{%t%&mO)+vvPtr||JTvPx zyl5v9*&MzRR<2I*>~k||QpI@0c<-GLSTVba?sb)nI$#`27A(SXgvQo3Ui;e{NNFdg z95eYpfzDIMD@ZbY4(co5Kl*_~s1KGCtJ>J={nQx}(ka!VQMVcob{Tti-I0;|# z*1Jn+P7A&`pdDQ0QCD8f>$4Yk~f{H{~xo!u;4;e~CuR|l$R+aPl$-`K%cr^=` zZ6WKFA<8KvndT+bDE72~|K}@#Kt7&ox6cVTwnCo&hoQ+*D84p(3E3zjZfWyy}jT9)FfnWr9mfa|XN9bdZeJ5*MdbIoU%JBU{CN@Av(&GuUx?KM;yeY34VhEBX1B4VzyMoB_4C=-=~=QvsSaQAxE2^ zU|>T7HC;R5W`)Got*qakCgqf4Ob*BOIbhTf#tyASa*%G!5jRH0B_!)&bF&hMn0Mel!A(1>r1?E27$A z@#0l9MJj1tx|-o*`_rwm0@q8DRxx&@T$1^{EX}C~n~V`a;V2QjoX5_z zp(&Xmwx)s4kM2doYKIEfW#O{Tv}7YREZM;L0rixZL|L(7Ij0>ugmk2gH{M&0<9H13 zTTNYUl>P%wz&H@`9EzeYqzix|?eo@DfO(??GN~-v6N;v669@Y~ol0V?TeFVgCyr)p zZZfaDH5bta?I_Zo(Bx^_V#PRG7&&qn6Gm1cfSYkBbp>BM8d|e#*y)jOX=CxS^>po0 z&Z3oD?U)MUOf5@?MvDa^GRELU;-r0-?db?!Q7KE;>|nxSed%26(zkb4)^FWLCMQIq z4!(Fc=1Cx;U}Uda-e0nk)!Q?;<)!S*8jKh^m$~%mUP1rUK1VXHC`HqGXNGl~8p!(4 zCNUavn&J{o@A@((^qfemhB8;t(x#}as-Vb?@%{(P*qAFL8ZD+sTMWhKOpJz91{D$d z)OF>h+4I@v716jM!9l}w4D4RT%A|`C*xq8;VjOTai&kz06$#l0akRq4;295e6fxlE zJkn___cb0yJdE#CQCdn>bth!SW?ZfCWKX-EvI@yRozS&kb`#0bv~?Zt&Rs_DLF2jb zk{^&>GL2jR_%ORG-5Q)SdJmbvnO`~$Et{G7c!o%P^4F~&y`0jCqEeD!=b%zc>`o_vDEOO}yY-AGFk&N%;DoN@e6 z{(Q@CPyukE7V8G~l3SVm_FHU8WV!jaKch*LPA6Htd^K6mpkwVbQe$Yhg3q3GB6r_< z3mZ3Y<)WWm!)J~=mQq)E{+Ve++%{hI5&-<-7eD8JFTawmHC1>Umx5c$h>1sY#+gSG zqnTOHP3O8_+(^@w22xoV7_G+7`4|yk{gP^4YlSd^Ujcjlk=CHoSXUY+yFrqMC2G0*bd5w>F4!$QA zdEWyumKsisPsE90d?A?%Vr`7U_yCTLzJ zjH9(>6>y!<;KiEtJNVNRZ!&IZSI#(bJkLEln{2X$x86V z^r`tjifqPmTscaS z^@J^(cCe+f2mO21(Ys3V>^ocWR2<_=kTLEDhh`y>P7{koakZdK7FP+L=i@7vWow&x z^@UeyiHp}vHYsL zi`iW#0n5kyUm$zUs0=<1_2UnJ&{afYaiUR8Te6kb))wMU%<9|dA@*wOsyk6+>T+wWq|O zM3o|nM^P+_7GcM>on*3xRMw+ZnE)`sV6q9sjo}oPqTM(b{NRU-9^MnJ0T}8isy_k5|XL;hWyP105U-FYtZY)MFv59mdO-V@% z&_v=9nwlH&42X6?N5C!S^sj!MF8zA(m%Hxgic2nJOPg@n#b3cO1|251@h?!H6c}Y= zLQy4@lyznDm_aO<`#Q&;a5$wA2PDIydGl$=C^~oVN#oXy3>-6=$A5eQ*In~tetOmQ zTzTyklodtnTI+=1{`*zI{qo6*2GCmJ8~+nvn=<%b3L!@>m!qarglII%g2g)+KD-P4 z>WUdNpex-vbz;ZXCf00fq@+t%Mh~oGU}r;*^1!|6%I z(3Z~8mPv5PL8BR1Tf|YL2Gh1R&5pJzhbyke&Rl%GEtJu&cG$cKa7(bXn)rw;$4kwXH(bAHjYjp)Bq*%Ln0giEq#$vp^ za3$S)*3hF$Q5DZoR_x-La3SybvRT)DK2g9ZlTTJL%DOhX)l^U(&9ZgP8eBg|Wkn@z zEor*f#TeYJ69cM>aeRZLJzT$$59DG2%c~4CRU&H z@i4r(cr|?n)pJ1aQhJwqbaoV4N7=kJMNw&-LH&EtDQc*%u0VM?(#aG~90vEPVsMvI zbk3)tsgVQ545PYOs4I_BRN2c=d)W34i)W`9Rpqv1zB!~uw4C&@geE+-OWBtZ$ zY+1jCi!Qv7zuY^OC!T$pDW{yt6Vs;g_!EzE%WZ!m=NI9pHLcC9L@PScvwJ7*yZKtq zIrE!5{>&@rqB6E^T*vfhUS#>YZ79b9r;PsndeOFi0q34Eh3{T|4Os>&h_+%yYa9EQ;1f^qKckTCh zW9D>j{?)H}^Yz!ccj{xDdEUhwcf#lB)29bu@RUnU_a6M}m)DWrw1^*Fb{&ZfING6o z+Rc7@{(ku+#kJlgWrNLi;I{mT3J(FF!%zo7;YM71C%PcPdc2OffXy8$*N+Ot!|;u z|5g=tU!jf5YiF&nYjcFMtsrX}r@ zQE}pKgtC$%lra{xRje)0bzCNl8-aEm-v3}7v*#}*=M?eevvc{}q!E1f`0;Gql41Ib zZ_%9b=s&WKgNF@9`!H|eI@axICF%LNC2N^*&;dlEngvUDuwmyi_OyItMbVJ)F$$8# zr_qZL#zi$HGo*~BOI})gq_3>9&*O11K6tg{*A(?}QhMg>0-$d8m^{n62 zKts-AMlM~kmI0Fn^4ZTH!aMVKuyscZYqvCz_BQY)>m15*eO-`8|%GG>ReP2e5qytl9DgJ9q5lBH0u?_tHYLJ5x-1{wyft?NCrlbd_ns4(_2vh> zwQvniq>L|o{$O@Arg(hDn>6`RDhzB-rO9X)BR*({veII-!e*>0gReF7mu)23(!%5e z`!jY-9}=y?3p3wk^|m%75+~_FLk2u?*x4pL`SLub96g4L&YMXzraM05!USX2FVrV* zC;1o2USa|R$e<7)T+4@B-vk%Y#eDzTtEueTl{@Zzk`FeuF!{)18Q7;D#dhlIyVJQO zf*UQTYqu_R>Ez%jKo=A5R6~9D&P0?Y_H)F~C#M8yb3`h;bKhgr`TphCG5zTmaLa2r zcJeqJqLg&1q({#xO0*$cR7P!&9#oc>(0|xaUVQm!etr7`q*G}YEZ=||EymZSoO<3j zn74EziB{o@C!bE&BEwC${E1~BETT(~0mK}ODJaHA1>ELBgqbaF)@-D)Wfh;Fath!6);W|`#JKwEE4lWDTUoqt5yu~Q z2oF8^EI<6-l|1|Gi%?X-(Z^1}i57ACSzl)P(v>_p^Br_)7qY%^?zb;yYeNfXa8|Z2Y6@|W#GtB+pz(nfjOiN0+WW_~DPQ;iOYfB&u48#Y(8DDnTiSs=6Lrb4hVha>C)e zl)Yc}%O@x5m|wjrN-KQhSx{P~_Yipg_e5+mNrzIQqa{Mnjzc<`Boc|*`ydv?HP7(j zbwH6f0mrR^fSS_-JWR0R6_$YDJg7pVa`J)SDugr0a}+5GglL8WiJ8VI9h~4LxW7Y) zb!e2upVJ|~BM>qIs61$aL&!vefS-3mDGOMv6qT_YCmlMJM`pZ1QsQ_9eC;C2#vW?p z7kEku3E+bkNk}s9fU+k?CDx+mOW$xKzS{cDY%%i=hWbx$gT5}%Mc1PK>W3Hl^p zb`JWwJHAfpoJRYZ}x`eSq zdh+Hgud_K5MRW|U9eh8C3Dkmeg23=x7Do&gx6iVX807@@^b7S=I;dxuC8~oyD6qm5 z`aF2<`Db0om=B+Sp5a7n5|ZS98!|!!4AsiI_f_Dk6&(`t*`h6cM_^GE3F>JrM`2%w z9L)-Y7TceuUF6Z%&E+Os=2p9mt>?HWsL;3uaaME~y9d)#S5?qCsN=gyrx z_~3(Fc;SV?ob1RlUf>V*^Yf+fd{n?DZPy+Na4EfH3okzVD62PZv-1%RL>YSESSC#x zPmIECBx*13cimR?uJ482(&zV976ie*dEGNuLZh&4 zrAC@I;pa4tb=t#cd#dG!DYu}m{AbJFpHC16p@hm3d$9TNyRIS#pUzAExhSWwh6V3~;|1+Q z{xOhfY2ptz-^z<`&c{;$pRkVbtxJByA(O`E=T-qh(8<>|gb@Ky;?vgB%8Z$_cz5|G z;<0khJo~GB^DAE<8n}2RUrwPORt$+mGdKV4M&6vW#9pNoqKo*>_kYCX38R8JZ6Huu zI`)Iw!(YxWeY&^n)b4HC!|(I84d^;QEsEdXW!F9~d}>9v`#*)}_%YXNzwDQN5%-T* zoJtrP9Lk4fv;4nw#`cr=!^Au|!7E4M93Iy1A1Uu26~#Zd5Vc?2qrllGA3?|(y0j-e_Q6utgcCmdHrC?+5 z8A^&H^J6ybn}42#b-(ecC=gDSbJOa zKHX6%y7e2(-`<{wQAO4}Acb`?44v5X!B10F)0MxyF$ZuFoIIyfN88dUs;gGjTw{)T4}dz$v(CQDmLWgOHDH4IeR3Qdr4Q7CH zV~&<|k)k@AxfS8I+VhF;>vbZ*3sAhj5jl>*d$n!7@mL~!J7Z|B6_t9u5z`&-Rpugf;!@@vFT+fv+U@ow z49>|B+LHKD@+EGMr=)$s^LIasb}XwN?1N&_dd(F-FTsCNB3qdGje?dFxd(7l!RWvj zA_uuESV=1GBkXTwej}{_d|!J>@#n}0qz?2!veZUATG;0_kt0OhKW<0(i;+;GO-xW5 zyTLgNZ0gKqb;#4X}vVT3DimNeuzfFJ4Em zXbA*(Gxgj0S%IjP-cRoYlj0RmzG?Dh-q})T+cdsXlugSrd3?A=U-d44K}}@-Y1g-& zxC8a{wx8(3gP-2m`6q<`H;BVeT^n0F94FLImEDp;1%~k(Op<`FJiPguBIjplh$c9q z9P%eI0woX9O091Ht*UmHexX$P&!5;ZA`rHA!H^q@03$7!P>voYj}S$0!QosE^Dllc z04}*`irwvXx5^eTC*xo|B8FpXbYi~>Ix1>oTY1%fqyr*UAw^&$7%2tOFzS|ydUQ1i znTV)h;$b$XY3Nu%XVuyEv$)DL%t=qH-OfJ1$MxNt4|IWfOQqFzX_5EwH-JOJfRLe{ zvFLEH55y*j!GXaFg>EGsS?7LLsO^e;shPU%%zssgfE8nP`yIp_rcQmsaHeI7haZ57 z*7Mb|azVuCLTcOZ+$Vdi4z0YltFDW+C=g`!eAp%wDApH6=e<`DMrRE}{iq_}&h7>5a%i5xRdG-dFFz169rFl!66B z#h~|NYn+GeoZe4PkGQET+H*{fL~pJRV&9z!J_Dd6EkRS+`-4KK_JcRnzssl{=42sk zk_&M25g5W!mv_l((}p6+osyh_cE6fzrhdOg#`SdaFIe)xA~|8)jQV@Hy8Sl=rCU13 z7v6fS&184cNMe?r)bl+AgY5uV12WCF$2}|B=Mkus^ti=BJ9bhTk64fM zcU#ifLax!sb`Y3MKkQ1J@n;9Vdhee28(dd%7+yzQG)mG6+O)~7)&v7`L)-foM7z5^ zI}8eT&wK24x94n^jh3lQUMwQrVMN8ki|;+&FI{`a1G}DdeNj^6VYxnMAs8%<_)dIx z|F;S#lx&{yY{2o|Qf9L=UmZU(IloZH%<*S0&0aJ6Hd$|1^!pXItgj%{DA-kpPp})F zZ+p_^H@fzjS@!MQWYt|$^Z5H%uiP$0sNe5wvDBBcT)Xe~5QUGN>zNNpRz{whnp3~k z5{}EP?_7qj?w#zf=X?I0pDz9`;Dr@%xU!yBg@nYt@=Y23v`szo+ahl%>DtxaQsrOV z`HKCxq~Xss_HeQp$Oz9jT|X$k+UUy~CzCPr$o`q@b=8sM-a8a;i&E|SDb{uShTZj7 zpD*TYQON)NDIj7POsAjQu4lSms6SA&?(RK-cvM14|2mZ33%|E~>sK0+*YO|c^5n9-T-hP*F)Jz8BH50}!7$hQ zvyCYkcWWwkZ3n{VSUmBfVH*$6vm|Sc?o9aY_jCrn>1#K_MpK@#m=)drY)<-kJ#7&Q z$V|73{{7Z%)8i!MF^Q&jqeXQjB`gM`<3^ZnbB5bnK4WbjH6177#!|k~R2RL5!%r28 zvhWP%yix)3`^jp|Y#!ghQ{}Rv9Hs5=7v;?6tMO`$nb|6FZWzSaVW`a@`y?^58FaEx zj4wZ;Cw~NC7{(!cuEGuoTl1_&e2`_VCZP?%25gpM@w({;OSL$8)flqt7hpb}JF+bZ zz0tpWYDkc%4UQJr$;iXEhbWoHEF*xpL6Jh77zQ0F;^u&O;Iri_@z));zcv$Szx14e zzuGv^zC9>Ef5GgJPtcPs#Y5^yIeaPlei-nQ$6X9v#{q^Sl>Tr;TfCUBci?V$Jr`A1 zN1B<=ke>wKVt!%C?_ddsF^Yt@6~l13o=?Zu%BH_=zB^ycCIEkW)nB*nIPJgC(XhOF zhr4ohT(Jer zcUs}r^4f#*U#&+eZ~u4z_=|Kq1G+u|q$tPe^*#VwJdYDDYwsqTg&bWSFCyc3#n#p# zw4Tw!14~lRM`yEZnvwsm-_PTF#=sJM;AXyWpgEp93jxC%b{<((6%xdkUlLeh?+5V@ z9d5S_Yy&N_8UykM6G13|1p)!8EYa#a8$H?&A{3Y~DmqwODEOJm!}AJdI-NCGW!F7+ zoAi&xZYSK|SyT&3&3;67C28?5_fM~fHf0&2cDLD{8Z;$d9b;&Ol;A>2Xj~9$NlHOU zB5jfio58*bNDs)b3x5JGs7X>11&5aAP~i&i>ifW5Y==1$?-8rP=AEZ0F(0h_uh|kn zK~poD33Q0O41p6|sx3kJXo--FjJ!aI)LeS+`L*q?^4wyH;r9g6%YlqHFunvo)`AVo z92p2GXdRh?NMiptCm#~y(EnCqkX~5K3goCx0RmyF0?XWnD4F`YDtJf{PGXF7kj~(~ z-kH+>4Nf&Di`#3|JI>D+Uvu zbs2#(0x~3=JS`O3q!YJ(RO?N(Nn!ZS5EaFc3Lou+1koZ-7fhyd`sc4N)A{ow2CpX^ zuH!`)lUkxIbhte455BstFSBG5#X3=Lu4dbDPTr0B$3BDMO&5syKyJJC%=)BKM!Pwo zZ4Hj7$iJqmF>b`hAh8UL%^Lw$kf0TP0RJ77xpe{dJM(-O9tSFk>;`)r2xSh8aY6G4 zlV5+GL3Gxi3VjyfFC4y%Je_1-L@VYS@Jqe}uu;J@Tks;&fNPIhG5haHZ4$KkV zmq>2|>*;W{+8rf)EO_M_g%gHi82&uIWgu&a0~LCw;dBVm!PQs6!YO+8+B!6ZsKC(7 zBalL={h?o)f@TE?;5P2(9}awnoq|NG@}-@V@eL$aY}AFbf7uJH5`dUr0M8^u6sME zWgZaX#`1q)7j7Cg(8`MjGWi7Bp^qvx%N2GLXzk($uv4jTcZGk03WIC3fAB8X>;w$l z4AYKPYvpO#VoP>eZAa{#?ssm?Z@2JnsTvT$tauESC6fm@V=xr1_j8r} z_Y~MATF0dc0RxWZ>ogD?+<-TSxlG`WbBPRx%VUU7Kvx8zn44$zN#yfyDt< z;S}h*9w|eC4k46XX^`Yt3WnRH&}9j`fGQbf<}xV(E9pZZkjZSl7#dxd<;fy<^MzRu zH#|f*n?M|I7R^7eS3Rd$5JJS> z8ZST)yV$gtH-oygHFJkP--`IArTs_7KoN5)lQrhXN}#Za%>}FJwsGdWjIglnJ1(&k z133D>pUvJ5=DciNM^sUy$k;TI^P+1}=)bft(oTAZVYNp$+Xrbv?JyP?LJAs=$phum z2BVq1vyb|+h%zhhJHQ6Nu#a8`*yWsfp79d8o;dAV9PqmR zk$do9lZAYv;XlBYo%3V)X18czpgUhNlEb>Tc~kBFLJD=p+hX;Z?~XaTYjC<}=|e9= zSs8vX-{sP&xWd7+pSanZnbu3E=i;|k!5OpoJ%8L$TFWk<^Xg$9&v-%6i2Qln@*KUL z-uT|(E%D(ox+h+>+4Mg@x75d-?|C+J>W;EeqY!R1h^7#$z;eN#Xm5O{u9*KjGyHIn zDv9yTvVc0cool+AmO0iPj^vBe_EA8NYQkd=uqv!ZOvE(Xi+@JNenH~Lq6(RZ3=0B} z+{+nK#wgWhbSy(R1sR3Sjk^*H3Ka$e5h}!Ps35@#?f2;I+JCs?^;iC-uGmkYDj}sp z8W$-@5%V~hrvnTvySrX&7vkn9*;%OBQmwXFTaO&?76>P&q!4To?zwML4semsBi?;)mIv+-2XKS!F6k~(tp+~B)Ro0`nIj`ECkk_s_ z9{i-4%;x1zm!x-XLuO{dTTXhHJp3%lMkk3 zS=(b_L^#Xv;n!<(X*NDfjL;kI>gr~T#L?%Ol~0Rd!DIfP7huZ|XrlKcfU0E9mGMAq zXLRczkF1#0wLCZs&pW*HnN=`@Vv_ zTU~KUk5G$ES@Z37?km)|c|F@~!K6S1tta+3Sg}{@o#20>m>zIv;gwbD9WK>qlnj)Z z&mFe?`HV};h-#SFYB$D@Yq%vQBuZv>35`q01C+7uGZ9xgO=34dSaV`gE;Yw?b z2UB$}xb1@{=gw>SQIa4EXf!S;0vO zHJdN{@^x`nTdl}l&Js0((B(PA*T15pC6_L{+4Eqlw)DmtI7MZwu*5m!aNoNYYf@Hq#rXSkfW z?S+sGVZO*^xwL|IHT?}&q3$KAE6=X}71QRdK>oor`Q~!&;qW!#Y`u|q-`NVNTGDgc z-Bp~oT-xsf79N#LOlO)@qgGQ;(H?r;;$A4Ur8;l9EHL{H7}^l^emjD1vRH_CYli80 zJr;Mp=9aS5#2Tc-og7OdU+Z$A7Y@@sjQDFckn&T4-1A8Dza`cmkj<7m2>Y%#Bw!|8 zml*}UXl!c#asP2%6kU-lv(hLuC z0$s0G5Zp3BPbma0Ik1^5RkN5fRyTUgILwG z9UL-M`pD1Zbe0r69+kmrh6oXh;&^swV2j206Da$U9r^d)UY8K`ojlXqwAQQd=Q9e* zA*16Vt@rC7S~eC$O*cw&qHXYeJb_3$YaWf!nNiZ;0kk}t?{EmbT%nTXi?t_E_APhf zb9NgM1IDX4vzNUQ8%TP~BiveQ$s*yd*Kv?i**wA37D_sL@CGXBV;oMv{?zB`nZSi}2{x;D#~l#BJoyt_)O$SRyBgcs*<(9RY{ z+kKLKBxK6Tossel-;uY+^HJW630C&4v2|E}MHQFGTliR$@2?;VnFy ztvRV#IZ|o8+zBsyU!l=7G4*tu^_Gk=WW2({%EYNGwwqnz1&UT0-SkfsJ-=sIF;BD- z6*Prm29Wlw2soTN#_NTiE_0~P{J16+tu(_hw;}Kf(&fxz@ z8iOrc6to_;+tOWc>q=74v3D=T@Qu%Xj52yeC4$&{99^#iILA{tK}V}J>TUj%jc7>0 z%tTRa2*%3`KPbtq)`%#1!q$8o!cX%JLQcBeYERk-c}d|a!vPbIVp6i3Ij;%#w{~<$ zDNtG#3n*Yq6Lw-kzMK!A4fT&Qenli`WaymzBeiY)_W+*d+Sg!>#=Kz(i6WMA$PE?i zwT_S~)W0M5eFQ$B2kF3u!*^)UZ_qaR>jprjVWJrP#g5rU2C)ftnxY_mx0F(P%UYn~N-(g@_(I8wJ@Ua7P)UqLF zue%|})3K`~WfRu>^+@~%k0}DU!j+Ish|cAS>q;_G?|89!gTd}^BPUA;4l0by*{Lh6 z=17x_}~_<-dO&K`#&#)P&o!Xw>STEkIiMlZ)|(-$O9b2wX1B_%CozF|Y~ zLvkwgHKnr8W)h!!9H4H09sb?^G`|gl!{8sMTC=-a+f8D^3aB8@BbcTj8LNA}8AOFS z@n%hBIQ2WV4}H88vXrvf{#rQKc9Zmq9H+)yuEOW_YAR9nE z2Y9-Wy{%vxC=f#Xdeou;Zy`RJZ~c+w=h8@OINILCo0chnmELa*2yjI;90`khP4N(m+0-jUp^J@NlR28DHLKdS(g@v4TTC4io^HR8<~ zGO9RSE&)5FblP_e2l=Q;@2R|J;o&m(H6Vr^o!MY14F-$nM`3~yf!O11Y{3ef9wNkN;W<1L8^iAP!l6^Ys*<`;(l=)3#QWfgq73* z9LHRUPnYXaMgJM_y?eqsMBJvw{>x#9CD)~@Q)O`k`lUp2Gdnb*@$q&Z-Te%I*mOM@ z?By3$!zwspHEAz&@#0GxH{+X;-GW=e(G?O24Kab3UP^L8VGV>UhGnZ$u;}l|K*}LC z@3m`!L+hOW`9dAyez7+*p9krcphDQIYv_Dy+DIx}XT0Nd(s z2Z)s&d*U2!S#n0!6suY+vAQQ0`&o0~UxdNP!^yvtBv5=cn=QoT4*ncZ`XCbb;7w^R zk5F(NMG|7iC#3W*lTzCU5`Z8{lf-LO(J5(t+XemZ^8sUJ$ z-v+-_3MGMDz(Xs1{1R1Ap|+xdc{2%)|qaXx;e0zr`UKA3H*l zgy2j>PBppw@Q{Uk36Y26NiY$1khD%|cj9bl@u_C5`2fgmi#_ZzA}AgkZnm;;vvs?|W{=I$^BX=eFtln_b%n+-QVnfLr=|yqsH%sF@t2cI&F>g3F~snL1(RxVP`n!3_ifhKuI= zMVhYXM2KlY#=4|Jg+I&!`O0v(?Y;doRm7CNs&TK%$LdxG;rv{l0%{H~o>1(O+ASEEa2thaH?BwyOdiZsz}?tHq+( zOp}^RUbUIA{D{o^pv5aVg}1~Z#WU?wuii^#Ft3*iS6_pVlR3{!KSI#aYJc|wzB{lD zHyiO*S702Tdve$nrmT_>4ut$+AxZTPQ_{#H9X3TbMeFA6r(>S9I~ipHMv) zSOXabnVDQV|M*(xgBW(5sl|%MwVq3c2+D}2i}|ec&_}>}mfi6c1fJ1FIe&bvO4M}s z%m`Tml@`-YgMsyWa~%J+FY|&apJZ9;4x{G~Ym@mxE;My4#8r3fr19yMFtA)aF+{85 zR!!W^?Bc7oyKby_B)BFt%xQvuAPCu-(dut&HGDHrQ6=&pA!=jhf;OI(jOL? zA@f8eW1j+u{2UsFY_>-`{mCI3xX4LzT)D163lE3(sr&Tv}~$lxFos8WqN*(~6dKJJ;k zC<8MQfBrFZWbYhq*79cXc+rW+9nUo@bJya`XL@E>$aL7@Jf4x&1I+pO22B^(^BV8& zQ-WP^#P9DgmzlEY`CgOJ0lmXv_&qUNHfQ7|s&H{XK=>bSA4Thxru5}{GpF+*29ZM6 z>A@9wK90{L<~%qLmzcqBJO65K{W zHC?YJ6oawLkagSVW4}65aJvLpg?SZKk8c)BESRQ&~e zZl#ovY5H!N+O@bbi@7rj~V(|xkq2lnRpXUjmGc-gvsFV{7CTO4w zgv-@d)dGEB=^9sPC!i1>7eY)D7m@^`eFO6G=&73Wi1cg+qx7o0TmKq6?FnOYu6)N-}@gC7m=fW?|;D}#F_m#=qv78KeefEqh(ve|&^?DEI$bVF=F(P*}s z>yZ5&8A-+A_(GC1V5m0D&J@?LTl#d|%BLe%x5#*G{en!mKHLR@i*_aaI} ze&L<^#@>7~E0rPojP|P898(-69)@@40uuK%X`;&0>-)r%`VNxvh%3fkH$OXf3^`h| zBH6xuXV)BXu92MoAvHg>oLfLc6C!AKt|x>BAb?bKVR7!2#zo1aDk&m@ut-ri{ebC_ zDs-rEDYbdU7gz|8ZdGc{8aw%~c_>2|qVrRPIb622F8M-NWPgX+5z(2`0hH16@g_#)mRNl2HW?hAfHUd^{Ut^#>J<}kuXg> zu3_IkHWrL<am@D*8=Zt9Y z(l!U_z(e&};pNy;l8ViO8ZWPiFItAK;-`-@KI=zr5deI}kn>JAf_o*L;|&fYn7^ba zt0S4tqSB%TpaYg0N`w(=_FP7Es&BU~>e2`&q@QlOs3R;@cP$p=IR0Wf1+d<3`%SxP zz@fQNtO60L_oRh%@NxCtec84m^r)yhQ-$5Ef`=J%V;10g&JFwg7Ll7ZI$L}*TJmde zSsE+BDBsf;k;u}9qI;_yz53y}vEz)MX;~dx;(tvFv){HPvkPJGth@gNH$#?)EfSX4 z_BjbFV)MhXf=kHYD`LT@h;+NLVpNGb(z(WC94QMDRw2P+SIYNnsV@={4LslHDe8n( z0@XIkx)HJGwy0`0*F{*QxFHDU>$v2zu2d<$NIt^%XZj1#tOA${MMaa242RF(( zk!R>hJvE8Og90IY?|lnH(0Lz~);oTkhI{9eVJ<>brTP9;>JBBqvyoL3K=k`%w? zEalaZQ9(l%FxuaAf|s$5dB(s>#`Rm&*cV4c<5bixAR#Fcw8@Oy36vyaqS}! zcR_%Nw;4B(`Ju9!HD~6x8~*`CGsh;~C+>X=&taXDhPz$*@8=IeGZN zg$97Phd>uJ_pyCq=q@q~F~Aa4rrb5r4oU3shpChN_u}doos!6pPOUkGT;uGtAIlRh zFHGORqsq2SJ&2%DixW6q;78{Lvb){tHo_i}#~FDtPw5lzoa1BHJY*8pz^#hJ%XdV< z!Z*)SP{BkkV2~O=8KCd`E!nOI5*67XBo!nW9B*DSr%4cUnji&H!JBC|R8ZoKjzp=m zU9w4+y`U2oQiU2OBC-(dZWJ3|XlZ%eZt**%T&Sq~`cbJts*2;&`VwvA&NQ_Mw z1vT}vF7;28n#BPbv|P?Uz;`o&!xGk1_j63oy_X$IEu%X__o^U?@! z?0MQ+LlTO=R!ces*VSw08ylVn_mgL?JLmFU>Az~dACYl!t<;CmBEVXJpbz?P+KT>e zT`v`J_yA`e_(&wFKY>-~z;mU;MWfa_8p(F=yMe!Vs`W>!Q*m1Sv3BWPZH6la54S^H zEbp|>2>}PIcbW6y*M4OFjWy0sLAOB84b2hIGLi9l09N(+q&2vd#dRMV&^al7C@7D8 zqqIA6YpqDoBuo~gi0G4+wF(Fij&H)o1l=2N`>`pLY*lta66VtX6*jn{JMLx3o3~HD z{*hcR-O`kP)q3iafRz$EQEo04*@vIiyNg#g#Tu7yArrAcv{VC*(sT{g84^xWYInq>urwRw%(i(moS3WGe6S&wz%XJ%VX?1 z;oY0m`#-51zCU{V*{|dxtcXP^jHAg46x`tl(ynTd@r%+oq9HJtnsxjkXeVqY9)l{{ z1j51U*avcO2yjmvd>jxFmk$#WAizNyOdD~Tz8Xq`a6=s235n@WqVT&34hcFy3CRY7 zB%HvjrJ8(jw6wYb`Y3HE18q+VJLadcFVYvc1J!W(&dOrG5;tE-mH0vC5c=~y)YE{H z%6@zS?KfSNq>-q=357vw2%`Anz<8H}ne1^O*<_~kPuOur)gzF&cn~M_;U^p1uHdMVTZ4o%?^Z^<`11_$eG_1K}vE9%ny8O)CZn6chAml zXddOm&AwN)5_vaH6+9y@w}K~gz6fy{CtgVv*v~-dt)EHq_Msc8zN>DFvI?DgaN;kG zBn!F#7(syxZK@wgS#60R{($VohlzK^n4lV*r4T5EJ<3Rf2&w@=pG**#gI9(3+U}+27la( zKRjrF}&zC zzA*VP$PKKK1pV}v58q&W`wJ?X-%U)40|LXZH`0O|Pq-eJHEs_3FeC;zHU=sb$q$6y zz96Oj7K?fT!voMNhUf0q7Q66ZH_An(9RFu4L7vp>>>CYtzOa08{)dh;QDZpjPp9o9 z32(~78&}imlrT@$DQQI((+jWRl1*LP9uvL($QT^-m-IOnU%YO6%iVetL(} zzjH~C$*(_;qV>Rh@dc+;E<-@bZ~zn4F0;4m>zDNQce;R-O^5UOv<^Fbe}nMH>!nGx zR%eJo+QU&HuujIu4T==>9cQjyAM7*Vz$3bg2uNK|M=*WQ=48yuM<^Shn8D^4q*93O zNc8mq#~b!}%LiMsRBip2zkmcsiy6d^dS1bsv73gr+Jll^ia4@lPYohYZkC zKE-a;b6k<(#8@ms(f^maZZ8wNcCYa{_4ZI%K5?m2;0W!?b?_hxczxyAvQ@OCdHDIM>}1i!uO6 z6GQ)nf|l#w4`%FGz#;u`NaTVlDxrwnaV&2h z41)|k2>S7B`_Gt*`Dpn$o#}iVW3p=KYMTXj^NhuyIDXIInF{sGMB?)pZALdNB+58hb3QC7FUf$nm%>4hn0CTN>T^7Xfx~_q@HEt3A ziH6AJJV1`fr4Sz^wObrY&|xwW%;A9k>jyWtD=$(D;v14x$uLXQw_A|LY%u?6jD?oh+Zj*nQSt+B|2?E-vgz+8PWv#2A%NWp#7tC0)urQYyOh}>V8O>nLz~nnqFfvkbUQ< zp+Bep#$l_b)p3wDE%7+{?jo77>3Tctysk44xpT!~4mPRX_@u%a;aj})@G($%J&LVrRpm!=c;zh_YI=9^9F?eY%x+_gN@-Zfj@fc zNcUPM#R zm(xEOp~hY&fcyl8@8^+384fK$v;bBhqTA-wQJS7iDdyqOFe)S^l%$|sl`9YL0cJ9> z$J?A__1BlzucyoN(yNkT=rB&-3ycF(`a{)Fji%60J^38h2AHQ&a9^Uf#@x z&4Xw^eV7fug%H+rzhXr>@m%){L7Wl^Imny6#AnFgL74Z)NIdmHdu}qv1Jbo7_9MUk zoyisS3oy@2+W-sAD8P8GK(WUx#936XhbOXl--%tJix$(yXJqg*d>11Z5BLE)3N zI(|{nA73SZZjlH0AB23-k=(8}b2cR^8Q_70eA>!!`P;j5>6e4xhzIkX$mj15=mR|8 z#3N~4qU#|Tl|b)1rZOOZT#i|24RBW9_KkF z*;I;?T7TmOyn*}(5NdW}q>v%AXtCJ|oq3|rXbGxO#w2gc*eU;w{@0l|_zg8r-6!N3 z17r3+dR`X2Y1?_k=Igb0G@08Op4i}s!X_1x5K2HeEn@XkBf;MfG%{oI z+^|P?8PTj+So~2-({AqOBgEG4Q}4ZEF?+`Ivqq$ z6LD06md#=l&>*y~(-JWssfuS|faRBT;FGcFF!64aBhaf+pAN^aHJY{i)p!vEPf63* zwJwQGYaRTn0{m8zlBC3B*6#)ggiEHs;Imq{J5x@FJ1I3`m=l)SLYqHehW(;&CtvVl zt1WQOE!J?V12#C>_`QXf#s^?S*QO6NSl5eLRh@n}uM9aTE~UzQOrJh6npJD~Aq@W? z#GUK)YIH)j=zR;WgcM|aYC>egpu|G4;sP28DY@EnrMrWPu+_MbYf6kYd|E7O8< z`3_4ITus(rqie;~y0?VvBEd)Axqe)OB4Es}+2Ye<1C_-b^ym-){Co+;$;O(kwqo5h{QTDI zl8~ow+F|!=&EG&lbnUU8YZ=DHWJze~BCES?;f0|qsU{eMwct||GDQpofq}*=4o7c!=B?NTBq0pA zR;gf=lvLFt4c?$$WE8L{Wj;bBv;S65)D0DO^s~+@W2kr|C-$f5PGj5k2%TsDlJP!K zjK$}Tke3R+)CZwb|2NP+ld#mpX-DUi7J)qM_3tsTO#r7re>P@YBIqI6{i@pyhPvk^ zlD=L{rTKevU6fL$HK6~-gJgV&0S2bv27I3}MfhKZ5)3dZDk@59 zYGPvI36cikmYnfIpFK|Uk?XKn6Tmxk2r8^_M4OyDCUIYRmGE~!e%lMm7-loV0K5c@ zvXV|--JH@Nw|dJxHhKy9Z@GZf`OCW$kfs4RaV|6xO@B&4oXUY;2xQ?v>kgDJQS{xz zODo$$Bltc8k7{~HY-y0}Z|0DLDdq{#HQE6gg#+F~vBCtL30%$0l;iXuHBi)9fei%B zR%UYrI$qn}?>2P3#z2i_GlwHKVPm7?hO0MK>R)SV-cLtZeD8+f=ufACePTwAavRH= zE;~6dC1cZtIyjtqGrDG3~b7NyYyVDnVAir&r+!Iex=$nXC+6FJ$)z>QdIxa;TqG@xTHElb_8N4I{HR&I+|hK6edR4cJ;uC?kPYf@%#VnxCn`#bULZw(@&r zF0$=RRnzs%K&58?G0zv_widvEQw1->p#iZ$M6O<*XXm8 z3=+(rJ3N)usQ=XYaPEZHjBMSZH=Bokg&}>gY{M8t?qT;Twe5Lt0^>*7AIY=r?m|fJ z)na^{qL>F+Pkry(h3 zO7zn;SJYJsKn*;e(!41%!Jj|PE+wf<8X_&Z`*%Eb!S5VhI3N_9tbrI!sfCnECz9AiT?l&|tbih# zdF94a4_omoEC*a<@@UhsEW7x`t#I8f?ndu-vEqkffOVhZ5ESf7{QM)ubhTDk9r{$6 zbY4_NPJY{dWC4x$CF+kKOujXB?Z+`@#lvI6M`72mCYS~miS^shxfX1kVY3v?ev4&R zecg3QHF*GlY*Ije+|a;Trs~hNE@CMO6knQmx$!((>q9OzF)pbV z=}!oyqVnV7p>Nymisdl)H$hKFa2?3k_4NM8pd$HP)Q5k4>R#KWj0GE=IsSEn+X0sfke5o3lcRg2F&=*P#zB4$+O0DsH7O~;H z_md0M&_2gy5TC9T1#88wuj9oxz`$4{tMO&9?Q4cvG(2^5*iZb2gln-f zMNp&NaOA05g0{RGy3l%5M$+&*7PjkiIZtw8I^XNrR^6W#)R@&=VnWPVltSLg##b10PDYRYy5AF9X|IFg?!+MWU`KK*<0V9ifh9ZS$JSf)0! z#mh~uJF46))*RJK`a;3Mw{rXN6uz@^VB~az&>zo? z)3l(10z-az8>-W^ts){L&Lm=Ep}z8*4qCQ6pitE>al!5*C*CyMA>iz-@){>Q&W`;3W zi(N?g4dida)kZITfLu<2cRPm+jw8Ju(fKCSmFJCy?bnF#rlSr#TaDg7=Az-dH8Cd(@!rT3^_aOCo{yF7(L%K5a?wk_fD9wCUY=0?e;{8ea0W-)hv!RmVbG}!4qKie zCP{6Te*BrNl@t3O_Z)5o{${%FxpJ4-3hu8QJF;&fT+P@GW&l^Np8&5!Oy3mpRFxbxY{$2q%?BbEx7z?bL4yh^xs~ZiNn))8PaGo87ihsaaFo z?Ni}wv3lsN0W3&xT4%h(D~~T(I(%=kU7E#qKG5>? z)EIE6z{i?HCYw1|Df?SSaXit4x?(vW+^*}94pY*EVzfs>#u~?F!>v!i;aCVSCaaZ* zlukfS7uaT_xy&*pl48VQE)ZNF)A?jRV4Ih#(f3l5?TTYG=b2w54=*RY|Jcx#FD8qn z(9trn7VThV@m^h-f`TG{HMPlhCE(+NhDvq3*muiwRWNMgmGs9Xn4vF7*Mcd(@nrKe z@r9=Wm}xkQll?O~TI^awg_2CQ-ee&hcKo>3VZnRvs}-COFVy=5YOY?!g^8M|(eC>@ zC#zMzKaN?VN+a%)`+2U(!fH6$H}`H#@=uLo8WkoKjrt9@AnG8$9+q%SGzr}GX8)q( z!fM+&5NK_8Zq=J}zSNQwik*bI;@dmY_$}Y6ru6t;A6c8a#f8 zo$xuuPS?6kc1zK3k64Z`yNH^tmNL4dWbHz~C~p}rHhZ#ox!D>mmmFKJI3;=mR_2R! zP0;9aXWnEt%C$T3eBK|6Tur$!D;y@XdgHsgh}K(91$=eke*9IXN@6DKtyUAaMI-7h zhP+#EdLzW}JHpw({~t}~7#?S|e*KseyRmIsO*3&C+h}atw(X>8)Yw)tVUxzTZNGEQ z`M)3M)66x`-ZOizd#&HXn=&lcIe+2N!( z_a2r-B^H+LjJE@~?;>bhDmA)KS_rtFPOB;je>IU{C)B9fxq{7csffplj5|EWlUAkX zMCs%Ly8DxZ>(P}FA0hn4Z2kRp(?$Y8F;5^&S+?E0J#`x9qq$Y|+~J@4IFr7! zBm#h1JPZQaJab7b5Ne8OT_Q&$;cB%QhpR4&Nc^Nd8cDX3!c8wNBw3t|i7Zf)Ooz@f zRO1lgCpuXo#a8Q|K5<}Ocz*ecYi{25A|qG#A3@mJj1Lw6a~|qYmZ+ff4`#SyFHP8v zZ-tmZNh3^Wa;rdy_#9X34k#=hSw1=w$2H~&F=Jp?Mm#{iEK8I!2b*TT(&8(Hnm{NrX{E_-xLa{$Bjt4w)BX>h?D>R&F-j-UkLR9jXJhXjW7u|rey!k z9(f(Dgbb~ZF&C5GxIS<65`njb5G>ZEtBKyrQnbL}zNX`kJ3H^sv-Tw@zOsrZ8^$Se z*fAIZ2Z|Ec9L90&FIQ>^JvQ7$c7J~%j2b{zn@;jbNua{>HjS4~)^0Q=VM76e+2tHh zM0yk^2PE9!Lwwu<_x7bA9v$e>1uzf6=o^`_$-pEsNyOLULolZdD;sCQ_=m(qu{B+1 z7$fov9~1mHz-$c>paOVa-L(*U!tNW-cT7_a(#p#XJgng9mn}9)`=temH45vKzxU;b z72D@4QYah!WbZ^_Pxnv#Zh>a&h2n2<0{?2~G7k+r=V6t;KxEe*${AZ9OnHQ8UufSI zaK&N(<(qh_;rY0(Qo_T~y<_w`j8K`gxhlLTv;S3pkI~__{#&cg+j6-S<1C(;Uf8Hd zE`a9>ZbhbtLV$rJokC>e@=QixGhq*{4T!`DLGKtT7?3FHFFlSch=esZCc7_>`ih8L z1ViHuAwv9#cyG;HsxkTUuSz{)rP=y#l}CX7KP?1apLuBMKx1PBlvsAIt7f6V!_!6} zIwZj3R%1XS3V)J`{QVkQa?uH(RjO7SYkvGoDjlbP3kfTh4?SJljU_$%l}bTW`NWL`3 z%C6&Fb>Lqx2haouVLyLW`Qu5)KW7adUrdq+zUvv5Hwg}gCK+Ei8+7PINkS^$_pflF z(>`>2BqKQeM-!XlfA9b(r#vN!lO5nMEN5l@bhg`ul*QtZVx8pFiBox~=qrSAWMq46 znY;?zm^o-m>Jc_ElMlgl+Y(C}nu(W19ewYr=bXz%D?x|bM!Dphg7y4QneGne%-$b3 z_>f%6_aOh#wgmooe*|oUPHZ~lprG*Bzkz-KSsUM912~FGZ_wvAf7k=EtB_BnN(ub8 zPaI>jB`{pGs3#}G`hiQ6$oc;W3e7v@RZH~6+JBL&AWlTKNl$i3#hwNR+mD z8^B({pA;>6sd33X_)a3q_q!Keg|wf4G{d)SYP1|A?>V@-&IN7ZPNH{zMw$|^NbSWW zwuyfE!=GK|+-#4bDKH^KBbPFWGzcvs@_xe61`aT?C;Gu~W7)41IU|gz!kLFBmD5|Qx!!M>5S*k3S>PEHt%G9V$VDlJKOT<5iqG=)g& ze|k^ulnCm_Ebp{O5w$`nV+&1xncG^_)#U(VLGM`i8=4Is2Tsw7<&FOR=ZNO@P`A>5 zL8?D}wK)Sdz3#S8QxfW|Z?%<1=fw6qbd;`*g#>m0jtIWeHBP|J8w<<6IMjkD)&1{| zQHQ-ifMg2DF4}!?8JrmtOh8-4MyTXvKX-jtIj^U`NWbj(47F;v7tipDo{@HUyQGlA zd)bm`w?$mK!1oGvt(8*<+P1hj$wGppUgEZ`n6`k<02#1EswW_Jr0Y`_e=`&(TF$pk>h)yZcKb(b`>`fxk> z;n7fJ8>)igP?!)Dw9PH)g_-!WCPBdRg!7TmH-K4x#0J@IAmna{uw6$^JOP$SU57#n zM}K&WhXr4OjaUDDXzzyyDY7fn&zD(|pH3;m)rLG7UNM@Te|1^#2e5KAHP4uzCK9$Y z=9FiR|IJOaxq-O4S-t;EaBgzrZiGI&Tmr(#3UI~)Oy?K!ykow{f420Q)=`1zO{P*W zwR_DoNK5vcwe+0K&_>?IJ~%DJr9MvXb)M@!$|g0N6rFZvP{TL91-;sbiI(cK%o!KI zV>)SVJJT`T_!t~CMDnG6=2!5a_3PGVVmZ>WOqk4~sq%Z(i-jmWzQ*rfEwu6C-_PEL z+QJJ$MSF{VYtv~#x3HB*%H)02e8?3z9PGGy6f&56cM589wqnN^QwXb{{0x%1(fK?; zCVBQ6ezHmQIQjP-jE2b$d2MliyF&HP?F_|~4tVI>sA;lV&w_r94--$`oVp6CGn=E} zXRLjy{#4lSH@*~x&xI;idJi%^WO)Jb(8w+UKAqM)?x2Y3C_4hs>kdqGP=2)O`G0w`7patt_NuUW)d)U@VLjt;0 z+iCA(Ts|!0BLDY&oz5yM;6})JF;F^%E4^5pfU- zQm!A7k?l#nc-K4JBlSu4 z%0hGoUWx={*mXXf2zUneIT=@N*mCtB+B+h&Dv{_Gzdh);@5+_V-_31^Dn(n=L1+d(z_%#0_K0c9OrV*kTy1o|f-&gw0xB0Yb-- zy!9$FsDkukoh3dzx_7^XkKOa?PuH|=gqvpzoT$weq0I9${lw0uo6me~x}bQVxfa5Scq^o+FfG4U&K+NcgVK!nT0O2GXY{ zxxyT9ulTM^&K##X8e6WDc5}AckWG5XRJ^o6TcuZqc^SYKZ#~b!Wk+M{>K%qf5>NzI z(8!RWKY%2RZ*0aLHLZxy#2$I@A?VHng+@J z3?!cApU#9^&X*74BUcq!C!mxmLNP%JDtEP9@MWKvx&#>wtQG#d38l_^jcb30!*hLjll{P7Sv36;J-tC7T~;a} z^ziTYj}h)%?`N{N8{tf$zhuwThox+q!bUqZfRrOumH?+RF=?thA^u=(9}_*8e$#gl z+%}dpusv`rEaW*21XU~+yY!y6Wg3dngEj@a*hV%Gc2A~weMmRFw<`2sdjLuY0$^A)H?V3W^FD{i`D4i)&X6}!R=vt;aB`48 zSv@vR!RpvN-)j%!mqx8@=aleLlMiWF#+1wSRSr-|;qau&;h?WS1xTjl8UMIRBxg}3 z&rn|R*RF3;?@uFtn;*)$fCo7 z65$uegFSZpu3hr@f@#TcB(1yCgeF_Pf-l^sR~HqkbPV&g8y*I}u^scAKzZirty70> zHG7fawhJpfZJP;J@q-47ZTW0o2l2@hH&4GcpS@Hh1Q@yrk!jOMVexOy0*ip|IAL1W zBDF+^o{#u~!|HDg5k^x4`CXQL+}3JkHVNWqLXO#q!8>oaLf3tHr4|}R`j1u1-Jb{y zY6H8EB0y^uW-yb9@xe}CGT}mBM!sqa?4g6_$XPTXm@HB1JrFHMka(;2rT_Dub5s-8%{q{pVh`7ib3^$OBX)cp2faEFnRcFBJfCT8nT98O<*vA4Jj zqq5!53*RFQp7YI-DpSL~gtYN2AyeD}f8L~N(bv?=o{!uDiz%93vKaLo_v_`>xh!7G zYQtoK|L+Chsi(H|JipHvV?n`4*6wgeKBg95RFG2Cr!i`*!0WFcsMKwz9}eot9{% zzVFP)2h%0q-VC32T_qK6us1@1E!h=lZ%$#tQM4q|KL7FBPUG0FA z%{+EikTrbg;-|&;9j|e{;0!F2 zOIK#6PIsVHB2z*{CE*_%E${{XGDrR~S4u-k>Wc(YGwTPxvG51Ya|x9W`rqy1U32nfb~`Yv{8kzhPppvWBh znX~wPp5O*1v3yUQ4Na_Z3>DA1p;sG=q*YEFJh<1@YPn@wbr(jU_A<+3I=HJ>{ikSy z{#QG1Cdia*LhIK;t=u|Nn$^lrnl$UhBIA@7SL^v$H;swTbtq_h-(4tl zb^HleczrfMVCvxR#lis=s!l_4*=5V7{4&qHJymlj5mr|%#92!izm|d$C9%%M}cram^Pu(N^RV4FohDRK}%E& z^FI}L!@2oiMmgLsgh1t3h8)+Omw&o*rF7yH^@N;L`5OZcyR{ju)_xHSkLBRG`sE>5rs_c0@F;DTJO-36$po4y z7d3>AA4`yGhX+RZ2&(A6O%SO{6O;1gqs#cbmiznqQps_rUbEca>nh|vAxr<5ToA1V z4HIf`nk|t@Sa8graFv=jh69e)qyHM#6n+(__)#fB3bV?j+nyCK9M1ORYCcnMXG74z zY&Lg2wD$6=ydH(ZN^7~n+_zXqIOo?mUgwt`ZHaIQ?SbJ&X{}B-QmGq&++uA%{e;xW zkki$SzXj_GNJ+J)#Qc_qjv8aQLYYELLe`6+j8>V(Ou6Da<+lK#sJ5Fl&#ib}r`WGA z`rLF-9*F1SiHVsSdDizfb4~W@3rvR7C;W{+by`RXABiY^2IT!Sh0=<1WB#2kg_%f; z>tS-A{HqYpV<6gS4C2;(xIGLuLn4rRs~yjw`3Pcgi5e`b@ z9K_M;dg86TSL^S?MKTwckRWO)@v()KS2IQ+hpo@llI3KYon?1up>zT`g2{RvQ#$fs z5}F1&Tk{2jQ8v`^k(Qt&z5E~qj>Q9D&^4rz2!MgC*tZTukyl;pyyevZ3%Gb1?xA17 zb1Eiz$Vl|~CbuM`?Jc1G8LyEJ!ZF#o2@x%@eb3c^@R4Ow_uto_=oS+Em_+d8a*m~n zgc#*4igrkPb?@XP^q3TQ9SW18XgE@bO4(j zeKtUnAX1De9O3A<^x%w>BNUrFRCyFN(PSZFP>roE4h0JhZl~G_I{#pdyUSvrZX}Ty zKaw#+YU+|Ay{s(L+)YdcU(44ofn|r>G)5;+BVs~z-4Bp8Cl#iZ=3bbA&wV_^IHGmH|LtfbSJp^_(xN zc1#?g;4JBa+YWSkaTD52(c-+QqX2v@MaUctR`b!8^{&TZTLujWvH4PGgw+uz zD5@cvnKla!Ra(EvDdE?pj#Dx(>K43<1kBlK8sXnQyvN5lUfaW(ZK>*g`_;Z2oU_aI z{wQF+p!sKi3HJVBQdau6b`BXTnu^XKC0y=b3udD)Zf9$5siqavb8YIX{#nn^c#1?| zd`hHTdwV9N@+`6@9@!ejbdou5s&i0fJ`{DK8e+0)l}e|qz-G@o7<^}YnB(AI+6OE) zpL@ZtZJeos#;?7>nA&016bV}wpWA|W#5U6`K5#~#k%=@GM2 zWn|1=vzv+dJ+pT$8-G(``lq4W`%(ijSO`^{t+{7au(J5=zIgG6>HPs!Xi1n@n0r5* z48%J07%jFCpKbW0HV~j#t&^qD7bKV-J_yUde0YFpGz(>&2?SbdM%R`(ml|zY1s{k? z3aLs@zfodT)N$HV+z|2K~XeW?Jz0 zRz`jq=4=*fibQavr`zYr`b3HAXeL5-e=bTLi5|MNY_Z&J_sc}~6C@t10aYh{12Rk+ zqlURrg}40Yg=x$A%6Q8=?H~H4N^lNN5UhGUZj_wy`^Hj6JYW%8UMF;36jR~v%q~k# z81fYy_c8%2ospv&B#BmgQ}S{=>RtbG9I$9hzV=A|+$<$#wpKS0#dhJ}B*(rJ z`&||z9K-iZtx7Hj?%4NzL(X=!IRZrx)ihn9?0e(4Hz6+yFTCmGygWH4D}-?*Fi1&6 zf7H8QuNPiP=UPl@!#5q7J*^lgbu3BPFN#d9NFxw-N0Ud$sY^F%)IMt2$7QfJmHE`eWs>wqY!wcJVz@@ zs}9{^@E1J^ISxHB{?PEVjfT=DyD3%+g(TA=o_O6p4`!!9oW38Ek7_as102{bvSc*M z`3WMvacgIDt`{qLMZBn%w-5UG8boM9&oI~F{oI-;W=C;@%N}PGi)fuu1vGv#8H&Qs ze%sDOWp6NqD4p`97zw7CnLl`#+a&}p{ogP;!J#RiMSDQ!K5om|N<^&OUiWlQF%ysG z{mJleU1{edR~}KtkKmM7p1&2~n5$uPN`|3tR`k9JzWXbRT21D+&3s{k_W^t)Sy?VI zEOxDiRQ!yje_6kA=~OM>kYd8^R_03G;X+;?wx16TC>Sdsj8lt4i*+~qyEtF?^8@z$ z!vWnv?tXQqS8kFB2>OQT=7nDYDnllfm{8jlFd0cO;!NiP9(%V+o5puX8SNkCoj?Bm zVx*K_i?td_*5*$+Bv6=%G=JJ_bQ;nbzB?C9B}mHyUwh}O3I^U<;%Ty2c*MtMj8+D{l>(AuKQ z7&S^#B@G_71!;kD7t^Wz^tn4-T!Gwt{ z6mni~+~wC{yXmiv_inH{n(B0h$Pj=~@I@hMvgzaz;WneXRD06-;#Ef$xz!i(M{DJS zLe`Rs@fWBvS9>dZBcz(3lc;QZL)v9i_kj-74qI0M$!-a^`?_-v=telT!!~jockn)V zubYoYXS zUF$O=n5gunFVoQsA0Wi1at?W2&uU2(Dmr&Zh8iL{a+D>AWR;kqBHb%emt*( z<9fA9)eK8%VVPh?42tyzQP6qWf_QrENo0`bndD;p94AHE5O(+`ytEZ8R?W2W2`Ir{ zo7_CpAFWI!G26{@4E+9+XqI&V0 zCfqck*tXxIx_m!#Fo29GWBvA^Pd`J#2H_Nwts^pFz-^RKNqktar^b*Gxr+xnztm)j zYp@1K*;aW)-~ZtsNxrX>(0h3NUJE%f0$o&MM}7g<8o4r(Im|T`;9aD6|I_vn#HL@_ z?`UPg+Ocp|WsDS^$$PDedp>4)*QN=K*YXhXS-jT1yjqtkqKLOepB*j@J8qT01A5#o zeMy?f3JLs*Ss@9hr*FMF@6%wwXrF@S>srPrS&1s`FD>7wso|G0m8rf%dsr?-xW={Zyg5 zH996rraX6Z7rnr03N6bz&*DTnSUKFu-4Zm>5~{tleIB4})gRrK) zwCyq>(YR_~Nxg0T`ci(E{oVeV*pF|Hm>2H~DX1)XB3B@u1+L@0g3Me&n}~Fr&AF!KeY<-yLFyyCQdt@hIL|`7UNsR2C~6g zcFmV#Q2{S?o=n;rL%VUW0b1~SPsm@lh2fAcJ3oX$Rby6R zqk_g7Z1RleAUEf+(Tkd zCxIWT5QQ;}owHuD!N9)V3W*=Z?PU!(6&^RQLy(k8M?UZh{k^7EK zhcKO^BoanZTw*csVP}YEq<(Q@*uy^689#gpg96 zjD$CC-fx;bP`ppD1KA)o^1xJe;}tj zN;6Hjvx5R>)fKu-DGUK8eJDCN<_d$7pROjo2!TvLaF1m2P^$Zq0Wb8&G55O0Ix1xO zenOfUCbWnYlU`IiTPOYiVp@aWBF3-9U((hlx%tpVA#cnMEHh$q)6HKI!Bg?Rw1;$Q zmDG)8=)fp)+fpXu(*t2D>I&6P`(^~L?O-a&>7Z?4n6G^R!!MH_x<15gdg1e@DPfo8 zYDaBC;xL}qP}rf!7gBALA|X~!g_M}92JIulLn~s z@4dpxPHA*RAh3aT>nzE)BS2aydepPcxJX9n<}b~W>f7d9b#eid?Gv;Z!Ld6^Nc|Xd zHwYkU=*N`kXIgHI1w-k_b+3$P#61sT_oUwkU zM1l$CRx>3+TjozWzDw(bdq?@_XQKWKVWbA3Wd6rky|mfmC>3cC!D)+@<}re{>8doMpQ> zw1;N^lY1lbt&*6b_^AbM_+y6gl3hyb?d!*Z^g6|FM4Y_ss8Ldj;g*mKH?lgu+MtkB zSlf+;964<%42U$w5j9{=SYv?6bF^D%VB(b$=C!thBqQLl;pLIHg0A}i?j8BZzsxoc z@VpK`tK=a#{%G!QnygF^tSFo&d;d(VgDITXz=>43g6;)koqr(!c>_3 zAMNaA(5rcoDKBHFK*QvTZ-u!~BHk_lmjjkUEiZdPc*!uXf>OPYYN~_^lCBsjMh)fQ zOLRBrMK`?+SAFe(;KUaX94K`p*%M`-47VY>h&aXQnc*GR!~ni3?V?kZleRyOy;Rri zaCWOrG&Cc7tp)x@H$#Z|Ay|`Quz!PYH&pzS|x0TLpEbdGxHHMHYSt9$o=){WxbYnI;2*c(DF$O8)D9M?6 zF1d1vi|=Ix%6ma38ILi6Y#815nZh_qf^9fUNq!?Lr#` ziaz((bCLO@X#*#XsG{Ht*#(~xGL;p*5R{L|g(CBM5!j)<_gmY*>Z(N_;5GQ?|#0sRJ03*rG;R$ZhSQ% z5TDvdeq-}u&~+y+G@i3q^V@_T`lE87nDZz4K8KF(JD2rJa_2>N0+Km4P1!^qcTNes z(oC5u<3*brdV&8HhID)`MYjs~h5sJ=uMA!`^+*CydGk|J!8U(K(d>Ce8ZDKtL`ZWi zW*e-xPk!4Rpz?C|x7t^*iyf0Ab^7U1)cmt(a4#eLXzuWfecQGU=8ins-fiiZ+3=+v zJ3>yH>79w^7&DE^fyjV0sdew>C=67~1d_d5ho0TF_Lw^Ywn&>=0$??Pq>KzAxXbXV9X{d7(&VIQR$Q^LnI8J~I;pEp1As>DD$wG7W$nE$MNNi>|F;jLp`z}99P3AlGvwI6sFa`UrSvr` zEm35spJz?+|7Z9r$Rwv&@87BOfVWYlGoP(Bb;u`vXIMlznk-tk@!T7;tlVr7j3ZP# zn8J8$u(~yNzGY#ze|zLQU5bEw_rBTpak$!!ApK53E!cXtwRCL?q%utS49pUpK0L{> zFLSAA8Ok0hxZ&bX;Ip65N{pt>_e>6Vv%zA61w|J}moU=^PYA2xlwx%%2pk6;SBPLxDq)aY5MY3H4Pf}z( zc;H&y9j^5My#Utw5wr!~vHH@i5bQufF#|>Rkh-4i?o-X%nY>nKcF~NS@XZ)(bFZuZ zh@XayaFD!HHKTpxLf5n7cNc%NmX=^TTu=J_S~rJ!;*h=k&j>@!BGE?T_V-(Ri%l^pKd($ zgnSfz<6_R?p;^GT)$566uj>+@4$@TR4^@X4bOW%LXYd8L*{`Piz zNhIPJZ5rWz`#eOTC+tes%s}IOc%HEJvtfa?B=F)tcSwvzUYC(obK;Xv{R4adD>BdPA!gEKJkd0i8E9&7P* z9b%ugc1vDIRAJhOZO1D?*h@5vs3-lM4!xj>_VGlJ#d`-z?lc3{>yDMbVN+@l@A|jJ z76tHvIb3eLM~_EBZ`vVnKNODjJ|@UsP%vI;8haas2lp1ubKe~;$34Ly8waVOf}Ap+ zjw5`Z_8;#^*aDHITV^|_jaUxT5`8}SZgK0%mUz%%mU_IfMip~ojRrr{2{ryF8P#!} zUiwEakO=8(P;v{Wz}+(_<3^0lY0NfmirGJp#-+L-E&FV7Y{ms7;7P}csf5=G!_5?H zXlKvM?^Z5~Z0k)43yi9VBB%^RbFYGZD7;pGI|#}(P2;a{i=Z!Htt$8F=s=^0uvRM_ z%y5=TnWbi_WmX}-Qj^4krIv@%=*Md%eJTyA;9?$f3+aCTPNU$a%mRN1bk)q^m0`Ib za~-g>38ZDd&wwc+-H{^b(Xk)jClkP;&T}mnBTK%!{)#GZJG&e%bGcnBs_TVL#3|3^ z!BMTBS*zl9f}P-#^$S2pO|Dp}V#M`yBLO9+bq62UDl5zNay{i^o$$B+6ISjts4Sh@ ziD(hF5(<2;nJx8)O;(oozw`miN(WWwv_YNy~hy)Vy0Or9MyX z%|<^Y)oRjZoVLx`03Gg^(G0>7%)|_()N?-#;G#n5ruZY0gP}(gl9JOwD|xScE)P)1 z0lIyohKj{5offI8Wud`%knrOOP8a_~aG4F|FU1G>T#wLEa=6T%U(WTWrpW1q(|+q^ zPJL0B2JX&m$fc&6{jHbtk(ax7`uo%0JQ)FlVX8=e`Kvq8 zlBCYCtAzuEEB?a8bWtc<`{;6oQATtM%HVH8=e;iWcujksd5>r*@eP z?-&Oi+Tj>Q(oplfXWNXW6wg-1;`4ltR$6K6Gecv#AVLvj#Mi@Xj_0f3g;y5$pFY;# zI4nhcRG6yUoP`8Wyf`o=Q-LW32NR}GeL4t(1L;uIc9@{DnPwkp&|Ky)qer8~vP$;+ zQ5} zy7U{I2Tj^(0;C#jGAeQD9eOXl4mF_jv)cPgWQlhg(w=!9gsw?c;1rB<@LdyCDRC(u zHq_t{8&$tD`*4f+^H2jmCMkNT3#KsokE6tDkVUmC&<9xqul$&U`mfyy0>~`*m zDI%|dyqnJuj66wg95PGp2=uP58N4F#P4rB3g^JA}wMvy7@3>XA@;l$$BpsOycF^cY zHq^88m0^~O$vo<*kcBS#^dH}9m#PD4$yspGQ|l53_K_>xd^4?#bvj6jt+r_JJQ4W> zw6}(`m}VK&sA!CgGjXjdt@K3v;3SVc6^w@=k{iaHhG>VBi2&^WZ=Fr{2063^p1H3D z_zL0(wwjdF5TQ)w3wwyMpKmT-ZTUf|a{W$#=xAAlv=z0=+}hR4V;n~KIY&CCiK2h> z#Twn&YPBj^2gCwb1DP2zit@9~yP>ck^Y&QJ3;#2jaFmmQ98*K1y>3c=uWKk;#oQ9- zFj=)qy|9&go!gzGdNoC*ZD$Qs9L9>%dkVYXc7UQp*&PI8Lk5%G$b=YjEfs)lQnC>` z60VAE#BVubYcq`^=Y4BHn>(LF@3p`+&64a6J`^<(c%!ReGR*Fl!<5e)vw~1LJVw5b z^jwqT2XPE#$c(rX*%}+gK+IMt&=a+~#z9G|BpOQ0e^Ez7!U7*@=NZeBb6oNZRrm(J z62M8|rz*u#1rx!E5Fk4kB|OBfIluj$AteL04o zm+d*yrhbn=7{lGw*YK%ej-yYEL+z8TA%6oxo6CWF5`i*|hYOxCp;3tf2#fAS(Y7H? zO38RrR$3eT+EAT|)=Fj0k!aUSnH>Kpq~k5H%RvPvW9jFsG=~$7WalQo@~koG zD2H#S=~0oh=Og1yIrG;gzP(9wG&z8-B?bAt@95gw!3^V`l<-NN5D3ZiV#dC98kl^F zune5FRvSXpi_O8PM!YuHZ6-mF%MyhQ1EcIrVDxR{*z~yNeS-pwB;+r1jjvGPPXMvVP5cev0XQ-o3uI;<42xCyRgmGQY6T_ta~OWDQvIChlE#wa&zrg&WzX*#Lr zQnLnDi4(cQuLu%A*N0Arn@xfk=5G_AtjzY#@~zn+ZeoUEEGA706eo{Z zb9UAnkEO`-GJh_gZ)WpqylS_-4WLqP-!p4W*mnDM-Vm^6;1?m>N4cRh*`=|fp*q``*HJ*R^Oii5CW>b5#gVKG51L;}t z^^WIVgH3-`7G;FSvv+51NGKGAeLhSSldlty zDCKu`ylcy?B84vJ-A++7A^Z#n||4oGkOx2Lr>a8Xea1C=#V~-nYpr2F^dU4=(*pR=d|rE3-U((CAN zh3E7B;_*y7E$`YBvVg}AcbyOT51r15dv{iQ-}5L@zf7{vO>dR!l5Vff zP0^%Ba+=h!>-in?w|zGuCda9z({-y%O}oOBi`vbEPy_7q!94BZxgER_Sh_6wd0f9V zIwe;E@C<#hd{B=@e<_KG7dd?mVG&C;y*villC29vp`M4IsI4zJ4 z4eoF@)N?0bpRQ1N&3}74F%7avus3tb7D1;Ksu=aPQHYoiTt4@?Fu=>b)FrgbsS29FKSLeQ(a?HHGssAbC~F9U`d6n^=NI+g5V9+%D#~7;8{8jG3q2|sOHm}OSl|SQCj5cj>$hz##M&>Fp+CHpf8Kvh1}t$z1a865 zr{3_rJ*j%`Mho)2Ho4$89+HhH@P+1FdL`dZ=Sr7539icuZnd$;3wsIR83u?R*6EEr z`9;(p7ApRb#)ui_-)`b;b3YJ%JFBik;IN`0;mAV7qS-p4nSuPqL~0BdmLALe@?E=t z&!ifD4QKF>G~iGBDc+2h;dtWr2*(NIl;gxhmm7Lowp+Z66gG^uT>G(n*x*f|owN=}BxnFnL8w+AQ7,+{EZ~ zTBT%lT*4UTc#q|5b9)Hsx*ZvRs^k*wJwS5bbm4QF|I<`5>N2N}_kFg7ab1esMYAvcK#0rONkalH;Q7(*MS^J{P_};ABy^ zs`)?r^fU9Fvd-|r{qIU$Ec;CzmGb11mENdIeko@nJJLQM_E6t6SCWjx)<}Qc_n)e^ zI`7=C@_aG8o9~g3-K)vYT+arvnF#(P(nKgEp0i>!=ezJuu@AtZ-M`1hX^H(D9a(C` z;#*t0ViT0pZjNs>DwSN{hX3YEPlUNPK<kwFfkfmV+Ye7CMhWBa0?4Y|4v02TI(Lmu) zI_j@!#llD=vg5ORI^l7+mHNW(zz(TLA2e+Z-A2LAmvV~qjM1KZWBcUWu@WbK-EJrG zijProqvAv|#8WmjRx{TX1PKKU1CIr9JYJ1lLC#9Nnl3lltqqRyC-!i!<~h8*wG@Wvdpl0qIAFD zE>dIMI#NrGDD70tscG0BCaTtL{Xd${fxEJ3>DqBRwrx8d+qP}nwmY_M+qT`Y*|Dwf z-22||51g^jSYy|!J!{r8_r>vz`UdbUW-YQsg3?VSN?~I!4mjb-*G2X^BQQwlskmRF zOEx8k4?Uz36m?N^sHM>zpk2wUB zR>)xM>&)YO%0(qRIvPP4A@6;}ykZHu;6{!_SO%xU&QQf*{6QMqE31Oa7P>`l7n^@& zd#nOu+VuDwz^Ewy_4@X7N@6I%abls9GGLM^@d1$sb`bUw#Tq|rF+4+2i(?_zg*Zn+ z4=m^$un5giz$l1vRvfqBiOC?Ai-Kr!4i)6XOu6L|4Mvr@7$!oC5FQ}YiL}cB#wA9J zKcot6suV#gStdv-mXFq;5#7#QtlYAPTEL58n^`W;Ieg%Vyn*;C$t*_F;B#QqGO?7w zDxFGKBp#RBH5^nEMO3q5RrB2U_nRBYL3||M-_bCls)yECpO$<$nVb=VDd-S&58&HW zmq0W~mL8oDCW9WInj?`PzHdT0QMH880#S{?SRMX#`$f*@@uGWfg##rbU@0igb0Anf<_8GMcW@GiWMZy zcN&uFeci+;W+sBnR^k8$$7M8Q#oNFjd8MQf6tWiKrexjt-Hwd>Or7T87kLcj;)23HC2h{ymaS};L>D_0Uyo@lP|3#lS9V)z!>aVwre^@T?U=<1E7u_YQ+FmYi=!7ON!J?;HpDEu&Vlr-#F=T9)|%-R7?k^qq6Yxw)Pg}oer4@`RO;MOrpFapCChh zE#YK?K~_`kCq$c?ulq3zz^Q)mHS|DjpDG||_ z!horSFro$;l=L@~S5+g5dXb5v2nn{kqeq_}qb>IOihnA|V<-Yr-}6;|DC$QXf&5!PQF1%m z@Oq-M70oOew))tKDRF*^arlc zvOn2iik(W93KQev(Ui{^)tTi41#!6C6zKjoN+~Xu;*H_{PF4|fn}?61{RKAWN_1Nz zl8u?%s3O_ANk=LpwP{>&iz=!)e;xAPtJy2}S1G%2aAKVp=yVT?s8EVBVf^7A0Y zQw~>t;o}t|kf`JjwYbg{^q3Yf42lVFkel&^>*Ss8)tcY4d~mwM#Bx5V)`%)h{G<@f z#X|i?m!dy$&8otta00Jgu|YwEi;u7Yja=(`&eEeTw&9dx(FRf#cNXX+X+AhLScFr} z>S;Ix@8<45^-cRtpLlSH!tBfWHRtB3mlu^4!euaWj1hyETg8G!=RcYD<@v-!`O0+h zN}A8Nc<*K72A{AkF~GJPsOt}tQEyS;Wr~~BAiU@n*iI@;gPJBFc_z+@K|vtizlGIY z@N~hV;X=*oOkpIZ;Pa84j-N@*qap^WCnD*L+?`(jbRLM zRIh*`pFd)LY?;ag6p?&gD(GtoDRy2C!vuDfr?wV4s_zHS!AJ2#-RRfpK1zkikPj`E zNS`efjnTJR!a=tEr~B#a`pWb8B4!yi85(#O_woPM|E&&6E^I4{cG0GSRQ}85*sera zBI(c*idREQh*#tA;k)bR_KAIW&zeFSG@*;M87O1kM121E4}@)bRfUPRENL)$2#n%& zzeO`td9}va%6VA*+(H>JH}s|0SW|uRNH|7Vhg0Uvm9?5bhYd{?1}=O6WlZGOZ_SN( z*58|}4}*XDO6W5RdRwFDQdA8!*vE)(v+?r&br%9d?WW)zX(N?18I0Kxp;H?7ByfZD z10}%b{k$=B|LlB#39`Z`yyoa?#DJ;Tu8YVDgPzT^m=NEZ3*{A57{7JTwckc%EVI6Y z1)A`>OJyK(O8p~?Rw*IF9UFJ9Y+`I~Y>d)2+mYkC3U-Qoj-n4LSMXOi2uB*v_4q~O z+;fby5*a{9x5Pn%iqcb1==KzQB`%zISYTD)+}h7_zh$+B3upN!z4@0GX}2A9R~-|u zMAVaYnsS~@=>B%SG1sXc48#75Xi&9;9`*Y8MW1&{)Fj<&z*~ZR>OuquG$XK9$y%c+ ziX};U{Gg;{v0)C&ieMt(7|Jc>zWXu7fZ|iXdS592TK)Gb|0(@Sx7y3m*8&L!`{`s* zWD=MkMtPYzx--`&#_}8<)KE$%1`n}zXdVy4n+5CL9$lFJII&i%(=+~ppEMb29o3Le z)?IbRz&8G^hi38#Bo1=h=6I9Ces{o4unyaZXmM4pY9H@HmX_*#BZz3Lhjvg`JP(jXpKrft~u>~4{OR?kTxPfD5NY5n&*3m zmL3r2_ru)hbApu#r2kp{lEBEWnEV7LY75?51IboMw>Om|ASHCQl^@C{Q4L82LL8Vk znojuWtaaOBHG$ll!_5u`i;jAMI1hR zi0fL^{FYVC;(V?LeKR|wUfe&WL|ouJME{KwBXMNf*1z=P+xvQ{jE!?~Ss#)+l6q(T zmS79hXo)x)Fi4@>m0DHXn|Pd}DlyE5I1d5>3UglK36rMpMYKz+Ez0HHNnQ12lM{@c zpu@Ng4f5a0`2+VMPH3-wbM+Z@D-I(Xyx z4fiLtc2rfUt{3!dqXks3F;`Stt+A&QLd0UVg~InEHR+TK*YmRB2%}Auw0};e$>xoV zO`T0aLuJ~o3vR^Gb~X`i4hxkprbRow&*XQDY*?*s7h^e(obnZU@0S<7|38)KfSv7s z+eIu7y_xdH)Ut+-OrT-#B?@n>DmABB9sXs?n_$B4DN9Y>-fGo4L!&WSk)HUVVb@}U zg81~nT=)0|4vZ$5l^Trp_?&)`ZX3D@mqh$y-+wDTG>%Kd@2+Uo8}(=?V1P+}{NkeAaPp+)p0ASZW;(k+ zV00bUt&yGU`?1vFEN*mQtQ145*%~r=&INGVW3gHwhC0r?P9#}Qg0;sQ9p97LY&8dx z6L2-tmCWV)p>hc|_GZ@geFm9u4bAs{oh>!NsAjP@x{Po!3ku{l5?6uKQcrh1RBUyp zn$oZlatX%qeVwgz@XkCvRckaP50Hc*ukz8P(vuyx8XI`ZyOidROszDQII(C~U05=6 zJ#w6YKnfzoPp~%ljBru6+K`b0=X9kd$bH!CwxZSLr|%DiDWW>BH(KIJr`3@n%C_x% zQPNyQ(ag|l*C*4Z{El#QI-)k@$(PFdTmdY9wdWXfAQ_PhvZ3qM4 zX_R&q!rfR+dm!eUyfKj9L}j?I06|l(!la_Ms$?)}HD#Q}|8|NXzow=v6pvd=NrjJ3 zo@jL&0-F~eFO${K7h%)0iCQfuN(1FA;_9TGXst)IJbee)v88J1Pme zf2OzRVtVu0fn&S~-qS@Ml}xVe&BvV8a4<@7wB_9EO3L ztv5q~gCXNFf&|b!)o(rD_q)=&d|0-_FU9jJA>LnbqwllIH`;S=(CH`?30=$8rQ#&8CMW!d|S_8C`$kH`CA?O?B3F+|5#~`NsKbHrX)Ab@B0Vc%z5P z{V|^siV2{j!C*XGR>tyvoM2^NW_h`=Uo);_YNm;LSZ|x^Fgvl8Su4tJ(|e=q^LghC zyK2Drqpmh@|L=Os;VQ-F^@H8xvq5~#cyQlFM?aAMy8o(eTc*^BtZnC=5`pi7c5=aH zQ)hsEm(KjwAWm?*vg2fO$|BW>tC_)MVPi&z{{cNLrDHnRmjbPY{_EqJY^4+wfa+`% z8PF}zzBe46 zwD-+l+ zMx(fG%|55!mE~|v*Bv>t4PqyLcTi}5fp04_nOhj)Lve6!~oA)#zTs z677WBA7-;G4qL%8o6IR!D0=KhsH2aVy6pk{k3BqmpL4V@xZRuP}|2d`WPE+)>Z7&wx&6eX8eVvh32+>o&AuK*8(yz&> zUdX;oZ0nAfld3zE64X?9fsy;OErdncmTHaG+|f+4_op+dhtw3G_dAN^6}G$e)rXF& zKuFBLW5F&cRqE9vCI_(pc2dQ!J2JY7!X1au$_kW!>$r}{0&p}o@9_U75P}8PN4)>j z3awcEa6TIY@6}2axdVmW^Ba(>QnBlJbbnrkbroxgL`QVr9q~HtfMZC+L=-PdX0Z8& z>A0$I3WC$$)A`1Rr#;}nh#Yrd{SLneX`RuZ+y98Y@&3O z-1979^LQi6E`hqi_;$lteyRY4e0=3xi%E&DZQHX;$LERG(n^PFX)c?*&X-4@S&WpC zxHsa}Xm}0(PkJ%!=PTOVM5Oq5>AROCS=+?hsV;Hb?pt!T_IFA2j(@gKt4~#NG(%SE zY(kG44mm)wCvuLT!^ zY}seZ>o|qaa2u3VT3<8y*t1XK^!Jk$lg}kj*=(Cka@VC=n(b1u%4A8b+@wvD%cE|> z_Y?c(dg11@xGzx3k&=vGr(Ml<&(3z8$yr>h*Lb>;M^I5yr`GBv`wI&qWRrSBD&O^7x_JZeHp;zl3EDn;I; zMc=;X;|U0X5tSkA^F3$EVD|I3w2_mn_brjZ2WXW zU>hG@S23iH<$B9ilEu$tsY%oUdr#c#e9J^nWc)J{ks+MPLZ8~BcYIsgJ(bLfSpKUr zB_GSD!T0&7Y?+#@Qmsp=+jT?k|9$JL$#bfU1;|U&Y-mvwVZI;EVV?v~)1|?&wldkc zQ#M_%QkPa{=s(uqyyQQG3(4zLHDJ{;oy3BSuZDnXr+c+>kKS6Nl%{`Nkl|9#){ zVEKP{a~`wt^oyP#;^qDEhu?F`gb8VmoHSQXstPq(g^E<-L@{ZSq@|r*YH2CCrIl4; z9N)XdmOsAS7g2sU}+5cQuQ0Yqc+Q6BO2c+@B6DZ zf6>nXff0#|ZX5jcSu=966GCJPLa~6+2axyVv<8y}=JQtf(J5nLUHqHthI{m~iMtkP6xg%_v_;_R85xmn$%xbC zI-~~}baNUZLtnsoB{rh0=11#%bIwMm?Uu`nugy+<7{JV_MyCt?U4W?rA|yA|ZZ@C4 zqheoGTDelz+=PQq<^{bJ(VqIaCUDw%Wl>pELNy*A0ZGau?94R;V28Iq#BLJh##QLa zI#;t}5h}ooZ8pX{Uq$^}FM_;Ssh&gsJVBRV%OFpWA0=B?ktPQ;>(#Ju$!^yIX^V0; z)oTKlj^ZKdaFo(fdOaHtW%j2D1LxP&l1+|FW?s)Yh7a~5ZCl>l7#%>Owo)998z4C{44-ymEdB^ROmEIu|5qH)+)(~q3OvnVQbgXs z-0Lft2NOb432mb@>-|GfAz|<&R``EfQR|i;pCo_8`xMMmU9qRvNu#G-hUm>4B(&~4F;rD#x^CF-c+nSP6D%sOSqpTr}RIANNRba`Y<~S#tfmo+d6XPD<*k{U{-K?l6 zRj`U;-cq*-4tTA%J&s2#*6bP_wgfqxPuA*fjiG#CP|E18V(hl1Ed~3J8r6o9v-Eq-E;lBI?oV=c9d8)-nch6Z zp)j#|9K3}~Owo}OY$+)z3+;dT!*f(?76rLTrc2-lcDP8kbw!5OznxS-5F9%4MsS4T&}Q^jc8&WF6Ya!G1eI2bIM2s4=;hKhhDgz zi;+C9<9N~doXOq<9*fU37GZ?J5Y(%6hi?>l2a8p;`?KpWEOvd4dmIt>5#IP4@|zD1 z(3JFc(xxL`h~p7|4QAEgVGI>h;V#6h6+2$^|2I8l+r%0^?)?$oy#9>h1IUQ_9eLvZ zU7S^;eZ$ExlaWoQy~dtzqh%f*Zu*_BRAvXmcRVjEs?)iy7=q4p{&{^N`n(T_u{Hye zwx|2v_J$UDwV&55FC6zFC{%Rx#098PbPv8 zB;?h4t_pV10^G?iw1@F`#vR|$C>-y@6`yZSeJn1YOwl{W9QHmBWDvHl;lV&Mne8-` z3=oq882?tPq8ai!{*2)hh{VNSaX#ixbbp`FY;if0`*x}ayj2vx+v)N*e)%e6 zZui&kbsRdEJw^tDmiJCw5$C3air|bA6z;sgBx%y@Ylz(kg>(Rn=kInN&!#)?$lu{G zWjyPiAOEd@_L;Hl`gKJl&GN({$noVs-oW0D9Cx|$$xm~owAzvQdbJ!5I+r@nzka2+ zx!`>vV9ItEgR1L#)4j~~W@Y~UV=0A$4GNPOoJ1 znjJ;y&1zx`sQY)Ya<76Iz2y?S^1)wW>2N4Vp4;XBKD0eio=neI0!37hLg zjgkAJd@sc8Qo|}ZI$33!Y|z{|ypDz9#T>dn&2>#;Vbj^os7rf=E~(tW!T#OGsfC%M@S|RQ<#g=pl*N2v*pZ?KHHK0 z>jhVOQx1>wt(*!SI!rzpXkrv%=l!aQ#KkUY@9cxXaPO8EbE%K6 z$LnS9N&hFTa)Cs%+X+SYS*cuu2%u}c{Uwoa^x5}%##)IHhUbobsB2I0HupS2Lt8Qd zyW+B0?+yb1|I@hfJ<|6g!n#}vYMgJGrWf7IiEugUnkBe!Z>FqD`T4P zfBx%c=xg}WxW(xCG4AnS@b0)IB@S{1pb2+=eNGAFA49A>p8w6;Irfz-!3K;0V7xDT zalCJO7+U`RZN8ZgbY|el13a2VdF@_jzl*O*< z=+;nMOlA{C+s)RorvsNWwb6dQcdLtYi=|c)^K4J_o-TJ%{{4oza^DDwD9KWv=Phqk6bjkW zW?^jz1gydQz~J(lDze=1!}#E``8s|3D!C*adX@YZ;c&TaOjZLRsImD{S)4F9Jdsnm zt9hpI#oQjOhD|*gE(79;6V#^|xXY&1+~^H=u+TUBy548+XMEl$jqU(p1pY+hIL>Gu zd1W1?!TRmzeCINFjU2dwa#`*7rwie<#b*zwxa*!NEWm%wt)jBpj2s9KZ`_;@bfLW( z1dxjFp*I)}4@@A^QkYJM+#R{y%5>Z8V9(eCq!~H`Vy~d*si)fTW;sILc*J6Ofv!A; zb!PIvK`~j(SbIL;@_TC&dc>}0N-*>VBzxump1^fKhI7hrI53BTL&%^5SB=ad(!vs7i-5?zVNfLKaF zt{kEh&Pz5U4sl#x(u(N9(%!)RuA7MvM`KHUrRnO6VDSI!eT2YV1gSVv&HJ&WaM(OA_(G_o>5U% z70qI^b$i=xcD+!WoSeLDwgCV0-^q@>)sO0{yL#WL*H3vT+0j#vk``sDYj;t7vBf|J&WJZEWvt@{bv04YS@Ylmp~W16wUD3 zOAWRrglTe02ny6+5!zji(PGDDF>|sy)IfV13E9n1>^ns<#A9U29I|CqF`G5{O~h8r zU}(<=5GaS{KZ1;64o&-dqKGjxz!1SC&?Pz`Oc9NCTJoN$tMdUxXdyiQ$djeuy)$o3 zN7e<*V&(p3C2PcFG1)fbK=W*rwJPaVn3XM5vJ%CB#r<;!{>bx+&>KF_xJ?58SnfQp zF!(pmVNjZf(k%%;S)_;*2pEvy1&EkG%t3CbYN+YeW;p~V4!Us)hw#mV7%1l*8_rJ6 zS7lJcQYjS*$8oIC7!fM6#CrS`%V8~gG$|=F%9?&+QwUJ0CS22|Fe%z1>(?5x$E;ki zGu*MG>CsQikvPb>n~sWFhQs-)VKQ73cNBAbshf6Y3VnPQ3;C!HPux1&-1gq|)r&Am^;cMzD| z;3)9xaM{e#PuARtfw4x)d7dxot&lfVa5Xh(wDY7$Wg< zK|~_`z$BvN2b!BH#Q_r>Z4~9o-DbN*TD89872j|oW-}GiwzWe`Ow4k?l~H?G54cmD z1V;-CAzAOHoMzyr_7{mF+U|1SJ$6^FGLraDSN0{p8FvTvtuYVj!vKrx+h*Tw@T9R%N@?=AdQvT1Ow zu77)E9JjQVJsjd`1#Zjb^p=9LRM!m&FV}7nSY*SowyMie@)UQfSHKt*H! z&J?P-13I=yMhVi^)`~@8JK@-n8Z=ap^ML2HG%f^V2O(8N3r5>BooweoM%JJifoq#Bl&`yPXTyv> z6j>Dt-}h-Wt`d4D!--T&Po2;HX6x{sw%fji2T_!RH)@Q z24b*D__*mSf6wJ!M#xpA5nY3`dbwH)SlAj7*47Rz@jkenv1 zVSJly5w^)dcg-ixZ;oJhG{G)m97`6CW1dP{KT9F>zYpMnjKH zR)LJBn*DOEkzj1RubcgZY;$MRny9$TUmfR_z+d(>QF&_-5V&rFi z&6{#4!SL8({l=Sc+e@of$)oocLL#kYG*0Xx&Rlw!NiCiTIvRd2wUe2W!7t;%!avp7q^U}pO(7c}Jk z;=y;hZRN zzX!R7zPhy^hXyqMp4r~D+EY5GC$_BSpg=V{5HuXDBuRc|Jn_U`HXzguOEJu%7zxT610RV zFu-l0fFeO)P{3^Vpq0gI=5NW2t;W^4`h?w$`T2UIEe#ctOg#COdE=jkCxvUCdhWO) z&`HoM4J;nuJJ4h%&FJcwH+-P2vvpF)x+9P*ytLEHF>X&LZJ>66c@gp?QeivZt5_H( znEXcnWz|&$ZGCyOGP=tlfhd>GglI~UW1?ZLXH~^t+hJ}vI926q8Uyb!SrTu7IsS=7 zEZLybO#)PmfQq7Gw=Ok$#G`)caGntLSQ`*})GhPu&SYuTYHun$0#RAnx|BUz@2Sl@ zDt|vhL2&!{P-plF#E+;HXkGFc-Iy*3HkLl$hly8Ys&@5D<+qgQ^Zv+@&flCnOAb9` zzH+caK~6Ao=nk4>CN|TcEy%FjHEMM<&dLq;^mp6OgTx1odYfbT#00vrzarQN9f+;R zfp=rT{r{)C_?v&+0QKkie`jOi@EuO`*1Fh{`&2 zMjx3#Cf*j0i47c@Rzfh;Yxo%i8`UqJ0wPF40P$5LM_b|5Mz1Mgs8t|0jKQ z*C*U8a+Z!qxj~N*CDwWhx@xFfCJTdN1ENn?e4olRP4BL$;DiuYA4&+$Y>)z}gf6@g z6E`S696=kcrXLJgi<$DSsh@{?5Sr$+6lkK}^^GUj|2%EEc*#)85EC_-@DVzckR;yW zGGy%9H{dkSKhTT>(+7U-Tre{o$*Yn6mx(QJROL2>bVHXvU<(o=aT$EA`Qdw z2{(RWC70#qoEz)-EEbfnZ6T}0%;bnO$4B>{buIhf{&WaR%YBT)F&c9PA(0)6AW2Sv z9k$#%XxA7%6-|(j+wPGbGNznV~@5RSTknx#M*~AvE=CgbUK+2{wE-- zngy+!J)|u(T^Z?<=NBEYA6%BveA0<-2L6Hq2Sh$`!vG&xsSg8OpDWG0Ts02XqG)Tu zR8Y%m`+il2iN9$@TRdI3U|1rW)QPa%i8+*7I;>J3YqvSUiqNKspI>$U#hbaFV29%C zLXeW{J+8Q@CO`}lcMAkNgms(077w3^YQbf(LlKaLBMgPY^^&_R>Jo*bg(_J0f@djy z1skR|izGpSpvEFK7ZWn(!$^d$j-UbaM>?TyL?)m@))0m%Y}C-aZ2$iADH7C2_Z3El z1{{v-&1#7X1x6>Sz%-1%9h(yZjyx$CdP=eO+>f9eK@TSDW{6Q{iUTeMlWq}>{5n}` z>;-bLTHu0PbbmJlv&RW9l_@xKiK{^E9&*WOI96k|WOXwA79{NNWd>s@8!)rPLKVGO ztQy@eMYJL8!1USIt66gYq00Ue@*Z=ULCL^V%5((laIk%&ZF7LbTyR+k@ug zHi+KGg^tn46;;#-VLy6%JQ&n?IS6iwV3wK4agri7LbzWr#KXApi?RwTx+f(8NT{Rn zKIgAm6GZ+{r-NcySX`mS^nas&0uls^Gx~h*$b8@7Pb;=G1m6!J=w5JT{c5Ij*V+h?(GV4puM>DF-(+``yYkk^E?Bs z%}XabzP|67DVen!%J>)ELDXj~XCQzb z{A4*v-f-Zcq!`SuRh2>@YgAnDJKV3Z6BimM+&3O@uqWUy&s6@S-1W^%dA!Q#6^kCV2WMchQg8^o%`!BW+!3=S)Ov6%Hd-{-ZM zyj&+}id@zl-)H>UX=a9S(0Pt$DC8^laP;D)puvl#&+A^2T#hT`>t!BZ`ufw#^O$6x$zCW zl_BnM-cBw$a9N&E#o~AaNZ@%h`@WBr7mYkF-0dCrUO@rdEQGaP`)olfC|N7CfV>QP z)4|s}z-k6=UGEn~kboP=`LjRS?SMCd<7@F@y5n=n=jVN%^K?S^!e!Z7w;8ba6<>DU z2?JQ>+xpw-Z52EJ-cHxe$vVY#QAbDOANtBpowv-@xH zCYLkpivhAzE~@a(PO}yJ>ce#7*kb@_=gsU|NRG=A0!~&kI`5#nsnl^*Siauy&}^3X z!e&%9eVj-ff2#7YwMM4_{urJ+Gu#svcB}o-yS3d>fFvZ-cfeQ1?+d$1>kCGsc7svR zXe{1T#iHl^?uw2 zJZaNoHt+FlFupsSj>C5vtcFuevAFHHB6$92cK;vx3_?j=-{0=rt_UADef%h61pQY{ zc4d`JlD4jJX?f0U#uPGU_XT6Or~Ljx)T%Rwal8{m;VgJv5;MYo1w~O$F*YmOq9ME+SBId$GPhO0;fb@${y7qmJQ(J&D z!j0qLD9`Ed977>%?#UE?_juX^`okW}oKkZ2Y2lRpiMs6puJ5?rw0>8{Zuc!TXeX)1 zSE#v%!*kD;+l_BK7eWb|rR4p%Fhc#yzdIfGu?14ZsQddy_*ferX()!?Ph@cdcUW;; zez?Pr;T}@GLOA}fb;)UtV~dSrPLBo3si=mlhtXzBgyB@L-J-fj+e4U=WBl`a{I!5@A?isY~Ns&)IK<$FIy!-|H_>BJ&@UQyX5B=bH{z(lSe_L0DNoc-U~zB z3b0@?wEC=Rpk=wkZ)G|Ci5>dPANymNJ?i$oulLp`v>HRk^8Dd;wMPJ()m{d@@0z^; zm3_|>+nnDk86LM=VY2|s>4UrH_20IRkHC+!>{G|*b@hi2_V0d2WrU;FP5WZ`Jp2H% zYx3%BHzbuq^y^MnbmO?J0Y~N0`w#Zr{aDSm`>frqF%o$`VZ@tZlsUcdi_w32TF@eo z(sXF^yFV*dP%Zy4x&u^^uJyQznJ*^%o*!tS@A)Y&5VE6q7#WTHw>nQJHV%#kFi}y* zgW9p6I*f)@z9LE*hN9JeL4ZL6Q0VV|i!f8xMa1Sz{affs&XeN~nz>MKtmy^T#}c8i zlwfb_E{vo?DVy(;rszy@6RFzDCIWoTOdjtAQ#k+dwmtkbxbNI4CVzbU^RqOO^$1WF zyv&0@^{69>6iYT3GKlkz)f$ZGH5dSkDhMLML`Aq1O91F&3dn>7A&-}{(+?lUW^U|A z%ieKbb3J`ux6td;a-JL4KBwAzc~B@6`7{XsY;A_0Sbzgf?}y&j(65HhxA5=oYQ>H`R{Guam@2lroh1YhKE1{QnZx<(dlsFUGJC4dNfK=+q;oSN5>9gB81S`*8eafzFr;i;1Q`1cPpwy z#0*}!HF>QgtJP?Uzv%f|EHt9=Piyy2WZQ&P?%xe3s5Bs_P^$^GRE&+bT5ea;+g?u=YwdixovmhfiD=8VThS*oS-10e>`ktRc09S1 z&vx6>txwixODzOv6}B2}h9u&Rawtf;fr4LN%A7>A&tKr62bIa$e3=95Eaqp6H7sZ} z6iaR1;x~S-1@3$zHJz>%%1vCA+!7>*%h*5XEaCO0$CrL#IYEXYNTdFU zese&y_RXRAho9edm;nWP{rNW8vR1T?PS-yh6lRuV=4he?&CP3*?1_ox5)A8};A*)E zXCxn6nuRDd2I&x$QL2aqA`0pH(WM;@Rn+Nz#b9w$G1BL#7@DdjQNPqsv@l%#s9>=; zqfTlz7_X`bIu2XAGCo&=Q{~4Q6;K&{L%ZMZHMSNcr*)e{WUJEdCztgZOCqOg4ru5` zz*uF;*hZ%=>SBv_{|-4wCMk8RM7L>di5RHV*szN(C@3h@{K>aeGbQ`QDl0f7;B0At zjf#; zs-&P1!p^p{VhKKjCj>%5`z?w!j>$sDY-X8qm0l{RrwH62iRReR^RI;Ok(hv3t)P9l zxP7hv@Q(RBmK%T&BTFjvmEH9t$>8&2t<>HhS=BQhSN&QjMmUQkr=kxE5T@CKXH`_e zD-I;8!4*?iAtkBBAO5uOJzmzFIE>pFZOfB8=$V60N?eJAW?J~Q)IU!~k2G+)WM2Py z3f}$nEM2|b9Ud;`Ho_|VSsJ+u)OMZ@b4(qZBSkGLD)FaB=_zk4nJpArO;OURS%b*8%nW2eKn;ZLoMS4El*jPkQ4|puQHuB8kvm1v;mDKMaY0^iyz}{3BKFg3 zNL1g&o$DlXwOl8RYQ^hhcD%sO%p#5NV(#zX#H#-WVR8tsAQXp<2b32EA zkwi0oQ`~AB8k%ccP_j2eb3A_S7Dd0gy4E*4KTWE{e*Z=caPTbG>tdV2nBG4n!_jE6 zL$UR8Jx(i;PUrVV;`e)jYdWPfJCb$Jx5VxpboTk#UIoCD5+Mn^Q^Kg|%5gFN^a~)_ z@kIRr5I645s~8$w{-URTHRf&w`M^#yKL&$LoU2~UOT&4&T}b&|gG0mkF4roDr%0#P zTV0_8g#CcR3X?ouaXr5T*CMvBeCTub%DH<{7|rJ?F*e&>QLnUFnM~Huzcecjul;&% z_PYVvBeg(q%Rt&~l*)y_z(-j7+F%y zH9{Yc=#-VQh^4xoG`5EtAk>+%R@oXQ+DE=?TtT+CjX*3csg&sFh>=mh# z1nwKtw|g`|1O;%! z!=nnVf0h*ro^&BKg%hhWLzSAH>D#&O5n5(6CR5bkhZBV=H_%MBT9}ctjK^d5#||e- zd;w+EcrH%!rdQ8n2rIQZ!H48d+!>xo3O3-jv6(_}8jS`k5(;Mdb+NLh*&3H$vPjdIMnD)M@lbGYs;&4Lbn=hOAT zqdfWTS9FHY?=NR^f0pp;?GI!snc@oVIh{(;siJk<#K1*u%d{~GMz|@Ks$Wp0L4}=y z*!k^_-Xxrj_K=>Qp(+)MIVCW?#xtWcHX99p^gzR$&P~X7XR;>}jK$ZR%qhGqndoUD z1f`QnEdGJR3e*cV2?0#eT59zAfR}8CVvItvb~}AXm#e|)dUZPEcUE2BXP_sb?_6pb z;_yC4l}@c8tdK%GU#SJ~<3235D=5TSV(%x8;y7F$39VOa2lW%@?u^4b-ZQh-8cu=a z=<{zyj3}|WUoI(1t>CnZTTCWDlGeH%$qp&}B%0{clzZf$d$^kSTbN#$UdrA+8=ZcS z#o`?w-33Q?pNOf|u7_Ek+i0~ULlXGJUv9ymV(9HRm$NDGPYQNmyrkl5SyJJ8*$FZCx-6$^qLZ8kN4qkTSVKZZmOwfD2-jQ^g z(PFikk9d4U$K|Y#lSJV+y7`9nTIVXST*5E};WP8$ifkK|H#ys|-2zY+UCtIW0Aulb z%NeCofav5HiPmvKRxEBo{{I6^L9@Q7gr2>6pkT0Z>t51Z zbs*lOv3LJby7uf&&E#riWgKGiN0Z1e@zeLp{l&s` z|B5O#8}Q2OuaFRBGUMY9`C!7wY}lQ_1CKmH_pTl3+_?)z(Rn`qYzhk(ub^(76jGa{ zSe{pc#-M^EA|{%WVjmw){D`BOr|H_UD@j#qa`N~|29Fp@qk1(dDL6-|^m51Tw-BL9 zcJ16jLQ))+t0wW?FN<^q^+-YHVJ=nu;~*(57uic5hnE z$5TEdBBmmJdS5};b}g9o%?!T!>RT=p`RLrS9lFot$kA-NckO`Ntpz(CfCLJe{q0vA zJndt}iWL+V74rDlvDB_rlbXp@sZueD3Ga_*`@Taw^yKsO>)DB%%p<(=@^gIt)ptZ! zsLV4jzC@G8jp^2|1q?iuKk4%Crze7la`Er;&Ec4qG{ct8LCmpC!bAW>8f=!Pfev#LIevIt)gAK z4%Dh%kyDvR*t+K+oxAnKtNQt6^#&5F)Fw5hp5@~<49=cCM_gRoMZcTE+QDIj5ypQK zeym{hU^y-7S40<9G)%R_R)%fBs@UYdrodEHOxx?BI8GKj)TQXfNa4X$T!EY- zRa(@9ah8xY30gP)HB~%`6kl5=_N|iH2tQEGiI1#U*uY1zrrHTKqrK z4?;o5WtRX*kj0q7gMk|29m3*Nl!k2(N_H*&o;N<8#w#CxPKD@bM*7%@0Re_B!xyq50~~%r!@xwfRWYO~Kyf6_?EFQk zBZU`TTGD@tEJeo+LZC^XwU(rcR9u+SUME6gI^`(R1X+TiXqYIt0+J_|7f@m#QLL~q zR^L%T4;1s8NYg}DGz6waKO;N=N*z`Dt-K3+4ur70jM7x?yk9>E-I@>K3g*%Iv$^@Y z;WX$riihsG6|c0Ye-w#LF=K#`7*fL&Dw>oCX^{s>#cgp#+UrBeQY#f!@!&_;jEsgw zY7IdTsPuu*@Y#=R)+f*aX?;EoXT3=)O#q>x3!BeUmSPIagtnL}eVDj0P;pU;iH2?q zQz}y8^Odr1{{d>$sBzJ6rm$j27-59*cj33HfG=k3Ii9=F*BA2wUdrezZvdL6$?4Ol z?G!wdzsUdury5ZzZV)Ppka+A{9>N2{Wf^rgmzaSEO>?8!#;!{`?^(A)Rj9Tes@o!= zRTWB$^Xbqwow(Q-Vq;^8i;W>BHj#Vo8;w*Wtm{h9q)mn*G!P!! z0xWSBH(>-qs5aA`ZBQzzZ78WAqEMuU2AHZF6l-6E2EuJ?9@}QB@Bpqrk1VffBnm1n zE9;C`UV5JRm>6PXqlt@+B{n9W^t6r?n{I@nSqc>P@mgRGJ)lG&uvAg35UUr|NDwNj zeY+Q6lPY_y_St6jefQl%Tx>jX(Xk}N#1R*rK!*-JkRlRrAtbnM2eoC{DE5q~fESIR ztes`qxDj{=6dKrVwMqtTPDrDe*I#~~goHR^qT+~&iY7WbhHgFklX>!tZ3)|Y$o85N ziYstF)t)be*IF0Ck!SXx31N+ma9i&yt^l89b_uK(O993++}pm?y9uIm4d6ks z&+DWfT&y4{j4;9oiCNhKu9Zj9$~A62rx`c)iUo?)6RGkBA`|lJT~a>`OS6*{xC!KH8G_h z#irMhGGGFgY3-llVF+oA83^E(Z=bL=b}!bO;EC*-)6k z$szW|z9vZ9115yPFf32BEg{UGwI;0(g^3i_gNAgBqVk0ySRS^&(ohIpLjg4$fhC!O zLz!Z!x2WPz`bY-GQR1k>Se4j*6ydh!K-%s;B$y_q(5we7+bFhlxb62HIY#Hf?XQ5e zt}R7SAKUq+xY)PEA3CL!0qx+hCoqgK!uX%Ur3yaEzYZ<>C~vqqe`}idhrEB6`kkGf z9lW>yZH04ET45aw3|ngL(rncV;I=9+?JWUw%8Hv^C>nG+TO8TeIb8J+stt^U#%)ZAx)r&U0XM@ecxf*0dcXLiv+WT)l28IbN>+x zE3vCw`<&a9b7Oa`A6f3_-$R)*Ny)Lj+qq`sNY3XKk#%@K8#ZmnP=3p&`RfzPGJndz z_WyR1g`dLQY`*(p0mVLNoPvgC@S0`kDA;Nl`1j{PfUWC{2wmq+{+aQoUhR@7H=Y4A zO0gHU?XhznIR3oLI-{*4C}Qiz4IIkMw!MNu{Mt7f3LQf);>~gIla-Z&s;K;xSUC45 zzWZ(#rG`UUZ7@ z(+SL)zXYGKJ&-o_NpL@h(7|ur5bYbN#EzaRg296ala`idn-113wY=@(Y?0WB|LFFa zg{8l0W-Q;E<#|&=#Frgnn6klYrzJXI zT;wKJ*8B;*cBmOi$k_vz5RgzgiBUJ*NMwYY)l23xYxZmk?W*e*}gZj)*ECpcTq5tt?H-L{ISo_(DQrIzYOV4rd}X0R=eW#|OBmB5%@ z`eR|*>n3zGgYCRX$L&@)G&qL+6S|8|nQ<=nZrSx^1lDcY?PcdGXtbAYhm$N2=%eE~ z4KL>IvahOqe;Mi^oIU&rs|_m$uGV*C7-(HHuY znVE@Vr3C)nU#|v27Bl&s*J)ZeozYLcfLU^m`Lk!zp?ya>b?nHDS&J~GL1E58Zol;= zQd_nrwM9B(o_T|F`946hV(B7w?%s(XKe^e582#{lG-{U4kZW$^LSbR>wiCD;=^Wa= zk%9d#C#6{$W5&KgQIQY5D3=!>8$+W8t$E><*EyYakgNLlrfH)F47++HyN{m55E{ZL z<>^Nrrb+#_O#JvWjN)wGePn=^6pH1d5qhVML6Kbk=qG;gzQzqiOSW+V{AUOl7sfO#^2tP169glogACId6uZPEyuS<&aGa38zXwq7DrgfX{Y}>t^ z+}v!&KJ_?FnlvJ3(T z&&yc6Yz;mMh$1$vTTcHzmy_1KC2zd?JWoFTH1B`<1Esp)?CF!-dff)^nK4yRQ8J#<{p;MP0%$dI&KX4)Y1b1FDh?eOsY1uTD zr=ED8bA?u3X2IE0{PV`!X`IrADN{aT=lZ4eA25gpP1|zK&9_tP%Vov#MfB|6h4yXR zF=^_zlt>lb&_S^udqV6#iA0(bq#wWU924JtgS51kbi1rSt2S?E!B1atS@-rdYLvo& z{#WqA3op>ILnk`4NoU3nizr5dQOufO7Sg*{SK78~%gnjU&;eiR1%?bA#ZL>CqXP)5 z%3lf@YGv9lf(CgQVT2LJ|8`u;7z}mZ{g$y<{=HDcFf%ig&6_u)DT-1y41BQ%{67(v zQ^E2yjJWY;?!NC)l4IO#-@Kf+#=pyhPdtUH7xLW8uMi)hkXql%Pm5OZ+MDl_oZ#ZU z@$d5TO9ebV_6aWJUZ9{b4-mZh#@poPmGJT8k5LpiUXRE2ZU~e>g1hAH*IuD>$1c2d z-R+c=`f+>R2+hSkk37uq;Uh_kkyMD%dFqMLL_|dK?!?b{{Mpx;{?4N)s>*$19%9gt zYp5D&Fk{MiR{XM=H{Kk_hIMNge(g;xS@a{-D`-{~YoPE!av|pwTQ_dvwaL>l3$l51 z^wZpU?<4&4u2DSm(g!SFvWaW@HsQq=Un29Ik9Wqu%fbZ<89C$%X8!mSdv@Cui#)hh)8*nveLbzXeR;%NKw+wVAE=%YcM1YC-rpMP0P zO08b3UcLlROa<00U&_LtX7m0>(=lBU)T$dt#@6FhtyhmPznn>O9GHb?cw)?GF1vgP zci-QHho2fp)rwJE)uR#f7q4W(M<3x;^11ikN4f6C>zOun3h%!2E;DD%=FYqCuqsTY z<2^G_L#uR}L_U)~`Hc1JwlZthY^48oW_~@Li4!LA!pq}1a`ZS4KJ*Y@%$UKh?YoGMie~aB zud#dGTHYM@7WJDqMmv9yr^k-vimPuTy?F|WaVpz)A7iDaR~hkL$B_Gp$MA_Dd@?x*0_l@^ZDkBPno@FC9l8v4v{hO)Tv#Q zFMs-sx^?UD@>`Gb{nUxfpTCIbUVoFUz3X`WjkoC7qdP|ruH~+OKElm+-9uWFCcOLF z`<5?QDAcG?o#?12`_mjo7-59*{|7FWFLl7VIRNS#i)T*68ylF6N>1x__>qD;r{fIIP*}8cb-%OoM(`W8QcU7Qq%MPT~@z9{M z!abwMaXK#_Me(94l0v6I5rO>Ju3JRC290IApo2U5_eVPlr9-$;$-ZRmS> zA2jVOrs^T4Qbp?4P9#E>PNaEewbzs2Ddf=6Q!JjhfWepDg|2x?NpDAbdZXZ!n`TH7 zp&-3g8$O!$73EES3el40tsjX>TGlF() zzolWr6xy^(p_Oxme2L%V%ykR5vJoi5BS~sKU+<6vJfGj!B!X>N8Es0{vC!Zqy1zb3Div359 zq7zBQDz#|UstqmcC$eb8dd}t-le>K@m1{I&2WYYguP2JHr+!0GZWjA9j*{Fk zo%jf^MbQ#Wp+pFio$J<+-uW`FzVUiuWht6@iXUhEOt-6UrBDB>(EQnKTf2ZSXZ}FL zf82n9ASE@OrZrrQ*wLMX8CjT8U|)SDibR##X5hLPF^UzWm}#2HyD`ox69#BTR%e(WINC zDm7@D+Jva#eL0d-O0zcUG_C38y{U7_J#&G*o7PafNe8aK<1P|~$-y-n*mE)q)g8l| zZ@*+w)dU7awLaHns`~?_BVmLQMi~Eb_@l*azh~54$}qgtapm97%F1H%=FK76!GHIo zwJGhCBN0g3l9&_}6cAOp5O*YO(? zcZ3%MrwW)5*Oo=UAykcjJU)izKQH9IM;>Cv^iE9qU<^Vi7`C%e=tYcw?L~gtn8Uai zA7$5urF<}JFVd8l2vlKJ8cWl_?=NN4t+&&%eP<$l1&n>sORbvKQN_iQ=7k+b6M#Xa z*MrYzk?*=)8ijeKn0`Ns>cSJ_MMvUxyNGaWk@VIyzki&_6<=emt--nNH(UT#VK2G#g(?i`+f;WgT{Xv2)DZ&M-Gs+?Br_UJ{$ z)U4l_2cCYJczG5Tg}5jaUqKc=sbDBBRK-PXbOb(sDWDMN(LgtCLqlRSX4@fBlj0&D z9lBh`L-*f-CW?7NJWWES8mwQk1c?HQMVIGwEBFi@i6ka60@JT!>N;_WN!<15)6|Xy z;WvnnQc=}xP^`6Lx!omxzfMGy*9vL8Y}uVni;g`oBsMRmWeEy<%@h|E z6CGQ_3VI4a6%^#>5nm-fpvj$>5J%pT0!&k&s4iPJ(I7fD8s904PFi)jE&3GzDN*c7 zY>U)Lr?fDi=%^}zuy0a@1pK8X=%$sWYnlcM7L|=-dI?OVX^?jzpNObvs{qHY05=R3 zMX_n%-7YLGW{Kw3&|Dh+QXjtJLL#GM0}oH8;YZ+b021<4rv%0Y>?}el?WftGIY^nk z!U!XbF#fY~F(dBx_WP~e!HXG=Sy@>D51^Ei#Kc60!S-*=q7i_mQn7Lp2X}7Z$e~P* zo;XA6PVLyVW*Nu#>|@84oy=dll3x9#fWsTdQ5B6LhC zi1tKKr%DtHfBJ#L8OJ%Ckwu};u&Q{=1g;D+j~}IR(X!ND(nwCO%E4XRIh>J2PF@j>QX8{){%nlm3uxX5 z3`N1^Re#gscaq$Zp*JguUkYLqlSxjD;`_-{IhK*ZcR#M+tUrPlO&g(N7kEe~Ko~SC zrG4j&iH+je!98RiJ;mY79J=-D!ron*S+{y6hYp=!{-UL{YTp)w=Gfx)nVhl##innu zLas*-?I$s*B5%L_4yMr9z3(W|@fGQoUYj@Hoj}dzooQ6NI(cVKk$2$&k3RYsy?XU! z?b@xx#3Y~;WwU?VMh@)DAijD7N=gdZzjYNZmqw9c5)l)RX_^Q}YeG6Qd*Bob1jC~C zJ2tnAP-00*X~gmU>&QNxiRO)`$k2$4iNw;@u(WrDlqga`kygQvkP?YXWMXA1CC0LE z<8r)i1zav7ViWB)NK7FuH4{%9HL6wNm-!3GJaK|UCr*)XdQc-1Xq(=cpXYr^UVc8V zhy)B%!Q)bq!XRj_N+%P6I*pogaQ9}mu3Amz(PLy}p2igsMbEz7nDE|5Y~8Yx1}W8$ ziZ%Yuda>w`R2rl{z#+tm7v+dc1&^Z91`j@z?C%wTo?A_A_tkX8QH+fmhQ} z)gX(cBC#I2gi4gx#i6a+$vmD-PWE|pGej~_QE8N##@4mV*u7yBd-v?-z0bcTtxInb zA|i=4@;P(z1Vu(@36un(BD`^2cKKy2n=_k(`wnpUSSDw4i!3sB6w32aTGQ;uP!yV^ zw`bqhUs$^EXO0~|&dJtF`DG|0(1!nCiy=k)pf-})vBBaAS@_>ab=s(#C8zQeDK$BX^#7=X^-6)IGqZQHhv zP=&C_2aTXC$zRwlgwPmx^>B*LW-(&OwY>H2N3`wMg>D_%a`&hkx$};@>Dsdo!>_x> zl85uq|)pH}VWp8FpnKEj2Gfe@A&#sl}=#>Tb3FzBiw-1(3DIeR|OGLodU z4I9e{oH%|w{rV1J>6B~L&1 z8a1m|MsvHl|Dng&uwn^Ah74!M_djvN9d}YWA%z`fRwWS#Q5p{iLT0{4?n=P_g`bc6$7~EpAT^?D;on1P5LakH31fH zq}3?DqJfYBr4#A+g`@&R(Xmq}t{c&ZM<02Repe3W$+0g|Q0hY})_hxI?Zw26OWKlh zLP5bKA|{CkA9{eLv%X;9l>@lx*1Oqr=oknuiZsxq&sLF(=H7q(lP$l@XUM>QeDujw z3QRAC8pF*uUCU*in{mgTcW~99t9gIIBuaHZhJr0&Cjc+l^IpGsIyc=gg6AH(pTSoR z;O%$bM@OSe@7`qRmf&%DNvTsKke?}?DrNzgDs8&=W$2ZCcKIf_dL-_Hh#rW}} zVgzUb)4TLy*ucI#{?EI)dDP9+Xx56`{`CMAqT{*eh9S)U_G@x4EqrX>yp~CyenV-gkK)2SrcHXEbz63!V{+`^ex7~#Ei$vu z{R!V!VT2Jz82=ggElQc+3L~F9d9sWLutJ3jv}w}@RaFs&F0EjzVtLD~{G-1zh+@;U zNNH*K;)Ilpz$<4jMV63tXdA8j-pRa0OG&MhV0F&^U)a^GPUSDCm_iANQ<$cSs#x`| z)=k;4+#y26wDo0Gbh}tZbA}FtLC_eo=wK`=Hxm?xzC$AL0~$yxPs)(e4y}q%Ux)3< zu{=AbqM=Hkb$b>Xs_pHPD0UsOX&Gd~VvEBb72!M)2!W73Oxvim^iwrVEG<_6QwaNv zjzy~3V``mG!Eg89k|L9KQHfJ^WZ2rZnjNo~LP19$3>~BRJUh3pV*Doyd3nMIRCY^L zTcO2LlW@ky3Ct^H=F6cgakQ5Ox@{OZMMHM?(LwqxEm)xjCF07!Z_lSYaCYpm64>XF zx;@sarP+)KjC(M=7?R&6bxdI?AzR+WQt}H+&`p6$l<>v$ANYCYcBXy$E^c9)C8BKW zLP>^HQ@6%N2&+#B!15NGSkcX6W?@l?W98>9Xh5?n)J#`L&vmLr&Wx=xtujZNN<8;YZWay4^{%K{$pYY7XlMS zN(?(C!}%0T8CDDlBaATq=WwZ9zR=f~D(Wx{BkLX9qGFQml4g(?IX{y+;IGs6k1 zT5wrk-bnoZ62^^tgHxxnEd$UrFolawow{(%h#`UVXjW#Db-0irXV(aYGelA-K~7(R zZM=w(zL@OXzKzenm`+hqDNf_!;u5*}=9{Qjua2$l>JI6<5)uNnw~CN4a3DhRorF86 z!78+X=7(hWqP0p93D zo_b;o(UESPn$ciQOXyeywSUXJE>}blJXQ<7mSAG?!|d;wJ8u!_rI;d;yYG1rml7Po z^5#MrqHaaAayO-EE0S1YQ7H{fvxsqTzRvF5M@VUwM&G{O5r)D1Ip4Bq@d|Y5aP&cJ zd?JrMKAM<_$bi01Pz$>3SO-Q!C_ydZ!2ZGY6&y7s8zz zdk@)_!U{qtq_=6ubvImVYhstFF$#{6a1neo2pQ{gpa1e}rp!BK`U8&gN?=|^`Ll%) zMi^oI??8Eam(cBhgfp=GHn-bNT3Q+#H*N&LFbpBXgpfSD>n59QYzii-=85=>K~AT7^>+lALId3Q=A!8YTh-iNy35;q&|Ps}V%H-4`h>|2O&*XlF=&qym(p z>pn_K70W*)Oav;X-9F3sy|^*<-*1fwdF{jJ_o3_78d6mkE|=>!`(Cy`Ay0btxr3{? zgpyJnzv;s5cB82Zis?u9=i%2)5MHdjNDWgcxV>I9A^sKv=ht&$``t|w@KIV)h#^(m zW2j;vFf@$_w>w}2mW4wJ9rDogH&$+hJ%M3_5yt-{e$NwFp33E7-aW^gr)kIg-<$eDF?-N*Lb z$7oQm4l$7te{oO32qTOz{&(QFDuMs#zQ2d6RjZPoo*wWBo;h=doSYmK6vcY#l~^~d zzoAlCNFUjmhuL%F1U_+TFQl|-Ov)UKv<)!96-^tdQ*Av5C8G zxru>;hp}eE7Avn)hBi-zw9yGP+P~$WWdJ$|ojXzHC)9`c#~?BM`5Zd9pCZ$=bNqtu zSyj;nGDI#-NCnWWkgSkoW$fmSH{YfRiE)Xm{8=yoAq0~rOk~%-z2p@Z^72bBlaX}_ zT{u)V5-F^_Q$tZPi}QHozJIW3*8z0FZ)ghpDJne2Lk~a6v16zI;+}*NMi^oIXXC$O zYn9(Ow1D@I@&*D_sZxdX^z=ZawU%R|c+J=iuGY;SN+9q=QOw%V{g z$!Y~$UdfRt|^$PSgS@4_?0iV z)`D8V2KhNhcznzwoH~EOmJ}>I2NG#>_BrcDV0|X7N!9&@oIZWZTHT_I(lSU(yI6*9 z!?e~4X2_g4*9-QytWtMi@DKv>a&svuEwTKb!t#(?p9iDtTnnoxBkxQ$rKXiKpc^G2 zeKbSbWgtyI=g$|S8%|&S1PZ1C`#CGd`IP@!jW{&G9^6`HQy5`{5yt;nI3eHv4jhl5 zW9wtBuzKkdUKWCOtx_3qc~|!A+0BAQOOV1%m!5q{ZPo~*=qx|Z znMcO)lNeH=Nz)ee?A?<{w?@r+wW&}s2^Eu)f^#fh^fTM{9V02ZI@gXIMuf*@-_o7X zsLAQ9qx?8$9+_wJNo$o(->wb8SHS!q=Wr@3lTPhh(zR`KW_mR^zPM(?roZ~@|V?Y+PWKWbQD(%98R^$31|UT3)_n%O^VK+;)n0P z;pmw>r0St%^Ol^?$tEKsg9c4na#`O##7B83DavEf;zexVb&$$6>oQ=#Kq|#VaP;6l z7A=@Zc3vsoh$wpZy@JLK>*9%tr(vV|cohX#X(8)ZuHcmy-k?e26ow7xLC*2R%vrdc z+=4ru;nrM~-El#v2hu`?hU4aBwdtv(L~lr3t!>L`R0;f(KX3qRYoXst!ZKp1@Y2TIz z)ut?x)&r7a6EYj7jwvOYrqZB6T_U|I7tWpH=bvVCFf$8W(RAw6jdtzZqDZWB7(V<( z1$;UEGtxU;hQ};so@d_t#q2wLg4o20jJn}kylxjr14XDI;}iTJf@u=Jn*|X@7-59* zzZiyL*fj?KJvfHo!i5V_6cIw=8hqsb%V2#`TOqJYHR{s3(`7WMQ;TE!xAU)mJxrb+ zNpZm$ZochKcJDvT*_>lM^3+TC)M%okTs;5e!%Ut$8J{UxGH(Ifc5KIw!L-SfcyHnq zDkRs&8xiTGvD?HISYA7!^TsQ$vvco0Qd_q~Qx$|T@JoZ_lvG-G?oORLbx{;Ikuk9} ztX-MeUryoKm&fD7gQ;j#Z8~+X~*6zmi7cgn!$2|AS2gJw6@beGf z^3U6DA=hWHa@h*L`RZG$)vU>xjNLpw=5aF5=aY9fn{U3JNrB&wP$iXX)TC9Hel$&K zf|+}oJ8!$4Jx5PbF-~FhV-K@p<4*jgxlH}^Gmf7sqIT_uM0z7p5tyb$-4o1))2Ljz zBCR@gphap+3eM#4{NrQryCSJrtp<@^4=&Y1!+Q0Qr6oM`_!FEj_Hq39NhZEKk+{m0 zaI2*}bmxsMTE2!I+jesAU3U?cRF%rf)hup6(+}<#nzrsh`*vx>sd>CLZXDCTUPMxb zM5ayrkmsKqOR+SV`o-5QUc8bzwd;})8^iwn`OZL&jj2bbF16eu5L<+_{ za0hdite`w?qcbV3bMJ$rIj5_jMG_ZZk;ZkZ zG2_Fxcz@F87>1v(rc7etvW+Cytj)TWOStd;$H>Y#hhcm4oVsCwL})I&QE@cy(3|x1 z*2G5|d_V0&#=bIv*u*3@tXav^Prg8juN1$umU^q<9PY0 zNBC*^Itu+h-XHfmuf92f*u-R9stZ-MJ+px#uF&e?U*~3CDpxa%Fv1Aq{{sGuv^~cV zv@*EMDlz?~5ZE0Mf|~Uk(xYb!;tW4ujenJvt=n_oBli$(6mUGdfC=xs!IKYlB`N^&caFTyD2WViUJxosY9<`skrmc z^WmI1Tz*AAs@14LoVy2~KJYgC4;>+?MeV>)nbqAdqdswn;CF4K-lD17Mam|&z=+XO1R&Cr&i4UsRsKu}m!*LJn$j}=e z;KZ48)KaamvME8A3N`A~qieUO#3T83!rOQv<9Pgu$Eg%kLVk(D%&%wCx!H~QO@+&^ zxSA`vHww;6NIHN3OsSAmxe8r6cOu^7;llpi=zc%_2MwZOofvVDJ!z-E|WMevJkxEf_KK8WhE3*|HVHS4?Kuh!ON? zpURT?KhS^32wFFc<-pd}Y}vJs0eySoxk$pOzf{sJwH1Sh4yC5Ih)HucFyi{*oNHa3 z*`uByE5}E}xF}MZG^61BNm?{dVfm_!+;`hx{KZA2wCv8v8?NQ%kpmbp;&%4z-%nyv zdm;j9e|C`AG>M6gr&EUp)K5x)a|d|w*{8X8+_zji@G^!D?8mLQ+|9wvEE?6TQ^t#B zaYLHas#~82AHAJQicXw6lBtv4WAM;^RIFT;I&~XSSXxZ|diB}6XAh0*RU|sXMg7{f zXxX9}QPEM%pY{>wvd_}4bsJ(`rBtt8oh{ol=#bV7)&497>Q%5zP}5#hrZkZP{H985 zVs)+=c_XsqG~3s&;O7;qXfmt|hGFo{^r;jP%Y=_VAu-Oyz^jLG)v%HHg=&8gg5G#! zAzRn(BfHaIb7po|U6y3ak}Nm5V`GZ3={@uo0wJOI(2F5J=$#M} z5-<<~gc=umLLh`d2qg)aVq;Tn+|_K!>Sf!^ocH&~%5 zoO5Q+cfN1=-gOP5N90kYdbt0AhnYBGG;h7Vm?su4Wb~L(!~laku#iorld=glDqvrS zl6r@1$cF6yf+?l`X)rf-xo>w{RR4tmRw!Uhezq>T3K5{C^^U;D6PWLR*@& z;|B3;n%4FnDr;(j_c11p8BIrXJ$Qn)B6#AL?j2QCfuz%<(heR5Q7O_+g8sC{u=28? z^sLYSgee3_nDU{y__Fhf;&93N7x9aE57VD?{VZeSX9Y(j#cvlr$i&#j9_rUb}1={l5)Hte$Mh&KNZC@ zSpc!7ej_8RYbh?sL!lW}Q%g_lCLiD_3nxgB36o(gWo7Fi0+yvSKw68S#6v4z{#oPF z-@TC=e{>ZuzW55Ce7=(2u3lW@Vvs5z)_z4mGJ`#Ra|=HBgWr!$y(p?c&Kte#tGj-OBq*Kc=C%m9!JYt15%h zep-jJBa9tUN=Ii$5T_VMvPm%26)KZWEyVl!=&aUqfG&Mc8nrBPE&I|Y0r@Ma=h9G!rCu_rnYVhbFaFDM<1WZYp=dU z!}@g;6&DhZCrG=7bi9YZz400c9eo1l{ctYd|Lzf}pyp0daUp%Zy?CBM+lmpR%BilM zz!_(s#YGpK%lT)0pRrZLg3=~3Fwazch9yiOP?=^0naW})C@dwA4nY0-2hc6bFUOH)2vywmf8t3Kg30N8wDLOjZXzMdvbjjtM_k+{fs&*t|QiO%P z{cARe@_grfq>z0M{toxwKaU+}OyYsNeu3i{1dS2}*hGs_1`UHE{JG-B<1Bt>F(;mNA!p6K zko^zX17#VMhM29vO(R~KR3gFJO}z{+uk>kkB^WebaBO7^crK~5gX0;BOG~I3IfB)n ze}Q;uy1F}Q?Kh07tRf0Q=5-iTDiBEBxt_sw()|6y&lo*^E4-e~y#CIIoO8vsTzv6G z>^N&Cwr7ai#T;_f2|W1V-PDvRo>=rd#*UkeWoeH1-f^6F;U%1Z?wRZ`y)Ml00TpP; zhytw<&&6?^Y~dZ{kD;%|0ho-Eb1=Se;boVR?rP<_xfhdk1lM&)BojE{7>Ea2Fvh`n znh9HNPfu$zZJS&097FxuM#haF$C%1|B3?J2tyoRU^Kf0)PsK?mNhW&zG#znBCwl2m zJHhlfq|#}S;J*K+A8Lne$cAjl{)eX2mJ@ToZd<4z^3NXQ>pru;=^slYf{qrk%U=8Q z;y^OdZehM;^#a@7%#9=UqgeNsx4H&cEnfbZR|Ls)yTdx`9!pniXHHthn_C?Bul{0tl`3xUcl3CaVL5$0<=G{fZre?a6!syx> z%7%|-&%O5Nrh699vgQkRoH2&o_TGg9B`Hd0YuM5M5YBffVczj*8^)_?vb zd(N54VaJ}twYT2O$}d(?SX@BeglU|A&Z*e8VO!j^U1*F6IwgO`vhZT24OmJa(Kul@0H{jRdTXvI;R+L;@XR6$Ix`nz0@CFT8^* zFTRye&(?GJ0efRbi?Af^Ya^>7hE+}CsBa(2tyj!t{Fvd?uW8`gn{H=(btM*Q zeBEV#>iSPHejKAAh9^-h9JGpJRFoKouU4${k&o6sQ>CyF9Yc98Q6Q-zXl=;Li!f)m zUHRp_pYhk%r?CEukEs|j6C3axhu2isgy;md=#Uq ztGM~fn;1KG6lZ+@0Dk)Od-=()o@T`df1$0don80dmoZf%(Z&UBXJEZT5s4I%>TTnO z%dbOvTG+HX&NbIwPtB+*zP0zx+;YQJOspHrvgOO!X8L57EPjtg&pbzdOtX4@6DJ&W zGW&dMHh+8THGX)}g^U_iLs>;7r=4*+W2-BJK2gDc{@6~OGM1;FdYY|f&cbLNWMPMC z82%%Sr=uwG@UThi7?l;}-22lTIQz6yS+r;o!z_niKlUgOEqsl?W2nwzMp9KmrXe4lGCyNC(Xwxb}wfVp!oX65qt zxcJ<2c5I z$(5T61aIZ=x_@j(M)ZvIWmguzo`W-Te-w!^)U2x|*)e zO*AxZLR3B#RimgXi_p6MLuT!B8V^3akTJsxuuDo9JEoR=%VJYwGm-o#B^4!T$D_G% zBb~i{*wK6@P8dfl63Hlh_=P?UjT=_b*_9xzV${@BQ#HH{lj>vrh7EKjgprlyj4Usp zzJ3$^y-8FwO5U&v#@ALss+YCvn~5hqDyv3NU0KfNmS$QvwUgFS%7<4_TT@L$88E&~ zn6C*8$^LHEuU}8yl<7q66zkSEP*_pRh~fg;+d6PvsH!T*GyT*z)YH@J63Z`S+}N?? zX`7DCt@I@0j2b%{TjH$W&_a3DX!7Z&eq$$9_Ot^%OHzn{&U z+ZZ!uG~y;%vvwUL#!g^Zo~EU71736()m4>PLMGXDfa7%%h{Do2KR#JUhaK(W5AeDVjGm)85&G$}48f=rNSUd^tChBlV{-IEfA# zH@48#lfu$b%BrduSvj1Dap~#ppsA^ebV@-q#+d3#Y#bUIn@AZ=q^N{(W5!Vwfn;9? z^-Y`TPkQ7Pl`wkrXbPecKgv!5$w38pX?l7#vY|E3*m09+-&jvYbrp_*j!m1HGAie8nLLMxv3dP6;L~J z1fG+kp`n@KwWBD=&nL2l^xz@IkRcngA^T6-|3o`DS209Hd=E+R-nMNl%ld~J!nuEk z@7vnizIhPnyJh`=cO@R8Be(*#F`&FaZ6I*dnI4)qe8Tqoox>}CdW&uA%7S>dAn_xk z7$S)AzbnQ8iL+`neFH%t*EI^FhCByMcHng&}=RFPfdTIWEYi49^sL?+)#!lha(3Fye@OgJW6n~XN5 zgUxLYCfn-CL^@yD>)@7NZDML()T zfJyxZ5xfQVA{a}cJf^+=CX%N*wG70?GWG^H{C+nyhaxOk8{I6PKMM=tkm%!x5vZBeSeL;f`EWocIekzN^*d}T6o_DHE7lq6qJ%HG%+K0n0Z@6~W=l!zu^ z?6?>i{UVryyZwU^J|)fy^0L`^wZqEz?CG$y>R1huG+eSfjHORMOh%Q|?3l-OBNPtg zoo>Q#6KWruBWKnuzH5gt_O7ShV@pI1^+Hj8+idw!EQg76gn{(-mv(z5x57v6rXCH` zZ*JBiPN4um0qhCC+h_6jvZZ0rbnK5L;*M-?EU(J$kK7w{=JcB}%Z)>NB&m$8!!D#S zw~VmvM_My^Z3qx+4`E;Bt4I-xz550ylq`30bNo$P_r?yNe%M;D#J>d}E}jNHr9g6j zmt$wo$9jEGERwcogtCncmG^((yWIOWSWt&CYsxP-gY@9w;JS-vk88KDKA-y|ChsZW z%+Z(dJAWIb9QGRQWFth)zdyT>;-N`*w;Mk{Q#DZLP}DW&AssDhLcXVnz9FS7c-NY~ z-pyHGUyLGP5NV{)Ew)*zIVj1(L4n`EvjLw!lHpHa3;p?oRHI{4B5(JbHR|&DmLS2-B(%gRLv=0Jf;p^fdvcoIt5ZZtLHo~pj)z~71Fc};E? zN_ST)nmFh~_4&e&9X~xfNk2_FINWcO@Zd4qBq2YtBvdGNsinZ^2Zdn~>H^i0z~{)o z9@-)<@G?P2cd#)*_%T@?GxF(pJSW%F(%pi}n;~#mfApHfs*4lR#f|xZ;Z&`EhjAl#<>ogAEd>I6fL;Gxw4cyBn7c99%t589_KZa zVf6Xw&IZ1F%48+JJi3YrK5qD7E506u*3QZ$&d0<6?Vz?t>kKR2>W=VR8C z5bj9}f?izb)L9x6>+N2!TaPM(ha4PMi`K$w^p7{R!)^rL3({kd8?II6fcn5~a2eM8 zBusdqk+ERPQp}6Y^2_QJdiTV%cmOawiej=AwWNM9n@Z6Cs^Wi9ae_`QgO{_S(baZ^ zMzl3&)~fKo$Lw=)V6@#!wk5;}2OcZMT7c~edLT~YtxZRa4)=(71ltE6qSDo~>umD9 zmt_K?9628A8HK3ONjCj)>_BNjT*%yS=)Sr3Ldq@~$M8ta%+aVx6ZaIzoajjt{lNld zyZ#Q!?$W?bJVsBeUo?K;bq0`Z4;dAkvCLT;21wQ$IL1PW8 zWD%BXhq-df&c5g(p5!U|veR+)!bgZwa=;Euy)f1V1dExWy4!*sPY|6d8p-t!9_0x8 z8N!mirkz)YTFawk-~v%(u|pAnLn=o(Wa_-$wSFE?=;dlK`R$=(lSVyLxXoN%dfZF$ z$BJhIq|T9WgpHu%`m6YpgTKFnk?5wS+Hf2qJhtH2N3uv2bY!#O4Gh>9)De9kWh;x9 zL_T}{*;=}ckvL_ffJBw|I%GZvn&SD@LZS^dmMG}-cwS<2Kn$tTbWBMeg`l25A!v5j zC0_x(q0cRX#AnHVWYxw~|9sp3HVK+oYgd4;4@psiQ3jnewMcmc#A%NVk zBFxz91wPDiwv{RyeUGMD^C#{(9Jvn8Qmuo75TT&`(`x$4VrF~W11<(WYh9%l-CF}V zSWsl|N3)$8EN9kYV}#nuhJ0n9K9ha(WlJ%@!D z(5LzYsHYPk5TL0OznUa1}BhV8~QN9>*r026Loq7*?+R7zK69!B8lhBN7Nkq+Efd zHvtzMKd8hv(k4u}B4?|$KW;~GbQ%x*7m}*L5y-(0P{D6i(Es96m`icCL&t@*UkbWz z=L&wEt+%5y6aIeZ)K*C)J#}>an5XLgSTeM=U?lX)bSO?N}O(cbh0-<;$QPP=ZMI zy5`~b>ICPITCKQrIWAT4MWorZES5=mWlt1vM5O0v@oo&*0`E>v^=BN~HmBd7dcpeO zJ2EIZF8KTdPrymDNf$kDFx38K1>LAw?bF@hvG;lEk7I>>*-~oka_KytAp&6E)^~6e zX6+HgA(fE9ru8`hMm~8254j?(ctU5>9#*Q+5V6VT1E2Tak1W?OS##6^eV>+A&p3&( zcFO_RuWpMRjJoZSR8wjD2ku0>{>Fl_x9m$vDw(I44`%(Xr2-vS(FoqBHC}R1W9bF* z`2hm2MX6`!2Wtu}JDbYAlyK$u%rtpCcA-JM(ZWR^V1m;QIVFa{hU?U&;Oj?>cgOzIHe}#$)b|}Vg#R69 z*}T`uk6MGQ?@_?KZoLIz?eJl7VM6*g9Jaj`3;NIn>?@5%ep)p2_C_T_LB--~iVCKJ z%r^*1nBc=x*{WGdT-2Jq9$#p2BDxD*!&B4Hm(XTAb|Bmtqt)Q|sZKA>DDq^{qNMTI z{CHc#>!nG-$h{|cFAao>4HANb1t;M#IBN}perI73;Nx*sXP8KZH9Oi5O4S$nAXedi zM~vVy@{@dBw$srP3Cn6kk47+ae|}h4S%J|Ey^EH&pOUtlNEv-((P1@=Ze6BU%Y&FJ zEpG<>Q^S(KCmN|J&exk9=)k)yx_dUGDR)VlLZzgm(3rmBH5ugQ77K-0tYV@t6xEXs zjGy@EH_Ku&+IsMsCXM@mXkF}imP(CM2T zsG^}MZD>L~Z``0If0Kimt;SYSrzs)Dj+QafxMWSc%@(R^h0C;Ls+@^|oP|YPODhNHEuzVpu-C{APtN_FUQEl1 z$7YO7Q$^NC3eR&^?J6R%@|gj z<@T)QaaeqUQuglR(8&ebTOfeH3xk%Es>A{l`-s9YCw^8KU9NB3+i;$BQX!^3Wn`vp zLmFTLu1go2Tv$~V)9W3r4FJbFwD{K=2IqS4xxgE|m|xIShOmNb8WyH;AW;2oiif3F zXJIgeX)7N?HyiV(wIi;1-}vxYovjdFFn#ogQT@-EpVINw#)CJm&OhZaN(zcG*H5j? z^jNU4h9;VR_Y_3{z0n0UDuq+5>GjU4sBmKrL&xqZUxqmZQHJ(RBk1|_b!nFOMRkwK@&5pXoMrfK{4OU z$vMZ)%+AZU{g-6rgBlT$Ie!#pQcdpo%B%+c&msg`rt#+>$?DW9CjG&S}n4t?(mY>Hn)qa3kg`3ich z%H}gg*kZ;XC&G}-<{KD^*aIGj1gc3CkHDYG4A z>=bw}&+Zjk(f8nsQex=Xk$HCh!sr{Y9!eT$Jv&PzblY>eXkEA84zmZdkS*=xJt(+leU6^u+YOblHhcw7 z-+Dl}@-ru!`@ADg3wUEQY>rH^a@(9)VRJcP&GY>bJL-CrtH&3 zS(+3?eshFLH}b|-iV~-f;j&xiQsDyNhoPl=#N`tDU!3N6?2&QS=}q{1eWt`0&m1e! zIkp4kpK`gP7r*nOH56hd(3TWY46xDUPtI@ig?3%HBefMoPt|p$K?oKkb20So4Bk7M z?;YT0@wAXu2A-{{y0>~Q%r8v|^#LO3xJm?pQ~8aR9U&ew2KEBJG_@UfrfVWT5$XVE zvL77BqLum9x3aaprHTUW#(Uy6p( z-m;!!L7NL`lMsMq(UOc-moU>qtfhY|@s!boWR>SHEJN%AS(f9?S=al5m@pH7|3hu2 zy|bo$r#rc#ns#)MjH29H|LXl#$?xS92Qx0WKQvRodH41mUCjIbP(-z_HIX9WUosJO ztnrr6^Wwt%%v)((4%;&|awZ2dq#?i-d`kEwlqAQUvkLfxI3-}u-1p>~v&?njv10?$ zaR+{Ae8VyFA=sx;EaMfKEYZrH!$|l{L%|6cEi3~lF;H_ zGg4g$Tk+%M`f~GpzI+FGy!+4+{_N82xE;-(-<$_6b@b=z_rwd0E|&t12zZa%KaeV#p+xNa!=JSRh+UY@6D1-yq60;ZoW zB(xIrUFP+DE_hJn`ic)uoJh!6x?dXIpJ<9{@-WA6(b&ibzJ_tpqNXZju9)tRMVJjL znjeZ6Oc#{yikjjR^98$A_!nz=9d%<@Xl{Fn<(`@+77<92`66;ibA{quPx8zT$`a<% zmz!xOB>Oh_pUr(9c8wIAx|P$IjOZ^D{n+!2s-{(F0>DhT27D+GN;@Rl9-jwF# z(DN1p4T*ny^K-L;-ab3u%dc-16O}D$Ux#|G2dZPTW&!$n9bcXucUc4_RG0D_peHsb zNVdIZW~I~fTkP$Pdtzy2lU8e+Q+cn)?y#BTdm4?A4!M6+N-<&INFL-DuJZ81gb(OD4jWz* zCP#3#NN*+8_H1MbC-6kj(2_BewW-F4JDV6^KBv$VcqT1Gx>aiPd5nJUeKr~cAy(b; zL#UX^Yu9O_ykj1oJtnENwkWL(oO_4gSEf>;I1a1OUG6GPa%$m#Qz+E%=IJIs+M$af9h@z$CzSLVI2_7e4X=AX{i=Lv$(%hkDg+2&J{ zl91eK)Yu4Dt-Hswtb$!OE`_Neh3U`3%m}AMhi5@WZlAq`5WC^w?1M}g$CMgRK1J?U z?(yBOzvJa=^R5>iE3yg!;%XgjPaK^f&?hMYxBV}V^W}-P7CVcX zEUvq&uIovjYh>i2=M*SUa8F6IsIkgahD=U>>Q||-6jKhXuFUTD<^0>;HkQ#@8Z{Mp zlf0RW%d$Pe`d_`0=mX-zzj-!gWLOk4*;5OHy9>S>psJ^;*FuozJb-MRR)wB#N8c6r zcH5IzEu`_Z(FC!`up8=?f|b)5kFxZL`_G-q>e|B0ftucV(Do@r6fA{ow~*&rOZR`X z`;G>}<}h5kGK5R<52^7`U()2FT2%gN`$%D?(n-hDjF&0;-e!}@ z3mZ&q=?uY^G`2&ZYQsKot;5&PU+FS{zopH*@>WJ!Xi#ej5|Ap`lhGzpjD>kajVNgx zHVcUKc6M}siR=a3@aF{IsmH~YavH0>32Ywe3y+0D^>f)kmI|{ieww7>p^DRf%eV`>zaD0$e2NOHjQC&mcr8- zC(Hd(Y|H5^3C6y_h9X}5}4=1|Z zo!DWouYcod$IflYw)&z(`aa3}y5GSUsKwMJ5W22gnIMWi5OcK@0f5*wxK!=Q5}`bE zdk3ufSbM_^>E8p)q*>`>k$1b2u_5s~n3%e;mD5&kG7LycOdk)E9h?qVqGi6aj~?h= z2BzAy0>P>2GB!~o(>0}c%X`XgxMkF|ebRZ+i6jk??KZ-1I~b)7JP}EauF=C5Z-3#s zpJz=yGdoxc&HlZS;=K7#m7} z_@+r29Z7Z?EP4Cc)hfk*S=da1{Oh}by@)T5Cg2V&Chvo3%>QdW1?M0Hm+`SKjOV(2 zKRy$p`v1f1?PmYn1)28CbNSxT>g_b`fty2KWKeM)93G;@N%!rc0~092U!tG^nHgJo zv;FE-xWbLWGuc@mVFO{|qu7al>lZllQ`hF`-7i3_JqEUI%U)VB?cv zIqjKj?d+@_Y$y{WDQLM{o7qhzp?)R9RY4XF7NfEx+XgLQYNm47n!~YtTs>FYo?2z+ zJ{PtY=0qja-1keM+)N_`?7XG}$8E+)WPB85N8jc60JpYi1Qt?gEJ!wef8~Mot`~!} zOxgI6V7K1U!ZNh<47X$%iC`S>##9({6(6!f8j#AXz-_U{utRvmU#W#kNs>++eSinH zc%ef<(5MC!EG>e);&B@bWAa3Yw$U!N_Cvch469#+C;3?67kCa+cj3qgRtPP@RIAI# z?la3rUTHWsvG;=u!1I_0Q;Mlswt(>Bm_{J)&+`0CB-(Gu^@3~zy%X&e^KJoI$NF-j zA0tO;)UoGDo`l@3t!e_Egz`4zqg19J*=;6fG-xKErcm18k=-%B2pE#Qv1z%M9Fb@Gv+VVdmpNX1XZ1mZ`{Sl}K*U}D2Myn0?4nCt z2<<>?s5|?Wgrx&Ul+=m+c8U@J4WYp)BA$JsA0@Ruw{* z&1ZDk-D#_T!E0-Z67SJ-#Ao-g?Vm@R0qu0c4w^}VMEuS`m($S_6pHgUOTgth%omD& z2ZL7a^oQ~PZjrk#Nlw277;J2>SRh5n5t|gszBDp2-0KJumvwa!jJZHxypzZws!l>P zBuwZjTkSd^_;{8X(9yO0v)S%xzkayS_}alNu1ntjI%NX9Z(z_a#Z&V8ya2maZL;My zyyhhQ&i_czF)>N66W8JlEOWnKXpVt^(@@2+VO(@t!*kn_iY6`)we`VI5HOf%9*3AMzUA^lZA19~h8!Cfs)6CQQZG=@`X<>2j znwrV;H&2VJ)D?=+-?kb^{%XSwGMCwM^|0sW8LSM;A?4blm?iej)|hPeL{inTL-aKD z=bn0O&+jm|Lkx90uU3Yo_Iuwi_^tE+U#st8%MEdqNX1a=5Egpn1>e`lReyXOY9%x* z&HAdQmGPb2^!$gMov-Hr0}mBuKJGxbkC&(X_jfx4RrK;>OLgr=C~12Qp!3s~2g+>6 zjSS&eQ9gTPX&M`rPwZq@_B+5;D1z7nf@qTtS;*UKG@-)eFKfhpZvZAu9vhAvHJ|&O z3u259WBWU^=cX@8Yp!q($DBZf(WWPbPY+S|Lm3Y(aUaq?{b;h2@K_{rQhU=`9k}X& zLZ6RK>|OA%UQA@`0B*BpFMmu)!~GN;!{j~-3sXTWx3q);Ol@j{1KnK@ud>h+Y*gMi zo%$0VjTI%6hk7-~UQ=end64()lPx*+dYeq?SOb?v?=4yE2=9WZ?W$kn0<9nf6}Cu{^0|F3Zyqr;9JDg(Ts%>lM)NLearm1@f%GbkjXELDnramo%3w+ z+&Q$uQRS=7suWKjOcDn^O_F5tnLsEhZT?I2i;hOX<><`{L)i$E8yaRC!sGCORyZ;k zbOPv%-3$u8VZfR4&y11uPGr3y-yww0UyHJDO%jQ8Bp=3zm;)D;QDd}4Lr>Q)r@4-a zhNx)#BMy%Zhc%O_Z~tK+SSw)Oeqg1es}mKN8joajZgMmJJY(ziJ#hIjS#w7gHYbV3 z(`UNRZ=zE#-RZpQyP5f~*&}ESm}wmbeinTWU5COEbub#YGkpm9)weJ*G;QMU(=CR-`@SsMQ3?GCFSpn9v+|BdL7Y=Y%4QcHaX$pO%=f98y<=hUZ#w;%Sw8(Ig|xb9V};!C!1?d&f}Us_763FXt_Li zC5R30g*=NCRJA2Y^!ekiI|;?DHhC3vHKl{xD%d<9Xpx1j14`%q#e=NZg2Uf_j>Z$r zHBWf_Gr2Xysx+pJrJ)oWVeYz?5}PhWY0nf9@Q(WSw$S~4 z^#nZ{y-=<%WGM~??1BYILr_)FE3NlEHT`(va{*v z=?Cuxb@lY{1UwmmOadvi?Egap5Pq)%m;qO}^O-Kw&$)@am0>9tPdTF`gRvMi3u3J# zPo1t{Sc;zQK1@4_sf)5>Cevtd=ha1&?9w=Vzhb;kmFt==i`6jEF^6Xo%OOasMi};j z8EB`FMdPj^r)dRnQ53AuTuUeQVb>%-p6D*yR-P1Warb}Udg%Ih@Zpp+*`lI5x-FK= zBBrEP^c^bz!sOxd0xm=iXX@-u?25y^88MkCUTPyF7O?Yh8L{M>=va3fLN9osYq{qh zOD-jYG&2ekG*l#1hY|Luz9DI0O+5CaV{>YZvIJH$BCL4SJBUO(i}Ljuf2rVTN`5pl z1Ngmh-6PSAJe37;un1`|rEkjuVdx|AW-$G@!L8vT4doc{KGXe{OL6}`GY zt$u~wvV~wtBu!9`jEod7+6aF>EdC#iEtV*{8|DVW&H0XQX7&cB;0D7{ux+`4MkhCxV!+K@0_nqE;vWkGk5=dUx>1+k6Xfl^O> zB4v?xNYxTQ2h+>v2nQMHrypR$P$J_-=l1U(=MxU9V2G;5Qo;4Y;0jP3;()h78HKI= zq!<>^?j!THl!##$=XrYud3_dfcmzZiBN`lXW^}6+0b?tt6(`o4*@*tw6C{~lA2^24 zVH*5}^td^nwqqw7LHCN6DTv2vr2;L`P7FpzXL$kQ23a#CyB9U@UMzm!E3(Mnrw=>9 zjkN5OKt5{CuAMmBqGvxwnHhwt%h#S~Emb0larkJJY0d?ACj)A=qA+~6Asgf}>H7_o z_;s2(6j(47kmtC+t?K(-RlJ~utiq6$z{s`f^giS*45)fg_V@5}JY&JD@?%U{RoqmC zR6Sczy=%N6ri1&@M?B8N8LP6B>BmxBhpP_NObuU z!N>!Fzzn)QLL%L{RwpftZM2TcI(D4r>kk3_&lh_cQqx2;c4Lu{IF?NUaok)bd@z+A z`aaPn7JJgEmw0C;sM8R~*}x<4x+4(PlXO0mP`%2jv^gdI9y+a%{ei)oEa+MNEsbITDDqt*pn(stslo)$~j#axj*G*2)Mn*(fz7&G|yW7NdG?*;p>Ubs_ z8!3J9auZ303I^}ZH0^18}$2}A%?tObF z(r3iZD}$igt-fdMN|@MbQ<02Cg|%6S5eh;~rz+^F=G1;lVJ53W4elH`k|^Yi=F~xJ zsn(kjsf&>FCFLe=D9G*YT6rQ3zIL1y@@0;nxeQSWTd}IFCNxfuqnc{|k>oA!+@KQV zmn%>n*HOSG7~Izm?J%$U=e75o;Ln~()I`0u`O2G^8D=oo$@!_pE=9rujyZXRxe~4W z`LB_f-4!h4Y`t^7%MXRse|RuODyC%U;20D*?hI@?s57EimKYGkg5sN}HxIP=s~8RS zKYl?L!8W^m^Rk59;ULNm(Uh`?Pv@hir-|V^kw_Jw=N{$K9>poUPZ6PM!IDUcyS+u& z;}>oxU_A~EI)9ymXAv|sX#@v9qV?cMFY5^y6 za2e!0xK;t=I(H-+?wnI3TcF(Co5I}Po9~n?-eo?GzJ7=+^C)df`TYdRS&5?T-3eEuyQ7KUwlxV2HTixTv;)Q7gDGG)rU)b2w4 z(YJV!S4rJBbidnOHAA0ErM=J`g>osvD-v;7b`9Mpx^I$f^?18)1aMq3GBR+2j zj6688pgV#5*^ihcE<0;Y#N{Bev??w@oqOvjluI|qB@$pfT zJdrH@=6~2rG8g%`{Pu9Lj&dX~BtiWH#wvCJ22|;YA6_d{cao^ddzV^y$Dhwz13z|X z!B9%{ZwU3jA%m-ig)9u1Vmmt)au(Wu7daMuTJtrshh%bLMW%IbU{75WbZ^yc4qQgo zeHVF=rW;ncTSJ&@{Mc7^k+4*&vyyK3KP~|JP6>N)fhzt!rT5*gQG@HqaWS}ZP>B+l zs2}o>I=r$~$1vkH?gb6qHd8rf-rcHFNicqJ+Tn^D28uH(ntuP1SR8X*=*Jj(zjgP{ZQc$tVS|D{q(JdHHaxy z8n&@TyBI8=Nv??)8j3?wo3jL|Iz)Mji@aN!wSQ?T|MFaDcF-N$jUXH?mRrQ-aTK)5^JGSf ztMM*u|H^y!el1B?g^fGcbX`6zWB1&^L>Bnqef#-7cm)rbHI^K$Q?(i zYfqCbOm{DgAgJpOk~3@FPb1luQ*fhzxoBcZ9{t;RT6*xw9x0puk2fcG_3;6Q^6y$lhzO!L2jNe5ta#V}z-`-f9$Tu5hsSh|a0pGF zw(Mk!wS&WPr(NBc66Ju~%hKk3hOi?vPL3B@1&|o{&~^OJrHm+((+6bF{!@TR$R$Su zMda(&K{2lpX`g!f05nyE&!D;;2npZH^Q4Z?o}3EsMuOt31*R0m^9LW*5(Dqv2rl}z zfr>foVO4d#nO9o?L8uy{TtdGSF~vNMu?d>o$O+_1iLyK39!kAIM8ejWz&nvM z>^{xxPEySA9v|{=-ygdT_NVN~B73l-%7k+|BD^3Q{cO49^Ea$mTvmhbm-VttE-NqU z?>PgxUY`&v?aiD#ZvTEqumUc$4ShbDwqD0@~feS5Uy`v~;M6#+oN5CI5lvb&lV>BorH z)%x+ftrf0+4b72d-o3v}@sym95 zNHD(pGP~~EFD_r;aeVQutn8v;KOiOLQ}|^r3XTRYmPAX9YS2V#JQ$dy7zv;8?I=)3 zRh11D^A}-w4#&4?Rz5GS-1`rg%1U1qug~u5Cg9WRT%S+$tT)QZtXi+fwYC{agQ3uce>yQc;Ct;v@2)ht z-Tws1=BL+c1XNS*m(T0i4jXi6@l2kk%WRfQDI5gyX0+~)6LWoo5m?TK-jE39$*d;` zn)3Iee@oEPBT!h7p@?uMrf&md3%ip+J|O$e0{e=cxl5@|y+(?>M_0hFV-`&voy>e1 zjJEa>CdV%jtvqPk2t2rfxL*VwiNMgc!zuv5t(R3*8bWJZFr11Y{dW8Sl=5_-*ZTng zF*0~S1tbMhO#Lcs)AHIq$rm zN^7iN$0XiYnPajFio=gAyD)d5dygyImM1q=+O0pKyf$1Aeyf0S@PYJ5B&MrtR2v)s z&ZVlAqcE+lgLEUDKW$n9rNV64YBs+SV|+<+XIakETsD75yzV^WOwcF#y&RS);)(?8 zjcrUM#zG)QF$+gh3#jJg&mfI34&H6 zDIMy|x$A+sDxCXUUzS8)KMdu$tQn+d#l3T3k6q zH0J#tukBLV!8HG|j(~+CM%@<-e_zkhg$5gPDw@@He-RENK=$jlpA;`oa>79%{{~wkv|d)GD&Glv`$Q^5`O`wVMB~x3I z^`>i{w;w#*#KeZrcF0GgIa*WM=7_IT&&2$OUno}bSN$%d_B}z}tWO@l4LG7syqUGG ztvVhpjcoA_?Kbd+Xs+iT*~tG9PiRggqWHkPw)08XcB!^V9TO7qY$fi(EMnF7ftQ_d zw?D7P{o-#B$+7=T-Y4F4E>A)Q%EoL=lM!{Fc0$h)_~+NBQ<_Z{7X9TOHmE)?MFxPG z(c}4HVPEj5v5(OB;X#KH8o*LpUZNmQl|fQ6woLpV$+BsO#dRB#tH+N824x(wiQM0q z`SVGRXG*SDQB1W{E4B-$Y6vnn_<*{#J!a@SP+`22qH6MVCH7msNvmGMvQ?HyiS(_0 zlAS&#{3vx}9l74X8NPo5=F*0~LWAStkinFt)M`zZ_;i@+89t%M`TkKJRq1NlNfD~g z_V#qDlhk}%L0Met4e%UtMmli(STLExs@PSeQ(KnC>+rDLddm0qrsudpt4DvXdN^&D-Xt^;G?lh{cfB z1-E^mwwLcdh0+GWX9 z%t&SoA4;bpevFErkr6)eYXFDisx`a(4Zz_@6d*GB5RLE7Rjp;?Z}RNsZ8obQ_`YF( z)g3?|Uh?P>XB=tEr6$Xv@Gq%1W@#$D@#i_5qz^Mx7@GY3_xcVgcHcH9v%$~gdJW+) zJ}SgY%);rka#8Y@^QAJ?edy4sgx@i251p+ul4snGa#hk3`fGgz*-!T7Mx)@|7jwH? zHWb!t^~mpMe-R!g;f0g4P6N9A< zS>^~Fp-7g(=27bHNfZ!E*?8l>()y%XH=0L%Dr_kO3ND#en0~Kej4%1chB#D~dw;o2 zguV=>gh3%QIRyvX1BW|El`f@)mzEj<2Z`aF0~>C!vlD32$w>gAa02Pg6j;rGPo$?c zdUhrksVNVCZ6LkjPT|n$c~pV3ZLvGY;B)@!+pkKyJ_@PfgEl89oEp1fkhGH$gSIFf7(6$;nL! zX!ZMjs10#Q$U*jBS#GOKs82}{9ys_O_F}1$Ba>L?I;~V8>oVJ-%d^`j|9Y9`dLPia zDoacipb!w#PjGsOXYI; zTfD!9P|A(U*m;9P|5ifYa{CO`DX_)LZ*c8`&t3w^KCNf;_|AIhDEU>E}%0O zo0$<{PdfY1Abqn4bU&bb`=vXzN}38T!CZ8S=iqbN!qdK2ndk>RwIYT5PPvC|MT_l! z%V#w6o;GILD;qb=KB@$mFj$2zF5_Z?4HL(eH%UJS>!rYq#}b9Cx?Ll1y8q-6;W$r> zs@4$+6}ak%lNWzKL8==ckuUb@i_vZ~#p}92pS9jj%}Q01MW!2#>q%9p?aGw=twNs3 z-%@FeIxrwkrhg@yn@_K*ok9j@ig9TB5To7=x%(fsb9qN;44|TUmg&FF2OkhAOpi(} zz!*FP7k(uF`pyAn0$u*&nNyR=V7hWCTW-5Cb@tfHVl^p@@za7&cvdu94cGz;2Nz*+_ryO%O5E z)dwnUV01=6R!PBP+Tp8!wCvZ%hADm?fd90w#?tQXyQlr8)UYNlT}7mEU~woIFLxvu z54Mtg{m@0071PVVc=KFhye2b@(MnsMI7>;fp+L-oj$ps^A5@<17mcX!HtrdFAZY@~k+k}IU7>NN;)6@mVQpm`mqbcgd+kj4HXjOSU+=WpU zW7K|h>dm<;#eoTm?%TI)`?bd8nbURFYDjdYkzOKSYryDgj$s-0HsFzurpaxBH!li} zj_knuFDtY#MNU$2nNyKv?jo-LChK=gbK?jHHHmuDSM&v*GPj!@@Mt20BzlVA-~-8T zLy3^Ef6ArtrvePdD<7CHHu9y;v1fFE_kP&G=1?MmXEk(?56HyZ<2o%%dTjTdE2E9u zK|k3uoJ7YGeW!(h*Y&=)C$j|fbCJ9}zCi0$iQ(oVU#}Mr19qM1(q!D<@@>K)`JF|S zZ3-5in4ySgvan+Ru_jqq*xuI!2$B+bJTHlL7z5W=p=S1-qZMks^46@dk0o(m8QjYtwFKVKc%-(qVZ75vz4kbp8SA` zvq9LJd^tW6e8r7Q<>7aBk+c zL|ktBcPR^S|Mrn6q}Q5X=OMB;-Hp#o42m~;jX_fj-jI%cKO!qJ-#X4`JFelOMUJ4G zp4*uy%eOr5#ZYahaTdzO8e%MiZyE!YTFiPt^kDk>mC z4lV;u-{X^sv)a^kX-7=(`OG(GwT7onKY;34UnF=QWF+wOLOUF>2UZM{LTy;)x)&t( z*K%#<9sZVFs=~)6NlTX)DoPIyvB6=3p14N{{d_ueSu~ccr4bzaTlY4aSlE02$4~dJ z$XzY{v3dsP60!RyL=qRFLy(}vrB1l}>-2ep(-Y!V=IKw5p4aHMNF4HI7KWm%`6PyN za)%j`#5>Afj8nSHjDy$w*I@02%ccb)?jKOr-|P2xq8>`Ogux+H$!W;x6i!4cH1b4I z)+kH`u&9i*FbgF1Hv?J-)@oh!V(RFy8M-ZElx9%qEfLeO ziMX6_5V@U3qMP^?h?k2oG7--ZwrzBhQ}6d&r+z_QReP^B=Nx0+Bm2^!L_r7Va3ua9j+>Fi^3Ktn zfbQsgw1VX|&f;vXl2njhUpfzh9*HC<0`Sro55u0X20+1L(p&5m0t2=XrR;ldbQpR} z(b#ixrKfS!wVnnwpRTtvzCr5?6?bDg3pEuv*B9r2l&rdPmt`?oj}BzdT;`QFT5N_J zs_Rd-3^E+21M|0>kJ06F*+NpYYcshIojAS$S+L%(2Pe#jYXLohJaHS3&!@Ky{_DOB z=bI6__JpHkxWgBo21sx3)rdO~g|4y|&Ry>1v}oarbNPfTHi$E2xL!@E zDDcVO84O?e<0l(#;EH^z@5w!G#V(BiZng9x$J1&zuKwlyc(+732208E`P{D6=PQ8e zO4v_Xz_1s4;zl*eKf!-!Uo4x^oXPv6X%9$nQ!xeZqt{iiH~6#3S^EJf=Rg7MVUg3v z*%I|l3M!+8>xF%|&Qd~?`tEFEP{_OUo_a^PvFT~!d&WK`H5>_=;e7nf_0;@$dUSvn zR-;}=-oRdfnS|ddMtAGr#n7lCxNmJWARYJY>jpC_6GBAhofquw){kao1O69jYM2T| zJTX&QIRY@O6<8z`l(O8&cdP5UAMWng9qo0th6ndYKiUQ_S(y+_0~<56jC5*6+6DMk zX*o`kh!GDt5nUKtf(gkTIzB5BjRLqE z%?vCOEB$4JIFTfhv|r^odq^CtLE3Q>t{jduE^x&l31twMml%m;PxS>yCglpsXs<&% zog!Wq)3_L_%auR-myT3}JSs71rU){!u$-C67*tzUWD#0;({^rPVEGboaQqUn0~$qH zcC!@O9uzDnZqY;_S*a{xac>Rsmk4%f7y<+YuqXxyaA;CsNxza&=>A^e@m;^FJ@nzP z{SFkn^k^bSHvKpwl=~5xF#QTcAnGSiXtR)_bIno^D=Il{garxhapn&ej_?v8u;R-E zCJ`DW;eom(9V8|y$n(Njv8@L@I=s~CiJ}HK;aF7HG!Z=8jD*=#6kzSI$WmUaonIKWEv(LXEAZtW+WWacXL&-*=N>o;X*pBEC ze-n*3$4LSYFILV!nLt9>>`;(O;Znt-#PG=3SGWHR1^@2E zYg@A_JRx_HJ?jVzO#sYMuBhLGGP z{k|@flgF}@;`0(F<`Z-U+81#@$M_2s?4Q;P6wDCCOZJO|$)u%VyBZi83k$3#Z9n9k zs#fv8#hM=k12WP1`n+BL{#3(Q#COI&ywa?yBB%Y0$@}>2nM?Fy2@kZL;yFOn zczf7k&$hUmWRm7yR)Q2h=jRwBjRZr@7q}PK^#okD8lHKK`KYS47T7DVZ(;3CU{t31 zng+ICNIvuQTDo8$RfKn4=9Uzy0<&MPhEvf(StUmMZ?;%x*?w1_8cCn~reoK|s5O~k z?{#GQIwo=GVt+$LFp%mgCCx0;zaGBt(|hXqAGT*x_`q#nedx8#1I@mbQ1`kIbM}z; zx%lY9Zz8_yjz=0LngbN&OAsRXaa&D7F%Kb|n+^hY!zy`;XbmkLX4MOIavwyY1-pWZ zgWx+bSlS6ZiB%S=*~9C4x8wRGENbJ@jQR_9p{)7G=uC*tQzfV$yIPOfAM7*1swAmU ze83A#_|+QY19JF(1B7+MXP6Oh(B6W+N0BR}#gEg5tX-SyqNITY1{ zlkF;Cj!;NQ(S`LWG{q6p@K<<0id~MJu&`x4YaIwZ*&--Rsfd+u4u&e;DGl3mX_vIs zKu)f1^?#yK(0_#m2=wlrC8jZfig_qt0)3!pgAj-Hd42c+r#cQEae3mH3NXBE2Bj~G z6p30G*^(XG>*5jnEu$cgN$vVrUvS90qR#Rb_qfyW8w|`9aTm2<)`*N0@_`3l{*j!J z(fZs}ks&n`z>l&Q#|o9#vV_;awdKjxlC%0&-pT*O?j%Q$fgwBz5yDEJL1)#|*F=Yv z5T-f@H4d;fCTe>6Ta+HYSVg9cRKIC#+yOM`hx4Gzs5f`Ppa2gRcDe2{SU>?XiR9_! zzN06h*@fM#z_x@Y(`fwe%o1-VaY~IbOMM&fSl#Lu2&?m`^s%cUQRIvXc$^7xUY%ewSI_@d0K29?HC$vbU#gFw$YQXf3iRaP z?b)g``~14=4Q78q58P1jV?dPePQ_-qGIjD{h?a?<^hU)W|ztp z|G-vN(Ymc9j0ywbe?0Sm-G047)Zs8EPxYuYDdL%Z-t-DEH+ZBXyI_=d7mXx`j(T$F zlO5SN5sbO~jrk;;fR(`YY@p@jjX5pI7gn~inli7a8k;^CAUM4{UKO;|DkUj6s=}^OK#2UKd=Zd7lErpnge#UK2%F#S~A#TIbc)LzpFrO^X!j`W0%EyT7~+tiESR(K0Y=J$|@8FE^wRVV$Q@Gnswq0g#*ek>p?lOo>gA&pDjQ zs&!`YZi0NtZhDT#zm#Uu>2=5HsOB41^HR>d+_<=4PI{}oca-Yk^D9`rLp}KUHw-T0 zRAD|2de4!;e~m@hi5mh161jLl|a>y$ObGLkyF77S(b%i=934KS98 zF3hFN&tcATz+iBjB+Wg0)psZoDVk`?avXi8(`j2!jK#c}ZyGo`@yHvoXacPwq|TiPd~9)a5eQ?f+@`)x5F#`l=4$U)7@tK0pKjIj zx{wanm&&+qyvRhP`+m9_C=mAlPxOF)tI)ch4cxuu3s(-kf6Y2IVp7ZWBJ}Go1Fbt* z$2={}1p$oY`^Nwvgr(n?@BZ^NwnbFq+yhVJDV@G+OyLGRsiy`xvcgdzOkk7=gruB; z8BiQyUJ;%~FRXejM=~RFnPLXg)X2qZ^E(i(j;|CWTmGb&h&U6?^*y56+T5v_cOy0H za5pa04!!pRommmsK8ta1H>(NVw_OqZqYsX9u=}ZZ1FEdpYd<&w|7-=CdICEMdjN}C zt4uF#%(jAwLHM9lZ1eRm=|=@z{X^Xntd3_&;rjmA_0wKyQHcCQg|Z*_Ym2Ph%4)$N zG7m1E-&qw{EKe#oy|>8m7HRub5z{v5j-&FVSWI^)60sfeWwa|QH(Fv76Kn0aL`I^< zFgf*tUI|8D^+)rR7OE=ggELQQTi%QEdK{)u1^(;>B%{I`?^8d%44Q`g$-*IZN1x)d zv}cbb185kgj>qb&jpkn*{luqh90d9Qkg&yvueLjrd~Wcj=O*h9t~(#85H9;|yqp9) zcAOwH;Jb6RXaC4$+5MvV`^WA)mySjpg_zO=(PP_-F(e{>Z+*R9iNL8JNs4TsVO*ds zK^k#;dT)~9`22K-to=8fq*uP^E@o8XuFw~>yZ2wjp7))Io_`m(Ja9VR z!2mc!)|0*u^~9v<#n&M=mnT)pZJwODL1PRWe;{E|4IALh%p6M)te+EFo-vy^g4Awz z!Q5Za%P)B65)C()7>Y_6=Sm7WOn3DZ;^#GCOra1Mn=8s-{TiJbkvN?3Lg0*M*I@@!GeWa1`k!Bx zKY!%BkDTI9Qh}2fwoJA>K0U+X{}-0#JL==WKl*s{{EN$i;*93t3505Ax@V#c^Q=Id$HsiEmx z+TePl6FVZ`8<8I*e3|B~K`g!x<)mf}so*UYtSaGHlHO`S~6;<_1mv<`K|;LY{^U}GoIrvm>^n7gUKg=HBfUFHuH79dn)S@ zr$j>uBPkv^N{Sj zz-d=5XC0jZ>topeglX{W2>z##?v#wvz=J+6oBjCXvi{&aOR?E<9cRFd+n4pnCcEu? zEEM{6vC3@H666n1s=TublD5XcfOt$4)!!(;Zf0*bzKUadUKfV9n1{0<}UodU=%}BZ?umhW5v+m#2bXqTmhQ<>XZl)Bl%B7EG zDz{u#_4yv3C5u@Gdvr7|>6I zCc8<4JQO3$2BYQrTq>%Q^YcZn1`9}3O8Mi1AWC@)f)0Iv8!zT#%F~0o2;chmKNm}8<%Y*d?>lPL+ka;(lB`WqGSU)7Y|OuH)<+YV4)>{D`x+1dpp;UxNe(E?E!iBAMSPpLk5&=U>@lgf4wPrW^%@_Q6?5cg1HhTq1 z6b94%;Ck&od(g#v&t&3321;V)q~ZZSKooR*?bg46KzSLJKylfHs5Jyhgj=)SZ#Wc? zWGlp7Nf{mWk!|Mi1c9v4e+6wLJdywFBZjX7CcdLzZ~8qi6b5!8t6esssE-U^wsf>fvOT57sJjL-M;5ZK|?@wVC(aUlnF^)a9WCu+{-yP zCoI;fqtfA#EEGF$cePk6$KbH5L~=RuQDzKJrYn)t4+Vi@r>4o`4HkQEZ?stE%A}DE zHx*#2Rv4IQ)M(2ZNeirFYhP`;Fj4F(p5K*&ki*v~v0QiO4*#}^n7giVcjda}^M2wf z2*P~c>tCroGAA?zB$)F(T=+a)uO?U!;LEO$+tujxA?vCad)JQS?w0U+#C9fMq|wEn zq6ZQqlLP~mrj{=MmQNX3=I+&DF`W7e4wv6>eq3vW!`h0$t?vzfFYtv9C$c4XGJgej z<*f&eyHKM%Gq2y5A_88N+HbS@Xf``^Fhx&$Jf6ip-)bZGS!FQ&{ML)lr!pE&E|7A3 z&}wu>H-bY+u3q%%7lL@X9Y+tD+0WQbN7m>lvKt==n}p_t-r}?(>18+@=sb0OGMO)@ zF_}GKr_*oF`PT%7@$-b5R*SMyqc2X~;Ts168I;W9(BvMsamDYM+4SH$W4Qq~*yxC2 zt<>)1ve9BMbBrdgCDV2-IPnp8zEqt)H2(!~7Km#%ps*`Ch{c%4{mw3BDw7|RanAFl z2#5Iv72{pOURcN^H*$}fyV%JN4eUUS+l4QIM4a4tb?~^}d9I0&JGNg^uQAtQB)T9H z*7N?&SE`<7i1{PePi1jE;u<|~&ToS@Xq%2;dXdWZSv+eZ~St-HuzaT zTl86&6x;D^{_%99kYoPLv}J7)CC*K)R=b`EsM3{Nz3sZ(>_;7T10wbFC$p!!&-})r zXu^{HAY>S?`{5`OH7a;E0hPa{bT+$vs0uKNIk`25mH6XHg);TLm;}iczkBHLWB@Te zc~Wf1r;vDJxOnXcyX8&;$2c@J85TzQp?a_`59~lvsk%%_&y@M?%yx^VN2=vLx&Qc2Uz-3HgsUjmn9oXI*j9lN}kY_IY+FPvO z5F*lc3N7%vJq9J;yv#Ns#Cd-%yBwxCCa@xNKUTE!GR63uO#?63&kj1?%jzD z+n>yib4q{SulP6Ec=b>Hq3at4gsGy+c9)Da7b(cegCeg36UivT9it~3WG9(Yh0`Xa z14%laQPfpLjxf+rkSXHl-n9n+`YGAOAP?qrqJ426@POlZ0=~5SiFB1(oiJ5mBv6$` zot(XWejO7!aVZ>$39N8W3Q@l!*H7_FD%zFB=?&?1a-JD!RCpL|m`{zT3S5tz`dk&wmmxmGv)n?5_RMFO8tK5UV!sO+UR zXjL7@(9N67u?4pXtHm3+DouGY?lLZ!#hf)65@af)AR{FVgiF{^cEEHfx!M7H@{M=& z@dZ|K@idwEO3-;=7-ykZ^NG*nY$H`?nY>z~W^Xyce=qo3lW4$bfTdr1o1t*ii@(!& zh{~LgCreFej0q$9VL?TVNQ?76l|PQ+AGQed3U%{;)9v?5s*FNJ zz-HkMY5mG5MbTN`XM?^UU)CFW^FfO?>Z2{d=we87%kwH$+jercx|$cXU@AIL)hPVl z&xb+K9(RM1^^VVG8O>jJ%B8wfCNzu<1rmoR7KwP{M34Oj{%>aJ*RvNw1_~T$)hnf{ zufVyRy_~4GeK|g(dI^g8q<@uf27@vft4aI?^8#K6ZT}l460Y@C?Z45s;-i-yee1)2 zRlqaRFD%eF9rPnKu{@4VP#4-|u&y^5k-uY)a<$wN#rW%sui9f;dZB8IXp9Ien4jD& z&R$AYsm0(#NkeT?;9-z~p;qeh2er~>II-|Xm}qyVO7x&0&bDL_>FG$^3Sctd#xSn` zxg^5IURRTmKVJLeXId~tNlBaY#oOj2TrZHjSi)<^>pH~d7H8Kwu{^fcodMu-P}4D# z88u5>ZT6;|z+cW4yXj`LIY?Ps6NRJB0U?*Y-&K=r$iYD7{5rFor z{l^r3^ntX+as?oslCzP+Ow@9^xrOq3rwlEj#S`qv+Pe#AgO}yHd~;u|wFTvEwk4-& zk2R@ZTCH}5NSMLs1FDsjyOQG$87MU1nhExE?-T5vk0n$xwMy|xcYW?=KS>mI>PqNn z3_ISr7Bk9=)v7S1W2#)Nx^_$C_>(Wzv$;BUNrY?TuZiU&v(qHMCM0nr(p*I+1A*t9 zR#JN9Ul}J0rN`K8_M1uG&(;?Y$j8t4O!7!w6R!(KA)e1+r`o;dsKeysWZ2}UcstYM zTX+hlCysah#0=d}EHeVHdN^!$(egmDV82t$o&Svy#9Lq{>XHF0HaxtG8IEUj$j&l& zGWzWC$-%xGtq#LB^?b5M%Ax8uoF8VG%727mSzBpV_1JR}4Sj-8AZM=m1GASe7t5XO zU|d)&H=5vUH(ZOPQ_8iZf=T2w%#qcrSBQm>FIQ_wXsc7-VKtO$z2$M(Y$mu*-7LNq z!c4CO<=hPf*58k%tb&)8INYis$GKX?jD#HNmsbr{oXAGFG>_{%2JGItF@Z1;-=4DmIO3w{GU?0 z4bYO(4Uf{h4cVeuom57Nd1>Px?3aFJ1^-iMc`m9P*4P#3CTZ5PC^Q zegF++Qi>#S7~iDM=moa^?&H&?Qn{K~QQ#TN%|?9~tWRfI=o=(NLpod)8SKSx+oZ+Z#)w&{MgfQpv3@WjgE7dUE%-;?KvqE{R{Ehm$! z5@KDK6PhYPK$32KA298&g|gFOKF?Xp9s-;}y5!Nai@N@;UO|<`vC$PMwCNadSY!N-&CM13)@%XG7zihE89Rm)zZx z>wH`%FyRO{v!bu^KzIr^E9sl{I1p7xr6GlSvyqOMd1>b$LPeWWX5OxSnI1bmArU9O zGF04A5c0aL_CrMGiUkr;Fe>%JF6DyGg5^L~Qb-&ysN`~VW~5AxVnCwOJnq*+q0k-= zM@v>*$T6(EEdckQec7y+#lwuQOD4-Tu(<;Mq>TgrtWAB7+_KKJ=ibh|tMw+9yw3p& zH*G)lVb=NLddndaNXTQ?YlVaijOb_HbWH`}{&M@J)8jO!%QpL9*7F-^CUqKDX42?y zn|caMa_7Tk(X8(+THhzY?v2N`Jls_PunmU)U$+v8Bs92R>Q&O#DjVwvwLx?f~C5zF`dWZv|0Qv5N&YDsi{L#+KS4(-slorp0p9H1;=%|_Q9cK z;RuA%O=wc`=|gs_@cVxuDH=)qU@_r)l6@R-C!X75j|XBLjxLxplFq!{(y9xC7iLM{ zxwH5l*VH&}xFw(~;X1EWXjX0e69xFazLV~Kb*dRScR6w|0m|DWV?cj#y#PhKl=FOl zl2(wK_v^*DY=Zo8i1l;F^9%A5E=z7ffd1qfuH=DMnv_&kwAsK!nc(At%`Fmi#xD)- zJl0vuu`V-M&(oOUDep&mYY2HTltGl--9E%ci0$c)s05{I8J6^_8A1Dwe9ruUbWB-U zsp{oS3-g(BVfL7WU9ST4%Z2w}JKbdK>vG<|KtvsKhQ^3{wOXCooAbT0X8qs7j}i&H z6957}M*EM>Cuv%es^IIDM-}OX12IHwHp4=L+nEIUK?ef8tQ9+K0+zVZuiwrrFSSJ` z1V0r@lhNN0u*)1A@4WWTW^=5&e_+e4k&JLM63R5bn4+~=`Rw}=QIsiUGO?US`p<@8Zx+5aO5CsnKvCBI0P!h zzLnrb_2)oXVs!YCu*Ti{rm&Kpvq*I#Odybox0=Q=MBz=$4NhXgvK_U3)zs=+vR-nG zBE+RDQE7Dqj&!qar@ZVv;MZdPOSP|1gY@M0sY5*OsCha@%6k-6xY?#RG2|m_M-U-4(}B> zPP2i>JZvI*CO!}>dEdJ6@U2e;>TQN&WrXz`(73S6dbeBJ1TCF?Wj<)_a5P|Bql>vV zSIzPUWsDJ;a9HcqTgc& z(Zv5J0QA`gpw9q?xFQY4!_j@asK47IsR%QJMu9Cp>iN`>QbomJYH{{8K1M8gJNC&i ziGRI&>klv-q|E*ywduwvEED_HiQxlDF)+w55J$?Gb@u85F0X|=oKS8LXZ%Y-q3$FoRP z>xCq(>fPimtTJn8F-SM}yRvf^OL`(n`_Rx|zlbmT(h9m(ZSDb6JMcxVKW$gKk|jAZ z6Z+o~gqbNz@I)1=uDSq@oEfEJl{B3JYOPE2(*|**Mc=SRv zjA+2>M3d({W2yv+_n%ZE=1LgRaJWL9v0&cuswm{<8zCbshOtMCg1bQN;UrNinAKK#7!a*C7iVRN9EEoNJp{Ihy_1uBh#Zs%*pzpdZ>_ZBJ*uglk zP(TK)=-(ad6@W5aWydg8tJFwq?gHQ|`$K9Jh=iE9u^|srr>V_>_>dw7P_a~Ro{by! zsIS2c$4R0qwi?qsJ8cBUTm>Hjlbneidb?U1W-dZmLZC!_B5IUC;^+F;9!X)~Jg&k5 z_+Pg()4i-|2l{@wPVqC=Z)yb9qr81G&&P4V;!+Qacay~>@kb11V+L+yIKfRO_vlPP6HGKExBDyEr;d&mDP zeHFg+t`19mF%BW{XV6cqDzggLZw_c*=9HN48DqOZh)L+yKjdtOQS2~0P6|4!kc7=< zB@>6;x(II44-2JKtuEH=Oq*5Am9F^5c#S=*im5yri!tlBV>?Qt%k!!rE;twXqf-Z-Yz~ux_>_>j3`iO z)8FTbpr3xkfxpyleWRHQI7t^S0^YnJ%l z>a`foKZAfCm}hrA)vMB9bvmRSj!ORL*n~X zUK*gbwMG&QuFl&isNml);m9tD83ey3);M?>=I%DG-K2aF__5&T-!tZcO1oF|ZX2B@ zS~NrD7_i(E z9;wx8JopKu+X&(GUz>hrg#t}QexCBA*gt!b=VLi0R=~jQE>Z-i0kn1u26>MV@A2go zcUeVALd4Y?bjN9$ryo0+s_n$|l_zR<_*RS(R}>oiv^=R-&wp!Ip8IaQZc>?qwT|-n zM&MTs{{D%T6YQ_}i^a^FrfX#F$uy?EqMqBNNOL8XIS7e}Doh;K&n6x=`(@rWHX7nH zvHRTnBC&blm2BM0LQ`Hp;In@k>~%2$;@e*{iwr)%@TYd`-bJR1}m@T-~ zqosII=RI)B?wgQr1geZl4Ngf(C+P5PUi1inHFGnmJmb^QBEVsw6@*m`aiRY?5f&A9 z{Z88q(Mo8`cs+~ryOI;{BlJOq!Gxkg<`-ea-4sW;_<_TV67;2~={Z64uYS9^Mf^UbjS+nN zF36?+Pl~R%p5+3ey#xEUi;Dub@xF9xS)GEtq1u$!d*$#Hcbb7lxZaf&vxe8KKPzsb zim27~K;b9`rYl9jqLHDZ8l&VLT^14V)aBwqRPsEgWKcrNt`o_5iTB)_LB1h4w=e%N zW6MGQnJOfX4iQ13rZswfnMTWye4<>SNN<)8SpC!oMfl;H7*WM{0@4lVc78)by}^l4 zQ6@*T`{+^bOC3Nbc>LkcWRPlnwh(z2hnfHOCg4Y$@>E1Z(79c?-y}1sI|kiATivABf@2_OTyW>97ZUi``VEGy0S1%FbM9#9 z|9b)K7C>vXx|boFaGut1*n)M@4!rL9h_LkecWfnD5!t2G?SF1>2;CZ472qFb9=xU96 z(nC)Ub(@uw8V0+yHY<8a#Us)|rFI275opJ=exqa>^$L^K=1O($G)HOR^PClzGe-&q zWe)MOW2j2($xtKYFnb)7P}27r?cRJ7Y%i=Jq-mYjBJszOBU6H3%NOuy=`acoE4l91 zIwh&1!Yj-Id7r>RsZ~!`^C1^e5Swjv7PCPmWaUeRliU`{)Z?au*@l%)IP<`BQ%Nn){ozpH{&lj?2Dygx;kM92P z0~Q@9isg7b_(Jr35Et%ZU)XBYQ+lrS0GQ~ZPW~BEw57Be6w%c|Drx%_<&~OE83m`% z5qaFjPCK{g80WX+)!|$|r_j2*jrn3}KZL9G@snDg2Iz%46N`)G>L?mU4Q`g}!976`Kxk-E96&B11x9 z)q3f4qm9p;s}ic;e-I|<#AbrI&2T2YxMC+QEiK9oQ#7&OW=6`3KtP=U)WMz3W$~Io z`@8$5X&|z5Pb$~*>7JeELhNR(elW^-%JRAWp1avfY9gU8UkQ`sXG#e09^|>7zJ&hM z6Zm!|SjKJJ8=7hL<+bTda2)KOP(tY{_%-5E#q))(u1zVxn4 z?VR%y7geA@^~yScz>sL5HPXK9@JAa%qKhGFp!o=c1B(j@At9APfvA*{vZpGEZ0z`~ ze0*y)dklDe{kim;eU3U^?(7xWFg2Ht`W#pF@9Qmt!Y860m())CwdoMSRULroZo4zq z+rA@8j=<~x6_#O$C%GDQicE+Z0}r*|!A%cYROM;^6eE|-hi_;LGAbi$m7X_nN6UC1 z#DuKw9_mz5VEpAE8QH{UDEFQ`C>i2y+)@sJf^-cZR4C; ztvcPR5JeulL?YqvP}(pt6>Byc+~v(|k)iAP=5JE3kM{eb3<3t>UP${+k=5v8q6(AA zh8oTh=HBD5Qs#D|`fkAJTEHI>5gmFA-!JYQ5Bzeo%{IRGGbvL&68V^HW8?u8^cuZ) zR7C!NZ1c?i{yGn&imF=lZ; z>bn1HEBMo^!~Fb69qWH0j*^m`#cT$H%TagOlE3Zw^f#cv_Z-I9UXYHO}zzKX$Sj^DUboy`fuzw6ix(Rx-KE5G+ zU(Qd-OqVEmXwqX-!Thy40!1Ma?=M1MqvBerC+eqd9ONk~3aQ7Xnc1c)M-^!`9&R>o zo%h2)GkIMIJa+g&cm?9kVoq7@HrRNcxl=-PS6o)NJ&;qhBYJTIPD-Q~&$cQMA=|zt zOiD%^N5CAOq&&}dP>A_x2v_#xZKO0x1A_K_VLD#Zo<~_0QiZ{vb$wCbyY!{8RJ|DyggAp!+JZ_-mh9 z=&{sr{%P8N;(x?DVbBrTT(VSAZN~CHtX+Bm>?_?xXn)y2pSquq#MXDIlGpr5{1ik0 zKBI;~s*K2_LPHPRA%HP>`ny~(&1Lpm9_{=v9LD3bI8^qHoE&;2I3#=DrelU5c)nyHDh3y7N zeI;+*d}aNzijPx4DZ_Vdh<(Q8R2^CU*JBT_jKbq~ZcU-bEP!#M1=2G3SHG|EzTX}J z?RE$ToXh0StCXyQBn%v|>MWeMBxYOty9!1)I^iwTvT6eVg>Y>&ep=V_`Z!8VRa(Ru zM?U)~t8nF|C@uw;+~)=LIDwLz8aa%`h4C+uy4ff-zc(O*wa;`s*Gz?i^_V79qlx) zheR}0Xp=Cw)nYODCna5Jk6zF&AFWIX8b{F{G>1K}obcjeL#c#iOmGi~#`Ri6B7LJT z261~qi&u)RjC=jz-o8E>A>R-H;wyF^iAN=cFVdHPBmDi#rcxBgkcjD+-T( zqnVyA6uQ$ati*c$vpOiIYeq0?G#kgm!*`5eH8rhLC3V7EoGZvr8fcH<=<+Y3P$jLU zI@~iNPfRz+$qgU%G=8FLccoHV7+8si4&M61O-yfXw*0pa;2MdyGi{?9x-~!~9ykOx z|1qBu+3QfwL(0y?BK&N}6m90iv&-V#kMFW{v5TXNBco@>r&XKy>&H7TKTA<47sR~R z&$-KRd=tPYl+#v=&HLaVsX6KSx_nCPPKj&|nu=1}e3m zFx6qbU!sxcJ+xXsI7oUkvT~yoTlS^{NrGdKV^;&KDD7;YO#D!l=PZ}P8cDy zmlAE5t`GyKUWiV8Ua6*rcls8EI`$-ngfS6MPQeftnyU7ZH=k342|uDNk-CO#t|b=b zNTEU8iv2lOl`_y}=hHB~JtVBuZlsT6z9IMRi-GGwaGV_cK?zRH!X-5A{(LESx!FzG)c+Z7I*yrl=Tr8VHhX8r zV~gkbO0<-A)kBfKZ>-Vo0u1&1=8hZuKK*qNWk4!WT*vZ6nMH+YkOnaJ|03bS29ZBW zpPqvU697H|{3ODA)R#fXKp5X0X!iI5vE76|Sy2Ez2+bb?ULc3MKyklq)4sxLk;1aJ z^CjCx2_zJ)F5M7KC*)c!`?x!$#LnmG@cKN#X_g*wj*K&=%WbhzvjP}*)vte|mG{i$ zgs5EMGkVj$J1)0}ghpo4bMJdIGCqzYt3Og#j1B%l*YUD7<6&v=b-vPv(b&Ye!&C?| zwIQxIv%#tKTE`ApB|DIXBCiM&(dcO{$yRR}UfCczUUsMV-!)$Cv zO8z$Q<6>~9*ec_I1GKYqv)5~0yLPKNc{QL-mRz(iEhkG(N162V*b)&=ao6K|qpRzE z=gG(ZMB$A=L?$#_Y|_W{RvM@e5ebVFd8R9rM@Enq) z3}si^&2jp%qhP3rkjggmAc$uAkQV2r+A3!F}ZsA?HagneP;n38Z=_0 z?6XX?=xoe;KuBS;m#C!1*Ar_av-HqN*+Pkn?2e}yTlI=-vBmA;yjG|PQif8DY=r($ ziX#8`iy9V!?I6#4pLpmhs=? z-QC^WrEwe{xARdYUm?oKx-ilB_;i{2=c46mBmKPqVN{e;E_0!vRpt56&`457fue!C z=m84qIK8FVV2`h{tzc{Og-T|IthEdu_j}y$-9qB?%GR^_GJNWLe`D0-FUJZv*(EJ@LV-v-{8v;MD zD~Cphll12@d;W=dyW5G!?ke_r!()3NA1~GCNS`Nx(tWrypCV$5$kcA+vOckVyq+2N zc#3P;%tCcol0j2byWY;HWu93sT%I_tr)kb}wF~@3^~q#C_4$C~iP*qC&vn`Hdb-@j zm4$L{x?Jd7v?3cKPfpF0ODT^VpPC?}Ck+dx2rFHl7;+e$@39haYes1_V-ug&SqSLQ zTB^?zKV8&O=A{iOJ%YnQM^gcaZrSWsa$i@r4-YsCm7=u&zO`U<+fOep9SRk6P?(hk zoN+OeQVJAP$;WH-3nbnl22BF$zgzmL-G@#K}@KC>$)bg6+D)_Md^Kr({vbabEKk)l>_h2KZ?sTFkL~cYGdzim3FcD*|uDoQAYgaBWJW}RpC<-Ru``GUr0O-nH?8R1546@&8Dww_r5g&kg}_F#m}DVd=g0U3HINol3K1QDbphL9430SOTarH3H}B!-~{ zq`RdA21c48{_{M~`n~JDKb*Dpm$T2>XPt9j*R}6`Ut!O%`l?fpy5@o`IHJD;4Ed2> z%oH!;sVo~j)(WusEBj|lTv9@?L)F)x#WbIqG>*x=O_Pc@2&)A&CZb*5>%Cv^E@uwI z(ms|5!%srEt@iTEL89lMejbH1RZ>c#^C;9L1V9gEl;I(7Rb7*&l!43)H4VQ=fac;p z2GMtosnC^_g6u4;Qiawo!#r0Z5tvVOXod6g-}nl>RFt?-(d~V&)Gt3HQ6CG9_oO2s zEC8ib$V<2wx%n;1BCE(C)9)*&&_1=8Utm%t4tSY#N7`x!DH6>z_mF$GIY|DX70X$? zVUp@;x1QFt_Q&1D;{9DS^@rw`E_7f`AaOE{nV}uA=dcPZYfRi}!~7W&MNq=ozWo~N zY&LvF^I;{IM@}bWuD+($=J0bJO(JyDF7N$Mvm+G%+6DEiR7w6~-6zo<44l$$MM4wt zAnvpk#E$qN0X?rjFQW)5*^1~inHy}z&mA4OpJ^>9(8m*B)jc6%-8gM>tz75;zt8}V zN`U9tK&0?B>;Yz0iW}XYvt*sk5shy0Jm6HPgo=yhdSyG31<_QrU2} zI#mu}!nbJPC8bQl#7tHkZ?S)r7^p12`_QkjzJ(gOKa{@tJ>#bDAcbyob{fK6BxuBq z)U8BUafR!;?#IvZZrgB_dB>gDkMf;n;THKkoBRcED?h0MU~g+D?* zmbvN4#~@RUmCL2br#(%iu2;Od?|YmF`yL99fn9BFes>93Q#+H87C%Hdso2cGxUS-J zB8bCh^JGggp-|*YN7K3-<%`T~TRT?fi^sWDWZ53YiDGTvN#LpvI|aB7GJ<)25;OJI z{Yn2ylDXyfK;-JCJ@6n#0kEg(#J9Fsh7>-wwPk;{iK4$Bz&*^8V1yp{t)0B3oq(Ts>>)r`T_A44)Zs^*PYI+cLhrn(xo3aW$!+eM$zZ?1){e)X+}RGG zJaeF@F_6{M+2xzgO!LkvHTxN08eTkCjUp@Ui|Y$GnYta$Qa#DT;Fl>;3e#@mWGY*k zet9!@_6zX&eu`=n?bpeO_b3AHHqBqO6oC&}v|T7XEJtRX^EZ5gcpBJ;DWKoV9uH6L z&nKN^R8UYzucO0bT76JnU14-ePIYuPa z%Bql1bbST$)t#pUYiguHw_Vkv5UzB3VyUEh%X9Dql_VLVOR9bbrnE9Z|GogxeL(?X zrQ{x_T>69Ap{%d@YcA$$NvM3aB4eS2-FTC{b^6r=uCk~XmHZ%K?xLZ~^k6+0!;Du6 za4oe$=V3*us~(@(`HVxobW`TtjE#+lQ&F!sve*o!lHY!9 z2OxhW|C16PJh(OQGon79RLu%#{!>Il5?|J!pV4FpEb%Bcj#CMK4PTl6o=(UPesq=X zSrfd=pq}#P6Qp=iQNa3o4HUJv)R;qV8DI)nQ2183n3yIbdzXdybu=rRD|<3#fo!q8 zPCrJw0{l5cYt5Crb8&~gGjxt{DhdA%ehWs(j9&N1+9Fl5ZT&_5}JCq>4Q;E_}o{t~O0 zBs3&SZ{elQkB$|#5?}%?+=-{sjHL=gF1jPs#}&{M)xS8S1=}jr=pY(VhiZ|-A|+bO zfxo_Z{%XLSy}~vX5z)MqfH~$U$_fYw3Oi0B0N*MqP>hW3ks8`jw0MIlNMtH+f2oRz z%U}vklcCfdIuoK*4o{!D{vjxx*?{sND##3xz$lml>T~8^ASr{yw~f(wn(-DzEd|zW z@R~*TkhA)*5zaU0Ht5|WhDLh504zI*^!iaG0n~(#>1cwe&B8#(#y~J8cYdDD#F$T7{?&mhc9{KXTcCJD zq3<;96I*KV$}>)Bl|5+{uJAtL$p6+mKP40r{Coj5l&rhkgvl-sM6bKjO(od(=k6?= zEjTDmDyA(+y zm|UwWl%pf!YFQGKX^d|^b1H^0T-bWy>X6&69 z^1Xq%4N~TlpG*`mXdE>|?*OPs{-#(s2S-scrKt}JWrBy)J z5ZT@&l(32&5?dQ1>aa~^N1VB+5^}xq)x)guZQ2-KD4|t{LgRCljhfI_*;Cmz%a#vi zpFg_}1}vO(fTm2G5-Gl0C>*x6#=lG681Bt43EqwIu&R&V>S^nZPos%6C406MB<*~L z?)$@Y#H8fJ)~%tf^=&zEv@jn`(_Nz=-{f{U>EMLI?Ddrg9j5lWjD<42whrbr;0lqX z7Ytkad849yb1}glA{#7scX(gdO{Q@7W)<#*;Zjct{j_=;7+s)pU^|uh!F9BW!H@Sx zf8s{F$XaPlE9O|!^cDeA$&j)R&L0VVZKGVre)>V`!C?>{9wnugs?g zFd=g}G-dnzA&uuyT+TtE?}yDqrcm-_;mhPqrSrs3U(YtD2-VZl4RZK@N|dR;Jsq#d zGCx-QYdUq?8tESMd<56m*KugU{0iBF-tVZ>?sDVZNI(nLw=;~ubindS$ED9Eo0^|cZ!m3<%Emk z^@{bUaP&Qk_H!z3bZee?RZ}b}VSab(h0@;(K5?dr!n?Q<1lxt(Y6AoFVe6FkpKBZL zGL;c3Zh34yp@)x{4I+!SAvpa;+0GDA(^VW|4W)gI+LOiA`j^S?Ojh4J(D~REQ$N46 z0GxMlTvSxiCar__4|zk@_v9+9Ya_q#Mwuhlo;BC;+bz{m&bA)#+xNEjkJ@i6U^_ls zN$s({{8RMi)b-!w8ZN8%!!s9OUMPF%I{5EZk^XmhxHH4;xww97kdnA!Ue7z+JWJ)2 z26E8|J6RjU7>FL~T{5>UC<)m91;_7rdLQ*^K8*%*0&$%MPwEsa`A&{r#(yR0R|e99 z-IBgUlIJvt?F>RgYMU6tUPb=>+!YZ;XmvZCy~S#WZFoLw`Di=jl0$5a0H4t04MCl5 z2w0BU6;tPG(O2C`Kr?RGH&Qt`ZREUaoB?k+7rE=bqvBRcCIf?1&_DU(Cf=fn^Kh7{ zapVq8R?ZY3;g(!1FiivG`#*IFGrQs*Nq!Tf(DK^A_n0V2E`X=VuTzghR5ppJJ#v5s zhy1~qXGejT#TZq0HJvCY8O{XWAq#G9+Ul&c0S&7VUe}$SI)MRh<#a?#AV8^V=_j(d z{a58P;V-Z7uHubz`3nP=mC--8gu*OZlFhzG_AK5vD5Ylsh!P7tdb+vs?O%d?EFb3NG-19 z;(P1yUTs~T%#zDCbSnbd!AUZh?0C*|*SyB#!6MmCPQP_sWm%gR_U-X)BMa zEWPH=I_`L@M8${8-fP9cf8$Ck_szTvv5ey7Cto4`AE!Lt?O1`2(0x~f^xm_6UkUH& zkMV#Xx^*C`IbJEw)MXf`17R&}%L4}iI2#L|o6(S?_)s-o<4Y`rH3rC+SR8}F5a&ue z5RE*(7D=N@ei^3=;UsyDL{93dkkYJupelQ}u0g3{(L7q?XR<^FLc;52avfW-?5eoIk$z>vWBExRlv{yUdFER}yr1zafagRJRWQ5{w=H zsv&K|tbjjAGXv(x#goZ!2_YKPP`|#vAhSm@{P@h{%A&vnARx+-5rqK0wwYlsqM~9@ zgBdno$1q^D`uz`<5*U}m?pnGO(W&`hSDJ#;9?Cy8Myc`FRjUJeEG6Snzq~h1B|CV79%u=VJFyJ!qGrIS z7a(5OlR86B#+WaM3=MF*WnmLYKyZdVNJ{JoVzOGrm7&mx7w`W(ly|2Tzk%}=7wQ`d;+v@b-pcTW5t3BFi z0l1rq_r(SyEFPl+NiR$Cv)!_}g3egnp;cx7O6( z9oF5{d*F0~god0>HW~|v2ilcF0uJW7+tLh^?*TjX-9jWxO$2C{nMQKE1!rC_*!6vP z{@aO~HgE8!SE^k6Ib}`w?OWMO=e(EQ-{VmNoe@xQD2~bAH`lVNH3kpguXfZ9QFY}hKwD_SDkEs^4GD#toD;9HaYT`))C6T z^dl-QP3#eVCWz9z5#m#h)q*6v8}Oh1QPJ#;hHX(>zMu0~XGluRdy&9#G&N_BId z?|P5eCX_L7wV2QKnQ<)h5kp!Q)lk)b&P;=!QnLMhk94Y{sbMaVY=&rxQYVy=f=f#A zqiv@35Nt#I;xa+YW2QC5araa$MEdc+apR`i8l|71_gVeBxpYEgj5!;KQsnm-=R=h0 zhl~uJ+a-mpqkS5up-;LdB2Td6bA={v*Hkoirhf2=HaKC2e@Fhr1`pe{pdBEb%bYsgQw-r%gc`wBLgc>e2GViOY6L+vJhj25QyHd z!eHraX>aw4=VCkK0u`3+sY}s9x2NiVZB0U9gc}^H41O%?YIKlVrk^p!eH# za>wZDSX1c5&+HTO=Q>y#+xcTwkvOL$L}_LQlJCP;ctBUcT>Xw_wN2ikRsyBsO=5nS zg<6>H9q26iOp_Pr)e%X5zw2Ad2&(M6gvs_7UtDIJMfJX=)w4>C)=%Tj)q6owhCM&Z zI^Pj@9#%JFV3+q_No-RvtKDQ&%$0yHpYDAPt{!(CFB2dmZ5D`G=vl&Z}&K74Wd zEm@%-X2ac?LtPEp7C03l& zkjZ8{jLc_}+7m;J8P$N|_x<_?zI9J26kCNXnX~aPr6_S`G=JP-1Ij`&y%ytA;<4kNEAI08Lw0akMK8|BLizK zkn}%CK2h^7!>fVF1JIZ6` zW2nBoc_$S@rbETkl|3wp{{(sGb1*eDoujPQ%a&c8T{e=stN}SJR+0@!O-K&hAUR^2 zp}yYrfypmuGs#k~hq6(4EqWGp5TqbU@f7~~*WEPd{?%Ctr{Ltkn{nCqBYcn;?H~Bf zG=|)-OX|VxJ_b)bj`|~H@{Y7f%@fx;pX<~+`MW>L>p#xQ%od*A?h*$FUU_1~BK`r) zG1(tGa78vpfT$$Xk_kc3G(8G**OXSz`da_Y)3`mzQ`V4A>2q9auhE`VTP% zUSY002RjdgIj0T?t#56FR}OFuT8S0H&#*SzTmL-)M#KKrM&SG)oBjXI({k7dA`JfD zE%Gi{cM0D7ZxnhF{Qr$~WjB^O|F;AW!WC}`M;v + + + + + + + Time + + + + + + timer_callback + + + + + + timer_callback + + + + + + prev_ekf + + + + + + latest_ekf + + + + + + ekf(ignored) + + + + + 1 sec + + + + + + ekf(ignored) + + + + + + ekf(ignored) + + + + ... + + + + About ekf + + + + + + Time + + + + + + timer_callback + + + + + + timer_callback + + + + + + prev_ekf + + + + + + latest_ekf + + + + + + twist + + + + + 1 sec + + + + + + twist + + + + + + twist + + + + ... + + + + About twist + + + + + + twist + (ignored) + + + diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml new file mode 100644 index 0000000000000..9f38cf6e00262 --- /dev/null +++ b/localization/pose_instability_detector/package.xml @@ -0,0 +1,34 @@ + + + + pose_instability_detector + 0.1.0 + The pose_instability_detector package + Yamato Ando + Kento Yabuuchi + Masahiro Sakamoto + Taiki Yamada + Ryu Yamamoto + Shintaro Sakoda + Apache License 2.0 + Shintaro Sakoda + + ament_cmake_auto + autoware_cmake + + diagnostic_msgs + geometry_msgs + nav_msgs + rclcpp + tf2 + tf2_geometry_msgs + tier4_autoware_utils + tier4_debug_msgs + + ament_cmake_cppcheck + ament_lint_auto + + + ament_cmake + + diff --git a/localization/pose_instability_detector/schema/pose_instability_detector.schema.json b/localization/pose_instability_detector/schema/pose_instability_detector.schema.json new file mode 100644 index 0000000000000..b45b43102444d --- /dev/null +++ b/localization/pose_instability_detector/schema/pose_instability_detector.schema.json @@ -0,0 +1,75 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Pose Instability Detector Nodes", + "type": "object", + "definitions": { + "pose_instability_detector_node": { + "type": "object", + "properties": { + "interval_sec": { + "type": "number", + "default": 1.0, + "exclusiveMinimum": 0, + "description": "The interval of timer_callback in seconds." + }, + "threshold_diff_position_x": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position x (m)." + }, + "threshold_diff_position_y": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position y (m)." + }, + "threshold_diff_position_z": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position z (m)." + }, + "threshold_diff_angle_x": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle x (rad)." + }, + "threshold_diff_angle_y": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle y (rad)." + }, + "threshold_diff_angle_z": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle z (rad)." + } + }, + "required": [ + "interval_sec", + "threshold_diff_position_x", + "threshold_diff_position_y", + "threshold_diff_position_z", + "threshold_diff_angle_x", + "threshold_diff_angle_y", + "threshold_diff_angle_z" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pose_instability_detector_node" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/localization/pose_instability_detector/src/main.cpp b/localization/pose_instability_detector/src/main.cpp new file mode 100644 index 0000000000000..34e679e86730f --- /dev/null +++ b/localization/pose_instability_detector/src/main.cpp @@ -0,0 +1,26 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose_instability_detector.hpp" + +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto pose_instability_detector = std::make_shared(); + rclcpp::spin(pose_instability_detector); + rclcpp::shutdown(); + return 0; +} diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp new file mode 100644 index 0000000000000..afb7d6e007db2 --- /dev/null +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -0,0 +1,176 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose_instability_detector.hpp" + +#include "tier4_autoware_utils/geometry/geometry.hpp" + +#include + +#include + +#include + +PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & options) +: Node("pose_instability_detector", options), + threshold_diff_position_x_(this->declare_parameter("threshold_diff_position_x")), + threshold_diff_position_y_(this->declare_parameter("threshold_diff_position_y")), + threshold_diff_position_z_(this->declare_parameter("threshold_diff_position_z")), + threshold_diff_angle_x_(this->declare_parameter("threshold_diff_angle_x")), + threshold_diff_angle_y_(this->declare_parameter("threshold_diff_angle_y")), + threshold_diff_angle_z_(this->declare_parameter("threshold_diff_angle_z")) +{ + odometry_sub_ = this->create_subscription( + "~/input/odometry", 10, + std::bind(&PoseInstabilityDetector::callback_odometry, this, std::placeholders::_1)); + + twist_sub_ = this->create_subscription( + "~/input/twist", 10, + std::bind(&PoseInstabilityDetector::callback_twist, this, std::placeholders::_1)); + + const double interval_sec = this->declare_parameter("interval_sec"); + timer_ = rclcpp::create_timer( + this, this->get_clock(), std::chrono::duration(interval_sec), + std::bind(&PoseInstabilityDetector::callback_timer, this)); + + diff_pose_pub_ = this->create_publisher("~/debug/diff_pose", 10); + diagnostics_pub_ = this->create_publisher("/diagnostics", 10); +} + +void PoseInstabilityDetector::callback_odometry(Odometry::ConstSharedPtr odometry_msg_ptr) +{ + latest_odometry_ = *odometry_msg_ptr; +} + +void PoseInstabilityDetector::callback_twist( + TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr) +{ + twist_buffer_.push_back(*twist_msg_ptr); +} + +void PoseInstabilityDetector::callback_timer() +{ + if (latest_odometry_ == std::nullopt) { + return; + } + if (prev_odometry_ == std::nullopt) { + prev_odometry_ = latest_odometry_; + return; + } + + auto quat_to_rpy = [](const Quaternion & quat) { + tf2::Quaternion tf2_quat(quat.x, quat.y, quat.z, quat.w); + tf2::Matrix3x3 mat(tf2_quat); + double roll{}; + double pitch{}; + double yaw{}; + mat.getRPY(roll, pitch, yaw); + return std::make_tuple(roll, pitch, yaw); + }; + + Pose pose = prev_odometry_->pose.pose; + rclcpp::Time prev_time = rclcpp::Time(prev_odometry_->header.stamp); + for (const TwistWithCovarianceStamped & twist_with_cov : twist_buffer_) { + const Twist twist = twist_with_cov.twist.twist; + + const rclcpp::Time curr_time = rclcpp::Time(twist_with_cov.header.stamp); + if (curr_time > latest_odometry_->header.stamp) { + break; + } + + const rclcpp::Duration time_diff = curr_time - prev_time; + const double time_diff_sec = time_diff.seconds(); + if (time_diff_sec < 0.0) { + continue; + } + + // quat to rpy + auto [ang_x, ang_y, ang_z] = quat_to_rpy(pose.orientation); + + // rpy update + ang_x += twist.angular.x * time_diff_sec; + ang_y += twist.angular.y * time_diff_sec; + ang_z += twist.angular.z * time_diff_sec; + tf2::Quaternion quat; + quat.setRPY(ang_x, ang_y, ang_z); + + // Convert twist to world frame + tf2::Vector3 linear_velocity(twist.linear.x, twist.linear.y, twist.linear.z); + linear_velocity = tf2::quatRotate(quat, linear_velocity); + + // update + pose.position.x += linear_velocity.x() * time_diff_sec; + pose.position.y += linear_velocity.y() * time_diff_sec; + pose.position.z += linear_velocity.z() * time_diff_sec; + pose.orientation.x = quat.x(); + pose.orientation.y = quat.y(); + pose.orientation.z = quat.z(); + pose.orientation.w = quat.w(); + prev_time = curr_time; + } + + // compare pose and latest_odometry_ + const Pose latest_ekf_pose = latest_odometry_->pose.pose; + const Pose ekf_to_odom = tier4_autoware_utils::inverseTransformPose(pose, latest_ekf_pose); + const geometry_msgs::msg::Point pos = ekf_to_odom.position; + const auto [ang_x, ang_y, ang_z] = quat_to_rpy(ekf_to_odom.orientation); + const std::vector values = {pos.x, pos.y, pos.z, ang_x, ang_y, ang_z}; + + const rclcpp::Time stamp = latest_odometry_->header.stamp; + + // publish diff_pose for debug + PoseStamped diff_pose; + diff_pose.header = latest_odometry_->header; + diff_pose.pose = ekf_to_odom; + diff_pose_pub_->publish(diff_pose); + + const std::vector thresholds = {threshold_diff_position_x_, threshold_diff_position_y_, + threshold_diff_position_z_, threshold_diff_angle_x_, + threshold_diff_angle_y_, threshold_diff_angle_z_}; + + const std::vector labels = {"diff_position_x", "diff_position_y", "diff_position_z", + "diff_angle_x", "diff_angle_y", "diff_angle_z"}; + + // publish diagnostics + DiagnosticStatus status; + status.name = "localization: pose_instability_detector"; + status.hardware_id = this->get_name(); + bool all_ok = true; + + for (size_t i = 0; i < values.size(); ++i) { + const bool ok = (std::abs(values[i]) < thresholds[i]); + all_ok &= ok; + diagnostic_msgs::msg::KeyValue kv; + kv.key = labels[i] + ":threshold"; + kv.value = std::to_string(thresholds[i]); + status.values.push_back(kv); + kv.key = labels[i] + ":value"; + kv.value = std::to_string(values[i]); + status.values.push_back(kv); + kv.key = labels[i] + ":status"; + kv.value = (ok ? "OK" : "WARN"); + status.values.push_back(kv); + } + status.level = (all_ok ? DiagnosticStatus::OK : DiagnosticStatus::WARN); + status.message = (all_ok ? "OK" : "WARN"); + + DiagnosticArray diagnostics; + diagnostics.header.stamp = stamp; + diagnostics.status.emplace_back(status); + diagnostics_pub_->publish(diagnostics); + + // prepare for next loop + prev_odometry_ = latest_odometry_; + twist_buffer_.clear(); +} diff --git a/localization/pose_instability_detector/src/pose_instability_detector.hpp b/localization/pose_instability_detector/src/pose_instability_detector.hpp new file mode 100644 index 0000000000000..761a10b7a6bf7 --- /dev/null +++ b/localization/pose_instability_detector/src/pose_instability_detector.hpp @@ -0,0 +1,70 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POSE_INSTABILITY_DETECTOR_HPP_ +#define POSE_INSTABILITY_DETECTOR_HPP_ + +#include + +#include +#include +#include +#include + +#include + +class PoseInstabilityDetector : public rclcpp::Node +{ + using Quaternion = geometry_msgs::msg::Quaternion; + using Twist = geometry_msgs::msg::Twist; + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Pose = geometry_msgs::msg::Pose; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using Odometry = nav_msgs::msg::Odometry; + using KeyValue = diagnostic_msgs::msg::KeyValue; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +public: + explicit PoseInstabilityDetector(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + +private: + void callback_odometry(Odometry::ConstSharedPtr odometry_msg_ptr); + void callback_twist(TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr); + void callback_timer(); + + // subscribers and timer + rclcpp::Subscription::SharedPtr odometry_sub_; + rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::TimerBase::SharedPtr timer_; + + // publisher + rclcpp::Publisher::SharedPtr diff_pose_pub_; + rclcpp::Publisher::SharedPtr diagnostics_pub_; + + // parameters + const double threshold_diff_position_x_; + const double threshold_diff_position_y_; + const double threshold_diff_position_z_; + const double threshold_diff_angle_x_; + const double threshold_diff_angle_y_; + const double threshold_diff_angle_z_; + + // variables + std::optional latest_odometry_ = std::nullopt; + std::optional prev_odometry_ = std::nullopt; + std::vector twist_buffer_; +}; + +#endif // POSE_INSTABILITY_DETECTOR_HPP_ diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp new file mode 100644 index 0000000000000..4747582cdd163 --- /dev/null +++ b/localization/pose_instability_detector/test/test.cpp @@ -0,0 +1,168 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "../src/pose_instability_detector.hpp" +#include "test_message_helper_node.hpp" + +#include + +#include +#include + +#include +#include +#include + +class TestPoseInstabilityDetector : public ::testing::Test +{ + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Odometry = nav_msgs::msg::Odometry; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +protected: + void SetUp() override + { + const std::string yaml_path = + "../../install/pose_instability_detector/share/pose_instability_detector/config/" + "pose_instability_detector.param.yaml"; + + rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); + if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { + std::cerr << "Failed to parse yaml file : " << yaml_path << std::endl; + std::exit(1); + } + + const rclcpp::ParameterMap param_map = rclcpp::parameter_map_from(params_st, ""); + rclcpp::NodeOptions node_options; + for (const auto & param_pair : param_map) { + for (const auto & param : param_pair.second) { + node_options.parameter_overrides().push_back(param); + } + } + + subject_ = std::make_shared(node_options); + executor_.add_node(subject_); + + helper_ = std::make_shared(); + executor_.add_node(helper_); + + rcl_yaml_node_struct_fini(params_st); + } + + void TearDown() override + { + executor_.remove_node(subject_); + executor_.remove_node(helper_); + } + + rclcpp::executors::SingleThreadedExecutor executor_; + std::shared_ptr subject_; + std::shared_ptr helper_; +}; + +TEST_F(TestPoseInstabilityDetector, output_ok_when_twist_matches_odometry) // NOLINT +{ + // send the first odometry message (start x = 10) + builtin_interfaces::msg::Time timestamp{}; + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the twist message1 (move 1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); + + // send the twist message2 (move 1m in x direction) + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); + + // send the second odometry message (finish x = 12) + timestamp.sec = 2; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // check result + const diagnostic_msgs::msg::DiagnosticStatus & diagnostic_status = + helper_->received_diagnostic_array.status[0]; + EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::OK); +} + +TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOLINT +{ + // send the first odometry message (start x = 10) + builtin_interfaces::msg::Time timestamp{}; + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the twist message1 (move 0.1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the twist message2 (move 0.1m in x direction) + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the second odometry message (finish x = 12) + timestamp.sec = 2; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // check result + const diagnostic_msgs::msg::DiagnosticStatus & diagnostic_status = + helper_->received_diagnostic_array.status[0]; + EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} diff --git a/localization/pose_instability_detector/test/test_message_helper_node.hpp b/localization/pose_instability_detector/test/test_message_helper_node.hpp new file mode 100644 index 0000000000000..51444f9736b02 --- /dev/null +++ b/localization/pose_instability_detector/test/test_message_helper_node.hpp @@ -0,0 +1,80 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_MESSAGE_HELPER_NODE_HPP_ +#define TEST_MESSAGE_HELPER_NODE_HPP_ + +#include + +#include +#include +#include + +class TestMessageHelperNode : public rclcpp::Node +{ + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Odometry = nav_msgs::msg::Odometry; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +public: + TestMessageHelperNode() : Node("test_message_helper_node") + { + odometry_publisher_ = + this->create_publisher("/pose_instability_detector/input/odometry", 10); + twist_publisher_ = this->create_publisher( + "/pose_instability_detector/input/twist", 10); + diagnostic_subscriber_ = this->create_subscription( + "/diagnostics", 10, + std::bind(&TestMessageHelperNode::callback_diagnostics, this, std::placeholders::_1)); + } + + void send_odometry_message( + const builtin_interfaces::msg::Time timestamp, const double x, const double y, const double z) + { + Odometry message{}; + message.header.stamp = timestamp; + message.pose.pose.position.x = x; + message.pose.pose.position.y = y; + message.pose.pose.position.z = z; + odometry_publisher_->publish(message); + } + + void send_twist_message( + const builtin_interfaces::msg::Time timestamp, const double x, const double y, const double z) + { + TwistWithCovarianceStamped message{}; + message.header.stamp = timestamp; + message.twist.twist.linear.x = x; + message.twist.twist.linear.y = y; + message.twist.twist.linear.z = z; + twist_publisher_->publish(message); + } + + void callback_diagnostics(const DiagnosticArray::ConstSharedPtr msg) + { + received_diagnostic_array = *msg; + received_diagnostic_array_flag = true; + } + + DiagnosticArray received_diagnostic_array; + bool received_diagnostic_array_flag = false; + +private: + rclcpp::Publisher::SharedPtr odometry_publisher_; + rclcpp::Publisher::SharedPtr twist_publisher_; + rclcpp::Subscription::SharedPtr diagnostic_subscriber_; +}; + +#endif // TEST_MESSAGE_HELPER_NODE_HPP_ From 5930a79badb8d72db7d522c75b12360567891cb8 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 Nov 2023 13:29:22 +0900 Subject: [PATCH 114/223] fix(drivable_area_expansion): fix bug when reusing previous path points (#5586) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 3008f98331c92..ebc1f686865a6 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -53,7 +53,17 @@ void reuse_previous_poses( prev_poses, 0, ego_point) < 0.0; const auto ego_is_far = !prev_poses.empty() && tier4_autoware_utils::calcDistance2d(ego_point, prev_poses.front()) < 0.0; - if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1) { + // make sure the reused points are not behind the current original drivable area + LineString2d left_bound; + LineString2d right_bound; + for (const auto & p : path.left_bound) left_bound.push_back(convert_point(p)); + for (const auto & p : path.right_bound) right_bound.push_back(convert_point(p)); + LineString2d prev_poses_ls; + for (const auto & p : prev_poses) prev_poses_ls.push_back(convert_point(p.position)); + auto prev_poses_across_bounds = boost::geometry::intersects(left_bound, prev_poses_ls) || + boost::geometry::intersects(right_bound, prev_poses_ls); + + if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1 && !prev_poses_across_bounds) { const auto first_idx = motion_utils::findNearestSegmentIndex(prev_poses, path.points.front().point.pose); const auto deviation = From fe50118ed82efa5562eda244578ba7e85650a144 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 15 Nov 2023 16:23:03 +0900 Subject: [PATCH 115/223] refactor(pose_instability_detector, ar_tag_based_localizer): specify file path using get_package_share_directory (#5588) * use get_package_share_directory Signed-off-by: Kento Yabuuchi * use get_package_share_directory in pose_instability_detector Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../ar_tag_based_localizer/package.xml | 1 + .../ar_tag_based_localizer/test/test.cpp | 5 +++-- localization/pose_instability_detector/package.xml | 1 + localization/pose_instability_detector/test/test.cpp | 5 +++-- 4 files changed, 8 insertions(+), 4 deletions(-) diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 24b737c309016..7e83220dadf2a 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -13,6 +13,7 @@ ament_cmake autoware_cmake + ament_index_cpp aruco cv_bridge diagnostic_msgs diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp index 6b302ee6bc862..1b44327fd9e8b 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp @@ -14,6 +14,7 @@ #include "../src/ar_tag_based_localizer.hpp" +#include #include #include @@ -29,8 +30,8 @@ class TestArTagBasedLocalizer : public ::testing::Test void SetUp() override { const std::string yaml_path = - "../../install/ar_tag_based_localizer/share/ar_tag_based_localizer/config/" - "ar_tag_based_localizer.param.yaml"; + ament_index_cpp::get_package_share_directory("ar_tag_based_localizer") + + "/config/ar_tag_based_localizer.param.yaml"; rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml index 9f38cf6e00262..7774407a7990d 100644 --- a/localization/pose_instability_detector/package.xml +++ b/localization/pose_instability_detector/package.xml @@ -16,6 +16,7 @@ ament_cmake_auto autoware_cmake + ament_index_cpp diagnostic_msgs geometry_msgs nav_msgs diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp index 4747582cdd163..5ea03859d7731 100644 --- a/localization/pose_instability_detector/test/test.cpp +++ b/localization/pose_instability_detector/test/test.cpp @@ -15,6 +15,7 @@ #include "../src/pose_instability_detector.hpp" #include "test_message_helper_node.hpp" +#include #include #include @@ -35,8 +36,8 @@ class TestPoseInstabilityDetector : public ::testing::Test void SetUp() override { const std::string yaml_path = - "../../install/pose_instability_detector/share/pose_instability_detector/config/" - "pose_instability_detector.param.yaml"; + ament_index_cpp::get_package_share_directory("pose_instability_detector") + + "/config/pose_instability_detector.param.yaml"; rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { From 2bc49aeda4d3f60c261d0466104f2b5ec88c7a74 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 15 Nov 2023 23:41:49 +0900 Subject: [PATCH 116/223] fix(detected_object_validation): add 3d pointcloud based validator (#5327) * fix: add 3d validation bind function Signed-off-by: badai-nguyen * fix: check validation point within shape Signed-off-by: badai-nguyen * fix: add 2d validator option param Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * Revert "chore: refactor" This reverts commit e3cbf6cb524a34ad3b693a8c0eaa1680e3141f72. * chore: update docs and param file Signed-off-by: badai-nguyen * refactor: change to abstract class Signed-off-by: badai-nguyen * chore: add maintainer Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...acle_pointcloud_based_validator.param.yaml | 2 + .../debugger.hpp | 13 +- .../obstacle_pointcloud_based_validator.hpp | 88 +++- .../obstacle-pointcloud-based-validator.md | 1 + .../detected_object_validation/package.xml | 1 + .../obstacle_pointcloud_based_validator.cpp | 377 ++++++++++++------ 6 files changed, 344 insertions(+), 138 deletions(-) diff --git a/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml b/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml index 745a0fd6591a9..f7a27a52bfa8a 100644 --- a/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml +++ b/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml @@ -11,3 +11,5 @@ min_points_and_distance_ratio: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0] + + using_2d_validator: false diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp index 9ef1f75427b65..6597475ae297e 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp @@ -71,11 +71,18 @@ class Debugger void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) { pcl::PointCloud::Ptr input_xyz = toXYZ(input); - for (const auto & point : *input_xyz) { - neighbor_pointcloud_->push_back(point); - } + addNeighborPointcloud(input_xyz); } + void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) + { + if (!input->empty()) { + neighbor_pointcloud_->reserve(neighbor_pointcloud_->size() + input->size()); + for (const auto & point : *input) { + neighbor_pointcloud_->push_back(point); + } + } + } void addPointcloudWithinPolygon(const pcl::PointCloud::Ptr & input) { // pcl::PointCloud::Ptr input_xyz = toXYZ(input); diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp index 5819302664907..e7df2c409b18f 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp +++ b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp @@ -25,8 +25,13 @@ #include #include #include +#include +#include #include #include +#include +#include +#include #include #include @@ -35,12 +40,88 @@ #include namespace obstacle_pointcloud_based_validator { + struct PointsNumThresholdParam { std::vector min_points_num; std::vector max_points_num; std::vector min_points_and_distance_ratio; }; + +class Validator +{ +private: + PointsNumThresholdParam points_num_threshold_param_; + +protected: + pcl::PointCloud::Ptr cropped_pointcloud_; + +public: + explicit Validator(PointsNumThresholdParam & points_num_threshold_param); + inline pcl::PointCloud::Ptr getDebugPointCloudWithinObject() + { + return cropped_pointcloud_; + } + + virtual bool setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_pointcloud) = 0; + virtual bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) = 0; + virtual std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) = 0; + size_t getThresholdPointCloud(const autoware_auto_perception_msgs::msg::DetectedObject & object); + virtual pcl::PointCloud::Ptr getDebugNeighborPointCloud() = 0; +}; + +class Validator2D : public Validator +{ +private: + pcl::PointCloud::Ptr obstacle_pointcloud_; + pcl::PointCloud::Ptr neighbor_pointcloud_; + pcl::search::Search::Ptr kdtree_; + +public: + explicit Validator2D(PointsNumThresholdParam & points_num_threshold_param); + + pcl::PointCloud::Ptr convertToXYZ( + const pcl::PointCloud::Ptr & pointcloud_xy); + inline pcl::PointCloud::Ptr getDebugNeighborPointCloud() + { + return convertToXYZ(neighbor_pointcloud_); + } + + bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud); + bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object); + std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object); + std::optional getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud); +}; +class Validator3D : public Validator +{ +private: + pcl::PointCloud::Ptr obstacle_pointcloud_; + pcl::PointCloud::Ptr neighbor_pointcloud_; + pcl::search::Search::Ptr kdtree_; + +public: + explicit Validator3D(PointsNumThresholdParam & points_num_threshold_param); + inline pcl::PointCloud::Ptr getDebugNeighborPointCloud() + { + return neighbor_pointcloud_; + } + bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud); + bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object); + std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object); + std::optional getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud); +}; + class ObstaclePointCloudBasedValidator : public rclcpp::Node { public: @@ -61,16 +142,13 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node PointsNumThresholdParam points_num_threshold_param_; std::shared_ptr debugger_; + bool using_2d_validator_; + std::unique_ptr validator_; private: void onObjectsAndObstaclePointCloud( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects, const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud); - std::optional getPointCloudNumWithinPolygon( - const autoware_auto_perception_msgs::msg::DetectedObject & object, - const pcl::PointCloud::Ptr pointcloud); - std::optional getMaxRadius( - const autoware_auto_perception_msgs::msg::DetectedObject & object); }; } // namespace obstacle_pointcloud_based_validator diff --git a/perception/detected_object_validation/obstacle-pointcloud-based-validator.md b/perception/detected_object_validation/obstacle-pointcloud-based-validator.md index dd67aab3db0c9..36b3815e7e689 100644 --- a/perception/detected_object_validation/obstacle-pointcloud-based-validator.md +++ b/perception/detected_object_validation/obstacle-pointcloud-based-validator.md @@ -28,6 +28,7 @@ In the debug image above, the red DetectedObject is the validated object. The bl | Name | Type | Description | | ------------------------------- | ----- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `using_2d_validator` | bool | The xy-plane projected (2D) obstacle point clouds will be used for validation | | `min_points_num` | int | The minimum number of obstacle point clouds in DetectedObjects | | `max_points_num` | int | The max number of obstacle point clouds in DetectedObjects | | `min_points_and_distance_ratio` | float | Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink. | diff --git a/perception/detected_object_validation/package.xml b/perception/detected_object_validation/package.xml index e19b2b1c399b2..31bb633294748 100644 --- a/perception/detected_object_validation/package.xml +++ b/perception/detected_object_validation/package.xml @@ -6,6 +6,7 @@ The ROS 2 detected_object_validation package Yukihiro Saito Shunsuke Miura + badai nguyen Apache License 2.0 ament_cmake_auto diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index 47640c9332e4d..3249581513dd9 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -19,12 +19,6 @@ #include -#include -#include -#include -#include -#include - #ifdef ROS_DISTRO_GALACTIC #include #else @@ -35,44 +29,247 @@ #include #include -namespace +namespace obstacle_pointcloud_based_validator { -inline pcl::PointXY toPCL(const double x, const double y) +namespace bg = boost::geometry; +using Shape = autoware_auto_perception_msgs::msg::Shape; +using Polygon2d = tier4_autoware_utils::Polygon2d; + +Validator::Validator(PointsNumThresholdParam & points_num_threshold_param) { - pcl::PointXY pcl_point; - pcl_point.x = x; - pcl_point.y = y; - return pcl_point; + points_num_threshold_param_.min_points_num = points_num_threshold_param.min_points_num; + points_num_threshold_param_.max_points_num = points_num_threshold_param.max_points_num; + points_num_threshold_param_.min_points_and_distance_ratio = + points_num_threshold_param.min_points_and_distance_ratio; } -inline pcl::PointXY toPCL(const geometry_msgs::msg::Point & point) +size_t Validator::getThresholdPointCloud( + const autoware_auto_perception_msgs::msg::DetectedObject & object) { - return toPCL(point.x, point.y); + const auto object_label_id = object.classification.front().label; + const auto object_distance = std::hypot( + object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y); + size_t threshold_pc = std::clamp( + static_cast( + points_num_threshold_param_.min_points_and_distance_ratio.at(object_label_id) / + object_distance + + 0.5f), + static_cast(points_num_threshold_param_.min_points_num.at(object_label_id)), + static_cast(points_num_threshold_param_.max_points_num.at(object_label_id))); + return threshold_pc; } -inline pcl::PointXYZ toXYZ(const pcl::PointXY & point) +Validator2D::Validator2D(PointsNumThresholdParam & points_num_threshold_param) +: Validator(points_num_threshold_param) { - return pcl::PointXYZ(point.x, point.y, 0.0); } -inline pcl::PointCloud::Ptr toXYZ( - const pcl::PointCloud::Ptr & pointcloud) +bool Validator2D::setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) +{ + obstacle_pointcloud_.reset(new pcl::PointCloud); + pcl::fromROSMsg(*input_cloud, *obstacle_pointcloud_); + if (obstacle_pointcloud_->empty()) { + return false; + } + + kdtree_ = pcl::make_shared>(false); + kdtree_->setInputCloud(obstacle_pointcloud_); + + return true; +} +pcl::PointCloud::Ptr Validator2D::convertToXYZ( + const pcl::PointCloud::Ptr & pointcloud_xy) { pcl::PointCloud::Ptr pointcloud_xyz(new pcl::PointCloud); - pointcloud_xyz->reserve(pointcloud->size()); - for (const auto & point : *pointcloud) { - pointcloud_xyz->push_back(toXYZ(point)); + pointcloud_xyz->reserve(pointcloud_xy->size()); + for (const auto & point : *pointcloud_xy) { + pointcloud_xyz->push_back(pcl::PointXYZ(point.x, point.y, 0.0)); } return pointcloud_xyz; } -} // namespace +std::optional Validator2D::getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr pointcloud) +{ + std::vector vertices_array; + pcl::Vertices vertices; + Polygon2d poly2d = + tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + if (bg::is_empty(poly2d)) return std::nullopt; -namespace obstacle_pointcloud_based_validator + pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); + + for (size_t i = 0; i < poly2d.outer().size(); ++i) { + vertices.vertices.emplace_back(i); + vertices_array.emplace_back(vertices); + poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); + } + cropped_pointcloud_.reset(new pcl::PointCloud); + pcl::CropHull cropper; // don't be implemented PointXY by PCL + cropper.setInputCloud(convertToXYZ(pointcloud)); + cropper.setDim(2); + cropper.setHullIndices(vertices_array); + cropper.setHullCloud(poly3d); + cropper.setCropOutside(true); + cropper.filter(*cropped_pointcloud_); + return cropped_pointcloud_->size(); +} + +bool Validator2D::validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) { -namespace bg = boost::geometry; -using Shape = autoware_auto_perception_msgs::msg::Shape; -using Polygon2d = tier4_autoware_utils::Polygon2d; + // get neighbor_pointcloud of object + neighbor_pointcloud_.reset(new pcl::PointCloud); + std::vector indices; + std::vector distances; + const auto search_radius = getMaxRadius(transformed_object); + if (!search_radius) { + return false; + } + kdtree_->radiusSearch( + pcl::PointXY( + transformed_object.kinematics.pose_with_covariance.pose.position.x, + transformed_object.kinematics.pose_with_covariance.pose.position.y), + search_radius.value(), indices, distances); + for (const auto & index : indices) { + neighbor_pointcloud_->push_back(obstacle_pointcloud_->at(index)); + } + const auto num = getPointCloudWithinObject(transformed_object, neighbor_pointcloud_); + if (!num) return true; + + size_t threshold_pointcloud_num = getThresholdPointCloud(transformed_object); + if (num.value() > threshold_pointcloud_num) { + return true; + } + return false; // remove object +} + +std::optional Validator2D::getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { + return std::hypot(object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); + } else if (object.shape.type == Shape::POLYGON) { + float max_dist = 0.0; + for (const auto & point : object.shape.footprint.points) { + const float dist = std::hypot(point.x, point.y); + max_dist = max_dist < dist ? dist : max_dist; + } + return max_dist; + } else { + return std::nullopt; + } +} + +Validator3D::Validator3D(PointsNumThresholdParam & points_num_threshold_param) +: Validator(points_num_threshold_param) +{ +} +bool Validator3D::setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) +{ + obstacle_pointcloud_.reset(new pcl::PointCloud); + pcl::fromROSMsg(*input_cloud, *obstacle_pointcloud_); + if (obstacle_pointcloud_->empty()) { + return false; + } + // setup kdtree_ + kdtree_ = pcl::make_shared>(false); + kdtree_->setInputCloud(obstacle_pointcloud_); + return true; +} +std::optional Validator3D::getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { + auto square_radius = (object.shape.dimensions.x * 0.5f) * (object.shape.dimensions.x * 0.5f) + + (object.shape.dimensions.y * 0.5f) * (object.shape.dimensions.y * 0.5f) + + (object.shape.dimensions.z * 0.5f) * (object.shape.dimensions.z * 0.5f); + return std::sqrt(square_radius); + } else if (object.shape.type == Shape::POLYGON) { + float max_dist = 0.0; + for (const auto & point : object.shape.footprint.points) { + const float dist = std::hypot(point.x, point.y); + max_dist = max_dist < dist ? dist : max_dist; + } + return std::hypot(max_dist, object.shape.dimensions.z * 0.5f); + } else { + return std::nullopt; + } +} + +std::optional Validator3D::getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud) +{ + std::vector vertices_array; + pcl::Vertices vertices; + auto const & object_position = object.kinematics.pose_with_covariance.pose.position; + auto const object_height = object.shape.dimensions.x; + auto z_min = object_position.z - object_height / 2.0f; + auto z_max = object_position.z + object_height / 2.0f; + Polygon2d poly2d = + tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + if (bg::is_empty(poly2d)) return std::nullopt; + + pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); + for (size_t i = 0; i < poly2d.outer().size(); ++i) { + vertices.vertices.emplace_back(i); + vertices_array.emplace_back(vertices); + poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); + } + + pcl::PointCloud::Ptr cropped_pointcloud_2d(new pcl::PointCloud); + pcl::CropHull cropper; + cropper.setInputCloud(neighbor_pointcloud); + cropper.setDim(2); + cropper.setHullIndices(vertices_array); + cropper.setHullCloud(poly3d); + cropper.setCropOutside(true); + cropper.filter(*cropped_pointcloud_2d); + + cropped_pointcloud_.reset(new pcl::PointCloud); + cropped_pointcloud_->reserve(cropped_pointcloud_2d->size()); + for (const auto & point : *cropped_pointcloud_2d) { + if (point.z > z_min && point.z < z_max) { + cropped_pointcloud_->push_back(point); + } + } + return cropped_pointcloud_->size(); +} + +bool Validator3D::validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) +{ + neighbor_pointcloud_.reset(new pcl::PointCloud); + std::vector indices; + std::vector distances; + const auto search_radius = getMaxRadius(transformed_object); + if (!search_radius) { + return false; + } + kdtree_->radiusSearch( + pcl::PointXYZ( + transformed_object.kinematics.pose_with_covariance.pose.position.x, + transformed_object.kinematics.pose_with_covariance.pose.position.y, + transformed_object.kinematics.pose_with_covariance.pose.position.z), + search_radius.value(), indices, distances); + for (const auto & index : indices) { + neighbor_pointcloud_->push_back(obstacle_pointcloud_->at(index)); + } + + const auto num = getPointCloudWithinObject(transformed_object, neighbor_pointcloud_); + if (!num) return true; + + size_t threshold_pointcloud_num = getThresholdPointCloud(transformed_object); + if (num.value() > threshold_pointcloud_num) { + return true; + } + return false; // remove object +} ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( const rclcpp::NodeOptions & node_options) @@ -85,13 +282,6 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( tf_listener_(tf_buffer_), sync_(SyncPolicy(10), objects_sub_, obstacle_pointcloud_sub_) { - using std::placeholders::_1; - using std::placeholders::_2; - sync_.registerCallback( - std::bind(&ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud, this, _1, _2)); - objects_pub_ = create_publisher( - "~/output/objects", rclcpp::QoS{1}); - points_num_threshold_param_.min_points_num = declare_parameter>("min_points_num"); points_num_threshold_param_.max_points_num = @@ -99,10 +289,25 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( points_num_threshold_param_.min_points_and_distance_ratio = declare_parameter>("min_points_and_distance_ratio"); + using_2d_validator_ = declare_parameter("using_2d_validator"); + + using std::placeholders::_1; + using std::placeholders::_2; + + sync_.registerCallback( + std::bind(&ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud, this, _1, _2)); + if (using_2d_validator_) { + validator_ = std::make_unique(points_num_threshold_param_); + } else { + validator_ = std::make_unique(points_num_threshold_param_); + } + + objects_pub_ = create_publisher( + "~/output/objects", rclcpp::QoS{1}); + const bool enable_debugger = declare_parameter("enable_debugger", false); if (enable_debugger) debugger_ = std::make_shared(this); } - void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects, const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud) @@ -119,61 +324,23 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // objects_pub_->publish(*input_objects); return; } - - // Convert to PCL - pcl::PointCloud::Ptr obstacle_pointcloud(new pcl::PointCloud); - pcl::fromROSMsg(*input_obstacle_pointcloud, *obstacle_pointcloud); - if (obstacle_pointcloud->empty()) { + if (!validator_->setKdtreeInputCloud(input_obstacle_pointcloud)) { RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5, "cannot receive pointcloud"); - // objects_pub_->publish(*input_objects); return; } - // Create Kd-tree to search neighbor pointcloud to reduce cost. - pcl::search::Search::Ptr kdtree = - pcl::make_shared>(false); - kdtree->setInputCloud(obstacle_pointcloud); - for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); - const auto object_label_id = transformed_object.classification.front().label; const auto & object = input_objects->objects.at(i); - const auto & transformed_object_position = - transformed_object.kinematics.pose_with_covariance.pose.position; - const auto search_radius = getMaxRadius(transformed_object); - if (!search_radius) { - output.objects.push_back(object); - continue; - } - - // Search neighbor pointcloud to reduce cost. - pcl::PointCloud::Ptr neighbor_pointcloud(new pcl::PointCloud); - std::vector indices; - std::vector distances; - kdtree->radiusSearch( - toPCL(transformed_object_position), search_radius.value(), indices, distances); - for (const auto & index : indices) { - neighbor_pointcloud->push_back(obstacle_pointcloud->at(index)); + const auto validated = validator_->validate_object(transformed_object); + if (debugger_) { + debugger_->addNeighborPointcloud(validator_->getDebugNeighborPointCloud()); + debugger_->addPointcloudWithinPolygon(validator_->getDebugPointCloudWithinObject()); } - if (debugger_) debugger_->addNeighborPointcloud(neighbor_pointcloud); - - // Filter object that have few pointcloud in them. - // TODO(badai-nguyen) add 3d validator option - const auto num = getPointCloudNumWithinPolygon(transformed_object, neighbor_pointcloud); - const auto object_distance = - std::hypot(transformed_object_position.x, transformed_object_position.y); - size_t min_pointcloud_num = std::clamp( - static_cast( - points_num_threshold_param_.min_points_and_distance_ratio.at(object_label_id) / - object_distance + - 0.5f), - static_cast(points_num_threshold_param_.min_points_num.at(object_label_id)), - static_cast(points_num_threshold_param_.max_points_num.at(object_label_id))); - if (num) { - (min_pointcloud_num <= num.value()) ? output.objects.push_back(object) - : removed_objects.objects.push_back(object); - } else { + if (validated) { output.objects.push_back(object); + } else { + removed_objects.objects.push_back(object); } } @@ -185,56 +352,6 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( } } -std::optional ObstaclePointCloudBasedValidator::getPointCloudNumWithinPolygon( - const autoware_auto_perception_msgs::msg::DetectedObject & object, - const pcl::PointCloud::Ptr pointcloud) -{ - pcl::PointCloud::Ptr cropped_pointcloud(new pcl::PointCloud); - std::vector vertices_array; - pcl::Vertices vertices; - - Polygon2d poly2d = - tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); - if (bg::is_empty(poly2d)) return std::nullopt; - - pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); - - for (size_t i = 0; i < poly2d.outer().size(); ++i) { - vertices.vertices.emplace_back(i); - vertices_array.emplace_back(vertices); - poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); - } - - pcl::CropHull cropper; // don't be implemented PointXY by PCL - cropper.setInputCloud(toXYZ(pointcloud)); - cropper.setDim(2); - cropper.setHullIndices(vertices_array); - cropper.setHullCloud(poly3d); - cropper.setCropOutside(true); - cropper.filter(*cropped_pointcloud); - - if (debugger_) debugger_->addPointcloudWithinPolygon(cropped_pointcloud); - return cropped_pointcloud->size(); -} - -std::optional ObstaclePointCloudBasedValidator::getMaxRadius( - const autoware_auto_perception_msgs::msg::DetectedObject & object) -{ - if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { - return std::hypot(object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); - } else if (object.shape.type == Shape::POLYGON) { - float max_dist = 0.0; - for (const auto & point : object.shape.footprint.points) { - const float dist = std::hypot(point.x, point.y); - max_dist = max_dist < dist ? dist : max_dist; - } - return max_dist; - } else { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "unknown shape type"); - return std::nullopt; - } -} - } // namespace obstacle_pointcloud_based_validator #include From cdf4b77c26e66e8b56e0b8fa6b65c22b952e5e7b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 00:09:19 +0900 Subject: [PATCH 117/223] fix(goal_planner): fix detection_polygons visualiztion (#5596) --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 84b4032cde4ad..6b363f206204c 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1752,16 +1752,16 @@ void GoalPlannerModule::setDebugData() "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "detection_polygons", 0, Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.01, 0.0, 0.0), tier4_autoware_utils::createMarkerColor(0.0, 0.0, 1.0, 0.999)); - + const double ego_z = planner_data_->self_odometry->pose.pose.position.z; for (const auto & ego_polygon : debug_data_.ego_polygons_expanded) { for (size_t ep_idx = 0; ep_idx < ego_polygon.outer().size(); ++ep_idx) { const auto & current_point = ego_polygon.outer().at(ep_idx); const auto & next_point = ego_polygon.outer().at((ep_idx + 1) % ego_polygon.outer().size()); marker.points.push_back( - tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), 0.0)); + tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), ego_z)); marker.points.push_back( - tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), 0.0)); + tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), ego_z)); } } debug_marker_.markers.push_back(marker); From cae657b2b44b67e17c07fc77903322bf0de14477 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 15 Nov 2023 18:10:28 +0300 Subject: [PATCH 118/223] ci(sync-files): remove stale label pre-commands (#5597) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 4d316b9fb2481..5b60a371abd93 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -12,8 +12,6 @@ - source: .github/PULL_REQUEST_TEMPLATE/standard-change.md - source: .github/dependabot.yaml - source: .github/stale.yml - pre-commands: | - sd "staleLabel: stale" "staleLabel: status:stale" {source} - source: .github/workflows/cancel-previous-workflows.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml From 9026da87af473d8c6ac3147de25b8302bf4ba30a Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 16 Nov 2023 00:21:30 +0900 Subject: [PATCH 119/223] chore(run_out): add maintainer (#5598) Signed-off-by: Tomohito Ando --- planning/behavior_velocity_run_out_module/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_run_out_module/package.xml index fb3c49bb750a6..7bd27fca3407c 100644 --- a/planning/behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_run_out_module/package.xml @@ -9,6 +9,7 @@ Makoto Kurihara Tomoya Kimura Shumpei Wakabayashi + Takayuki Murooka Apache License 2.0 From 62c34195456b1659ca457c0d7b724fad623713df Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 03:54:21 +0900 Subject: [PATCH 120/223] fix(goal_planner): fix extending current lanes (#5595) * fix(goal_planner): fix extending current lanes Signed-off-by: kosuke55 * fix build error Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 22 ++++++++++--------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6b363f206204c..a0a84adfcf6f8 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1064,9 +1064,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); if (current_lanes.empty()) { return PathWithLaneId{}; @@ -1152,9 +1153,10 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const const auto & common_parameters = planner_data_->parameters; // generate stop reference path - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; @@ -1621,10 +1623,10 @@ bool GoalPlannerModule::isSafePath() const planner_data_->self_odometry->twist.twist.linear.y); const auto & dynamic_object = planner_data_->dynamic_object; const auto & route_handler = planner_data_->route_handler; - const double backward_path_length = planner_data_->parameters.backward_path_length; - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length); From 58b909fed5a9e26d3c15898484e4837ae4271579 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 09:27:35 +0900 Subject: [PATCH 121/223] fix(geo_pose_projector): fix -Werror=deprecated-declarations (#5599) Signed-off-by: satoshi-ota --- localization/geo_pose_projector/src/geo_pose_projector.cpp | 5 +++-- localization/geo_pose_projector/src/geo_pose_projector.hpp | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/localization/geo_pose_projector/src/geo_pose_projector.cpp b/localization/geo_pose_projector/src/geo_pose_projector.cpp index 6d5308b929b25..d147888bb743b 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.cpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.cpp @@ -36,7 +36,8 @@ GeoPoseProjector::GeoPoseProjector() // Subscribe to geo_pose topic geo_pose_sub_ = create_subscription( - "input_geo_pose", 10, [this](const GeoPoseWithCovariance::SharedPtr msg) { on_geo_pose(msg); }); + "input_geo_pose", 10, + [this](const GeoPoseWithCovariance::ConstSharedPtr msg) { on_geo_pose(msg); }); // Publish pose topic pose_pub_ = create_publisher("output_pose", 10); @@ -49,7 +50,7 @@ GeoPoseProjector::GeoPoseProjector() } } -void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg) +void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr msg) { if (!projector_info_) { RCLCPP_WARN_THROTTLE( diff --git a/localization/geo_pose_projector/src/geo_pose_projector.hpp b/localization/geo_pose_projector/src/geo_pose_projector.hpp index b24b976b1eb61..b0611fec36984 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.hpp @@ -39,7 +39,7 @@ class GeoPoseProjector : public rclcpp::Node GeoPoseProjector(); private: - void on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg); + void on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr msg); component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; rclcpp::Subscription::SharedPtr geo_pose_sub_; From f12df94c098256e7c50cfbc224652d42a20b073f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 11:03:59 +0900 Subject: [PATCH 122/223] refactor(goal_planner): refactor select path (#5559) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 36 ++++- .../goal_planner/goal_planner_module.cpp | 135 +++++++++--------- 2 files changed, 100 insertions(+), 71 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 2e95ca82735fb..d647caeabbc44 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -168,20 +168,39 @@ class ThreadSafeData return false; } - void set_pull_over_path(const PullOverPath & value) + void set_pull_over_path(const PullOverPath & path) { const std::lock_guard lock(mutex_); - pull_over_path_ = std::make_shared(value); + pull_over_path_ = std::make_shared(path); + if (path.type != PullOverPlannerType::NONE && path.type != PullOverPlannerType::FREESPACE) { + lane_parking_pull_over_path_ = std::make_shared(path); + } + last_path_update_time_ = clock_->now(); } - void set_pull_over_path(const std::shared_ptr & value) + void set_pull_over_path(const std::shared_ptr & path) { const std::lock_guard lock(mutex_); - pull_over_path_ = value; + pull_over_path_ = path; + if (path->type != PullOverPlannerType::NONE && path->type != PullOverPlannerType::FREESPACE) { + lane_parking_pull_over_path_ = path; + } last_path_update_time_ = clock_->now(); } + template + void set(Args... args) + { + std::lock_guard lock(mutex_); + (..., set(args)); + } + void set(const GoalCandidates & arg) { set_goal_candidates(arg); } + void set(const std::vector & arg) { set_pull_over_path_candidates(arg); } + void set(const std::shared_ptr & arg) { set_pull_over_path(arg); } + void set(const PullOverPath & arg) { set_pull_over_path(arg); } + void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); } + void clearPullOverPath() { const std::lock_guard lock(mutex_); @@ -221,6 +240,7 @@ class ThreadSafeData } DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) + DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, lane_parking_pull_over_path) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_idx_increment_time) @@ -231,6 +251,7 @@ class ThreadSafeData private: std::shared_ptr pull_over_path_{nullptr}; + std::shared_ptr lane_parking_pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; GoalCandidates goal_candidates_{}; std::optional modified_goal_pose_; @@ -394,6 +415,7 @@ class GoalPlannerModule : public SceneModuleInterface void generateGoalCandidates(); // stop or decelerate + void deceleratePath(PullOverPath & pull_over_path) const; void decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const; void decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const; @@ -428,13 +450,15 @@ class GoalPlannerModule : public SceneModuleInterface // freespace parking bool planFreespacePath(); - void returnToLaneParking(); + bool canReturnToLaneParking(); // plan pull over path BehaviorModuleOutput planPullOver(); BehaviorModuleOutput planPullOverAsOutput(); BehaviorModuleOutput planPullOverAsCandidate(); - void selectSafePullOverPath(); + std::optional> selectPullOverPath( + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates) const; std::vector sortPullOverPathCandidatesByGoalPriority( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index a0a84adfcf6f8..ba846efbb0a50 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -54,7 +54,7 @@ namespace behavior_path_planner GoalPlannerModule::GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map) + const std::unordered_map> & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, @@ -518,20 +518,20 @@ bool GoalPlannerModule::planFreespacePath() return false; } -void GoalPlannerModule::returnToLaneParking() +bool GoalPlannerModule::canReturnToLaneParking() { // return only before starting free space parking if (!isStopped()) { - return; + return false; } - if (!status_.get_lane_parking_pull_over_path()) { - return; + if (!thread_safe_data_.get_lane_parking_pull_over_path()) { + return false; } - const PathWithLaneId path = status_.get_lane_parking_pull_over_path()->getFullPath(); + const PathWithLaneId path = thread_safe_data_.get_lane_parking_pull_over_path()->getFullPath(); if (checkCollision(path)) { - return; + return false; } const Point & current_point = planner_data_->self_odometry->pose.pose.position; @@ -539,11 +539,10 @@ void GoalPlannerModule::returnToLaneParking() const bool is_close_to_path = std::abs(motion_utils::calcLateralOffset(path.points, current_point)) < th_distance; if (!is_close_to_path) { - return; + return false; } - thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - RCLCPP_INFO(getLogger(), "return to lane parking"); + return true; } void GoalPlannerModule::generateGoalCandidates() @@ -619,23 +618,10 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return sorted_pull_over_path_candidates; } -void GoalPlannerModule::selectSafePullOverPath() +std::optional> GoalPlannerModule::selectPullOverPath( + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates) const { - // select safe lane pull over path from candidates - std::vector pull_over_path_candidates{}; - GoalCandidates goal_candidates{}; - { - const std::lock_guard lock(mutex_); - goal_searcher_->setPlannerData(planner_data_); - goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - thread_safe_data_.set_goal_candidates(goal_candidates); - thread_safe_data_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( - thread_safe_data_.get_pull_over_path_candidates(), thread_safe_data_.get_goal_candidates())); - pull_over_path_candidates = thread_safe_data_.get_pull_over_path_candidates(); - thread_safe_data_.clearPullOverPath(); - } - for (const auto & pull_over_path : pull_over_path_candidates) { // check if goal is safe const auto goal_candidate_it = std::find_if( @@ -654,42 +640,10 @@ void GoalPlannerModule::selectSafePullOverPath() continue; } - // found safe pull over path - { - const std::lock_guard lock(mutex_); - thread_safe_data_.set_pull_over_path(pull_over_path); - thread_safe_data_.set_modified_goal_pose(*goal_candidate_it); - status_.set_lane_parking_pull_over_path(thread_safe_data_.get_pull_over_path()); - } - break; + return std::make_pair(pull_over_path, *goal_candidate_it); } - if (!thread_safe_data_.foundPullOverPath()) { - return; - } - - // decelerate before the search area start - const auto decel_pose = calcLongitudinalOffsetPose( - thread_safe_data_.get_pull_over_path()->getFullPath().points, - status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); - auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - if (decel_pose) { - decelerateBeforeSearchStart(*decel_pose, first_path); - return; - } - - // if already passed the search start offset pose, set pull_over_velocity to first_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - parameters_->pull_over_velocity); - for (auto & p : first_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = std::min( - p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); - } + return {}; } std::vector GoalPlannerModule::generateDrivableLanes() const @@ -847,7 +801,7 @@ void GoalPlannerModule::updateSteeringFactor( } // NOTE: Once this function returns true, it will continue to return true thereafter. Because -// selectSafePullOverPath() will not select new path. +// selectPullOverPath() will not select new path. bool GoalPlannerModule::hasDecidedPath() const { // if path is not safe, not decided @@ -928,8 +882,31 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates - // and set it to thread_safe_data_.get_pull_over_path() - selectSafePullOverPath(); + // and set it to thread_safe_data_ + + thread_safe_data_.clearPullOverPath(); + + // update goal candidates + goal_searcher_->setPlannerData(planner_data_); + auto goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + + // update pull over path candidates + const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( + thread_safe_data_.get_pull_over_path_candidates(), goal_candidates); + + // select pull over path which is safe against static objects and get it's goal + const auto path_and_goal_opt = selectPullOverPath(pull_over_path_candidates, goal_candidates); + + // update thread_safe_data_ + if (path_and_goal_opt) { + auto [pull_over_path, modified_goal] = *path_and_goal_opt; + deceleratePath(pull_over_path); + thread_safe_data_.set( + goal_candidates, pull_over_path_candidates, pull_over_path, modified_goal); + } else { + thread_safe_data_.set(goal_candidates, pull_over_path_candidates); + } } // set output and status @@ -937,8 +914,10 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() setOutput(output); // return to lane parking if it is possible - if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { - returnToLaneParking(); + if ( + thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE && + canReturnToLaneParking()) { + thread_safe_data_.set_pull_over_path(thread_safe_data_.get_lane_parking_pull_over_path()); } // For debug @@ -1450,6 +1429,32 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( path.points, current_pose.position, ego_idx, pose.position, target_idx); } +void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const +{ + // decelerate before the search area start + const auto decel_pose = calcLongitudinalOffsetPose( + pull_over_path.getFullPath().points, status_.get_closest_goal_candidate_pose().position, + -approximate_pull_over_distance_); + auto & first_path = pull_over_path.partial_paths.front(); + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, first_path); + return; + } + + // if already passed the search start offset pose, set pull_over_velocity to first_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + parameters_->pull_over_velocity); + for (auto & p : first_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; + } + p.point.longitudinal_velocity_mps = std::min( + p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); + } +} + void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const { const double time = planner_data_->parameters.turn_signal_search_time; From 8ea6094d7065df58532fd648f7d13414af82f1fa Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 16 Nov 2023 11:48:38 +0900 Subject: [PATCH 123/223] feat(lane_departure_checker): better cubstones's search (#5582) * feat(lane_departure_checker): better cubstones's search Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../lane_departure_checker.hpp | 15 ++- .../lane_departure_checker.cpp | 114 +++++++++--------- 2 files changed, 65 insertions(+), 64 deletions(-) diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp index c77503106e485..dc55576640133 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp @@ -29,6 +29,7 @@ #include #include +#include #include #include @@ -46,7 +47,9 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint; using autoware_planning_msgs::msg::LaneletRoute; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::PoseDeviation; +using tier4_autoware_utils::Segment2d; using TrajectoryPoints = std::vector; +typedef boost::geometry::index::rtree> SegmentRtree; struct Param { @@ -137,13 +140,15 @@ class LaneDepartureChecker const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints); + double calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const; + + static SegmentRtree extractUncrossableBoundaries( + const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, + const double max_search_length, const std::vector & boundary_types_to_detect); + static bool willCrossBoundary( - const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints, - const std::vector & boundary_types_to_detects); - - static bool isCrossingRoadBorder( - const lanelet::BasicLineString2d & road_border, const std::vector & footprints); + const SegmentRtree & uncrossable_segments); }; } // namespace lane_departure_checker diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index 9d413b2bf0a70..5bd0fcace9909 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -30,7 +30,9 @@ #include #include +using motion_utils::calcArcLength; using tier4_autoware_utils::LinearRing2d; +using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::MultiPoint2d; using tier4_autoware_utils::Point2d; @@ -41,15 +43,6 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; using geometry_msgs::msg::Point; -Point fromVector2dToMsg(const Eigen::Vector2d & point) -{ - Point msg{}; - msg.x = point.x(); - msg.y = point.y(); - msg.z = 0.0; - return msg; -} - double calcBrakingDistance( const double abs_velocity, const double max_deceleration, const double delay_time) { @@ -67,27 +60,6 @@ bool isInAnyLane(const lanelet::ConstLanelets & candidate_lanelets, const Point2 return false; } -bool isCrossingWithBoundary( - const lanelet::BasicLineString2d & boundary, const std::vector & footprints) -{ - for (auto & footprint : footprints) { - for (size_t i = 0; i < footprint.size() - 1; ++i) { - auto footprint1 = footprint.at(i).to_3d(); - auto footprint2 = footprint.at(i + 1).to_3d(); - for (size_t i = 0; i < boundary.size() - 1; ++i) { - auto boundary1 = boundary.at(i); - auto boundary2 = boundary.at(i + 1); - if (tier4_autoware_utils::intersect( - tier4_autoware_utils::toMsg(footprint1), tier4_autoware_utils::toMsg(footprint2), - fromVector2dToMsg(boundary1), fromVector2dToMsg(boundary2))) { - return true; - } - } - } - } - return false; -} - LinearRing2d createHullFromFootprints(const std::vector & footprints) { MultiPoint2d combined; @@ -172,8 +144,12 @@ Output LaneDepartureChecker::update(const Input & input) output.is_out_of_lane = isOutOfLane(output.candidate_lanelets, output.vehicle_footprints.front()); output.processing_time_map["isOutOfLane"] = stop_watch.toc(true); - output.will_cross_boundary = willCrossBoundary( - output.candidate_lanelets, output.vehicle_footprints, input.boundary_types_to_detect); + const double max_search_length_for_boundaries = + calcMaxSearchLengthForBoundaries(*input.predicted_trajectory); + const auto uncrossable_boundaries = extractUncrossableBoundaries( + *input.lanelet_map, input.predicted_trajectory->points.front().pose.position, + max_search_length_for_boundaries, input.boundary_types_to_detect); + output.will_cross_boundary = willCrossBoundary(output.vehicle_footprints, uncrossable_boundaries); output.processing_time_map["willCrossBoundary"] = stop_watch.toc(true); return output; @@ -334,38 +310,58 @@ bool LaneDepartureChecker::isOutOfLane( return false; } -bool LaneDepartureChecker::willCrossBoundary( - const lanelet::ConstLanelets & candidate_lanelets, - const std::vector & vehicle_footprints, - const std::vector & boundary_types_to_detect) +double LaneDepartureChecker::calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const { - for (const auto & candidate_lanelet : candidate_lanelets) { - const std::string r_type = - candidate_lanelet.rightBound().attributeOr(lanelet::AttributeName::Type, "none"); - if ( - std::find(boundary_types_to_detect.begin(), boundary_types_to_detect.end(), r_type) != - boundary_types_to_detect.end()) { - if (isCrossingWithBoundary( - candidate_lanelet.rightBound2d().basicLineString(), vehicle_footprints)) { - // std::cerr << "The crossed road_border's line string id: " - // << candidate_lanelet.rightBound().id() << std::endl; - return true; + const double max_ego_lon_length = std::max( + std::abs(vehicle_info_ptr_->max_longitudinal_offset_m), + std::abs(vehicle_info_ptr_->min_longitudinal_offset_m)); + const double max_ego_lat_length = std::max( + std::abs(vehicle_info_ptr_->max_lateral_offset_m), + std::abs(vehicle_info_ptr_->min_lateral_offset_m)); + const double max_ego_search_length = std::hypot(max_ego_lon_length, max_ego_lat_length); + return calcArcLength(trajectory.points) + max_ego_search_length; +} + +SegmentRtree LaneDepartureChecker::extractUncrossableBoundaries( + const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, + const double max_search_length, const std::vector & boundary_types_to_detect) +{ + const auto has_types = + [](const lanelet::ConstLineString3d & ls, const std::vector & types) { + constexpr auto no_type = ""; + const auto type = ls.attributeOr(lanelet::AttributeName::Type, no_type); + return (type != no_type && std::find(types.begin(), types.end(), type) != types.end()); + }; + + SegmentRtree uncrossable_segments_in_range; + LineString2d line; + const auto ego_p = Point2d{ego_point.x, ego_point.y}; + for (const auto & ls : lanelet_map.lineStringLayer) { + if (has_types(ls, boundary_types_to_detect)) { + line.clear(); + for (const auto & p : ls) line.push_back(Point2d{p.x(), p.y()}); + for (auto segment_idx = 0LU; segment_idx + 1 < line.size(); ++segment_idx) { + const Segment2d segment = {line[segment_idx], line[segment_idx + 1]}; + if (boost::geometry::distance(segment, ego_p) < max_search_length) { + uncrossable_segments_in_range.insert(segment); + } } } - const std::string l_type = - candidate_lanelet.leftBound().attributeOr(lanelet::AttributeName::Type, "none"); - if ( - std::find(boundary_types_to_detect.begin(), boundary_types_to_detect.end(), l_type) != - boundary_types_to_detect.end()) { - if (isCrossingWithBoundary( - candidate_lanelet.leftBound2d().basicLineString(), vehicle_footprints)) { - // std::cerr << "The crossed road_border's line string id: " - // << candidate_lanelet.leftBound().id() << std::endl; - return true; - } + } + return uncrossable_segments_in_range; +} + +bool LaneDepartureChecker::willCrossBoundary( + const std::vector & vehicle_footprints, const SegmentRtree & uncrossable_segments) +{ + for (const auto & footprint : vehicle_footprints) { + std::vector intersection_result; + uncrossable_segments.query( + boost::geometry::index::intersects(footprint), std::back_inserter(intersection_result)); + if (!intersection_result.empty()) { + return true; } } return false; } - } // namespace lane_departure_checker From 8c69bba61a7edf93b91442c2c2a8e75fbe22ff0f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 16 Nov 2023 12:10:23 +0900 Subject: [PATCH 124/223] build(tier4_perception_launch): add tracking_object_merger (#5602) Signed-off-by: kminoda --- launch/tier4_perception_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 336588891d9b2..7e6ba83747a8b 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -39,6 +39,7 @@ shape_estimation tensorrt_yolo topic_tools + tracking_object_merger traffic_light_arbiter traffic_light_classifier traffic_light_fine_detector From db036686f5f76ea9823ea4a4293f6cc25b63c9ef Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 15:15:14 +0900 Subject: [PATCH 125/223] fix(avoidance): fix avoidance exit condition (#5592) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 2d85f8cbe3224..46dfd93d83432 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -222,6 +222,19 @@ bool AvoidanceModule::canTransitSuccessState() const bool has_base_offset = std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold; + // If the vehicle is on the shift line, keep RUNNING. + { + const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); + const auto within = [](const auto & line, const size_t idx) { + return line.start_idx < idx && idx < line.end_idx; + }; + for (const auto & shift_line : path_shifter_.getShiftLines()) { + if (within(shift_line, idx)) { + return false; + } + } + } + // Nothing to do. -> EXIT. if (!has_avoidance_target) { if (!has_shift_point && !has_base_offset) { From cbc54cf5952a90da7cfcf91cac2c64c4fb7b1067 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 15:41:42 +0900 Subject: [PATCH 126/223] fix(avoidance): fix wrong reason for unavoidable situation (#5558) * fix(avoidance): fix wrong reason for unavoidable situation Signed-off-by: satoshi-ota * fix(avoidance): fix misreading variable name Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 46dfd93d83432..54771cc4e66c1 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1010,13 +1010,13 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( desire_shift_length > 0.0 ? feasible_relative_shift_length + current_ego_shift : -1.0 * feasible_relative_shift_length + current_ego_shift; - const auto feasible = + const auto infeasible = std::abs(feasible_shift_length - object.overhang_dist) < 0.5 * planner_data_->parameters.vehicle_width + object_parameter.safety_buffer_lateral; - if (feasible) { + if (infeasible) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 1000, "feasible shift length is not enough to avoid. "); - object.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; return boost::none; } From d808d0458c7c2ce130802ca9a7c891b7b2690f74 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Thu, 16 Nov 2023 15:47:15 +0900 Subject: [PATCH 127/223] refactor(radar_object_clustering): move radar object clustering parameter to param file (#5451) * move radar object clustering parameter to param file Signed-off-by: yoshiri * remove default parameter settings and fix cmakelists --------- Signed-off-by: yoshiri --- ...ar_radar_fusion_based_detection.launch.xml | 5 ++--- .../detection/detection.launch.xml | 2 ++ .../lidar_radar_based_detection.launch.xml | 5 ++--- .../radar_based_detection.launch.xml | 14 ++----------- .../launch/perception.launch.xml | 3 +++ .../radar_object_clustering/CMakeLists.txt | 1 + .../config/radar_object_clustering.param.yaml | 15 ++++++++++++++ .../launch/radar_object_clustering.launch.xml | 20 ++----------------- .../radar_object_clustering_node.cpp | 18 ++++++++--------- 9 files changed, 38 insertions(+), 45 deletions(-) create mode 100644 perception/radar_object_clustering/config/radar_object_clustering.param.yaml diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 20b1b5a4d0b27..1b4c3f38e038d 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -50,6 +50,7 @@ + @@ -78,9 +79,7 @@ - - - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 33994934949ac..b69f1c0ee8b14 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -32,6 +32,7 @@ + @@ -145,6 +146,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml index cee6829ea3b4a..ed37f6270c913 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -11,6 +11,7 @@ + @@ -37,9 +38,7 @@ - - - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml index 5b5646a061ac7..26e7af07646cd 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml @@ -6,10 +6,8 @@ - - - + @@ -43,14 +41,6 @@ - - - - - - - - - + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 8b241db9774b3..fe6636c0f74a0 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -12,6 +12,7 @@ + @@ -175,7 +176,9 @@ + + diff --git a/perception/radar_object_clustering/CMakeLists.txt b/perception/radar_object_clustering/CMakeLists.txt index acb544bfe4f6a..ba911c3035765 100644 --- a/perception/radar_object_clustering/CMakeLists.txt +++ b/perception/radar_object_clustering/CMakeLists.txt @@ -37,4 +37,5 @@ endif() ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/perception/radar_object_clustering/config/radar_object_clustering.param.yaml b/perception/radar_object_clustering/config/radar_object_clustering.param.yaml new file mode 100644 index 0000000000000..2abbf14622a3f --- /dev/null +++ b/perception/radar_object_clustering/config/radar_object_clustering.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # clustering parameter + angle_threshold: 0.174 # [rad] (10 deg) + distance_threshold: 10.0 # [m] + velocity_threshold: 4.0 # [m/s] + + # output object settings + # set false if you want to use the object information from radar + is_fixed_label: true + fixed_label: "CAR" + is_fixed_size: true + size_x: 4.0 # [m] + size_y: 1.5 # [m] + size_z: 1.5 # [m] diff --git a/perception/radar_object_clustering/launch/radar_object_clustering.launch.xml b/perception/radar_object_clustering/launch/radar_object_clustering.launch.xml index e216bec45798a..68fca44bcc723 100644 --- a/perception/radar_object_clustering/launch/radar_object_clustering.launch.xml +++ b/perception/radar_object_clustering/launch/radar_object_clustering.launch.xml @@ -4,28 +4,12 @@ - - - - - - - - - + - - - - - - - - - + diff --git a/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp b/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp index 74e85bde21385..8612fa19ca7f3 100644 --- a/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp +++ b/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp @@ -71,15 +71,15 @@ RadarObjectClusteringNode::RadarObjectClusteringNode(const rclcpp::NodeOptions & std::bind(&RadarObjectClusteringNode::onSetParam, this, std::placeholders::_1)); // Node Parameter - node_param_.angle_threshold = declare_parameter("angle_threshold", 0.174); - node_param_.distance_threshold = declare_parameter("distance_threshold", 4.0); - node_param_.velocity_threshold = declare_parameter("velocity_threshold", 2.0); - node_param_.is_fixed_label = declare_parameter("is_fixed_label", false); - node_param_.fixed_label = declare_parameter("fixed_label", "UNKNOWN"); - node_param_.is_fixed_size = declare_parameter("is_fixed_size", false); - node_param_.size_x = declare_parameter("size_x", 4.0); - node_param_.size_y = declare_parameter("size_y", 1.5); - node_param_.size_z = declare_parameter("size_z", 1.5); + node_param_.angle_threshold = declare_parameter("angle_threshold"); + node_param_.distance_threshold = declare_parameter("distance_threshold"); + node_param_.velocity_threshold = declare_parameter("velocity_threshold"); + node_param_.is_fixed_label = declare_parameter("is_fixed_label"); + node_param_.fixed_label = declare_parameter("fixed_label"); + node_param_.is_fixed_size = declare_parameter("is_fixed_size"); + node_param_.size_x = declare_parameter("size_x"); + node_param_.size_y = declare_parameter("size_y"); + node_param_.size_z = declare_parameter("size_z"); // Subscriber sub_objects_ = create_subscription( From 7b1e139c652917d68a78efce7b8e5f47ed8ecdf6 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Thu, 16 Nov 2023 16:56:30 +0900 Subject: [PATCH 128/223] feat(radar_object_tracker): Change to use `use_radar_tracking_fusion` as true (#5605) Signed-off-by: Shunsuke Miura --- launch/tier4_perception_launch/launch/perception.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index fe6636c0f74a0..6582dfd32d91d 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -104,7 +104,7 @@ From bce08008ac0a59f63753534d63eb6395041e898e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 17:10:37 +0900 Subject: [PATCH 129/223] fix(avoidance): fix bug in shift lon distance calculation (#5557) * fix(avoidance): consider avoidance prepare time Signed-off-by: satoshi-ota * fix(avoidance): consider avoidance prepare distance Signed-off-by: satoshi-ota * fix(avoidance): use std::optional Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../utils/avoidance/helper.hpp | 3 +- .../avoidance/avoidance_module.cpp | 78 ++++++++++--------- 2 files changed, 42 insertions(+), 39 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp index 11388dd6bb74a..b4c6230750946 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp @@ -185,7 +185,8 @@ class AvoidanceHelper max_shift_length, getLateralMinJerkLimit(), getEgoSpeed()); return std::clamp( - 1.5 * dynamic_distance, parameters_->object_check_min_forward_distance, + 1.5 * dynamic_distance + getNominalPrepareDistance(), + parameters_->object_check_min_forward_distance, parameters_->object_check_max_forward_distance); } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 54771cc4e66c1..80baa5230f4f5 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -920,8 +920,9 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( const auto & base_link2rear = planner_data_->parameters.base_link2rear; // Calculate feasible shift length - const auto get_shift_length = - [&](auto & object, const auto & desire_shift_length) -> boost::optional { + const auto get_shift_profile = + [&]( + auto & object, const auto & desire_shift_length) -> std::optional> { // use each object param const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); @@ -931,55 +932,57 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( const auto avoiding_shift = desire_shift_length - current_ego_shift; const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(avoiding_shift); + // calculate remaining distance. + const auto prepare_distance = helper_.getNominalPrepareDistance(); + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; + const auto constant = object_parameter.safety_buffer_longitudinal + + additional_buffer_longitudinal + prepare_distance; + const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance; + const auto remaining_distance = object.longitudinal - constant; + const auto avoidance_distance = + has_enough_distance ? nominal_avoid_distance : remaining_distance; + + // nominal case. avoidable. + if (has_enough_distance) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + if (!isBestEffort(parameters_->policy_lateral_margin)) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } // ego already has enough positive shift. const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3; if (is_object_on_right && has_enough_positive_shift) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } // ego already has enough negative shift. const auto has_enough_negative_shift = avoiding_shift > 1e-3 && desire_shift_length < -1e-3; if (!is_object_on_right && has_enough_negative_shift) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } // don't relax shift length since it can stop in front of the object. if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } - // calculate remaining distance. - const auto prepare_distance = helper_.getNominalPrepareDistance(); - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal - ? planner_data_->parameters.base_link2front - : 0.0; - const auto constant = object_parameter.safety_buffer_longitudinal + - additional_buffer_longitudinal + prepare_distance; - const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance; - const auto remaining_distance = object.longitudinal - constant; - // the avoidance path is already approved const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; const auto is_approved = (helper_.getShift(object_pos) > 0.0 && is_object_on_right) || (helper_.getShift(object_pos) < 0.0 && !is_object_on_right); if (is_approved) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } // prepare distance is not enough. unavoidable. if (remaining_distance < 1e-3) { object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; - return boost::none; - } - - // nominal case. avoidable. - if (has_enough_distance) { - return desire_shift_length; + return std::nullopt; } // calculate lateral jerk. @@ -988,13 +991,13 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( // relax lateral jerk limit. avoidable. if (required_jerk < helper_.getLateralMaxJerkLimit()) { - return desire_shift_length; + return std::make_pair(desire_shift_length, avoidance_distance); } // avoidance distance is not enough. unavoidable. if (!isBestEffort(parameters_->policy_deceleration)) { object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; - return boost::none; + return std::nullopt; } // output avoidance path under lateral jerk constraints. @@ -1003,7 +1006,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) { object.reason = "LessThanExecutionThreshold"; - return boost::none; + return std::nullopt; } const auto feasible_shift_length = @@ -1017,7 +1020,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 1000, "feasible shift length is not enough to avoid. "); object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; - return boost::none; + return std::nullopt; } { @@ -1026,7 +1029,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( std::abs(avoiding_shift), feasible_relative_shift_length); } - return feasible_shift_length; + return std::make_pair(feasible_shift_length, avoidance_distance); }; const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; }; @@ -1061,9 +1064,9 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( // use each object param const auto object_type = utils::getHighestProbLabel(o.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto feasible_shift_length = get_shift_length(o, desire_shift_length); + const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); - if (!feasible_shift_length) { + if (!feasible_shift_profile.has_value()) { if (o.avoid_required && is_forward_object(o)) { break; } else { @@ -1072,10 +1075,8 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( } // use absolute dist for return-to-center, relative dist from current for avoiding. - const auto feasible_avoid_distance = - helper_.getMaxAvoidanceDistance(feasible_shift_length.get() - current_ego_shift); const auto feasible_return_distance = - helper_.getMaxAvoidanceDistance(feasible_shift_length.get()); + helper_.getMaxAvoidanceDistance(feasible_shift_profile.value().first); AvoidLine al_avoid; { @@ -1091,14 +1092,15 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( // start point (use previous linear shift length as start shift length.) al_avoid.start_longitudinal = [&]() { - const auto nearest_avoid_distance = std::max(to_shift_end - feasible_avoid_distance, 1e-3); + const auto nearest_avoid_distance = + std::max(to_shift_end - feasible_shift_profile.value().second, 1e-3); if (data.to_start_point > to_shift_end) { return nearest_avoid_distance; } const auto minimum_avoid_distance = - helper_.getMinAvoidanceDistance(feasible_shift_length.get() - current_ego_shift); + helper_.getMinAvoidanceDistance(feasible_shift_profile.value().first - current_ego_shift); const auto furthest_avoid_distance = std::max(to_shift_end - minimum_avoid_distance, 1e-3); return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance); @@ -1110,7 +1112,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( al_avoid.start_shift_length = helper_.getLinearShift(al_avoid.start.position); // end point - al_avoid.end_shift_length = feasible_shift_length.get(); + al_avoid.end_shift_length = feasible_shift_profile.value().first; al_avoid.end_longitudinal = to_shift_end; // misc @@ -1125,7 +1127,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( const auto to_shift_start = o.longitudinal + offset; // start point - al_return.start_shift_length = feasible_shift_length.get(); + al_return.start_shift_length = feasible_shift_profile.value().first; al_return.start_longitudinal = to_shift_start; // end point From 20345f4e034f1bd330997eaebf8e16e5ab8ff3c4 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 17:11:06 +0900 Subject: [PATCH 130/223] fix(avoidance): prevent sudden steering at avoidance maneuver (#5572) * fix(avoidance): prevent sudden steering at yield maneuver Signed-off-by: satoshi-ota * feat(avoidance): output debug info Signed-off-by: satoshi-ota * Update planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp Co-authored-by: Fumiya Watanabe * style(pre-commit): autofix --------- Signed-off-by: satoshi-ota Co-authored-by: Fumiya Watanabe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/avoidance/avoidance.param.yaml | 3 ++- .../utils/avoidance/avoidance_module_data.hpp | 3 ++- .../utils/avoidance/helper.hpp | 8 +++++- .../avoidance/avoidance_module.cpp | 26 ++++++++++++++++--- .../src/scene_module/avoidance/manager.cpp | 6 +++-- 5 files changed, 38 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 96b6ca452bbcc..ad06a1a9f6a10 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -190,7 +190,8 @@ max_deviation_from_lane: 0.5 # [m] # avoidance distance parameters longitudinal: - prepare_time: 2.0 # [s] + min_prepare_time: 1.0 # [s] + max_prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index c8b87c7b4759f..60cf9b1244236 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -211,7 +211,8 @@ struct AvoidanceParameters double stop_buffer{0.0}; // start avoidance after this time to avoid sudden path change - double prepare_time{0.0}; + double min_prepare_time{0.0}; + double max_prepare_time{0.0}; // Even if the vehicle speed is zero, avoidance will start after a distance of this much. double min_prepare_distance{0.0}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp index b4c6230750946..e1d51122e5c1b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp @@ -91,10 +91,16 @@ class AvoidanceHelper return std::max(getEgoSpeed(), values.at(idx)); } + double getMinimumPrepareDistance() const + { + const auto & p = parameters_; + return std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); + } + double getNominalPrepareDistance() const { const auto & p = parameters_; - return std::max(getEgoSpeed() * p->prepare_time, p->min_prepare_distance); + return std::max(getEgoSpeed() * p->max_prepare_time, p->min_prepare_distance); } double getNominalAvoidanceDistance(const double shift_length) const diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 80baa5230f4f5..ea4eab425b66b 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -437,10 +437,27 @@ bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const { // transit yield maneuver only when the avoidance maneuver is not initiated. if (helper_.isShifted()) { + RCLCPP_DEBUG(getLogger(), "avoidance maneuver already initiated."); return false; } + // prevent sudden steering. + const auto registered_lines = path_shifter_.getShiftLines(); + if (!registered_lines.empty()) { + const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); + const auto to_shift_start_point = calcSignedArcLength( + path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx); + if (to_shift_start_point < helper_.getMinimumPrepareDistance()) { + RCLCPP_DEBUG( + getLogger(), + "Distance to shift start point is less than minimum prepare distance. The distance is not " + "enough."); + return false; + } + } + if (!data.stop_target_object) { + RCLCPP_DEBUG(getLogger(), "can pass by the object safely without avoidance maneuver."); return true; } @@ -1654,6 +1671,10 @@ void AvoidanceModule::applySmallShiftFilter( continue; } + if (s.start_longitudinal < helper_.getMinimumPrepareDistance()) { + continue; + } + shift_lines.push_back(s); } } @@ -2407,9 +2428,8 @@ AvoidLineArray AvoidanceModule::findNewShiftLine( for (size_t i = 0; i < shift_lines.size(); ++i) { const auto & candidate = shift_lines.at(i); - // new shift points must exist in front of Ego - // this value should be larger than -eps consider path shifter calculation error. - if (candidate.start_idx < avoid_data_.ego_closest_path_index) { + // prevent sudden steering. + if (candidate.start_longitudinal < helper_.getMinimumPrepareDistance()) { break; } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index 6ed67fc817f28..f71024dcc5034 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -221,7 +221,8 @@ AvoidanceModuleManager::AvoidanceModuleManager( // avoidance maneuver (longitudinal) { std::string ns = "avoidance.avoidance.longitudinal."; - p.prepare_time = getOrDeclareParameter(*node, ns + "prepare_time"); + p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); + p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); @@ -390,7 +391,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "prepare_time", p->prepare_time); + updateParam(parameters, ns + "min_prepare_time", p->min_prepare_time); + updateParam(parameters, ns + "max_prepare_time", p->max_prepare_time); updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); } From 8753183f42d78b3a8e86c6c2a137478a07546266 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 16 Nov 2023 18:06:09 +0900 Subject: [PATCH 131/223] feat(out_of_lane): more stable decisions (#5197) Signed-off-by: Maxime CLEMENT --- .../config/out_of_lane.param.yaml | 2 + .../src/calculate_slowdown_points.hpp | 35 ++++++-- .../src/debug.cpp | 87 ++++++++++++++++++- .../src/debug.hpp | 20 ++++- .../src/decisions.cpp | 36 +++----- .../src/decisions.hpp | 22 +---- .../src/manager.cpp | 2 + .../src/overlapping_range.cpp | 11 ++- .../src/overlapping_range.hpp | 10 --- .../src/scene_out_of_lane.cpp | 59 ++++++++++--- .../src/scene_out_of_lane.hpp | 7 +- .../src/types.hpp | 73 +++++++++++++--- 12 files changed, 273 insertions(+), 91 deletions(-) diff --git a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml index c74c5b3d87c1d..092f1d32b27b3 100644 --- a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -17,6 +17,7 @@ use_predicted_paths: true # if true, use the predicted paths to estimate future positions. # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. + distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered @@ -26,6 +27,7 @@ skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed precision: 0.1 # [m] precision when inserting a stop pose in the path distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane + min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled slowdown: distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap velocity: 2.0 # [m/s] slowdown velocity diff --git a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 5d22f01222919..0c9e6448bb374 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -29,6 +29,11 @@ namespace behavior_velocity_planner::out_of_lane { +/// @brief estimate whether ego can decelerate without breaking the deceleration limit +/// @details assume ego wants to reach the target point at the target velocity +/// @param [in] ego_data ego data +/// @param [in] point target point +/// @param [in] target_vel target_velocity bool can_decelerate( const EgoData & ego_data, const PathPointWithLaneId & point, const double target_vel) { @@ -40,9 +45,16 @@ bool can_decelerate( return acc_to_target_vel < std::abs(ego_data.max_decel); } +/// @brief calculate the last pose along the path where ego does not overlap the lane to avoid +/// @param [in] ego_data ego data +/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) +/// @param [in] footprint the ego footprint +/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits +/// @param [in] params parameters +/// @return the last pose that is not out of lane (if found) std::optional calculate_last_in_lane_pose( const EgoData & ego_data, const Slowdown & decision, const Polygon2d & footprint, - const PlannerParam & params) + const std::optional & prev_slowdown_point, const PlannerParam & params) { const auto from_arc_length = motion_utils::calcSignedArcLength(ego_data.path.points, 0, ego_data.first_path_idx); @@ -53,12 +65,17 @@ std::optional calculate_last_in_lane_pose( // TODO(Maxime): binary search interpolated_point.point.pose = motion_utils::calcInterpolatedPose(ego_data.path.points, l); const auto respect_decel_limit = - !params.skip_if_over_max_decel || + !params.skip_if_over_max_decel || prev_slowdown_point || can_decelerate(ego_data, interpolated_point, decision.velocity); - if ( - respect_decel_limit && !boost::geometry::overlaps( - project_to_pose(footprint, interpolated_point.point.pose), - decision.lane_to_avoid.polygon2d().basicPolygon())) + const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.point.pose); + const auto is_overlap_lane = boost::geometry::overlaps( + interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); + const auto is_overlap_extra_lane = + prev_slowdown_point && + boost::geometry::overlaps( + interpolated_footprint, + prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); + if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) return interpolated_point; } return std::nullopt; @@ -67,10 +84,12 @@ std::optional calculate_last_in_lane_pose( /// @brief calculate the slowdown point to insert in the path /// @param ego_data ego data (path, velocity, etc) /// @param decisions decision (before which point to stop, what lane to avoid entering, etc) +/// @param prev_slowdown_point previously calculated slowdown point /// @param params parameters /// @return optional slowdown point to insert in the path std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, PlannerParam params) + const EgoData & ego_data, const std::vector & decisions, + const std::optional prev_slowdown_point, PlannerParam params) { params.extra_front_offset += params.dist_buffer; const auto base_footprint = make_base_footprint(params); @@ -78,7 +97,7 @@ std::optional calculate_slowdown_point( // search for the first slowdown decision for which a stop point can be inserted for (const auto & decision : decisions) { const auto last_in_lane_pose = - calculate_last_in_lane_pose(ego_data, decision, base_footprint, params); + calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; } return std::nullopt; diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp b/planning/behavior_velocity_out_of_lane_module/src/debug.cpp index 0574a5226dc4a..489bb3f5abc78 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/debug.cpp @@ -34,13 +34,12 @@ visualization_msgs::msg::Marker get_base_marker() base_marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); base_marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); base_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); - base_marker.lifetime = rclcpp::Duration::from_seconds(0.5); return base_marker; } } // namespace void add_footprint_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z) + const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) { auto debug_marker = get_base_marker(); debug_marker.ns = "footprints"; @@ -54,12 +53,14 @@ void add_footprint_markers( debug_marker.id++; debug_marker.points.clear(); } + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); } void add_current_overlap_marker( visualization_msgs::msg::MarkerArray & debug_marker_array, const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z) + const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) { auto debug_marker = get_base_marker(); debug_marker.ns = "current_overlap"; @@ -82,12 +83,14 @@ void add_current_overlap_marker( debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; } + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); } void add_lanelet_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color) + const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) { auto debug_marker = get_base_marker(); debug_marker.ns = ns; @@ -103,6 +106,82 @@ void add_lanelet_markers( debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; } + debug_marker.action = debug_marker.DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); +} + +void add_range_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t first_ego_idx, + const double z, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.ns = "ranges"; + debug_marker.color = tier4_autoware_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); + for (const auto & range : ranges) { + debug_marker.points.clear(); + debug_marker.points.push_back( + path.points[first_ego_idx + range.entering_path_idx].point.pose.position); + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.entering_point.x(), range.entering_point.y(), z)); + for (const auto & overlap : range.debug.overlaps) { + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); + } + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.exiting_point.x(), range.exiting_point.y(), z)); + debug_marker.points.push_back( + path.points[first_ego_idx + range.exiting_path_idx].point.pose.position); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + debug_marker.action = debug_marker.DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); + debug_marker.action = debug_marker.ADD; + debug_marker.id = 0; + debug_marker.ns = "decisions"; + debug_marker.color = tier4_autoware_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); + debug_marker.points.clear(); + for (const auto & range : ranges) { + debug_marker.type = debug_marker.LINE_STRIP; + if (range.debug.decision) { + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.entering_point.x(), range.entering_point.y(), z)); + debug_marker.points.push_back( + range.debug.object->kinematics.initial_pose_with_covariance.pose.position); + } + debug_marker_array.markers.push_back(debug_marker); + debug_marker.points.clear(); + debug_marker.id++; + + debug_marker.type = debug_marker.TEXT_VIEW_FACING; + debug_marker.pose.position.x = range.entering_point.x(); + debug_marker.pose.position.y = range.entering_point.y(); + debug_marker.pose.position.z = z; + std::stringstream ss; + ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time + << "\n"; + if (range.debug.object) { + debug_marker.pose.position.x += + range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; + debug_marker.pose.position.y += + range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; + debug_marker.pose.position.x /= 2; + debug_marker.pose.position.y /= 2; + ss << "Obj: " << range.debug.times.object.enter_time << " - " + << range.debug.times.object.exit_time << "\n"; + } + debug_marker.scale.z = 1.0; + debug_marker.text = ss.str(); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); } } // namespace behavior_velocity_planner::out_of_lane::debug diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp b/planning/behavior_velocity_out_of_lane_module/src/debug.hpp index 06bc6d935f310..2b6b65638ec40 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/debug.hpp @@ -29,27 +29,41 @@ namespace behavior_velocity_planner::out_of_lane::debug /// @param [inout] debug_marker_array marker array /// @param [in] footprints footprints to turn into markers /// @param [in] z z value to use for the markers +/// @param [in] prev_nb previous number of markers (used to delete the extra ones) void add_footprint_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z); + const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb); /// @brief add footprint markers to the given marker array /// @param [inout] debug_marker_array marker array /// @param [in] current_footprint footprint to turn into a marker /// @param [in] current_overlapped_lanelets lanelets to turn into markers /// @param [in] z z value to use for the markers +/// @param [in] prev_nb previous number of markers (used to delete the extra ones) void add_current_overlap_marker( visualization_msgs::msg::MarkerArray & debug_marker_array, const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z); + const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb); /// @brief add footprint markers to the given marker array /// @param [inout] debug_marker_array marker array /// @param [in] lanelets lanelets to turn into markers /// @param [in] ns namespace of the markers /// @param [in] color namespace of the markers +/// @param [in] prev_nb previous number of markers (used to delete the extra ones) void add_lanelet_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color); + const std_msgs::msg::ColorRGBA & color, const size_t prev_nb); +/// @brief add ranges markers to the given marker array +/// @param [inout] debug_marker_array marker array +/// @param [in] ranges ranges to turn into markers +/// @param [in] path modified ego path that was used to calculate the ranges +/// @param [in] first_path_idx first idx of ego on the path +/// @param [in] z z value to use for the markers +/// @param [in] prev_nb previous number of markers (used to delete the extra ones) +void add_range_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t first_path_idx, + const double z, const size_t prev_nb); } // namespace behavior_velocity_planner::out_of_lane::debug #endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp index 78d9b73c86a17..be72109db4548 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp @@ -26,7 +26,6 @@ #include #include -#include #include #include #include @@ -63,7 +62,8 @@ bool object_is_incoming( std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const rclcpp::Logger & logger) + const std::shared_ptr route_handler, const double dist_buffer, + const rclcpp::Logger & logger) { // skip the dynamic object if it is not in a lane preceding the overlapped lane // lane changes are intentionally not considered @@ -72,8 +72,7 @@ std::optional> object_time_to_range( object.kinematics.initial_pose_with_covariance.pose.position.y); if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; - const auto max_deviation = object.shape.dimensions.y + range.inside_distance; - + const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; auto worst_enter_time = std::optional(); auto worst_exit_time = std::optional(); @@ -308,7 +307,8 @@ bool should_not_enter( // skip objects that are already on the interval const auto enter_exit_time = params.objects_use_predicted_paths - ? object_time_to_range(object, range, inputs.route_handler, logger) + ? object_time_to_range( + object, range, inputs.route_handler, params.objects_dist_buffer, logger) : object_time_to_range(object, range, inputs, logger); if (!enter_exit_time) { RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); @@ -317,27 +317,14 @@ bool should_not_enter( range_times.object.enter_time = enter_exit_time->first; range_times.object.exit_time = enter_exit_time->second; - if (will_collide_on_range(range_times, params, logger)) return true; - } - return false; -} - -OverlapRange find_most_preceding_range(const OverlapRange & range, const DecisionInputs & inputs) -{ - OverlapRange preceding_range = range; - bool found_preceding_range = true; - while (found_preceding_range) { - found_preceding_range = false; - for (const auto & other_range : inputs.ranges) { - if ( - other_range.entering_path_idx < preceding_range.entering_path_idx && - other_range.exiting_path_idx >= preceding_range.entering_path_idx) { - preceding_range = other_range; - found_preceding_range = true; - } + if (will_collide_on_range(range_times, params, logger)) { + range.debug.times = range_times; + range.debug.object = object; + return true; } } - return preceding_range; + range.debug.times = range_times; + return false; } void set_decision_velocity( @@ -375,6 +362,7 @@ std::vector calculate_decisions( for (const auto & range : inputs.ranges) { if (range.entering_path_idx == 0UL) continue; // skip if we already entered the range const auto optional_decision = calculate_decision(range, inputs, params, logger); + range.debug.decision = optional_decision; if (optional_decision) decisions.push_back(*optional_decision); } return decisions; diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp index 2898595c2e74c..0612cc041c1ef 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp @@ -31,16 +31,6 @@ namespace behavior_velocity_planner::out_of_lane { -struct EnterExitTimes -{ - double enter_time; - double exit_time; -}; -struct RangeTimes -{ - EnterExitTimes ego; - EnterExitTimes object; -}; /// @brief calculate the distance along the ego path between ego and some target path index /// @param [in] ego_data data related to the ego vehicle /// @param [in] target_idx target ego path index @@ -64,13 +54,15 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx); /// the opposite direction, time at enter > time at exit std::optional> object_time_to_range( const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const rclcpp::Logger & logger); + const std::shared_ptr route_handler, const double dist_buffer, + const rclcpp::Logger & logger); /// @brief use the lanelet map to estimate the times when an object will reach the enter and exit /// points of an overlapping range /// @param [in] object dynamic object /// @param [in] range overlapping range /// @param [in] inputs information used to take decisions (ranges, ego and objects data, route /// handler, lanelets) +/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range /// @param [in] logger ros logger /// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in /// the opposite direction, time at enter > time at exit. @@ -94,14 +86,6 @@ bool will_collide_on_range( bool should_not_enter( const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -/// @brief find the most preceding range -/// @details the most preceding range is the first range in a succession of ranges with overlapping -/// enter/exit indexes. -/// @param [in] range range -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @return most preceding range -OverlapRange find_most_preceding_range(const OverlapRange & range, const DecisionInputs & inputs); /// @brief set the velocity of a decision (or unset it) based on the distance away from the range /// @param [out] decision decision to update (either set its velocity or unset the decision) /// @param [in] distance distance between ego and the range corresponding to the decision diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp index 2422c6fe84e56..23de809e429ec 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp @@ -50,6 +50,7 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".objects.use_predicted_paths"); pp.objects_min_confidence = getOrDeclareParameter(node, ns + ".objects.predicted_path_min_confidence"); + pp.objects_dist_buffer = getOrDeclareParameter(node, ns + ".objects.distance_buffer"); pp.overlap_min_dist = getOrDeclareParameter(node, ns + ".overlap.minimum_distance"); pp.overlap_extra_length = getOrDeclareParameter(node, ns + ".overlap.extra_length"); @@ -57,6 +58,7 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node) pp.skip_if_over_max_decel = getOrDeclareParameter(node, ns + ".action.skip_if_over_max_decel"); pp.precision = getOrDeclareParameter(node, ns + ".action.precision"); + pp.min_decision_duration = getOrDeclareParameter(node, ns + ".action.min_duration"); pp.dist_buffer = getOrDeclareParameter(node, ns + ".action.distance_buffer"); pp.slow_velocity = getOrDeclareParameter(node, ns + ".action.slowdown.velocity"); pp.slow_dist_threshold = diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp index 98a9e4404e013..6f74f42af2056 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp @@ -23,7 +23,6 @@ #include #include -#include namespace behavior_velocity_planner::out_of_lane { @@ -76,10 +75,12 @@ OverlapRanges calculate_overlapping_ranges( { OverlapRanges ranges; OtherLane other_lane(lanelet); + std::vector overlaps; for (auto i = 0UL; i < path_footprints.size(); ++i) { const auto overlap = calculate_overlap(path_footprints[i], path_lanelets, lanelet); const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; if (has_overlap) { // open/update the range + overlaps.push_back(overlap); if (!other_lane.range_is_open) { other_lane.first_range_bound.index = i; other_lane.first_range_bound.point = overlap.min_overlap_point; @@ -94,10 +95,16 @@ OverlapRanges calculate_overlapping_ranges( other_lane.last_range_bound.inside_distance = overlap.inside_distance; } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open ranges.push_back(other_lane.close_range()); + ranges.back().debug.overlaps = overlaps; + overlaps.clear(); } } // close the range if it is still open - if (other_lane.range_is_open) ranges.push_back(other_lane.close_range()); + if (other_lane.range_is_open) { + ranges.push_back(other_lane.close_range()); + ranges.back().debug.overlaps = overlaps; + overlaps.clear(); + } return ranges; } diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp index ab4d31480e1cb..24bd6b3f16eb9 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp @@ -21,21 +21,11 @@ #include -#include #include namespace behavior_velocity_planner::out_of_lane { -/// @brief representation of an overlap between the ego footprint and some other lane -struct Overlap -{ - double inside_distance = 0.0; ///!< distance inside the overlap - double min_arc_length = std::numeric_limits::infinity(); - double max_arc_length = 0.0; - lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length - lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length -}; /// @brief calculate the overlap between the given footprint and lanelet /// @param [in] path_footprint footprint used to calculate the overlap /// @param [in] path_lanelets path lanelets used to calculate arc length along the ego path diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp index 1487d9e63c8b0..539cdefb31fdf 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp @@ -55,8 +55,7 @@ OutOfLaneModule::OutOfLaneModule( velocity_factor_.init(VelocityFactor::UNKNOWN); } -bool OutOfLaneModule::modifyPathVelocity( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) { debug_data_.reset_data(); *stop_reason = planning_utils::initializeStopReason(StopReason::OUT_OF_LANE); @@ -68,6 +67,19 @@ bool OutOfLaneModule::modifyPathVelocity( ego_data.path.points = path->points; ego_data.first_path_idx = motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position); + for (const auto & p : prev_overlapping_path_points_) { + const auto nearest_idx = + motion_utils::findNearestIndex(ego_data.path.points, p.point.pose, 1.0); + const auto insert_idx = + motion_utils::findNearestSegmentIndex(ego_data.path.points, p.point.pose, 1.0); + if (nearest_idx && insert_idx && *insert_idx > ego_data.first_path_idx) { + if ( + tier4_autoware_utils::calcDistance2d( + ego_data.path.points[*nearest_idx].point.pose, p.point.pose) > 0.5) + ego_data.path.points.insert(std::next(ego_data.path.points.begin(), *insert_idx), p); + } + } + motion_utils::removeOverlapPoints(ego_data.path.points); ego_data.velocity = planner_data_->current_velocity->twist.linear.x; ego_data.max_decel = -planner_data_->max_stop_acceleration_threshold; stopwatch.tic("calculate_path_footprints"); @@ -87,6 +99,8 @@ bool OutOfLaneModule::modifyPathVelocity( debug_data_.path_lanelets = path_lanelets; debug_data_.ignored_lanelets = ignored_lanelets; debug_data_.other_lanelets = other_lanelets; + debug_data_.path = ego_data.path; + debug_data_.first_path_idx = ego_data.first_path_idx; if (params_.skip_if_already_overlapping) { debug_data_.current_footprint = current_ego_footprint; @@ -104,6 +118,10 @@ bool OutOfLaneModule::modifyPathVelocity( stopwatch.tic("calculate_overlapping_ranges"); const auto ranges = calculate_overlapping_ranges(path_footprints, path_lanelets, other_lanelets, params_); + prev_overlapping_path_points_.clear(); + for (const auto & range : ranges) + prev_overlapping_path_points_.push_back( + ego_data.path.points[ego_data.first_path_idx + range.entering_path_idx]); const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); // Calculate stop and slowdown points stopwatch.tic("calculate_decisions"); @@ -113,14 +131,27 @@ bool OutOfLaneModule::modifyPathVelocity( inputs.objects = filter_predicted_objects(*planner_data_->predicted_objects, ego_data, params_); inputs.route_handler = planner_data_->route_handler_; inputs.lanelets = other_lanelets; - auto decisions = calculate_decisions(inputs, params_, logger_); + const auto decisions = calculate_decisions(inputs, params_, logger_); const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); stopwatch.tic("calc_slowdown_points"); - const auto point_to_insert = calculate_slowdown_point(ego_data, decisions, params_); + if ( // reset the previous inserted point if the timer expired + prev_inserted_point_ && + (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) + prev_inserted_point_.reset(); + auto point_to_insert = + calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); stopwatch.tic("insert_slowdown_points"); debug_data_.slowdowns.clear(); + if ( // reset the timer if there is no previous inserted point or if we avoid the same lane + point_to_insert && + (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == + point_to_insert->slowdown.lane_to_avoid.id())) + prev_inserted_point_time_ = clock_->now(); + if (!point_to_insert && prev_inserted_point_) point_to_insert = prev_inserted_point_; if (point_to_insert) { + prev_inserted_point_ = point_to_insert; + RCLCPP_INFO(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); debug_data_.slowdowns = {*point_to_insert}; auto path_idx = motion_utils::findNearestSegmentIndex( path->points, point_to_insert->point.point.pose.position) + @@ -132,14 +163,17 @@ bool OutOfLaneModule::modifyPathVelocity( tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = point_to_insert->point.point.pose; stop_factor.dist_to_stop_pose = motion_utils::calcSignedArcLength( - ego_data.path.points, ego_data.pose.position, point_to_insert->point.point.pose.position); + path->points, ego_data.pose.position, point_to_insert->point.point.pose.position); planning_utils::appendStopReason(stop_factor, stop_reason); } velocity_factor_.set( path->points, planner_data_->current_odometry->pose, point_to_insert->point.point.pose, VelocityFactor::UNKNOWN); + } else if (!decisions.empty()) { + RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); } const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); + debug_data_.ranges = inputs.ranges; const auto total_time_us = stopwatch.toc(); RCLCPP_DEBUG( @@ -160,18 +194,23 @@ MarkerArray OutOfLaneModule::createDebugMarkerArray() constexpr auto z = 0.0; MarkerArray debug_marker_array; - debug::add_footprint_markers(debug_marker_array, debug_data_.footprints, z); + debug::add_footprint_markers( + debug_marker_array, debug_data_.footprints, z, debug_data_.prev_footprints); debug::add_current_overlap_marker( - debug_marker_array, debug_data_.current_footprint, debug_data_.current_overlapped_lanelets, z); + debug_marker_array, debug_data_.current_footprint, debug_data_.current_overlapped_lanelets, z, + debug_data_.prev_current_overlapped_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data_.path_lanelets, "path_lanelets", - tier4_autoware_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5)); + tier4_autoware_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), debug_data_.prev_path_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data_.ignored_lanelets, "ignored_lanelets", - tier4_autoware_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5)); + tier4_autoware_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), debug_data_.prev_ignored_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data_.other_lanelets, "other_lanelets", - tier4_autoware_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5)); + tier4_autoware_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), debug_data_.prev_other_lanelets); + debug::add_range_markers( + debug_marker_array, debug_data_.ranges, debug_data_.path, debug_data_.first_path_idx, z, + debug_data_.prev_ranges); return debug_marker_array; } diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp index cdf8eef8f277b..310e2a9764d36 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -48,9 +49,13 @@ class OutOfLaneModule : public SceneModuleInterface motion_utils::VirtualWalls createVirtualWalls() override; private: - // Parameter PlannerParam params_; + std::vector + prev_overlapping_path_points_{}; + std::optional prev_inserted_point_{}; + rclcpp::Time prev_inserted_point_time_{}; + protected: int64_t module_id_{}; diff --git a/planning/behavior_velocity_out_of_lane_module/src/types.hpp b/planning/behavior_velocity_out_of_lane_module/src/types.hpp index 64d88f15e6966..34bd52634ce7b 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/types.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/types.hpp @@ -24,7 +24,9 @@ #include #include +#include #include +#include #include #include #include @@ -47,6 +49,8 @@ struct PlannerParam bool objects_use_predicted_paths; // whether to use the objects' predicted paths double objects_min_vel; // [m/s] objects lower than this velocity will be ignored double objects_min_confidence; // minimum confidence to consider a predicted path + double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in + // the other lane double overlap_extra_length; // [m] extra length to add around an overlap range double overlap_min_dist; // [m] min distance inside another lane to consider an overlap @@ -56,7 +60,8 @@ struct PlannerParam double slow_velocity; double slow_dist_threshold; double stop_dist_threshold; - double precision; // [m] precision when inserting a stop pose in the path + double precision; // [m] precision when inserting a stop pose in the path + double min_decision_duration; // [s] minimum duration needed a decision can be canceled // ego dimensions used to create its polygon footprint double front_offset; // [m] front offset (from vehicle info) double rear_offset; // [m] rear offset (from vehicle info) @@ -68,17 +73,16 @@ struct PlannerParam double extra_left_offset; // [m] extra left distance }; -/// @brief range along the path where ego overlaps another lane -struct OverlapRange +struct EnterExitTimes { - lanelet::ConstLanelet lane; - size_t entering_path_idx{}; - size_t exiting_path_idx{}; - lanelet::BasicPoint2d entering_point; // pose of the overlapping point closest along the lane - lanelet::BasicPoint2d exiting_point; // pose of the overlapping point furthest along the lane - double inside_distance{}; // [m] how much ego footprint enters the lane + double enter_time{}; + double exit_time{}; +}; +struct RangeTimes +{ + EnterExitTimes ego{}; + EnterExitTimes object{}; }; -using OverlapRanges = std::vector; /// @brief action taken by the "out of lane" module struct Slowdown @@ -102,6 +106,35 @@ struct RangeBound double arc_length; double inside_distance; }; + +/// @brief representation of an overlap between the ego footprint and some other lane +struct Overlap +{ + double inside_distance = 0.0; ///!< distance inside the overlap + double min_arc_length = std::numeric_limits::infinity(); + double max_arc_length = 0.0; + lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length + lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length +}; + +/// @brief range along the path where ego overlaps another lane +struct OverlapRange +{ + lanelet::ConstLanelet lane; + size_t entering_path_idx{}; + size_t exiting_path_idx{}; + lanelet::BasicPoint2d entering_point; // pose of the overlapping point closest along the lane + lanelet::BasicPoint2d exiting_point; // pose of the overlapping point furthest along the lane + double inside_distance{}; // [m] how much ego footprint enters the lane + mutable struct + { + std::vector overlaps; + std::optional decision; + RangeTimes times; + std::optional object{}; + } debug; +}; +using OverlapRanges = std::vector; /// @brief representation of a lane and its current overlap range struct OtherLane { @@ -164,12 +197,32 @@ struct DebugData lanelet::ConstLanelets path_lanelets; lanelet::ConstLanelets ignored_lanelets; lanelet::ConstLanelets other_lanelets; + autoware_auto_planning_msgs::msg::PathWithLaneId path; + size_t first_path_idx; + + size_t prev_footprints = 0; + size_t prev_slowdowns = 0; + size_t prev_ranges = 0; + size_t prev_current_overlapped_lanelets = 0; + size_t prev_ignored_lanelets = 0; + size_t prev_path_lanelets = 0; + size_t prev_other_lanelets = 0; void reset_data() { + prev_footprints = footprints.size(); footprints.clear(); + prev_slowdowns = slowdowns.size(); slowdowns.clear(); + prev_ranges = ranges.size(); ranges.clear(); + prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); current_overlapped_lanelets.clear(); + prev_ignored_lanelets = ignored_lanelets.size(); + ignored_lanelets.clear(); + prev_path_lanelets = path_lanelets.size(); + path_lanelets.clear(); + prev_other_lanelets = other_lanelets.size(); + other_lanelets.clear(); } }; From 1b5ef956d8622f69f8dafbf97fc2d993f20472f9 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 21:49:50 +0900 Subject: [PATCH 132/223] refactor(goal_planner): add prev_data instead of status (#5561) --- .../goal_planner/goal_planner_module.hpp | 79 ++++------------ .../goal_planner/goal_planner_module.cpp | 94 +++++++++---------- 2 files changed, 64 insertions(+), 109 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index d647caeabbc44..a31442def538f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -68,64 +68,6 @@ using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using tier4_autoware_utils::Polygon2d; -#define DEFINE_SETTER(TYPE, NAME) \ -public: \ - void set_##NAME(const TYPE & value) \ - { \ - NAME##_ = value; \ - } - -#define DEFINE_GETTER(TYPE, NAME) \ -public: \ - TYPE get_##NAME() const \ - { \ - return NAME##_; \ - } - -#define DEFINE_SETTER_GETTER(TYPE, NAME) \ - DEFINE_SETTER(TYPE, NAME) \ - DEFINE_GETTER(TYPE, NAME) - -class PullOverStatus -{ -public: - // Reset all data members to their initial states - void reset() - { - lane_parking_pull_over_path_ = nullptr; - prev_stop_path_ = nullptr; - prev_stop_path_after_approval_ = nullptr; - - is_safe_ = false; - prev_found_path_ = false; - prev_is_safe_ = false; - } - - DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) - DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path) - DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path_after_approval) - DEFINE_SETTER_GETTER(bool, is_safe) - DEFINE_SETTER_GETTER(bool, prev_found_path) - DEFINE_SETTER_GETTER(bool, prev_is_safe) - DEFINE_SETTER_GETTER(Pose, refined_goal_pose) - DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) - -private: - std::shared_ptr lane_parking_pull_over_path_{nullptr}; - std::shared_ptr prev_stop_path_{nullptr}; - std::shared_ptr prev_stop_path_after_approval_{nullptr}; - bool is_safe_{false}; - bool prev_found_path_{false}; - bool prev_is_safe_{false}; - - Pose refined_goal_pose_{}; - Pose closest_goal_candidate_pose_{}; -}; - -#undef DEFINE_SETTER -#undef DEFINE_GETTER -#undef DEFINE_SETTER_GETTER - #define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ public: \ void set_##NAME(const TYPE & value) \ @@ -288,6 +230,22 @@ struct LastApprovalData Pose pose{}; }; +struct PreviousPullOverData +{ + void reset() + { + stop_path = nullptr; + stop_path_after_approval = nullptr; + found_path = false; + is_safe = false; + } + + std::shared_ptr stop_path{nullptr}; + std::shared_ptr stop_path_after_approval{nullptr}; + bool found_path{false}; + bool is_safe{false}; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -380,10 +338,10 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; - PullOverStatus status_; ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; + PreviousPullOverData prev_data_{nullptr}; // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. @@ -412,7 +370,7 @@ class GoalPlannerModule : public SceneModuleInterface // goal seach Pose calcRefinedGoal(const Pose & goal_pose) const; - void generateGoalCandidates(); + GoalCandidates generateGoalCandidates() const; // stop or decelerate void deceleratePath(PullOverPath & pull_over_path) const; @@ -470,6 +428,7 @@ class GoalPlannerModule : public SceneModuleInterface // output setter void setOutput(BehaviorModuleOutput & output) const; void setStopPath(BehaviorModuleOutput & output) const; + void updatePreviousData(const BehaviorModuleOutput & output); /** * @brief Sets a stop path in the current path based on safety conditions and previous paths. diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index ba846efbb0a50..509214d37cd5a 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -121,7 +121,7 @@ GoalPlannerModule::GoalPlannerModule( goal_planner_data_.collision_check); } - status_.reset(); + prev_data_.reset(); } // This function is needed for waiting for planner_data_ @@ -240,7 +240,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() void GoalPlannerModule::updateData() { - if (getCurrentStatus() == ModuleStatus::IDLE) { + if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; } @@ -259,11 +259,14 @@ void GoalPlannerModule::updateData() updateOccupancyGrid(); - generateGoalCandidates(); + // update goal searcher and generate goal candidates + if (thread_safe_data_.get_goal_candidates().empty()) { + goal_searcher_->setPlannerData(planner_data_); + goal_searcher_->setReferenceGoal( + calcRefinedGoal(planner_data_->route_handler->getOriginalGoalPose())); + thread_safe_data_.set_goal_candidates(generateGoalCandidates()); + } - // Only after the path is decided, approval is allowed and the module is Activated. - // The path index is not incremented until after deciding the path. - // So return here, if (!isActivated()) { return; } @@ -308,7 +311,7 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); - status_.reset(); + prev_data_.reset(); last_approval_data_.reset(); } @@ -545,33 +548,24 @@ bool GoalPlannerModule::canReturnToLaneParking() return true; } -void GoalPlannerModule::generateGoalCandidates() +GoalCandidates GoalPlannerModule::generateGoalCandidates() const { - if (!thread_safe_data_.get_goal_candidates().empty()) { - return; - } - // calculate goal candidates const auto & route_handler = planner_data_->route_handler; - const Pose goal_pose = route_handler->getOriginalGoalPose(); - status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { - const std::lock_guard lock(mutex_); - goal_searcher_->setPlannerData(planner_data_); - goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); - thread_safe_data_.set_goal_candidates(goal_searcher_->search()); - status_.set_closest_goal_candidate_pose( - goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()) - .goal_pose); - } else { - GoalCandidate goal_candidate{}; - goal_candidate.goal_pose = goal_pose; - goal_candidate.distance_from_original_goal = 0.0; - GoalCandidates goal_candidates{}; - goal_candidates.push_back(goal_candidate); - thread_safe_data_.set_goal_candidates(goal_candidates); - status_.set_closest_goal_candidate_pose(goal_pose); + return goal_searcher_->search(); } + + // NOTE: + // currently since pull over is performed only when isAllowedGoalModification is true, + // never be in the following process. + GoalCandidate goal_candidate{}; + goal_candidate.goal_pose = route_handler->getOriginalGoalPose(); + goal_candidate.distance_from_original_goal = 0.0; + GoalCandidates goal_candidates{}; + goal_candidates.push_back(goal_candidate); + + return goal_candidates; } BehaviorModuleOutput GoalPlannerModule::plan() @@ -695,14 +689,14 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const { - if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { + if (prev_data_.found_path || !prev_data_.stop_path) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path - output.path = status_.get_prev_stop_path(); + output.path = prev_data_.stop_path; // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE( @@ -713,7 +707,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path - if (status_.get_prev_is_safe() || !status_.get_prev_stop_path_after_approval()) { + if (prev_data_.is_safe || !prev_data_.stop_path_after_approval) { auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( @@ -721,7 +715,6 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output parameters_->maximum_jerk_for_stop); if (stop_path) { output.path = std::make_shared(*stop_path); - // status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { output.path = @@ -730,10 +723,9 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } - // status_.set_last_path_update_time(std::make_shared(clock_->now())); } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path - output.path = status_.get_prev_stop_path_after_approval(); + output.path = prev_data_.stop_path_after_approval; // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); @@ -934,7 +926,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() path_candidate_ = std::make_shared(thread_safe_data_.get_pull_over_path()->getFullPath()); - updateStatus(output); + updatePreviousData(output); return output; } @@ -961,17 +953,16 @@ void GoalPlannerModule::postProcess() setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); } -void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) +void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) { - if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { - status_.set_prev_stop_path(output.path); + if (prev_data_.found_path || !prev_data_.stop_path) { + prev_data_.stop_path = output.path; } // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); - status_.set_prev_is_safe( - parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); + prev_data_.found_path = thread_safe_data_.foundPullOverPath(); + prev_data_.is_safe = parameters_->safety_check_params.enable_safety_check ? isSafePath() : true; if (!isActivated()) { return; @@ -979,15 +970,15 @@ void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) if ( !parameters_->safety_check_params.enable_safety_check || isSafePath() || - (!status_.get_prev_is_safe() && status_.get_prev_stop_path_after_approval())) { + (!prev_data_.is_safe && prev_data_.stop_path_after_approval)) { return; } - status_.set_prev_is_safe(false); + prev_data_.is_safe = false; const bool is_stop_path = std::any_of( output.path->points.begin(), output.path->points.end(), [](const auto & point) { return point.point.longitudinal_velocity_mps == 0.0; }); if (is_stop_path) { - status_.set_prev_stop_path_after_approval(output.path); + prev_data_.stop_path_after_approval = output.path; } } @@ -1061,8 +1052,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible // stop point is found, stop at this position. + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); const auto decel_pose = calcLongitudinalOffsetPose( - reference_path.points, status_.get_closest_goal_candidate_pose().position, + reference_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); // if not approved stop road lane. @@ -1136,6 +1129,7 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, /*forward_only_in_route*/ false); + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; @@ -1432,8 +1426,10 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const { // decelerate before the search area start + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); const auto decel_pose = calcLongitudinalOffsetPose( - pull_over_path.getFullPath().points, status_.get_closest_goal_candidate_pose().position, + pull_over_path.getFullPath().points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); auto & first_path = pull_over_path.partial_paths.front(); if (decel_pose) { @@ -1663,7 +1659,7 @@ bool GoalPlannerModule::isSafePath() const pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = - status_.get_prev_is_safe() ? 1.0 : parameters_->hysteresis_factor_expand_rate; + prev_data_.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); @@ -1727,7 +1723,7 @@ void GoalPlannerModule::setDebugData() // Visualize pull over areas const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green - const double z = status_.get_refined_goal_pose().position.z; + const double z = planner_data_->route_handler->getGoalPose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); From 4d916ddeca062680144426dc05093a076c056a18 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 23:59:35 +0900 Subject: [PATCH 133/223] feat(goal_planner): keep margin against objects as possible (#5569) * refactor(goal_planner): add prev_data instead of status Signed-off-by: kosuke55 * feat(goal_planner): keep margin against objects as possible Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 7 +- .../goal_planner/pull_over_planner_base.hpp | 1 + .../goal_planner/goal_planner_module.cpp | 147 +++++++++++++++--- 3 files changed, 130 insertions(+), 25 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index a31442def538f..87340cc665edd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -366,7 +366,10 @@ class GoalPlannerModule : public SceneModuleInterface // collision check void initializeOccupancyGridMap(); void updateOccupancyGrid(); - bool checkCollision(const PathWithLaneId & path) const; + bool checkOccupancyGridCollision(const PathWithLaneId & path) const; + bool checkObjectsCollision( + const PathWithLaneId & path, const double collision_check_margin, + const bool update_debug_data = false) const; // goal seach Pose calcRefinedGoal(const Pose & goal_pose) const; @@ -416,7 +419,7 @@ class GoalPlannerModule : public SceneModuleInterface BehaviorModuleOutput planPullOverAsCandidate(); std::optional> selectPullOverPath( const std::vector & pull_over_path_candidates, - const GoalCandidates & goal_candidates) const; + const GoalCandidates & goal_candidates, const double collision_check_margin) const; std::vector sortPullOverPathCandidatesByGoalPriority( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index acb034a29d9e5..5023401263b8d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -53,6 +53,7 @@ struct PullOverPath Pose end_pose{}; std::vector debug_poses{}; size_t goal_id{}; + size_t id{}; bool decided_velocity{false}; PathWithLaneId getFullPath() const diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 509214d37cd5a..5a51353143fe0 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -174,6 +174,7 @@ void GoalPlannerModule::onTimer() auto pull_over_path = planner->plan(goal_candidate.goal_pose); if (pull_over_path && isCrossingPossible(*pull_over_path)) { pull_over_path->goal_id = goal_candidate.id; + pull_over_path->id = path_candidates.size(); path_candidates.push_back(*pull_over_path); // calculate closest pull over start pose for stop path const double start_arc_length = @@ -533,7 +534,15 @@ bool GoalPlannerModule::canReturnToLaneParking() } const PathWithLaneId path = thread_safe_data_.get_lane_parking_pull_over_path()->getFullPath(); - if (checkCollision(path)) { + + if ( + parameters_->use_object_recognition && + checkObjectsCollision(path, parameters_->object_recognition_collision_check_margin)) { + return false; + } + + if ( + parameters_->use_occupancy_grid_for_path_collision_check && checkOccupancyGridCollision(path)) { return false; } @@ -597,6 +606,48 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return goal_id_to_index[a.goal_id] < goal_id_to_index[b.goal_id]; }); + if (parameters_->use_object_recognition) { + // Create a map of PullOverPath pointer to largest collision check margin + auto calcLargestMargin = [&](const PullOverPath & pull_over_path) { + // check has safe goal + const auto goal_candidate_it = std::find_if( + goal_candidates.begin(), goal_candidates.end(), + [pull_over_path](const auto & goal_candidate) { + return goal_candidate.id == pull_over_path.goal_id; + }); + if (goal_candidate_it != goal_candidates.end() && !goal_candidate_it->is_safe) { + return 0.0; + } + // calc largest margin + std::vector scale_factors{3.0, 2.0, 1.0}; + const double margin = parameters_->object_recognition_collision_check_margin; + const auto resampled_path = + utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); + for (const auto & scale_factor : scale_factors) { + if (!checkObjectsCollision(resampled_path, margin * scale_factor)) { + return margin * scale_factor; + } + } + return 0.0; + }; + + // Create a map of PullOverPath pointer to largest collision check margin + std::map path_id_to_margin_map; + for (const auto & path : sorted_pull_over_path_candidates) { + path_id_to_margin_map[path.id] = calcLargestMargin(path); + } + + // sorts in descending order so the item with larger margin comes first + std::stable_sort( + sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), + [&path_id_to_margin_map](const PullOverPath & a, const PullOverPath & b) { + if (std::abs(path_id_to_margin_map[a.id] - path_id_to_margin_map[b.id]) < 0.01) { + return false; + } + return path_id_to_margin_map[a.id] > path_id_to_margin_map[b.id]; + }); + } + // Sort pull_over_path_candidates based on the order in efficient_path_order if (parameters_->path_priority == "efficient_path") { std::stable_sort( @@ -614,7 +665,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri std::optional> GoalPlannerModule::selectPullOverPath( const std::vector & pull_over_path_candidates, - const GoalCandidates & goal_candidates) const + const GoalCandidates & goal_candidates, const double collision_check_margin) const { for (const auto & pull_over_path : pull_over_path_candidates) { // check if goal is safe @@ -627,10 +678,20 @@ std::optional> GoalPlannerModule::selectP continue; } - // check if path is valid and safe + if (!hasEnoughDistance(pull_over_path)) { + continue; + } + + const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); if ( - !hasEnoughDistance(pull_over_path) || - checkCollision(utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5))) { + parameters_->use_object_recognition && + checkObjectsCollision(resampled_path, collision_check_margin, true /*update_debug_data*/)) { + continue; + } + + if ( + parameters_->use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision(resampled_path)) { continue; } @@ -888,7 +949,9 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() thread_safe_data_.get_pull_over_path_candidates(), goal_candidates); // select pull over path which is safe against static objects and get it's goal - const auto path_and_goal_opt = selectPullOverPath(pull_over_path_candidates, goal_candidates); + const auto path_and_goal_opt = selectPullOverPath( + pull_over_path_candidates, goal_candidates, + parameters_->object_recognition_collision_check_margin); // update thread_safe_data_ if (path_and_goal_opt) { @@ -1205,7 +1268,21 @@ bool GoalPlannerModule::isStuck() return false; } - return checkCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath()); + if ( + parameters_->use_object_recognition && + checkObjectsCollision( + thread_safe_data_.get_pull_over_path()->getCurrentPath(), + parameters_->object_recognition_collision_check_margin)) { + return true; + } + + if ( + parameters_->use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath())) { + return true; + } + + return false; } bool GoalPlannerModule::hasFinishedCurrentPath() @@ -1297,18 +1374,19 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const return turn_signal; } -bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const +bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const { - if (parameters_->use_occupancy_grid_for_path_collision_check && occupancy_grid_map_) { - const bool check_out_of_range = false; - if (occupancy_grid_map_->hasObstacleOnPath(path, check_out_of_range)) { - return true; - } - } - if (!parameters_->use_object_recognition) { + if (!occupancy_grid_map_) { return false; } + const bool check_out_of_range = false; + return occupancy_grid_map_->hasObstacleOnPath(path, check_out_of_range); +} +bool GoalPlannerModule::checkObjectsCollision( + const PathWithLaneId & path, const double collision_check_margin, + const bool update_debug_data) const +{ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length); @@ -1323,7 +1401,30 @@ bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const obj_polygons.push_back(tier4_autoware_utils::toPolygon2d(object)); } - std::vector ego_polygons_expanded; + /* Expand ego collision check polygon + * - `collision_check_margin` in all directions + * - `extra_stopping_margin` in the moving direction + * - `extra_lateral_margin` in external direction of path curve + * + * + * ^ moving direction + * x + * x + * x + * +----------------------+------x--+ + * | | x | + * | +---------------+ | xx | + * | | | | xx | + * | | ego footprint |xxxxx | + * | | | | | + * | +---------------+ | extra_stopping_margin + * | margin | | + * +----------------------+ | + * | extra_lateral_margin | + * +--------------------------------+ + * + */ + std::vector ego_polygons_expanded{}; const auto curvatures = motion_utils::calcCurvature(path.points); for (size_t i = 0; i < path.points.size(); ++i) { const auto p = path.points.at(i); @@ -1341,16 +1442,16 @@ bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const tier4_autoware_utils::calcOffsetPose(p.point.pose, 0.0, extra_lateral_margin / 2.0, 0.0); const auto ego_polygon = tier4_autoware_utils::toFootprint( lateral_offset_pose, - planner_data_->parameters.base_link2front + - parameters_->object_recognition_collision_check_margin + extra_stopping_margin, - planner_data_->parameters.base_link2rear + - parameters_->object_recognition_collision_check_margin, - planner_data_->parameters.vehicle_width + - parameters_->object_recognition_collision_check_margin * 2.0 + + planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin, + planner_data_->parameters.base_link2rear + collision_check_margin, + planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 + std::abs(extra_lateral_margin)); ego_polygons_expanded.push_back(ego_polygon); } - debug_data_.ego_polygons_expanded = ego_polygons_expanded; + + if (update_debug_data) { + debug_data_.ego_polygons_expanded = ego_polygons_expanded; + } return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons); } From 9513782933672a100d01318ca33288d464f431a2 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 17 Nov 2023 08:26:21 +0900 Subject: [PATCH 134/223] feat(out_of_lane): improve reuse of previous decision (#5611) Signed-off-by: Maxime CLEMENT --- .../src/overlapping_range.hpp | 3 +- .../src/scene_out_of_lane.cpp | 42 ++++++++++--------- .../src/scene_out_of_lane.hpp | 2 - 3 files changed, 25 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp index 24bd6b3f16eb9..2b0830acc28cc 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp @@ -49,7 +49,8 @@ OverlapRanges calculate_overlapping_ranges( /// @param [in] path_lanelets path lanelets used to calculate arc length along the ego path /// @param [in] lanelets lanelets used to calculate the overlaps /// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelets +/// @return the overlapping ranges found between the footprints and the lanelets, sorted by +/// increasing arc length along the path OverlapRanges calculate_overlapping_ranges( const std::vector & path_footprints, const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelets & lanelets, diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp index 539cdefb31fdf..d739c6440ae75 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp @@ -67,18 +67,6 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto ego_data.path.points = path->points; ego_data.first_path_idx = motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position); - for (const auto & p : prev_overlapping_path_points_) { - const auto nearest_idx = - motion_utils::findNearestIndex(ego_data.path.points, p.point.pose, 1.0); - const auto insert_idx = - motion_utils::findNearestSegmentIndex(ego_data.path.points, p.point.pose, 1.0); - if (nearest_idx && insert_idx && *insert_idx > ego_data.first_path_idx) { - if ( - tier4_autoware_utils::calcDistance2d( - ego_data.path.points[*nearest_idx].point.pose, p.point.pose) > 0.5) - ego_data.path.points.insert(std::next(ego_data.path.points.begin(), *insert_idx), p); - } - } motion_utils::removeOverlapPoints(ego_data.path.points); ego_data.velocity = planner_data_->current_velocity->twist.linear.x; ego_data.max_decel = -planner_data_->max_stop_acceleration_threshold; @@ -118,10 +106,6 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto stopwatch.tic("calculate_overlapping_ranges"); const auto ranges = calculate_overlapping_ranges(path_footprints, path_lanelets, other_lanelets, params_); - prev_overlapping_path_points_.clear(); - for (const auto & range : ranges) - prev_overlapping_path_points_.push_back( - ego_data.path.points[ego_data.first_path_idx + range.entering_path_idx]); const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); // Calculate stop and slowdown points stopwatch.tic("calculate_decisions"); @@ -148,7 +132,28 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == point_to_insert->slowdown.lane_to_avoid.id())) prev_inserted_point_time_ = clock_->now(); - if (!point_to_insert && prev_inserted_point_) point_to_insert = prev_inserted_point_; + // reuse previous stop point if there is no new one or if its velocity is not higher than the new + // one and its arc length is lower + const auto should_use_prev_inserted_point = [&]() { + if ( + point_to_insert && prev_inserted_point_ && + prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { + const auto arc_length = motion_utils::calcSignedArcLength( + path->points, 0LU, point_to_insert->point.point.pose.position); + const auto prev_arc_length = motion_utils::calcSignedArcLength( + path->points, 0LU, prev_inserted_point_->point.point.pose.position); + return prev_arc_length < arc_length; + } + return !point_to_insert && prev_inserted_point_; + }(); + if (should_use_prev_inserted_point) { + // if the path changed the prev point is no longer on the path so we project it + const auto insert_arc_length = motion_utils::calcSignedArcLength( + path->points, 0LU, prev_inserted_point_->point.point.pose.position); + prev_inserted_point_->point.point.pose = + motion_utils::calcInterpolatedPose(path->points, insert_arc_length); + point_to_insert = prev_inserted_point_; + } if (point_to_insert) { prev_inserted_point_ = point_to_insert; RCLCPP_INFO(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); @@ -157,8 +162,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto path->points, point_to_insert->point.point.pose.position) + 1; planning_utils::insertVelocity( - *path, point_to_insert->point, point_to_insert->slowdown.velocity, path_idx, - params_.precision); + *path, point_to_insert->point, point_to_insert->slowdown.velocity, path_idx); if (point_to_insert->slowdown.velocity == 0.0) { tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = point_to_insert->point.point.pose; diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp index 310e2a9764d36..6133bb1ea0d6e 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp @@ -51,8 +51,6 @@ class OutOfLaneModule : public SceneModuleInterface private: PlannerParam params_; - std::vector - prev_overlapping_path_points_{}; std::optional prev_inserted_point_{}; rclcpp::Time prev_inserted_point_time_{}; From 1e65d39418bea9027effae90b32982669fe9cd07 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 17 Nov 2023 13:47:18 +0900 Subject: [PATCH 135/223] refactor(start_planner): support new interface (#5606) * refactor(start_planner): support new interface refactor state transition logic in StartPlannerModule Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 6 ++-- .../start_planner/start_planner_module.cpp | 35 ++++--------------- 2 files changed, 9 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 8d2532504926e..838cf040c3f8b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -91,8 +91,6 @@ class StartPlannerModule : public SceneModuleInterface bool isExecutionRequested() const override; bool isExecutionReady() const override; - // TODO(someone): remove this, and use base class function - [[deprecated]] void updateCurrentState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; @@ -123,11 +121,11 @@ class StartPlannerModule : public SceneModuleInterface bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; } private: - bool canTransitSuccessState() override { return false; } + bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } + bool canTransitIdleToRunningState() override; void initializeSafetyCheckParameters(); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 75562f59a402f..a39af7a376b02 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -228,33 +228,14 @@ bool StartPlannerModule::isExecutionReady() const return true; } -void StartPlannerModule::updateCurrentState() +bool StartPlannerModule::canTransitSuccessState() { - RCLCPP_DEBUG(getLogger(), "START_PLANNER updateCurrentState"); - - const auto print = [this](const auto & from, const auto & to) { - RCLCPP_DEBUG(getLogger(), "[start_planner] Transit from %s to %s.", from.data(), to.data()); - }; - - const auto & from = current_state_; - // current_state_ = updateState(); - - if (isActivated() && !isWaitingApproval()) { - current_state_ = ModuleStatus::RUNNING; - } else { - current_state_ = ModuleStatus::IDLE; - } - - // TODO(someone): move to canTransitSuccessState - if (hasFinishedPullOut()) { - current_state_ = ModuleStatus::SUCCESS; - } - // TODO(someone): move to canTransitSuccessState - if (status_.backward_driving_complete) { - current_state_ = ModuleStatus::SUCCESS; // for breaking loop - } + return hasFinishedPullOut(); +} - print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_)); +bool StartPlannerModule::canTransitIdleToRunningState() +{ + return isActivated() && !isWaitingApproval(); } BehaviorModuleOutput StartPlannerModule::plan() @@ -278,7 +259,7 @@ BehaviorModuleOutput StartPlannerModule::plan() PathWithLaneId path; // Check if backward motion is finished - if (status_.driving_forward) { + if (status_.driving_forward || status_.backward_driving_complete) { // Increment path index if the current path is finished if (hasFinishedCurrentPath()) { RCLCPP_INFO(getLogger(), "Increment path index"); @@ -739,8 +720,6 @@ void StartPlannerModule::updatePullOutStatus() if (isBackwardDrivingComplete()) { updateStatusAfterBackwardDriving(); - // should be moved to transition state - current_state_ = ModuleStatus::SUCCESS; // for breaking loop } else { status_.backward_path = start_planner_utils::getBackwardPath( *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, From 4d27fa4f55437a890a1098b2afb16ead74398620 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 17 Nov 2023 15:57:30 +0900 Subject: [PATCH 136/223] fix(lane_change): regulate at the traffic light (#5457) * fix(lane_change): regulate at the traffic light Signed-off-by: Zulfaqar Azmi * fix conflict Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../config/lane_change/lane_change.param.yaml | 1 + .../scene_module/lane_change/normal.hpp | 3 +++ .../lane_change/lane_change_module_data.hpp | 1 + .../behavior_path_planner/utils/utils.hpp | 1 + .../src/scene_module/lane_change/manager.cpp | 2 ++ .../src/scene_module/lane_change/normal.cpp | 21 +++++++++++++++++++ 6 files changed, 29 insertions(+) diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml index f98eac5315006..0cb7f3f1a7a92 100644 --- a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml +++ b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml @@ -81,6 +81,7 @@ regulation: crosswalk: false intersection: false + traffic_light: true # ego vehicle stuck detection stuck_detection: diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 503542be7cda6..4a117e5350baf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -135,6 +135,9 @@ class NormalLaneChange : public LaneChangeBase bool hasEnoughLengthToIntersection( const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const; + bool hasEnoughLengthToTrafficLight( + const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const; + bool getLaneChangePaths( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, Direction direction, LaneChangePaths * candidate_paths, diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index c664ae3e15aef..3f53f4b9c51e8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -65,6 +65,7 @@ struct LaneChangeParameters // regulatory elements bool regulate_on_crosswalk{false}; bool regulate_on_intersection{false}; + bool regulate_on_traffic_light{false}; // ego vehicle stuck detection double stop_velocity_threshold{0.1}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 3f9591f6c2143..4d34c548e640e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -45,6 +45,7 @@ #include #include #include +#include #include namespace behavior_path_planner::utils diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index ee7b45de09e93..e772c21331ae8 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -84,6 +84,8 @@ LaneChangeModuleManager::LaneChangeModuleManager( p.regulate_on_crosswalk = getOrDeclareParameter(*node, parameter("regulation.crosswalk")); p.regulate_on_intersection = getOrDeclareParameter(*node, parameter("regulation.intersection")); + p.regulate_on_traffic_light = + getOrDeclareParameter(*node, parameter("regulation.traffic_light")); // ego vehicle stuck detection p.stop_velocity_threshold = diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 5bffef1a4b421..c0655b3f18b5f 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -19,6 +19,7 @@ #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/traffic_light_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" #include @@ -38,6 +39,7 @@ namespace behavior_path_planner { using motion_utils::calcSignedArcLength; +using utils::traffic_light::getDistanceToNextTrafficLight; NormalLaneChange::NormalLaneChange( const std::shared_ptr & parameters, LaneChangeModuleType type, @@ -1086,6 +1088,19 @@ bool NormalLaneChange::hasEnoughLengthToIntersection( return true; } +bool NormalLaneChange::hasEnoughLengthToTrafficLight( + const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const +{ + const auto current_pose = getEgoPose(); + const auto dist_to_next_traffic_light = + getDistanceToNextTrafficLight(current_pose, current_lanes); + const auto dist_to_next_traffic_light_from_lc_start_pose = + dist_to_next_traffic_light - path.info.length.prepare; + + return dist_to_next_traffic_light_from_lc_start_pose <= 0.0 || + dist_to_next_traffic_light_from_lc_start_pose >= path.info.length.lane_changing; +} + bool NormalLaneChange::getLaneChangePaths( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, Direction direction, LaneChangePaths * candidate_paths, @@ -1345,6 +1360,12 @@ bool NormalLaneChange::getLaneChangePaths( logger_, "Stop time is over threshold. Allow lane change in intersection."); } + if ( + lane_change_parameters_->regulate_on_traffic_light && + !hasEnoughLengthToTrafficLight(*candidate_path, current_lanes)) { + continue; + } + candidate_paths->push_back(*candidate_path); std::vector filtered_objects = From dd3e9fb68f9c00209d811786e8193a811e64f847 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 17 Nov 2023 18:53:10 +0900 Subject: [PATCH 137/223] fix(start_planner, goal_planner): remove inappropriate reference value (#5618) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 6 +++--- .../scene_module/start_planner/start_planner_module.cpp | 8 ++++---- .../src/utils/start_planner/util.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 5a51353143fe0..6fdb46d058aef 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1751,12 +1751,12 @@ bool GoalPlannerModule::isSafePath() const ego_seg_idx, is_object_front, limit_to_max_velocity); // filtering objects with velocity, position and class - const auto & filtered_objects = utils::path_safety_checker::filterObjects( + const auto filtered_objects = utils::path_safety_checker::filterObjects( dynamic_object, route_handler, pull_over_lanes, current_pose.position, objects_filtering_params_); // filtering objects based on the current position's lane - const auto & target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( + const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = @@ -1956,7 +1956,7 @@ void GoalPlannerModule::printParkingPositionError() const bool GoalPlannerModule::checkOriginalGoalIsInShoulder() const { const auto & route_handler = planner_data_->route_handler; - const Pose & goal_pose = route_handler->getOriginalGoalPose(); + const Pose goal_pose = route_handler->getOriginalGoalPose(); const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes( *(route_handler), left_side_parking_, parameters_->backward_goal_search_length, diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index a39af7a376b02..d8370381f5eef 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -742,7 +742,7 @@ void StartPlannerModule::updateStatusAfterBackwardDriving() PathWithLaneId StartPlannerModule::calcBackwardPathFromStartPose() const { - const Pose & start_pose = planner_data_->route_handler->getOriginalStartPose(); + const Pose start_pose = planner_data_->route_handler->getOriginalStartPose(); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); @@ -770,7 +770,7 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( const PathWithLaneId & back_path_from_start_pose) const { std::vector pull_out_start_pose_candidates{}; - const auto & start_pose = planner_data_->route_handler->getOriginalStartPose(); + const auto start_pose = planner_data_->route_handler->getOriginalStartPose(); const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); @@ -1074,11 +1074,11 @@ bool StartPlannerModule::isSafePath() const is_object_front, limit_to_max_velocity); // filtering objects with velocity, position and class - const auto & filtered_objects = utils::path_safety_checker::filterObjects( + const auto filtered_objects = utils::path_safety_checker::filterObjects( dynamic_object, route_handler, current_lanes, current_pose.position, objects_filtering_params_); // filtering objects based on the current position's lane - const auto & target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( + const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( current_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 7b4d4566bba27..ad841822aeb0d 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -89,7 +89,7 @@ lanelet::ConstLanelets getPullOutLanes( { const double & vehicle_width = planner_data->parameters.vehicle_width; const auto & route_handler = planner_data->route_handler; - const auto & start_pose = planner_data->route_handler->getOriginalStartPose(); + const auto start_pose = planner_data->route_handler->getOriginalStartPose(); lanelet::ConstLanelet current_shoulder_lane; lanelet::ConstLanelets shoulder_lanes; From 14e5101cfbd33598c3115314dbaca37be61c4760 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 20 Nov 2023 10:33:18 +0900 Subject: [PATCH 138/223] feat(component_state_monitor): monitor pose_estimator output (#5617) Signed-off-by: kminoda --- system/component_state_monitor/config/topics.yaml | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/system/component_state_monitor/config/topics.yaml b/system/component_state_monitor/config/topics.yaml index c00203dbb6073..5672d13dcb43f 100644 --- a/system/component_state_monitor/config/topics.yaml +++ b/system/component_state_monitor/config/topics.yaml @@ -50,6 +50,19 @@ error_rate: 1.0 timeout: 1.0 +- module: localization + mode: [online, logging_simulation] + type: autonomous + args: + node_name_suffix: pose_estimator_pose + topic: /localization/pose_estimator/pose_with_covariance + topic_type: geometry_msgs/msg/PoseWithCovarianceStamped + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + - module: perception mode: [online, logging_simulation] type: launch From 93e45ac72a2c480559cd8ca8d2c23f45ab211f03 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 20 Nov 2023 10:34:25 +0900 Subject: [PATCH 139/223] fix(simple_planning_simulator): fix ego sign pitch problem (#5616) * fix ego sign pitch problem Signed-off-by: Daniel Sanchez * change variable name for clarity Signed-off-by: Daniel Sanchez * update documentation to clarify that driving against the lane is not supported Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- simulator/simple_planning_simulator/README.md | 2 ++ .../simple_planning_simulator_core.cpp | 5 +++-- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 0c5441c1ad9c8..1491f8ffea36e 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -98,6 +98,8 @@ Ego vehicle pitch angle is calculated in the following manner. ![pitch calculation](./media/pitch-calculation.drawio.svg) +NOTE: driving against the line direction (as depicted in image's bottom row) is not supported and only shown for illustration purposes. + ## Error detection and handling The only validation on inputs being done is testing for a valid vehicle model type. diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index a3715a1efe8ab..f0b126cbc61be 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -331,8 +331,9 @@ void SimplePlanningSimulator::on_timer() // calculate longitudinal acceleration by slope constexpr double gravity_acceleration = -9.81; - const double ego_pitch_angle = enable_road_slope_simulation_ ? calculate_ego_pitch() : 0.0; - const double acc_by_slope = gravity_acceleration * std::sin(ego_pitch_angle); + const double ego_pitch_angle = calculate_ego_pitch(); + const double slope_angle = enable_road_slope_simulation_ ? -ego_pitch_angle : 0.0; + const double acc_by_slope = gravity_acceleration * std::sin(slope_angle); // update vehicle dynamics { From 9e99bfc04301da81ba6aad82691a2e9a0fc7803b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 20 Nov 2023 14:45:38 +0900 Subject: [PATCH 140/223] fix(utils): fix monotonic bound create logic (#5565) Signed-off-by: satoshi-ota --- .../behavior_path_planner/src/utils/utils.cpp | 40 ++++++++++++------- 1 file changed, 25 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 19c408359e5f2..0d1eaef0237b3 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1933,22 +1933,33 @@ void makeBoundLongitudinallyMonotonic( return ret; }; - const auto is_monotonic = - [&](const auto & p1, const auto & p2, const auto & p3, const auto is_points_left) { - const auto p1_to_p2 = calcAzimuthAngle(p1, p2); - const auto p2_to_p3 = calcAzimuthAngle(p2, p3); + const auto is_non_monotonic = [&]( + const auto & base_pose, const auto & point, + const auto is_points_left, const auto is_reverse) { + const auto p_transformed = tier4_autoware_utils::inverseTransformPoint(point, base_pose); + if (p_transformed.x < 0.0 && p_transformed.y > 0.0) { + return is_points_left && !is_reverse; + } - const auto theta = normalizeRadian(p1_to_p2 - p2_to_p3); + if (p_transformed.x < 0.0 && p_transformed.y < 0.0) { + return !is_points_left && !is_reverse; + } - return (is_points_left && 0 < theta) || (!is_points_left && theta < 0); - }; + if (p_transformed.x > 0.0 && p_transformed.y > 0.0) { + return is_points_left && is_reverse; + } + + if (p_transformed.x > 0.0 && p_transformed.y < 0.0) { + return !is_points_left && is_reverse; + } + + return false; + }; // define a function to remove non monotonic point on bound const auto remove_non_monotonic_point = [&](const auto & bound_with_pose, const bool is_reverse) { std::vector monotonic_bound; - const bool is_points_left = is_reverse ? !is_bound_left : is_bound_left; - size_t bound_idx = 0; while (true) { monotonic_bound.push_back(bound_with_pose.at(bound_idx)); @@ -1961,13 +1972,12 @@ void makeBoundLongitudinallyMonotonic( // opposite. const double lat_offset = is_bound_left ? 100.0 : -100.0; - const auto p_bound_1 = getPoint(bound_with_pose.at(bound_idx)); - const auto p_bound_2 = getPoint(bound_with_pose.at(bound_idx + 1)); + const auto p_bound_1 = getPose(bound_with_pose.at(bound_idx)); + const auto p_bound_2 = getPose(bound_with_pose.at(bound_idx + 1)); - const auto p_bound_offset = - calcOffsetPose(getPose(bound_with_pose.at(bound_idx)), 0.0, lat_offset, 0.0); + const auto p_bound_offset = calcOffsetPose(p_bound_1, 0.0, lat_offset, 0.0); - if (!is_monotonic(p_bound_1, p_bound_2, p_bound_offset.position, is_points_left)) { + if (!is_non_monotonic(p_bound_1, p_bound_2.position, is_bound_left, is_reverse)) { bound_idx++; continue; } @@ -1975,7 +1985,7 @@ void makeBoundLongitudinallyMonotonic( // skip non monotonic points for (size_t i = bound_idx + 1; i < bound_with_pose.size() - 1; ++i) { const auto intersect_point = intersect( - p_bound_1, p_bound_offset.position, bound_with_pose.at(i).position, + p_bound_1.position, p_bound_offset.position, bound_with_pose.at(i).position, bound_with_pose.at(i + 1).position); if (intersect_point) { From a8000409b5be540211189dcc8a7cd8e3a981d960 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 20 Nov 2023 15:16:59 +0900 Subject: [PATCH 141/223] fix(lane_change): fix abort path (#5628) Signed-off-by: Fumiya Watanabe --- .../src/scene_module/lane_change/normal.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index c0655b3f18b5f..702ed16166e2b 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -1636,7 +1636,9 @@ bool NormalLaneChange::calcAbortPath() const double s_start = arc_position.length; double s_end = std::max(lanelet::utils::getLaneletLength2d(reference_lanelets), s_start); - if (route_handler->isInGoalRouteSection(selected_path.info.target_lanes.back())) { + if ( + !reference_lanelets.empty() && + route_handler->isInGoalRouteSection(reference_lanelets.back())) { const auto goal_arc_coordinates = lanelet::utils::getArcCoordinates(reference_lanelets, route_handler->getGoalPose()); const double forward_length = std::max(goal_arc_coordinates.length, s_start); From 3bb70d0a507a49abc8808ee9b2b735c7ab934f32 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 20 Nov 2023 17:20:22 +0900 Subject: [PATCH 142/223] refactor(start_planner): add verbose parameter for debug print (#5622) * refactor(start_planner): add verbose parameter for debug print - Added a new parameter "verbose" to the StartPlannerParameters struct. - Updated the start_planner.param.yaml file to include the "verbose" parameter. - Added a new method receivedNewRoute() in the StartPlannerModule class to check if a new route has been received. - Updated the updateData() method to use the receivedNewRoute() method instead of directly checking if a new route has been received. - Renamed the method IsGoalBehindOfEgoInSameRouteSegment() to isGoalBehindOfEgoInSameRouteSegment(). - Added a new method logPullOutStatus() to log the pull out status. - Updated the setDebugData() method to call logPullOutStatus() if the "verbose" parameter is true. Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner.param.yaml | 3 + .../start_planner/start_planner_module.hpp | 5 +- .../start_planner_parameters.hpp | 1 + .../scene_module/start_planner/manager.cpp | 1 + .../start_planner/start_planner_module.cpp | 77 +++++++++++++++++-- 5 files changed, 79 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 4a42da9bc5ac3..3a94a18e011b9 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -1,6 +1,9 @@ /**: ros__parameters: start_planner: + + verbose: false + th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 1.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 838cf040c3f8b..54e13de85e8da 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -129,6 +129,8 @@ class StartPlannerModule : public SceneModuleInterface void initializeSafetyCheckParameters(); + bool receivedNewRoute() const; + bool isModuleRunning() const; bool isCurrentPoseOnMiddleOfTheRoad() const; bool isCloseToOriginalStartPose() const; @@ -207,7 +209,7 @@ class StartPlannerModule : public SceneModuleInterface void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // check if the goal is located behind the ego in the same route segment. - bool IsGoalBehindOfEgoInSameRouteSegment() const; + bool isGoalBehindOfEgoInSameRouteSegment() const; // generate BehaviorPathOutput with stopping path and update status BehaviorModuleOutput generateStopOutput(); @@ -218,6 +220,7 @@ class StartPlannerModule : public SceneModuleInterface bool planFreespacePath(); void setDebugData() const; + void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 6978a7d494f30..bd4017e5dff7d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -46,6 +46,7 @@ struct StartPlannerParameters double collision_check_distance_from_end{0.0}; double th_moving_object_velocity{0.0}; double center_line_path_interval{0.0}; + bool verbose{false}; // shift pull out bool enable_shift_pull_out{false}; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index 46db10417d19e..fdc28139aa8f0 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -33,6 +33,7 @@ StartPlannerModuleManager::StartPlannerModuleManager( std::string ns = "start_planner."; + p.verbose = node->declare_parameter(ns + "verbose"); p.th_arrived_distance = node->declare_parameter(ns + "th_arrived_distance"); p.th_stopped_velocity = node->declare_parameter(ns + "th_stopped_velocity"); p.th_stopped_time = node->declare_parameter(ns + "th_stopped_time"); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index d8370381f5eef..ed70e68414543 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -128,11 +128,7 @@ void StartPlannerModule::updateData() status_.backward_driving_complete = false; } - const bool has_received_new_route = - !planner_data_->prev_route_id || - *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); - - if (has_received_new_route) { + if (receivedNewRoute()) { status_ = PullOutStatus(); } // check safety status when driving forward @@ -143,6 +139,12 @@ void StartPlannerModule::updateData() } } +bool StartPlannerModule::receivedNewRoute() const +{ + return !planner_data_->prev_route_id || + *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); +} + bool StartPlannerModule::isExecutionRequested() const { if (isModuleRunning()) { @@ -161,7 +163,7 @@ bool StartPlannerModule::isExecutionRequested() const } // Check if the goal is behind the ego vehicle within the same route segment. - if (IsGoalBehindOfEgoInSameRouteSegment()) { + if (isGoalBehindOfEgoInSameRouteSegment()) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); return false; @@ -1118,7 +1120,7 @@ bool StartPlannerModule::isSafePath() const return is_safe_dynamic_objects; } -bool StartPlannerModule::IsGoalBehindOfEgoInSameRouteSegment() const +bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const { const auto & rh = planner_data_->route_handler; @@ -1306,5 +1308,66 @@ void StartPlannerModule::setDebugData() const planner_type_marker_array.markers.push_back(marker); add(planner_type_marker_array); } + if (parameters_->verbose) { + logPullOutStatus(); + } +} + +void StartPlannerModule::logPullOutStatus(rclcpp::Logger::Level log_level) const +{ + const auto logger = getLogger(); + auto logFunc = [&logger, log_level](const char * format, ...) { + char buffer[1024]; + va_list args; + va_start(args, format); + vsnprintf(buffer, sizeof(buffer), format, args); + va_end(args); + switch (log_level) { + case rclcpp::Logger::Level::Debug: + RCLCPP_DEBUG(logger, "%s", buffer); + break; + case rclcpp::Logger::Level::Info: + RCLCPP_INFO(logger, "%s", buffer); + break; + case rclcpp::Logger::Level::Warn: + RCLCPP_WARN(logger, "%s", buffer); + break; + case rclcpp::Logger::Level::Error: + RCLCPP_ERROR(logger, "%s", buffer); + break; + case rclcpp::Logger::Level::Fatal: + RCLCPP_FATAL(logger, "%s", buffer); + break; + default: + RCLCPP_INFO(logger, "%s", buffer); + break; + } + }; + + logFunc("======== PullOutStatus Report ========"); + + logFunc("[Path Info]"); + logFunc(" Current Path Index: %zu", status_.current_path_idx); + + logFunc("[Planner Info]"); + logFunc(" Planner Type: %s", magic_enum::enum_name(status_.planner_type).data()); + + logFunc("[Safety and Direction Info]"); + logFunc(" Found Pull Out Path: %s", status_.found_pull_out_path ? "true" : "false"); + logFunc( + " Is Safe Against Dynamic Objects: %s", status_.is_safe_dynamic_objects ? "true" : "false"); + logFunc( + " Previous Is Safe Dynamic Objects: %s", + status_.prev_is_safe_dynamic_objects ? "true" : "false"); + logFunc(" Driving Forward: %s", status_.driving_forward ? "true" : "false"); + logFunc(" Backward Driving Complete: %s", status_.backward_driving_complete ? "true" : "false"); + logFunc(" Has Stop Point: %s", status_.has_stop_point ? "true" : "false"); + + logFunc("[Module State]"); + logFunc(" isActivated: %s", isActivated() ? "true" : "false"); + logFunc(" isWaitingForApproval: %s", isWaitingApproval() ? "true" : "false"); + logFunc(" ModuleStatus: %s", magic_enum::enum_name(getCurrentStatus())); + + logFunc("======================================="); } } // namespace behavior_path_planner From e5c4b0873783cc170b5b36907b3625d10a759f1f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 20 Nov 2023 18:13:23 +0900 Subject: [PATCH 143/223] refactor(goal_planner): add rss safety check function (#5620) * refactor(goal_planner): add rss safety check function Signed-off-by: kosuke55 * has_collision Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 5 ++ .../goal_planner/goal_planner_module.cpp | 64 +++++++++---------- 2 files changed, 37 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 87340cc665edd..b04a3fee41dcb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -62,6 +62,7 @@ using freespace_planning_algorithms::RRTStar; using freespace_planning_algorithms::RRTStarParam; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; +using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; @@ -471,6 +472,10 @@ class GoalPlannerModule : public SceneModuleInterface const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const; bool isSafePath() const; + bool checkSafetyWithRSS( + const PathWithLaneId & planned_path, + const std::vector & ego_predicted_path, + const std::vector & objects, const double hysteresis_factor) const; // debug void setDebugData(); diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6fdb46d058aef..9712faae5712a 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1716,6 +1716,34 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( goal_planner_data_.ego_predicted_path = ego_predicted_path; } +bool GoalPlannerModule::checkSafetyWithRSS( + const PathWithLaneId & planned_path, + const std::vector & ego_predicted_path, + const std::vector & objects, const double hysteresis_factor) const +{ + // Check for collisions with each predicted path of the object + const bool is_safe = !std::any_of(objects.begin(), objects.end(), [&](const auto & object) { + auto current_debug_data = marker_utils::createObjectDebug(object); + + const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( + object, objects_filtering_params_->check_all_predicted_path); + + return std::any_of( + obj_predicted_paths.begin(), obj_predicted_paths.end(), [&](const auto & obj_path) { + const bool has_collision = !utils::path_safety_checker::checkCollision( + planned_path, ego_predicted_path, object, obj_path, planner_data_->parameters, + safety_check_params_->rss_params, hysteresis_factor, current_debug_data.second); + + marker_utils::updateCollisionCheckDebugMap( + goal_planner_data_.collision_check, current_debug_data, !has_collision); + + return has_collision; + }); + }); + + return is_safe; +} + bool GoalPlannerModule::isSafePath() const { const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); @@ -1759,41 +1787,13 @@ bool GoalPlannerModule::isSafePath() const const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); - const double hysteresis_factor = - prev_data_.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; - utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); - bool is_safe_dynamic_objects = true; - // Check for collisions with each predicted path of the object - for (const auto & object : target_objects_on_lane.on_current_lane) { - auto current_debug_data = marker_utils::createObjectDebug(object); - - bool is_safe_dynamic_object = true; - - const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( - object, objects_filtering_params_->check_all_predicted_path); - - // If a collision is detected, mark the object as unsafe and break the loop - for (const auto & obj_path : obj_predicted_paths) { - if (!utils::path_safety_checker::checkCollision( - pull_over_path, ego_predicted_path, object, obj_path, planner_data_->parameters, - safety_check_params_->rss_params, hysteresis_factor, current_debug_data.second)) { - marker_utils::updateCollisionCheckDebugMap( - goal_planner_data_.collision_check, current_debug_data, false); - is_safe_dynamic_objects = false; - is_safe_dynamic_object = false; - break; - } - } - if (is_safe_dynamic_object) { - marker_utils::updateCollisionCheckDebugMap( - goal_planner_data_.collision_check, current_debug_data, is_safe_dynamic_object); - } - } - - return is_safe_dynamic_objects; + const double hysteresis_factor = + prev_data_.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; + return checkSafetyWithRSS( + pull_over_path, ego_predicted_path, target_objects_on_lane.on_current_lane, hysteresis_factor); } void GoalPlannerModule::setDebugData() From eb9c7149021a51d5458f723ce9b05ba221c6cc63 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 20 Nov 2023 21:54:04 +0900 Subject: [PATCH 144/223] feat(goal_planner): prevent auto approval for unsafe path (#5621) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 9712faae5712a..f39d706eb7ceb 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -862,6 +862,12 @@ bool GoalPlannerModule::hasDecidedPath() const return false; } + // If it is dangerous before approval, do not determine the path. + // This eliminates a unsafe path to be approved + if (!isSafePath() && !isActivated()) { + return false; + } + // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data_->self_odometry->pose.pose; const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex( From 6c2d806791f722febc3c549a94d853e917b6507e Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 21 Nov 2023 10:30:26 +0900 Subject: [PATCH 145/223] refactor(behavior_path_planner): separate drivable area functions (#5604) Signed-off-by: Muhammad Zulfaqar Azmi --- planning/behavior_path_planner/CMakeLists.txt | 1 + .../static_drivable_area.hpp | 99 + .../utils/goal_planner/util.hpp | 1 + .../utils/path_utils.hpp | 7 + .../utils/start_planner/util.hpp | 1 + .../behavior_path_planner/utils/utils.hpp | 86 +- .../src/behavior_path_planner_node.cpp | 1 + .../src/planner_manager.cpp | 2 + .../avoidance/avoidance_module.cpp | 1 + .../dynamic_avoidance_module.cpp | 1 + .../src/scene_module/lane_change/normal.cpp | 1 + .../side_shift/side_shift_module.cpp | 1 + .../static_drivable_area.cpp | 1871 ++++++++++++++ .../utils/goal_planner/shift_pull_over.cpp | 1 + .../src/utils/path_utils.cpp | 105 + .../behavior_path_planner/src/utils/utils.cpp | 2179 +---------------- .../behavior_path_planner/test/test_utils.cpp | 1 + .../static_centerline_optimizer/src/utils.cpp | 2 +- 18 files changed, 2222 insertions(+), 2139 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp create mode 100644 planning/behavior_path_planner/src/utils/drivable_area_expansion/static_drivable_area.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index e71d1dd9d86b4..7fc35355202ff 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -48,6 +48,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/utils/start_planner/geometric_pull_out.cpp src/utils/start_planner/freespace_pull_out.cpp src/utils/path_shifter/path_shifter.cpp + src/utils/drivable_area_expansion/static_drivable_area.cpp src/utils/drivable_area_expansion/drivable_area_expansion.cpp src/utils/drivable_area_expansion/map_utils.cpp src/utils/drivable_area_expansion/footprints.cpp diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp new file mode 100644 index 0000000000000..e7a05bc473c03 --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp @@ -0,0 +1,99 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__STATIC_DRIVABLE_AREA_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__STATIC_DRIVABLE_AREA_HPP_ + +#include + +#include +#include +#include +namespace behavior_path_planner::utils +{ +using drivable_area_expansion::DrivableAreaExpansionParameters; + +boost::optional getOverlappedLaneletId(const std::vector & lanes); + +std::vector cutOverlappedLanes( + PathWithLaneId & path, const std::vector & lanes); + +std::vector generateDrivableLanes(const lanelet::ConstLanelets & current_lanes); + +std::vector generateDrivableLanesWithShoulderLanes( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes); + +std::vector getNonOverlappingExpandedLanes( + PathWithLaneId & path, const std::vector & lanes, + const DrivableAreaExpansionParameters & parameters); +void generateDrivableArea( + PathWithLaneId & path, const std::vector & lanes, + const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, + const double vehicle_length, const std::shared_ptr planner_data, + const bool is_driving_forward = true); + +void generateDrivableArea( + PathWithLaneId & path, const double vehicle_length, const double offset, + const bool is_driving_forward = true); + +lanelet::ConstLineStrings3d getMaximumDrivableArea( + const std::shared_ptr & planner_data); + +/** + * @brief Expand the borders of the given lanelets + * @param [in] drivable_lanes lanelets to expand + * @param [in] left_bound_offset [m] expansion distance of the left bound + * @param [in] right_bound_offset [m] expansion distance of the right bound + * @param [in] types_to_skip linestring types that will not be expanded + * @return expanded lanelets + */ +std::vector expandLanelets( + const std::vector & drivable_lanes, const double left_bound_offset, + const double right_bound_offset, const std::vector & types_to_skip = {}); + +void extractObstaclesFromDrivableArea( + PathWithLaneId & path, const std::vector & obstacles); + +std::vector getBoundWithHatchedRoadMarkings( + const std::vector & original_bound, + const std::shared_ptr & route_handler); + +std::vector getBoundWithIntersectionAreas( + const std::vector & original_bound, + const std::shared_ptr & route_handler, + const std::vector & drivable_lanes, const bool is_left); + +std::vector calcBound( + const std::shared_ptr route_handler, + const std::vector & drivable_lanes, + const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, + const bool is_left); + +void makeBoundLongitudinallyMonotonic( + PathWithLaneId & path, const std::shared_ptr & planner_data, + const bool is_bound_left); + +DrivableAreaInfo combineDrivableAreaInfo( + const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2); + +lanelet::ConstLanelets combineLanelets( + const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes); + +std::vector combineDrivableLanes( + const std::vector & original_drivable_lanes_vec, + const std::vector & new_drivable_lanes_vec); + +} // namespace behavior_path_planner::utils + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__STATIC_DRIVABLE_AREA_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp index 062a84bcd5aef..2977dab91fd14 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp @@ -15,6 +15,7 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" #include "behavior_path_planner/utils/utils.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp index a9cbf859dd9d8..4b3c026ae8064 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp @@ -106,6 +106,13 @@ PathWithLaneId calcCenterLinePath( PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & path2); boost::optional getFirstStopPoseFromPath(const PathWithLaneId & path); + +BehaviorModuleOutput getReferencePath( + const lanelet::ConstLanelet & current_lane, + const std::shared_ptr & planner_data); + +BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr & planner_data); + } // namespace behavior_path_planner::utils #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_UTILS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp index e7f51b2e86d5b..71571b6d7a6c6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ #include "behavior_path_planner/data_manager.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 4d34c548e640e..144dad3b6feab 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -59,7 +59,6 @@ using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; -using drivable_area_expansion::DrivableAreaExpansionParameters; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; @@ -209,56 +208,6 @@ boost::optional getRightLanelet( const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes); boost::optional getLeftLanelet( const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes); -std::vector generateDrivableLanes(const lanelet::ConstLanelets & current_lanes); -std::vector generateDrivableLanesWithShoulderLanes( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes); -std::vector getNonOverlappingExpandedLanes( - PathWithLaneId & path, const std::vector & lanes, - const DrivableAreaExpansionParameters & parameters); -std::vector calcBound( - const std::shared_ptr route_handler, - const std::vector & drivable_lanes, - const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, - const bool is_left); - -std::vector getBoundWithHatchedRoadMarkings( - const std::vector & original_bound, - const std::shared_ptr & route_handler); - -std::vector getBoundWithIntersectionAreas( - const std::vector & original_bound, - const std::shared_ptr & route_handler, - const std::vector & drivable_lanes, const bool is_left); - -boost::optional getOverlappedLaneletId(const std::vector & lanes); -std::vector cutOverlappedLanes( - PathWithLaneId & path, const std::vector & lanes); - -void generateDrivableArea( - PathWithLaneId & path, const std::vector & lanes, - const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, - const double vehicle_length, const std::shared_ptr planner_data, - const bool is_driving_forward = true); - -void generateDrivableArea( - PathWithLaneId & path, const double vehicle_length, const double offset, - const bool is_driving_forward = true); - -lanelet::ConstLineStrings3d getMaximumDrivableArea( - const std::shared_ptr & planner_data); - -/** - * @brief Expand the borders of the given lanelets - * @param [in] drivable_lanes lanelets to expand - * @param [in] left_bound_offset [m] expansion distance of the left bound - * @param [in] right_bound_offset [m] expansion distance of the right bound - * @param [in] types_to_skip linestring types that will not be expanded - * @return expanded lanelets - */ -std::vector expandLanelets( - const std::vector & drivable_lanes, const double left_bound_offset, - const double right_bound_offset, const std::vector & types_to_skip = {}); - // goal management /** @@ -294,8 +243,6 @@ PathWithLaneId refinePathForGoal( bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal_id); -BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr & planner_data); - bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes); bool isInLaneletWithYawThreshold( @@ -349,10 +296,6 @@ PathWithLaneId setDecelerationVelocity( const lanelet::ConstLanelets & lanelet_sequence, const double lane_change_prepare_duration, const double lane_change_buffer); -BehaviorModuleOutput getReferencePath( - const lanelet::ConstLanelet & current_lane, - const std::shared_ptr & planner_data); - // object label std::uint8_t getHighestProbLabel(const std::vector & classification); @@ -399,26 +342,23 @@ lanelet::ConstLanelets getLaneletsFromPath( std::string convertToSnakeCase(const std::string & input_str); -std::vector combineDrivableLanes( - const std::vector & original_drivable_lanes_vec, - const std::vector & new_drivable_lanes_vec); - -DrivableAreaInfo combineDrivableAreaInfo( - const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2); - -void extractObstaclesFromDrivableArea( - PathWithLaneId & path, const std::vector & obstacles); - -void makeBoundLongitudinallyMonotonic( - PathWithLaneId & path, const std::shared_ptr & planner_data, - const bool is_bound_left); - std::optional getPolygonByPoint( const std::shared_ptr & route_handler, const lanelet::ConstPoint3d & point, const std::string & polygon_name); -lanelet::ConstLanelets combineLanelets( - const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes); +template +size_t findNearestSegmentIndex( + const std::vector & points, const geometry_msgs::msg::Pose & pose, const double dist_threshold, + const double yaw_threshold) +{ + const auto nearest_idx = + motion_utils::findNearestSegmentIndex(points, pose, dist_threshold, yaw_threshold); + if (nearest_idx) { + return nearest_idx.get(); + } + + return motion_utils::findNearestSegmentIndex(points, pose.position); +} } // namespace behavior_path_planner::utils #endif // BEHAVIOR_PATH_PLANNER__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index ef44bee663985..689444a3bf995 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -22,6 +22,7 @@ #include "behavior_path_planner/scene_module/lane_change/manager.hpp" #include "behavior_path_planner/scene_module/side_shift/manager.hpp" #include "behavior_path_planner/scene_module/start_planner/manager.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 79e6055d26a81..478b74c9051bb 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -14,6 +14,8 @@ #include "behavior_path_planner/planner_manager.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" +#include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" #include "tier4_autoware_utils/ros/debug_publisher.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index ea4eab425b66b..1bd4fb3fef616 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/avoidance/utils.hpp" #include "behavior_path_planner/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 7aba1d1b2d97f..f917f1e2f3c65 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -14,6 +14,7 @@ #include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/utils.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" #include "signal_processing/lowpass_filter_1d.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 702ed16166e2b..d213eec21cdbf 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -15,6 +15,7 @@ #include "behavior_path_planner/scene_module/lane_change/normal.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/lane_change/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 46332e738f82f..0e86508ca6afc 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -15,6 +15,7 @@ #include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/side_shift/util.hpp" #include "behavior_path_planner/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/static_drivable_area.cpp new file mode 100644 index 0000000000000..becbf4ceb508b --- /dev/null +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -0,0 +1,1871 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" + +#include "behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp" +#include "motion_utils/trajectory/trajectory.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace +{ +template +size_t findNearestSegmentIndexFromLateralDistance( + const std::vector & points, const geometry_msgs::msg::Point & target_point) +{ + std::optional closest_idx{std::nullopt}; + double min_lateral_dist = std::numeric_limits::max(); + for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) { + const double lon_dist = + motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); + const double segment_length = + tier4_autoware_utils::calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); + const double lat_dist = [&]() { + if (lon_dist < 0.0) { + return tier4_autoware_utils::calcDistance2d(points.at(seg_idx), target_point); + } + if (segment_length < lon_dist) { + return tier4_autoware_utils::calcDistance2d(points.at(seg_idx + 1), target_point); + } + return std::abs(motion_utils::calcLateralOffset(points, target_point, seg_idx)); + }(); + if (lat_dist < min_lateral_dist) { + closest_idx = seg_idx; + min_lateral_dist = lat_dist; + } + } + + if (closest_idx) { + return *closest_idx; + } + + return motion_utils::findNearestSegmentIndex(points, target_point); +} + +bool checkHasSameLane( + const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelet & target_lane) +{ + if (lanelets.empty()) return false; + + const auto has_same = [&](const auto & ll) { return ll.id() == target_lane.id(); }; + return std::find_if(lanelets.begin(), lanelets.end(), has_same) != lanelets.end(); +} + +bool isSamePoint(const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2) +{ + constexpr double epsilon = 1e-3; + return std::abs(point1.x - point2.x) < epsilon && std::abs(point1.y - point2.y) < epsilon; +} + +geometry_msgs::msg::Point calcLongitudinalOffsetStartPoint( + const std::vector & points, const geometry_msgs::msg::Pose & pose, + const size_t nearest_segment_idx, const double offset) +{ + const double offset_length = + motion_utils::calcLongitudinalOffsetToSegment(points, nearest_segment_idx, pose.position); + const auto offset_point = + motion_utils::calcLongitudinalOffsetPoint(points, nearest_segment_idx, offset_length + offset); + + return offset_point ? offset_point.get() : points.at(nearest_segment_idx); +} + +geometry_msgs::msg::Point calcLongitudinalOffsetGoalPoint( + const std::vector & points, const geometry_msgs::msg::Pose & pose, + const size_t nearest_segment_idx, const double offset) +{ + const double offset_length = + motion_utils::calcLongitudinalOffsetToSegment(points, nearest_segment_idx, pose.position); + const auto offset_point = + motion_utils::calcLongitudinalOffsetPoint(points, nearest_segment_idx, offset_length + offset); + + return offset_point ? offset_point.get() : points.at(nearest_segment_idx + 1); +} +} // namespace + +namespace behavior_path_planner::utils::drivable_area_processing +{ +boost::optional> intersectBound( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, + const std::vector & bound, const size_t seg_idx1, + const size_t seg_idx2) +{ + const size_t start_idx = + static_cast(std::max(0, static_cast(std::min(seg_idx1, seg_idx2)) - 5)); + const size_t end_idx = static_cast(std::min( + static_cast(bound.size()) - 1, static_cast(std::max(seg_idx1, seg_idx2)) + 1 + 5)); + for (int i = start_idx; i < static_cast(end_idx); ++i) { + const auto intersect_point = + tier4_autoware_utils::intersect(p1, p2, bound.at(i), bound.at(i + 1)); + if (intersect_point) { + std::pair result; + result.first = static_cast(i); + result.second = *intersect_point; + return result; + } + } + return boost::none; +} + +double calcDistanceFromPointToSegment( + const geometry_msgs::msg::Point & segment_start_point, + const geometry_msgs::msg::Point & segment_end_point, + const geometry_msgs::msg::Point & target_point) +{ + const auto & a = segment_start_point; + const auto & b = segment_end_point; + const auto & p = target_point; + + const double dot_val = (b.x - a.x) * (p.x - a.x) + (b.y - a.y) * (p.y - a.y); + const double squared_segment_length = tier4_autoware_utils::calcSquaredDistance2d(a, b); + if (0 <= dot_val && dot_val <= squared_segment_length) { + const double numerator = std::abs((p.x - a.x) * (a.y - b.y) - (p.y - a.y) * (a.x - b.x)); + const double denominator = std::sqrt(std::pow(a.x - b.x, 2) + std::pow(a.y - b.y, 2)); + return numerator / denominator; + } + + // target_point is outside the segment. + return std::min( + tier4_autoware_utils::calcDistance2d(a, p), tier4_autoware_utils::calcDistance2d(b, p)); +} + +PolygonPoint transformBoundFrenetCoordinate( + const std::vector & bound_points, + const geometry_msgs::msg::Point & target_point) +{ + // NOTE: findNearestSegmentIndex cannot be used since a bound's interval is sometimes too large to + // find wrong nearest index. + std::vector dist_to_bound_segment_vec; + for (size_t i = 0; i < bound_points.size() - 1; ++i) { + const double dist_to_bound_segment = + calcDistanceFromPointToSegment(bound_points.at(i), bound_points.at(i + 1), target_point); + dist_to_bound_segment_vec.push_back(dist_to_bound_segment); + } + + const size_t min_dist_seg_idx = std::distance( + dist_to_bound_segment_vec.begin(), + std::min_element(dist_to_bound_segment_vec.begin(), dist_to_bound_segment_vec.end())); + const double lon_dist_to_segment = + motion_utils::calcLongitudinalOffsetToSegment(bound_points, min_dist_seg_idx, target_point); + const double lat_dist_to_segment = + motion_utils::calcLateralOffset(bound_points, target_point, min_dist_seg_idx); + return PolygonPoint{target_point, min_dist_seg_idx, lon_dist_to_segment, lat_dist_to_segment}; +} + +std::vector generatePolygonInsideBounds( + const std::vector & bound, const std::vector & edge_points, + const bool is_object_right) +{ + constexpr double invalid_lat_dist_to_bound = 10.0; + + std::vector full_polygon; + for (const auto & edge_point : edge_points) { + const auto polygon_point = transformBoundFrenetCoordinate(bound, edge_point); + + // check lat dist for U-turn roads. + if ( + (is_object_right && invalid_lat_dist_to_bound < polygon_point.lat_dist_to_bound) || + (!is_object_right && polygon_point.lat_dist_to_bound < -invalid_lat_dist_to_bound)) { + return {}; + } + full_polygon.push_back(polygon_point); + } + + // 1. check the case where the polygon intersects the bound + std::vector inside_poly; + bool has_intersection = false; // NOTE: between obstacle polygon and bound + for (int i = 0; i < static_cast(full_polygon.size()); ++i) { + const auto & curr_poly = full_polygon.at(i); + const auto & prev_poly = full_polygon.at(i == 0 ? full_polygon.size() - 1 : i - 1); + + const bool is_curr_outside = curr_poly.is_outside_bounds(is_object_right); + const bool is_prev_outside = prev_poly.is_outside_bounds(is_object_right); + + if (is_curr_outside && is_prev_outside) { + continue; + } + if (!is_curr_outside && !is_prev_outside) { + inside_poly.push_back(curr_poly); + continue; + } + + const auto intersection = intersectBound( + prev_poly.point, curr_poly.point, bound, prev_poly.bound_seg_idx, curr_poly.bound_seg_idx); + if (!intersection) { + continue; + } + const double lon_dist = motion_utils::calcLongitudinalOffsetToSegment( + bound, intersection->first, intersection->second); + const auto intersect_point = + PolygonPoint{intersection->second, intersection->first, lon_dist, 0.0}; + has_intersection = true; + + if (is_prev_outside && !is_curr_outside) { + inside_poly.push_back(intersect_point); + inside_poly.push_back(curr_poly); + continue; + } + // Here is if (!is_prev_outside && is_curr_outside). + inside_poly.push_back(prev_poly); + inside_poly.push_back(intersect_point); + continue; + } + if (has_intersection) { + return inside_poly; + } + + // 2. check the case where the polygon does not intersect the bound + const bool is_polygon_fully_inside_bounds = [&]() { + for (const auto & curr_poly : full_polygon) { + const bool is_curr_outside = curr_poly.is_outside_bounds(is_object_right); + if (is_curr_outside) { + return false; + } + } + return true; + }(); + if (is_polygon_fully_inside_bounds) { + return full_polygon; + } + + return std::vector{}; +} + +std::vector convertToGeometryPoints( + const std::vector & polygon_points) +{ + std::vector points; + points.reserve(polygon_points.size()); + + for (const auto & polygon_point : polygon_points) { + points.push_back(polygon_point.point); + } + return points; +} + +// NOTE: See the PR's figure. https://github.com/autowarefoundation/autoware.universe/pull/2880 +std::vector concatenateTwoPolygons( + const std::vector & front_polygon, const std::vector & back_polygon) +{ + const auto make_unique_polygon = [&](const auto & polygon) { + std::vector unique_polygon; + for (const auto & point : polygon) { + if (!unique_polygon.empty() && isSamePoint(unique_polygon.back().point, point.point)) { + continue; + } + unique_polygon.push_back(point); + } + return unique_polygon; + }; + const auto unique_front_polygon = make_unique_polygon(front_polygon); + const auto unique_back_polygon = make_unique_polygon(back_polygon); + + // At first, the front polygon is the outside polygon + bool is_front_polygon_outside = true; + size_t before_outside_idx = 0; + + const auto get_out_poly = [&]() { + return is_front_polygon_outside ? unique_front_polygon : unique_back_polygon; + }; + const auto get_in_poly = [&]() { + return is_front_polygon_outside ? unique_back_polygon : unique_front_polygon; + }; + + // NOTE: Polygon points is assumed to be clock-wise. + std::vector concatenated_polygon; + // NOTE: Maximum number of loop is set to avoid infinity loop calculation just in case. + const size_t max_loop_num = (unique_front_polygon.size() + unique_back_polygon.size()) * 2; + for (size_t loop_idx = 0; loop_idx < max_loop_num; ++loop_idx) { + concatenated_polygon.push_back(get_out_poly().at(before_outside_idx)); + if (before_outside_idx == get_out_poly().size() - 1) { + break; + } + const size_t curr_idx = before_outside_idx; + const size_t next_idx = before_outside_idx + 1; + + // NOTE: Two polygons may have two intersection points. Therefore the closest intersection + // point is used. + std::optional closest_idx = std::nullopt; + double min_dist_to_intersection = std::numeric_limits::max(); + PolygonPoint closest_intersect_point; + for (size_t i = 0; i < get_in_poly().size() - 1; ++i) { + const auto intersection = tier4_autoware_utils::intersect( + get_out_poly().at(curr_idx).point, get_out_poly().at(next_idx).point, + get_in_poly().at(i).point, get_in_poly().at(i + 1).point); + if (!intersection) { + continue; + } + if ( + isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i).point) || + isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i + 1).point) || + isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i).point) || + isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i + 1).point)) { + // NOTE: If the segments shares one point, the while loop will not end. + continue; + } + + const auto intersect_point = PolygonPoint{*intersection, 0, 0.0, 0.0}; + const double dist_to_intersection = + tier4_autoware_utils::calcDistance2d(get_out_poly().at(curr_idx).point, *intersection); + if (dist_to_intersection < min_dist_to_intersection) { + closest_idx = i; + min_dist_to_intersection = dist_to_intersection; + closest_intersect_point = intersect_point; + } + } + + if (closest_idx) { + before_outside_idx = *closest_idx; + concatenated_polygon.push_back(closest_intersect_point); + is_front_polygon_outside = !is_front_polygon_outside; + } + + before_outside_idx += 1; + + if (loop_idx == max_loop_num - 1) { + return front_polygon; + } + } + + return concatenated_polygon; +} + +std::vector> concatenatePolygons( + const std::vector> & polygons) +{ + auto unique_polygons = polygons; + + while (rclcpp::ok()) { + bool is_updated = false; + + for (size_t i = 0; i < unique_polygons.size(); ++i) { + for (size_t j = 0; j < i; ++j) { + const auto & p1 = unique_polygons.at(i); + const auto & p2 = unique_polygons.at(j); + + // if p1 and p2 overlaps + if (p1.back().is_after(p2.front()) && p2.back().is_after(p1.front())) { + is_updated = true; + + const auto concatenated_polygon = [&]() { + if (p2.front().is_after(p1.front())) { + return concatenateTwoPolygons(p1, p2); + } + return concatenateTwoPolygons(p2, p1); + }(); + + // NOTE: remove i's element first since is larger than j. + unique_polygons.erase(unique_polygons.begin() + i); + unique_polygons.erase(unique_polygons.begin() + j); + + unique_polygons.push_back(concatenated_polygon); + break; + } + } + if (is_updated) { + break; + } + } + + if (!is_updated) { + break; + } + } + return unique_polygons; +} + +std::vector getPolygonPointsInsideBounds( + const std::vector & bound, const std::vector & edge_points, + const bool is_object_right) +{ + // NOTE: Polygon is defined at lest by three points. + if (edge_points.size() < 3) { + return std::vector(); + } + + // convert to vector of PolygonPoint + const auto inside_polygon = [&]() { + auto tmp_polygon = generatePolygonInsideBounds(bound, edge_points, is_object_right); + + // In order to make the order of points the same as the order of lon_dist_to_segment. + // The order of points is clockwise. + if (!is_object_right) { + std::reverse(tmp_polygon.begin(), tmp_polygon.end()); + } + return tmp_polygon; + }(); + if (inside_polygon.empty()) { + return std::vector(); + } + + // search start and end index by longitudinal distance + std::vector polygon_indices(inside_polygon.size()); + std::iota(polygon_indices.begin(), polygon_indices.end(), 0); + std::sort(polygon_indices.begin(), polygon_indices.end(), [&](int i1, int i2) { + return inside_polygon.at(i2).is_after(inside_polygon.at(i1)); + }); + const int start_idx = polygon_indices.front(); + const int end_idx = polygon_indices.back(); + + // calculate valid inside polygon + std::vector valid_inside_polygon; + for (int i = 0; i < (end_idx - start_idx + static_cast(polygon_indices.size())) % + static_cast(polygon_indices.size()) + + 1; + ++i) { + const int poly_idx = (start_idx + i) % static_cast(inside_polygon.size()); + valid_inside_polygon.push_back(inside_polygon.at(poly_idx)); + } + + // add start and end points projected to bound if necessary + if (inside_polygon.at(start_idx).lat_dist_to_bound != 0.0) { // not on bound + auto start_point = inside_polygon.at(start_idx); + const auto start_point_on_bound = motion_utils::calcLongitudinalOffsetPoint( + bound, start_point.bound_seg_idx, start_point.lon_dist_to_segment); + if (start_point_on_bound) { + start_point.point = start_point_on_bound.get(); + valid_inside_polygon.insert(valid_inside_polygon.begin(), start_point); + } + } + if (inside_polygon.at(end_idx).lat_dist_to_bound != 0.0) { // not on bound + auto end_point = inside_polygon.at(end_idx); + const auto end_point_on_bound = motion_utils::calcLongitudinalOffsetPoint( + bound, end_point.bound_seg_idx, end_point.lon_dist_to_segment); + if (end_point_on_bound) { + end_point.point = end_point_on_bound.get(); + valid_inside_polygon.insert(valid_inside_polygon.end(), end_point); + } + } + return valid_inside_polygon; +} + +std::vector updateBoundary( + const std::vector & original_bound, + const std::vector> & sorted_polygons) +{ + if (sorted_polygons.empty()) { + return original_bound; + } + + auto reversed_polygons = sorted_polygons; + std::reverse(reversed_polygons.begin(), reversed_polygons.end()); + + auto updated_bound = original_bound; + + // NOTE: Further obstacle is applied first since a part of the updated_bound is erased. + for (const auto & polygon : reversed_polygons) { + const auto & start_poly = polygon.front(); + const auto & end_poly = polygon.back(); + + const double front_offset = motion_utils::calcLongitudinalOffsetToSegment( + updated_bound, start_poly.bound_seg_idx, start_poly.point); + + const size_t removed_start_idx = + 0 < front_offset ? start_poly.bound_seg_idx + 1 : start_poly.bound_seg_idx; + const size_t removed_end_idx = end_poly.bound_seg_idx; + + updated_bound.erase( + updated_bound.begin() + removed_start_idx, updated_bound.begin() + removed_end_idx + 1); + + const auto obj_points = convertToGeometryPoints(polygon); + updated_bound.insert( + updated_bound.begin() + removed_start_idx, obj_points.begin(), obj_points.end()); + } + return updated_bound; +} + +[[maybe_unused]] geometry_msgs::msg::Point calcCenterOfGeometry(const Polygon2d & obj_poly) +{ + geometry_msgs::msg::Point center_pos; + for (const auto & point : obj_poly.outer()) { + center_pos.x += point.x(); + center_pos.y += point.y(); + } + + center_pos.x = center_pos.x / obj_poly.outer().size(); + center_pos.y = center_pos.y / obj_poly.outer().size(); + center_pos.z = center_pos.z / obj_poly.outer().size(); + + return center_pos; +} +} // namespace behavior_path_planner::utils::drivable_area_processing + +namespace behavior_path_planner::utils +{ +using tier4_autoware_utils::Point2d; + +boost::optional getOverlappedLaneletId(const std::vector & lanes) +{ + auto overlaps = [](const DrivableLanes & lanes, const DrivableLanes & target_lanes) { + const auto lanelets = utils::transformToLanelets(lanes); + const auto target_lanelets = utils::transformToLanelets(target_lanes); + + for (const auto & lanelet : lanelets) { + for (const auto & target_lanelet : target_lanelets) { + std::vector intersections{}; + boost::geometry::intersection( + lanelet.polygon2d().basicPolygon(), target_lanelet.polygon2d().basicPolygon(), + intersections); + + // if only one point intersects, it is assumed not to be overlapped + if (intersections.size() > 1) { + return true; + } + } + } + + // No overlapping + return false; + }; + + if (lanes.size() <= 2) { + return {}; + } + + size_t overlapped_idx = lanes.size(); + for (size_t i = 0; i < lanes.size() - 2; ++i) { + for (size_t j = i + 2; j < lanes.size(); ++j) { + if (overlaps(lanes.at(i), lanes.at(j))) { + overlapped_idx = std::min(overlapped_idx, j); + } + } + } + + if (overlapped_idx == lanes.size()) { + return {}; + } + + return overlapped_idx; +} + +std::vector cutOverlappedLanes( + PathWithLaneId & path, const std::vector & lanes) +{ + const auto overlapped_lanelet_idx = getOverlappedLaneletId(lanes); + if (!overlapped_lanelet_idx) { + return lanes; + } + + std::vector shorten_lanes{lanes.begin(), lanes.begin() + *overlapped_lanelet_idx}; + const auto shorten_lanelets = utils::transformToLanelets(shorten_lanes); + + const auto original_points = path.points; + + path.points.clear(); + + const auto has_same_id_lane = [](const auto & lanelet, const auto & p) { + return std::any_of(p.lane_ids.begin(), p.lane_ids.end(), [&lanelet](const auto id) { + return lanelet.id() == id; + }); + }; + + const auto has_same_id_lanes = [&has_same_id_lane](const auto & lanelets, const auto & p) { + return std::any_of( + lanelets.begin(), lanelets.end(), + [&has_same_id_lane, &p](const auto & lanelet) { return has_same_id_lane(lanelet, p); }); + }; + + // Step1. find first path point within drivable lanes + size_t start_point_idx = std::numeric_limits::max(); + for (const auto & lanes : shorten_lanes) { + for (size_t i = 0; i < original_points.size(); ++i) { + // check right lane + if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); + } + + // check left lane + if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); + } + + // check middle lanes + if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { + start_point_idx = std::min(start_point_idx, i); + } + } + } + + // Step2. pick up only path points within drivable lanes + for (const auto & lanes : shorten_lanes) { + for (size_t i = start_point_idx; i < original_points.size(); ++i) { + // check right lane + if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; + } + + // check left lane + if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; + } + + // check middle lanes + if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { + path.points.push_back(original_points.at(i)); + continue; + } + + start_point_idx = i; + break; + } + } + + return shorten_lanes; +} + +std::vector generateDrivableLanes(const lanelet::ConstLanelets & lanes) +{ + std::vector drivable_lanes(lanes.size()); + for (size_t i = 0; i < lanes.size(); ++i) { + drivable_lanes.at(i).left_lane = lanes.at(i); + drivable_lanes.at(i).right_lane = lanes.at(i); + } + return drivable_lanes; +} + +std::vector generateDrivableLanesWithShoulderLanes( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes) +{ + std::vector drivable_lanes; + for (const auto & current_lane : current_lanes) { + DrivableLanes drivable_lane; + + const auto right_lane = utils::getRightLanelet(current_lane, shoulder_lanes); + const auto left_lane = utils::getLeftLanelet(current_lane, shoulder_lanes); + + if (right_lane && left_lane) { + drivable_lane.right_lane = *right_lane; + drivable_lane.left_lane = *left_lane; + drivable_lane.middle_lanes.push_back(current_lane); + } else if (right_lane) { + drivable_lane.right_lane = *right_lane; + drivable_lane.left_lane = current_lane; + } else if (left_lane) { + drivable_lane.right_lane = current_lane; + drivable_lane.left_lane = *left_lane; + } else { + drivable_lane.right_lane = current_lane; + drivable_lane.left_lane = current_lane; + } + + drivable_lanes.push_back(drivable_lane); + } + + return drivable_lanes; +} + +std::vector getNonOverlappingExpandedLanes( + PathWithLaneId & path, const std::vector & lanes, + const DrivableAreaExpansionParameters & parameters) +{ + const auto shorten_lanes = cutOverlappedLanes(path, lanes); + return utils::expandLanelets( + shorten_lanes, parameters.drivable_area_left_bound_offset, + parameters.drivable_area_right_bound_offset, parameters.drivable_area_types_to_skip); +} + +void generateDrivableArea( + PathWithLaneId & path, const std::vector & lanes, + const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, + const double vehicle_length, const std::shared_ptr planner_data, + const bool is_driving_forward) +{ + // extract data + const auto transformed_lanes = utils::transformToLanelets(lanes); + const auto current_pose = planner_data->self_odometry->pose.pose; + const auto route_handler = planner_data->route_handler; + constexpr double overlap_threshold = 0.01; + + if (path.points.empty()) { + return; + } + + auto addPoints = + [](const lanelet::ConstLineString3d & points, std::vector & bound) { + for (const auto & bound_p : points) { + const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p); + if (bound.empty()) { + bound.push_back(cp); + } else if (tier4_autoware_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { + bound.push_back(cp); + } + } + }; + + const auto has_overlap = + [&](const lanelet::ConstLanelet & lane, const lanelet::ConstLanelets & ignore_lanelets = {}) { + for (const auto & transformed_lane : transformed_lanes) { + if (checkHasSameLane(ignore_lanelets, transformed_lane)) { + continue; + } + if (boost::geometry::intersects( + lane.polygon2d().basicPolygon(), transformed_lane.polygon2d().basicPolygon())) { + return true; + } + } + return false; + }; + + // Insert Position + auto left_bound = calcBound( + route_handler, lanes, enable_expanding_hatched_road_markings, + enable_expanding_intersection_areas, true); + auto right_bound = calcBound( + route_handler, lanes, enable_expanding_hatched_road_markings, + enable_expanding_intersection_areas, false); + + if (left_bound.empty() || right_bound.empty()) { + auto clock{rclcpp::Clock{RCL_ROS_TIME}}; + RCLCPP_ERROR_STREAM_THROTTLE( + rclcpp::get_logger("behavior_path_planner").get_child("utils"), clock, 1000, + "The right or left bound of drivable area is empty"); + return; + } + + // Insert points after goal + lanelet::ConstLanelet goal_lanelet; + if ( + route_handler->getGoalLanelet(&goal_lanelet) && + checkHasSameLane(transformed_lanes, goal_lanelet)) { + const auto lanes_after_goal = route_handler->getLanesAfterGoal(vehicle_length); + const auto next_lanes_after_goal = route_handler->getNextLanelets(goal_lanelet); + const auto goal_left_lanelet = route_handler->getLeftLanelet(goal_lanelet); + const auto goal_right_lanelet = route_handler->getRightLanelet(goal_lanelet); + lanelet::ConstLanelets goal_lanelets = {goal_lanelet}; + if (goal_left_lanelet) { + goal_lanelets.push_back(*goal_left_lanelet); + } + if (goal_right_lanelet) { + goal_lanelets.push_back(*goal_right_lanelet); + } + + for (const auto & lane : lanes_after_goal) { + // If lane is already in the transformed lanes, ignore it + if (checkHasSameLane(transformed_lanes, lane)) { + continue; + } + // Check if overlapped + const bool is_overlapped = + (checkHasSameLane(next_lanes_after_goal, lane) ? has_overlap(lane, goal_lanelets) + : has_overlap(lane)); + if (is_overlapped) { + continue; + } + + addPoints(lane.leftBound3d(), left_bound); + addPoints(lane.rightBound3d(), right_bound); + } + } + + if (!is_driving_forward) { + std::reverse(left_bound.begin(), left_bound.end()); + std::reverse(right_bound.begin(), right_bound.end()); + } + + path.left_bound.clear(); + path.right_bound.clear(); + + const auto [left_start_idx, right_start_idx] = [&]() { + const size_t current_seg_idx = planner_data->findEgoSegmentIndex(path.points); + const auto cropped_path_points = motion_utils::cropPoints( + path.points, current_pose.position, current_seg_idx, + planner_data->parameters.forward_path_length, + planner_data->parameters.backward_path_length + planner_data->parameters.input_path_interval); + + constexpr double front_length = 0.5; + const auto front_pose = + cropped_path_points.empty() ? current_pose : cropped_path_points.front().point.pose; + const size_t front_left_start_idx = + findNearestSegmentIndexFromLateralDistance(left_bound, front_pose.position); + const size_t front_right_start_idx = + findNearestSegmentIndexFromLateralDistance(right_bound, front_pose.position); + const auto left_start_point = + calcLongitudinalOffsetStartPoint(left_bound, front_pose, front_left_start_idx, -front_length); + const auto right_start_point = calcLongitudinalOffsetStartPoint( + right_bound, front_pose, front_right_start_idx, -front_length); + const size_t left_start_idx = + findNearestSegmentIndexFromLateralDistance(left_bound, left_start_point); + const size_t right_start_idx = + findNearestSegmentIndexFromLateralDistance(right_bound, right_start_point); + + // Insert a start point + path.left_bound.push_back(left_start_point); + path.right_bound.push_back(right_start_point); + + return std::make_pair(left_start_idx, right_start_idx); + }(); + + // Get Closest segment for the goal point + const auto goal_pose = path.points.empty() ? current_pose : path.points.back().point.pose; + const size_t goal_left_start_idx = + findNearestSegmentIndexFromLateralDistance(left_bound, goal_pose.position); + const size_t goal_right_start_idx = + findNearestSegmentIndexFromLateralDistance(right_bound, goal_pose.position); + const auto left_goal_point = + calcLongitudinalOffsetGoalPoint(left_bound, goal_pose, goal_left_start_idx, vehicle_length); + const auto right_goal_point = + calcLongitudinalOffsetGoalPoint(right_bound, goal_pose, goal_right_start_idx, vehicle_length); + const size_t left_goal_idx = std::max( + goal_left_start_idx, findNearestSegmentIndexFromLateralDistance(left_bound, left_goal_point)); + const size_t right_goal_idx = std::max( + goal_right_start_idx, + findNearestSegmentIndexFromLateralDistance(right_bound, right_goal_point)); + + // Insert middle points + for (size_t i = left_start_idx + 1; i <= left_goal_idx; ++i) { + const auto & next_point = left_bound.at(i); + const double dist = tier4_autoware_utils::calcDistance2d(path.left_bound.back(), next_point); + if (dist > overlap_threshold) { + path.left_bound.push_back(next_point); + } + } + for (size_t i = right_start_idx + 1; i <= right_goal_idx; ++i) { + const auto & next_point = right_bound.at(i); + const double dist = tier4_autoware_utils::calcDistance2d(path.right_bound.back(), next_point); + if (dist > overlap_threshold) { + path.right_bound.push_back(next_point); + } + } + + // Insert a goal point + if ( + tier4_autoware_utils::calcDistance2d(path.left_bound.back(), left_goal_point) > + overlap_threshold) { + path.left_bound.push_back(left_goal_point); + } + if ( + tier4_autoware_utils::calcDistance2d(path.right_bound.back(), right_goal_point) > + overlap_threshold) { + path.right_bound.push_back(right_goal_point); + } + const auto & expansion_params = planner_data->drivable_area_expansion_parameters; + if (expansion_params.enabled) { + drivable_area_expansion::expand_drivable_area(path, planner_data); + } + + // make bound longitudinally monotonic + // TODO(Murooka) Fix makeBoundLongitudinallyMonotonic + if ( + is_driving_forward && + (enable_expanding_hatched_road_markings || enable_expanding_intersection_areas)) { + makeBoundLongitudinallyMonotonic(path, planner_data, true); // for left bound + makeBoundLongitudinallyMonotonic(path, planner_data, false); // for right bound + } +} + +void generateDrivableArea( + PathWithLaneId & path, const double vehicle_length, const double offset, + const bool is_driving_forward) +{ + using tier4_autoware_utils::calcOffsetPose; + + // remove path points which is close to the previous point + PathWithLaneId resampled_path{}; + const double resample_interval = 2.0; + for (size_t i = 0; i < path.points.size(); ++i) { + if (i == 0) { + resampled_path.points.push_back(path.points.at(i)); + } else { + const auto & prev_point = resampled_path.points.back().point.pose.position; + const auto & curr_point = path.points.at(i).point.pose.position; + const double signed_arc_length = + motion_utils::calcSignedArcLength(path.points, prev_point, curr_point); + if (signed_arc_length > resample_interval) { + resampled_path.points.push_back(path.points.at(i)); + } + } + } + // add last point of path if enough far from the one of resampled path + constexpr double th_last_point_distance = 0.3; + if ( + tier4_autoware_utils::calcDistance2d( + resampled_path.points.back().point.pose.position, path.points.back().point.pose.position) > + th_last_point_distance) { + resampled_path.points.push_back(path.points.back()); + } + + // create bound point by calculating offset point + std::vector left_bound; + std::vector right_bound; + for (const auto & point : resampled_path.points) { + const auto & pose = point.point.pose; + + const auto left_point = calcOffsetPose(pose, 0, offset, 0); + const auto right_point = calcOffsetPose(pose, 0, -offset, 0); + + left_bound.push_back(left_point.position); + right_bound.push_back(right_point.position); + } + + if (is_driving_forward) { + // add backward offset point to bound + const Pose first_point = + calcOffsetPose(resampled_path.points.front().point.pose, -vehicle_length, 0, 0); + const Pose left_first_point = calcOffsetPose(first_point, 0, offset, 0); + const Pose right_first_point = calcOffsetPose(first_point, 0, -offset, 0); + left_bound.insert(left_bound.begin(), left_first_point.position); + right_bound.insert(right_bound.begin(), right_first_point.position); + + // add forward offset point to bound + const Pose last_point = + calcOffsetPose(resampled_path.points.back().point.pose, vehicle_length, 0, 0); + const Pose left_last_point = calcOffsetPose(last_point, 0, offset, 0); + const Pose right_last_point = calcOffsetPose(last_point, 0, -offset, 0); + left_bound.push_back(left_last_point.position); + right_bound.push_back(right_last_point.position); + } else { + // add forward offset point to bound + const Pose first_point = + calcOffsetPose(resampled_path.points.front().point.pose, vehicle_length, 0, 0); + const Pose left_first_point = calcOffsetPose(first_point, 0, offset, 0); + const Pose right_first_point = calcOffsetPose(first_point, 0, -offset, 0); + left_bound.insert(left_bound.begin(), left_first_point.position); + right_bound.insert(right_bound.begin(), right_first_point.position); + + // add backward offset point to bound + const Pose last_point = + calcOffsetPose(resampled_path.points.back().point.pose, -vehicle_length, 0, 0); + const Pose left_last_point = calcOffsetPose(last_point, 0, offset, 0); + const Pose right_last_point = calcOffsetPose(last_point, 0, -offset, 0); + left_bound.push_back(left_last_point.position); + right_bound.push_back(right_last_point.position); + } + + if (left_bound.empty() || right_bound.empty()) { + return; + } + + // fix intersected bound + // if bound is intersected, remove them and insert intersection point + typedef boost::geometry::model::d2::point_xy BoostPoint; + typedef boost::geometry::model::linestring LineString; + auto modify_bound_intersection = [](const std::vector & bound) { + const double intersection_check_distance = 10.0; + std::vector modified_bound; + size_t i = 0; + while (i < bound.size() - 1) { + BoostPoint p1(bound.at(i).x, bound.at(i).y); + BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); + LineString p_line; + p_line.push_back(p1); + p_line.push_back(p2); + bool intersection_found = false; + for (size_t j = i + 2; j < bound.size() - 1; j++) { + const double distance = tier4_autoware_utils::calcDistance2d(bound.at(i), bound.at(j)); + if (distance > intersection_check_distance) { + break; + } + LineString q_line; + BoostPoint q1(bound.at(j).x, bound.at(j).y); + BoostPoint q2(bound.at(j + 1).x, bound.at(j + 1).y); + q_line.push_back(q1); + q_line.push_back(q2); + std::vector intersection_points; + boost::geometry::intersection(p_line, q_line, intersection_points); + if (intersection_points.size() > 0) { + modified_bound.push_back(bound.at(i)); + Point intersection_point; + intersection_point.x = intersection_points.at(0).x(); + intersection_point.y = intersection_points.at(0).y(); + modified_bound.push_back(intersection_point); + i = j + 1; + intersection_found = true; + break; + } + } + if (!intersection_found) { + modified_bound.push_back(bound.at(i)); + i++; + } + } + modified_bound.push_back(bound.back()); + return modified_bound; + }; + std::vector modified_left_bound = modify_bound_intersection(left_bound); + std::vector modified_right_bound = modify_bound_intersection(right_bound); + + // set bound to path + path.left_bound = modified_left_bound; + path.right_bound = modified_right_bound; +} + +// TODO(Azu) Some parts of is the same with generateCenterLinePath. Therefore it might be better if +// we can refactor some of the code for better readability +lanelet::ConstLineStrings3d getMaximumDrivableArea( + const std::shared_ptr & planner_data) +{ + const auto & p = planner_data->parameters; + const auto & route_handler = planner_data->route_handler; + const auto & ego_pose = planner_data->self_odometry->pose.pose; + + lanelet::ConstLanelet current_lane; + if (!route_handler->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { + RCLCPP_ERROR( + rclcpp::get_logger("behavior_path_planner").get_child("utils"), + "failed to find closest lanelet within route!!!"); + return {}; + } + + const auto current_lanes = route_handler->getLaneletSequence( + current_lane, ego_pose, p.backward_path_length, p.forward_path_length); + lanelet::ConstLineStrings3d linestring_shared; + for (const auto & lane : current_lanes) { + lanelet::ConstLineStrings3d furthest_line = route_handler->getFurthestLinestring(lane); + linestring_shared.insert(linestring_shared.end(), furthest_line.begin(), furthest_line.end()); + } + + return linestring_shared; +} + +std::vector expandLanelets( + const std::vector & drivable_lanes, const double left_bound_offset, + const double right_bound_offset, const std::vector & types_to_skip) +{ + if (left_bound_offset == 0.0 && right_bound_offset == 0.0) return drivable_lanes; + + std::vector expanded_drivable_lanes{}; + expanded_drivable_lanes.reserve(drivable_lanes.size()); + for (const auto & lanes : drivable_lanes) { + const std::string l_type = + lanes.left_lane.leftBound().attributeOr(lanelet::AttributeName::Type, "none"); + const std::string r_type = + lanes.right_lane.rightBound().attributeOr(lanelet::AttributeName::Type, "none"); + + const bool l_skip = + std::find(types_to_skip.begin(), types_to_skip.end(), l_type) != types_to_skip.end(); + const bool r_skip = + std::find(types_to_skip.begin(), types_to_skip.end(), r_type) != types_to_skip.end(); + const double l_offset = l_skip ? 0.0 : left_bound_offset; + const double r_offset = r_skip ? 0.0 : -right_bound_offset; + + DrivableLanes expanded_lanes; + if (lanes.left_lane.id() == lanes.right_lane.id()) { + expanded_lanes.left_lane = + lanelet::utils::getExpandedLanelet(lanes.left_lane, l_offset, r_offset); + expanded_lanes.right_lane = + lanelet::utils::getExpandedLanelet(lanes.right_lane, l_offset, r_offset); + } else { + expanded_lanes.left_lane = lanelet::utils::getExpandedLanelet(lanes.left_lane, l_offset, 0.0); + expanded_lanes.right_lane = + lanelet::utils::getExpandedLanelet(lanes.right_lane, 0.0, r_offset); + } + expanded_lanes.middle_lanes = lanes.middle_lanes; + expanded_drivable_lanes.push_back(expanded_lanes); + } + return expanded_drivable_lanes; +} + +// NOTE: Assuming that path.right/left_bound is already created. +void extractObstaclesFromDrivableArea( + PathWithLaneId & path, const std::vector & obstacles) +{ + if (obstacles.empty()) { + return; + } + + std::vector> right_polygons; + std::vector> left_polygons; + for (const auto & obstacle : obstacles) { + const auto & obj_pos = obstacle.pose.position; + + // get edge points of the object + const size_t nearest_path_idx = + motion_utils::findNearestIndex(path.points, obj_pos); // to get z for object polygon + std::vector edge_points; + for (size_t i = 0; i < obstacle.poly.outer().size() - 1; + ++i) { // NOTE: There is a duplicated points + edge_points.push_back(tier4_autoware_utils::createPoint( + obstacle.poly.outer().at(i).x(), obstacle.poly.outer().at(i).y(), + path.points.at(nearest_path_idx).point.pose.position.z)); + } + + // get a boundary that we have to change + const bool is_object_right = !obstacle.is_left; + const auto & bound = is_object_right ? path.right_bound : path.left_bound; + + // get polygon points inside the bounds + const auto inside_polygon = + drivable_area_processing::getPolygonPointsInsideBounds(bound, edge_points, is_object_right); + if (!inside_polygon.empty()) { + if (is_object_right) { + right_polygons.push_back(inside_polygon); + } else { + left_polygons.push_back(inside_polygon); + } + } + } + + for (const bool is_object_right : {true, false}) { + const auto & polygons = is_object_right ? right_polygons : left_polygons; + if (polygons.empty()) { + continue; + } + + // concatenate polygons if they are longitudinal overlapped. + auto unique_polygons = drivable_area_processing::concatenatePolygons(polygons); + + // sort bounds longitudinally + std::sort( + unique_polygons.begin(), unique_polygons.end(), + [](const std::vector & p1, const std::vector & p2) { + return p2.front().is_after(p1.front()); + }); + + // update boundary + auto & bound = is_object_right ? path.right_bound : path.left_bound; + bound = drivable_area_processing::updateBoundary(bound, unique_polygons); + } +} + +std::vector getBoundWithHatchedRoadMarkings( + const std::vector & original_bound, + const std::shared_ptr & route_handler) +{ + // a function to get polygon with a designated point id + const auto get_corresponding_polygon_index = + [&](const auto & polygon, const auto & target_point_id) { + for (size_t poly_point_idx = 0; poly_point_idx < polygon.size(); ++poly_point_idx) { + if (polygon[poly_point_idx].id() == target_point_id) { + // NOTE: If there are duplicated points in polygon, the early one will be returned. + return poly_point_idx; + } + } + // This means calculation has some errors. + return polygon.size() - 1; + }; + + const auto mod = [&](const int a, const int b) { + return (a + b) % b; // NOTE: consider negative value + }; + + std::vector expanded_bound{}; + + std::optional current_polygon{std::nullopt}; + std::vector current_polygon_border_indices; + // expand drivable area by hatched road markings. + for (size_t bound_point_idx = 0; bound_point_idx < original_bound.size(); ++bound_point_idx) { + const auto & bound_point = original_bound[bound_point_idx]; + const auto polygon = getPolygonByPoint(route_handler, bound_point, "hatched_road_markings"); + + bool will_close_polygon{false}; + if (!current_polygon) { + if (!polygon) { + expanded_bound.push_back(bound_point); + } else { + // There is a new additional polygon to expand + current_polygon = polygon; + current_polygon_border_indices.push_back( + get_corresponding_polygon_index(*current_polygon, bound_point.id())); + } + } else { + if (!polygon) { + will_close_polygon = true; + } else { + current_polygon_border_indices.push_back( + get_corresponding_polygon_index(*current_polygon, bound_point.id())); + } + } + + if (bound_point_idx == original_bound.size() - 1 && current_polygon) { + // If drivable lanes ends earlier than polygon, close the polygon + will_close_polygon = true; + } + + if (will_close_polygon) { + // The current additional polygon ends to expand + if (current_polygon_border_indices.size() == 1) { + expanded_bound.push_back((*current_polygon)[current_polygon_border_indices.front()]); + } else { + const size_t current_polygon_points_num = current_polygon->size(); + const bool is_polygon_opposite_direction = [&]() { + const size_t modulo_diff = mod( + static_cast(current_polygon_border_indices[1]) - + static_cast(current_polygon_border_indices[0]), + current_polygon_points_num); + return modulo_diff == 1; + }(); + + const int target_points_num = + current_polygon_points_num - current_polygon_border_indices.size() + 1; + for (int poly_idx = 0; poly_idx <= target_points_num; ++poly_idx) { + const int target_poly_idx = current_polygon_border_indices.front() + + poly_idx * (is_polygon_opposite_direction ? -1 : 1); + expanded_bound.push_back( + (*current_polygon)[mod(target_poly_idx, current_polygon_points_num)]); + } + } + current_polygon = std::nullopt; + current_polygon_border_indices.clear(); + } + } + + return expanded_bound; +} + +std::vector getBoundWithIntersectionAreas( + const std::vector & original_bound, + const std::shared_ptr & route_handler, + const std::vector & drivable_lanes, const bool is_left) +{ + const auto extract_bound_from_polygon = + [](const auto & polygon, const auto start_idx, const auto end_idx, const auto clockwise) { + std::vector ret{}; + for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) { + ret.push_back(polygon[i]); + + if (i + 1 == polygon.size() && clockwise) { + if (end_idx == 0) { + ret.push_back(polygon[end_idx]); + return ret; + } + i = 0; + continue; + } + + if (i == 0 && !clockwise) { + if (end_idx == polygon.size() - 1) { + ret.push_back(polygon[end_idx]); + return ret; + } + i = polygon.size() - 1; + continue; + } + } + + ret.push_back(polygon[end_idx]); + + return ret; + }; + + std::vector expanded_bound = original_bound; + + // expand drivable area by using intersection area. + for (const auto & drivable_lane : drivable_lanes) { + const auto edge_lanelet = is_left ? drivable_lane.left_lane : drivable_lane.right_lane; + const auto lanelet_bound = is_left ? edge_lanelet.leftBound3d() : edge_lanelet.rightBound3d(); + + if (lanelet_bound.size() < 2) { + continue; + } + + const std::string id = edge_lanelet.attributeOr("intersection_area", "else"); + if (id == "else") { + continue; + } + + // Step1. extract intersection partial bound. + std::vector intersection_bound{}; + { + const auto polygon = + route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + + const auto is_clockwise_polygon = + boost::geometry::is_valid(lanelet::utils::to2D(polygon.basicPolygon())); + const auto is_clockwise_iteration = is_clockwise_polygon ? is_left : !is_left; + + const auto intersection_bound_itr_init = std::find_if( + polygon.begin(), polygon.end(), + [&lanelet_bound](const auto & p) { return p.id() == lanelet_bound.front().id(); }); + + const auto intersection_bound_itr_last = std::find_if( + polygon.begin(), polygon.end(), + [&lanelet_bound](const auto & p) { return p.id() == lanelet_bound.back().id(); }); + + if ( + intersection_bound_itr_init == polygon.end() || + intersection_bound_itr_last == polygon.end()) { + continue; + } + + // extract line strings between start_idx and end_idx. + const size_t start_idx = std::distance(polygon.begin(), intersection_bound_itr_init); + const size_t end_idx = std::distance(polygon.begin(), intersection_bound_itr_last); + + intersection_bound = + extract_bound_from_polygon(polygon, start_idx, end_idx, is_clockwise_iteration); + } + + // Step2. check shared bound point. + const auto shared_point_itr_init = + std::find_if(expanded_bound.begin(), expanded_bound.end(), [&](const auto & p) { + return std::any_of( + intersection_bound.begin(), intersection_bound.end(), + [&](const auto & point) { return point.id() == p.id(); }); + }); + + const auto shared_point_itr_last = + std::find_if(expanded_bound.rbegin(), expanded_bound.rend(), [&](const auto & p) { + return std::any_of( + intersection_bound.rbegin(), intersection_bound.rend(), + [&](const auto & point) { return point.id() == p.id(); }); + }); + + if ( + shared_point_itr_init == expanded_bound.end() || + shared_point_itr_last == expanded_bound.rend()) { + continue; + } + + // Step3. overwrite duplicate drivable bound by intersection bound. + { + const auto trim_point_itr_init = std::find_if( + intersection_bound.begin(), intersection_bound.end(), + [&](const auto & p) { return p.id() == shared_point_itr_init->id(); }); + + const auto trim_point_itr_last = std::find_if( + intersection_bound.begin(), intersection_bound.end(), + [&](const auto & p) { return p.id() == shared_point_itr_last->id(); }); + + if ( + trim_point_itr_init == intersection_bound.end() || + trim_point_itr_last == intersection_bound.end()) { + continue; + } + + // TODO(Satoshi OTA): remove this guard. + if ( + std::distance(intersection_bound.begin(), trim_point_itr_last) < + std::distance(intersection_bound.begin(), trim_point_itr_init)) { + continue; + } + + std::vector tmp_bound{}; + + tmp_bound.insert(tmp_bound.end(), expanded_bound.begin(), shared_point_itr_init); + tmp_bound.insert(tmp_bound.end(), trim_point_itr_init, trim_point_itr_last); + tmp_bound.insert( + tmp_bound.end(), std::next(shared_point_itr_last).base(), expanded_bound.end()); + + expanded_bound = tmp_bound; + } + } + + return expanded_bound; +} + +// calculate bounds from drivable lanes and hatched road markings +std::vector calcBound( + const std::shared_ptr route_handler, + const std::vector & drivable_lanes, + const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, + const bool is_left) +{ + // a function to convert drivable lanes to points without duplicated points + const auto convert_to_points = [&](const std::vector & drivable_lanes) { + constexpr double overlap_threshold = 0.01; + + std::vector points; + for (const auto & drivable_lane : drivable_lanes) { + const auto bound = + is_left ? drivable_lane.left_lane.leftBound3d() : drivable_lane.right_lane.rightBound3d(); + for (const auto & point : bound) { + if ( + points.empty() || + overlap_threshold < (points.back().basicPoint2d() - point.basicPoint2d()).norm()) { + points.push_back(point); + } + } + } + return points; + }; + + const auto to_ros_point = [](const std::vector & bound) { + std::vector ret{}; + std::for_each(bound.begin(), bound.end(), [&](const auto & p) { + ret.push_back(lanelet::utils::conversion::toGeomMsgPt(p)); + }); + return ret; + }; + + // Step1. create drivable bound from drivable lanes. + std::vector bound_points = convert_to_points(drivable_lanes); + + // Step2. if there is no drivable area defined by polygon, return original drivable bound. + if (!enable_expanding_hatched_road_markings && !enable_expanding_intersection_areas) { + return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); + } + + // Step3. if there are hatched road markings, expand drivable bound with the polygon. + if (enable_expanding_hatched_road_markings) { + bound_points = getBoundWithHatchedRoadMarkings(bound_points, route_handler); + } + + if (!enable_expanding_intersection_areas) { + return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); + } + + // Step4. if there are intersection areas, expand drivable bound with the polygon. + { + bound_points = + getBoundWithIntersectionAreas(bound_points, route_handler, drivable_lanes, is_left); + } + + return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); +} + +void makeBoundLongitudinallyMonotonic( + PathWithLaneId & path, const std::shared_ptr & planner_data, + const bool is_bound_left) +{ + using motion_utils::findNearestSegmentIndex; + using tier4_autoware_utils::calcAzimuthAngle; + using tier4_autoware_utils::calcDistance2d; + using tier4_autoware_utils::calcOffsetPose; + using tier4_autoware_utils::createQuaternionFromRPY; + using tier4_autoware_utils::getPoint; + using tier4_autoware_utils::getPose; + using tier4_autoware_utils::intersect; + using tier4_autoware_utils::normalizeRadian; + + const auto set_orientation = []( + auto & bound_with_pose, const auto idx, const auto & orientation) { + bound_with_pose.at(idx).orientation = orientation; + }; + + const auto get_intersect_idx = []( + const auto & bound_with_pose, const auto start_idx, + const auto & p1, const auto & p2) -> boost::optional { + std::vector> intersects; + for (size_t i = start_idx; i < bound_with_pose.size() - 1; i++) { + const auto opt_intersect = + intersect(p1, p2, bound_with_pose.at(i).position, bound_with_pose.at(i + 1).position); + + if (!opt_intersect) { + continue; + } + + intersects.emplace_back(i, *opt_intersect); + } + + if (intersects.empty()) { + return boost::none; + } + + std::sort(intersects.begin(), intersects.end(), [&](const auto & a, const auto & b) { + return calcDistance2d(p1, a.second) < calcDistance2d(p1, b.second); + }); + + return intersects.front().first; + }; + + const auto get_bound_with_pose = [&](const auto & bound_with_pose, const auto & path_points) { + auto ret = bound_with_pose; + + const double offset = is_bound_left ? 100.0 : -100.0; + + size_t start_bound_idx = 0; + + const size_t start_path_idx = + findNearestSegmentIndex(path_points, bound_with_pose.front().position); + + // append bound point with point + for (size_t i = start_path_idx + 1; i < path_points.size(); i++) { + const auto p_path_offset = calcOffsetPose(getPose(path_points.at(i)), 0.0, offset, 0.0); + const auto intersect_idx = get_intersect_idx( + bound_with_pose, start_bound_idx, getPoint(path_points.at(i)), getPoint(p_path_offset)); + + if (!intersect_idx) { + continue; + } + + if (i + 1 == path_points.size()) { + for (size_t j = intersect_idx.get(); j < bound_with_pose.size(); j++) { + if (j + 1 == bound_with_pose.size()) { + const auto yaw = + calcAzimuthAngle(bound_with_pose.at(j - 1).position, bound_with_pose.at(j).position); + set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); + } else { + const auto yaw = + calcAzimuthAngle(bound_with_pose.at(j).position, bound_with_pose.at(j + 1).position); + set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); + } + } + } else { + for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) { + set_orientation(ret, j, getPose(path_points.at(i)).orientation); + } + } + + constexpr size_t OVERLAP_CHECK_NUM = 3; + start_bound_idx = + intersect_idx.get() < OVERLAP_CHECK_NUM ? 0 : intersect_idx.get() - OVERLAP_CHECK_NUM; + } + + return ret; + }; + + const auto is_non_monotonic = [&]( + const auto & base_pose, const auto & point, + const auto is_points_left, const auto is_reverse) { + const auto p_transformed = tier4_autoware_utils::inverseTransformPoint(point, base_pose); + if (p_transformed.x < 0.0 && p_transformed.y > 0.0) { + return is_points_left && !is_reverse; + } + + if (p_transformed.x < 0.0 && p_transformed.y < 0.0) { + return !is_points_left && !is_reverse; + } + + if (p_transformed.x > 0.0 && p_transformed.y > 0.0) { + return is_points_left && is_reverse; + } + + if (p_transformed.x > 0.0 && p_transformed.y < 0.0) { + return !is_points_left && is_reverse; + } + + return false; + }; + + // define a function to remove non monotonic point on bound + const auto remove_non_monotonic_point = [&](const auto & bound_with_pose, const bool is_reverse) { + std::vector monotonic_bound; + + size_t bound_idx = 0; + while (true) { + monotonic_bound.push_back(bound_with_pose.at(bound_idx)); + + if (bound_idx + 1 == bound_with_pose.size()) { + break; + } + + // NOTE: is_bound_left is used instead of is_points_left since orientation of path point is + // opposite. + const double lat_offset = is_bound_left ? 100.0 : -100.0; + + const auto p_bound_1 = getPose(bound_with_pose.at(bound_idx)); + const auto p_bound_2 = getPose(bound_with_pose.at(bound_idx + 1)); + + const auto p_bound_offset = calcOffsetPose(p_bound_1, 0.0, lat_offset, 0.0); + + if (!is_non_monotonic(p_bound_1, p_bound_2.position, is_bound_left, is_reverse)) { + bound_idx++; + continue; + } + + // skip non monotonic points + for (size_t i = bound_idx + 1; i < bound_with_pose.size() - 1; ++i) { + const auto intersect_point = intersect( + p_bound_1.position, p_bound_offset.position, bound_with_pose.at(i).position, + bound_with_pose.at(i + 1).position); + + if (intersect_point) { + Pose pose; + pose.position = *intersect_point; + pose.position.z = bound_with_pose.at(i).position.z; + const auto yaw = calcAzimuthAngle(*intersect_point, bound_with_pose.at(i + 1).position); + pose.orientation = createQuaternionFromRPY(0.0, 0.0, yaw); + monotonic_bound.push_back(pose); + bound_idx = i; + break; + } + } + + bound_idx++; + } + + return monotonic_bound; + }; + + const auto remove_orientation = [](const auto & bound_with_pose) { + std::vector ret; + + ret.reserve(bound_with_pose.size()); + + std::for_each(bound_with_pose.begin(), bound_with_pose.end(), [&ret](const auto & p) { + ret.push_back(p.position); + }); + + return ret; + }; + + const auto remove_sharp_points = [](const auto & bound) { + if (bound.size() < 2) { + return bound; + } + + std::vector ret = bound; + auto itr = std::next(ret.begin()); + while (std::next(itr) != ret.end()) { + if (itr == ret.begin()) { + itr++; + continue; + } + + const auto p1 = *std::prev(itr); + const auto p2 = *itr; + const auto p3 = *std::next(itr); + + const std::vector vec_1to2 = {p2.x - p1.x, p2.y - p1.y, p2.z - p1.z}; + const std::vector vec_3to2 = {p2.x - p3.x, p2.y - p3.y, p2.z - p3.z}; + const auto product = + std::inner_product(vec_1to2.begin(), vec_1to2.end(), vec_3to2.begin(), 0.0); + + const auto dist_1to2 = tier4_autoware_utils::calcDistance3d(p1, p2); + const auto dist_3to2 = tier4_autoware_utils::calcDistance3d(p3, p2); + + constexpr double epsilon = 1e-3; + + // Remove overlapped point. + if (dist_1to2 < epsilon || dist_3to2 < epsilon) { + itr = std::prev(ret.erase(itr)); + continue; + } + + // If the angle between the points is sharper than 45 degrees, remove the middle point. + if (std::cos(M_PI_4) < product / dist_1to2 / dist_3to2 + epsilon) { + itr = std::prev(ret.erase(itr)); + continue; + } + + itr++; + } + + return ret; + }; + + const auto original_bound = is_bound_left ? path.left_bound : path.right_bound; + + if (path.points.empty()) { + return; + } + + if (original_bound.empty()) { + return; + } + + if (path.points.front().lane_ids.empty()) { + return; + } + + // step.1 create bound with pose vector. + std::vector original_bound_with_pose; + { + original_bound_with_pose.reserve(original_bound.size()); + + std::for_each(original_bound.begin(), original_bound.end(), [&](const auto & p) { + Pose pose; + pose.position = p; + original_bound_with_pose.push_back(pose); + }); + + for (size_t i = 0; i < original_bound_with_pose.size(); i++) { + if (i + 1 == original_bound_with_pose.size()) { + const auto yaw = calcAzimuthAngle( + original_bound_with_pose.at(i - 1).position, original_bound_with_pose.at(i).position); + set_orientation(original_bound_with_pose, i, createQuaternionFromRPY(0.0, 0.0, yaw)); + } else { + const auto yaw = calcAzimuthAngle( + original_bound_with_pose.at(i).position, original_bound_with_pose.at(i + 1).position); + set_orientation(original_bound_with_pose, i, createQuaternionFromRPY(0.0, 0.0, yaw)); + } + } + } + + // step.2 get base pose vector. + std::vector clipped_points; + { + const auto & route_handler = planner_data->route_handler; + const auto p = planner_data->parameters; + const auto start_id = path.points.front().lane_ids.front(); + const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id); + + const auto lanelet_sequence = + route_handler->getLaneletSequence(start_lane, p.backward_path_length, p.forward_path_length); + const auto centerline_path = getCenterLinePath( + *route_handler, lanelet_sequence, getPose(path.points.front()), p.backward_path_length, + p.forward_path_length, p); + + if (centerline_path.points.size() < 2) { + return; + } + + const auto ego_idx = planner_data->findEgoIndex(centerline_path.points); + const auto end_idx = findNearestSegmentIndex(centerline_path.points, original_bound.back()); + + if (ego_idx >= end_idx) { + return; + } + + clipped_points.insert( + clipped_points.end(), centerline_path.points.begin() + ego_idx, + centerline_path.points.begin() + end_idx + 1); + } + + if (clipped_points.empty()) { + return; + } + + // step.3 update bound pose by reference path pose. + const auto updated_bound_with_pose = + get_bound_with_pose(original_bound_with_pose, clipped_points); // for reverse + + // step.4 create remove monotonic points by forward direction. + auto half_monotonic_bound_with_pose = + remove_non_monotonic_point(updated_bound_with_pose, false); // for reverse + std::reverse(half_monotonic_bound_with_pose.begin(), half_monotonic_bound_with_pose.end()); + + // step.5 create remove monotonic points by backward direction. + auto full_monotonic_bound_with_pose = + remove_non_monotonic_point(half_monotonic_bound_with_pose, true); + std::reverse(full_monotonic_bound_with_pose.begin(), full_monotonic_bound_with_pose.end()); + + // step.6 remove orientation from bound with pose. + auto full_monotonic_bound = remove_orientation(full_monotonic_bound_with_pose); + + // step.7 remove sharp bound points. + if (is_bound_left) { + path.left_bound = remove_sharp_points(full_monotonic_bound); + } else { + path.right_bound = remove_sharp_points(full_monotonic_bound); + } +} + +std::vector combineDrivableLanes( + const std::vector & original_drivable_lanes_vec, + const std::vector & new_drivable_lanes_vec) +{ + const auto has_same_lane = + [](const lanelet::ConstLanelet & target_lane, const lanelet::ConstLanelets & lanes) { + return std::find_if(lanes.begin(), lanes.end(), [&](const auto & ll) { + return ll.id() == target_lane.id(); + }) != lanes.end(); + }; + + const auto convert_to_lanes = [](const DrivableLanes & drivable_lanes) { + auto lanes = drivable_lanes.middle_lanes; + lanes.push_back(drivable_lanes.right_lane); + lanes.push_back(drivable_lanes.left_lane); + return lanes; + }; + + auto updated_drivable_lanes_vec = original_drivable_lanes_vec; + size_t new_drivable_lanes_idx = 0; + for (auto & updated_drivable_lanes : updated_drivable_lanes_vec) { + // calculated corresponding index of new_drivable_lanes + const auto opt_new_drivable_lanes_idx = [&]() -> std::optional { + for (size_t n_idx = 0; n_idx < new_drivable_lanes_vec.size(); ++n_idx) { + for (const auto & ll : convert_to_lanes(updated_drivable_lanes)) { + if (has_same_lane(ll, convert_to_lanes(new_drivable_lanes_vec.at(n_idx)))) { + return n_idx; + } + } + } + return std::nullopt; + }(); + if (!opt_new_drivable_lanes_idx) { + continue; + } + new_drivable_lanes_idx = *opt_new_drivable_lanes_idx; + const auto & new_drivable_lanes = new_drivable_lanes_vec.at(new_drivable_lanes_idx); + + // update left lane + if (has_same_lane(updated_drivable_lanes.left_lane, convert_to_lanes(new_drivable_lanes))) { + updated_drivable_lanes.left_lane = new_drivable_lanes.left_lane; + } + // update right lane + if (has_same_lane(updated_drivable_lanes.right_lane, convert_to_lanes(new_drivable_lanes))) { + updated_drivable_lanes.right_lane = new_drivable_lanes.right_lane; + } + // update middle lanes + for (const auto & middle_lane : convert_to_lanes(new_drivable_lanes)) { + if (!has_same_lane(middle_lane, convert_to_lanes(updated_drivable_lanes))) { + updated_drivable_lanes.middle_lanes.push_back(middle_lane); + } + } + + // validate middle lanes + auto & middle_lanes = updated_drivable_lanes.middle_lanes; + if (has_same_lane(updated_drivable_lanes.right_lane, middle_lanes)) { + middle_lanes.erase( + std::remove( + std::begin(middle_lanes), std::end(middle_lanes), updated_drivable_lanes.right_lane), + std::cend(middle_lanes)); + } + if (has_same_lane(updated_drivable_lanes.left_lane, middle_lanes)) { + middle_lanes.erase( + std::remove( + std::begin(middle_lanes), std::end(middle_lanes), updated_drivable_lanes.left_lane), + std::cend(middle_lanes)); + } + } + // NOTE: If original_drivable_lanes_vec is shorter than new_drivable_lanes_vec, push back remained + // new_drivable_lanes_vec. + if (new_drivable_lanes_idx + 1 < new_drivable_lanes_vec.size()) { + updated_drivable_lanes_vec.insert( + updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, + new_drivable_lanes_vec.end()); + } + + return updated_drivable_lanes_vec; +} + +DrivableAreaInfo combineDrivableAreaInfo( + const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2) +{ + DrivableAreaInfo combined_drivable_area_info; + + // drivable lanes + combined_drivable_area_info.drivable_lanes = + combineDrivableLanes(drivable_area_info1.drivable_lanes, drivable_area_info2.drivable_lanes); + + // obstacles + for (const auto & obstacle : drivable_area_info1.obstacles) { + combined_drivable_area_info.obstacles.push_back(obstacle); + } + for (const auto & obstacle : drivable_area_info2.obstacles) { + combined_drivable_area_info.obstacles.push_back(obstacle); + } + + // enable expanding hatched road markings + combined_drivable_area_info.enable_expanding_hatched_road_markings = + drivable_area_info1.enable_expanding_hatched_road_markings || + drivable_area_info2.enable_expanding_hatched_road_markings; + + // enable expanding intersection areas + combined_drivable_area_info.enable_expanding_intersection_areas = + drivable_area_info1.enable_expanding_intersection_areas || + drivable_area_info2.enable_expanding_intersection_areas; + + return combined_drivable_area_info; +} + +lanelet::ConstLanelets combineLanelets( + const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes) +{ + lanelet::ConstLanelets combined_lanes = base_lanes; + for (const auto & added_lane : added_lanes) { + const auto it = std::find_if( + combined_lanes.begin(), combined_lanes.end(), + [&added_lane](const lanelet::ConstLanelet & lane) { return lane.id() == added_lane.id(); }); + if (it == combined_lanes.end()) { + combined_lanes.push_back(added_lane); + } + } + + return combined_lanes; +} +} // namespace behavior_path_planner::utils diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp index 60cc2d19c5f35..ac8e458fd0d6c 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp @@ -14,6 +14,7 @@ #include "behavior_path_planner/utils/goal_planner/shift_pull_over.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/goal_planner/util.hpp" #include "behavior_path_planner/utils/path_utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/path_utils.cpp b/planning/behavior_path_planner/src/utils/path_utils.cpp index a6d7bc0040c23..44501977eacd6 100644 --- a/planning/behavior_path_planner/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/src/utils/path_utils.cpp @@ -14,9 +14,11 @@ #include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/utils.hpp" #include +#include #include #include #include @@ -589,4 +591,107 @@ boost::optional getFirstStopPoseFromPath(const PathWithLaneId & path) } return boost::none; } + +BehaviorModuleOutput getReferencePath( + const lanelet::ConstLanelet & current_lane, + const std::shared_ptr & planner_data) +{ + PathWithLaneId reference_path{}; + + const auto & route_handler = planner_data->route_handler; + const auto current_pose = planner_data->self_odometry->pose.pose; + const auto p = planner_data->parameters; + + // Set header + reference_path.header = route_handler->getRouteHeader(); + + // calculate path with backward margin to avoid end points' instability by spline interpolation + constexpr double extra_margin = 10.0; + const double backward_length = p.backward_path_length + extra_margin; + const auto current_lanes_with_backward_margin = + route_handler->getLaneletSequence(current_lane, backward_length, p.forward_path_length); + const auto no_shift_pose = + lanelet::utils::getClosestCenterPose(current_lane, current_pose.position); + reference_path = getCenterLinePath( + *route_handler, current_lanes_with_backward_margin, no_shift_pose, backward_length, + p.forward_path_length, p); + + // clip backward length + // NOTE: In order to keep backward_path_length at least, resampling interval is added to the + // backward. + const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + reference_path.points, no_shift_pose, p.ego_nearest_dist_threshold, + p.ego_nearest_yaw_threshold); + reference_path.points = motion_utils::cropPoints( + reference_path.points, no_shift_pose.position, current_seg_idx, p.forward_path_length, + p.backward_path_length + p.input_path_interval); + + const auto drivable_lanelets = getLaneletsFromPath(reference_path, route_handler); + const auto drivable_lanes = generateDrivableLanes(drivable_lanelets); + + const auto & dp = planner_data->drivable_area_expansion_parameters; + + const auto shorten_lanes = cutOverlappedLanes(reference_path, drivable_lanes); + const auto expanded_lanes = expandLanelets( + shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, + dp.drivable_area_types_to_skip); + + BehaviorModuleOutput output; + output.path = std::make_shared(reference_path); + output.reference_path = std::make_shared(reference_path); + output.drivable_area_info.drivable_lanes = drivable_lanes; + + return output; +} + +BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr & planner_data) +{ + BehaviorModuleOutput output; + + const auto & route_handler = planner_data->route_handler; + const auto & modified_goal = planner_data->prev_modified_goal; + + const Pose goal_pose = modified_goal ? modified_goal->pose : route_handler->getGoalPose(); + const auto shoulder_lanes = route_handler->getShoulderLanelets(); + + lanelet::ConstLanelet goal_lane; + const bool is_failed_getting_lanelet = std::invoke([&]() { + if (isInLanelets(goal_pose, shoulder_lanes)) { + return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); + } + return !route_handler->getGoalLanelet(&goal_lane); + }); + if (is_failed_getting_lanelet) { + return output; + } + + constexpr double backward_length = 1.0; + const auto arc_coord = lanelet::utils::getArcCoordinates({goal_lane}, goal_pose); + const double s_start = std::max(arc_coord.length - backward_length, 0.0); + const double s_end = arc_coord.length; + + auto reference_path = route_handler->getCenterLinePath({goal_lane}, s_start, s_end); + + const auto drivable_lanelets = getLaneletsFromPath(reference_path, route_handler); + const auto drivable_lanes = generateDrivableLanes(drivable_lanelets); + + const auto & dp = planner_data->drivable_area_expansion_parameters; + + const auto shorten_lanes = cutOverlappedLanes(reference_path, drivable_lanes); + const auto expanded_lanes = expandLanelets( + shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, + dp.drivable_area_types_to_skip); + + // Insert zero velocity to each point in the path. + for (auto & point : reference_path.points) { + point.point.longitudinal_velocity_mps = 0.0; + } + + output.path = std::make_shared(reference_path); + output.reference_path = std::make_shared(reference_path); + output.drivable_area_info.drivable_lanes = drivable_lanes; + + return output; +} + } // namespace behavior_path_planner::utils diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 0d1eaef0237b3..763719f11ebd9 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -14,7 +14,6 @@ #include "behavior_path_planner/utils/utils.hpp" -#include "behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" @@ -68,68 +67,6 @@ double calcInterpolatedVelocity( const double interpolated_vel = std::abs(seg_dist) < 1e-06 ? next_vel : closest_vel; return interpolated_vel; } - -template -size_t findNearestSegmentIndex( - const std::vector & points, const geometry_msgs::msg::Pose & pose, const double dist_threshold, - const double yaw_threshold) -{ - const auto nearest_idx = - motion_utils::findNearestSegmentIndex(points, pose, dist_threshold, yaw_threshold); - if (nearest_idx) { - return nearest_idx.get(); - } - - return motion_utils::findNearestSegmentIndex(points, pose.position); -} - -template -size_t findNearestSegmentIndexFromLateralDistance( - const std::vector & points, const geometry_msgs::msg::Point & target_point) -{ - std::optional closest_idx{std::nullopt}; - double min_lateral_dist = std::numeric_limits::max(); - for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) { - const double lon_dist = - motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); - const double segment_length = - tier4_autoware_utils::calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); - const double lat_dist = [&]() { - if (lon_dist < 0.0) { - return tier4_autoware_utils::calcDistance2d(points.at(seg_idx), target_point); - } - if (segment_length < lon_dist) { - return tier4_autoware_utils::calcDistance2d(points.at(seg_idx + 1), target_point); - } - return std::abs(motion_utils::calcLateralOffset(points, target_point, seg_idx)); - }(); - if (lat_dist < min_lateral_dist) { - closest_idx = seg_idx; - min_lateral_dist = lat_dist; - } - } - - if (closest_idx) { - return *closest_idx; - } - - return motion_utils::findNearestSegmentIndex(points, target_point); -} - -bool checkHasSameLane( - const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelet & target_lane) -{ - if (lanelets.empty()) return false; - - const auto has_same = [&](const auto & ll) { return ll.id() == target_lane.id(); }; - return std::find_if(lanelets.begin(), lanelets.end(), has_same) != lanelets.end(); -} - -bool isSamePoint(const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2) -{ - constexpr double epsilon = 1e-3; - return std::abs(point1.x - point2.x) < epsilon && std::abs(point1.y - point2.y) < epsilon; -} } // namespace namespace behavior_path_planner::utils @@ -140,413 +77,6 @@ using geometry_msgs::msg::PoseWithCovarianceStamped; using tf2::fromMsg; using tier4_autoware_utils::Point2d; -namespace drivable_area_processing -{ -boost::optional> intersectBound( - const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, - const std::vector & bound, const size_t seg_idx1, - const size_t seg_idx2) -{ - const size_t start_idx = - static_cast(std::max(0, static_cast(std::min(seg_idx1, seg_idx2)) - 5)); - const size_t end_idx = static_cast(std::min( - static_cast(bound.size()) - 1, static_cast(std::max(seg_idx1, seg_idx2)) + 1 + 5)); - for (int i = start_idx; i < static_cast(end_idx); ++i) { - const auto intersect_point = - tier4_autoware_utils::intersect(p1, p2, bound.at(i), bound.at(i + 1)); - if (intersect_point) { - std::pair result; - result.first = static_cast(i); - result.second = *intersect_point; - return result; - } - } - return boost::none; -} - -double calcDistanceFromPointToSegment( - const geometry_msgs::msg::Point & segment_start_point, - const geometry_msgs::msg::Point & segment_end_point, - const geometry_msgs::msg::Point & target_point) -{ - const auto & a = segment_start_point; - const auto & b = segment_end_point; - const auto & p = target_point; - - const double dot_val = (b.x - a.x) * (p.x - a.x) + (b.y - a.y) * (p.y - a.y); - const double squared_segment_length = tier4_autoware_utils::calcSquaredDistance2d(a, b); - if (0 <= dot_val && dot_val <= squared_segment_length) { - const double numerator = std::abs((p.x - a.x) * (a.y - b.y) - (p.y - a.y) * (a.x - b.x)); - const double denominator = std::sqrt(std::pow(a.x - b.x, 2) + std::pow(a.y - b.y, 2)); - return numerator / denominator; - } - - // target_point is outside the segment. - return std::min( - tier4_autoware_utils::calcDistance2d(a, p), tier4_autoware_utils::calcDistance2d(b, p)); -} - -PolygonPoint transformBoundFrenetCoordinate( - const std::vector & bound_points, - const geometry_msgs::msg::Point & target_point) -{ - // NOTE: findNearestSegmentIndex cannot be used since a bound's interval is sometimes too large to - // find wrong nearest index. - std::vector dist_to_bound_segment_vec; - for (size_t i = 0; i < bound_points.size() - 1; ++i) { - const double dist_to_bound_segment = - calcDistanceFromPointToSegment(bound_points.at(i), bound_points.at(i + 1), target_point); - dist_to_bound_segment_vec.push_back(dist_to_bound_segment); - } - - const size_t min_dist_seg_idx = std::distance( - dist_to_bound_segment_vec.begin(), - std::min_element(dist_to_bound_segment_vec.begin(), dist_to_bound_segment_vec.end())); - const double lon_dist_to_segment = - motion_utils::calcLongitudinalOffsetToSegment(bound_points, min_dist_seg_idx, target_point); - const double lat_dist_to_segment = - motion_utils::calcLateralOffset(bound_points, target_point, min_dist_seg_idx); - return PolygonPoint{target_point, min_dist_seg_idx, lon_dist_to_segment, lat_dist_to_segment}; -} - -std::vector generatePolygonInsideBounds( - const std::vector & bound, const std::vector & edge_points, - const bool is_object_right) -{ - constexpr double invalid_lat_dist_to_bound = 10.0; - - std::vector full_polygon; - for (const auto & edge_point : edge_points) { - const auto polygon_point = transformBoundFrenetCoordinate(bound, edge_point); - - // check lat dist for U-turn roads. - if ( - (is_object_right && invalid_lat_dist_to_bound < polygon_point.lat_dist_to_bound) || - (!is_object_right && polygon_point.lat_dist_to_bound < -invalid_lat_dist_to_bound)) { - return {}; - } - full_polygon.push_back(polygon_point); - } - - // 1. check the case where the polygon intersects the bound - std::vector inside_poly; - bool has_intersection = false; // NOTE: between obstacle polygon and bound - for (int i = 0; i < static_cast(full_polygon.size()); ++i) { - const auto & curr_poly = full_polygon.at(i); - const auto & prev_poly = full_polygon.at(i == 0 ? full_polygon.size() - 1 : i - 1); - - const bool is_curr_outside = curr_poly.is_outside_bounds(is_object_right); - const bool is_prev_outside = prev_poly.is_outside_bounds(is_object_right); - - if (is_curr_outside && is_prev_outside) { - continue; - } - if (!is_curr_outside && !is_prev_outside) { - inside_poly.push_back(curr_poly); - continue; - } - - const auto intersection = intersectBound( - prev_poly.point, curr_poly.point, bound, prev_poly.bound_seg_idx, curr_poly.bound_seg_idx); - if (!intersection) { - continue; - } - const double lon_dist = motion_utils::calcLongitudinalOffsetToSegment( - bound, intersection->first, intersection->second); - const auto intersect_point = - PolygonPoint{intersection->second, intersection->first, lon_dist, 0.0}; - has_intersection = true; - - if (is_prev_outside && !is_curr_outside) { - inside_poly.push_back(intersect_point); - inside_poly.push_back(curr_poly); - continue; - } - // Here is if (!is_prev_outside && is_curr_outside). - inside_poly.push_back(prev_poly); - inside_poly.push_back(intersect_point); - continue; - } - if (has_intersection) { - return inside_poly; - } - - // 2. check the case where the polygon does not intersect the bound - const bool is_polygon_fully_inside_bounds = [&]() { - for (const auto & curr_poly : full_polygon) { - const bool is_curr_outside = curr_poly.is_outside_bounds(is_object_right); - if (is_curr_outside) { - return false; - } - } - return true; - }(); - if (is_polygon_fully_inside_bounds) { - return full_polygon; - } - - return std::vector{}; -} - -std::vector convertToGeometryPoints( - const std::vector & polygon_points) -{ - std::vector points; - points.reserve(polygon_points.size()); - - for (const auto & polygon_point : polygon_points) { - points.push_back(polygon_point.point); - } - return points; -} - -// NOTE: See the PR's figure. https://github.com/autowarefoundation/autoware.universe/pull/2880 -std::vector concatenateTwoPolygons( - const std::vector & front_polygon, const std::vector & back_polygon) -{ - const auto make_unique_polygon = [&](const auto & polygon) { - std::vector unique_polygon; - for (const auto & point : polygon) { - if (!unique_polygon.empty() && isSamePoint(unique_polygon.back().point, point.point)) { - continue; - } - unique_polygon.push_back(point); - } - return unique_polygon; - }; - const auto unique_front_polygon = make_unique_polygon(front_polygon); - const auto unique_back_polygon = make_unique_polygon(back_polygon); - - // At first, the front polygon is the outside polygon - bool is_front_polygon_outside = true; - size_t before_outside_idx = 0; - - const auto get_out_poly = [&]() { - return is_front_polygon_outside ? unique_front_polygon : unique_back_polygon; - }; - const auto get_in_poly = [&]() { - return is_front_polygon_outside ? unique_back_polygon : unique_front_polygon; - }; - - // NOTE: Polygon points is assumed to be clock-wise. - std::vector concatenated_polygon; - // NOTE: Maximum number of loop is set to avoid infinity loop calculation just in case. - const size_t max_loop_num = (unique_front_polygon.size() + unique_back_polygon.size()) * 2; - for (size_t loop_idx = 0; loop_idx < max_loop_num; ++loop_idx) { - concatenated_polygon.push_back(get_out_poly().at(before_outside_idx)); - if (before_outside_idx == get_out_poly().size() - 1) { - break; - } - const size_t curr_idx = before_outside_idx; - const size_t next_idx = before_outside_idx + 1; - - // NOTE: Two polygons may have two intersection points. Therefore the closest intersection - // point is used. - std::optional closest_idx = std::nullopt; - double min_dist_to_intersection = std::numeric_limits::max(); - PolygonPoint closest_intersect_point; - for (size_t i = 0; i < get_in_poly().size() - 1; ++i) { - const auto intersection = tier4_autoware_utils::intersect( - get_out_poly().at(curr_idx).point, get_out_poly().at(next_idx).point, - get_in_poly().at(i).point, get_in_poly().at(i + 1).point); - if (!intersection) { - continue; - } - if ( - isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i).point) || - isSamePoint(get_out_poly().at(curr_idx).point, get_in_poly().at(i + 1).point) || - isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i).point) || - isSamePoint(get_out_poly().at(next_idx).point, get_in_poly().at(i + 1).point)) { - // NOTE: If the segments shares one point, the while loop will not end. - continue; - } - - const auto intersect_point = PolygonPoint{*intersection, 0, 0.0, 0.0}; - const double dist_to_intersection = - tier4_autoware_utils::calcDistance2d(get_out_poly().at(curr_idx).point, *intersection); - if (dist_to_intersection < min_dist_to_intersection) { - closest_idx = i; - min_dist_to_intersection = dist_to_intersection; - closest_intersect_point = intersect_point; - } - } - - if (closest_idx) { - before_outside_idx = *closest_idx; - concatenated_polygon.push_back(closest_intersect_point); - is_front_polygon_outside = !is_front_polygon_outside; - } - - before_outside_idx += 1; - - if (loop_idx == max_loop_num - 1) { - return front_polygon; - } - } - - return concatenated_polygon; -} - -std::vector> concatenatePolygons( - const std::vector> & polygons) -{ - auto unique_polygons = polygons; - - while (rclcpp::ok()) { - bool is_updated = false; - - for (size_t i = 0; i < unique_polygons.size(); ++i) { - for (size_t j = 0; j < i; ++j) { - const auto & p1 = unique_polygons.at(i); - const auto & p2 = unique_polygons.at(j); - - // if p1 and p2 overlaps - if (p1.back().is_after(p2.front()) && p2.back().is_after(p1.front())) { - is_updated = true; - - const auto concatenated_polygon = [&]() { - if (p2.front().is_after(p1.front())) { - return concatenateTwoPolygons(p1, p2); - } - return concatenateTwoPolygons(p2, p1); - }(); - - // NOTE: remove i's element first since is larger than j. - unique_polygons.erase(unique_polygons.begin() + i); - unique_polygons.erase(unique_polygons.begin() + j); - - unique_polygons.push_back(concatenated_polygon); - break; - } - } - if (is_updated) { - break; - } - } - - if (!is_updated) { - break; - } - } - return unique_polygons; -} - -std::vector getPolygonPointsInsideBounds( - const std::vector & bound, const std::vector & edge_points, - const bool is_object_right) -{ - // NOTE: Polygon is defined at lest by three points. - if (edge_points.size() < 3) { - return std::vector(); - } - - // convert to vector of PolygonPoint - const auto inside_polygon = [&]() { - auto tmp_polygon = generatePolygonInsideBounds(bound, edge_points, is_object_right); - - // In order to make the order of points the same as the order of lon_dist_to_segment. - // The order of points is clockwise. - if (!is_object_right) { - std::reverse(tmp_polygon.begin(), tmp_polygon.end()); - } - return tmp_polygon; - }(); - if (inside_polygon.empty()) { - return std::vector(); - } - - // search start and end index by longitudinal distance - std::vector polygon_indices(inside_polygon.size()); - std::iota(polygon_indices.begin(), polygon_indices.end(), 0); - std::sort(polygon_indices.begin(), polygon_indices.end(), [&](int i1, int i2) { - return inside_polygon.at(i2).is_after(inside_polygon.at(i1)); - }); - const int start_idx = polygon_indices.front(); - const int end_idx = polygon_indices.back(); - - // calculate valid inside polygon - std::vector valid_inside_polygon; - for (int i = 0; i < (end_idx - start_idx + static_cast(polygon_indices.size())) % - static_cast(polygon_indices.size()) + - 1; - ++i) { - const int poly_idx = (start_idx + i) % static_cast(inside_polygon.size()); - valid_inside_polygon.push_back(inside_polygon.at(poly_idx)); - } - - // add start and end points projected to bound if necessary - if (inside_polygon.at(start_idx).lat_dist_to_bound != 0.0) { // not on bound - auto start_point = inside_polygon.at(start_idx); - const auto start_point_on_bound = motion_utils::calcLongitudinalOffsetPoint( - bound, start_point.bound_seg_idx, start_point.lon_dist_to_segment); - if (start_point_on_bound) { - start_point.point = start_point_on_bound.get(); - valid_inside_polygon.insert(valid_inside_polygon.begin(), start_point); - } - } - if (inside_polygon.at(end_idx).lat_dist_to_bound != 0.0) { // not on bound - auto end_point = inside_polygon.at(end_idx); - const auto end_point_on_bound = motion_utils::calcLongitudinalOffsetPoint( - bound, end_point.bound_seg_idx, end_point.lon_dist_to_segment); - if (end_point_on_bound) { - end_point.point = end_point_on_bound.get(); - valid_inside_polygon.insert(valid_inside_polygon.end(), end_point); - } - } - return valid_inside_polygon; -} - -std::vector updateBoundary( - const std::vector & original_bound, - const std::vector> & sorted_polygons) -{ - if (sorted_polygons.empty()) { - return original_bound; - } - - auto reversed_polygons = sorted_polygons; - std::reverse(reversed_polygons.begin(), reversed_polygons.end()); - - auto updated_bound = original_bound; - - // NOTE: Further obstacle is applied first since a part of the updated_bound is erased. - for (const auto & polygon : reversed_polygons) { - const auto & start_poly = polygon.front(); - const auto & end_poly = polygon.back(); - - const double front_offset = motion_utils::calcLongitudinalOffsetToSegment( - updated_bound, start_poly.bound_seg_idx, start_poly.point); - - const size_t removed_start_idx = - 0 < front_offset ? start_poly.bound_seg_idx + 1 : start_poly.bound_seg_idx; - const size_t removed_end_idx = end_poly.bound_seg_idx; - - updated_bound.erase( - updated_bound.begin() + removed_start_idx, updated_bound.begin() + removed_end_idx + 1); - - const auto obj_points = convertToGeometryPoints(polygon); - updated_bound.insert( - updated_bound.begin() + removed_start_idx, obj_points.begin(), obj_points.end()); - } - return updated_bound; -} - -[[maybe_unused]] geometry_msgs::msg::Point calcCenterOfGeometry(const Polygon2d & obj_poly) -{ - geometry_msgs::msg::Point center_pos; - for (const auto & point : obj_poly.outer()) { - center_pos.x += point.x(); - center_pos.y += point.y(); - } - - center_pos.x = center_pos.x / obj_poly.outer().size(); - center_pos.y = center_pos.y / obj_poly.outer().size(); - center_pos.z = center_pos.z / obj_poly.outer().size(); - - return center_pos; -} -} // namespace drivable_area_processing - std::optional getPolygonByPoint( const std::shared_ptr & route_handler, const lanelet::ConstPoint3d & point, const std::string & polygon_name) @@ -936,56 +466,6 @@ bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal return false; } -BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr & planner_data) -{ - BehaviorModuleOutput output; - - const auto & route_handler = planner_data->route_handler; - const auto & modified_goal = planner_data->prev_modified_goal; - - const Pose goal_pose = modified_goal ? modified_goal->pose : route_handler->getGoalPose(); - const auto shoulder_lanes = route_handler->getShoulderLanelets(); - - lanelet::ConstLanelet goal_lane; - const bool is_failed_getting_lanelet = std::invoke([&]() { - if (isInLanelets(goal_pose, shoulder_lanes)) { - return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); - } - return !route_handler->getGoalLanelet(&goal_lane); - }); - if (is_failed_getting_lanelet) { - return output; - } - - constexpr double backward_length = 1.0; - const auto arc_coord = lanelet::utils::getArcCoordinates({goal_lane}, goal_pose); - const double s_start = std::max(arc_coord.length - backward_length, 0.0); - const double s_end = arc_coord.length; - - auto reference_path = route_handler->getCenterLinePath({goal_lane}, s_start, s_end); - - const auto drivable_lanelets = getLaneletsFromPath(reference_path, route_handler); - const auto drivable_lanes = generateDrivableLanes(drivable_lanelets); - - const auto & dp = planner_data->drivable_area_expansion_parameters; - - const auto shorten_lanes = cutOverlappedLanes(reference_path, drivable_lanes); - const auto expanded_lanes = expandLanelets( - shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - - // Insert zero velocity to each point in the path. - for (auto & point : reference_path.points) { - point.point.longitudinal_velocity_mps = 0.0; - } - - output.path = std::make_shared(reference_path); - output.reference_path = std::make_shared(reference_path); - output.drivable_area_info.drivable_lanes = drivable_lanes; - - return output; -} - bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes) { for (const auto & lane : lanes) { @@ -1018,1285 +498,160 @@ bool isEgoOutOfRoute( : route_handler->getGoalPose(); const auto shoulder_lanes = route_handler->getShoulderLanelets(); - lanelet::ConstLanelet goal_lane; - const bool is_failed_getting_lanelet = std::invoke([&]() { - if (utils::isInLanelets(goal_pose, shoulder_lanes)) { - return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); - } - return !route_handler->getGoalLanelet(&goal_lane); - }); - if (is_failed_getting_lanelet) { - RCLCPP_WARN_STREAM( - rclcpp::get_logger("behavior_path_planner").get_child("util"), "cannot find goal lanelet"); - return true; - } - - // If ego vehicle is over goal on goal lane, return true - const double yaw_threshold = tier4_autoware_utils::deg2rad(90); - if (isInLaneletWithYawThreshold(self_pose, goal_lane, yaw_threshold)) { - constexpr double buffer = 1.0; - const auto ego_arc_coord = lanelet::utils::getArcCoordinates({goal_lane}, self_pose); - const auto goal_arc_coord = - lanelet::utils::getArcCoordinates({goal_lane}, route_handler->getGoalPose()); - if (ego_arc_coord.length > goal_arc_coord.length + buffer) { - return true; - } else { - return false; - } - } - - // If ego vehicle is out of the closest lanelet, return true - // Check if ego vehicle is in shoulder lane - const bool is_in_shoulder_lane = std::invoke([&]() { - lanelet::Lanelet closest_shoulder_lanelet; - if (!lanelet::utils::query::getClosestLanelet( - shoulder_lanes, self_pose, &closest_shoulder_lanelet)) { - return false; - } - return lanelet::utils::isInLanelet(self_pose, closest_shoulder_lanelet); - }); - // Check if ego vehicle is in road lane - const bool is_in_road_lane = std::invoke([&]() { - lanelet::ConstLanelet closest_road_lane; - if (!route_handler->getClosestLaneletWithinRoute(self_pose, &closest_road_lane)) { - RCLCPP_WARN_STREAM( - rclcpp::get_logger("behavior_path_planner").get_child("util"), - "cannot find closest road lanelet"); - return false; - } - - if (lanelet::utils::isInLanelet(self_pose, closest_road_lane)) { - return true; - } - - // check previous lanes for backward driving (e.g. pull out) - const auto prev_lanes = route_handler->getPreviousLanelets(closest_road_lane); - for (const auto & lane : prev_lanes) { - if (lanelet::utils::isInLanelet(self_pose, lane)) { - return true; - } - } - - return false; - }); - if (!is_in_shoulder_lane && !is_in_road_lane) { - return true; - } - - return false; -} - -bool isEgoWithinOriginalLane( - const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, - const BehaviorPathPlannerParameters & common_param, const double outer_margin) -{ - const auto lane_length = lanelet::utils::getLaneletLength2d(current_lanes); - const auto lane_poly = lanelet::utils::getPolygonFromArcLength(current_lanes, 0, lane_length); - const auto base_link2front = common_param.base_link2front; - const auto base_link2rear = common_param.base_link2rear; - const auto vehicle_width = common_param.vehicle_width; - const auto vehicle_poly = - tier4_autoware_utils::toFootprint(current_pose, base_link2front, base_link2rear, vehicle_width); - - // Check if the ego vehicle is entirely within the lane with a given outer margin. - for (const auto & p : vehicle_poly.outer()) { - // When the point is in the polygon, the distance is 0. When it is out of the polygon, return a - // positive value. - const auto dist = boost::geometry::distance(p, lanelet::utils::to2D(lane_poly).basicPolygon()); - if (dist > std::max(outer_margin, 0.0)) { - return false; // out of polygon - } - } - - return true; // inside polygon -} - -lanelet::ConstLanelets transformToLanelets(const DrivableLanes & drivable_lanes) -{ - lanelet::ConstLanelets lanes; - - const auto has_same_lane = [&](const auto & lane) { - if (lanes.empty()) return false; - const auto has_same = [&](const auto & ll) { return ll.id() == lane.id(); }; - return std::find_if(lanes.begin(), lanes.end(), has_same) != lanes.end(); - }; - - lanes.push_back(drivable_lanes.right_lane); - if (!has_same_lane(drivable_lanes.left_lane)) { - lanes.push_back(drivable_lanes.left_lane); - } - - for (const auto & ml : drivable_lanes.middle_lanes) { - if (!has_same_lane(ml)) { - lanes.push_back(ml); - } - } - - return lanes; -} - -lanelet::ConstLanelets transformToLanelets(const std::vector & drivable_lanes) -{ - lanelet::ConstLanelets lanes; - - for (const auto & drivable_lane : drivable_lanes) { - const auto transformed_lane = transformToLanelets(drivable_lane); - lanes.insert(lanes.end(), transformed_lane.begin(), transformed_lane.end()); - } - - return lanes; -} - -boost::optional getRightLanelet( - const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes) -{ - for (const auto & shoulder_lane : shoulder_lanes) { - if (shoulder_lane.leftBound().id() == current_lane.rightBound().id()) { - return shoulder_lane; - } - } - - return {}; -} - -boost::optional getLeftLanelet( - const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes) -{ - for (const auto & shoulder_lane : shoulder_lanes) { - if (shoulder_lane.rightBound().id() == current_lane.leftBound().id()) { - return shoulder_lane; - } - } - - return {}; -} - -std::vector generateDrivableLanes(const lanelet::ConstLanelets & lanes) -{ - std::vector drivable_lanes(lanes.size()); - for (size_t i = 0; i < lanes.size(); ++i) { - drivable_lanes.at(i).left_lane = lanes.at(i); - drivable_lanes.at(i).right_lane = lanes.at(i); - } - return drivable_lanes; -} - -std::vector generateDrivableLanesWithShoulderLanes( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes) -{ - std::vector drivable_lanes; - for (const auto & current_lane : current_lanes) { - DrivableLanes drivable_lane; - - const auto right_lane = getRightLanelet(current_lane, shoulder_lanes); - const auto left_lane = getLeftLanelet(current_lane, shoulder_lanes); - - if (right_lane && left_lane) { - drivable_lane.right_lane = *right_lane; - drivable_lane.left_lane = *left_lane; - drivable_lane.middle_lanes.push_back(current_lane); - } else if (right_lane) { - drivable_lane.right_lane = *right_lane; - drivable_lane.left_lane = current_lane; - } else if (left_lane) { - drivable_lane.right_lane = current_lane; - drivable_lane.left_lane = *left_lane; - } else { - drivable_lane.right_lane = current_lane; - drivable_lane.left_lane = current_lane; - } - - drivable_lanes.push_back(drivable_lane); - } - - return drivable_lanes; -} - -std::vector getNonOverlappingExpandedLanes( - PathWithLaneId & path, const std::vector & lanes, - const DrivableAreaExpansionParameters & parameters) -{ - const auto shorten_lanes = utils::cutOverlappedLanes(path, lanes); - return utils::expandLanelets( - shorten_lanes, parameters.drivable_area_left_bound_offset, - parameters.drivable_area_right_bound_offset, parameters.drivable_area_types_to_skip); -} - -boost::optional getOverlappedLaneletId(const std::vector & lanes) -{ - auto overlaps = [](const DrivableLanes & lanes, const DrivableLanes & target_lanes) { - const auto lanelets = transformToLanelets(lanes); - const auto target_lanelets = transformToLanelets(target_lanes); - - for (const auto & lanelet : lanelets) { - for (const auto & target_lanelet : target_lanelets) { - std::vector intersections{}; - boost::geometry::intersection( - lanelet.polygon2d().basicPolygon(), target_lanelet.polygon2d().basicPolygon(), - intersections); - - // if only one point intersects, it is assumed not to be overlapped - if (intersections.size() > 1) { - return true; - } - } - } - - // No overlapping - return false; - }; - - if (lanes.size() <= 2) { - return {}; - } - - size_t overlapped_idx = lanes.size(); - for (size_t i = 0; i < lanes.size() - 2; ++i) { - for (size_t j = i + 2; j < lanes.size(); ++j) { - if (overlaps(lanes.at(i), lanes.at(j))) { - overlapped_idx = std::min(overlapped_idx, j); - } - } - } - - if (overlapped_idx == lanes.size()) { - return {}; - } - - return overlapped_idx; -} - -std::vector cutOverlappedLanes( - PathWithLaneId & path, const std::vector & lanes) -{ - const auto overlapped_lanelet_idx = getOverlappedLaneletId(lanes); - if (!overlapped_lanelet_idx) { - return lanes; - } - - std::vector shorten_lanes{lanes.begin(), lanes.begin() + *overlapped_lanelet_idx}; - const auto shorten_lanelets = utils::transformToLanelets(shorten_lanes); - - const auto original_points = path.points; - - path.points.clear(); - - const auto has_same_id_lane = [](const auto & lanelet, const auto & p) { - return std::any_of(p.lane_ids.begin(), p.lane_ids.end(), [&lanelet](const auto id) { - return lanelet.id() == id; - }); - }; - - const auto has_same_id_lanes = [&has_same_id_lane](const auto & lanelets, const auto & p) { - return std::any_of( - lanelets.begin(), lanelets.end(), - [&has_same_id_lane, &p](const auto & lanelet) { return has_same_id_lane(lanelet, p); }); - }; - - // Step1. find first path point within drivable lanes - size_t start_point_idx = std::numeric_limits::max(); - for (const auto & lanes : shorten_lanes) { - for (size_t i = 0; i < original_points.size(); ++i) { - // check right lane - if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { - start_point_idx = std::min(start_point_idx, i); - } - - // check left lane - if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { - start_point_idx = std::min(start_point_idx, i); - } - - // check middle lanes - if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { - start_point_idx = std::min(start_point_idx, i); - } - } - } - - // Step2. pick up only path points within drivable lanes - for (const auto & lanes : shorten_lanes) { - for (size_t i = start_point_idx; i < original_points.size(); ++i) { - // check right lane - if (has_same_id_lane(lanes.right_lane, original_points.at(i))) { - path.points.push_back(original_points.at(i)); - continue; - } - - // check left lane - if (has_same_id_lane(lanes.left_lane, original_points.at(i))) { - path.points.push_back(original_points.at(i)); - continue; - } - - // check middle lanes - if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) { - path.points.push_back(original_points.at(i)); - continue; - } - - start_point_idx = i; - break; - } - } - - return shorten_lanes; -} - -geometry_msgs::msg::Point calcLongitudinalOffsetStartPoint( - const std::vector & points, const geometry_msgs::msg::Pose & pose, - const size_t nearest_segment_idx, const double offset) -{ - const double offset_length = - motion_utils::calcLongitudinalOffsetToSegment(points, nearest_segment_idx, pose.position); - const auto offset_point = - motion_utils::calcLongitudinalOffsetPoint(points, nearest_segment_idx, offset_length + offset); - - return offset_point ? offset_point.get() : points.at(nearest_segment_idx); -} - -geometry_msgs::msg::Point calcLongitudinalOffsetGoalPoint( - const std::vector & points, const geometry_msgs::msg::Pose & pose, - const size_t nearest_segment_idx, const double offset) -{ - const double offset_length = - motion_utils::calcLongitudinalOffsetToSegment(points, nearest_segment_idx, pose.position); - const auto offset_point = - motion_utils::calcLongitudinalOffsetPoint(points, nearest_segment_idx, offset_length + offset); - - return offset_point ? offset_point.get() : points.at(nearest_segment_idx + 1); -} - -void generateDrivableArea( - PathWithLaneId & path, const std::vector & lanes, - const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, - const double vehicle_length, const std::shared_ptr planner_data, - const bool is_driving_forward) -{ - // extract data - const auto transformed_lanes = utils::transformToLanelets(lanes); - const auto current_pose = planner_data->self_odometry->pose.pose; - const auto route_handler = planner_data->route_handler; - constexpr double overlap_threshold = 0.01; - - if (path.points.empty()) { - return; - } - - auto addPoints = - [](const lanelet::ConstLineString3d & points, std::vector & bound) { - for (const auto & bound_p : points) { - const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p); - if (bound.empty()) { - bound.push_back(cp); - } else if (tier4_autoware_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { - bound.push_back(cp); - } - } - }; - - const auto has_overlap = - [&](const lanelet::ConstLanelet & lane, const lanelet::ConstLanelets & ignore_lanelets = {}) { - for (const auto & transformed_lane : transformed_lanes) { - if (checkHasSameLane(ignore_lanelets, transformed_lane)) { - continue; - } - if (boost::geometry::intersects( - lane.polygon2d().basicPolygon(), transformed_lane.polygon2d().basicPolygon())) { - return true; - } - } - return false; - }; - - // Insert Position - auto left_bound = calcBound( - route_handler, lanes, enable_expanding_hatched_road_markings, - enable_expanding_intersection_areas, true); - auto right_bound = calcBound( - route_handler, lanes, enable_expanding_hatched_road_markings, - enable_expanding_intersection_areas, false); - - if (left_bound.empty() || right_bound.empty()) { - auto clock{rclcpp::Clock{RCL_ROS_TIME}}; - RCLCPP_ERROR_STREAM_THROTTLE( - rclcpp::get_logger("behavior_path_planner").get_child("utils"), clock, 1000, - "The right or left bound of drivable area is empty"); - return; - } - - // Insert points after goal - lanelet::ConstLanelet goal_lanelet; - if ( - route_handler->getGoalLanelet(&goal_lanelet) && - checkHasSameLane(transformed_lanes, goal_lanelet)) { - const auto lanes_after_goal = route_handler->getLanesAfterGoal(vehicle_length); - const auto next_lanes_after_goal = route_handler->getNextLanelets(goal_lanelet); - const auto goal_left_lanelet = route_handler->getLeftLanelet(goal_lanelet); - const auto goal_right_lanelet = route_handler->getRightLanelet(goal_lanelet); - lanelet::ConstLanelets goal_lanelets = {goal_lanelet}; - if (goal_left_lanelet) { - goal_lanelets.push_back(*goal_left_lanelet); - } - if (goal_right_lanelet) { - goal_lanelets.push_back(*goal_right_lanelet); - } - - for (const auto & lane : lanes_after_goal) { - // If lane is already in the transformed lanes, ignore it - if (checkHasSameLane(transformed_lanes, lane)) { - continue; - } - // Check if overlapped - const bool is_overlapped = - (checkHasSameLane(next_lanes_after_goal, lane) ? has_overlap(lane, goal_lanelets) - : has_overlap(lane)); - if (is_overlapped) { - continue; - } - - addPoints(lane.leftBound3d(), left_bound); - addPoints(lane.rightBound3d(), right_bound); - } - } - - if (!is_driving_forward) { - std::reverse(left_bound.begin(), left_bound.end()); - std::reverse(right_bound.begin(), right_bound.end()); - } - - path.left_bound.clear(); - path.right_bound.clear(); - - const auto [left_start_idx, right_start_idx] = [&]() { - const size_t current_seg_idx = planner_data->findEgoSegmentIndex(path.points); - const auto cropped_path_points = motion_utils::cropPoints( - path.points, current_pose.position, current_seg_idx, - planner_data->parameters.forward_path_length, - planner_data->parameters.backward_path_length + planner_data->parameters.input_path_interval); - - constexpr double front_length = 0.5; - const auto front_pose = - cropped_path_points.empty() ? current_pose : cropped_path_points.front().point.pose; - const size_t front_left_start_idx = - findNearestSegmentIndexFromLateralDistance(left_bound, front_pose.position); - const size_t front_right_start_idx = - findNearestSegmentIndexFromLateralDistance(right_bound, front_pose.position); - const auto left_start_point = - calcLongitudinalOffsetStartPoint(left_bound, front_pose, front_left_start_idx, -front_length); - const auto right_start_point = calcLongitudinalOffsetStartPoint( - right_bound, front_pose, front_right_start_idx, -front_length); - const size_t left_start_idx = - findNearestSegmentIndexFromLateralDistance(left_bound, left_start_point); - const size_t right_start_idx = - findNearestSegmentIndexFromLateralDistance(right_bound, right_start_point); - - // Insert a start point - path.left_bound.push_back(left_start_point); - path.right_bound.push_back(right_start_point); - - return std::make_pair(left_start_idx, right_start_idx); - }(); - - // Get Closest segment for the goal point - const auto goal_pose = path.points.empty() ? current_pose : path.points.back().point.pose; - const size_t goal_left_start_idx = - findNearestSegmentIndexFromLateralDistance(left_bound, goal_pose.position); - const size_t goal_right_start_idx = - findNearestSegmentIndexFromLateralDistance(right_bound, goal_pose.position); - const auto left_goal_point = - calcLongitudinalOffsetGoalPoint(left_bound, goal_pose, goal_left_start_idx, vehicle_length); - const auto right_goal_point = - calcLongitudinalOffsetGoalPoint(right_bound, goal_pose, goal_right_start_idx, vehicle_length); - const size_t left_goal_idx = std::max( - goal_left_start_idx, findNearestSegmentIndexFromLateralDistance(left_bound, left_goal_point)); - const size_t right_goal_idx = std::max( - goal_right_start_idx, - findNearestSegmentIndexFromLateralDistance(right_bound, right_goal_point)); - - // Insert middle points - for (size_t i = left_start_idx + 1; i <= left_goal_idx; ++i) { - const auto & next_point = left_bound.at(i); - const double dist = tier4_autoware_utils::calcDistance2d(path.left_bound.back(), next_point); - if (dist > overlap_threshold) { - path.left_bound.push_back(next_point); - } - } - for (size_t i = right_start_idx + 1; i <= right_goal_idx; ++i) { - const auto & next_point = right_bound.at(i); - const double dist = tier4_autoware_utils::calcDistance2d(path.right_bound.back(), next_point); - if (dist > overlap_threshold) { - path.right_bound.push_back(next_point); - } - } - - // Insert a goal point - if ( - tier4_autoware_utils::calcDistance2d(path.left_bound.back(), left_goal_point) > - overlap_threshold) { - path.left_bound.push_back(left_goal_point); - } - if ( - tier4_autoware_utils::calcDistance2d(path.right_bound.back(), right_goal_point) > - overlap_threshold) { - path.right_bound.push_back(right_goal_point); - } - const auto & expansion_params = planner_data->drivable_area_expansion_parameters; - if (expansion_params.enabled) { - drivable_area_expansion::expand_drivable_area(path, planner_data); - } - - // make bound longitudinally monotonic - // TODO(Murooka) Fix makeBoundLongitudinallyMonotonic - if ( - is_driving_forward && - (enable_expanding_hatched_road_markings || enable_expanding_intersection_areas)) { - makeBoundLongitudinallyMonotonic(path, planner_data, true); // for left bound - makeBoundLongitudinallyMonotonic(path, planner_data, false); // for right bound - } -} - -std::vector getBoundWithHatchedRoadMarkings( - const std::vector & original_bound, - const std::shared_ptr & route_handler) -{ - // a function to get polygon with a designated point id - const auto get_corresponding_polygon_index = - [&](const auto & polygon, const auto & target_point_id) { - for (size_t poly_point_idx = 0; poly_point_idx < polygon.size(); ++poly_point_idx) { - if (polygon[poly_point_idx].id() == target_point_id) { - // NOTE: If there are duplicated points in polygon, the early one will be returned. - return poly_point_idx; - } - } - // This means calculation has some errors. - return polygon.size() - 1; - }; - - const auto mod = [&](const int a, const int b) { - return (a + b) % b; // NOTE: consider negative value - }; - - std::vector expanded_bound{}; - - std::optional current_polygon{std::nullopt}; - std::vector current_polygon_border_indices; - // expand drivable area by hatched road markings. - for (size_t bound_point_idx = 0; bound_point_idx < original_bound.size(); ++bound_point_idx) { - const auto & bound_point = original_bound[bound_point_idx]; - const auto polygon = getPolygonByPoint(route_handler, bound_point, "hatched_road_markings"); - - bool will_close_polygon{false}; - if (!current_polygon) { - if (!polygon) { - expanded_bound.push_back(bound_point); - } else { - // There is a new additional polygon to expand - current_polygon = polygon; - current_polygon_border_indices.push_back( - get_corresponding_polygon_index(*current_polygon, bound_point.id())); - } - } else { - if (!polygon) { - will_close_polygon = true; - } else { - current_polygon_border_indices.push_back( - get_corresponding_polygon_index(*current_polygon, bound_point.id())); - } - } - - if (bound_point_idx == original_bound.size() - 1 && current_polygon) { - // If drivable lanes ends earlier than polygon, close the polygon - will_close_polygon = true; - } - - if (will_close_polygon) { - // The current additional polygon ends to expand - if (current_polygon_border_indices.size() == 1) { - expanded_bound.push_back((*current_polygon)[current_polygon_border_indices.front()]); - } else { - const size_t current_polygon_points_num = current_polygon->size(); - const bool is_polygon_opposite_direction = [&]() { - const size_t modulo_diff = mod( - static_cast(current_polygon_border_indices[1]) - - static_cast(current_polygon_border_indices[0]), - current_polygon_points_num); - return modulo_diff == 1; - }(); - - const int target_points_num = - current_polygon_points_num - current_polygon_border_indices.size() + 1; - for (int poly_idx = 0; poly_idx <= target_points_num; ++poly_idx) { - const int target_poly_idx = current_polygon_border_indices.front() + - poly_idx * (is_polygon_opposite_direction ? -1 : 1); - expanded_bound.push_back( - (*current_polygon)[mod(target_poly_idx, current_polygon_points_num)]); - } - } - current_polygon = std::nullopt; - current_polygon_border_indices.clear(); - } - } - - return expanded_bound; -} - -std::vector getBoundWithIntersectionAreas( - const std::vector & original_bound, - const std::shared_ptr & route_handler, - const std::vector & drivable_lanes, const bool is_left) -{ - const auto extract_bound_from_polygon = - [](const auto & polygon, const auto start_idx, const auto end_idx, const auto clockwise) { - std::vector ret{}; - for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) { - ret.push_back(polygon[i]); - - if (i + 1 == polygon.size() && clockwise) { - if (end_idx == 0) { - ret.push_back(polygon[end_idx]); - return ret; - } - i = 0; - continue; - } - - if (i == 0 && !clockwise) { - if (end_idx == polygon.size() - 1) { - ret.push_back(polygon[end_idx]); - return ret; - } - i = polygon.size() - 1; - continue; - } - } - - ret.push_back(polygon[end_idx]); - - return ret; - }; - - std::vector expanded_bound = original_bound; - - // expand drivable area by using intersection area. - for (const auto & drivable_lane : drivable_lanes) { - const auto edge_lanelet = is_left ? drivable_lane.left_lane : drivable_lane.right_lane; - const auto lanelet_bound = is_left ? edge_lanelet.leftBound3d() : edge_lanelet.rightBound3d(); - - if (lanelet_bound.size() < 2) { - continue; - } - - const std::string id = edge_lanelet.attributeOr("intersection_area", "else"); - if (id == "else") { - continue; - } - - // Step1. extract intersection partial bound. - std::vector intersection_bound{}; - { - const auto polygon = - route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); - - const auto is_clockwise_polygon = - boost::geometry::is_valid(lanelet::utils::to2D(polygon.basicPolygon())); - const auto is_clockwise_iteration = is_clockwise_polygon ? is_left : !is_left; - - const auto intersection_bound_itr_init = std::find_if( - polygon.begin(), polygon.end(), - [&lanelet_bound](const auto & p) { return p.id() == lanelet_bound.front().id(); }); - - const auto intersection_bound_itr_last = std::find_if( - polygon.begin(), polygon.end(), - [&lanelet_bound](const auto & p) { return p.id() == lanelet_bound.back().id(); }); - - if ( - intersection_bound_itr_init == polygon.end() || - intersection_bound_itr_last == polygon.end()) { - continue; - } - - // extract line strings between start_idx and end_idx. - const size_t start_idx = std::distance(polygon.begin(), intersection_bound_itr_init); - const size_t end_idx = std::distance(polygon.begin(), intersection_bound_itr_last); - - intersection_bound = - extract_bound_from_polygon(polygon, start_idx, end_idx, is_clockwise_iteration); - } - - // Step2. check shared bound point. - const auto shared_point_itr_init = - std::find_if(expanded_bound.begin(), expanded_bound.end(), [&](const auto & p) { - return std::any_of( - intersection_bound.begin(), intersection_bound.end(), - [&](const auto & point) { return point.id() == p.id(); }); - }); - - const auto shared_point_itr_last = - std::find_if(expanded_bound.rbegin(), expanded_bound.rend(), [&](const auto & p) { - return std::any_of( - intersection_bound.rbegin(), intersection_bound.rend(), - [&](const auto & point) { return point.id() == p.id(); }); - }); - - if ( - shared_point_itr_init == expanded_bound.end() || - shared_point_itr_last == expanded_bound.rend()) { - continue; - } - - // Step3. overwrite duplicate drivable bound by intersection bound. - { - const auto trim_point_itr_init = std::find_if( - intersection_bound.begin(), intersection_bound.end(), - [&](const auto & p) { return p.id() == shared_point_itr_init->id(); }); - - const auto trim_point_itr_last = std::find_if( - intersection_bound.begin(), intersection_bound.end(), - [&](const auto & p) { return p.id() == shared_point_itr_last->id(); }); - - if ( - trim_point_itr_init == intersection_bound.end() || - trim_point_itr_last == intersection_bound.end()) { - continue; - } - - // TODO(Satoshi OTA): remove this guard. - if ( - std::distance(intersection_bound.begin(), trim_point_itr_last) < - std::distance(intersection_bound.begin(), trim_point_itr_init)) { - continue; - } - - std::vector tmp_bound{}; - - tmp_bound.insert(tmp_bound.end(), expanded_bound.begin(), shared_point_itr_init); - tmp_bound.insert(tmp_bound.end(), trim_point_itr_init, trim_point_itr_last); - tmp_bound.insert( - tmp_bound.end(), std::next(shared_point_itr_last).base(), expanded_bound.end()); - - expanded_bound = tmp_bound; - } - } - - return expanded_bound; -} - -// calculate bounds from drivable lanes and hatched road markings -std::vector calcBound( - const std::shared_ptr route_handler, - const std::vector & drivable_lanes, - const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, - const bool is_left) -{ - // a function to convert drivable lanes to points without duplicated points - const auto convert_to_points = [&](const std::vector & drivable_lanes) { - constexpr double overlap_threshold = 0.01; - - std::vector points; - for (const auto & drivable_lane : drivable_lanes) { - const auto bound = - is_left ? drivable_lane.left_lane.leftBound3d() : drivable_lane.right_lane.rightBound3d(); - for (const auto & point : bound) { - if ( - points.empty() || - overlap_threshold < (points.back().basicPoint2d() - point.basicPoint2d()).norm()) { - points.push_back(point); - } - } - } - return points; - }; - - const auto to_ros_point = [](const std::vector & bound) { - std::vector ret{}; - std::for_each(bound.begin(), bound.end(), [&](const auto & p) { - ret.push_back(lanelet::utils::conversion::toGeomMsgPt(p)); - }); - return ret; - }; - - // Step1. create drivable bound from drivable lanes. - std::vector bound_points = convert_to_points(drivable_lanes); - - // Step2. if there is no drivable area defined by polygon, return original drivable bound. - if (!enable_expanding_hatched_road_markings && !enable_expanding_intersection_areas) { - return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); - } - - // Step3. if there are hatched road markings, expand drivable bound with the polygon. - if (enable_expanding_hatched_road_markings) { - bound_points = getBoundWithHatchedRoadMarkings(bound_points, route_handler); - } - - if (!enable_expanding_intersection_areas) { - return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); - } - - // Step4. if there are intersection areas, expand drivable bound with the polygon. - { - bound_points = - getBoundWithIntersectionAreas(bound_points, route_handler, drivable_lanes, is_left); - } - - return motion_utils::removeOverlapPoints(to_ros_point(bound_points)); -} - -void makeBoundLongitudinallyMonotonic( - PathWithLaneId & path, const std::shared_ptr & planner_data, - const bool is_bound_left) -{ - using motion_utils::findNearestSegmentIndex; - using tier4_autoware_utils::calcAzimuthAngle; - using tier4_autoware_utils::calcDistance2d; - using tier4_autoware_utils::calcOffsetPose; - using tier4_autoware_utils::createQuaternionFromRPY; - using tier4_autoware_utils::getPoint; - using tier4_autoware_utils::getPose; - using tier4_autoware_utils::intersect; - using tier4_autoware_utils::normalizeRadian; - - const auto set_orientation = []( - auto & bound_with_pose, const auto idx, const auto & orientation) { - bound_with_pose.at(idx).orientation = orientation; - }; - - const auto get_intersect_idx = []( - const auto & bound_with_pose, const auto start_idx, - const auto & p1, const auto & p2) -> boost::optional { - std::vector> intersects; - for (size_t i = start_idx; i < bound_with_pose.size() - 1; i++) { - const auto opt_intersect = - intersect(p1, p2, bound_with_pose.at(i).position, bound_with_pose.at(i + 1).position); - - if (!opt_intersect) { - continue; - } - - intersects.emplace_back(i, *opt_intersect); - } - - if (intersects.empty()) { - return boost::none; - } - - std::sort(intersects.begin(), intersects.end(), [&](const auto & a, const auto & b) { - return calcDistance2d(p1, a.second) < calcDistance2d(p1, b.second); - }); - - return intersects.front().first; - }; - - const auto get_bound_with_pose = [&](const auto & bound_with_pose, const auto & path_points) { - auto ret = bound_with_pose; - - const double offset = is_bound_left ? 100.0 : -100.0; - - size_t start_bound_idx = 0; - - const size_t start_path_idx = - findNearestSegmentIndex(path_points, bound_with_pose.front().position); - - // append bound point with point - for (size_t i = start_path_idx + 1; i < path_points.size(); i++) { - const auto p_path_offset = calcOffsetPose(getPose(path_points.at(i)), 0.0, offset, 0.0); - const auto intersect_idx = get_intersect_idx( - bound_with_pose, start_bound_idx, getPoint(path_points.at(i)), getPoint(p_path_offset)); - - if (!intersect_idx) { - continue; - } - - if (i + 1 == path_points.size()) { - for (size_t j = intersect_idx.get(); j < bound_with_pose.size(); j++) { - if (j + 1 == bound_with_pose.size()) { - const auto yaw = - calcAzimuthAngle(bound_with_pose.at(j - 1).position, bound_with_pose.at(j).position); - set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); - } else { - const auto yaw = - calcAzimuthAngle(bound_with_pose.at(j).position, bound_with_pose.at(j + 1).position); - set_orientation(ret, j, createQuaternionFromRPY(0.0, 0.0, yaw)); - } - } - } else { - for (size_t j = intersect_idx.get() + 1; j < bound_with_pose.size(); j++) { - set_orientation(ret, j, getPose(path_points.at(i)).orientation); - } - } - - constexpr size_t OVERLAP_CHECK_NUM = 3; - start_bound_idx = - intersect_idx.get() < OVERLAP_CHECK_NUM ? 0 : intersect_idx.get() - OVERLAP_CHECK_NUM; - } - - return ret; - }; - - const auto is_non_monotonic = [&]( - const auto & base_pose, const auto & point, - const auto is_points_left, const auto is_reverse) { - const auto p_transformed = tier4_autoware_utils::inverseTransformPoint(point, base_pose); - if (p_transformed.x < 0.0 && p_transformed.y > 0.0) { - return is_points_left && !is_reverse; + lanelet::ConstLanelet goal_lane; + const bool is_failed_getting_lanelet = std::invoke([&]() { + if (utils::isInLanelets(goal_pose, shoulder_lanes)) { + return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); } + return !route_handler->getGoalLanelet(&goal_lane); + }); + if (is_failed_getting_lanelet) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("behavior_path_planner").get_child("util"), "cannot find goal lanelet"); + return true; + } - if (p_transformed.x < 0.0 && p_transformed.y < 0.0) { - return !is_points_left && !is_reverse; + // If ego vehicle is over goal on goal lane, return true + const double yaw_threshold = tier4_autoware_utils::deg2rad(90); + if (isInLaneletWithYawThreshold(self_pose, goal_lane, yaw_threshold)) { + constexpr double buffer = 1.0; + const auto ego_arc_coord = lanelet::utils::getArcCoordinates({goal_lane}, self_pose); + const auto goal_arc_coord = + lanelet::utils::getArcCoordinates({goal_lane}, route_handler->getGoalPose()); + if (ego_arc_coord.length > goal_arc_coord.length + buffer) { + return true; + } else { + return false; } + } - if (p_transformed.x > 0.0 && p_transformed.y > 0.0) { - return is_points_left && is_reverse; + // If ego vehicle is out of the closest lanelet, return true + // Check if ego vehicle is in shoulder lane + const bool is_in_shoulder_lane = std::invoke([&]() { + lanelet::Lanelet closest_shoulder_lanelet; + if (!lanelet::utils::query::getClosestLanelet( + shoulder_lanes, self_pose, &closest_shoulder_lanelet)) { + return false; } - - if (p_transformed.x > 0.0 && p_transformed.y < 0.0) { - return !is_points_left && is_reverse; + return lanelet::utils::isInLanelet(self_pose, closest_shoulder_lanelet); + }); + // Check if ego vehicle is in road lane + const bool is_in_road_lane = std::invoke([&]() { + lanelet::ConstLanelet closest_road_lane; + if (!route_handler->getClosestLaneletWithinRoute(self_pose, &closest_road_lane)) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("behavior_path_planner").get_child("util"), + "cannot find closest road lanelet"); + return false; } - return false; - }; - - // define a function to remove non monotonic point on bound - const auto remove_non_monotonic_point = [&](const auto & bound_with_pose, const bool is_reverse) { - std::vector monotonic_bound; - - size_t bound_idx = 0; - while (true) { - monotonic_bound.push_back(bound_with_pose.at(bound_idx)); - - if (bound_idx + 1 == bound_with_pose.size()) { - break; - } - - // NOTE: is_bound_left is used instead of is_points_left since orientation of path point is - // opposite. - const double lat_offset = is_bound_left ? 100.0 : -100.0; - - const auto p_bound_1 = getPose(bound_with_pose.at(bound_idx)); - const auto p_bound_2 = getPose(bound_with_pose.at(bound_idx + 1)); - - const auto p_bound_offset = calcOffsetPose(p_bound_1, 0.0, lat_offset, 0.0); - - if (!is_non_monotonic(p_bound_1, p_bound_2.position, is_bound_left, is_reverse)) { - bound_idx++; - continue; - } + if (lanelet::utils::isInLanelet(self_pose, closest_road_lane)) { + return true; + } - // skip non monotonic points - for (size_t i = bound_idx + 1; i < bound_with_pose.size() - 1; ++i) { - const auto intersect_point = intersect( - p_bound_1.position, p_bound_offset.position, bound_with_pose.at(i).position, - bound_with_pose.at(i + 1).position); - - if (intersect_point) { - Pose pose; - pose.position = *intersect_point; - pose.position.z = bound_with_pose.at(i).position.z; - const auto yaw = calcAzimuthAngle(*intersect_point, bound_with_pose.at(i + 1).position); - pose.orientation = createQuaternionFromRPY(0.0, 0.0, yaw); - monotonic_bound.push_back(pose); - bound_idx = i; - break; - } + // check previous lanes for backward driving (e.g. pull out) + const auto prev_lanes = route_handler->getPreviousLanelets(closest_road_lane); + for (const auto & lane : prev_lanes) { + if (lanelet::utils::isInLanelet(self_pose, lane)) { + return true; } - - bound_idx++; } - return monotonic_bound; - }; - - const auto remove_orientation = [](const auto & bound_with_pose) { - std::vector ret; - - ret.reserve(bound_with_pose.size()); + return false; + }); + if (!is_in_shoulder_lane && !is_in_road_lane) { + return true; + } - std::for_each(bound_with_pose.begin(), bound_with_pose.end(), [&ret](const auto & p) { - ret.push_back(p.position); - }); + return false; +} - return ret; - }; +bool isEgoWithinOriginalLane( + const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, + const BehaviorPathPlannerParameters & common_param, const double outer_margin) +{ + const auto lane_length = lanelet::utils::getLaneletLength2d(current_lanes); + const auto lane_poly = lanelet::utils::getPolygonFromArcLength(current_lanes, 0, lane_length); + const auto base_link2front = common_param.base_link2front; + const auto base_link2rear = common_param.base_link2rear; + const auto vehicle_width = common_param.vehicle_width; + const auto vehicle_poly = + tier4_autoware_utils::toFootprint(current_pose, base_link2front, base_link2rear, vehicle_width); - const auto remove_sharp_points = [](const auto & bound) { - if (bound.size() < 2) { - return bound; + // Check if the ego vehicle is entirely within the lane with a given outer margin. + for (const auto & p : vehicle_poly.outer()) { + // When the point is in the polygon, the distance is 0. When it is out of the polygon, return a + // positive value. + const auto dist = boost::geometry::distance(p, lanelet::utils::to2D(lane_poly).basicPolygon()); + if (dist > std::max(outer_margin, 0.0)) { + return false; // out of polygon } + } - std::vector ret = bound; - auto itr = std::next(ret.begin()); - while (std::next(itr) != ret.end()) { - if (itr == ret.begin()) { - itr++; - continue; - } - - const auto p1 = *std::prev(itr); - const auto p2 = *itr; - const auto p3 = *std::next(itr); - - const std::vector vec_1to2 = {p2.x - p1.x, p2.y - p1.y, p2.z - p1.z}; - const std::vector vec_3to2 = {p2.x - p3.x, p2.y - p3.y, p2.z - p3.z}; - const auto product = - std::inner_product(vec_1to2.begin(), vec_1to2.end(), vec_3to2.begin(), 0.0); - - const auto dist_1to2 = tier4_autoware_utils::calcDistance3d(p1, p2); - const auto dist_3to2 = tier4_autoware_utils::calcDistance3d(p3, p2); - - constexpr double epsilon = 1e-3; - - // Remove overlapped point. - if (dist_1to2 < epsilon || dist_3to2 < epsilon) { - itr = std::prev(ret.erase(itr)); - continue; - } - - // If the angle between the points is sharper than 45 degrees, remove the middle point. - if (std::cos(M_PI_4) < product / dist_1to2 / dist_3to2 + epsilon) { - itr = std::prev(ret.erase(itr)); - continue; - } + return true; // inside polygon +} - itr++; - } +lanelet::ConstLanelets transformToLanelets(const DrivableLanes & drivable_lanes) +{ + lanelet::ConstLanelets lanes; - return ret; + const auto has_same_lane = [&](const auto & lane) { + if (lanes.empty()) return false; + const auto has_same = [&](const auto & ll) { return ll.id() == lane.id(); }; + return std::find_if(lanes.begin(), lanes.end(), has_same) != lanes.end(); }; - const auto original_bound = is_bound_left ? path.left_bound : path.right_bound; - - if (path.points.empty()) { - return; - } - - if (original_bound.empty()) { - return; + lanes.push_back(drivable_lanes.right_lane); + if (!has_same_lane(drivable_lanes.left_lane)) { + lanes.push_back(drivable_lanes.left_lane); } - if (path.points.front().lane_ids.empty()) { - return; + for (const auto & ml : drivable_lanes.middle_lanes) { + if (!has_same_lane(ml)) { + lanes.push_back(ml); + } } - // step.1 create bound with pose vector. - std::vector original_bound_with_pose; - { - original_bound_with_pose.reserve(original_bound.size()); + return lanes; +} - std::for_each(original_bound.begin(), original_bound.end(), [&](const auto & p) { - Pose pose; - pose.position = p; - original_bound_with_pose.push_back(pose); - }); +lanelet::ConstLanelets transformToLanelets(const std::vector & drivable_lanes) +{ + lanelet::ConstLanelets lanes; - for (size_t i = 0; i < original_bound_with_pose.size(); i++) { - if (i + 1 == original_bound_with_pose.size()) { - const auto yaw = calcAzimuthAngle( - original_bound_with_pose.at(i - 1).position, original_bound_with_pose.at(i).position); - set_orientation(original_bound_with_pose, i, createQuaternionFromRPY(0.0, 0.0, yaw)); - } else { - const auto yaw = calcAzimuthAngle( - original_bound_with_pose.at(i).position, original_bound_with_pose.at(i + 1).position); - set_orientation(original_bound_with_pose, i, createQuaternionFromRPY(0.0, 0.0, yaw)); - } - } + for (const auto & drivable_lane : drivable_lanes) { + const auto transformed_lane = transformToLanelets(drivable_lane); + lanes.insert(lanes.end(), transformed_lane.begin(), transformed_lane.end()); } - // step.2 get base pose vector. - std::vector clipped_points; - { - const auto & route_handler = planner_data->route_handler; - const auto p = planner_data->parameters; - const auto start_id = path.points.front().lane_ids.front(); - const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id); - - const auto lanelet_sequence = - route_handler->getLaneletSequence(start_lane, p.backward_path_length, p.forward_path_length); - const auto centerline_path = getCenterLinePath( - *route_handler, lanelet_sequence, getPose(path.points.front()), p.backward_path_length, - p.forward_path_length, p); - - if (centerline_path.points.size() < 2) { - return; - } - - const auto ego_idx = planner_data->findEgoIndex(centerline_path.points); - const auto end_idx = findNearestSegmentIndex(centerline_path.points, original_bound.back()); + return lanes; +} - if (ego_idx >= end_idx) { - return; +boost::optional getRightLanelet( + const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes) +{ + for (const auto & shoulder_lane : shoulder_lanes) { + if (shoulder_lane.leftBound().id() == current_lane.rightBound().id()) { + return shoulder_lane; } - - clipped_points.insert( - clipped_points.end(), centerline_path.points.begin() + ego_idx, - centerline_path.points.begin() + end_idx + 1); - } - - if (clipped_points.empty()) { - return; } - // step.3 update bound pose by reference path pose. - const auto updated_bound_with_pose = - get_bound_with_pose(original_bound_with_pose, clipped_points); // for reverse - - // step.4 create remove monotonic points by forward direction. - auto half_monotonic_bound_with_pose = - remove_non_monotonic_point(updated_bound_with_pose, false); // for reverse - std::reverse(half_monotonic_bound_with_pose.begin(), half_monotonic_bound_with_pose.end()); - - // step.5 create remove monotonic points by backward direction. - auto full_monotonic_bound_with_pose = - remove_non_monotonic_point(half_monotonic_bound_with_pose, true); - std::reverse(full_monotonic_bound_with_pose.begin(), full_monotonic_bound_with_pose.end()); - - // step.6 remove orientation from bound with pose. - auto full_monotonic_bound = remove_orientation(full_monotonic_bound_with_pose); - - // step.7 remove sharp bound points. - if (is_bound_left) { - path.left_bound = remove_sharp_points(full_monotonic_bound); - } else { - path.right_bound = remove_sharp_points(full_monotonic_bound); - } + return {}; } -// generate drivable area by expanding path for freespace -void generateDrivableArea( - PathWithLaneId & path, const double vehicle_length, const double offset, - const bool is_driving_forward) +boost::optional getLeftLanelet( + const lanelet::ConstLanelet & current_lane, const lanelet::ConstLanelets & shoulder_lanes) { - using tier4_autoware_utils::calcOffsetPose; - - // remove path points which is close to the previous point - PathWithLaneId resampled_path{}; - const double resample_interval = 2.0; - for (size_t i = 0; i < path.points.size(); ++i) { - if (i == 0) { - resampled_path.points.push_back(path.points.at(i)); - } else { - const auto & prev_point = resampled_path.points.back().point.pose.position; - const auto & curr_point = path.points.at(i).point.pose.position; - const double signed_arc_length = - motion_utils::calcSignedArcLength(path.points, prev_point, curr_point); - if (signed_arc_length > resample_interval) { - resampled_path.points.push_back(path.points.at(i)); - } + for (const auto & shoulder_lane : shoulder_lanes) { + if (shoulder_lane.rightBound().id() == current_lane.leftBound().id()) { + return shoulder_lane; } } - // add last point of path if enough far from the one of resampled path - constexpr double th_last_point_distance = 0.3; - if ( - tier4_autoware_utils::calcDistance2d( - resampled_path.points.back().point.pose.position, path.points.back().point.pose.position) > - th_last_point_distance) { - resampled_path.points.push_back(path.points.back()); - } - - // create bound point by calculating offset point - std::vector left_bound; - std::vector right_bound; - for (const auto & point : resampled_path.points) { - const auto & pose = point.point.pose; - - const auto left_point = calcOffsetPose(pose, 0, offset, 0); - const auto right_point = calcOffsetPose(pose, 0, -offset, 0); - - left_bound.push_back(left_point.position); - right_bound.push_back(right_point.position); - } - - if (is_driving_forward) { - // add backward offset point to bound - const Pose first_point = - calcOffsetPose(resampled_path.points.front().point.pose, -vehicle_length, 0, 0); - const Pose left_first_point = calcOffsetPose(first_point, 0, offset, 0); - const Pose right_first_point = calcOffsetPose(first_point, 0, -offset, 0); - left_bound.insert(left_bound.begin(), left_first_point.position); - right_bound.insert(right_bound.begin(), right_first_point.position); - - // add forward offset point to bound - const Pose last_point = - calcOffsetPose(resampled_path.points.back().point.pose, vehicle_length, 0, 0); - const Pose left_last_point = calcOffsetPose(last_point, 0, offset, 0); - const Pose right_last_point = calcOffsetPose(last_point, 0, -offset, 0); - left_bound.push_back(left_last_point.position); - right_bound.push_back(right_last_point.position); - } else { - // add forward offset point to bound - const Pose first_point = - calcOffsetPose(resampled_path.points.front().point.pose, vehicle_length, 0, 0); - const Pose left_first_point = calcOffsetPose(first_point, 0, offset, 0); - const Pose right_first_point = calcOffsetPose(first_point, 0, -offset, 0); - left_bound.insert(left_bound.begin(), left_first_point.position); - right_bound.insert(right_bound.begin(), right_first_point.position); - - // add backward offset point to bound - const Pose last_point = - calcOffsetPose(resampled_path.points.back().point.pose, -vehicle_length, 0, 0); - const Pose left_last_point = calcOffsetPose(last_point, 0, offset, 0); - const Pose right_last_point = calcOffsetPose(last_point, 0, -offset, 0); - left_bound.push_back(left_last_point.position); - right_bound.push_back(right_last_point.position); - } - - if (left_bound.empty() || right_bound.empty()) { - return; - } - - // fix intersected bound - // if bound is intersected, remove them and insert intersection point - typedef boost::geometry::model::d2::point_xy BoostPoint; - typedef boost::geometry::model::linestring LineString; - auto modify_bound_intersection = [](const std::vector & bound) { - const double intersection_check_distance = 10.0; - std::vector modified_bound; - size_t i = 0; - while (i < bound.size() - 1) { - BoostPoint p1(bound.at(i).x, bound.at(i).y); - BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); - LineString p_line; - p_line.push_back(p1); - p_line.push_back(p2); - bool intersection_found = false; - for (size_t j = i + 2; j < bound.size() - 1; j++) { - const double distance = tier4_autoware_utils::calcDistance2d(bound.at(i), bound.at(j)); - if (distance > intersection_check_distance) { - break; - } - LineString q_line; - BoostPoint q1(bound.at(j).x, bound.at(j).y); - BoostPoint q2(bound.at(j + 1).x, bound.at(j + 1).y); - q_line.push_back(q1); - q_line.push_back(q2); - std::vector intersection_points; - boost::geometry::intersection(p_line, q_line, intersection_points); - if (intersection_points.size() > 0) { - modified_bound.push_back(bound.at(i)); - Point intersection_point; - intersection_point.x = intersection_points.at(0).x(); - intersection_point.y = intersection_points.at(0).y(); - modified_bound.push_back(intersection_point); - i = j + 1; - intersection_found = true; - break; - } - } - if (!intersection_found) { - modified_bound.push_back(bound.at(i)); - i++; - } - } - modified_bound.push_back(bound.back()); - return modified_bound; - }; - std::vector modified_left_bound = modify_bound_intersection(left_bound); - std::vector modified_right_bound = modify_bound_intersection(right_bound); - // set bound to path - path.left_bound = modified_left_bound; - path.right_bound = modified_right_bound; + return {}; } +// generate drivable area by expanding path for freespace double getDistanceToEndOfLane(const Pose & current_pose, const lanelet::ConstLanelets & lanelets) { const auto & arc_coordinates = lanelet::utils::getArcCoordinates(lanelets, current_pose); @@ -2759,72 +1114,6 @@ std::shared_ptr generateCenterLinePath( return centerline_path; } -// TODO(Azu) Some parts of is the same with generateCenterLinePath. Therefore it might be better if -// we can refactor some of the code for better readability -lanelet::ConstLineStrings3d getMaximumDrivableArea( - const std::shared_ptr & planner_data) -{ - const auto & p = planner_data->parameters; - const auto & route_handler = planner_data->route_handler; - const auto & ego_pose = planner_data->self_odometry->pose.pose; - - lanelet::ConstLanelet current_lane; - if (!route_handler->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("utils"), - "failed to find closest lanelet within route!!!"); - return {}; - } - - const auto current_lanes = route_handler->getLaneletSequence( - current_lane, ego_pose, p.backward_path_length, p.forward_path_length); - lanelet::ConstLineStrings3d linestring_shared; - for (const auto & lane : current_lanes) { - lanelet::ConstLineStrings3d furthest_line = route_handler->getFurthestLinestring(lane); - linestring_shared.insert(linestring_shared.end(), furthest_line.begin(), furthest_line.end()); - } - - return linestring_shared; -} - -std::vector expandLanelets( - const std::vector & drivable_lanes, const double left_bound_offset, - const double right_bound_offset, const std::vector & types_to_skip) -{ - if (left_bound_offset == 0.0 && right_bound_offset == 0.0) return drivable_lanes; - - std::vector expanded_drivable_lanes{}; - expanded_drivable_lanes.reserve(drivable_lanes.size()); - for (const auto & lanes : drivable_lanes) { - const std::string l_type = - lanes.left_lane.leftBound().attributeOr(lanelet::AttributeName::Type, "none"); - const std::string r_type = - lanes.right_lane.rightBound().attributeOr(lanelet::AttributeName::Type, "none"); - - const bool l_skip = - std::find(types_to_skip.begin(), types_to_skip.end(), l_type) != types_to_skip.end(); - const bool r_skip = - std::find(types_to_skip.begin(), types_to_skip.end(), r_type) != types_to_skip.end(); - const double l_offset = l_skip ? 0.0 : left_bound_offset; - const double r_offset = r_skip ? 0.0 : -right_bound_offset; - - DrivableLanes expanded_lanes; - if (lanes.left_lane.id() == lanes.right_lane.id()) { - expanded_lanes.left_lane = - lanelet::utils::getExpandedLanelet(lanes.left_lane, l_offset, r_offset); - expanded_lanes.right_lane = - lanelet::utils::getExpandedLanelet(lanes.right_lane, l_offset, r_offset); - } else { - expanded_lanes.left_lane = lanelet::utils::getExpandedLanelet(lanes.left_lane, l_offset, 0.0); - expanded_lanes.right_lane = - lanelet::utils::getExpandedLanelet(lanes.right_lane, 0.0, r_offset); - } - expanded_lanes.middle_lanes = lanes.middle_lanes; - expanded_drivable_lanes.push_back(expanded_lanes); - } - return expanded_drivable_lanes; -} - PathWithLaneId getCenterLinePathFromRootLanelet( const lanelet::ConstLanelet & root_lanelet, const std::shared_ptr & planner_data) @@ -2937,58 +1226,6 @@ PathWithLaneId setDecelerationVelocity( return reference_path; } -BehaviorModuleOutput getReferencePath( - const lanelet::ConstLanelet & current_lane, - const std::shared_ptr & planner_data) -{ - PathWithLaneId reference_path{}; - - const auto & route_handler = planner_data->route_handler; - const auto current_pose = planner_data->self_odometry->pose.pose; - const auto p = planner_data->parameters; - - // Set header - reference_path.header = route_handler->getRouteHeader(); - - // calculate path with backward margin to avoid end points' instability by spline interpolation - constexpr double extra_margin = 10.0; - const double backward_length = p.backward_path_length + extra_margin; - const auto current_lanes_with_backward_margin = - route_handler->getLaneletSequence(current_lane, backward_length, p.forward_path_length); - const auto no_shift_pose = - lanelet::utils::getClosestCenterPose(current_lane, current_pose.position); - reference_path = getCenterLinePath( - *route_handler, current_lanes_with_backward_margin, no_shift_pose, backward_length, - p.forward_path_length, p); - - // clip backward length - // NOTE: In order to keep backward_path_length at least, resampling interval is added to the - // backward. - const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - reference_path.points, no_shift_pose, p.ego_nearest_dist_threshold, - p.ego_nearest_yaw_threshold); - reference_path.points = motion_utils::cropPoints( - reference_path.points, no_shift_pose.position, current_seg_idx, p.forward_path_length, - p.backward_path_length + p.input_path_interval); - - const auto drivable_lanelets = getLaneletsFromPath(reference_path, route_handler); - const auto drivable_lanes = generateDrivableLanes(drivable_lanelets); - - const auto & dp = planner_data->drivable_area_expansion_parameters; - - const auto shorten_lanes = cutOverlappedLanes(reference_path, drivable_lanes); - const auto expanded_lanes = expandLanelets( - shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - - BehaviorModuleOutput output; - output.path = std::make_shared(reference_path); - output.reference_path = std::make_shared(reference_path); - output.drivable_area_info.drivable_lanes = drivable_lanes; - - return output; -} - std::uint8_t getHighestProbLabel(const std::vector & classification) { std::uint8_t label = ObjectClassification::UNKNOWN; @@ -3339,192 +1576,4 @@ std::string convertToSnakeCase(const std::string & input_str) } return output_str; } - -std::vector combineDrivableLanes( - const std::vector & original_drivable_lanes_vec, - const std::vector & new_drivable_lanes_vec) -{ - const auto has_same_lane = - [](const lanelet::ConstLanelet & target_lane, const lanelet::ConstLanelets & lanes) { - return std::find_if(lanes.begin(), lanes.end(), [&](const auto & ll) { - return ll.id() == target_lane.id(); - }) != lanes.end(); - }; - - const auto convert_to_lanes = [](const DrivableLanes & drivable_lanes) { - auto lanes = drivable_lanes.middle_lanes; - lanes.push_back(drivable_lanes.right_lane); - lanes.push_back(drivable_lanes.left_lane); - return lanes; - }; - - auto updated_drivable_lanes_vec = original_drivable_lanes_vec; - size_t new_drivable_lanes_idx = 0; - for (auto & updated_drivable_lanes : updated_drivable_lanes_vec) { - // calculated corresponding index of new_drivable_lanes - const auto opt_new_drivable_lanes_idx = [&]() -> std::optional { - for (size_t n_idx = 0; n_idx < new_drivable_lanes_vec.size(); ++n_idx) { - for (const auto & ll : convert_to_lanes(updated_drivable_lanes)) { - if (has_same_lane(ll, convert_to_lanes(new_drivable_lanes_vec.at(n_idx)))) { - return n_idx; - } - } - } - return std::nullopt; - }(); - if (!opt_new_drivable_lanes_idx) { - continue; - } - new_drivable_lanes_idx = *opt_new_drivable_lanes_idx; - const auto & new_drivable_lanes = new_drivable_lanes_vec.at(new_drivable_lanes_idx); - - // update left lane - if (has_same_lane(updated_drivable_lanes.left_lane, convert_to_lanes(new_drivable_lanes))) { - updated_drivable_lanes.left_lane = new_drivable_lanes.left_lane; - } - // update right lane - if (has_same_lane(updated_drivable_lanes.right_lane, convert_to_lanes(new_drivable_lanes))) { - updated_drivable_lanes.right_lane = new_drivable_lanes.right_lane; - } - // update middle lanes - for (const auto & middle_lane : convert_to_lanes(new_drivable_lanes)) { - if (!has_same_lane(middle_lane, convert_to_lanes(updated_drivable_lanes))) { - updated_drivable_lanes.middle_lanes.push_back(middle_lane); - } - } - - // validate middle lanes - auto & middle_lanes = updated_drivable_lanes.middle_lanes; - if (has_same_lane(updated_drivable_lanes.right_lane, middle_lanes)) { - middle_lanes.erase( - std::remove( - std::begin(middle_lanes), std::end(middle_lanes), updated_drivable_lanes.right_lane), - std::cend(middle_lanes)); - } - if (has_same_lane(updated_drivable_lanes.left_lane, middle_lanes)) { - middle_lanes.erase( - std::remove( - std::begin(middle_lanes), std::end(middle_lanes), updated_drivable_lanes.left_lane), - std::cend(middle_lanes)); - } - } - // NOTE: If original_drivable_lanes_vec is shorter than new_drivable_lanes_vec, push back remained - // new_drivable_lanes_vec. - if (new_drivable_lanes_idx + 1 < new_drivable_lanes_vec.size()) { - updated_drivable_lanes_vec.insert( - updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, - new_drivable_lanes_vec.end()); - } - - return updated_drivable_lanes_vec; -} - -DrivableAreaInfo combineDrivableAreaInfo( - const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2) -{ - DrivableAreaInfo combined_drivable_area_info; - - // drivable lanes - combined_drivable_area_info.drivable_lanes = - combineDrivableLanes(drivable_area_info1.drivable_lanes, drivable_area_info2.drivable_lanes); - - // obstacles - for (const auto & obstacle : drivable_area_info1.obstacles) { - combined_drivable_area_info.obstacles.push_back(obstacle); - } - for (const auto & obstacle : drivable_area_info2.obstacles) { - combined_drivable_area_info.obstacles.push_back(obstacle); - } - - // enable expanding hatched road markings - combined_drivable_area_info.enable_expanding_hatched_road_markings = - drivable_area_info1.enable_expanding_hatched_road_markings || - drivable_area_info2.enable_expanding_hatched_road_markings; - - // enable expanding intersection areas - combined_drivable_area_info.enable_expanding_intersection_areas = - drivable_area_info1.enable_expanding_intersection_areas || - drivable_area_info2.enable_expanding_intersection_areas; - - return combined_drivable_area_info; -} - -// NOTE: Assuming that path.right/left_bound is already created. -void extractObstaclesFromDrivableArea( - PathWithLaneId & path, const std::vector & obstacles) -{ - if (obstacles.empty()) { - return; - } - - std::vector> right_polygons; - std::vector> left_polygons; - for (const auto & obstacle : obstacles) { - const auto & obj_pos = obstacle.pose.position; - - // get edge points of the object - const size_t nearest_path_idx = - motion_utils::findNearestIndex(path.points, obj_pos); // to get z for object polygon - std::vector edge_points; - for (size_t i = 0; i < obstacle.poly.outer().size() - 1; - ++i) { // NOTE: There is a duplicated points - edge_points.push_back(tier4_autoware_utils::createPoint( - obstacle.poly.outer().at(i).x(), obstacle.poly.outer().at(i).y(), - path.points.at(nearest_path_idx).point.pose.position.z)); - } - - // get a boundary that we have to change - const bool is_object_right = !obstacle.is_left; - const auto & bound = is_object_right ? path.right_bound : path.left_bound; - - // get polygon points inside the bounds - const auto inside_polygon = - drivable_area_processing::getPolygonPointsInsideBounds(bound, edge_points, is_object_right); - if (!inside_polygon.empty()) { - if (is_object_right) { - right_polygons.push_back(inside_polygon); - } else { - left_polygons.push_back(inside_polygon); - } - } - } - - for (const bool is_object_right : {true, false}) { - const auto & polygons = is_object_right ? right_polygons : left_polygons; - if (polygons.empty()) { - continue; - } - - // concatenate polygons if they are longitudinal overlapped. - auto unique_polygons = drivable_area_processing::concatenatePolygons(polygons); - - // sort bounds longitudinally - std::sort( - unique_polygons.begin(), unique_polygons.end(), - [](const std::vector & p1, const std::vector & p2) { - return p2.front().is_after(p1.front()); - }); - - // update boundary - auto & bound = is_object_right ? path.right_bound : path.left_bound; - bound = drivable_area_processing::updateBoundary(bound, unique_polygons); - } -} - -lanelet::ConstLanelets combineLanelets( - const lanelet::ConstLanelets & base_lanes, const lanelet::ConstLanelets & added_lanes) -{ - lanelet::ConstLanelets combined_lanes = base_lanes; - for (const auto & added_lane : added_lanes) { - const auto it = std::find_if( - combined_lanes.begin(), combined_lanes.end(), - [&added_lane](const lanelet::ConstLanelet & lane) { return lane.id() == added_lane.id(); }); - if (it == combined_lanes.end()) { - combined_lanes.push_back(added_lane); - } - } - - return combined_lanes; -} - } // namespace behavior_path_planner::utils diff --git a/planning/behavior_path_planner/test/test_utils.cpp b/planning/behavior_path_planner/test/test_utils.cpp index 4eefa27e88806..46e08c6697f65 100644 --- a/planning/behavior_path_planner/test/test_utils.cpp +++ b/planning/behavior_path_planner/test/test_utils.cpp @@ -11,6 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner/utils/utils.hpp" #include "input.hpp" #include "lanelet2_core/Attribute.h" diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_optimizer/src/utils.cpp index d5169ac17af8a..ef05f98c368d9 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_optimizer/src/utils.cpp @@ -15,7 +15,7 @@ #include "static_centerline_optimizer/utils.hpp" #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/utils/utils.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/static_drivable_area.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" From 691ab7848ac6fa8e383efe564ac2f2bc93669047 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 21 Nov 2023 10:38:19 +0900 Subject: [PATCH 146/223] perf(image_projection_based_fusion): replace std::bitset (#5603) --- .../src/pointpainting_fusion/voxel_generator.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp index f462b9b0ba17a..f1ba163ee69b9 100755 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp @@ -60,9 +60,13 @@ std::size_t VoxelGenerator::pointsToVoxels( point[2] = point_current.z(); point[3] = time_lag; // decode the class value back to one-hot binary and assign it to point - for (std::size_t i = 1; i <= config_.class_size_; i++) { - auto decode = std::bitset<8>(*class_iter).to_string(); - point[3 + i] = decode[-i] == 1 ? 1 : 0; + std::fill(point.begin() + 4, point.end(), 0); + auto class_value = static_cast(*class_iter); + auto iter = point.begin() + 4; + while (class_value > 0) { + *iter = class_value % 2; + class_value /= 2; + ++iter; } out_of_range = false; From 06af6c17ffc6e1377b368115e883a607a68352fa Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 21 Nov 2023 11:35:21 +0900 Subject: [PATCH 147/223] fix(bytetrack): fix uninteded roi value error due to casting int to uint (#5589) * fix uint32 conversion bug in bytetrack Signed-off-by: yoshiri * refactor outside xy variable --------- Signed-off-by: yoshiri --- perception/bytetrack/src/bytetrack_node.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/perception/bytetrack/src/bytetrack_node.cpp b/perception/bytetrack/src/bytetrack_node.cpp index 358a5053b5d4a..eb5e73312a890 100644 --- a/perception/bytetrack/src/bytetrack_node.cpp +++ b/perception/bytetrack/src/bytetrack_node.cpp @@ -83,10 +83,18 @@ void ByteTrackNode::on_rect( bytetrack::ObjectArray objects = bytetrack_->update_tracker(object_array); for (const auto & tracked_object : objects) { tier4_perception_msgs::msg::DetectedObjectWithFeature object; - object.feature.roi.x_offset = tracked_object.x_offset; - object.feature.roi.y_offset = tracked_object.y_offset; - object.feature.roi.width = tracked_object.width; - object.feature.roi.height = tracked_object.height; + // fit xy offset to 0 if roi is outside of image + const int outside_x = std::max(-tracked_object.x_offset, 0); + const int outside_y = std::max(-tracked_object.y_offset, 0); + const int32_t output_x = std::max(tracked_object.x_offset, 0); + const int32_t output_y = std::max(tracked_object.y_offset, 0); + const int32_t output_width = tracked_object.width - outside_x; + const int32_t output_height = tracked_object.height - outside_y; + // convert int32 to uint32 + object.feature.roi.x_offset = static_cast(output_x); + object.feature.roi.y_offset = static_cast(output_y); + object.feature.roi.width = static_cast(output_width); + object.feature.roi.height = static_cast(output_height); object.object.existence_probability = tracked_object.score; object.object.classification.emplace_back( autoware_auto_perception_msgs::build-t>^ z1UMiKglawA*^bVe$C2fH#zS^6h{P3sZOAbHm(9sNukO*|57ftdIZ{UzMt)zjYEG{? z!vz*X{8Y!-v5&VLx=IEbltb}ZJarxA6WH_rSzG4j+@2bmACTBqQdUQ?i%)<}+T#4L zM87{fJpQS^y978+SEhCj?~Bd zE>g!MjQo0UTnUIvh1cFzN?q_##O8fQQYK-aTqwThG4JctGzzZ&_oPc*I`x$1dE=5O ztRt&sK>EMy|7d%E>iTmy|7(!-Ah(t$O{68Z@;z=dS`QNZCA4*xtwcLzuA*)qTw+1c zlhZkHiIwu5m(^GE00nbmS1vqG1cBFedl*-Z;|p)8b;Z!ZH%Nt+R0o|40e5u1wS_97 zFR{7oS1+qfuz_kME}N^*Y}Y>Y9`wTS>r!6nm3Zp<<>GMpNF7-Dc~pi}B){hZYGxDq z!^X3ygCnWF4Uq>WWZ7--4hrR58CNOTK{m+NHf%aT^8*r&!a5G!@)W6q&mckG>SVlK zuT80tcsrkZu8hX}%jYKxEO3df3>Taw@^&-YzONGUuDIxDFJtHd<_qv_3=a~)iKk{u z|G*_S!%Q?-h`t?6h4~*};}rtr8f-QuFrf1m4p-Fh;#dk4k+`usYqRiO=)Auk7aVuh zqdwlENF7-Dok`oQS-6H91m3vbP8W^M`}n22`C|A5X-;*qK$RTq9i)>->he4H+G(Em zs5@nKoK4H<2}oY#twzS%CG12iiT5+V5+yX=>-XGQ;D@|Fc%`ZmPj8>gnr?amdEd+G zytHYb2Pmw2{ge~lLAo!ae%~nMy;E}Zt@V<2U~iH+lwlSE#5RR8HUG;FvQJ&ZvtDK? zSc}B9o|r$f(*T{fy83&e250Ky-H+6vhLK`93oO}?^ zH#!mgV+{p6$gUyV8qJq9&l^W+9kDNZh+mL~-Fpie?*qC$;UwNqPK0elQASt1U3 z&s?cJOys@XronLt@-`X{TV3ww0hqRKyRfGy5lrNHj=YAvn|enSV;R~(k8$t5!tWs< zr10k^#YFV(&2*sWhlI&e5QfCmY|DVl?Dj9EQ zmg^}b-e-1cDx&fJ9bETV8S>V5KX#kQn;}<~V;u6n@>p$q`%$>}zIbN4@cBf*@1f?< z1bIK-dyt`pu^r_8!RNod6$<7DXFHVD(XYKdATWMvU&Rh^L;u9RW7~87#9H*z+o7|8 z{6+@UH~&9E>UfWlU(=IFc@_9_;<+nPSw)+$PjBmfpN!0g*WL=+&oSlLV)MS9BdPO5 zWh>2hZ{8b})xmkRD9P{Gf6xDuW;Lq*376QdWIgC$$E)P_!w_7WN>GMn%1Aum_!y$lrG$&mF8PG8a`6P68YIc=RRV{4cq1#GYw^0PdX< z6!{5Xv70MXh0FHgY4jy_#O5%8Ge(f==Kmz54y^nf zw}zsveA?EedM{#RD|?rtq$itp0kSN_fX1T#L+rLESP;Wf?oAYXUN>ZmVQ zrF#*(c!5-#jJJ3CPz-5_U0@}sq48!HNj826d20yVe@W!cv1CFt7xGR}O9AG1chIu? z3$q|s5)j9;H3>uBh98;DFGJpZ5^q+2U=9W0d@d)J!cXy{{nPgx{GbwO&juoqxa!)e zrj?=Sye*cg7N=gNKHdkBIe zXV7^w(8t9zN3nq&NSuJDgq*k^I`489oXF>g)W@3{siOiTKZA#E!wDtaU_xSzs&yMS z@4dCn9?x?%@#7s8Dfhgwzur2(yiMuC3oDu*kn{y9tAm$w$GM=m#qO;|#@kcrc{+)= zp__{;8t(_^PCV{|yt8H^^@zM9ZGLfOLEhUQubObD^8gcb+3%l!N(Ae+wwG~1-sXHx z5>=3Qd!FrZ+w&0cyJFbkU@$swvp}|rLxpSrSNTtzotfnGUT<{XOjDe;PM@fcw-r(c zR(_l%$Md8PmAVe@9#Rv>oZi6(xAsc!eu1_~ZdOd9)6XGi<^O%ZVK{onil(YF6o^yhH?*CXpe0T1UFzaT}N{{;=~n9zC< z|C2(TFYG~SI&u*z%xKQIf!AP6Aj3HcEL4XC1i~J~|Mdgi;4cEu z{7eW5vWD;fXZT?&uoAro1w2*X>3ob8Fd}h0N=qbMzd4}}RE{;AIWg@5cq;nME~es- z)Zv7YU$6Y_ispCl{ePnmj2*Vkpw>yM&uRH!iOgC%yqxdGK-uRFnDMxSYag)i{U7)S zNjQadM0n32A4uCy#@qi)Z6R@qCGxJHlw(BW-SP`(brkY`d$y;N$ouRZS1a-T|LX1i zdn1>-1CA>rCc{=qK)68TiU;J)!DDtadzJw7c7LKzd=dh-CFpnPB%||QVg8{vFP9Y< zAaPa8QvdARgucWw&bGhpnxsD7q&k=|@{`{9RU|iy3ls(^$a7r6=1uQZGRD980DkY_ zi^>O_*hlPtPb^+?|)C1FV6ql$awo%dP$LZE8ZJlg2ww;$)AnM zkhkW1{y34h%;Zk5e8~G%8+X}B6?c$PpS?Z6CZX2r`xc3>#X5-`|Ra|Z+PKZd`7zovwLT3G4@dn@1c3#+J`8s!{g=2H~Y^n^42Be z?JIeD@dfF`?p?syNRP%l>eS@63y^nq-Tn>4(_0;g+*%yh(Lz#K`acb=K`dV_ZO1Nyq5wR_x;~tK{iq z%VZb4;En3Xe;Bb(Z*jXn9B{a3OY_|ux0kXyMA{lsiwpj{{!g0KsQM@DK|9HMP)J4N zdr}W7mfXpX)`Nm?FK<LgkxE35_plK zT3QEtkWK76nKeHMpk=nSEV(xXR976I<0(U5V$}~GD*E)81=JyN^i!+ct$EOU&=&)N z`P*XDHy~|6>KMn!j}eG<`aR+Hg#yj|E>f#-w#2w_er-Dn-csJf(kkN#^>+c&B5_!L0 z)1AK@F0r-ch01$;+<^8}L$E+(5~wIslPo3je&SwCH%$Qjc0uQvZifKvJr|RBqS1Mm zGwiGL8Ds(5kvPE{9mlKa(Rn{Id9y!Vjrw?(A$7E1n#k(cn9sgMn~%2<@z63(RiyA zy*pt5c?U4`^bvWd{5qY!1@iXW!6#Lj;s%zj%qy!4O#+{t4fAs#?{9kx6^0@25u4F1 z=MqBz{gT;1B@1-k(+RhqA7W$$Oi0{NmTrmd5A@U93qPuwYHX;F_Yb6wER6iJ6;F>p z5QU$&I1>IzwHKSWOVE{w^k{FqTE&(!-d^l0NR8_F`)jK{(>!k-QOfFY-!8rS&OfiW z&?n=4MBtk*iT7FON)|NU`Da4uEFkaQla1WO<1PP|UGBv9|8o~z=B;;H@W%B(Z~U=xZd2A{6m;(xy*D$l zBQ(!D(ucA-e02w|P5$$7q8((s1IItX|Mkzs2~UUP%xJv(*9g@-2SyjQ5t z==IpKf?6alHB?XY8zcJW#OUPuo`zED<4vk#7e;>a&2_JfuW$hlThZ?`!q~@KV*Y*{ z-K*{J>kcrrJUobfyrnFmt55&Eo93VY=iEeD9i8gi_wP9M-~3P2b3Z9LIREb<>p{n^ z<9J9t=;=wogVuv;R?1dSv6g5zWIRAeX_#XZfF0mJk614VC5Q=G4ESecphwI^J3_sy@zL z?B2V`c!#sL%aM5VS>|)1@eYYq$>oQ(pCj<;qyV z1|-g{H}L1N4d}dwS6ph0Vy8adcab_qF!JMgE4}@bKR1vX;J5r>iOt*Imj8743O9Te zD`T;0Su^Hd9cRAW6R=IuJnzWel-032dE%`PJl^{6{(sVtO~pUq{BKUygW@g(ttIuK z1y^MOv>x<>K1HG$&i^-5_aC){ODy+~p}K2M@C(uk%f2x;xq=Qa)lFbo5)gRg!m=OE z|3`nmTPyaN0P4rSH6K?A1%iig6KfUGm)K61&ua1~n1K)y_tsf+_4`@$BX;|xgLtmA${*>?*gYuH>o)s( zo+GrsgLJ2?4&Je*uY|(I9i$l*_7?&W&z^4aTp9|ThM!nH#-a1Ra`y0j z#T(4v01`L5b#DK?QFPv(+^Wk4x%sJ%_a&qbFO2*IkG}219pV9&=g&5^@nO&Z$IrE0 z@#FWxhv0v2y6cS1`@U~!W#+o~G|&5~7iD#f2@0NRJio}>l#F-GrfxqH@2xt|m!t8H zQ6oHg26>wtdND-g?R>jj_ygp<(l|Z01@d0Tp!8PzD*;pn zUHdaN5d!i`y=|Qb(07pSoJS(pw=je2NF3V^&9vD;bl!AIqbt_PQy=d(qz-zF{6>NT z3~$u%fR&!Ff6*&o^B%DuE8YZoSEz6#j5cAP-r^Kwmyd1vNb|gLVieY)@}%#=KVNUz zOU65z)pj|Fw{-e-J~ZC>${wnHkoQ4dCPCuy7U$iz7#?_W!faro=l6muXjobh7H*jY zicgtHOF`b-O=LT?#t1;>=Id9YZ$p5>#owQ6pP=*Rd{lbBahw@!MB=LJaZ`5h(RrWV zO2^$|Mt!{5kvh^a@>9%rV>>y=4Sbb)O}Y1D^A5GB={E54#K#*S-m`Tb_WZx3IsN#} zS_hhcy~RuoWpyxwG7ca8=jB8uWV|DL4iu4i=d3!yi^lu<+QampAa5nf$2*C<3F8fn z5sC%o=_YofboZ%*0twCfjh_dT7^*b&51k@ zpUsLQ7T}G_tbgd8>BL zyRP-|#0Og}|1NCZ>4emn(z zT^Xjn`M(XRBM>7$`Y+kb^?7-~#Z4LeJaE|a|5rkkY`2jw{`k0JsrCcxJ4kV2AxA># z{|`KaBtlso?(PFFN&kF7%9@OKQb6+G*IUZ!EL)AnJCE_XMIz)~ptin_$h*mHiHHN_ zJrjNV*iQK3^V+g|x$S9*AeVP(X&L0rVsO-y=>q}0_dEak(slTOG&`rH%h%C)Z+_6@ zHlNN6#E>}eS5dDsB+!@G<4Y%U$&T)QSgeL51|udO<$hV{D9OFLRlS5cZ4Q(#4lb!vLfT1sG|FK2kD$cScS&> zvwZ!>vyk^a!+8S9yx-vplH^=O92*irluI^Tz$5td0Z`d_!^G;_;Rx z8SjKy13S{@WXbQ-E75pAIjRwS1@h*Z+`Wo;ycOLI!V)2GgYPzd?-m_acT_f}(IEnXF!H_q7K zu5lOj@zzG_pu@<|w4rYGR}UW0u~kz3*%55sv3>qY7RwIdkEq}ehf(nLmV=jy38!M7 z)BFX}%q+_4a0{=$d_8WFw*?vR_}Bi6-`*xZoVdExM-YuSv%?FwV#qt#Z;25(?~+Wx zJpO9fy`RdC20`BIQV-oY1bN>){>A9`CjziNd~H0a5uVau%9#d&{2G1WEdAUU#2fuWOo`|d- z$ERdIIq~Kl0XP{q(Eo}J1y}F#Fov8*Ut+xypRHMoX9CxdxL4wyB8*?qd(f+o;pGx4 z)YpUDkvcjt@)K*U$h#!U1BO-#xf-cYVP5~&h=^@|-(!z=+OmDtmk0Y9B-}dF%I<>q zwBLgSDXe38bHdhtZjiPkY1bOet zELPmG{s4%0U!o9Q0(mD`9_5C-^9SZeOZy2xz5Ge^#m!-0kS^BhfPp*eU*j7QUKNE8 zOyC0&m#(_uqqZ^n4$^|~@PXGp>f`+yslyT@zrMFDca1-BgCRqq7hOlNc}KimJtAS^ ziVsX+!Nssq@QNMIUwt)^2WfvmVxz1M{X@fB0&g$wAor8;KDBn+Iuh??y7xuVc;9>5 zw|XDseX!sG9dZ8unzC?*84gHImR|R6o;d(kvD6=$A36>qo}S(K2kszqrSo*2z9)d| zK7J~KieX@5V(*fR+UUGjt8q@7EMo?nkhrknnBI6(bl&0LJ+ca7sE_wbq>iH)`ROMq zzNUM^1D5MuJ{f-jn|FBit(hY`_u<(Uwo2%+V}HFx`wr6$qwzO1&wKV3Wp%6*DOo5= zSv=m_N5=ak+ls~a{}TtKvddRQ(0K0`m%8B!dF$UeBTMA1sAJHs40%@v=Czs$xB#Vf zOxN`!5&>VQu)qZ5O*cuW<2?XhPW(bU)Wj$Zw9w%{4_cw~cFhalbw`I8v>|afiunT_ zJkWVxr@uQnSV4Wfosl{UF!DRy@JG&tj|Z5UyGg6x!RGy%H;M0#-9G%9A@PH!)=|*C zo10gM)4inq&B+bQ>L@%~x{>L8Jn{X1wq(3dG?uuNy7yauJ7F~5S9U)=<_~$Nd2X>I z@@AIW`D!cV{b+hd`IearSjpY|o=Yzg^uF^p_y~F94ksE9K;C-`g~C7n3I(bK20?W6 z=)Bi|4}5&tk{PHYants(uO|QH;Y6R--MgJzsE@Z8QpX{T{P^?lGOE1c0etf|>0Sfa zyn`e!YSQiY#na>8U0rh!o45OXF}UDH`wu6|eWt9AbCbdJxc}b&PhE39S~jo;9U$vL z=fe`Nl6ugOpUXF(^&me^?Q%}ogO(_+eqaWB&;{#NLW-~l@$q-qrf@g`GXb`jGmjI1 z&nnT+VQ@e?|3q{6R1X2X-pU>LOdt$|+Ad6_ZbI)ts}(z19g>+qI1)#%uH&Jw4tG0yl-1!8A#Z4Oa&bU%CgYuMd|92udw_pL5{>sg*#}EkLf)n^#uG%| z_v61OeuwkFkX~WGbD9&-ob%pQ@+$!l6eJa0AaA#tM;Y(l5P;~aTBkq!@Cj1-A&*o= zbl!oNOEV2CnLsBJCv#Rxzx&@Fv1?Fo%2S{|-o8j3!x;G$bEj8YKjsFjBM0L-%CLE# z4Zc}g{@xWY|J}{h$`|{1%hJLqfrIA?%@0WQ=9JZOl0Tn8 z1RC%8^}&(riQQXzR+xCa^=M|4{u1PU$mqkXTt#Q_`i2nSjg7}alyOsv8RX3-*>tzQ zmjJx3?O%UGJ`9X+trLsTL+Ab3ck4@z_e@{{iF~diUPR{&+UbhWdDaKOJiho72X;MDVrjuH>bBwJXy#(~b|B-OR`Fqk#Jl_Lp7m(F_dny(R)@UzEwc+D@?Kjk zZ*UuSZrdv#!P1!RRkD!x@gJEtB;mEU9qsRCm%!Uwthd$Q^m>5K zJ6_lFJ4+VR-#7uM+%4lX=-1v@Ph9&@y`1{GcQjH58%BO!>NkT6y12pEn~ld^)?)KM z;EtD4d1;S7@pOOP5rDn-_H2v4f7Pv%=6QdqpsbFcO0?PD3cN9eJ*anLH+vhL|KmHRi#2)e!QFns+``*< zQ0mF7^$zwRj-EYRhhGwaL#dumcwZ<8>r2|!xeR>=*|@%nzR`^lgd%Zc4V&^dccS;8 z{j3f2LKA#cx5Pd`>afGe&+_q}vnPJ=fT@(F7PZRQJ4msOTzRD#9(c7k=4Y(RuphBg zu?iWgx$jK#1JaNgWp(6E`Fy31TD*efPR2XSxZnec_fw@ea%jBg*<%k5K;8iyPne1G z|Bs>e-UpDkS(X&wn{v`>Z{Z8VQcF6m8tkvl^uLz(h>Bm>IJMf6zm$gHD z7=4MIez|Z{HkJ`=LE?;R!fr&ipz|(F&}?41lnQr{NF7BO`CUGF&fh_f2Qbj}+po~Y z=KYS2<E@t}F$k*$=~Q7T-P8kD`bgLEU~oheof|JOfn zkZvuyFN?t_Wo!?{Utuhh>mA!6Hdva=!!UklbOAA)5e>8q-zXgS?gG zGiIN45&+N7#^RY_u56FUFT>n&W!cxT)a?;!CuGBcD$ zmX^!5gS=x7o?aNvasl% z`9J3Y_=n%F4XH97U;=lLxD_7tBg6363@!d_MCz0A0qW!Z6{!O&zo%+1o71=Q0Hx&? z;dCk3y!CYHcKR{<;j`^NYtFrGLH)gueqU#UyKXe}sndM-etn#>I&RJCXWxuF```Wl zBmmU>6VCrWWIgDbzg`Qe2i2Y9*o@YL60GBOuE8bNAR_}uod1P;p5}4GcaVq;g|oEr z+5(}i8%uKJwZ~dD!wg^_ z631q^-u3Kx^d01Jy;qDJhpBJ=KZewih>@SC#f?ufw|GGHj7;j&>Tj4mJ;{1P*jQ7>8@qb^CW@Ff`jK(|t z=Ev$1$lHl)oeYt8?)>#<43PH$`|{R=Zd;IFS>oWZCmtMSZmAN3ysgz&WdD3d0FCFY z4K9U-f_=;GtC`rrI&b5ejyYUe?tS?rt>C8y8Ah9e!)gGJfVS4oKc) zymMH8e_ix*KmPFq4QVBlahy#-8=*<0x`@k&G=E}aS0nZD-ig%Fgpprng|cm)KM&B@FRfwy1)F#KyStmOK6b}n z-EP{=OUc(;&I;%VzO|(N`TrJ$b#y9hllkZN7EdzX*;jS@NZngJR6`MsH)p^LF#_b> zhhr!u^1gh2@4F7jd!=QH@hvYqu+;B@@GL$aa6GOx`3iY|Sy6D84_f_CY)DeP_pZWpzZ+qdz37a}! zK?Q#7`Cl_f;78OSSA1-m*6UZ4e7(hv(fXR&C)(%jLRlRw;yW95UH|X;KQ)j2e{+NL ze*jqzx)CPhP3%D{;UjiyEbVY;J?OGD_ZMH-gE*M%6!yX%WG!GKLwtjDum82R+h;6+ z)}f$Z{yA~rg6yUEWVnNz7`rW3+DZTeYYZE@^}>MR+o0!pC(+L!pJc3!d-ILqZ=Bw$ z+d19c=sk#M>?q-V9QE~}$4DK^G4i`wu(|Sp3@>QoIlp0t8uk)g68H3$`R= zJE<68^B%q$8RQRnGgg0GT_Q%oD|UD`i3g}`qIuppZVKxdot{?yX9wv=#{2q|uqui7 zsiIR`(0C7hKc^H6d2ir!jU@7}uFT{Xg~wZ+k0gczyQ~3EScMk-TpVz#eUat?c^g;7 z;j`NaV9zG!k8&*GpmNt3@4zk()Kf~Hu92hSa*UuHiDQkD_?d2qeg&yxyXlM$@>NwdDOIRE>S@y=^*s3GyzsB~6E;~ius77D!xIaqJ1p zf4O_hqKom4p%wMnqNOlN=^;00poNm7o<*u2G*MUCzgJn^yqf96A-uz9z* z&@o>5@{Hzr|4yc?4m;Nar&Zwx(&66w5E<{>bJKrcZ{bO|Q3Z{6*EQLp49I(RVBjkv zZ=J9|r7L0g_H`>Azv^KFI2fHJkMhO?ZS~Ld`jEE)zxs#5b^?eCYR%7h6AH{Y2Xb`Q zp!2@^S?+#m2LsrP#Hq~EKU`UgzB!Rs8Isa)ras)b|SK1%A=IualTN!nvFCWw`|o_}5NeaUJKM zV#bdxe`_1x@RsHWq|wPfis~@Fj_(+GlTBP=gUEQ_6z9|=@!n^+juDMF^XI@NMv%9` z@~`Pc-aU^q4M!mFPOrX~=Y`F{bMMkywLEcPPc{3}2axyUsx8`Ao8cX#HfH7D`a{7X zPu-PcD(FjWK>x9xSIZgx#(6E-n8X%^zQjKKS$KZ*7WMJ=N9uTlk>97x9ODm`yx`O! zsn{E1l=BX~bKbes2m2K}MmK+^-MdBmFG&BCNm(63RuLs!iHo>0qzGyIKfS;~B5?@@H#f8vu@9eYfDytR=!a0&mO zAII#=&q-%^K>zLq?r=k`3HN8_zkSm(PR@;>i$?j4bLQS`UeddORw>#>{k6${`V zTV_k|7zbv@Okwku z;pt%Xf749!1CoF&Wp${Bd(0a}FLv)hGTw!!O#Df_g?&%aq45sUzZ>4>+@Ot}R6poA;(L zbx%+D{lAvgm+lMYQZWDf{TxbO)&i|apZ<=y{3@K$c=An%5xYW3l4m4ozAj4{R+UAq5#O`b!L; z7l|9cGc~$?1bvC+9?WUURii%M8b}>{82Rmg<6q!(MHI{%%muaCV)K?7bcicb(ZWv! z`rvMr)?@MxoKs_)I9)^YykGyKtd9D2$1%^8Mc!d#yvv4}7r)*@yn8F)`Y;()|%$t5WSd25;L)*h)e0e8C|MXc?J1&Ok}=G~C@VU-<40P=p#;lxz9 z`6y6Q_L;_A@kIS=k<^bC<*+{r5=ipV)G_loLE)OY`=ZzCF<{m#QT`K zuiFcONt!?2>XV|Z4#D(Rb=k`|h`d9{c;7l2&P?JRzV#S08t>ID2cx$@-oo4J4T-$R zS(uj*A5Pq>`NNPR-$0mUrQ4YZ?B=J>s-qdt}`K)Og?DGg8|1)OUKDiqzqck>4J%!GL{01k~n4u^<0T zIq%73QW;Zb9jLz-5^txx_}v1WBQ(!DIf=45rggg+cSq*_cm1CPfSP~C*(TGI^`Kgi z#7F8uXSy_a(0b56 zRp}|%gN|;#GoRZ?04`RiwN{)C14)g_}L#^{kn;G{XdzGjQ8DT`xaksNgR+IuX1vu@mBW9^7;;WTN~uB zC(i#F+^vDc`~M^4Ma7GyO~Am+tVrvXSRe<6CcZ-6HjlzH+29T`dUD0Lc=!bAhXi50 zU32J9kY+2Cuajk91pP>y@4=G|yu9eV72Tuc4D+aucP3JYGDdzA6OWIL>=y+lbVZ-1 zDc~(i{}1oFj46o*BkU_k!G+eD!G>>Wo_B8(Wp&((j128aCSE~G#*y)^9`<)4b#F!f zcgxUtYnO%J{|$MkJ0=(rd7I%fOF7^UQfO?`xc;9#U{+}DOdb6GdVKk>M;{??iyqB- zAIRI&>)7-#e7!|B&OpKXGdgdLZ#v0a-!gy;NSrg%``~^qbl$a5W`nDaQ6KLuNF8{L z{8%PF26!=xg05vYySBf_?%whlIwL;U&F~UR@AurQz(ZL~ zrahqV2;=qCqF9i2cD(34O?dzo~+H)op?0)$ANaVkKAZ^Qm(&gjT@a9A$ zj)DG6R+Sh!@35`+wgg#IAMedb9T6D$ZBrWm5w}GY=nYT2;rxTmyN%!buvx)gJijZU zJ7Y8U(_6i4At@ZyT6NUCPo^Zd9!ARQklgf3sWg0%cLW*lJI5}3BXw`9@hA>7-hB_x z-r$71?OM$@(o;AL_=Q{QAK8VzzjgcR_w{L>U zSy3=`bCPv4FZTQ|lltbJZq8o(VFfwc2Ye4P_ue?3bu#%8wEy;2oG^uTe0#fE0Y04g z-~IoTG>!kqF>nXTOxA-QY<(F?>OsY#+5%`jDDs>6y?by6dB`?l2XX#?x1n`MARLg6 z$fSX<)u!ORYPw!Jya%NAQm^A7;ciz%z?ec^1nYJ zbNG`V-pGZA{lYHnB^KwXyNavEkLJ%Had#-J;~c?Kdhr42WF|7+_3Xy%B;LQbF!7`D zzNb2%-voJ=zQTJFd56}&$UhEwe>i^j<)pqTd{yl7jxl(9L3TZhxh3SS@5!Dee4hZW z7#dsJ*M|bepgPrffWE};sfyd!@`eG>BXQ9c=MLJfKwn~?EV+PViKaf@yO25v82OE{ z>Mb2C5(NsJ=Pk!{v3VbLXz21^>5td7;bUdqh&}(~P90pYeV>l@2c$vD>hM>HUeO2# zblANa$#~y?eflr&jX3y#30zzbI{M<+;7=#V02h024<9f1-~0Ev@;-&U6Rqb?5_xkx zUAi>~@(y>rq%qdC7qsbGeCmY9Tbh>ZJhUM1H#aYUMmzyb%&G4_a4!@XTRE=eRYT|9 zB(J>8nu!q@B5@0+Z62$yMCUDqzhXpRM18y)kvgO?@~a9wdadt>7@*fQY}Inb<}I9C z8CA~bhu^s4-MAVjHt)bfFC2bP2+i}Z0NxbUVZ36&#|yqe8uDf!<9#ppKm)0JTU@)! zhsHbLkx*Y3cCjSK0M| z0N5v|R;<1l27-QyMuhRBU!3sCFAugf`N=)G>>Z zpUI!d6D2WXp#Guzo)z;?ueP@XNTJc9&A{f^=Mx^z4?Eku=X6$0kEj9WoiU z(fSpO-Fpcc?>gV6ViIq0dmmmj-k)x+a_fh@TQmGSiM&r)$|eyXPPF53Np=S&sjIJjwk3{@;%vbvR<=H#NI+n@NuZu*lFCeM`Z`i81wmE>4VX z_wir1?K$d9LP}^?m%5mq!5Gc+?pdI$j?3QVGSgB2UH>Qj{ZsW%xWuxP^`K^@+;CD4 zT9c%-2CWCVGYY>i+xGO`um?pSjjybLJ?NsU_EO8s=HPS73#&1B{oirs*|n!| zi8WHuy`y!90KmwLHHUda0n2;c$sgy@=l{YZWlTKR;DCh0y>XembTc1){@2dSFPPp< zeM{_hqzJ$`im<;Ege>@!H2-gLKDU)Irl z4|3-{Pf;B~rP;y97T+M9yp)XhqlHIVB;KAbe}vF@U-7ZolnHq&_O7cT^45s-pCJxN zhHX+SuPd2@m2WKcw!#7FSm!47M#%d?XJN;0$a~Gqi#zzFP#~3jm_3#geL$M)7E~j& zGJv&6T=Wr_GTTvf-cMIaHE2`e=PiCBbv(n!uW5hE>fKzTfcHv7?Zg*s-qGxdsXzPd z@x>+~9rUW$ym2COzbp4B&^&LP0EKmk1&m#Quh@azn~jWjV{^+N67PFz&8yIO^O-*n zx(0b)nn`{`K2w=Yfdy$(;7-+k)s^V)kI&YyHU$n*)7(p`PW}PZ|~)1*Zw&XFqU%Pw5|f1_xzy2?dWd-_^*A@PW$g+KOh~s z(NQHTYl8M4kdCFS4ukJ{Dv{-j^FIq2?}t8b-;uia6I~BMG~N;B5i=E#cNn+lTH^dq z;{C9~q9bUf8GO7YV*4QEeQw`39ivd-JT=l5+>XBY9?4K< z89l=Q?2x$7@b}Xa&(Jp~!dXt0^qSPidkCpR1S7v<-K7e?vm(Hz#VU7x0-Lvk0RL`V zc(-(5pwITJIlN#GdRKXLau@7DGgdEr1K<+d`8q1glGzH(O?cCtaEk@cs(v{2 z!yZ&;E*GR*3Ev>?AZ67X83L|;sA$gOL+?S`o^8%~$-V?!LgLIgmvQt#86SC= zY3renjbGqE`$NF$j>@CqW3H%w zEzQX5$Nkvul9AXOpyC9X9Xh zX;x={i0=jwNuH&mW!O8&mk#qz4dQJy&-V#0dSc`r|2(xu|K1dJnb`73x6UQ3|!UgI?NDu$2xo*?B#>R64D z-?Z2ED34BIaKlyf&-6GpZ@yMbd!JRiL2R{++rDz_9V9ONx+K${7c|csr%z!WK6~WzLSr zW5FJwXPrHe_u-El(o!JrRxK|XWy26~E`;+)NGCe)yCP+*zs@cJsYu+3XO-_fq|tdl zpC4#!(W5@zRY)DrF!IYueK>HeQWykTO4G(TMl#_BJqw4J0Oh4Tf{cjKMC^I*zOiU5=~n?LrC3x|TvhQW}&>*#xL z%}WpPo)HY-84}lH6MVR~0G;=g*%6%^($qKqt08q@D14VFTzIn>~Fnr#Goi;t?`=u$}mo{4&SmQr? z8!I&MHsWLr>sRm1jOB6p0n&e`;J^N#S$fcaod;Y&O3>Ay4lM;`v-3w(;8l_9b?&U$e{nIc%VeHty2zWZrxNb`83`c_PE`l`zxw|8cZD%5mn` zwQgFWX_YLPi)aQ(uN}f{9MONvt8!J@-A^`AT5L+sK757WAQ7ZUcP@Tl{r*3;dO1UR zC}h8Mrzb|)A3t>ZVzQxSPyMdO68P5DJR|SmjZjb}V zgd+SXC-Hed%d4rmUhPI%-w}9aqy&EjNqA^4yj`lD<#`iI7|dgx{U)`)Z*Pgx@oqcR zuova+mYuAM#rup@!gY7Z`*`G>Dk|?jvkziE z-WIexHsQ?gp^jhiCxO|(VXRJb-V1!*zu&($i2dS0DO)|eTp$j=dhh#syQ}JyG0XS= zk82sr<8wJzmQdQC>McUY`(cog9m;!Gyx&|b-eZ+6v3`*Eq0Kwnsk~*KuT}*>-j}op zCEM-b;l#N|gCf_uwfQh zLmOA-D9Qe~5u0~mrFp!JI`eIB>C^Hkz?q**^_eYNWNEPJRi?rPTYTOXy64wyF|(tj ztStF5HH^Q4l*!97=%{yK`3C6`iLpH7Yjj+`X8z$VO~;5PjOIJkS42?&rZPpzwBw>Lq7)>u<^C@=@4=P7`V@7s|I=7EPffE0eN3up=-=L z5CQfs`h9poDmL#B71wv8*|R_tZ5%S%e^!Em&0B4P|8lB5^YIR)<9YsNI{@cbw4D|muPX~AxxU)QOf+vG{%xcxw{@edc(eZv7 z{oyFe+oyu8g~fZk{C?3jPn-lFJMcYm$ zFdy%1S{{#Z=BLP>*F$!d0fM$0&m0}W=Y6Et$fw@V?!I%6m%Dr8NTbesZ#? zquSR6Z00OZUS^p9EL?!)PF7vkE`FZ1!Yx3W2t-fVrhiNc+1 zC$~x-|LrY>1WkD)ko6ZQBchDuaW(1E`6KY{t^dCNhjwdB{1f*7igY#T6<72ov<7iZ zAd9hTQ1-o5hQEmyj6H<|YDYrj2u~nHUJF!d^ixP+YUBej)Sq z|6gc%;LVTQ_uQNK5eZ;9BczbR`4P9DZ%SLQxLH;TC|Z3BIsO#C|Bsd0R_CtqmgW2Z z*m%bBNHXtypAWx*19>aZ@qW?qYY64Nx$TiY7Vk+F;$kAa#C}E=*-&{uJ-s6#6Y}nB zi%1BmafZ+LZ?E;`O9UF0>_Q5V_rSW<>Q^A|zIToD%|1qe@_;pp+Q+eZs}@|m^e&44 z&d|oi1hn#t7Gv|aj^5sV!kPJatJCtpo8QtDLqqr7l0ZVj=ANSwKJV)>yOYO97K4`; zA14cr;`jeaOV)idpIOWDD@gCxjO8J4`B~bl{6D3H{EIIs-mEfij|5R3Qd#~~Yj z$h%c_D3r>3*}Rsm@sPJv<+CmIubqL|$Ft^T!wF#ARi}d5Al-McPl|xN3ojp&dDj*J zTyEWQ(v899JaH7u9tWbM0B4H({E=JdEb_(C+`wrsMtmpyEFV zq!Fby>tXRe7dyC24DvSg7)qh?KD_h3%2vo*;Nm5V2_Y9yZ16jo{ZRrSJF~S>x3?-{ z72jGw-rI^TKO7DtgI_26_xQ}lZjfAr>RurO1TaP$r(V{0#`+sJ?_=xzcekHqKHhG$ zJn-h%-jV2hOHm4lKUmHF_%=Ro#Xb**bK0M7aa=Pw_@I-4{$IE(tkATJ^?7?UmdA}H zzOH@n0e!eQk)z}N%%tm|ueVNwtyqA?J9EOuT^90=+}m)5%G+p(LXIQky|K)xRomPJ z5S+iLPQ&;A`_rHMYC+!b6Sa#ZA@4J12Za~zBm+ZV&d_#cY~FiUM-{ymodxu0opFZjEFWz%YD;FQ#pBQb@~yFV%TK-Mcm%Ff*`2U=wD z`~O!mt1VMy`&obO{n(75JZ?rtTwcBJzy6OeP6XV!5UCtQ)QHd@fl`Zee> zV|f$|Po2Dc^3Nq!g^u@|7Rdu>gLKmC-cl^y2RA-C_y+P$Sz|__^1iXWp&}CURwO?) zPkZVFri~YQN$*bt7k79CP+xBWY@*lX;Oi~@r9H{7OUR%liSzm|A8g)g^UWUnt|5SW z+Bku`vlU~1VDsMU=kzdFocS)X8nisN;LK0f*}`&5ssyOe4&V|H9>nDxUw*l6CUhO8 zarBTncOicNU)|oecBdO)`4wd0BgXPDGr0W0@bBj>=g{$fefFXn%6s1QDMKvYxj}Qc zeT2L@bU1sdy!E~>v`B-zpX^?-TUyB(yxzXYYR!g3P;YTkR~Yi{Dy-{phrH9C9(y2B zKn52JX3vy6Ve?K;)?2Y^2LYU>jhk8HyI6e;oA-~GBJu@B%*T5_Ef2i;&3BTo(Bqc` zKF=4;3R{BDyRk}HDA#oz<-2L+{fjaT^#AFnrz36~u{>`=3WIs%Enbl0_2=`J%5=Q@ z;Vu!%+wEA?5-i>!8i~QfkoR$Cu^&|4zj;am^C!@Bc-57gVH{5E^_?k@dd z%*T5-Ef2i;nSahWG}}lLY;xc7dwU^1?>9MBPL@*^KxudH%Q6rA28ob}xNE$yW%v+PI@j z<()GBrT;HMBGwPcF(2=Bv^?vR}AIB@Y zs5OY%|LDIEwGXF6$e_a_)8oub>^n#me!5THmd=nK(8ih9wp%15W3M1V z%Z{pJo%~GK|6iizfj7S^nqe!pu}c6#k`U;vdXHOE3JZ0+E0UckQ)Tmyo|9!@1xfj0 zV;A<6^)Ino7|g?L;63dLQVlxZgEzT?P~J*)$_N&3x$#c3ddNFvwx%wX_j{pS!d=MQ ze%>L8t?74eE0?Vh9hX#Iw};iC<&;n&%a~@dFu}-@C-xV zlv|xewLxScNgf?lUx3XUk^H8){Ok-#kTz~O$th;RO>Ev?mK@S=Oqh>1k(LME{J1rD zUfHr<0^HQv(|BqHKJS$9czI5j5K6dCW_Yy?KJN#4?e0lbTqM#k(2OGTOM?l-&}9>)5=1 zY`yk2X%F-9Zl>jdH^1*)i}ydcD*=qV;zjjB@p*q&R2$QF458c#s2%k@$H2{rN?*ML zZp|#un^4GL9&a-eXrH%KrQtomhhA@9Y(OIJ6Rw}LVxI05L88xXY~E~+6^pj8 z6ToZQxX=?N=Ne_Ox3{cSCl_r!%6#|U*lBrK;>^#P^JYmyFTn->9YJtJ@U38{V3Xht z!SjOof|-JQ1-Afe8YUN z`JV7K@>TPd@g3*e&r`uu%#*{jk0+8Rl*g0DmdAugpGTEPiid}Ln)?fPA9p+V9quab zQtqSN>D?YYgkmvGPHmg5%SCUA{#z2)lUYT~-Vb)GAqE0b$4*LJQzE@v)F zE+ek_T#8>pXNZoF6!!aX#R@#d(Rdh!egZ!WqH2k<*=XEvGT39;XVY1Sc19k~l5klBFzHlA2^h0iuotuEu-VVh?A z!q&&u&US~bimjCGC|f#PG}{(7Up9L-Gqxpc^VsCr1pc@6F{|Q#zyJ3e^ZyO-vlH3i zo{*XsB?S=q(8%+M;58yI8hLnb^&#@0k-Pr0J|Z_7x&97MBXXgU%M&dQA}1O-m%9}Z ziD=}sv3iJzpphdu!b#*nBL|^yF(Nw}t?zwrMPx%GyW5EfaTXe_BWt`O641!jtaBgo z8;xv)7f_HHG+OhXFdO-WM%Gn7%8+R^vWoKmhD@Q6rQL;J$RrwBsOr@sKhbFQs810x zfktM{dB(^%8m&rM(Ta?r(aKE=HX}dK$W%iz4*8BoE5?nbkx?`rvjWpMLMj?G@G*3}{4e|<&)IYs0L|&qi+N~E}$O|-5%~d{t z^rF#Rzv&9(IU1>~`1KKahDOR$D(XlN8Ywl_@*~}7q?p5_g><2j!bZ+mq!W$gNk%ou zQ#6`Ai)Rpdf=03(m(`FCG?F$k7e;E)h!Ar4IdYR0ss3JQB!SeR(F{*F8M%Q*(;WxH zk?UwQmG_GqsYav8U0G(xH8lEZ&c}&Vq0xj$b`x?HjmBOSL?V@F^y8A^LF5V=ecye( z9jQR0(KQ~ckjrQ^B0koNTtcJa&s#c?ay0sSb<0xZA{u>3usw`iK%>uVzL+5A(P&6< z{X^s&8d3M#kuo%*Zcid-(TKX6gOs8XwfRNPpb@oKKuXYv`qUnB8jYwAIU&VpM13X% zIfX{lTj)p;8d2{!A}7&^`tBc6h(^>`rH}$NqP|&zHiAL13GLQpkL_Jyn*^frlFR>#Tv`8&kT3C~)jYf&@ zb_o!*&?upC`2p6WD8Y@{Ip1wdcrl5jz-i2fsr&cqMo0Mq@oe^ zxJe`hji{&dA^Xs%e#MhmBpHqB_-y!)Bs99!eUJ}HM5Eeb{{|!hjc#sfJdebqQ4L5H zL-wN44MF!FBo2+L--Y`kv1oMd#)%>%292s>@@MZ(djlsuU~C75{O1eE~&O70ce!FJGlt)N245@f@O#w8XZ=e4-j88I`s7`2jYW9 zS(O7H5N|X(cwp=d;)O<;UcKpvCmJ1?vr+}|K%@OU5;=%F8l~U45QMm)QCd#jQp6RF zQn#gzAuec?Vqkg>aYm!$NefTJ35}Av!+#@=Xq1?@YYyUoMhT%|$%s7~#V_jFimXSY zz1(i%h#eZmKJ!0^tV5%i5`qX~i$>AW+wu{c|K9&+{vMA2@Bi!2?LkskHRv9sXPpfn z)*fWE+NOKQ;U1)bcSN2g+=Coh`jCeW-a#sgIh>()-Vq$|jaT^6o&?OTCrV7<9^~>h zMO9+(4wAS5yWW-SWFXFo9J-T*y$6|nchxUd^F zl6jTu2tIer=JC6e1QO3kEHZ_>Kdz2%lYqSSn``|&BjG1@VvQdr*kbeUQf9a6bNxl~ zr;Qspux$IrbJ)Dw*^7g9r@-7VZNugf@yi+%}?aDvBcMIao}tG z=)qi5eBM0`voo4Alqg1Kn?J4lfzLZKoogt*uao6@KMQ0mk2%g+UI~Azw-z05>P8C6 zJNDfbE-c>O7pvtjLf(xTlKoWPR^L>5+#zp!KSH6Gzav;1kfNJjkOa=0uiHcA{n;#> zPag7KXZSd`8jyj$dx}B55H{~E{97^w@Bbp{(8lRsZF&0bFgEWai^=AF!OX{d6D^NC zocZ0`d9U&0LUAzs{Lt8-A3pDhVqZ!dNtvS6ptHZG5dZ#vY;nTFmAp?`o_FjH#`4g- zHm|A%;;1h zHt(&by=@aE%*Q*5mIvPaOp;afC*j&VJb80xcs4%ov&moR{hP|1Me{6*%)-D%*H$KuZh| zUacq}>VAjYAbpbZ%wKodfkG-7`B7+!e~F#@y597(@B)^<#BOY5EDx^`$yc&}KajSN zjyLsYAIjS!OGFrpcTVz3;S|VQXI7v&mA7i$(7qz-2~xhwcO_(fooP_*x8 zzboW@_PTh1&$(8xrKQ>bum>5`hGlslC1La4({*yrqvg}2YTCFqS34K+eb~IcH~Lxd zzhge$yJ>m&;LNWun{CaTbTKfeBcS&DC_e9azCqJDxek<4tC8j*9{l(J2||i1d-#{J zJa58E2J=V~7Nx!3qDRM@diNUTEw|)_AQtbvqa!ynAa9NQEH^6e&ca*$S0V4Q2US|B z*PTF7w`NZJP!iDmY`Vt|@{X9j_S`7s{YdldnV(#dz|Y=3^ynZqZ{Jgjl%cSxx3w#+6maAabvvLE2@-cBaVA#I#46z$-E z3@vv2-CM%sHBa43jjYd`!8`_D&N19u@@IPso}~KE%Zb#-F;LzCMP&k5ykCwxY{`PW zF9y5{qw+Rf7oz?U@^<9i)4IjX3D}8w9%vaz0*j{u!_6S?Lx)seG@Ne*2aUIN9r*=6 zPSi3}@Zvc(Z&yX6-T2xxDUCLc*Q#JX?`v${9~(Zz3cE8OZzozFLpbx(C?{Wh?j{a6 zo?eNlh{ET6ELpI^MOKGGDJU=az;PdUG4rbB_{j9-MJ#{*pXYtX@+d9Mn{tc(b8|wM zjyLuBB9wRYyhwg5-uEAz5zmFZ)nqw*fP<;C>{^5z&=wja6W2p+Gh*p~S!2{^1# z>80MB=+<_R8-u)^3H!F@Pm#f<8$}`cUD&*B9iC1eoth>E)5cW{9oh}vVe@`FVR1vK zfcbc@q2=)oXMUbbTym3ciGlbH;YvTw;qxAjT6buaSBKIvXyKT0wi%Z<;c;qlX&LLk z|4)cwERVJ8LIyeD*<1hh|E$sf8`9Mv>Jye|4cb<|L<*}0dCF992E!VpyyR4a1*}1* z?2jK@2y0MOb9+OSksH`>8>u`bnGD>{yGT308nkOMC^-sOkiKRm{^#aL0uTEp{rB=g znE!VgVp8}rMadY7cH;j z3O3tN+*a}?gB0~Iaz2o^xqXwmnq(b(+P$KhfZz8t9 zJ6pcK#`3&fO&QDM$<{}e#ea{tTujHC`cenV`}M60VpzN#j=DFJA@Apl)^k%EB=0)y zH$jlM)L_nOvji6qB|o+zl06x4nA&~{fV|sXcXH)G-u6}xEn{TJV71|4Gmlx=yo<9! zCi1hVNG7y#q={*+3oh8arI#%1S^=1kcM&ZQ8JziDcz1FoX+#t}-5u9`b`w5tll1ML zUFoX<->XlTceOEaK>FnQ=VBsNEYF*e%wQhDKTK5r9&fpbjyLr!C6xE)Z#zV>cwg8m zs}lox8=QWrK;`|~uJ>00C93GA~^-@5_w_I+SYN`$-}J0`xX zH6@HH7cev^>Od=I1NZ?`v~a1h~vyorP?Di(6AZ zpM14MPa>4^tnozX)cYpf@q|FPjXw=o{{!iS*)e}$a|u>CzQ&2ll_N$FUWh~@UCA;i#);FTXhQN=E=Y(F=_D%$opb$YgZNA zVqbf2ytw-o84Sor_f%G4^B!yad8$lelJu4~?&q?vvm>&wdF!7m)`@IlKHfiQc`U-2 zUrlb|>{kawfd?X?dmsy+_hL@9#I6}#P#W(LzE&T9drN)Q!9$7#)hxe)Y!75C4~Hkh zQOs%Qu-d0mb(mWyW{P{m}sk~nd z{!o7mc}KtNoH$qN4sKlO>Z;UE2Ek_8Mynz3(}Tv9p^*3eTuSrWY%*|9shGA+#^y~L zlnGg#3~x@*#<`B)duf?~&3jglwVJd6^X=ZEd9dTmPj`G&l*dpMH0ByFb+5kXh|*8n2GeyCgG^J1J^5%isThmdaQjYb~ZCFYNildnp}n>bFi%-a<1QrLlO= zd8AkB2YI(inO>ms24m9dYOw!z*3uM8FLeXw$teLza>-!l?3(7akazXs4vpV%?cLy% zpr(123_jdB9=_lxHt%_z-{d+B%kg1 zd4hD7Httx5Zmd!i_9fP{@`H0>F&ESI|Fe?+=HZ1iKal?&!S#pD^As#L_^+3#dik$L$)BY4v~d?c2OTo-!{*)gI!RJ*@p&Kq=5tAxe7YQkbafV`VC0wt-uBZZa2iXrdkQUi}eGrU1h z%f4L|Ta$s5Us-x07(uEyJ(lzD?ot)>Y3uU-;RFLOP_i?M^oX z)qAN++`yWfEYF*;kg+@z57ezG_}l**)A6Q$U=rp1J0M*Vi}xCy4>wmr-ZkwvwWz$W z$5fg;g}hgU4kiVudxPo5?@y~XB!iZeh^M{lmdE3iu7u zvAOdN>|buC7@j`4=Ef-g<1H)CFW`RBEY0%$Ki^r#@|a|69w+>LyamwlrhYLMQ7P$ZCsD>L(V7u*t|FV9^4ln%zV6?Xn6$V z%&(4j$|L_htlkA%1X>O7dD})^J>%EAnbPl(a_Q?42KxV&fp1NlFR*_9U&&w|sn7Z5 z{n!7qK=Ti$2v?BibTx?j&1kd+4T~tv!>U2VL+{*VU=6a7>58WI|CbCdNtSypG)^z& z^c^|x3rZ+Y52nHzbm+Te;ld;MEW()Aj#$v^?8~y_SlO7*u0NyI-rwjH$m#8jgwrISf9KUo44X)bqQg9=4+6S((=HYpKHhQD|g34 zfb_>DjYiM#d8>Cn@-V%#k@EY@&TC?)@mG){qANCx2%l#82C3`1F++JES^LL};3Iah zdYjSlrhe5Q<;|U1t%k*0J8pr&T*&*>4sedjo0vFa{Q>gM{BcWiubMBAU%KESS6DK5 z#9z^RAMzgB{L3luR4Ygd((7rOt!AZ**|iQ+YR~tTq>d{r}7T zyPv#m_W=dQ=9YEjWS~;E%J(MZJwIo?k6&>sP~*=$-usaZ{0;XQhmB(ME}BziyRKk@ zNy!jmsTvzp2P!ya$Sh-@w9emzdAxF*^T@Ipj z72T~Gue*nPGlP)SDHpm=m*xBa*l5P`SYu!rl6?42^-CQi*f|6Rd zbs+D@AA>uoyjQua9bE-^U)yqX&zDU;Ag|DG*AS@cRDQ(y!nm$1n*Dv z69uJTm4^G9@Odwuyp(xw{YJ{N)o(su^Tp?Ff970H$U+sCuiiUPGL{GTq@~)a6aPK` z&k`E|a0R)Bt_D$0o4lU&P&|X8szxw>&xSw3yl|>UZ9x& z@C8?Pm8C1f52Ptk7U>8peWhHmxze(rpcQEMACwIrj0E?BtXENHuxn7;BmJBjkqJ^g zZJgJ;SqtNSVAr6Y{L~9`9&s{V|NoelM;FfgzH)or?%faHAl3I>x3UO-5AxSy_8`r4 zUy6l-#dBe9{7>xUG-!Q~`clO5HHhyHV|mzzsA@g`dxO-PjyLrvHI#R6>a+P+yk+-k zXS2gg?1e9BN>twR!Ga0TA@9^XoqBA;zJRAV=4vfpGU)G)S%yH~*6U^^zJt7P^!!rZ zLx}{#Vt!AawPW)Ry>M6Kz1{@rBW+wqPq*^9fB8UKThnsa%&*MHJB*gcL!9|($*UW3 zJ`w@@Ghd#yiN)t#AlSL~>^@)0@%-t&r>F7n{}Wyr>gcJSWqIC&9>(%;?!u#kT<7;r6HBK&V+!y7VQ6T|9-l=dC(X17}b9@fe%P8 z6AF=Najb}U>Ai+8}Gw9f*NcY8~SEtU7`9-YWM z$U7)JF5>oUUr?dTxmdIzJzux0LDm zI-65Y6l2qrM^g1o`2BynYnzvD8SCF5m0~Q9NGsm)jAMVQw*?(<>gla0Z{&!%CKm5n zm7l$0koWj3uONEf5?j9McthT~VO%;2khjj;{AUA@cXxKi%kz+TXNlp1hGsHwyxGek z*@L~k^(y%36FJcd(mL9>{r<%R{UO-A{UenegxZ*IaneuA!w+YER>>;Sis7OlZjnyI z5CNZe{$>HMOC&pr*~kRYAIImt&-pg#=NBE8Uz}`gs%I#V#m1S(ysOMLsHApjwe=$}KI@~B{-3R;s>ym`b)$kI_m6zk72QRVVK^`sZ3Vgwwblx+& z{F1=1mqxf3Y>;{{uCm;7v=w};{PM}}2N`Vp`19=zLF`NHjrLuKZ|@r?ZK93K-=Y=k z5QJTW*8HqN8Z4Nv23@D+VTCh4@tp1-4XGkPvTf+=s#g4OkPsVp>%>tuP$oo;tlu&6 ziJe_qM(^t?SpO0m#9$uJZ>OmJy@RxljyLr{c9i#b zrsnJ`LlwwrQ3{GX+k{%oA)B;k&oBv#z`M(<9Pb+-z)zY-fPq<3qdUN@kaBo z#+jevESCpE#UeoFexG2oJ3jC9vny0j+4@mpZRBDPn&3aZ)y{iO!niDt<$2qGXDpAT zZ~9`({x(Q9bi5@+PG+OLHF|gHVeytHvDJQqyj6{UcTst7*>-i_3dlQejd_~hj4!Y^ z5ZrVVp59t}#r}decZn#!%(e~N%-%DZ+c7~u1EIqEy)W#>m346E0B&dBL4 zTY^t&>g2Hg;zWeOJVYya)&DL|*3$77A3D1b<$Yu}Sb)X5;fnFQamc%+%=H_U_cNsx zg&QI7-i>qj2~GNf>^iwqatNWI`MF^^nf`HQYX!<9#)JOroopkM|%g4{x0L73V}fHoYYRrlyY-G<4$k z|1vA9-;hoPQa*#A4x z)gZ+j9xZAOl6#{OI9%sJz^Xyq#BTX|Sc9%V>Jy^YpooAyNyG3Nq}PD+fWul}Q0M%} zT5VPmP_VX)Zh|%FNJQ9|{zI+c{oFM1?Wf4#bzOhhx4YPTkY9$kTGW+{k@{%kHVFhY z`)OcbVs|-{v`>c;neP7o5G{`#IP-Iww5@G?A`E_gm&l8|I)GVgQBl1g?Z1WW-%eS# zBqeD|2Y&?_lu=Kf>C&WSRPhyc;34n|I;8j((zW<$Qg@XV#7MxmSXW9OsFil z2YKgj(9)#x4mm!fbq(@1@2Yv}=->+$T&b#Q;7tOGOE2-2L*CC1O6n&ah95|Ob63)2 zHyO14YB=t89GmyYW0JK+m&Zu=Y2z{sP19yeVe=lVx%=(?PUhqNftJT8&ir!UXgie4 zih!E$T{~nl@p&%}dgmvUv7NHF?1A{y=R3In9SALb<(Jj}5A^@W4CWzUK-T%Yf^?wc zEl)D4L3w8>oHE4X-L(F=)kDZz)Jx5b$~#>03UL#a_nuECw>*5o?AIN?B&CwTTSpDv zT*$jOkf%c^w-v1Xyy;N$oJf#ST69Ku6?TJUn8DT>)i6d%rH$)%;QKJR1)F#4$;$;2 z`=&2*|T^CQQq$x0+wL$9!npnegb))DN*yL@}93Kvz`a? zCN6K&s@dQRuI606cT6=21WqjPih{gn94t=UI?@WB-QT|Vt!yM%thQYHUwE(oxrF@r81wOdNy}p$&is@tvs1FJhybBGA7U?k#P9zlemvSJ zd}9OUPQT6WxBKuLqzByBp6!!o{qz5P+p8GLqj2&3y|?53e7$8o9dFr=%W5d^$BXm~ zuy}{6#d2bqtE-oN?Cq;OOE|JLwT%NrgBX6 zz<>Qe+N&}3PuTyv)72o=T;&7Q8bs~?A8ha@V%4Cv6lbA)Sc6KeUc{Nf8dM87ZjQij zkjT`Yir2g13tXg6&RZ&x1l|QENed`{r8wTLDKk6(?;u4h=#_+!LCfsKQe7}o3{^NpMVyB(vvHS}1W>qaid2pQAchC&hAjsQ|j`v)@ z=?av0rL!`E#XCVB zuB=Rc#h%#;)FVjOgWwC&V*@3=-$Jl?o6nz`yLIOn2^|;py5ZfD=h(bEX0GiK1s#O+^CVwD zwoS-7z?}p*k6Aw$gDXg1wy=a&$oq*Nah{`? z2H(Nv{qq7S=QL+N-WzCnjN{DjhRnq^?_z|3=OS6>KyQ5B>21AoveEvO1t(n-_ix0n z-oqO@T%w1{Sf2L-CC2htb^VB$?%&;87dqa`Q!45x?@#`>*|2zn59W?nAn!Kgj&3UN zWgmvNg+bmoZ{I4P3HAkXDz-xV;LVB6x9^#Kg1jS!$18IV!tJe@Ni7a-GWg_FKj*kD zHgA{TyuY@kjgioC4s*7@7-_}kEknHc{+b>0@ph!;A%!zPy|&4cUroZ`K=%t#A0vF; zzC71*7bf^qMy2n$i8eLhE=~yV#SVTUl(IZ;!fOWec#*tc;cxYJrsJ*DSj&&{CLYR| zg~fYnW=HZ3$lD^wXpG8RUs_^jHsn369Tqd!+!xI6J!~;No(Nv-{u$E?d7CWr6*`jD z3a;G_wzchr$6InVzc(RZ_y2db!;H&MjFHfBLgf#S%{9gD|97Sbm+1O4AMe|=JhtP^ zkNc6^_>)XwaKAP0a^_q7-P=s>?t4DcTPQaD+ZFtN&VsI6#LEEI~ z%x-}-s3a)ruw~NrV;XFbW=5MU8@V`+=;U!b*(%8pl?%l&3Pgp1>n=Ed``j^-aQHJt3TV!`U?#7?~-5SzavOSrZw{Vj*u)hwEI_OYF{brH7wG-sS3j`s`|cK=szL&O?StKtO8lmram& ze38tXmVK?jsLC*`JwFoYC10CvzlY6xm*T*P-itBPLfW``m8b464r24>P_&bHb%yzP zZ=>bGjx#?ele;62DIy?z<0Z+|0DRtethv9n#q6NS9bfoa&l8`w{LMG_2LxIF^A-o9 z8Ovj4|G_M=v_HJP=y=al6#sL2D|PpFj`(|SEZ+BH_Wn+WysPcjs8f0Sp8ME240$g~ zsQV^2~k}|=hS2K=C2>D^ntw5 zar30Pcc}l%2~x$nelP5qkT*9ik0PA;ebQRHZX1s%Fq*qkfol~$?+Cu1EkB}nP{{cM zJSGhctRT79dXoYQS-*M{8O&qXx|g)mTRiD_tABc3h*odCf{R>OyqiYqpB#X^`R{0$ zQ+ZGKw|wJ;2c#X??D*zwqc1pN>8P|+HVMr4X?wC1^1k_GO2;%E9&afpAiVQLB*+3@ zip%d}^EMN!BF%a~MncCWtsA@$`!63zt9;ntq;-k;s<#O(j|!am?Wmka*e3=7zODK^2>3I*WBY*9@>kHOZo!VgzdDkrxUabOow`5-TqGYs! zrJ9rH5%}zF_LV5^z8385t-9#$hMil+NQY?SvK4N0usf-@dfgZN?Jd4_9luA|w^0aPAC_J3VW4{J8%O%&P*}hJ&jbwRG3#wm zye&Mv<-h))iTi$ZYOwzgq^m)C+k{V}HHhp;62YoLaU})4cCZHZ={>Qb_W$48W-J!L z6{O&!;=ycrf8chvaYL;ae8n!cSjlD1SIU;|8&-4%8l(U^-U}>hG*RAP zoP~w4c(<=wrt1oMTWdCKqVnENQCn;edCxf!yPo}rADF*iKKYnO5@4@%EvJhI!@bvZMv2Z zHg5s5%9R1t%*We;mIvPaeuys+N}VSH1Q*yXmm%WwwtAt>6ESNqWn4(NTeg^i734`v zb&5a*%U5s0DaP{P{Pp%y<=^xF{OEY=aO56Ec|YJR7r^3u;Kr-oAjmuW+?}&j-Zmrg zf)^q0{W;U;ucZ0`3FjI~#5oDf4Qs1>4jUxr)h$-r;#xtKoo)1@bO4(rBjgmW~-;R0DapE3_P3|_)Teg%|({yO;BMlk6)ID zHR0mqzy2R>vYGfN?EgdPYS5DK01vbVO&Tnf!m2@!GfS^(!5Rd#2d}JzHApUE{e@rf z9i)zT!C&_k2Y}%>66{0p0qHzb;k&Xb@CGSCGjvmEE9lZ`pY3*l41RPwgbCDOH%R$} zx2c_RW26z3IR}N;Gaqk7S{|l2 z^V=WhWUP2w7_`@fI~rfX=RM}GYP0@e4CUF}hui|Z_-~LB)T={p9PnfP2FZi5Jd6#O zREO37SwRNV@m?$t^XL2j)cgOr+)u@^cykj2)*3 z3&V-{r?))H%lsJ3^^E0tyMAXZ4>>lnrQF{aq=V>q>%Y`^fmUx1?J_Ye-gDg}Cru%5 zZ_gYNYJ(Kf-SfEw@_uwC4t#I)2UX%_Q6d&e0Gza~E`z+6rN4-7+|~;Ec=_k{Oq0P; z$B}AV4Q$?q&XWT_VfD_TjXU;xmT#>RHt%a@idK>9n2$G_M>Wp;YFk_D0-p*4ne!5J z=11Z44iiycCMz9Bv3KZbemnh+=MjfRKw9r-kHY_tdv9`|LnZSz<1bFM7QZ(QIIxK2d5`)r zmWRolrk?V&|GxkKPkCeJUtkT|LRW)G9yd+V8sz4#E{|1%qGa~SvBMg)(P)I1x`K?g zt^HsP`+tkyE!WTO+yLy>U0CH3mk18cYYmx!{lC#UyAX;;D-fTno%BUD67;p6>aMcI zu0dUILrm`FjFEb2ow8kVm?o|cT|u|&uD_5Hsq$jx-Tm+J?< zM0u;OoR-7leXS`!m>2TCMDf$6@>YGt_9y`I-kw!3yhwEe=7^gCKCOUjPgJP!+-ip!fI=+7EWtQhXWx-e;qFU9@ zOw#|XAj9Z*8?pDDLwQpQT4k|#C+OyNi9+5k9UeAR-g(!IF2+ONd%p6=NH+(9hFkHv zJ=YRJ_qJzJxsbO=^&y7{|5k93xa_WjA{or7<8U6f#OD1*`IoOl>KI9ZHqI+C=#d=> zoA;^BNoj$8%*T6xmPawp{8s8E=nbA01~x_gaXVb_c^{8jaeQ`OBIWk4GVe-8PH(Xn z{r1(Oisg9|92m^whB89Eg9H~Ro9K8iZJu&Ld2<{&EQ7`S+{xOFa*+3nec!fHd5@i5 zQCA9iv)7jnE_M$D-bZX+E_s#+BEFrbY=FGkujU_1+RzG$L)N||T_b}Ceh0#~*Vw%8 zI-G9$lrl!zK^ym~&q30=7n}Eul8tK~`Y<2wCR!eN^Rr2{-8nZz7-X+jDJN**^A@ko zNgO*7M-d3KiHqaBhr5`Gy`~}Q0}NRHcuPj};5JAzA3OS|dWX{SHY_Abp}dbE8>F## zA5@e5p#phZ<^^U`c~32TJJAh!+blb$GV&|{EK1k-rp2BFkb{MvjUeyAJ&W^AH@1TF z#3(I=dt{&&ow2ED1e^EL>h(E4VD;9ajVqmC8(cAp&07UAL5i7>_i|bub8+VPIV*~D zL$xr7?5rs76vXF!$h=pBy#n5Q6E92d1o%&H-Lyvb>^*Uhn&9Yjgj?)g zmOoFt>InkU&iBXJ*b;$8;rRh+Rd|9ldHUfJt5#4jSZZ7xvm30OE4TL3$zaS&!y}?n zmG{+g(hAzR$KA3n>h;+D|3_7)Q1%?=`vz${Essw)^UHKzzGzVpe8f&aM@UZL6XxFw z`tKHZU`$dw1SPZoN5PycLT@bXF}UEuzA;~iJ7=lwfWDt-9SK1!y+oy2uB_?KA1s}oyR?)pFQ z{r>{S@)#Nw zX^b{*W?I!f^&U3w(zP=pG3m_5+ntujS)BP@YI}Xbbx;`0OZ@6}kN0&uG#2Il;T=xL+qlPz1LbY?EmIMTchk4w zh7riS>0n3;J?}*=pOI|J2JrvbyVG#0-Zp;tn<$cDo1#=mhzwCO)V_$MRE9D|8c1d# zLguNc&?K3aq#~5DVj=T9G@yYJrDP{$=2^SezK{LlzkX}~pBK-w_i=Q;(S3Iv$9;b5 z)48s5jkkv?f)!xi5qch>4lwWYWzVXkjp4Vq{#Z7lAL9eQ?h)B&RfK+V0%}xY>)9|# z_>8QxwNrR&riae^Xz4TXfsyujS0Xu%Vbo_ZV>Dep2)`ih7+0))CpK?ph*x11%v*rT z;0_lxUvIhiU8d0QF5UCSy1C{o!+WJa(H3X7u0s<$H8NG&}y$UmVN`9 zw^EY!mE~>WP{X34n%^_*y*F;(5|zN+>U6*N#@SMrBblLZwf3Wb^FMi3qv@aU{O?22 zgZ3I`&yx?aP5i5+(0b6&sh6X9a1WZy=Bn8V?;z9p8F8cV{D1I6*O1n{9ncZZy1(>w z2pG#yba9X%LhDr(SA}eaU$NWwtf|`B2P8fcb78%N-h)I94(qSBo+Kn8>k94{xQhv+ z_aKgb<1@|&Xzvia0m*??pKpZTam{yl&@2kE{C>6lZO!%*Lvi}}Kz`QMv@_a1SDQZjGLS3{C$yuaKyyZ0%~+k7zU3yJqi z?{_u~@GW-RS#PPv&)9(#!_#IPR)hj??)IM>Vcxe^UA^~Ar5S`~Oy+Uu_y7Wf{I!** z(0M!gwr!L&pCs%+*3EW5jQ+)i&YSCcw`{T|?eTU&a^NxQ6TiuN!v>EB{+g%v5ME>R zKEOT~^yWb%D_`@}tg80hxaWBrgiyyT^{-Ci8ae zdnSR#+o&@)qY~yV`%;9Jw1bRnKeU1m=3Oe!*U&p@2eQox-krLkz`0EE#~1kQZMwlu z`-vURKun1kVyfi>ULG365v|dA?}{>eedORIp#xcW6>^FZ;z8%leCtNglnU+f)<$wH z!>G^0&>z=gga-$1)a$SM}?jt%isCmlY;lI2#sbk?+!l04QRX%Fc(U9!o0_Gigii6 z2MP~L0$TzMM zblxZPl8(%EnVx;dH3BW>`_jkJ>E7*j!zi%sl-Q%7bfAso-J4%K;!eh*UOmE@_}9=Hb~>w?gOn2n z;>|$qdiS}E1aBa8VcJls0G;=zCmc4+_a+I#$huu864Z46gSU3ys#_U1X^;0Hk^`&0 zL%$gEr6l0jTV6TlG(J6y*}bcU4xXvky#m?fMX4Xuqhdgk=o;R8w36<52Z~dd4@-r4H%zMsl6Xr_Kc9I8^IlQAQc8abyg6}R zHT=mx1TZ{~JI?^~mh#rrdMe!vTqAe%cRcq7=Y#6MOLw93E}UPfIecxB5P_`YReo6I z7lhuuiyxh0+!0KByq_XDukd5uf+W4 z&^9_EH)!yb?gu0#Dsza}q_1Owg+j*rVMgfC9~+F86SS-u%ut6`{m$>IZ=xFECKxjB1qk!Y&o3k8Fv zV;-H_(nKi1+4uX3@g~5gZJ1Z_-3xf7oAf#Twn05K)DC|7xi+Trm0PDt?vs;9Ss5!~`4l?}aYCW0&sU^xQnB1dc z2g!3*_wCt3biaed2~wG3Ro!igKd0C)Eur9T#O20I=I!zJjm07#JV6kuOX=Tc)*e27Eeb*Y~C;DiiyTB3>3T#E5n${ykl~G6wr8=+@Ak(2Iid;^{$=7d&{%WJ=HL8#~SUL#as5E z>~sI&oS|S)q_tMK9lkj6<85Iq7d!m@KbDi%iZ^?M{b`b>-J0mU+xudBGvLQt4k7EV zo6PN7Uy05;dUV=Fg9fkvzeaLk)#qh=@_xnwH(23ufceKNY~Im?431Xko6tG_cM(~J zwV2&La3u5SDNZB0=Zzy$mm@dWxBSPQKiwNg!P~%lV=tMvx1GjjG~Pz(qy2s`?_0sF zze&8gB-+1jgD+0Zh-F@qI1YF3z`&;KoFU-O4W?@+VBYtfWkaoan?ZgDK~wdoH^?0o zzLLp^KL0CSi(ECwG({*t)=5V$gDzb~pa1tisVrDGPkY^44atF3pONQ$U0VPTU~(O- z<*38HI3ZK_{dYU-b?EnnDMDy2_RWc*FO0WFm(l;Xw~H&N%TXQl%c?i}-}Qg;tVYv6 z;X^DdMGvyr($h!kL2KY=keJwy;m~@}+$kMbDYysi$XWGJ9qvJ{T7D||@ch5#(RzaZ z5eM+NVaQp)DH!N)Z_yu;AwtVS?kp>)X#%}E1g^XvUhs?3eO~_@M4$iPAFz$_FPkC| zkabf6$)a{!&=0Y7A0(QY-q7Cs{~5`FRUgwS!!G}K++el7^|Au+6Z4SS{BDhrCsQ)? zHtf!7V*Lxu^*H6+c|R3H`X7*_sm$RkGqwKj{Lezc`|zUMMe-r`u5P_58t>b}$}(GE z-e1a0+ey4L>Nl1b!MwGs>V*y;Z~#@Gm{&=h3kLJ0TP|3_yszaFwef9DU}-!5^stFH zaDIB=%!ncS4w6$#i^2Ey6u|>ocRn$dqaYofcfb-H=qaQ<-uy@otoq_3KU9s~;RdNp zT%{IEuz4??wA=S4D+y}In3o=($3Dd3gx$J_gZt>7cOVaSIlil2_qucI&kk}K1#h#L z@HJ7mdy}3Zb&^U@LF4_HV0?WC%==xP>2DHm_0G5*PhsBbPtGX5+u;Btzw7tgTnq*} z0mn>UZX!Y-nO8lv>}~=RM+rN2DtUwQuAOKL)NYPu&vfD3Y|C0 zjBnrMP1@r@cntc<)x(*yiIe=Q^>rBwQQBqcw3wg_@E8**0PvbMH-Oa_^;P~ z2J^NgFtNKzI{?$Uy;~fUg8{*(OF|dsUH5+b_>E6ZzccI@ahK3}pUYaQ^xd2Gcn2Xlu9i;1Qi!2w)Qm{3htzP-Z*M=oY*J(_v1vDm??Oh*cT6zdA9{9Y(wK6H}Y$P zKFnKQ;szk`UVh1+k<`8Qqvho8@;d;rq9vJ(1;M~Y>f1~;eC;hHRk$$tdlO(REbKNH z_Xas$Utbx@pz}_ZiE27(Hbp2z*7--5R+n5u=PmNFHss53+T(o>$$?ehDXBsm4PG9w zvC(?TC0%UZyPSvu_3*Vf)uMJ*>qYE)Z=JtvyQZzKL-(7LjA`m}5c@tgwBGnP|I_r` zPc9Cg|2Zgn&^P*X@$2SX4Qhgip)L7kRw^nVYM50yD&!;M7#&j0KbypOL=6(jSGj}vA_PGv zpP{DSU}fp-2f-cahuG?|0F&@_(}cCix~L2Wb^#~!LoAo7oh64Z?eT6#a&TbOH{A7P z_wp-c-Fv1|pqCMWYb(o7KcGfq8#bUSm9x?*Q_aCkI7J z1_K2PzRW~9BJ^bi+bR9~Fz?#ho%gqTgL6u^x);`=^R5$08N@G}CIlht1_Mv0*O;L5 zwh+9SdtHY1c()=s4rA1(k-Cn5U+Z2`9^*RH|Pj&vCHws=53>* ztYoa00!6y(2X_WzpWebb>@T12{7(10aYj_;@cK=RFZ$EHms9XQV(EIE%==*FWd=0f zOS?-x2*bQBKvWosccRCE_8gdZc|OLSO=uPp`F(0Q0ACYw*@|Ij2KaS3O@#QX^$OYP)|8F2Uu*D>4T ztN-SITA4xrvkrI%$wSeDY(;OZBln<;lzl7EdQgf}OJ5~C|N9Oy2$1Ig$?k!5*6?}zqD-v z+tiHpp6~GnGKa!47r4<6vDt<49n5#937e61KYUqmGwaX~v9hh1d4fM^ZwL7V$$?d0 zceHJo)+0Pn>-&2Dz7sa@=5u12sjau6H9y#Y2##a#AOqdU>z-V7r~5-}pc8dDqSM+t zBxC;UAn_EuPgXTLk$HCtjC7x<~lXIpC__{i5l7}ylLXLTC$EVS|x1x%&JZI!Ip&D5?{*rS= z1P40r(-s{`j7_x1TNTNHRUebOR#V>;9{BOeJz~|x=DqaoVSAh1X^`W$%ul;EVDr8% zbpK{vSQp*%p5vu1hvDplF}=U1x40;HTVHA)BlA98Rm_6M``XoGOrK%i-j1qqB;I=K zx+M3*ybYVwBj)xxg5jOY(!;gz=7gJX$r6}%=F(@Ti2+SOz8qSzV~sb6_{1plWDK2m zweanrvo6zwE6BP|otws&xzKsXTKaKWKBPU~O-K%``sAi@rd`_HAU1#3k2pna-rY6) zLNnTF&^Cv{BA$LKE>7HYzR$S-72Wg3Wm1{r+_w!fe>W$b6uhmD#`KVRU-OPwhQ?b) zK>f!E%=?UITqTLOcfVAl3e4O3hjgbWvm>a9SF92y1_Ae@rO?UEL`W!je6LPq69`q& zA3hE99@{>Y^Wi_b_pN=ct~<=93A4z$vAWkUOxL3GcD1OFvb;ijyi<`JSoNv!37-$f zbA#+Gh8^2DuzCNEe?1rjUwbqCtR?V%0DJxyj(GlXZ)q>x@4bC;smqbWIQ~s0_TT(Z zp4DjjCp`ZPQ1l?@ReC<;9_0RYFE?5b%H_NpauM!9`;T~P5#SyqLTGs^2KS)rEIW&( z9Gt;TapL5;p+IoSJxAi> z1X)+q=5O?H7JdFdZKG)sSx0;G{|6+;8I1a*yYJ)|EXRZL=5m==yMAHL|K(LG0kSpe z(00RI#%YgQ?Dak((#+)obbp8qbXiMPj*HDsH=Aqz3`i>}csqWa`E&n2>Gqb|UM@Tu zZ~oP%AI8GGgI~UL{=-{X#zq0=9a-ZQr7P|X_I8}*S&It-1sY3xhm_zCq*rBo-`Lm$ zrtJ=`x^3VMp6-qD*7=V^tXf=RTdL9wp%ht1h`Q@9`4OG>-kuNNpQq6tZ-C_3k5Qk; zr6DVxS9ma0kfWr!8Jl-v;3KJ!>U7ALyCgtngo+(x&&j<9m%7nCZ(KcB43$UVkN?%pD5?>W(UFFt55PlI`vTJqi^@xHchg{lV3ySPHADe{dISY48JM{89O zc<{^hl`PD=Ft;<$SE&iCSI!GihOZzU8oi)({|)+pRC=NQi@o3s!30_NBy_YpyAGYV z8PUve-k0`xzd&+WVAN-xeT{ke1|C4FJcqyuM=P>WGo+44gwB-j(a?|5}|^N$tD__O~7N$`~0M!H(1~BeuA+Bo%a@@ zjjMjmP7^jD>(2B%y1%gzowtVihy}YT?eSJYa%f`Im#C3tz|w~Ydw;R1Zy3iOkODs} zp6`Zv`xG*-84x6W;7-yhAU9 zcND?Ahiq(qka(wAYn?j@^InzQ;yTCa1T>9i+>DL{fgi8R&OL{(y{#+#BK%XY3B>1k z?`D8+Zy^LY4@mT&^BxpQ8jl*7CTJk*_<0I>z*}_QXL?-qZ>iEA@9#(s4~+VZ^4)ig zW#GZHU!LOoTd;Zi+l^k?&yWsv>Gn#t+G2Na-!Q&q`@6d7e*X9MqAo{V!m-oeqyEkR zG(Go|i-YI?H55JQ3=j02+=DpeR0Pm^P;;?%|jV=x$r$m7Y>%0 zjc#`Vq942Oaoz|7or6J6Z`Fvegjxa~K!5Ha6{6tn)`|P`1Sx6$pQ&eB ziN>4X)8(TD%)4#L{c9xNk>3=onqc0Lu-$zLUKg;aFA~grFAxZ`8K_UI5+Rog%RbYO zji6#7nW)9#1EBPkcH$A}ybHPxcplv|OCYZ^9nIp~eGr}Z>zfLze0$kwj`vd}M-N7Q zpE{O%>O)*$S3;wHd3p;sAG>ttr*(AC8`nr(j^|6J z;$;2~NUJG$yWSm4BX@7-(;a+hyiM$inCxKQ_X+70B;M+5FCPDZc^|rbeoOp-GazWC z*v~!-1U64TnhLbux>2I5+Z2O4j;oi`}Q<}E7ODgMa#9`ugG+y=Uhy@QnW zQmDY;&(S^a)PvOJkkd>0$#Uh-+1phVyiYriSCDzz2d46(@z!A(6!L(1yF9&0B=Kh3 zaF;;<9*_*)*mp4HI)hcs?(1q^27<%9>+H2uh|uZ@zjbwsjezs!Amep*AHYx?x5X(Q zowuEBaytK-SppNXE>BGKPPYd-@3?WB^}1=a$J+_Xk%&>>`t_Z+ru6VYWqI?7>U3=0 z&)q`!RAJs%JUq5rt)pW8-zjobje(c$2P7Q#TIzDR^nT|1JO2w(@OIhN`hm>*Y>68W z8t?F>CPslUZ(Bx=Riyc!%scu~PKsWpGf41y^(Nz0AaE4%;5n;Igt*o+@$hmq0i|8b zcLi5?19^wwc}Zh*-oKu=tXO|$hMh zN2Yo%VA*|~Z@>ndx1#WkV?t*$An~pv3^Mh#*qf7KLX zWrt@>W`?^sc9G>fmsv4|!oU3YA6okpfaiZviXP;>2)U7akZ`@sTC^U->;BV+2kt@j z^K60J;U1LfcJuTBcn8_K>q%K%kqgKr94-8@F%Sgr`W;oPPK5LywqAeg)d)JWPn-(y z@dk5Y4K29x|2PM^$6F`mHUf44#T`-b(NRI-FE>U*Sgx>RRX~w zWgYt}K!jpG*e@5n*a#lur(SFC_6B=;m~Xzhh0gnStWT}omRZ7HWZk}4dx6-^=)5Q5 zc_lSxXm1CZf#krdZol%Y>l>>w{#JbltB zLifCJp;YF`V}2w1cLymZ(Rf#v1P@BXye+q{e@o&$l@rc)3g&IP z5X)5(?*cB(7iaI&4FrBl<*%yAZaD`-2BiN>5th(zHd82HQ0}`;<{j5-D~QIssjL6K7Rbyy%! zvTd4a-A;tAeqE_&S>6b;E#p7z^6&xuUXG6n|KszP4|tP!Tm5DUpOJOkAywH5m(k~c zfx@bN#WcA0&Ovgl!l;j<_-)9qDlWjb^ZCxpYq5E6x%puE*W?FKZ^o(2)*|e;x8VBB zTvW4D>3{xzL0t~RCl~B?Z2mX@)7q&2f2;?d|0O7TP{4$nD7gpe*>4a->p@jEyaI0+ zv(+6Qy-QVtdr+rht78n@gL(#B3>V5=fY0HH?W}$Q;H-9_h?+JLI`*K85yuB#AXPgk zxjPg-2f0@?@zNFa0V!DJjVb>3EI|QTCo3}UTl3Qb^-yBWqgV2H89VfU%=rJ~{}_hk zz^adJxBEi385bBT2$p8F9!Jedj&jFTWrIjcE);yBlSjZA`wEiO6A$T<346NVL7Em* zm*eVFo!M1?uONw2@b<6I?;`Wwy>UhqjrXIU>ty<2-a0|sn@PMs#Y*d)hj|BvYkL=# zx&Zm%$orFN0YJ6&W%SBjM93zrWcAd>Mqm^Ddf~GXe2ZPm@qM$d=)AN2GT+O#%@WA# zxGraEtay*k+k|b%rnQsyPH*KPIk4(Wf7`3%e2oii`r5*R?g-O-SfuXr!vRO+shUH&i@-Ic>BeiJVEAtgtbBhjrZwQzwL-H@7u{H zGbG;EbZtevNjpeqhsot|_f}E5!|&D<01m}WI8130Au;|`#Y==np!v}*LafspuS^2PS)OgveU6yn0MFe8{(wXTWar1a;#w9kBm4)UXi@CTDghlzRiymf2VR-_d#Bzs_9t`06ad3|Tk4a)p7|33T39xm)D-`qCcn zEF{MjjQY3@SDw0jo(mLzU$X7(JobRZde66ZA?6X(PS}vfu5M_7051Y5sJBDRDVBR&v z2-AbhvG?A%;NFxwTN3Dh{*R(E$AORMH^G~ef7k!X(;5x`gy;WF6g?W+4!3Dfa-+Zf)e45XK-h+y*S0#CTrM>xI z5Xn)3QQw@g&rcCqF0l2*Sbx~c3Cu&LdtL1sNbw1z=N>lI-t=Ta}=Iv%QB8kTPxscGMJ23CkT|Xd4JKa}uik>$Bg|;Sb(MfO6GFrH@yat{3`tnoZj&^f| z4rJZ2G4}RrR5qJz4 z0eOR8o3M9~GdFK<@SUXpH%R|XqAmyFVxhDA)jzzYD0qj!uURDXwl9Vx(0EsA>)+3X zdAGK;@{;ENJMW92OEB+o;O$U3Q8{Sgbl(0N;Yon#5PKzqDjAvum<)K|S~w4(n$ z7qHoAeC~V?Ht*_CDW%4hk0GHtoh>JRP;q<9sxAEizenl5d*i6hA=LIj`tRwjjTF3t ztxaUeyj4dc#nE`**=WvP2J=3DCSVtdcZ-v{&{ddsLcwq)KFbAcDcjcZSu+5vQx{(q zqeFx^CEvY#Gt>a2(y9yhUiAT5_nLnHa6!L8S}<8d$WvjCup3#oIM-IU>mK^%q){>} z`QCBb<1K{bXu_y(;_Yj(y{EXq0rncpV^^?wZxp#XC$cLKI_JrZe^yeDxtYOf7KLwf zaHsqEAGedb9F{h(!$Z^mbZ(*Mheb8M;0A>UOSJP>;Q-~3O*WB>n3gXjOv6g}u-ud5lk2l3os zlSk`8#_z-0jo==XWcsO11@1v*J0$au!ab<&a6e2mW>Z?lJl+dBU1-yK6m+EF<&;Kl(#ktC@1(0gc!sFsD>;Vav)*l2CedvD& znMz#_$&k)2xA8$GI{?ql)P;B0k#>~n;=kuYqc7|iy zsQAS0HCLNpi!Xh2&wD+UIY#812?K?Hc93!uyd#3Ies!$-z<_zFxcH1em=|K^`FsF=z2#x~ zXc_kg;4*K(u2td#tX)~W^^DMYJG-3^&ptX&utnD0yzE&u>xkaHBVzTtDh4@dZgWD; z5s6XXg0zHfoevlMaiX%~E0);28_pFRyj}YQde^>#casD51=7Is--komKhXUJQjR9- za_k;ym|cJCPxqFg;C)^YFHPoc8n#y&jkiDNlcfwFE#)x+*9+UdT(H*c_&UY1pVyo5dToT?fp4|4YF=zZi!Rj z9rUxe9CsMhodju*H#r9#$0&&EV)M=#$f`DidCPAUo4-xXx3~QF zj!$O)qI=%BFe-D@3r2|lyZ%oj6DUR*@cget(SxpZKd2@5AfL9SN@zXkQ2Gi-UbqLX zS{gH=3?E`AHLZ44TPmvC={IRKt#bxa7p92yQ~sd9!7=K}VIm|sB7RHdYCSlZ{Ml$` zy$={~tv?$|K<`0$8Tprz%jXH?b!smB{$Q&fcQH=UD+mCEE zam9l>d4%tJCcja0lK(d6Yn~^tsTM-7ud%AOiEg1M-AO^S{9bA*T;8Z*Kl~4T)OLVD?pg5A(P` zP)~S#hS`h=$t#IC1?JWRk@sti#?yR&_k_>RU!~~0-$Z>%PKcW)cp>XD&#bXs?~Hzk z{S~hfs+U81yk8+Xeq+?P!>Y=|X#*Y*N-wjkufgUWIM%Q|!=wmec7Jf&^LZ`iKZn4W z@5j$@XVCqC6nKHU99l8MdX|5`|F?yLceG2T1(|oMTe2b=@44-1v$8PnpSt;bNW42D z%Eo75-UXcF@iuPGK)O3PqT`1@(EX-X5okh$#tQCj<8G-3Ru-T0kNW$7BZ{mIqq*q3 zWmQhDba9&}SRm{6DQl)Sokr*Va7J=(>}lHLy$Q*YgHd06MO){+<9JZYwS)cg4E7E( z&RU^mBBl^JzV>!vtpzskLFVI}@2ytQ{RPtJ)5oaFF=g#{Z2a%jTZ$CCqxOWu{|$#D zy}h-;#Z3W?cgxz%gK9AEZO=_SNxYBVo#7OQ=l^o{{J4aN&R`I_*3>xQ52kxf)t4F* zA@!!6TF<`K1B>gnJ^ju;fFKh0rMLi{_vtK+)m!(?6Ugf(N~}!%LeP1u=e0{MY^FWl zE=Ue7jQVCZ;vY(;;(>3I1E*s@HgA)(#WRm#-WTpz52lsXV0Leu<6|KIik0qp(%oF z^17On;j-%vpr774=l^T>)&$z){SnFGhfyE6DnC)mg$EV_(uc)Mv3Wa3e6HncD}a*g z;zmRGuy1dvJ$XF4y5E)VHz!(D<|wH=pHk}l@A^M^R-@^ka1T?@1YuoDs^!NN&-s^*Yhz(m5BI4l{WZ3#Z}DKCR`Qu;ZP){nwfOQm)AFq>A@9OXPIY z=)MOX`$%05uSot^T^IhmVn>yNcWi>y1M&{CNxNPZjkoEOAhq`}@2;mdiX`4;?zj9& zZ;BZ>a|c zT$*nOTzvpAS+4qC8=ZIlc4_5KsRe=tvhK6V#B^g5I`8ZoYWkx_w8#4~k|P(RzHirX zH#gPcflIj@p)eVncVCHH0C!(86g>j<43A;+-g)5D<6Afpx*w3dsm#$m8YI;U-$4p* zPLwHlUsql6zo)lk3QsDd@pfj>SDS`;8(f^aLgKCZGvEdb%$sYZB=XriCs4ZoQj@Ph z0Jwu2&n`YfgzQ&;{>*l$9yE_>t}in30nQ5Fe#U5`^DeVC);3?UKyX3U?Tp+J2X&+K zt`M(2_*I$qct1ySyuhgM=Xj9q&S@@S`kQObKqNNr_7_4PHoe8r+59Cj@hLUf-8*%j zyZzW2y625cp)LoXTDZ^t#6Q>nw^8uEw$w46+`V51DQrXI{bn|O%QDjZKX#>p#Jlwr z=b9Y&?CqvL!&zQNXP|D`BJ_Ljcx(^Z;UE9ic6a-fsC96ipTdR_$ld;cG;&7%Ludf-E> zIzt7aW zy#b)qv|TCJfe6{&ZBe|ZTnE&-h>&Nf6YwvNstR#aL*M_c8G{1g$Y zx0Y3V8de9Ea0@4LS^0pMCbkEdTG4qw@)_gHtXv?xLe|xt+j{@G06OoFT$RI@f6(3z z@&S?qt3J!1>PAjpJUHnXTl+*AoA=DeB8E2JQpoqN7`QEi-Mu|(hs-@zGSdBkB-ub+ zjy-FpWG?|8Yk0y6JFjw(hp-rwx|KRanG3?zm__{=lAf%7s+#=2W^~E`#^ZB+04|+>9%1*UoA7ZcFuSo730?>9CW{f%!;8dM|h0i+J zCuH60f#s!JMA3PlHY(=r-bH)7g^(OB81*UDXa2a^#RbCR+kf2l#O5vP`i8h;dpR^> zoAg?P9sB7mTwb`;i3mQr@7}m4)aBUx;OnpZ_y5iRG(Go|i-YI?y%as@{^R|*O+N9=37aJSWc}?0q{LYU*iKxMwZ!w4xMEd3YP+b+VT+*u0SH> zey%PEJxPu%s72QUhFXHb@5-s&Q~0f zG&uhwIfxkbJs-^#U4(m(>#a9{M`a2%C;6|f>!kbToBfrLvY~!So;~&s@{nJy-f*HX z-S;5RbJXR?**G9`{O>JxdnkBkUT#q&^R`S9#-s7}{nBf-6h6ed_l$>;c<+1^_~|Xo z`>oNpuG$iN5ItX1XXzUVOb%SN{^Cc3!VXACW#-iYyNTKj3=Zc&kmS#SN3rOk!6h$1O|Ib_CRH)3MIq_`u-yNh51@C*iax=)hd%5|n?E-;zO+!!ZIU@8y*SzUwUkw;-)R668 z>I;(c*tr{I(RYxA@7>NM!MxLub>Z2EI!c<*c}pC8oU33#d%T|@Im9vQ8@;OMV)TIv zB=EdC6|fSUw*b$FiK_7msC%MT?#omSX15RgB=~fX!VM%PLGJIea#O=VAe)(K z^~9S9Me%3FZsw>39C(w7bKJh5@i$|jq$xV@2mBi{%s6qN1zAUU*pOMuggzh@Yza9b zphJ7SGm#uv^(p5{Dw|8-!8_0Ud&`$$^X>wzdGihx(DLb}dT|QayhoB5Y=(LNdX&sUn*TR?eeE8DdHYy3 zv#S<50zRg9%f9al1f2$TF%QlXA?9;APQI$O;O?`BDg2G_>8+fSGdon#d0&_J-Ul(_ zfB~{@iLLlaxkdEuoxj9yz)+m_cwa$sVAa<>$|L&J3J;u2bO-j&V$c7v4JTU~Vcv}= zKvn8bDsFFiEf#sngN5$*-nf@k=5SfmP=Yrn|Gxi6p4MpiCp`b_QS_jkbbBXq4=P)& zB7oL|&UU$RWyACT;p=mOTi_m)<(1)`W&wYLWMTLTG28|yTZ*65xeCw!uMT-TTqHuL z!k%t2_p1gmQg<^a4Sc~v(N5Q{0Q3Rr%d+<`*jRBO7g?wFjZrEy-3)c7w8}D0dDj^2 z^`HSH$4ZR)d?$ZrUC6+Lqu?0NS4Zqa>?z*ojc2W^Av4>Q4d&cboP!+EG)xRuq5mHA zmC77B+Y;jbzGCM91@A}hjhSTLQDEsxG~O?^KEC)I=B<%+I-A7%WZZA*-!Sh3>r87) z)=DEyRC@8lH%ETs8g;LB;jNtk!1)o049KS_N-oT zC=p^!%xY#|Qv=_8Cv*4nB7FAtM0dc6N9epS%l3)|R;izBtj8 z;Pi5-^jgyg9oXo%i6Hu6q0(+T-nmPc31y=5ibl<&kj#TD&(-bQIZ~mv@p`W5Oc>X^`(Sr&SZOq9%Xuv{x zEm{w{UhVe567E5EJ(l+r;U2WccuC`+Is63a(8b4R1Fb;6N7))z)j+VFm(}NeED>tF z_sjXKT@`S({*czX-xuu4DbLzpZH+q58|OcI`D_^u>_OIjJKA?|WvVIa`Zt$Hv^o5E zAc|x(@ykO9dFewm|0Q-DF^z_a%EzlV#jq{F;T40 zrT-q(L|u*p%Z@&SRzLet`zoypSTrsMwTt_L)U3_<#jWVP`*da4 z%$DOoIXqdt>>C z8e;k>Ts4+kjrz}?{BQhANwTr$jXb*Ny|j?J930|v4sCb;@HV92{Y2wt4ViZUTkC2x z-c?prM*cAGw_C5xlX%DEITy3Rr?);#M=5W~w+7-7UkuIc1Hsb1XKe?s5}}*ntxr0; zs(=BHfqxLcFF19a)g$j4I&YbCyvfg3;D7_NuA@^pR*#6z`~1*sO1=*5@s>t%gkscJ z$c8($&jEhCa?|~7+Zl4`o;OaC${eHGM1! z{q)u~6HcB11={01jO2*HsL$Pg;|D!yJg|Pb)$NBjHgBjt#&b(XHT148caRT$u7cd9 zQGc>54b(sRg8t|KrPSpJYW*zVk^QH8>r?Q~eRWTb%-g)mMi7nnlQ)4WNigsIXN8SO zytmx z9h)~Jfo-S=zV?>W`OMK8e&`dGHS!y&Q5}3Nd*tc9dzW9LE=SO)PvRE%<3#_i|6|FZ zf!~Mce=~|6^ejH3liY*m=QfF<^`NBT+9*8SgSG^+yjOsGPF=zxO;9`p-MjTCO|I1o5L`+LkS0Q`9N@o;Yn5wbgR*Go721yBnb`XPh& z1BEMQ@9fG%=Y8t!OHRX~MM4R(?pSz*rr26jRNj(@YHk_!(;n}WNRIUw^=-<@PfnQS z0(12~a*T14B95TN@Tq;aOy1yozld{CAM1Rp05T zC7~bBfdP}vBNayIy!~90S;E(` z+*45kJpWr#^q`6hJ6@4{&{?Lkzj-)sd()=H!HSl3M+=J>Ke`RvJ zavbdYmJ?A@=LcS%GO2RShF`JkKJoLeU?teRM&W>yzc0{uYO`neZY$J*$BVs}Khb@W zpoOfFDjpDyu4a+G7#_n@Zqyxs~tsMT!sUh@dM2e}_# zlo1@LgG4=TRQ=kh=s^XHXLHxBr~moCh{_y?=K_%{NJl7mmm9QfBJ-{!3`wH#7PY$t zUc$WjzpT|J@g5n7Xr4c;s4n~4{PTlz$3eb1XS6h%KUj#|mM{Ad{=^QqxVO7$B{(zH z5h=^+2kd2fv)CHYc~58xGG2~`U$KL%Ta1j0tDQ&ZJu%FE;i5V1@g75RjAGQ6Efq5s zQpW|%zaG94b`P6(Cx0blpiUh$#n^PDgAMx>J8q{=<;q9d^v_$1x*VR{Sc6$J|Lh+kcR|cT+;JI2vy?g7UXtFmJW7^D!jeI>#oh zT43H~ntA4IhmM22Tq?WN^8G>JQ$7EC8Swr8nVYiXJ1fEa57h%l;nQ1!CGUslh0q5i z7V&K2Si>Sg2wAt$BCY#~D?0DI-@iY7+Dd!8mm)c`FzOpl8w)*XhzF^sHnOiz!RF00 z|C8bKKrJMg7t`27&DUFEmr6#jUPk}j`x=!wToh_ZH%P;K@52^WHr9o5{X&kr0clQ{nlrQaJ#fxA8(}?uY>G@s>k!7-G~H z;25^tni&tq2gmk1CSdbk$uyO*#<&(b_3QJoLmRQXxAM{cSE(OE=$`ji3+i&nT>gHS zIriW6|Nl=1&HuOmXK)X)qUb@j-b%;GJ!r*sHhHujG{MPS?*$)Xm#Fi5Y=(Q#U5$B0 zJ9z$oz3P^Qh{XxeWwiNLc$zQ37xwN8FD626b$)~HUFAS2`W8p}Za=V%?Lw&ULMMkLWH_1;*pL|VwJ%|g*A%#)jF&Fn|jPU#a)b>`zHCRe9_l^!Q_M+F+CcPEhc!*>lmA%sc%3 zds#Hz4^9ja&%?ZpyAH;ZcuS?Y2b;jWv)4ZUvT4%^VEBN0&9T?MK<>J;?U6zv)bO^i zd0e0ZC`OvITv+P|x+d*@eJ7&x-hHg>tikjGp&MCu5ih1-*^kcqwZ*cCOXal3dl!@7w=RhHV~>If;})l$l89HWUq#RAda95;9Mj8^{n94MZgwN}-}i zwp2)_42dSGl%kU|l%an6)Y+fstlxU}cb{ji-?P>^zxDZxx31N?-p9+e@9VzrecvNz zonmE~zW*oC>BCVyQ%a%qPyg>kgZKSGr70BeQNti*EW8ET7N{2>csuwQ_EYe#O4cLK zNAPYiTcDN!JA<6_58D^oM}aqSq55CS$uMyuebyuE9tcP|bHmg{*U*jNJX5-h{VyZx!< z121H8f-g()cxWpA_7>@;#$d-OS*EYvTFvzN5PkZ>cR}Kx?Jc`#@UAZ}S%>0n{AHaI z7T#Sil%gvTyrL9<6R_hWHj+GLVW~ zKWF16x4c$Cz*j9KH(5$Q-ir>Fh;awwZ*Li|*|%eMPJ-$2{s`0QV`0_}(`*0s|Njh5 z8TlKe|M#S+L9KhrtXG2_)BMXHYsoczq5UfsRRTM(QIk1N!@jbDQ_9E4@coFBmo zMh7GAkK@-M^@r+_(I(kUUxRoX=<_kW$!n?Z-}nDLXz*?^IAnq1owK1w6ASN`3zJ^z zBY4mIe&PoOZ(Vb;_hAI@I*sYaa<#ibP?+ZKC8_&CKwEeM>pe1jtH8Ot`~nQDsy3e6 zPl^PpZrwvYcG!52N$>3~K0ZfMp~lUs7Twa<#l}0DGtu-#1>@n3`iR8IZ(Do*ncszi zK==^9!HQ~pyzAec=zNagZMidk@iaY0?AQ)`xHp^6^mr5O==AaU!9%sb{l7a6-jBu3 zh@*IK8!FJi!h7Jym$pp^-q2j77-a;xL`>XwAqq65Qd7SR@&MjrUTMg+GtpnIoZbkE^*$6?bFfU9=)f`Rhf- z!+QzU$0eNn!oxfL-#H3`q~Va*&3EzfeqHL)l2h>rj@p|2>7plo^{y*+xITAr0n_*Y z@t5iIQF^q0Q04CiX*U|YAH9ijLGk{r5~hxY_X+LTT3ZC~?rJM73f^6p`8X(plY?Fd zBC?>};IU2i4hgnMkZyV|?~`lacEPjj&G7K}4Vy8nKT zgvKcpwh20BVdHId`qI_y#~BZAKB^CZli$Ig{iZ9<34&X1jy#vWgO7IvTejQ@1n+Pq z?W@O{?qd$x{uvj~-ZzU%`TyYUEqZ-CS5T4tTfJRr@NOz7`-$?(&fb&GmV)`2JbDyG_p zqk#O)?j3%u*ozbFGUpEZRsABNajfj4>xxfcFHUrPxb|e@2;K1~R|Ly<( zDQ}GY4buPn(A1zVry65Q4U$1FNQcwy30O7g&coD^H@`{@R78u{QyQcYVxdbeQiBH9 zK-K*G?m$YoydXv=0&soY%~{q$hUK(wdmc%x0j4Jc4EH!kfn^qC(yDqV%tyoKy6?AJ z5@tzq)VPMvEB(qew_(Qn7aN6HD~ZC4_EB%5`tZfcPv5zHo6%Y#xa?AXEVvoJ23-}6 z+vxf95&Tx?wS(dVI%?4GgB{Hs%zuJ3;TL^AE=p#Z+uZuIg5*tucc+@QJo<;D&GjEG@f*m(P;sv_4=&60AdaT>~{PpoaR@s{VFwpt>@czExl`dEsS z-@43ZF8_EUAnYYw-PVYYx5<3g1%e&O2-0Ur#?1yF?~NxN#5Y*lkUK+fgaQwQ7;%$HMj4l@5tx$J30U1F$$gYm3;C=3O_}0@1-fpgT3A@bPz_Xj? zbNP7@V8rUB({K|RZaSM8kd=8C`L~ zHwoByFTS(1<=Ich8$pIseaPVC=YR0s2jYDq(9yf8$x)Aww}PYlf6h{uBh=ZM%PO zs=~)xQeouut)xeAQc(SZeo6f8E&VDsJ2~0UGdR!C1@AU>)#!KxZ^^?RD=REr!OSgHO$+t?p!^a4BKC)5 z`1s)`Li%TGf&RP?iCzyQ0pF2A6HQZWyvun$K6tQcj>Joio7);2Xgi6Gw=dW8ao$13 z!yEPCjgz0$?DhT2H3Y%7T=?f=I`GcinkANs;4N7qr9AbFj_N(N`AETD=I{RrKj`zZ z&tlZV|H8lhKcn@c|7|`<{~th8gZi9z9;VbFO8;MEZVO@6pqP#k&yz@lbTRXMg9=iE z*67_7+=0}f+x?GrNlJNw`_0!sj`N2D#SretH9cf_u4lYGYPbqmdx1BzXCpz-@fnAl zJC2zByy$0*=JRPYq(Ew%icO8M#*eL-@#66gr$3)$yaq{_>O&MKzhSq^tZG3bcv-bN zH1{L^BUahsS8hvZGh95it+B(*eHcs_DEwVP@}t4~>9ou}w0b{X{hbvH?~&O}#WxYWzoriSpy2IyQEO2Ug17CB zuYy*#9zeCV^XKg?O7$KqzsG`w z_oBw+g8K;GG4b(2lm@B&a_Gtg1n<_LXEnoy+`-bS43$lH!-4dN(fy7cWLUw@#W5uQ z4tUJtGwWEVU{#Rjng|6lb>FIjkjm_mix!884vFkst-4u z{3OD9m#x@91dC=ux-_5S;~lI{IQeW@GaSEzbAif5{Ov9M-@VVl%QKlC@6j>(d~9QR zbovZ(Ksqw^_NBqQ`{W}%w0d(*r_aN}+pPCnN+*K%IiWCR3f{k2ciB+Z-nO~*-5zj4 z?%rle^_Jj?0GqZXyBujF!}q#31>|tnfO~5l5>!4!f&rcf`lqe1@wT$u+sNTOOL|3( zGqrZDuY8A%ck;N*i}baOhxc}>j|80j;&hKU+N2VJz0aa+o4fGwmLrM7*ATo*Ha0*P z7t!%@qKX7)Fk8m_n-l5vVY3C&Mg}MUp8x;fcHE5hL!<_U($t{WX3oda8q@@v@?zB> zcDD=;6Ql;6{RWv(Mv&jQ!pFmq8gzYMs*H527uabton(9?6sT;y{#xP{86NEks$Q*m z3uw&cMpgz#ftVccHQtsEm?OvquYcT4vYaMGQ{$3{J3_qXZ^ex7Ef(9xI>>l6NRsLU zFFz}d;zRE?5kX8Asm+r2C#Fvn9`kKEZ?+6I!^RrtquF9jhMd%?V{61 z%)L6TzYS6d4c@O7ur5UL-rO$6gN1h_r^{9=1n;?;rMoD2@98mLO=*yN4WSGDmR^8x z^mkelITUyh^S8vkAj6g0XRZ8dZvh31(2%I*Q9yEBxo2YxHs0zN7wi^0HcgVC#@W2w zvwaN-8}GFrNh;o*jEA=x)dyaFn$OkDH93i(@2ut%b2fauBOH7=p3i#>PgS(XImzQU zNS;6MuGuMjm+A2qo1)K$di4JM;$weCkij%~znI(}g5tf8?GqOk-tq1aPP!v_51#J{ zqu^~B75Zc^f_LXaC7+E=d%*COF8+I(VLPX$7yp4cG399pwoxPb{)CD)jNm=@8?yIH=uay zl;7aQ!uyb${8$KrxAcCa6BNAn9SZy5fZ$!?p_$5}xCbQUJ7)wP3V&i>l#c1x@D#pY6 zDb+^>PJYjuma$wGCIW>+PNd^w_;}xU_m<7peGGpLwiv0ugunhzuoTsEDqP3({XbzV zeLkXfN5ZR)|Eb=AGE9K%l{DWcO#_QnfuwF7;dd323-cWTv7@nq``FYMV{u@}!vG@WNi zqtrONqhB_$v0?ZBGbZs>PfHmOZxO1GpE&uoALy%GGKAorQFLADf3WuUq?G-|<^cTT zE#h_0mgHS#{=$D=}!C6zp7y)FAZ<-YaX6J4kmzlSxT8eZYO~gaM8FA>hMWBO%ZCWO$Hx?9iU1 zo1pwjan+hFG2nCP9?roId(1wUl;g;;HRC4F6dRsu<9#b8GJr~%an zUVh#4_Ph*jC4%qbEGdUf@EfGH?+3j#qnqKR#I2pvN%%Er)#p+R{$o;1|A^i9i9R3U z9)_{vf4A7}r@{N3(1KbNZ}KT#A{O4`^-b^CkVovBBkCV1c)x&-NfQygXD7KHKpZ|` zO>tfR!^sd}RQh_1?Hw6zS9ry8NT>pMnH@Y#Tp10LQVLH#3B<;GMtYZ|$IG9jWNKW2 zky1^|Wo*2I_K6cur7<4fvs52}IQd;sAJH>sA%YqUJpt+e0p6oV@7;sF@u#;~NG96- z>HJKO_p3GZ`FJ6jskAHg&j>Pt2JgY)&OaBVQ5HzMw+#tk;hiv?W+95;eO6fLHwEv9 zCENFPAtOkZ-eX!RByV6~f2sAZS}4dZ-B)*dkPN?6ExLa?s{+iWMRPSSiUv~Rrr&bk zVB>AwVfSLU!Zc|CHEz>`&n5vcvGLx%`IVvn0mj37C)LL`ocvz!7iH$ICxZ8mIo2oj z@T+$d7b}l3QoYYd+$&R}=k}IGKzE-F57XmKSWKsnic2?@|MvgkG`@ZPjKv}GxRccew07^OkVlP2)&NAUJNx7!kI+Y46rop@yu5(+}t1qYVAA;V=! zvh}fxE5Y8fWkS3kqCsYGE!V^p_Vm_;;m9`*;nSoHYTV&_!8iCdu>1d@m;+}%Mlv4W zc~l>PIQc!^^)jP^j|f-|1q9d1;N!iy;K;+YtY&!mIe5%S82{}p!fJ{6t7q>q{{?Bf z^!f1eQd-;f=uh^KzqBEd=k1yC+xB;$2Z?zhb4{UeF!t z({nT`6j&^-T5;($8Mb(IN}}L$C73oYV4e3c3Tz4r&T~=1##=FS)v*eRY0^e&oTA?T z$}Lma)qB-S1IvL4#_Ru4A38YsX+`F7c5)Mejdw-UHX=UW-?-Ec86slyrc2Z{2C%T+rWngTNURP4OD0 zuR$B>^pXBqQu19q#Dcd_9kq+f9+Pf zlhZpz>ZHag0x{pAbJ%#VO!;}qeHY{5{hR7T87IGIXKwKgL?PE(aMk;@X5r&4lAS)1 zj^I62TK&Vg2EYH0U6AtN-j@eVk2ir%AFaG~)%}#l@t$cDF>kV9JiLpjK7Qilw~M6X z48ei`a{uM_BpDxXoAu8Pq55X{r8DqWSckvDRdWAwrtkkhiPGmIJ)$do{om~^ z(KL8}fccYAynmg$A%cas(>96ZE(GtLk5mdNco*-Jua8FXp6ub@-B!F0#Od8X)My?8 zwh$*yiGC!*S3P3q4TaqRz*_F9d2%GM-88?N`y4jj*`xMLr}zFK*-_)-^lw)8z>#=|>@>ca~szl+N+J>p>{0^!3MOTNV6rS{dmX4p;dYu`TEdd$xS z9h?yK8c3(3<(VFDx_xxjny&aey%j}+_fW`bNfd93?E%7Ac)t$xAA5`7z4i@v4F&JQ zjI>Ng1aG#ESH{(5zCh|nIca}p2uP2UD7ZI-oZfn-aVV7KCg@Y@lP=DU1_@FD`g3pW zFn=vsW#bR|Eq{^{sd4MBsGokk6TAQ49HAS|eU0((&Zhb>!^!W&*s;lX5E01iw8<27 z!^b;j`SAtXA8BU%2$VJvD1!eb3FMhid33fkIoY;RB8*k2K zCUpdtNfH`onC{7?_8S{-K0Z?KwL-?j8}-41lb@)~l-o5^L2xj&crNEFKHhrP`72xz zydy^LuJ)+IpJFGpG;A-s_mJryv9Waekf=k3c7OW+R5lvCzqEC&M)B^=Xjp)Sx1a9I zVSfZ~|IFp9D0nYiqw~!k!8=3b>ek^>f57=-Vj|Tp7~I~>u|JqhhNnWe{Cv5*3|QpC z9Li~tfVblNrtAr9yfrU`MwVZlB=J$>iVtLdDprkQ%1x^AR`P^4jCi z2I*8*8oWpIxe(SMHmZl z%-W~O^mr4#)9E9t*;46G|DVc2gZGH<=P?v-?jFziSa?G#ec4YSc*}~dx2NC@F9_@n zL-5vkowGz&&L8BJ+>rm)7Yru(1~*HMlHuIEb^2u+%7KsZSd7oADB%CRrjCho%Nitte_o zYtXTtrE*v`s3Jgic6PSJ;60~h>k6a>hHCAmJ-2@uFo?D*3+0iQCqX$@9|!H)B;y4=dl^)FC~Q*PmtlDwDrNqql$s?yk%vnT+tvM@~`H0 z#>V@n&ET%Ypb1hMHSUXy?n?JX*!_R_fp}h)6vo4Qis}O|ze4+*GM`ao2k9=)BNH3& z@lLx@P<0H!d*|Ye;A$BHULi{j13UoVS= zcW!|w0DM1it$30Y1X>1fwci>i!;@xBJeTq> z12fZw{wK<#!4gBxHh&fD{@>S~ytL`T1ZgofZf@slVe5Eoytn9EY5IjS9^T$mA9(pG zM10=mSVRQ7vh()~DB2Bu?!^ro++o$HzZ{QuaE^!a$MHg9GZ zGJ-^^Hzy6=-;erlMDf-uII;)}?>4hM3l#+K!{x$L6ufnAe`VJ}8l=_Z21SwE0>JUv zDAR=vLEw?cogFpb$uPUock!s^E1>TD)k`7gqk$Z0Yo5+!Y`pi&Uz_}lEKV$@#$8$@ zQ+2Ex8}9_q?)E#o84vGpst>&Uj`**R~cyoFbuE;YD04gcGS}7etfM4fTN!2$p{N<#=f_I}OptZekb$WOd$WrN9`eYe4 z-f^p;8kNKv@>4+A4~NSi<93kQ$uO(k3=AG{CDy#0erms z-?~_^BY1BcnBKm=ijKvJlVRWCtIWUupKzK^A0h29<@OeCq*)nYts@A06L=@^RG>+q zTA)NAS0G&=ULZ)oU0|ocMge_+l>&#*YcO~=kaIoALb9^_u{wb zH|JO9m*W@X=j5B_8{vD!*TGlMcayJx?=)W$UnHL|pA(-Y-&#IxJ_SBWK3?8mykB_- zdAoTVcyIGw<~_@Ml>0h&KKDuPMD7S~Z*E6!3vMHBP3~pf65QNevs_=e2Dm!89&lB1 z6>(*8rEo=a`Ej{$ZRaxKTE(@TONxu1i@^Df^Bw0?&L+-k&JxaC&UDUr&LB>A&Yhea zIrTYLaxUT&;$-8PU}M*dW#) zte;q4u(q+*@y7B7@VfF^@vi69<5lLB<`v{+;Th){;(5l?%u~a2jpsbiah`)bAv~Tu zwmfD$Bpy|s#XKTB5cd!6PuwrK+qmoa4Op+U=Cht;O=OK=^=5TswO}=3)nr}9D#6Ol zGRyLXWq_rVw26~4oCy^aV&|6eFz61TxAgUZnLUurJP-P$e zA`u!um7QrqEc6;xwhF5%+SoP%o-1GHoTGr>NTEu|)#vL6y1krrS_Asy55k8bMvC+SJv@ z26dupd8%DCpWj)u>v@lI;#vp-TCQ&jsi4T=hLwt;i>MMh+O`|YLlx1r*BH8hDnZqt zV(2`o_@}iVLFZ7#*Y+U+%0(6L**n{y98~dm-;##TqKaFWMH9+K6&DBlYbXm<9R2H8 zL1$0}oi{-17uFg(|jn4eHQIRIw5j%b`qE&3iXl31y&)P-%D&Izd(PzvFI; zLB~<`%W6#*bPQE<3opKa(or?@p@RoXL)CP3!e!_vs(zl`$PT5V>W6JTKa_$h%6vPN zj4I0XB$R|I%4`mF1XYyg7fM7GrB{FwP(|6b2OUNgWs?(h2vw9lA<#ioQI^o51E`{` zI70ELqP+VD#i5GwsuUE9D$1KBPzaf~y5CcYV;-vF&u@WUa$2G=r-B@jdm>G^!%jmo0#PqAFZO$QAm5s?g7^DbN(ELaIB? zLX)TpK6qj~G=ZuhYb|kT994mfbXcM9sPZSrlAv#>^6Pu>1R6utzN3#cp|7a&-T7n! zBBRP@W!Y=!3suQeZn%bgP(`^A81hCH<^EJ?FRCclO+sF%qTJ30?Lk%Ro^mV56ICq+ zhb$luR6Q0uBM!Nv>d~7R7sw4&O$B9NAy-s2hHE=RyHVA!A=w{tLDfT132w+4Rrd## zrXVL&)t8s7gLa|nUgDY_$Pra_TicW&2UNj}jn6>#sJcsjG78zDs;0hu9I{2#oveZ` z$Ocu_wtUvmPE=JbK2;4_qw2P}-5baXRh3VQ;-DR~yO)udk&^A=vFg(=& zS)%Ityf2y1R#cVs6t0FWP*s}m4BCXM;_I8sppB?1N^R4CHlV6-U0DIN9#sVreZ7z=s`9^@e}YU%2fROLKrKLZ({>g;jn0}wz}wnKtC zL_$@TN=F5>234o0POC%us5;d$)D5jh)yeGLmmxh=WxBg>gLF}qp~w3JT7{|;karfO zgQ{bFmm48%RHa`?ISOf^Ds5lAJ*0`MqZP)} zkA5dTrN)^mC-Iu)Z^Vr6)y)&GSt!A9>;LajA2|8dTud)@Od^8gUB_Pxp2VMn93J1e ziUn?kAJnJbt1rgi|4&%M`sHhG1=CNl)9d5uhP>b>*Z!;^3DDq88K$Fn@8cLyz{2~z z+s2_v1aJAxhG!^vpOn^6kwNf2eBttEh429I?(z2uUt@nzUzB*D^CuZTnQltTK7SE( zZxBw~y(R{Ha%n#u7LSd0j`Pnso5Am-VQSnK%_`e(1K4=GH6IXDWMe$Mv#CB@aq>IB z@=f`dnGjIQd3M?K5I)`^4%)AerMAK%{BLylz44E?{C4z;BF{Eurr$w2NvDq^t;F)w zgg>vh@YCQ;={r%p8>Mf^W8uBz$${A>1n)I{+1bWrx#kQ@N|0tgy! zzxxAwVKG@Eg162Gcai$`d{B2V;`turcuRPHc{2AIY`hmmx;Z}58z-T0L1KI*3yIjf zx6Gn@TF;RgZ-G>X>SGg5eja?XGBc4xz<=*kNb&*t@m6-zbt0ML@7~(AUHIhPOcAEX zdpDgvDhdN@Z=U>9z4>VHrc9)ucz-WCx(o~NdY5|!&k?*$7rES|;B7x}uh$&Gn>3dh zLd**QP7D0h>K+7uHznmCjDL{f&PgFTwcnROR=AjZp9*rk<*MqgYN_p*gAJC(iY=;{ z=DxWdjR`4zU^36R zJD2q)!Rb65x3?Y~sEJX&#Qf*~9ir0*(WYqO-`!ihGAaKcFBEN5n3`+&=H9D+R2yTDBqb8RW z4UV&D2P$93##>eS&alhNandnr+^;)#q}wiF<1JqOxxKWG@$gom`oPOC?CXc7?m z{$KRJYLEhDZ3L}Bror5*ST*RL(KF&^qz3K!X5mPwK{_=9OWcqeWalQ4%rZX!+|lk$ zeQoUZN-VtRdv~iiB6$1l%XFjQ zy?^OK{f!9TuUY*Z9TfwB&4hq{)%0F)!DNJgW)?Z#vT(UpwMI5b)=Cq;wJiqZSbJ>xhg1|av7pfmHo|4-1P&&Rv-HX~YpE=W%mroo%CdX3_3 z0++17!rRmA{ib~g-qkx|d?Gn4GOy$_})4cfoKjF;LPE8LXrtkj=S#NGA3@=XntN^+PkeRtz9NEtmBXv&0;1Kn_|7abLfYzEI;D zO;$b%R>q#ay)$@a7gQigVdezG{^R?B-0O0I_UJ_l=g_%;>@4H36TbG%Kjo0Z+=~KB`mzxB#DI{NAP~} zcrKQLx6ALSni&M|q33rRm+V6N|LHeNbQS!-Dw&aCEd=jMjmEk?`WJxMRPR#x=h2|N zK56>`FKoOcL%gmhlD?Blsd3+Ytdt}ivGGnW%-+|a!+3Z{P<k>V;w`Pf69=N@X>G3Ae>mwaFDk9bU-}Qecm;pfgf64!< zK?;-|mS_!ndYGV%RfFOlw#k2=DKYSH{Gd;%L6LW>?W&OxPu){N%;E^kdV9n>@&1y|C;278Sd%-@~bBd1|^|d3jzmSelKh|PA6 zHlpDD{y_WY3IuO&ZKBSeCV#;9YvKDNi(J8AVn#DJf_IdQR#<*kDwrKSW*!+A1Dd{$ z8gg#Neq}D}%9WlD8#1Ym8s~9=w^7|38}GPbpQ6y;j5o!8n(8AKC%+Tbi(*vAiNKO= z+_P*IKHjA#gfFc?@HSl%eLk`rA8*3O(I)wiub3Whx_!uN{mMdKu|ul21P$JlJ@6>r zTA5iISa=s654tRl;Jx0jZ#@NXcnh0p34-^aw@=ck9)Ixhz*mbq4sO8vjb~T&FEVVy ze!1Rg?JSvEGPgNu@5jdb;I(a&Mc)_? z@B36A2XOM+B)?eScLfoA8!`RZBZ7~&+#PSDuglxvgbmmH?Hcj7x9s6{DYE^&i|PA+ zSvq~3em#JDRw1=x7UuZp$V&VbunJgGk7aPkX$Vc%ZoE(nU3DCwsQ(~q~*wo#QMMflTO zldmE_?73jd^mt#V(??>Bx#Ya`KmETL4c?Tulu*3SHX5j5;T@E;uWB`dH|y$Ilc4O=&9*DQqro=U4H}BS zv9GH*bguHKn9RaHb9aP8{&O-YClo~Wsv^!k{IYBB^QO*9Ctv@Ka@I>vw zd`Gb4!S0j8NP{FMV5i|eq72L$#*~km#R5%kl_TP-OfmahM_Jj&tYM!?E2(km3G#A= z_psv|rdR6^vd)JY?ZdXC`nZRapHJcg?@S{haKy(-#O@w`4XPd$k7@mZY>2Jellj+`;sC6Ex`a!SR0jcF)y6Bglm` zcvIe_NAaE;%FxBa+xOHxkGlxor7HwAD0n*v$Gv}#j3Ce1tc!Sa!XI!emS6w<(g|cu zaZR)#cz2#nJEXZV2w1DlRvuG`1?{GWhrD-Sj|fNdNyOU=M@bFTIQ`zQjo&%3{~VT% zt$%U1pYiY>rutZflb>RLt^2+TB2Zk`D*XH`KHhRxiZ|yrwZS7ZuLpQ)@f)O+Q{|Ik zPnrMq7R{6N`4HC9$xr%w{=XCr-jt&uP`pEluB)){HX}SBw;_0kaOh}J@Q$-iKU;&~ zeV%k>p>>r%5Lz>`-;mt}Y@E?4D@E|$-;%nns4EJT^DgmhQi%m~C#;sML}M>_ny`t8 zMa+znCa7^g6E%(2YhdG@tGz@gt&#EYHm3T>!pYA^P?>kxPa@Dv*4%p}1s`weWoz!r zo3+6az15qJnbOf9@pq_m%xh=<21$@kAKA@vlm-bIdoQ5Dn{w6(iuZ=|YC2eW2l5+z z7(noLI>Nh(7H^gxOV9V-K;GJl`+lTT(gpBz9rr(k;QeYs>~})b0r2Z1khc|#1z{V% zec5{k8}Hw%I%B%ujFSAQaRv}^@eczDlJeJJAOr}U89@1j2ue0sun z@zZX6yfy6OU%orr2J`m7LoG|1aL3-U-8_OEL^MvVjc z643Hd6U=zK1>HO{{EXNC4^n+>$I0);o-+0yJ4At4rI}l$<}9X9lqIXVR2PnvHn_Lq zL`L>{{8#J*@AgA1)4EJQ#qLX|kG-+Erv#99kPy6=(BMruz6`~C>uyG$PX@dzpL4L$_lWag|+ zEO@ecm0H)7A?B~~P5)b?0QC=~7HZt>=Py3j60rM!Rf)Gtmh~~-BlZ>5haygX^=Yp} zeRD*C{N$$HHnRA5r`11k?n`ci6IOrz%I{6b2y)zEbzeX8uOJcV^&$O|e~0g%5#(YT zyea4Lp?JF`kFa9leQVbPT{i@8(LOhI3f^CA%eNjt@a{L%sEcX!gVlBN8noxE;WYwX z^>+}wi)RvSUbXKBXZQMW%RGz)+xD<`9+oi1#QU1eFS|y8kEG4ixQW!q?xqshc=x`4 z%_&vIcz9o-`sl#PZ$nf7OZP`npf?fQsY}KmL0UKmD?u+>;i7Xoz0+y!n4cqB?Vl~( z(fnrdQ>L%p59#zF#-E=vP@hYw-m)}!Qx2F!@wWASz=DPM%@6T#2!eOSeXc*Vx4YQ< z1$H5LH(5dVKm726e`r0e)X%bk)tqySo+5bLed_5mTTDzL3Xwc)y|g(89@YZm8QY;x`e9R8QU@eZ|Ln z3l;Ck^8>r*`QvYIDLWH9Gn7%s^myme=_Bfu%wfWTKZ_HKXz-?-n2O@fqJC^17T(F? zjarEa-Us%E|5~31n+0ODqEDzoq_g1 zZ@8dOEU@GX)%&iCJ(ezJY3#MX_K9RhjT^nM8L;dkHs0y32Djs-8E@=;iRvQ>C%-Nu zzeitVi9q@Dp2)CQ_;|a>PAnHis&~d@tlscr{QjRn+`N4t#)9ele|mig-R#_HedXW& zAANc=^jG8&t4LFWC}&2aHE3S+241WhG~ec+$GhnggG6^FGs*~Z#Nb1VB~pXNAG`S3 zuJeOgYSp#(%5H&^J}&=}IY$QHQli8-;!cB5Vz$$hRk2{1^jn3_mQ|RK*zrqcnQ!+F zl9o{8nx$GYc1&W|EVjMZa=fx6VMhC`$EZGjd;RD9#D7aAoZTV{IIe7BDLakdAX)hG z##ga)z+5pam&M=0UqSLa%ocRNcM;P+Vz(vI=VPAL{4Tb?`~MYa@TMGsj^b_hQGy2x zZx7bAWm5>=L(#8HD0r_;yz$c)!COkOCaq+vA8ZsjeK+x?1swON&7Suc8Fci{jaq!q z1eM%u7fV*gf^|-<$){LXW8!TfF439j_?Bcyjl18IU*9%|jrZz_qBTCd84vF@R3BP6 z`Q-+0xU}TBD7ZCvUO4tBKHl$-ot?@<@Ls5@y!i7PI{N>f7xZjegNgSZ-`OsU9q&ke)VO;dH4YCs zu}6^Lj;pY)I^*H(LG_`Fli!0+SN5N=5Cu*HU&x1|@$uGkk=^q3T02~v#k+VxCqCX0 z)`w3#OwM5X>b=v3J|Akwg&o1)4bsbK@TOc-f#Q9(^#&&v-odX2YNQant3pqbDAhYR zs63$t!Q0f=^G=b!AFL4YnP*sbJN!X+v0Dd%H|rq(Ou}F~IPPs;_8G(i76(7x)#m^v z-cm&bwjs;+q-p!VajsCXK&&`6-nEd}MR69!!&{Q-;}%YSp~J$jE}a$y@3{?zzxd$e zUD;%Rz7WAX>4A{M=Fxi0&+(tZTF&a%HWAv)-yof%(+7KbvE1M4y_5!T%DpQn-frCo zIk50P(s@fu1;Km%jwn4^yvw)WQi<~QgD-6JI;pT}J8Uc5|5O_3|K(>xGWOM_fMY)w zJkx+;LI0SI`Qce?yr)9@9JWQiCq1FYZ8+v<(ES2?aI*fJ?z|_)jMx89P<&}AMX{@9yv`vWngxSjd&uA=&R4HLT8jQly)Q?{5 zCw-*GT@+|eIPnd;2A#=1^jKPa0nBJ0HK6)9g_ED_qwDj05=B7yy~hH$j6=AGL;u zs5?lNY4E1p4T$1B6#rTP3-8W{8;Y+WcwZiobf(~KyI1Y-V+8LJV;|vIEkAfwj>>4c zj0wy>+*0)x!F$1%YjuiZ=fSvYRrpP>SWw%t|H|yB8YbSuDFbSQ?_QCrsc~xuvX7kp zijB8M<(IQeZm-W6s&C;}qj(xCOTG- zKw!nv*G5d={}T-9^Ktu4LAK4`<1LkF@TOdLiQ+wbt%M&7@6R_sMO9q5O)=f6KIbajecT0?j1xgPR4u#ok zV&bhV$JT0dVt}MTjpNgLISc;7;KXiTLyZ^%;=P>e!wM(AWx({x=qpi>Z)Mr5T91#n zOqfk&2WJNyb?o@rvfuc4`)QkXTjyM6`s&@ViasBeRV$B-{CzobISt;F+gnk*`Aj1C zu<*8;kU8)K!P`Q5gCzy;&)MzQ^$@&=c6*W=kg+#mhv4V_J~Ozf_v?BgWbLiobDl$? z0CG6-j12eemRJy()VAVYmNq8dWzkps`l8;D!l`l2Z|6PT`5*9RtNT);)X8|$Ti2*Q ze#8Gcza2|77rqq`1=81Ntv$=}@zz`%_ zuj%tK0B?Vn_3!@we}4T8{SDIpYtYmn%Kg=74dP5Uk-(}!Ifp!_mmxLCV5x5zr3QWE zd-Nm>IfHaGsdcyK3c#}VuzsN@LhL)|YS-T8rkjk?Jtk~uOet!SAvQuQx zo=g_!zf%aT9&B!^&yE3uJ9wlkknJ2;fBFx_O8oWWJ4r97aW@q^hCBbm25He`|0#u~ zjEDCFst+Pgek^w)Rpti@gGFWbZ<`O|<1Hq$W%DWo@4B8x?5AYu=>J#7_C>JoV0yd> zDs=i_n@FPe|7tXN%LO`hpm>|Fcp{30x3y6WY=+={&O|knf_G5y`r-xz?|B|$-^U^@Y!D!w0N@U=^HFes=1e5zCKR7GBpe($6*I=y27Cf=e7DLRV}c9ULH ztl+Wp^c3A3X ztw?EOBj)FbmXFw+riJg;^fEo(v1jS?Ve#u$__MQrs<$c)-b>6p?x1+za=9deh4+!{ z+&#MxylbmE6DfFC6+F5%hu|&p(x=X0jUOyLWNMiup$_+5f8zHU!F&CL@)cW^OCZd{ z^2;aPSirq3RP$-TV$5HQ1J_Y^k({R_4r<&MX}%d3Hf+3a?gP7gl^G9jTdI$8ocv-> z2aZ>SHNRehj-}C>_hc{z?Mf(3$G&M;1iO&VJ1|`m_NMqF?UG061 zO+S$aX~8;{l}HV0vbne92=a)XcwBr!Y{fp9wOy!h+}0dCuQ(j({gn*jh?7P+(WPKk zwGsYg9|I~r3kB&-E{3r_9Jf^Y5l-kfsgfG^);*2meHiv5cGb(M43!MVn}c+w`q0A3 z@6smgy3Id`U{=iH>Q1R&n6(-Gygn1+BA}2CSo>82OC$>&k63frK;yhYJv*H?9=xQizH$?RTaPnKWHr(dWW+C7X`$pTa;p6?3UF($Ah7MTCUnS{{ zI{p-UV$vsN?#Uje$2-%OJ|BAD))0;y_%njkronspp5`$W?{yuI7hvJ-94~$O3xapO z@x0d*yvcI_czR`)_2BsBr3f$3O{)x_+-om^%iz ze5_mbvQ7vSZ&7>qpF>ygliaCslX`=Cj{?x`CTJ59sA(uli@rzs|qHX;b#OI0A4g7Y)OlAPw))jNFs68$AB8L$68O!X0jlV3BbMtX0(Ft}fRlu!GA zu=ci-&(+Zg#y{Son?)(2czP$(SMSxV^!fNjBB-p5&iMEKzyJFWixD-_|F5B`LF)G- ztI!%Ww@_9Ns|L9*>gV)CMvw}PqkAa*|FzcCPlHGe+P+_))G5#x-mN{N&+fAWJpW}m zxN4XTI5$Py{mgpvY-6U-@8r|^ARi9ss1>6xS%$N8rPlpAfdTtJ;3@1 zqbBWnrGGMB4HBjLh``BjWxsEB5>W`eKQv+#a0b6Y61m{&5t!Bi4|JW~vEefQ`ahvw zHQy`6nCWW}A(u`c-~3dy|BfK_Y4BD%_01Z^d#3EiVl2ERSQQ-iBY4l6T-rv#`?3vh zd>w-Kk+1L)%`#tjz=SRTbm%s)^7IkSho8vc%({>_yspvk z??;MqU1zkDYCloqwDped?M=kSTm9!uwhaT~{f_EG1t-7D`4fu6&xxS$P1tRd7<{}X z)2oYjBzM4H7OhYS(!rnJidC|$Tc~iI>G7`PqR+>&>w@<0Oa6=?SJU9F>bUtGig!q5 zwJa9i+V0;Zb|~KLI};XR;hn(arJjf2-Mes|A}!wK_dl!!8nF0mZ!ta?3r5P5s+{DylU{p%Dl@y<$7wQ=GtAmvfxdd?gbbsocR zkfy&xI+Sfrza-ouo#F zUtBIDk*RS4{?*YHsn~dD<$WAoo+F9*|6z^U|F?f`PxWyMCqLh;%Y_>cpu&}X&KgnfA%)PYKZ6Tp%+Y#H$j3?YHgLA}wg5=j+i^e$`a7L^>f_>xE z4W7c)9lIFs5z9^WQHqma|C%h~fXA6DaUdHXJMK*o%$#7o)9;H=P*|?^vpjPdNFV6bu(1PZtDo*BoQC$@q`h zqSr(z&GZgfwkDakViv#uC)f#O$%`yw`u;z5h&~@~Gj9n8OaJu$1~hnU+vldBc#r7a zmdC=|z-r;b6$sw`yanYHyt{v=SVtguN0a>9_67RDS3tTxSBxz<7WV#({yQ>w94sQ< z$XNmGYV-L?t7Ac^Eo88JZZ#&}0;9Zv0;%=2Xk7Sbsj7S>Y`lrDLJ!_|WjwrzR3E%J z`8k&EHh%U}5X9~57fS5M$Ggz}s6xWo4%l1fR$y}lKHdg_XT4X*9AtXD2|wub@rCu} zn@@Rv@CGz^YsvrD@fJHm4ll#Po8`q8MMDJd?@}wzQ1B+$es1MK@Lsi-!`O+>7oNCs zOVJ=>C*XRn6f*vv47mBY`^|RU1k*Of3%*y!f{*t;%cs=W9C7mN^2r-F`$Yt923;|QP55{(SA^kk1aDAj z%JtM5zyBxjZjsWetY`kg$wzbgd|0K%QQzJo(crByWoVC9?|`!wOR?}aypWf(9l=}6 zRyK};w;<{6`)OqM*0Hm6CS#2+ym7ker*7ct@5uG_NbVQ5#Q^R}G(QDRV6+7qgR)S$;=E0x5NGe{zH zVmVxUyx{i#!`_{TQ?XcJ7;3_w(HAS!?ZG z3O03EYY-!s-hF9k7If-mq*2|h2SNspWAm;tKvYG*WN}mju?M}73|mk$e1^rxIpqfa zS?Ndq%+i5pZdp77T!`QAfAnYeAAGY{xH@`K^7E|Tum~QqfX%z7lxXtN=l_mPtqYYe zdZDIz8LrL2==UIrN(~*bri&x{9>n5CTpc%65(Cbsu6@LgCIN4y2(eZ??@Y`~Q6%0< zil%yZVBXHWw3e&9r##D4w!yq_*5u}jaCt)qCf(=h$E?8?)qpR}&u4+E@zsqkl=XnG zUSu0EiUyiDb`?a+t0QvUGE<|dZ8V6*$5m_zPyC{S%$rLtWyfMC>G9^q)v*~RKb{7j zO-_@{Kv=lu$I3o#)=vfv4hkdSN-w~pR+c&5o@{W9}b@7hDQ!G9XT1fX3`-VIq9ZEQ9w5gT! zcpt;np@ov4Y@^-WaTykXHJiY)B%t%|6AO$#4|nfC@3-&sN{Bc?T4pT$dFvS2^Ty~h z5m!e-p04meS8opx@KzA?dWPp+kthk{6A|VBW`^E>llE z@P?B2xW;tp+JKVXi{?Yavq0=c>2g$gEl868d292JXfXZQqqDzL6_K|~lnm`%%RcNB zF0Sm!8#|E!WZv|A(iu&On^5@-6Tpd%qOdFcu7o@{`Z*>CRa?^}|A5I*I)!Ku^TSRfpVh-l5 z?UYQh%6q=_{i`i7?`O8JTi$v4K+hk0w-0LB0B@$d)Q?Bt*IR_krSMVJg56dcQXl7H zz|n+;2A8)gh`b~1eKpoQc4NbEai5oWx>58X^UmD-=8`7~UcHUR)sc>p->?1NYP%Cz zK-I&c$$2q!-Yc)Wa#rB8H`%?X$qUD!5pmh3NYC78V>s*bPj;^pdb|IYva z!I=2J7Yg?vU4kBT;QEoj15%U;jSNx`T8_}(BMbMS;;f1t;&2Z#+e-cQDSV0Dq3%=^ z?N1MgZZ2Zpsl)>83_GK$(lHAr+Ki_Le%%M-{cm>d_!$ifM>uuEHtQhvpw`cu?reE6 zip9r;_hl9O1?U2#9~Auyzsu?vZp810^#A+6{qNgwb%heNl;)^ z(DIsg5f$_*>xIgjInAV{o*@2Q@ZV?eQK2WIJDSOUi8Udz4mOjS$-5`k=6@Xm-s(Y5 ztnfQXdY?WiB;Ge_U$^PPyy^V0zgL%7w^}voQJ6Q!;*%T-Jx|Ey%B{}jeU>1toBn)Z z7yN>B6XCr9ruV@a)v4W2u+gBQqf3fE^B^Ke+Hv_%isCm|d|c9$M?@wCGVgs1^DAE8 zNN)#8hpR&ZCBGw!BBjh3%z(MPRr%5)`Vw2=`#{16=Ivwi`S<8D5j)7>{q!NPo{&9n z43Tx@?Ei2E{PPB>Lj=6l4hZYwdEXGaybp=@b8EREN0@h@dg-fG-pR9h?w?`a-l^wQ zOiMkXP-Cv!7OySA@(n4I?>)1iB;8+jdszceS2qnCycP}GjL$r#JgAMx+rSJP!Fu{N z_6aU-t7U`f!X+KVE|v5p#O>Ng(&KG}t0Ms=zf{G}iBHrlpj>8!Z}T)d?`{f6+qt3_ zl6b_}>rTMA+nB~GZUEgIco#bK?2^Y9Fl)O-a_SSpd=FSxgf`# zp)l`PN5kvacz04h_zCk?`yE$gy4ee&`j!9V*$pf3e4I5?v40j6k4tr>Q#1hQgHjtT zOQS&@d%To8w-zGryR;0P9`3KO^|(0t&2INtHIaFTx4b@6Ge&y6YjJgiqU2|jbST$P zodsm@7Wd_ip!2o~%Q@x?^WIY{bNKBz5jQ7#h`rk9C`$IcF~ruHY5Fg)__)!S%Rc;)$h?nz+{x5A zN_xD-adkwX>c!t!`aFLdVZ?fSt|^u0Gm6|*w(j+*>8 zCy~U};dJ&{ju-rT3r2YOSVwUc!?>MJjmDWe0sivezew#T0MGwM1U=|bPA+D(2W@{R z>_)9*gF)&+HDaGncK#?=2@lhlSe^fO3343xWU)`>X^(ztx|KV$zt#TWuTvI4nMrr} z1QxyriI?WS(#|Hp?Yd1+@>~q~QKGeRE1ePI5__L9EnY!y0{a~oXTx*L?bri-#2utS zQWtf-6gT4c```MpH{$9*%P;tvd3@_PW>9faLe|#`eg1#wQ0R6U+Y9a5x3Zyf1N!+t zX2)X|;lM8P??HUT)iHVMdL1?V86+@oLjv9hU7!CwAU)IAB9FxT8Eu#R7|c6EoxgFF zx3Y(Jv;usKT{=_G>!3^SP>E61{r5o@V15L%PP};*>}Sl$*SG=!hT@!(8J8Fk+jwj= zPS+5T1jp`1&BiFlfc|RN zY4MB5yw4S`8)bO^7K@KF+O9#p{0^D7JO&zJVlZz2289oQWXSE02Hv-Pv^QQhMqFaEOpP@nsXk$SaB(rz zOMcH43=#jV%^fP5{p3%2JqTY1T7L1rmWx>+W}q`|$G^7@y$7{lj-%jI>xJxxPVGAw zh`xigVPoRU>b*twJ?H|Fb$ro{p~qfX+d-NU@HTKa_{;mb-kxB=YOr7 zTjjm|?3PhAn0MnF+c%HjxNzn~@+^1hYyw?TC_mQw`_7~C@6M= zuzdnw@1CIRo_D zTZROrYU!3QlRfVNBI_sMsEUUbA zFaPc>g?UFGuUU7E#~n&&+M%OSYyl({Uk&v)%!0vvdvuP3H-Q69PnR0sz6y{@-WabznMuH#lYh_uNqX}CCpmcjwOSN8BL*%|n0t|F#x@tQ zG}XT!du0|t8-Ba)wtfJ&uLCVVrObO0&)+kF@=c+0wTtLIX#Vbd&H44c5QC0s!Z9Nvc98aM z?#&6=2iCM=ZHcua;B96UIF09By<;;y67PFQp@WR@68px7Ic}AA;}93C z9?bjqa6esKwhPp!3-Jtobpi~Pi&uJzXTeYBBOxYq4?xY`P1kcRW5ARjtCVQH86s~B zzPZQ~k#pEjxVTqtHMW1wBJ<9OZ;N8$B|YBwI?(c~!5VQfIx>T)0L=vFDRkb|RKD!Y z8+)PCgH;Nk6nzKz@cf<-mZfg8=lzq&I$Z0&UTQhN#@mvBw<({*+NZay-o2HS^nL>p zZ|d63n|8pw)vdb?S9u#A*LbrZ=6%M*>)Ysi7bv$U&vZ1~5#0FjC~4^0EO;-JzFoS$ z1+;Dd{h-V_20Vmltt56J^X{bPP>Xyri*3clnHj!6N^=OAxA{s~gB1_y@y6GImfxWB z;PdCP); zxABUY0KR(*tlXkS;;qd1a##lDT{n}&x5_(5z+`SS%)9#wg-yJQD^&Z|w)fa)dk~jX z(Aify3-0v4JT>j!0y4{0Sa(Oo09pe<<+2P@#O`fPQ<%bVWd=)!i_0yL)zhLz=8Z8* zwSLP_dc5&r=sIXZ~n*EftFue$CXkp6J{WIiCc#HF*GXic|Fz@&(jVmAq zeRG284s6I|`!D$HEh6jq)Yrrqo&N9r|70-zV=(ai??BLlY@&yg@jd83ggP5i54s@G zbn6T}|8JymZ{7#@Acogz9OCdDq}|a~brSJT&|}djJ_X&Lpx*N1gT}M7;C4+DCi~Mv zKx@St_~CgpuoEl$qS$PK*n^I-=iPB$_=0u8#R*@{(taUj0+4>DNy(?bJ{2UrB{mvY z2U>mx5*<+-7ns2Mgw}4XCWQ)8o%nyh-`@I}d20_eZ~I`wi`VEqD0Yr&zL)mDVE&&W zu8zkKUca=swl*Ny6Y#dyN{Yqv7Gq~(MdJPL%8*bh^0+k(v7S)AwPYuhi_ zPFx(NV*I@S8)HP?$($0d!n;V1w+pTgwETYgdO8fTF$1R*&&^%?(Rru#?W{B(?SZTc zVq7_v(FY`t;ec-HZ1R7+W#&0?b;#Pq#kz&9@wOx2Z6zd|h36f%^)oXP@1BddF4V!i zx3@8vtnyyhNSFHn9*|zNYWMM(IYaCGVuNjC+(Aat%Se^;@caL*_=LIj9s-UZm!`MA zjs`U&Uo3u}I*i!8%kBrw?0>v~y@!j_=zREPFaw$QI+aNQNfP9ZuLCW=A-|5#pVOJa z(VLqpsl?EEhv%K23xs(mcrY-~lo4@*bk&d;3u6cQ&;K`xtYclHw(LLizbyf8i?4~Z zc;4sO%b1XOXVo%Vb;G>$Ed%wKZck+?s0+t3B7k{el(}!$i-b@aIOglwL zuY2R`U_{AJHbhYRI2|*%Z|q{K#evTIV*=eLBl=#b_oSA77&8$MNbAfTS3EjK{`0>s zadljD@PGKLa;H->?(U+moupFgZ#-rCVwwBQ2sZr9zg zc`J(x7FhFpjNzmpO>E%qaK@4j8sFRcsa zv6RXG#D%@~+&L?c%-dDSpNEeGFK^-Na6!p$PMsxc9Dcn;2qS;QA4+uI?bQO;-@#{Z z*=}`;H;~^fMAorHaYp4+eCEIB|M+2zl>ZLT|E>f*$SG)n2j7E4 zljS&(dXTE*gQGj(9<*?+aZ(EIL2;Zbp`-AC6tqCilGft@6|F?3txWoYmXWvC^|7-+ z{pZOilt&+f&I|6NShHyGG|zQi>M+Vi??Hi|mxI$)d!QZdKdaAvBw`2ogCmY1QHAV# z5av6Pb!1i0;ck$2A>i$(%6K2oTUVTRGZOCrH%(4in0GtdhtgHvKfP6gAH%#O*dlLU z;B|z?vc&}Dz8?X-d!9_%Wc6zWLmLdkhGGSQ9WA$hY97wz=JZ^dE!Mxv^ zzVuz?y?4v_+!dI2=k)KMKcS8g4|m*!_7^_j*noIcandaKmZT%o@bVETsZ0wP6^;Q0 zTgD?2m#h%G_cul>d;6MiSQA{_)VTZJE#}C)j|@06s_Y{@-rsR`_@d<3eo<;!Ns~D~s>maTUr%lJ`Fa7iORwn}9 zcH`hBo_FNE;*ChWPp94pa)NoAf<&oR-rrLx_a1?HyPNnHR=skB7(Oni*d}=c^SAmR znNQ7veQEPobx%D4cPaKep9+cwv4Mg;=605dyleN^pOEJIhE2f5br==oz9~UIoZxeN zRV*q^dc5&+wxE|Ja2i4Aa*3)KV2EVhrzs$bu=!oUfznUd{=1<^Zu;xK~jB> z6XeD)f_YKz1=3`HrTV1Kg6`%Q2PhODfi0PNa(X(^AZCQ)R7C;u<*jVSxwn;ZU$Kd} zxJ60B!V?FPdGi<~{Cc&U^myazK+CVdU*qz!C^I;FYp!mW1A6xs7F?{HhP$`iAsUy% z_lbBoQJYQ;v-F(od1Ew)tb>Y8Y4zhR|God8lm~xYZt(o?MbLvhLSoiFVrTUZ(vtlB zyhuH$;pA-5-EZY8hCzjUWZ)i@aoDCt816xG`yFeZY;u5v1|Ds?XdeK&jr*Q{^qmD( zNiMsqmRdn+oBK`Qj$R`B}dzxfSij3}kdgL^{5q_aKUom$B~!x}m327cK`9^NO9Bi@BDJ{{{2^ zERl758YsfOV#kw!xBI^9#`q;R<;l`kB;K>B)vr5X-mLKglhQEnhr=~d4lwT=2f_~^@7E-s9|K%+i;_Bf0_1$ROKexAd5b$=Rnkc~YHfU_)M&kYZ=YjsWFmHMg zTC&PJU&j9QRhaj2KfwrkSqEsQb6jn_%pV+v_=VX+XThkUdrY@uE651z$Uk!`8fcvH zh)fhj<~_3ixH@=^&2kIj6C`+Z;!eQZ zXK(l(a&&$w$kKwYEkcNpdTfoWyf z#MSUwpy<=|$bVxiaQ}IJL;aO#U?3Vc#CypGadT4r!TM&q=pxn(7YBT;9`1=k=B-%G zUKVOidc5!8>QF|>&vdEfL0mZ#2pHkHl~je!`*NcM(_xr5gGTi0>_6x?Ct|upw8S-@ zko|xZ+fG~^3H&M+*jsD!zZ(H>=aL=nc-|xOUR#iO$L&dBVT9*@|KDGCt@7@_oDaUh z-8&*swD3!k1N0}>mb2@gAGpuDG%9&)77V9$^+i5@46aTKA1(`s2D{~KmF{*UA5Q4p zJmxH!_5&-1ixcS$A6#KV<{g{gbYEVV^mre_)e(o1U$(b}ga6rZ@eo&sUlGJPa{Ax<|H)wbU%UU`kDv$nTJ(Lx z_n;$w+XRq$P{-&(?m>8oJvDwVVL#l1;=j9|Xoc@VTI`2nUVGU=>>VS|zC8~FpT5jJ zRI`}{{<)vj?*~5tqk-5v&Wp#ujxDb%Llqnlmsqy^^c~jPzp#S1xU8nhWfd(8#2uu| z%hz*HGfA%pG2!ZPMahp+g6oYK{D5>_&V0aWaY_|5JLQb0D!E>DL(ljwK5v&t??E@| zD5@B%Z#xSw#51p@IE41`3BEhisIW2MBXp30`@TP<=jlARo)%m z?XF!gZ;DV^y3S!csMIR6^fnCnE=al?~q!D;Oc(nkn*d;jdahv&VK z5!#N#`|-|*-e8z_ilpF=)vLFsC+s8pVczS{4NXm1*h5NNMXs8R2C;RyylTBP5 zm5$*D`S!1MZyy5QUeETu$MgR4E0Yh2cR{}N=aVq+D{KLGR(anV{}VU_^Db_{exG`4 z51lR^mn)tK0B^d%y?pmsApiNB$5eV7kk~;PAwe4h*z_vGe(@pmKDr<|tZTl4-Gqyi zrd(EtzlO{^`va4bM?C5A4#CxtgOVRVbj35*fd%A_oWCSZiOyT^HN#Rdd^pi`!`kzW z2>PeD1WcHIWC&6s`|iD$$U3HzRHWqV*Dh~)6Y%!DDg@zqGX^_sL*gw-BmL+S%-d-l zo8Kz$Waj4lpD^!PiNW_F)DDoV)bsUm*8+gKC{LY%_bkvnXqPj7pbb2ocAlsnKL%VN zzB`^v$X9Q>E2C}PZ!TkfaB*)o>^L8H8ToJ`x;~>sGm!Lnci`%XLCNpCk@Cc?KTKes zS;h~M|A2RAEjQL<3P{5$`n&2S{~zr&ZcL4-yHcuO9wduEHiDyC@6ypaa7(HC1pAV&fHLel=|kQKz+Wno0$M zBzD#Jv0AgBGOIySgQ5exxb|dgRD2Y`8e4UBHy|&u+8J-&Y zQ@ud`Z;&#cB(9F?13tz~$!kk&5CQKXzWr2q-q-xcg^+mvxjBAj0p|U{%)e}vw|;v< zSq;ovd52odUK1Or+px3LS0)Gy0y>U19hkRkpjFK6cF^r`+Bn-b3ecT=R48bU%==3p z)k44PA1o6t?%2G7q8T$XZ^|2f2JxJv$9o=E2U>m(jZ&SA%1of^h8iV<9XjvC8$3Rx zFmLHI{ueOE(JybsmMh2}9ULV4B{sHQMRIoR#!=2jS{K%TLo@ zJS)452~5tsxTR@~&O7I+aPBcoFXZt(MWo9IeFtgrL))i`SCQ=J|IqKm)v=Vt-MRIj z8>9mWc>BM2*oWuMT77O867Q!6w2gUT-Ya!4Hm>r1X;&rK0Q1%_@!gT7Y6}I-IcfJP z1%V$`aoa^rXTh#ZZUZZOda(Ki+~NwvLUZysI}z!+URk0^WY9Po(g?Pnt3y4;w72EtJ zrAy3$+84jrI8Jwh^Il(CwX7q-jb*pQIQT(oq#sfC{o;=`9TZS0F785W7MtOFE5scn zKh+PN5>L|WK{>cO(DHLx65QGA#sZ=m83dkJq4%JT&qNa`qI;m{7QLEWHAM8Fk`yOa zs>fvCgD^za@jLg;p(hP%1JY3f-r*bBT=2a4AG{Dn;%za1%IE~lTk>v$^eXS#uua8T zFz>A+@3}084@2XL&qr%jf`Ev)xFn6tEXb9$lQ^%`3CdCr>(gsRf?Xy{X=bg+OKb*^ zTAzM|0uscV# zuf;u(w|Cm{Y*lpLolG>U)@a+B;Iku zlht`J@8d^Q-^;!YRbx;nGT>? z=e)_E{^deU5d{v^5w0#kO&w0L!`%h4p+xCz4 zUE8|fgat&akNsjOK<8bom*C8EwFgQ$n0&`k`yt}0_IGupYi@e6O@r)tV~DKddI(Ma z)Qz?79ZJAE^j_~pJnxrQ;d_yIzvK(sdK>2b<#j{WD({c3r@1*`-n3uyrC7FGLHUtc zpVr9+0l9uz@0ZH6fa^wbV)dmC0InKeVDpFskF6!IvYR6Fekyw0C8G`lwc+B1Wn>kc zbCG#FO<7Ry0;I=#09S`2N`7I{DzVz>ETEv#p}{>9owt(->%32A52R4_vuQw}1(kQp zA^M#c4;GR=?}tRzaU-hR-1E#D?+^msAqnS9@w}bY4(>tX?X7em^)bx5d>^OQD(@zX zTIQSZ{I4^kXQr8A4f!gTmwuBB0zZE%O30|sf;TQAM-LlzfCRcCt`l5Qz-3c0m2D9+ zZ%L0YN%A%r$Q>8Ap}#~(v<#W|r(3qsizN7Z3w#|PQSyt)p1ar8!vZAN`$k?pfzCUk zQ%)!j=3SH$6YxP8oi}Fp(K;$0Rr23^6I;jL{VaK2|33f!cl9RaFW~tE%kMYspqwpztD!AqGaoEbl4y+CExwC zRzN%HEwT7IzMLOr$(99l_f}w$h?mWm+>3uftud3a*9u)ACO|4+Ac4A zdPx2~$eFl0EDtlBn*Qej>0<=EV>WI7gkNHhUm21@;(gy(RbdOvTZRAOD+QRh>5=Tl zR+#tg`cGRrT1}w)c?(_NHwS?{+6a4%ZL=WuTd4cThh4xsSR%0RUIf6_8=o+^hJ1O8 z_dexGMXiEOAw!wOE%ZBsK=(fJ-WmQ`VAvEC857zC z{FBBKs%s*^^-8OIO18+n8>jrL>nA9oGF+Sk2Y2R~CTqm*eYI*!%z-@8H-Ju>jgw&BS7=qn<^b{WZn~EQsM8DD4`Zy+*fIzbMuFgd21hz z{L*rY^myazK+CWDwcwtu;Vj_kXNuT_m*~88GbuQphxb5XGoRvaQ~;mD(nI9{F&>=a6<#=P}abt&6JzEk6ndMVG60SbztI{jtJsblwV~ zjnXe+-n*C&1i5b}qI<6kzpr3H{?GqosEDj%N9ydJf8YOy?{1|1_eASdDuNz#LSia- zwFm8h-~T5fY=c4SK|7_!vopWI0}{R7iW1y|bTUq*CBQu>V@y~skJAVeulstbJt+WS zZRC}AQO*Jl)6dP_7khw+=`H^>B)wBr7&;K z#D)A--bKFwM;gpKGsV4jlaCS9q2Fuws5bye(wq2iqnQQ$A#8{A^?Shf_8?S`3j46`8L z;k^HgKi$B@kk@G2*GM2itrnaA8<}@|Ox}wdUDS{iE{=m!+`~Q;nfJ=jxwIn-q_=~_ z*Rh0>-@Ra7(H^*ar=79Ydbk~(cm1nanD-WtT5Tv| z4AEa~8tzXC1ogXO73W!I!HMDo%fZTSz}a`^hToq^Fn-<0Kd2Fz_i`X@>p}=M^Z^&= zuB7OF`MVwB=ERu7`quAR(&N2^tHTf_zdur&=ok1o089OFbOAj&Z?Ro9_s_$J6LX!v zvredWBmP|Qo3e1t$GY^E()aQIOs;?5Mr0i?M$;u!n+sO&|BoTyecUG`2){YmJtnaq ziT4??H0{qY@Awnur&oEeo0UCY5A)7C+#T3^$ryS-b@oRSRS>vYmY>zcF$>CS8CU|G zx0@;S^4XhVR%UWKGd1Lbi<7_oB|an67V+2U@Ju`I#yisEZGfx8 z4kbV4s?P@%_p<_~9X@u+MDXUr@#f#ep<%ug{p~I1FO()o3e=PR*;{`eadq_M=jz-^ z`1kYw$fAwG^FJ*?4>~QvAdjE_$2XdQB4PAGilnA8DSP0XKPKuD7N40<|MvoIZCVK;il92K#C;iBT17Z(K%r98VJwkc|(g$1}@hJJ#`dD9k9Lox#e)`vDB%&{|clS|d zovG-7Zf+Aa5$i4?%CbEt{-Y2hzXRcmiPo*K?ow8iEc7n8ec`J=! z=Qrak*F`20U&>+nnM+xyS_ zzn*~i$tT~#@ZFnl!#oud@12Lr=!{|B=9}+ut@3W@TTcEB^A6o|F<`T-A>_v!d$8+* zKZs}%=wSac1NJE1Ir~Me7i1nkIT)=R2{uX4%5Et|=52dkxskbRJ;aHNyP9S{%XkZ! zcYlkUdDB7CsG4u~x)Y?e7jE z$B35yff?D)|FJ~YQCt%A>Bv7H+f>oS>;!hI#Mi zx%qA%JRn8e+-TN~HiW3}*sOF+`GXPjJ>>$6Gk|?+sBzEMULfSX6eN5IemL=Q9F?vQ zGVf~*e)r$HuZPNTar#sSqp3%bd0$+A+2Di{>G8(baRDX2cXlpsQyN*p7+b5Vm^nIc znKs&_iqsyc&ghekc{uvv#ETugRhP`}kUei|e&XtwnPA#2mb$h%p(fy+2ZaQ=KeSq8$Jf8iurY|C#|p z>MPu3(>-99@BP2AXz)pnc9VN6Tx~Nhu(wUnI0@WuH6m2IO}RqX^~%~3%Rs<8 zeHp8S=dCWjogRs|Q7LCh7tC7>vom6qw@O)PhzZR5`P7GHOUn5Zm}ELYTpxx9IX!k4Un=m;q8FAwPCg_kpEM$m-qMNWd$0jJA1~8)CQ3tMc5%y?+D5 zhl?v#@p`jq7jpMbd?v8m0=&v?aK0n+1*uVX7pev!G6`~jwHpgv)t zU-Ak%ZL^v9!3qpaHBQoHqx0?(01u`7d!UQK2O^x4(Jyad%y^sLW6j8(cPx>0SRbzx zPbmEN{eS;kGv|Nw--UY+8$k~`&v|hK--9;x05+r^bdF0#?I66ww(NROc>rEwQ!*1= zQx5M_+4M1%O~&ppbkJ+h%^n61(0K5A7tP%nAjkZ4qMD)~yztDmGf)o)weNNm8aE*K zpjUTvHe6t%hp@P~=3d2jHRH%T$mu=PirqG(*MnZ*>X<^w&p)SsD58c1*j6j~^6#Wp zLHiv(xpYFLAiWbhSFRky>xDl5w=teIFT7hx_C4q)J#lrc*O-zwxwy82WF_F8J-(QS z=goJVg%yeSq_=dWJ0CqD0;leBz4#WEb7k>2;7?i zJ!OqHWg~sSK&cjUN;w>y|9yPYE)bcwqF(G6dmSB=kBi$8&l298h0L3Zt+&g?iu8CZ z;Od}6$#4DnB17h%EWpm|dRgrjbl&W9F)e*C??cWpG4!oOod0tVIq6N4|1EYHP9p2* ztZBr}|11Q&v+7>2eZ1xB2~zX1VP+)WIZ+<-Au#Vf)z|n}c?bNtbFmrbou9weYE!5g zq-!v3`>DqhY%Txkqy)_X(eUEQ;D$cHmSMkltT!ASVEDQeGmOl8`la>OSFUuBHZD#j zL2cZl3Yj;?m}*qef%JG!;p+Hf^#7mV0%WB<0I>k~&1LB`E9g7O3+dYR_02(uv=!Kj-OEDb| zcC-11G~Pnytr7Xlzmk;>62-+)T(Yjb5s1t?i-XyZ)r0hSAHda-iIQJV<1~#3Ju6_0 zw)B5Ah0fc$M$rFJb{E9?z;IlC2RiRkj{>EO9_0W2KQi8#I+!#{JR}CKT^8w-gx5C1n zz-Mnl%^P0@^#Nzf`_yNKBfyd=!sua`Bh@S#SRy;f~;$w<0VGXd2?frcWuwvcs$|GAo?YCOvdYZYTo~X0g1>u1mn6>Jm=2o}0L z10-_4b#|TU2U;ngZM~Mlf#cq9RwhBnyfbxq%Fg^`fZTC$(*;LTbWS1j=Dj;Qjrl`* zywBn4K+BKY^L=1M7%RB4gF3=q51scT!}PS@Z#toy(PP8eJJ27o`_8JF%y&+l><6UV zMApG$+p;p4v37#QLBKn&-0TdV_x8KJ97w!BPOVVTz&ps}CSzu+ys1ZzGMdA@A5Kw^ z_Z3+}IS%qKeEHmfspq;(|EuuTTe(TMR^{N1V>zh{PLAxmfVPyw%UK zjjtX~lz;s#6AbefDwz?Ep|*h7AE)GJJGcX{({J>ym(BoPdC!OATKypKsLkL}$q4X@ zx-86U8!~U>-6d~^tr(y&T-=*Pp0UH!$h^1G>$+ayBt71SxH{1C%hw(<-ujCLT+M!b zn_C8*x7ea-Pe(~7#Mt3vEAkEfa6(E~F+@0c8`%#?8Hb3gL+@$ZHJkJ`-s}Xtb2atN z@w{pC{n(LsuRHWXa39RuyqhtIkhk*8_z#V37SMcPCEsmJcOW2ll7IBp4B&F7a=0(h z53;empI$nKgKhlrf10)<&;M=T>K;h>&_jZ_IJ3CPNA()chP;|j0m-G!louW%{#^bJc>VmxnWgrTJ#S1Ok#%&p zi0=D${{Q>yC+RQX`F|@x4=Sd7_XppDluLH=BK4rJqnT}<@PHKmCNW(bUSco29S+up zm)Lv4#kWqdIzoGOLbo>`um^NclP{{r&Vc3h8679Bp8^vlQvG zhk1{A(%OU_1(#lLR8<#7<{kGidfgO;2`a|LeW?%@w&X|Vy@gSaQg#pN@ji~LgBvBk zG1C;mhZ8JdaGT>L?{swD!E&)`t*1JnOh)1E4V>un|GitB-}Gsf$$mikSxH2gDb?XW$x;FT&B-RcOqU6(n<(`SJ2w-ko;-}^yj$wa}Y#G}A3`m2I; zB{J{AISuSxM@A?F7xzIY$Y?SinfI@}Wxp*X`20V<4z&Ert8>e*II)1!Lfk6Fk?6dm z&6VDqpY4QdXpI}$KcUb68QyhrNnBURo_DSfadkiif8+-e);1@c1iUY))2@B~-|F34 z^Dn%%Ao2d~#m)N==6#ImYP!9~*R z-uODu^7HpK%-b`=0;FVF^h^WLdB2{oKa&UZrmwfBDLhNW{2yE_Pw&5*{P*6(*6})` zYumr`KS_`Mf0Kjf|Lp`l=*IW6eE21H`~sH%QV+837?=4uSFYmPzl%}_?m=Zse15uc z4_cQn|0Pz-5i0pprjwX#2XYMVo(OcE0SgIrucIgiz?Uh%$>XAt;1_M{r+j^H=x-kX z=NCf;yOu0iA?gkP#0fs{^;IABK%D}d zc6iNzOU}#vZ$_Vj_y^;*7VZ(?fnfBAC-6e#xTHYocxHeFdV-7ldiU*!$BH{5@AYTJ zWLyF1@y6Fdi;~~ak1Hql?}Fd|7ylMvlr@x;e zd)~g~#MO~g+U9Ub?d<9kq}vF1U%Mb{gy(%wzHvJeZ^7Vob%HSOG^Yk?Lf$?H#ZA8+ zc7%cl{f=*QwgWapry)`Q8L(G$lD`#t3etGy6IpV@!M*09KQ=<1h`eKkORn;nvOrC^ zxLfgAs#WaByia|nmbFYJy#rEw9cNJTUE{(j#^EO~^=0oCLdM%||4(6Tn zLL&blLHAaVmaT5FbA)*H7%!%p*ny|#Hp}J)&wv=0>K{jop8_k+Hy3J{!a=`<^R12k z9*Df#xSb+)4lzT|adElV^H>W)-4MI?2ZJxb`6uZONccLYQ1WYA*dTGiiv?gm98MBy zLgzin;c~*dq64BZ;5aw=0sZxs7ecm1KHASq_5;%BQR3=2m9xi`*YETyZyo~PS5;Eo z@Vujr*>6MQef^!=0TY<_g7A5ILf)tDZRWY;;RyLgHnC4C+JVd%DVfEH8PNT9$oWas zQy?w&&MAWNC>ZO0wW72IdH(nBKc?`roC%u5#jR{RmtW|Fd^o|U*Af4N1P>?hb?iXN zZPa$^sDa@Iyg}BOO`lV_s)LeFZ-afs(hV^0JN}OGx-jon z+S7&~SG%{n{rA(B&Jb_U;Klp@Y{=nTpr z^ZxyH>_o&#HYg4kx2^4H&D#!S-YJg`vGU}R9&dadX!*r{&RNph$p(6#Ia+?AMCUzf z8pBSL-ws{Y61?d+jm}%Q@%Gh?D`&}`w+)eX__Q@vCC9Bj-oj77yWIL#2cEYgx zyra(tUhIW=fBsNRy~-PZIFZycS|q&R5eiVWkhQL`1N&7BE32$#z^x%yR~xkfFvrzY z@N{PsxEm+0W|HfJ*u7IdGk9IR*r0p3xU>q4(aaWP-dFb?6}(zSdc5&XhKQ@9=XR@d#L2b8i5&#I z%l7#H!1FG-WxNxKw}ZiL%?X(Ir_BZNglBJRmOEb=07rl%Z3r*1 zcbx8>{{`*2TD3DX|$adeMAl84Q94cB-*QM8ZLM;yL|q zn~-~ujt}o$=O}h44i|UdAS1i59(jqa=W$_95Fx!Dgs-CxCBM?GsbWKySU?Q3SXf&; z`V#9a_;!x^ayvA7vHzr50ud)j=FA&|s_u~e{2yyUTpgDyR%B&vuPw2=33yl62Ykcx zzOeg^C=ze`;(JE2Fz@QV4TT0U?~H99EnmXCYi(jvg800kliwdd09#Fg$oJH@9a1x3 zy=*}lFW(?gO*g!B34X-xN|X}oH#TJ6!`}`KGh4Ak*Ku(>Pw22V9!KV_R&%hfL4ovm zzrxj_ijv<6T( zPsG&`cja1ieC`@=VFKQFPB5n6d7CO#h#>KfY=5^~ALeag`EAQ8?+=&mSQW#(FH9wK zQg85ta+ZC68lN)*$M(cjSjx|U+HtXFb<7~JYgH*OzZDL8>wOQs7DwhS%6-YPZ$CTq z3>SCU=wx-SBQkFZ`-=Q4I;6)NUk6%#jVIn;e=E)k+8_qIJ+`86e_3z*0Rr03h}b-E|oe;6ulp z<~u>;`Tw0%+wM^=c4!6{7m^}<_tqFP@A4nPbmtsMkM}sPjtZ3g=DY@&%9dC_s+IL_ zWkYn{XOasQhvnKKi;!;1`Ss}M|Co(}v_nVskp1Qa!$w>kuAL*kq!A^S)Ze)v|HU4Z2WfvD_$Y0jw@%2gqv7 zfQg!BWu4{$P*HyFy&nA8+dLKyF^TJtd3P#E4@!Myg9LDKU*`twj%OkBesOl+5jk(t z|&{KjlQHWP6aNVn@x z{>(()K|bQ91$o*VAyr&lftKc^(@r16of6NZrWyWa(z`(#U&j`d{2t5gZngDf1MHF2 zClspCdl2W5310*I)f1%fk78Bm4@gHnGNYDa=qCFf@k$U^^hrZCR<7^?k^RcOx{5i>p;vm?-J-M&uo-BXHu# zI?`KW@pXiwc2#6KU9E=s_=KI-N=Jnz!ah5L|r=l;>#_ZH@@tMAxh1oK|!(8|6A=B>7H zeUr$oBamoh=5B>B10YjS=d8gy15VU@-zsxy5cquE7E;i56g2$iy8rPAGH<3o4I%tr z*`dd{IF*akR*x?r^QH^)iK{_Xi@UJAl0Y+WRex|QG>ptvzuFF| zvZnRh>Z0>@!>VpmJwyJV|HsluTpj8M>kmCCTD!a@LcqIDuktFM_i&@XBogmvvkixS zz`V1Tw3JtQOX|13KF=eZ;s z7@ohqvt#p1rA!at~~Tc^8R_WA0$Rp%k5>3>8Xa;5i#_ zb6$7`d_T0GuhAYpoKSpPL(3Ts*3I9HKA?%r+cIFu^l$+?#Egr3OU2z=#OXF|@1V;I9`C$w)cIg~W9%9}e!dtZ?HlYNNdcrW*72T6?r@9O-xzwZB6 z2yW2A!kc%MFZWIaZ~gmsqeg7JqmrJRl+n}P z@)qhN3@5)S(TV3@1PFk;KYp1Hgpaq6?>(Qdb&YV(y-e6(2!93{)S zAKyYgtm;Od*hQ+hDh1wf&}Rd52D$u5##$`AQzSo^2OxM~x}=h6h2YI7qETdo;C;a$ z(4W}s2Mg<-tGUWz0JhUh?mIz025x>$d@8f19aL^T0v)Ug1_^1p)wkxct9QOn4CLp? z2d9wZ>_Eqh+`nm%)Y)`3rMYMiZ`8+Xoct^j=RC*SB>zl z$;a}YEckdQt7|{+?lW5O`~Tmm^l|celyM_1?@O8xb!;dw8QhHsIvP+oX0~{2T$S zzUo=MqaPpdk>2`^w(X7Z`hc;<>*aNrtJ;4}a!Lo&@5n9u=Pl`|^|3TjP~p$yM41Bb z2b_kPDBh|OYHP6Y7OD%_mW$wB-_#yriQxU^Y%2RWviBys?w)bd8edrTbkmzdhc<#! zg33}poMS+$x+$3d2eNwGb}=E(;{ez*w?jCs0lWXd)oGSE62b@jkmEil@MKyZ#@>7D z(Q|ynH9>oLqdq!t^0PT{u8N4f|9AfIdeg79_;`bGy5ZEJCfMzCN{5C9{@xp1P{X){ zvE{;_oCH$mBjsHkQMvHn{r|tp8!i8U%pkQWYEVP{?C%DN)c+G_t(dWD&`{%^RXt-R zdaG9yl-eRSD581On=xbtxzXm9FH9c<+gdE2{T?h2%x-Th_wODB$4<8N|6+O#%8GyH z<%I?Vk?8On7yjmewDmXT3ckrDunalwrNf&cjR#(sL&>oG+2D1%X|D!Zl6?%|JnCb*lI?NSi?i*7?Ru3%&*gf1u8X*0f9J zY}xM_rbC?LzlN6%`9WW!h5OW_USJO-d`Eg1W9;%Z#X*!A99SDSb z8u{FVuPTGrdZo+Oz8eLis?E&bKeU4tUQ_9tjt2uV7p2w4TR`gw0XBSHw>>~nL)-M=s&a_ z!CNoT{e&cf_xSeGosZfAV9)9!DU*V0z*KTv-oVf(*rM_b*gkFtLakv5Y}z59OXM)~ zu~zIEgVEQR(B3(;d@we?D(nLxFdltnFG9 zZ*TY(Jr>?=^T#tq5xgr)TR+$!cwac*;HHD%ZJ?^Kse>l~mMAViy}4l>SR%7ZA)Gi0 zTz5mUlO@RJL~q(_AHNXrOXz5U%zJFS9|rH;Ksd4lhJ^pb6;*fH#WZ8%ZL6XlzUC(F z;SH00SmETCRx99Tq`DaFU##kzEQ61?cKZXOGO{@lzSF0FP26M5NgF!JiQ0B7bYi#B zg0J3URQh5TjdNM0P_{Vq;Z$B^f$rb$R>;!V zje;n8r*QT|uffDCrwRA_L0~qF^V6;u*!_Pqo9U9;7=HLCIZm@TL$JdP8}BWhTMY9c z+M7W>Bm3Bhli#mpbRr`<1duym{3G`qKHh!l9cGUZyl3bXfmj9={eNbtcf^P53m$Je zYJD6|KeOUb|G$m`?&`g(>kfW1R%H5&f6^pA8);|)awCdP4G@h zfd-c${O2v`jO17*CKvwse` zymha>{a}aS4GFH(s6sX;I5^I{>3kam=ar0FX?+p`@yQqYZoe1>ii7I)5&EyeryrcP z-f_Xe{Oal{wu{(!f3h={eyz_BTan{r+lGGJDZs{i(teaEtWSG*50ib2;^eo#o@d*q zW&*g&I~%dd4L_)16YqL2gnuu}lGCC7zqm+PCA^~LP}zjdE@dpe%>`u}jUk6E1js<`P# z&!6W3jse2^28Qr!(3n>1_RkL*U^CA>hkLm3zaXVM&pS4)Ub*mVPyuy5Htz_Nsw(|G zgEXMP`(^y}CKT^2MFavC-j;_$4hSN6Ux~;tAmJT(qApYk!8<$I&N81E3Y*>Gw2LXw zgV(BYZSS~%9B<*fPH0|anKeNOic0*0IDZrC5e#+#{xFY&I90KADD_r`5mGXI

`XsJ)rl@M`6u8coK~>|CaE+q#m31 zq$=sphr^7=`wLpfZ=C!tJB557Il~X0y-R$%(ex=U@8u4rPo*9H_JPihBteteF2qsZCVNo7Vo^$eZrKpx2YT7Iw-vNG(JJr zCdkKI=9C$Tywm}FnWVaB-wogiey#5XM~1*2nP1tXhsa*SJ-7U1A@=sxfz37WQWWEzy-A~W9Kp%&cg*&7g17)!$D`65q|u4X z+jy;*@e73aT{ff5Le2QMw+QdD7wsYlG5_L(-a1O{3v!TeZ~6E0|5(#41N|JC|M$}L zAd*`2Vrmb1qi)QD)q{)_JBtWN50W~)K#em0=Z#-hOhfh{rOq23*8FS<)^fSZ7YG@{ zYbktXZG*=KXpeF+y7L*u$C^Hzqo?8EF*rn&6eZL7!(*S*i9by(u$*T)jG z*+`!sjP0B66c>!omD;^)O+FqKwW8w$>GWyevO8Q%&wEi8eRXI&&AnfAYIZ=1pyADP zDXp8zn`BtSg~fZhAWI;H_nwh&!W7;zbyo5+$bdAqP|8N-k~y%*5pCS(YXt3n_caF~ zyd&8k?}taoKsw8135j3=^ir>Uud~JGJq6{**ClX49W?G3xA>Q|2iUyJ9%$CiKf`#u z=QRGUqXH*Cwqa8fr)Yk#KF%t&u;c;euQ7F5`-C;Up>*^BJpR$(%Rn9-A5N@pUEn9e z$@IJlm2}oIx>`~8@9u3l4R7w9PD)hXk!KHZV)6b^H*ti*yYQQ!5QVpDN@jl;!kZ;3 zd>@oE1CdhUi7XOEaO-m2xW@?Zo39?pS|Ge@PT#BTur~pr14S4Z zaY_}L|J4mybHp5t!Qmxa9ocSS_n;6t{=TB)>~KFC_dd-{^&1!V9;9ftU0e5ww+y#} z+=td7jgwzo>C{4JePP^3>;JaoR}qyvZAeECf*0@Kt|T)5BlZ@3b##wCI2QT$f^-ZG zZ=or-*^k&!uD67y^YUZy=4$SrL*ae+*Xj8b-uvZ^6_y~p4dgDKT5!$=*!rlmMJE`+ z_wIANq!He=WcRTR2yaRFh-;y*F$nM`WQ1PE=AAHlls)VRJM=;03d;|cFYCd6#C~sn z?|*-a@pvCa>zKjGFExBapLfDP=Ur5LHtL!n{(v+j?Y*HXID+YU%gNAJ$FH=>xw*(k z?2zrPXd2#vcUPoPyZ6iUuZUQ@ou2I-q-<|(vAiis;XU;_dUrjtf}B1%tiMg(2K37J z7i-)!g2Kd+HS7rQp46Ve0EG9Zr&l&=>^BCdMk9Z(zlhB{He#o#r5gu4j>fgdrL@O4 zVe_`>Gwthle#da#I|;4B5huT@MMAv(4~2oe>Dc?O3$^%N{Jh1PDY0)2Pd2GtJ7Pk| zfRs1Fqp&fS>3I|At;4Zp3jOw$eKfoUvU|g*yjLe)~N7xhATi`=PCuR3E4a*IcGoy)L!yKGFn z+j^G+o<`$r9oNb|tik5ZC)zO*)XaFiz0f-5=VvIF~ii@Igj$0%jwZ~~26_Beii{8{X^_x)!6?no8JJDku#>v)WlpI}uhr!lQz0-=~xnCNuy1A3HMsTVEz{D_+t|Y& z;<(EWnDOr_y*OYD#SCoZyOACgJfwCx5II3gKk+o&h|?JOnWdQBT#DU;NIsX<=lQcj zZ#1r1ILRzx0J{gto?PquPVNoEtsq6vI+o+)=X=lP%jtt+xR2KVZRn`3rMS8q9X%*Q zIp)Oay-fdzB}CC#M{>+-JER98yxC}YFPOYvMCE<@8>a{s?=*)(D+=$G(|c#{|8G|j zE0jcd`(%H({g&Gfd}kLFI-G6{hZ@cA-b8pWTlZQg6XAVu4(Xz|n=yFjHAnWudu-m$ z343%xp0mPUG|ohlLtQ2q`+7_JuWe-k1B}PpgIWhpekxBJZTG$T=e&zL_Z&6Zi@znm z-`qxVx|Xl*fB$+g+dqfUS%;&Yopbyf%Jr5ERvO-775?+7ymy2@62{^^*ynCf;eC3j z{}-iuzs=m(!GZ9$SU07;?367Cx#4>yZ<#S%<8LH;8sV)sBV}KY@GgtZvM!#F%>Vmr zYOXxR9*}~1+C20P*bOUd-4mNL3!p+1@Rc!DK8b@L`(HsoGp8sVQJB4n#!+5-Rp>-_5$?wC0_>=S1 z{yFc~`ZMH0Rs7xCROesK~?XC3{-!~HXdDD!^?3k`1(=iL8%_SR@JL=cO2 zqwf=Q3U8m>J?xbEe|3&VA4GU>xRTK#=D!gfZ&aP*sBQ%1TFmd-BD{H@T;5GW=Kq?8 z-->0@#$bxnwZOp>oA;{+53v)NipG6jE zAjbc5-iQ6yfA0*(-`*ma)#e=#j$!`!--6CM3SSm3Law*`d;gyamY+xunn%-v7Kv0y zP#>{#TU8cf^`O=g;T%d28hp{vLwUrqWJAs}qzC3ScH`fz zuU<0T3X&VGgN&13DY)?X1=l|xkQTlhJGobvj`=^{_o{!?0p{;Padg(<)w5J%_KID` zTpHfe@AQ#>`ulndQ}(eu6ZLpqKUp;k_|YN^QE(9`pz%WU5b@ zz$|s~Dt(0a^Wd~yUl873SWFWKi;RHyTAq8C{>$qvh#P$-cks@Ef@s`Y9K{9=Kf@Q-hp4}t3yMu zZs6(3*%c%g4R5LPXBJf6)20u^v3MI4kP|4pZ@#h`q;&5IgUR6@)mdq&_wLvM zBd1fX)v6|N`@Qjv-;n`HUr9UB0^xmYeydk2zcFx?es^mo9((t8@Zba*NiIZQ(r3J>-y8oPaF7HDJzjgTYze&V{Q=x;tOuxOgF^axAL>~$4|CRgi z{eLEy{s{zR{wLD(pe4(awoxCk)_>&WuzHYAqBS?=6+7%NIw~oT*vMm5V?oFYlDDm5 zn~|9VIQRTZUhvip@KvMx%HPNea^(a^fB-TeebdO^-D_Y3;t0NktvuL|*wqQzMKzcH zG(@0r(HE|%R&ZiJV$TT4-FQCng5e&q>(M%jaq@HTYT{e`^q&t%A$lv5&)L!OiXFDL zkZwcff5i5&(pN`+L*UJd*x5%c9}VxtFCV#6c?-XsScJv<^5fqhDUaBUz}f~1?+E31 z(J+K}*8B=5?uVO!+T0WyuPqkPPx7VlTZFgny+jU8gtx}P^^ZOqjeykEtmSi9v3ZLu zb_jfuGSeW8#*GSobUFJI`w_e5&x?dl6cPF;0GlEeagfHvjw)tEqp@Ouw3r zkGG6(i7U{ZVg3~)y>*<69V$d#v4eDPUK-x=#S-VJym#Mdkip`uoRT{G_SO~F+wW0$ zD}D^rjYN3MJe08YUbz`)wzSV&P&S8RpGOCp5Zfd;uv6;}w@ zyx*0l0S;XPyn)6MQ;y8LGmg#MpsQ7aw7;9-cn_gc}K?){dsmp8xaE@RmEW|2LJly#E<#EZ(m9n~N#kTl9B- zJB4>h&Hj;SgtzyiO-}6zn?R8Pi+5O2^*IXf zD=}xEQFwFo`M%6Rct4r*M$BvdCa{Dk_4DarQ`n~4;+-p=6eQ1k>~WkwRY`o7b-VB9@C;q~YB;&tQQ!u$WRci&M>tlh%ElaM+|Kmi+w0-~TG(geXWbQB9BiWDJ$ zf>=RBQIXzzFQTF%V($%Gf}$WcR6qqQii&~?*bv*d2Q%;D-nHf=yz74V4R`4u`<#8& zqt0gi&Yu0uOeXWVcHC)P3+`mD5m%S1$sNfZ&K<&)<8rwSE}8S4^O^I3^M><+^O$p= zbBA-CbA=<|oZ%ej9OUfg?BHzXQ=}fLL2e?I$VKEFauPX=>_v7WTai2@14%++kT7IDvKm=|EJi#LS7aVyhfG5( zkjaPd#`cXw2Wt zZ_JO(cg)w!M&?6i9kZHQ#VluDV4h|kW$tJ0Vs2w@VrDT@m~qSqW-xON(~r4?xsd6` zoX@mpPG?#%QKm6dpE;JP&QxJ4G6yham@K9g<0s=Qqn**hc*%ImsAtqLZZawv7a8Xm zCmDwsdl@?!TN!zb3`PY!L&6rKiU%7LYfPnqQwWCg>T2Lobji|a*P3lPMaOx1MobYNGt*cL57W;dU ze}4jhe*%Ah0)Kx3|6@M^@{~jbM#0I6*jzX%5&m5A#DrjoCJAdH8YirRI3Zyw7R1kS>JUH0sY3i1rv$MhZZO35IP5gu7AFnyLmUg@`#5Zu`YtvMVr%RM zh%K>eAij$ZA?0kq#v2!54h@A=XdF)h(jjv5(L3|WD2I9lmkq{eVl_A#0Dnfh^I}qai*!~dj#d09l#xfw*#8M#M zjR}ExCuSYQ+cB#lR>!P_cq?WJ#G5gTAl``KLA)O00`XeRJcv~>vmsuMnGUfs#u{Qp zj2Xl$F_R!(jxmB*9-{~GQp{M07h^Oamc@*KD2N#bksmVz;)NJ_i05NuAfAgsAfAn( zK|B)!fm9j|{z<2!!9VF#H25c-j0XRt6VZzy9*+k9q+`+GpL8@D{F9DEgMZTDXz))u z6b=4K2cyA1=|D92C+&|0|D=7<;GeWN8vK*?L~BCa9S#0TCDGuYv@06?lZvCkKWS$) z_$L)bgMZTYXz)+k77hMMg;C(2v^5I+leR>Gf70eC@J}j;0{^5qqdXwyMS*`( zZWQ<@WgL}LB}BQgK0Bh?`W zL}LC|MPmN_BQgJek(mFLk(mEwk(mFbk(mD_5tx792+aTD2+Y4v1m@p60`tEp0`tEx z0`u<`u>hiH1m@o(0`t#{!2G*MVE)}AF#ii8F#oO*n17cD%)fI4=HDp-^FKdgBt*vu zWr*`4F#mHSF#iq_nEyEun1A~S%>V2N%)cGRe-@^HCWe0oW`8|2I*Sq zThdphFG-)5J|%rbdY^Q$bfI*6OyH(q7UFq#dPaOWR6YN>7oV zAgw2@B|S=7Sz19_URqk3DNW)2;C|t@ao=*AxKFqbxOcfXxE0(o?pf{$?ji0TZV`72 zH(WAFc=2g*%r!i#wHT&Yi?H`rzEyOsTl{fynfu4Uh1Uu9onpJ$(9 zA7Srf7qbi5`Rq(~GCP(X&fdTdWUplVvc1>~*pBSkY+JS^dkT93TaT^99>rE>E3oC+ z(rhN1g8V?fAZ^H7qzQR~JV5RuH;@XX3^|LOKn@{$kRoIYl8dAxiAXdOimXEdkmZOE z;(@pzbCFrdRKy&agcu?^$QVQo8HNl-WDyQRM@XzL)+g3`Rx|54>k;c7>o)5e>oSYa zDrFsG9blEPwzCRY*{oDnJS&p5k+qiP&sxe_#BygjvF5O5u&i08EEARiOPi&^Qe_Qg z4P^CWAuKBM7qgSu!E9x|Vm@OwFl(8&m{*yXnCF?Nm`9lVn8nOOW=EF-I|#nF>sKrgS$}@cQ@H-=DzWpTOUrz~7(1 z|IAN-vLz1&Kg#Aj82l&&c`*1KM{&=A!H?pW4U->bK{kwj6xVE+{U|QkF#J)Rvtjz9IAz25N12}u^B=`A8wNni zylj{NDRZ-71f)1*!wg87lMO>4#XcLRK+5cF7y~JG*)RuEW@W=5NST=plOSbAHjILl z>De#~Qf#wf7^FmL7b4~0MRIG7DU6WX%NR}Swb|(LLusBnLyOb8V^x7 zO9!G(mL|k;S)(9oXQ@COn>7@oR@NYhnpv_C$7FFKj?RJsm74*to{(!oFZX}U7RC+Xmy{5T!_lOLt`hxjlZ{F58f z!9Te^9sH9Yq=A3({WS1TzL&NdVqF^eC)cKde{xM4_$S{@1OMbZY2crHI}QAktJAk$$L`4KY4d5_$Qa7f`9U^RPawOP67Yqohjg-T$BR-$vaZ~AZ||q z|Kx2c;GbNW0{+QcQ@}rYOA7cWZ%(m?Sdaq#$(vHZKRG`I{FC!iz&|-R1^kn9QuHBa zr)WdWN&)}m%oOlX&PW0Ov z?`^B4}(s+eFO&v_#DR)I`j`O(N#s zIuY}4m5BMbOvL!;ZX2IvaN4>!g>$4t$oh zDeSz}qz6hfxn0~=*lFM9UV@!l%dB^V+>?4>0R_z`V;zX`X%}adI>$Bo=D$FUrG0%&!Jn= z4e1(m1v-cJi`GVaPOGI=&`N3hXj^Ehv~XGgZ4u3pHkD>V)1nQd^`lX!pQx{>52)9u z=c$LN+o_q4csABjgrRCetC)1Xp6N z!t)mgWC~@{Wg?}HNfk@wO2tcUkXkO~E)yu@1J_?{WhTLO7iAe)xZd(bx>>qGYPOWQ zl!4SJslieRc1AnYUPT|?R52JLElX%uDi1b8G;8{yjWe##2&)zx> zC`OLq*&Bn0>Bvz$d)<|^137|cuPTZcBZu+q{tVe?ND-dhQc}cQ+kA|_3Gv6Xf?&fI#1GFl z*~_dzR^nN{g4H}^1)k-;P5Xo_$FrQ99q*83c$OXJ(T*&|vn=}WscEWhxp=I z`iD*)vKY_O&b*00eDEwaqm+tx<5>#t#7|@qo+Xd}CWkDpp81zsTta5x znO~a5BxE|Ct>k^NLTvGD#e{)n$TU1#u0F68nTlsiuWrAO*x=cciw~O+YdrH^GMkN9 z;n`x7;R=W)p81SAdKj_5vqg`}>Jf81TX?{JKVpVwUct?Yh$)_V+Q@!EP(1UHt(%Ta z!87;9j1FWnp1B>@4nZd2*@8&5H^@XhbG2n>ASQU`qV_WyF~&2eRu_F_0-nu3^Y}Gl zglCR%N|A^mp3QUE{t+3EXLBb|MMGmD_0RAdyMnVV|sAS3b2On&PzL=Df-Z_RIz5qLJ`Sp6$R z70)JzF3Lqz@NANO^b|xH&n6C;9f=IbGvnszWMmkgO%QlnB1(8>l-&OzG8E4YBM0*l zMLZin3LStb;FXS$ipmB=7G)5%s%MF!&8I9;9*G62uU{w~;n z$m5w-&Abvs4$m~VOlJ88TNTQLE;)vOeJ%{n)L3tdDqxeG@yY1J5q&be%ym@vNMpbs5RPvx|2v7a{3*R#td%G?IpA zg7x)FkyJe6Padd_q~O_wxz>Cn8PCprm=lR4;n~?kgOia&JUbJ)=oXTIXQeaazasH? zcG_jJ9ukLVC!5E2A+dON;>2BjBnHop?@w$-qVeq5{2(PH3eS$JkGXN!TNFbhVo3u$6 zS&e6fvimn80eD8W@}sia@l0xH*)CQao{?XCYG!@FGtx;yiO!Iey+8ow9Jp1K3 zG?mqgXFruc7O-0I?0d_;NvyYc)^*_!mGuVCz9s*@%4){5&iVD}tk-zeLQQDu~cE*!?Wj&wPvh3JZn65Z7Hi3&z@xmQdl*3_SB{JI_oZ;JsCdl z73&V3J?aX*%({(d56_$5VpZc=L$XZ;>lU8X`&5^+ZsOSky)h-M8+dk~B6p5;9nb2n zg*;gb%E%!c6OB?tVMu5S}$HT{spwh-WV>%G!_vc-Hv+_;+MK zo;`cee*&@(&z>Gcb&$Py_9T$cL-yd=W7GEokllFph^69>l;Byz>#`7J7oOFhfirV4 zo;}$3RDkTnvs>>KxX5NayIJAGMGElj#>v6wkWF}Yeer95Bp=VNjU7G;$-}cM#B(c> zi)WSfyNr+=JgeAZbP37Evny-Y%OTk1RT7Q7i^Nqy%oz)*(eST-e@WU;06v2x-{Uh# z*i?gm25BWvVGLa4BCYWBCt=reygXNX^Oi4J3757=QVDzu?DPNkvlR=l&mhe{`JpWU zzG8=h?t1)Ysw+A^iBb7|oP)qN>DS@>gl6=CL)Jsb#3r=j{_<%qH>}V`7r!)KDe-5J zF8ZcD)85|2e#Nx3{EfD`E3wf&F$SU ze@=dAOy^aRzc1^B`MTGY;b(jIr%T>yj+k}CL}tg_*R6W1LBxBn zW{!C`?>qU081H^RlAav~-t)8$hwk3*g7Qm`+`X$lM_~Vk(-H){4MzC*hXU_Q6`xbQ zYpl>md4aX5TZnmYP5Hdyj^}s&J>j~;D-YkA7f;OlGTT0B)#y5j^z zhu&Ni<4t`Px)bC5IL76{Z{U5)W#sh04rg?h_MCntZLR!AzmHtuAiS8n$XR=e-GZ+g%q5(V{!5* zBHrWbb{k{73-&$QgYlmJ&}YdC_<;1MqJTN71DsJdtt-ak+bqHI2wgQ@;EgQ2Os@sr z>F3*+$H~^{ioJ^C3eOSqK5+kfsJGNlzPE5)=M~RYrhAFI_v=E%H`|l$NnH0nC9I=E z#PKPPBY$|mtoI*~Hk@;QtEaif<42k?INdbaNz6KmADBd3O}LHv4){p(|;M%?|$pDkQ>-6nc8V;J%4E$qjt#auI% zymxP%64tRm#PQv)wYAT8={@fq=USz$%EWlRg~FYWimd+w-~TsQygIIH<{mwK{O|k! zdf7bwGs|KBKcq(w!tRaWJt!wzMu(^e8MU4D$9mB9Ez;3g50aOS`7i?}$SvVPKU*%j zq1vn7O?(|PUywF@+r1Hq@D)3q(nW_7n$Qx*H*qctt$UDm9Pj(WI*dddUt^uD&BXNH^Imi2wyA#{8{rWs_(s?oK$Y?((oFE7F;EmnA#(BTB-!qno_x3nj2aNZCeUuc8_xkr* ziP#sUCn=V7%zd~39qgz$d-?Nu0<-c%*g64$+l2F)t)!X-;tW&4~d$cw^5O;k+j`PSqsh%`ukmzV~J_ z=z9*v+puHUS99RKcETKQrQ5Ek&!@rqOu4y&y2=kvPXq7K+FFLXz`O2O$OOt&E7bO! z>&_z$#KXzJ(zkEoG{w}rfD&G=yDSYu;ZVfT-9Pi-Ry@sFo3xw-5=e-?#fnYXm}yoY?P+_OVNjQziIo3qOlxjxUEWFuxBcFUx6 z{@g(t+JiUt3_Q;JYh95(5$_E1-9Z@d_g4$oV!S8%cD+ji-nSQ5E&jCA9n~BY^YB=! zv*5Gq6^97meP-F3$CH7#=io_aRXZ(F-)olnG4F_Z+nf0B$`gFzFA=W$S@z`X<3q%} zSuXpXojt21j<&l3%!)z9cX?*rTXA5k8NaR+GuWB8cC+xtH6jpEf2a`tp> z*WT{#t=NM%_Mr}(_neENdPKaps67h9cpoTTx*p@L);@mCI^aEBZ|%CtN$%*DaMz)l zuFisrop*JY0`H}>Zk0L%@81*O2HR7u&^!DDN2%Auyl)4brc2p<=Hu%=EA9GaSxn5E ze0SD|n31<7j`v+*9UKwIrxRPRXL6?Zyt5xk=gbHdgZCn?>=|C)|Mr&fV)5#jkaEp` zLRvR(g&w@IPbuNNH>yw8CE~qyPT@w3caXkfIL4bJmu=<~TckeA+SVy*q=`>VI}ZdVnJmKHsGldMPFpSi20&tKjmO%=0_ ze&pMRFr55-{{O#i)+8~7{r`v_JqY`pCf0-W;5$g4F7zZ3^`QG!7hSL(bXd1~5!QoN z&PyCpt*39AW_y7XSmlnEq_}U>zqml4cRu_2prmG$yG)st5Z{FUh<-l$c%dcgZ$Lfx z@fYza_E}TfZ_T;w{8hqrT{p^WmR~16#p*ptI=uE}mBgK5n}l_sB93p`=p9$WmF0T9 z|DR`PGK)_W;}pBXVOH7V{{tJOE#lQ-I%CB!`F-7|Sk)f9u@4^Or&tF2x(N~QcE&eX zjCZN8#$t^3_3M*OKLYRfBYo_z+;B$&%?4GuuU;USxHv383V4ryW3grj@P2Rp{!9Vz zE*l`XV^{+*?{Kpwjcb?N`S`l3abBB0=MnQBKkArWXWli5;~g!m!$QRI`P@#L^(M6U zymwDMMshV2{dmidaJgpAwa`AlLArKbygCqvNn`6Xx_PVg;EjEf9_PK%ev>f~@1X-U z7ht?U6rNmy@!p$Vt)T)FWJ*$n&92+-C}n!(;X8vD2oj~Nwco=8sYF%!bryK5t7J^R zRBVZEzwGx^uY#EO&yCvpF(w^+eBBJ?A*PMN#Jtykx}THia9!eflSBU0ks#vuc6V+m zf7jT1-ihcZ*~8z(xV%MUcVsM#>GQlvMq<`sAHGZYc#Com-q@=laNaBC`A#6>9kL;y zyL;3Iec-+AbidPez=A$bRrayuVog98qQXkw0Fzj(vX00oFQV-kGIRw@RBOkM}oW9XmxF zA1lmYTEywzU*38l_~6)7Df;o2(t%&5YXtY}^WEENqIh-OiIN|~jm`eM|L;}r_zx|H z{l7+!9)!K^3F|@F{{KPq96C`Cigf!Pi}fI1wGVb!589_XMd7fnzA1ME`A#~Ghwj+U z`&fIxO`xkkzRe9bNSUwHDh!|pU0nIH?Mj{{dT~eY2B-DJJ!s*~XZ!Z8_`oj{uB%QM z^-+BdaSysVlfzl%R4H+%*j2(h>O>shhVAY4tE*&tz5frdowaICgXj$sY4yFm;nDVe zz6X)kh*w9f`2tybN%tvMy$5gX^<_A3hg~CRM7(7iR&T&~R}3$jhwfGNUZh|^5w<|M&_sv0*bf*Gu?WD+^jaw|y&YYVT*A@};){;pW>NB{F zkFSduwnVGZiJ13i%g5aMcFE(dC#>VQh~x8g&QahE>-_}TdfZuG=d}oXk6DHNC z`#kS(hIn-hpHbnJ@#pcDQ9XEL@8iRHzpeNrMa28`(;>?+-cxlNTru7)qa%t<;qul7 zLG`4WPu)?A%c~Ttt=$9*<7U2^1ia%?_XaHh-i_aaeyH!YL|+|@bGWjQn78GIu4_u6 zZG3#)%z0fm56>s&-GAbs!`m{iN?iB071l9K#PRL9)naTN)O+5ua~|ed7l^U{zx{L9 z5#PSgn{-FaI{F>tjQR6;%g7$Qu@_9@yf@!CMU*fPoqzP4v2G4HUJc@YN9 zZG3#4UECVGcRs|tUCD~f851S%=0uFJjwK?FFF?NBIeBL9d25s{vpls-boVw)RPp)j zv$D_MAPuM$ua1Fojf**{-NT7m58l`tQ*qu8%rnVEyf0r`-_84K=KlY}TjkLo-aE4X z@LtIK!+ZM9KfK@GUPq4#ute`yEuo*rMr|M*r3-Ep*T(?%!??awF@zvYe{o89& zB#`%bVI6KFj?cyY3hk3^?|GMm%4WviDi=Moe@FTHDuqhcJa(2|CW3erYh9h<8DAV+qE4%p&>}jQ65@N1xaNZ?o`mSB`kY z<*j~!RFB#2f{;(okL3aH_SSn&AAq-ATQuouvL$*wh-^Y_pNh>ZTxaAQGTmwX5K?$-Wtts+JD%* zK@m@CWp%uovHBl;i9`L4J z>9^>P3JfRr(|^-C-2^i)Pn@$6c-MQk&FlyJf2qQ(%GBMKX!NdGNeA8#^ZsN-D$Drw zj*qXq%d9;!jY-_ScLy-St{YcKT=%9}|Ec4kh~pb-B5T`j-uoM*8rQrFQ_97-IdQrD z%R~9HzCWCli&;mVpm_7r0VvGgqkHhizIO%ZJwGOzLBu=Gik*S+PPad5i}7wQ8<7

*uGpR#psg2CSAt5yK-$9I)Rs{-$;W2=t5gPRkn?M3Sc>?7taFgiME z>9P0xWZ}BzqkbE+N{PF7^?cfqmMfCS`=+ptdm@hS=@Iu(hv?pS?=u}r-%lxue!OK} zuD_b!6ze|Uy`}TTtE19Gck%q_zxV%%hJT6r@6dzvdh{Udo2T#|6q#u!OVoo*)?AIm zdeG|Q{U=~Oh5(rup;GpmDZ&-jCe{Nte5xK7}46zsRgEA0|j`MYB19 zzbsHoi|5nI4TyVC;cw58dp(-@X2Nw#E2*^k9O537KW3rQm**EH?i9OUSjQF-$Cqtm z-#Kne?|YE`_jvCut3^M9R5bVK>|2Z6`+N_YvOv5#R*&w(36+5~;cw=9shV#BR zi`$=wcg4NoDHv~m`ME|I@0g&)I_rV=eA4C8b-_IJ5?^BH`;S7-w>I;`gzKj1*W4^@3n9Fe%&T3H_<80fiQ|1; zSjR#U$5-*9qALVzExr8Z_q*)TP&?6gkZ#MBeO5M@+vj-)4-&7AFi(f)*Ee-r<-kBND|uAh1^`GVx} zjuzI@BI5XRJ54I>{*A|5%p9bC+&A((0hvCHKamTAc_lS8fS)uBrHSjIpS-37XGWp2uB;p&SHwRx@HC(S; z;=1=*VI6lw9N(}vU%q<1?tS;JrtNz1Vyo!=fB4hpebmX%`aExO>v%t9tb%S#clXxr z!5jPbR-AX#v2ZRCZ#U!H2Ql8&p5fiYNk`}0)0V*7^u;Fggj^mP_QRImnC32Ey}!_U z1bDYjZl>J<-tT4SvsS>px0Az?+T)^#XYc3R7c0uzweazEk4|8xAJwK?Cm<`(iz4-sdYi*eQ0)Ws`lYpa=0ErL`|! z&O@!`S}4~|c>=H7{R^1M&8W$>%fA*w50Xks8h>=N1^Q^$poDV;#HZMaZmAiKMz8qw z!gUV6rL%tN5T9a0RI&qCqh%6zinS8f5ia8Rw3j#tf*X5(iZ!l_@aqZ|-Gjasd4v}A zQ|t4m*ww}2)zNt+ye&Gr`xI-~gE#ht>^SdKGIbCU@54Hy{4n01G7a@H-q}C4Dy#$E z z{94UE&zmG}9Z|_->=8TY-s5}lp69UrBhI_v!kqy`ycb+c4a9i+mOts_aA(B7y9E&GdLN_t`2)xV89Ck+l@9kqNt>h0_pacCzq%Te;=557M*j+mH zHD6x1?y&Xh>9PO7djfU$f`QVKclCC*unrRu$0wM@`{nw(_uc!qN75xXQ_)Xv#kZ=#=XoD<60eS$i-tM_bGo~?K@Z+@Cs0S?yrmV2<%xK6oldO7c<=prrTgZ@wk>YT z$-vv7a*Ior4-Z}0Uw5hUD|Z3?>ZzL7z}xEWPKPw$EjY2FVfiHsbXTmM^MnJ$ygQ4R zdEcmi%`XrWk{MI4{qm>U`29DCorod%8M8xFZ7 z`l|1W>M1m)S)bn^kyeRWhvxioihsJdeh=PrzE)=7yw6z#$Pw|r9(BH(cS^?P|H6Cn z#Xr2m2mRqKbNLT%sSkg6|BRh9UbV^sy^{0v;%7cF?{9Hywmk&i<-&F06d$=Ui-~!M z@NLaPB#<{P{!blYB93o`l-`h{+r97Jp2NP-l3$9Ry-8zAI)XPp?EAcR#H%C!rrUsb z@qhRK|CtSaFaK7UASdI-WYg?$EaG31>UtjJ02o)EYPx!`(K9e zh! zp0rm3<86NLo$F2DojB9@%f6jFwAwYR&^Cl8h-2#O=m78Y=+cc7fcM1Vfg0gMEYMGJ zH|mXdIS_ulWux+d+7_!Oe!Fnpgxc8$CfwUdxDi;#m4CV+??_=CVIq!ih6^jL zzh>`w`#d*rSY{)7f?VE_Kd$uH(LT@n!e{a7sGNoj2>Y}DH}1jPMeS!aKAhM|?^Gb- zJ*J<@42<`F{opYe??dXkH;aIG(6);Fqe(n8>wSomNgz+KSmWpFQNVlV5bLp)!24>z zvLxmR3smFomtXBg#Jtz6l~vx%Z{m*>uDdtzvATCHG4D3lGF84cU*dRg6xQ)Y#PMY$ zbXc^m?>%oy+_Q1Txnf+sZErnu%dzkCCUuBeN6k$?986MFD=YIV`ac|S2(I)sR~ z!|QRL81HnaSZ$2AeXLFXa^OwQTsG^@3LdH*c83@3$P*+VJ5?eJydUTB+g-8YWE(&J z`xXl{`M8dM(>dbdXL9@)LyX7PQE&c;rSrdxsdDZm_!`kT~9-g>^)UI6k-V zel0%Pz2|*`XR_ZZQH;l10ywJItM+Q6;W_O5yZ`UyPW(T!9QOZaJ$lf> z1NQsz9#rI}p+?k$nw7e~lA#C1y4@az^`Pd>@AjO89z?0Dj(P?A|LrfF^A2b71TAMB zA1sC*w7%%(z0a{tXz&E144R<@+F-5BS-OR|2mL?{f;S#(d2VgIS4Ld5a?_VgQjX>_*e{V6uuIpCn?RWT+=YO1Q=5`{j$K_dM~ z5wDJGF7(lVCP=ggZ%-T9FF5c1jTcpjco%iGBN*=h6D3uQxBmS*`X7LI{WDkNw|9AH zLt4bzM;SapK|f7}dBD4D>%qw!;5~Kt*s-&hSfImC>zt>3BIX@8EdAwQbc&uJNha^A=AJ6-`@D_C zt7EquN!|5N_ny*&w}))qbe#9Z+wsaoyv=lG$zi;g75*B5@jia`=|@GlIk7zEkjupf zJT!%~@z8AG?GnURoesS7hHX+G47^L`PPMUFZGjr=FHU^=H0)aznaw7=lpizx&udQU)RJF-<&v|^rh^+1o9pv ztfNfS@y%O1e4~5sc`w!3bA0G)(NAxY^o+{4a*y_T-XsGt>zFcqtv(DVf4~2aXxAn| z{~h-K);)UAl8XU%HX1gq>m=);rXUfKzPvTa&8$FhR<` zlH09Z$P;`GOKwPoQ|wWBd5ucg{||JQv0Vn&Addzf?%z4Zk?;;unbGnF(>+i5__}bT z8HIE`;#cgXk{maAe?BE~r`TJcQK0$?Si>Qeev?Uy{>GK<;iYemNQPnnd-{@2aeO8x(&uj*+5+{EnzQxH zEE6g*@0{q(KF8lb<7W%kg$LBu(~lGL4vH}}O3ITw-kXJWM2R@QiBV%8xBK*-w;6xM zzJ&2&@Se7pm2+-lpWh&rS??38j=dktL%NQ3-<&Y-!F$o8vU;5NyA4hwiFm7{d){HZ zgPZ1e&)$niT6LQ@53RCabDjje#~ozs^9SC)xAvRS0=y@#jCo%<#R7ep z=y$2Bnt1akf z{~w2ORlGNevHyRi;&5nDUZ3Yp;)_|w$4xWF{oVgd&?f&M4h1$y(|hzFzch_Wcn^{( zXX_C4pb>Fe=dm8N!ZN@66x+^_z9$JdmoYg!!O#o^i#^bTUOx`t z?|~llHDQrK|4|lb?d+=uNI}G>*pvqYv^WbN@oR+Z)HgoPtFR`12T6K*(}Hju*v3o}eTkhkGxfyAC02cYgA{HoUL9T!68zWxxr1ce zgZE0_7b~2%>5c|%BHkz8HD1JcU!82wy+QiOtvaFxybI(7H_Bh}(BWImuTVGf1T&wX za4ZJix`(v=4+8ITOUxeGjkG}L$I))DbtUFKYNu5!IPHd4 z>_GRP)`Rzo2?NV;-rjA8#uD+irYxw$cyB}>ck><*Wjo#nii;vx1V109Ae(LB5qNimptYx3)kr$r6!OE5%bp4 zeBwDKSn_y364qfP;`lhRYj!*g>OJpzx0@V4Lopt2c^}<6d)9$I&zp2a%sK+Ao(NxW zF|`Np<>~`lao!x`P%R?f{?~JEV7v`=vb#4(PhPwF(Y(J$Ns@y8S-RJBnqlNyIy`{OoOv_cHRVZr+`)6G~Cwy>NQJ8#(uQD7nHYu5>$3 zAh4d5nghI#-Q1=k0NxR^+tj~nTB1${>5Y2L^9k?0P5E(aTEDI*{Q1Il0?ik%s+=MS z?=cm)Rn#;EO5VM<8Nxbti8#KgKI5D{-wz|Kk7)O#!>-shx8sh;->19O{cz<5UZ3yY zaVx~Dql(s8R~%gY_x?W-97+1`FhS1l(Sz2+6>h_O&=fw^kf;ZJm4EMu^`Ng?%DbOI z+BQG)lnwNt7gE_?KNLMsgPRS@9Hl%2tT69)eCRm|BgO8^sFnwOL*cq_N0teaZHTWyrY?_&uA&^1xD8UPu#P+t$5*XimE}>>`~Cmi zeIL)9e~;{D5L{xXdB z%kSkX*c~Ky?wZFFfj7yt(|FMU543LCC$-oQJi*ca$@b@f_vQz~N;80WdPA#L#!GW_ z$%XJS3r&ePNTt?(i!Q9G=i}=<9ab+o`;nOUFwZwkhOgxDzAUUmUBvM*Pf;d&WcQx8 z++_O&6&YeokjGQL#D0=LCrO?4-#V64;?=RJK;xQqM)w3cs|WAZ>O-n<-o>Vc`b4}J z7=I7PczcaaACB=3s`HfaeR*t_(#il z^?rjiZTtnFd$UEq-lFlwvbep6Q~Esbt<~byL2J{>N=xg0yk%w&-m88&t-^WBI<3(o z;{7eQH4o!Wp^og{AT5!8H*g5>UcOf<>L}F%eKy?e$j zlltRZ4x6LT{nRZ;8;FOKO&4p)!!|eY8-?qF4!ye9^_=(t=~P`i2f>u%5;vTb2v();c`(S6df;&Gy{-iAgwu9h9JuFvx>i59PpOq;ofM*O*YJEI40|8k2< zIPZ2%RF{bNK7%QzFx~}Encer^G^Rf`U;^(T86PFtHXdqUmRea4A8$FISHU^}ytPc4 zjEjM{T$9g%>|f^Sp1_FcBvs<>O|#xSn|tjcf46X5was|y&wuFNp{8{z)k7uk-kZFz zj(8ErmuxFL$5X5K-Fx^BdoFLa7*}t1-MxNn@u|Llc`H@SIwt#uEC0R!|8LEI|LeaA z_W$#G^q}Clu#;F1(tk19r@qUBMAU;)^qhRK9@H{ce-Ji78eeUix*K}XmnO{_A9Os> z<=Y<3x?aZ`HYaePYN7raS1y+6fX+%R&~*eRknNE*j2%_pLR z`~3dj_n3Hf*m^17cZ%wsAm{ery}`P1E`EyLd;W?E5${o>26$k+k2km|V7xECXRX}? zyk$45O!_(21Kkr87_Ih#C#c=SW(ZVd`U&cE#a8>GFrZThIp6#WD# zY56mAv+NOlo_F{%@#^sM6|52bc|h8s2k-St?ZXbJAYpXPv9goeBv$OZL)m{BN%ueBRLk|2i{}!a-=*ui8n|M zp%e0{+V}Yy!gUjJ?#c8|B<9_s|8m+yzU1+464uc!;`n54E52^A?tS-e@Bd^z$z1f) zTdhXlihiz7>hrvd#H_=1Q`*$uh2598=Jenl)NytY&U@siMH7g4d%4!m!gwDli|xL8 zTj~G#p+E56!;W1ZKgt7D_h3(6Pw@~u@CsgY6?n6|?!Aow-WPt{I{|`zhU%l8t z%sXl#`pT=~J|AD#Z$iHH{wQMJ@7p!Yjm938xbB@QtmBJ_AIyJBSd%a z`0$3*=y5@Po_E_q@#+X}rsb#R{eA!6|N373-}wt+|L@YH2Sr2`DPuhd+yCFNcA^vY zpvT&G-;tmP(Ok^bunp2tZ}Ng=(1Y&QOgZcd`~P|8wxHEJd4lUHkE4HJr`Vv}atr7| zZ?Y~!g5bPBD)wQzw{eLQ*Yi_Is-fcxT!@mG;UX$6hDf@YXl>GBvpMm$x zki4lgfcHd=F+;poo1wr+%sAs*w=gBrbV_I$U89}Z|T42cXAoM&!1vRvSQXTZRjSgKNF-=58h#% zGqyPIOXPMbBHs0_<1{edvG*w5`+o(d-kccV{pHz`h5K|pP)ko^^!ag~;BDf#j(5Pj zj9NQp9`HUB*Idtmr?;*djCy@Cg1CFrWpiWKMAY)DgzIDjJjpN3h@b!eF8I0ZbN)ez z>)!o^bvde2*Lx~yB~Y0+12Nx#&5wUx5_K5sGWsLlECFdp6@4a3R& z9=tcgP`EDZ;W`_I3B6Enl*78T|YCXshmr6N8LwUr;l99o{jYavWWG7Nw~}qo*+9%& zDg4Z)F^P5jJ@~p(^G{q8V%}Sy`<*>HMDp&vX$b4sE8_S*1uWvqpYDD44p9F-J+$?z z$mjn_uavZATrcSJv$wc)4D%g5M5*BK{{P?Ej{mR!9yrDFdi0>Ur4`rk9@JJggG1DV z+}_um#rFSa5{7kugH-4+t(}$d4w9V*ubaLa;ekGG-K1&l#S@G?d_J0$(u@vZ-gP#B z9`qwulwZGsA(n2VE+)J+t-XUWq%!lJx)7 zaZSYWUD8p~H*^dv$wnH}=o|->nDl7%2l9 z&RakHC5wpn=Z3e}Fy8(Tk96}6@l{D11{0)_m&24%njWanV80@bSf0SgMLLoOycIOp z$r=Oi(w(FQx00ZHH{6jPwvM=akBvot{@j0;kFWb!)pUzFj<|bEeR|+`^n>K_9xtqe zE#ml$$C*bN>Gq!YIzuU{sTkkh@_h2;LsR|d_4)mOnyGkogjFt)lH1nZy%+T09raW@ z73V$i>S-ns?~_+1)nL2};{3aLyQ!a7@&ev3H^2W{H_ih+s(C5Y30`lJA#3j@1-ut- zG|im|yshR3Hh66|N6#+*9q=HTm^WYcotxG08a}=*=f$eY<7X1{4wJi;@g{e_#C7iq zVI6TIjxRXbGy6kg?|Fw^>}*e|65|2s6VvCuAN#rVe|`A;`SW1^zoe}Q7`x5t{t2a-M{UBS-$Jeza{Y-u=O?-+yclOA-Q{E*K zcZ#hM)^SC|@vY9j`7>ow?|abm{8pF#mqb4x9bU9A+0VJX@Asfe@#^r3eJ7<-(mg>g z?7=&E{5LtAx8gjR{zSa*EmTRycvo&(-pzZY=YIbv;5~lyga?CcVS{uiE+!iG|Nbo} zT?b&i{jab`0dMv>{oEi^b2Nstamf%fV&0Amua8o=TFuATHLzdwUsF$firs4ZS@vYJ zU@IV%_Ay-j;WH*Zsh?}@3vdo(?NX2)a?)P+ltDe!^k{|m1P zWP$fF=l2sv18>=Ji*~<2&C!+_Uv57hP0ZUUx{~E)ew&Z4+frNS9CDVJcX(0#PSsVr zC9Zo<64sF*;`od<)VzQCsQ0{MQ#Idzyd=g1X@2`^$|>(Y&zoc@W*wJx?rvT>0K5P1 z*@O50WADwwsqEhV|D8-JWy~z3!H`5rr7lw%WU3HlZw(R(l}e!yAh8`&?anKgZ|!efRzy-T&!0Z}<7`c-`-Hp6guKS^?Eb zA1Qdx4NISohPNmwD;~z%r>cfLocO%1IPoXgy)DRdiN6c_e_{65f}wi|q$sO3oIC(; zyT{1^iU9BG18Vihw6vjL2?~pCgwgRHFyXDdbGMpEi4$vgau58&`+vi;!f))EVLZIQ zB0459@{2VpswtGEAMd4B4{Gm;U>|Q;%T>%l%4uhMya!on({Z)PwCSi9dH!!rg|~mS zTOS4Qz7h{^G`tn<*)w3gKkPOj;~hGuljA(!5nb@U#)Nbu;^|A$-()P&0K)@ z(AqE3Dgf`qalgVhm$jkc57&d&64%_2EAi_hdhIPX_cZIMG~>PzV`OKPMeM^^Nzkq0B3LizW?{X z(y{+%e<@gE?WjB`+{D+3;z0r*R|}(gP}Nxf2H1nHMcS-{`+pH*&qouWg3LZyd&1Mi z8p7RszViMt0?B`u-OgpegH~_3dzlA#(B2=i3U!OLq3157&;nz058C$WWpT01D`Ghk zC!uxjXLm1p1-W0zDoMxrNa1{vIn}1mpebL;eaF?_54E?_q%V z^gG$yk6?SNvp!K}p9_J+@q~NnVt{w6!jX%D0B^Isv-noZfcyWPS)#URqvNd-d!%~( zoGPL%5?8~ut%j!_9q;7OvX74k7!Pj^M8_kH{B}m1=xVm0AMc~(cb{BIpkaa(wb9Ms z&P%4p8)r?Uj*Z18%YILgY^m@L8JZwa@P0o~D~N{oPW|NvVZ7(H^ee!4r*CyH>jHT5 zXvm8+@3DqngnZ!L1a@yblM<^W0p9l-KBtQUyaUHA6}il{Awt96(RLC#-pA5EO&`ms zBI1#_9;IgEL|^m@Qq@$q?VfES!@0LBqGJ8Y)P&_knMI znJ|5Wgj-IV4lx0XH9^03Zx2)99h}?eMZtS=X{-Pm-U``ATw%OfQ~~0(ghbGc`PQNE^ak7s&2S!wcl~8E?FO1auXeI2gRM{Gd+xl_fbU08I1fEZ;IG_*_D3011?^8X?h2{I2jh1 zWb?ndjp^N6yn!|yoBZN#Nc}#XXhVhf)zBPP3f`kvT=>!OKDN!Cj5pNT_iuPRA$Y$> z@ZN~v-GSh}WZH1tPfQ!ynj<53h7BF>VA6fh7l&RGw;*xX-e+G>_CYUB%v~x>-!UNG zHxL~MF!I}Q^Q^IydlCd|7TnE z|CQec`hQ0%4~jNfaE#(XP8KUA(L9Ld{H>Om*WmuYowL`IE6BFU#r|LqQuO;z{xjf; z-SuA*uE(AtkY;}z9#H~IY-kSt4hL9b-FIhJ^GbpFzYu4|tv~ERKKObYH?r>qaU&9E z(zY{+`y~1j`#FDYNB8CghN~d65FH~J`RyBX=E}cB{~jc9|Lj<jmkj_MHUuB{t>N(uSaK zFNkGGTnF^6G{+PjZ|yUzDGiSq5AO^_#}17A2BRlN>l^9EyG`Qcv#90Rc<(!)sPK-g`u2r__r@)8qG)(0gv=6#@h(gI&4U!P z124l3Ql-#BE!cxLh$*(@g9eGi%>H2WbpllHHpe)=0#DNR<7?UmJgA~9>{E~LC#X$q ze@@P4EhxBj+rpGs^a?Vx_FU}X%5vgWB+hKLgu%hh=oMsp2WNod_$`L3Afpi-gBbZ; z&g%%ds7-%^RH0LS>)>;25Bj{tsOsLrnsxtSdj3EEb$NOQH0jv7%KeCL0QrdB2`aqf z_#U`Z@D|-NEQ5x(f|ArV7;mw$qna?@c9p?aaRBc-_azbxZxbMy`AI1~pYbHIyrt)L z0Nx)DjUO8Vc+YK6(@ROvf(E`lu^1^tzyI$M$GJOA56g-DNZc>qot;U7=v(Y{GczKI zrtu7icMhWCJw|@RC9m=OJb1CM%J~OS_vhT^C*H%JAg$*R39gAEF+JXQO$BJu(Ys@$ za?9@t(s3%hV>>FAQSd(2RU(as_q5i`Z5Z!?_8bVtd)uehURQv(&n1UCgNFpjHIeXr zh@U{}zCZ9$1K=&&U#l|?@ZRw>%TVBs7W6n>om)2z9q*s_4Jvb#Du|DexaUJxk2X)C zKajR7(TuP)gYocYeeheyK8*Y(&c|C^tfU`r9ejeM`Z5~&f1j`M=d!by9&en&AZ4I9H)@ry6>3Qd&b;o0e5U97E!&af#cn z<)gcIP0S>Fw7_kKbMGodM>9r#if&c;{gL$J9sfnFVtxbm*IT%`Px1R7i!uN4mZof) zbnN6iqPHDfkPd2ZCn~&exT*D1@QyOyw+IdI8ZCpDFy0fA%QRrTN6KF5LjZ57noQSg z-2|v>(tLr)IRYvCior*C_7*XHu^issN^z;*5wcVp66{#0I@*Sgw-smlKGUk_M1CaB z_rS%*g~{l(_wjK(WBoS9!`l|o;f9glHb*kXx_b+IM{+5nVNAmC_O`=$#9`K-^*^h4YgC({}tM0^e4=rfaN^08j4SEH+ z!S{vD(Vi0GHze+1N|N$-8T2Lgc5a+Q`oma;TVk~l9SydvmmA0GyCH6+i+#@2d zX*eLAp4Q{>enOowA*3U#>#4NqSaDuR>30Qrh6?Yy0)p)nym2pjm!sjG5LHU<|NX;d z$aufLTX$$5z?&uXth(q;0%Ug4y3;iqPr6||w|^_ZJAG;|TOYvt`2m(QH}7dd_q4RL zW>nCZ*bV*W4nw<3iAhM@4U6g9o72$oUilh9&mP>f7N?zRceswW-piU{f zvjnDT!|vU;z*2ex!28v@JU+{40>t);^V`u3JSnedj-o!myYMBqSvSCYUB#To2a>g* zyu@I~?c(To*UuJ8NGmTT<|1(_@o9;z!RUC4b-QaEA7nhd+YlYgG4gw$XFBSJryp-i zy)`R6*I*xSVLdQg^Qn9v)8j2Qn}sGF-Z|@((nH92pQ6J1c1nyd1#ePo;8HZaSxkie zV7&Q)T+*<|F5r&apY~?Qu8)1z$@F;Rf@stsp;Es5cX8rEg?Ie%pd}Q%MF7+{!;?*cyGx+bmt?$TMM7x>piXo z$;HQ;mDQoUw=ui;#JlV=;&LR;JzxEOUI=>spD)DqlWjZW&EEDPI-X8bOzSW?WhT|>Vt5^!u_b@-+FO+D~q1U3a%MiTY`uF@l9evIJt5DGYdr*1MgH?tQ z#eB7sP~lr!=X@IiWMgJD`t&)TWUTnO8D3(0 z)^1dQm)Na?H_v=5(}H@!6J1wzqI*!z{;5kp4T_1qNZelh%(s(&_{2^LCw;0Ee}mzc zSR$fB9V5RLc@Ls%Tj=+oqs~8G4@+ZvkeTb59rKQrGrb3;ETm0Gf&#A!{t9{i?@opH z{aNAU7o_3mEgyaFP(s7o!8D%S|ML~3>%w?T{}{dA0q_=5h^cQnO@I=K3%})*;Yl1n zyL+|+yno#pPlX$#Py#cNL=J?YClYGju zAL(a2yssiUOfm91v9qYmpND?DWvh-a(Q3wSkZ_XbQu-|~nI3Q4BHDB~?bx;{;r9jU zZd7>RtG}B`ac_35v=wN0i>!Q1-o4G^HYMXdoY^=k2O1>S$6uUT0}0SMJ?jN3#dwmW zZd=0^fcN#<^Cq7G-X`PO8VSI?J>C^e))k=R%^6X5vsa*m=!V2CCyr(s*`wpVaeVBv zrAG|Ix%UD@$5xE|*o&*z;Qj}@w{y%w4zHiYKHl=V|IE~dugli|zbX>`Q~zCY8g+b^ z`1xw=_v@|asPImHp!AM{_Z$@$MKrv7Sy__d2C2Acn7n%%Sj9#R1bEk*`Mg|ohX9qD zUsd?=3{TSA^(#de;GMD7S!fX8O=O+A^{!S6Tz7fe_RMQ^yiZSiCrO?!AwELl#3Sk? zn*MM>8t$VG=a2y74JSMh9dj}AYwxXzvA#jSdv|1Qzk2cp4gG)Q*SMa!cFaGV;2x$; zhvq98`QQEjSt`7f4rS$2@b-MZSpg02c1u<=-rSb|j`!Pt;Jq2aI}^cs$6iaj(o0%U zi%@%(%}?~%TjO#c!)A{X;(H`c<=Vvg*#z|Mt%G9S%~u!@?+=I$M~wWoaaeha^3snt z-!e$X%^usmU)_Ovw+{_6J>CU{8)?#U_xd)-`|{uZ|39^A{;&QX-@TD6R37wrnS2?= zgG8g))zCa>{nm?C@Dh7+?!ql_gM|Nb&CVJ$NG__cEAdVQ=*g+5Gei~w>DIUJ*1N$H zdp0~zw;3$4k;gr9^TM?tAypm6fK2oyHsfKP@!3m-L;)mjX@_=nvN?JMx#=mJQp)S= z3|B$sB04r> zrG6B{;k_Kuu^uBoHz7es{r&XgEh&5Vu~a_|6{JD=o#x${OpiD2Y#D7j>a3ork}Jqa z92MSah4VI3@YX7dQ$@o&vu^MtjQ5gIDKg&2dpBJo0KD7x>?p0?Lx4VOy1caOz>|K4 zd6(@1c)uL?=5GOb7nRwb-dU#wJ(>tzyHykY3(`Rm>$u}7A?pe1!I^O2{icbHEC?fJBaqA#cWAlaRcwhGC zp0B$*n&I5r3egdck>86D|MCyr^yAIG-hd?Giv4k-;wyv9J(XHa@7{VxchICGS}kn* zeHZd@;ye}J53NITDR^tF)?S5%_t4N{^6{4QH9N?7zfE3a=LPV#N?X{$YEFPe9aO(= zeTgS6{*{wy4Dh~HL9F-y@Lu>;&{L;M3u<653OvY#j(2cvY;EIE5wQ`8<2bdI__`Lo zIH@&yN?O{$cz8!5I$ALDJJMRYqD+{6yxGcFJ66^|$Ns2s`>Iptt{5;q-nggAH0ju# zQz#gA>2Lr4zuLF|r+ztTkT|G3DBIFj1@@rTU_knuJr0NFLB|v4Il>iWme^-&AA%d&N4ge4+K5nZAM?122)&qC>2af4j)O+i?HSPK9??@0uT!C3gG9lJ#hK zrwxqmhw+|nuOTn7BX=A_t^vI3-A$Lr9Vb9~V%c3=g$bmIEJ1Dffb_M@Nm+RQuPr#% z&ILY@cC2dZGhBwg#M%UWu-@uMBsw5*na{3p&Kf~qVw*Z99L2sf9^S_h9qkzTY06gX z$QRJR#HK!2`#m-QyMk;{?iuoVvzF=c?iQgiW@Wd9vUn1prTddaqeKa$@1b4a;N9EW z6VEQa2Y442Db|IY(t-*;8^2xYi;j1(`mmQv35l48#64E{k-;H=?%ogmr>gh2GalZr z5gi#A`I){Z6ltxb-@SKerrvUTLBq$19+hgVUuQD?fE4Hdf;Js5Vg`QC|08Ep;r+z? zj06R5?)24b(eNhaKe}E;fMO2* zw44R{e?f}|HxuAN6+xC6ZNP(YH`^840<@q_&HUR8|FFeg`t|AKsqs7_C2l&0cS-dE z^ey%_U-jF!j)gN^1zCmY=)uVEz3Pv(UU33+SCH1LtaOM1H0(k0S*fD;|B{MVvI_k2iIg~{ z{ma*HpFv+@7kE3yOTJ?~yq6(5gfa3<(=PR3JtRms-d5rn3ae?jL8|bQQ>^fn45r6> zYdUQ@Qev`h2Am@I|6Ejf=cNe;QSfeAIyM^(?^|2qJz%{3)$Wt=KD}z?_iTXot}mw* zpd$pxBYafwAi!HCjgSE!kiI?OHw!)>omF_B#U8kKP+8L(sXuIQ#VK<=Dibdt1|o55 zma{f04WZ+mpX6#`uNlE`?tKr@QG$`5TKS@0-B|kFyT08xAWagx|Mz^UH^<<>W2VO& z_kuPZ1F^&1PT&S9P@K%6!aLXd&}$0bUvR}NXn60PdgKG+EwILteEwf2N!G9s;LWG^ z>blTD0>n4D(D{cTf#iP1>Dxwt_ZPuQp)r8>`W(6IEZ4Q5b)`1zG&i8Tccb51{k_=* zL^UKX`#9T;DK_-t#CqZI_KbAK!@CpFaRehjIbpGu{&xED=KT`hu+R#-|1bA#t#~ef zhv^%nr$V&p_^>)|mD&?B-kel;=NR~pQ}EU-x;hID?+0FCXJNc$aiZkeTmPqZmRSJr z$=d3tTDAnp_u!kZ1mNCz2h2BU1H6r@`@RnYykB063oZg5C$g-T?cIM99q)DQ-Yeg1 zeMbDH`a4ektLM`5+tKl!vT*8h5@x*Ngf60Ew&kDmyKHz#+ggnN;$)y?yS!Ks4Tlq- zr?CW`%3ylDagS)!asTsjFUP;{|1o60|Iehr63a{FK_x7Tr4$d!uh5@|=0R$H-?zXX z^dtKPx&L1;ald#T_{1(}>Se{5^91O|=0P3@aR0v+&xg+kfCp(BM-RUM9<;X1V%xB( z7Q{i=D*m1a-Gg>7TjrUjokL_t;)s_ecZgS_SCDxJYDG_<3uU+p(h|{8gpprtL7I?c z9sNt}#ECw=)EOE)=$f^|WC` zgckJmKZiIg1*ES%OBK=X=XgUgAg4rF!GzVab7jg zb^7rxYN+s*>Zajt{@js;awP4BuByf2V46bG`u%^ z3!1}t-|+uTe%``}@8x#*2C2pUN=J^IB|xc-Y8D(5c+x($Km!86`z^1Y>T7^E*U8BT z_0d{TG*lX<^8g+1osy}G8%=YGF-V+ib}P%=Kj6K0q<2A>W*FnSH=^SpMt-)Ffi1>ld1@E_u z^ElD)4yfZMz<6K3ZcoO$e{4Zq62Mzv!I$jC;P#frsY{zrfZ>G5FRcSs0Pp&zHZIiw z?=sg0TZ_Y5P$(PZSOQggp#FX>#l%W?VxzZEEp(%`q_gh3q5k`KF z-FK%Plj(PFey+y-`p>Ypx7t0fKU6hMVEP8h)bkomIyT%@>=6J1Qc#?5Q{heAxRCsM z3p{%}z1)uj4Q~U#vBNOl=RW*)?^PM;p(z0G;4D`ALnjFk>zjVPWtg)&*|E21kq4?Pb5hbjxztZx3~i|>iD{>K>^g>fA9Zeg7q1A z&_XH?dcn2-CS{48mNDQ%^Pte93yfh8!gEV)gg=mOC}W=wzyDWiRF|dz8l+XvY-ELA z<4Jut-jFT=51MW{nVbMT$nJ1&iD$DWbULj%04I&^K}y^KV$Vggh$oOZ2Wv6EWv=Ka zNb5CA1b*0FWw;7b1<~;VBfl-BA*I3F=zoJ$GVuJ}SAN)MkZ{QZtAu*LmW&Tm@3UXk7Q2z7HOPGE@ z+A}MVCLLX^%5g8l$ao7-;awiPwwQwV&5i8~(C~inbF&_dch~g@^80_kPUn<&0le?# zOADui-P_`~3s{T_@TBCp(}|}5-XXzZK^XvVX`RhRwhfxl$saPod86nzNOe>a-VVw< zB|0N3x~=(eQ58I<5)hecEV}-2Wf(+_97m3@5IX zU3j|{od4f3Evq-@F`mSkV=-Z>2ybT?^tyaKbc2Q ziPw?1wG|}}n}49=J!|1eQS6=&hI8*bhz@p){2p5vX$)~pt8g=ZJ z0(b{&N1i_e@P5n_8L>VSPkQ6*cIyzpJ7R6>Kn1{CFI?ij?p`hEc`V<73(Dx*TLm4T zq#qS#6DyFoy*ljIWxk{L|DEF&Jgwr4H=HOzbo625cWT+y|HY_0==Go|H)V-+F0_3hcdb1-4Pcn>tsRsA|w}v)&-GM7e%@MnSRay}L zGPziS3AzW>H(3-vQOO|AN8}PxTNluoRmngDC2RGE-oy-IHWC*%=;7x36@7`#J8)6%pm7kx;XRD#D8a~YbJMJ1 zx&OiTRwG8%5(58cPa@g<~uP;175~0HTRhBUM25Gp0Y>|2= zh=%uV!A=9%z1g>flV6Y?V~@=(0C*ejx>&ryiU7?q;G0vMgD1tk4(ap*c+bqz9%i^wco*$$U9<_YRa<@3~ttllTaUOa68{?Cd9Wy!k)eoT!;*JiMa#Y zTk=!XHbtKP3erifC=i%|Z|?o~`*LB6!2O~>r|lKF{2WcL=P!uzFdk29q> z30rYj01fZ$HL|;5yki2n$asfk%x!)E@E)4+D3f<1K=FGmAFq3dC;2Hn!CwY=Crw)A z-T-*FT|TiZTuloS9$^#cT!D_a=BZO3_Qhrr`H;Brb8H&o1L%0`Np+;`%DBRC?yZC9 zFv7^stgMDx&7J<@+e}wp*7_GUx*6t$`y;2 zQt-BFI>C>I_qDT&$#~DN_;>J=|^51Njet$bYeF>yT-XG!W7SUiUAK_6Tjquet68E%QiMgP|E2_wIZ(=H{C zKJsDq@&81M)%+mmSTzk3q~rJ>>-$xie~CR$qYe?bYpZ^r|6fFfcU}2$cM9G@Bh%t& zcwb%QAq(UEy+4{fAmu(N#|=Mk*&p1gYEp}b-u9+0O+Esi*j*G;b^+jR8$a*{#=9zF z`{3?LO^BmZuj%UuI^I_NzoZZOJtodZ;=JnA@llcJ6=Y)j<^wpL0EWZc8qx6pBfqjH zmHgQc>Brkca6puA4h<8epm6;ZdlK{GeU&yHJiJwMS-&Spl2mxtdR}@;!CTI;LJSS> znA2}oz<68PPLPkch%b+BEdqGU@Ql_E4d5ZQ0=+RCdpzk&tD`xL_kvga+wK9pkL1+% zm``a!)_Mvq{sZWE^Dhfv4;y?;+>6A0A0OK!AB2u~h{eyy8x4$y_d-O+b&UM16`Osk zXXwX!uKJVN@*3C^BwaiC$E(D|nZEx&Y)P9AH#;#oDK~P1BteCDjpdOH3f}zM38H9t z7sUImh4G#|t4GFr%%HsN1HfBs#!8`N9s$Bv3eI;wiYFDXT>9xe!29`;wdFA0p`X_^ zuH(>xa=pYH+kc?rjbE$wZja>?Vg?d-l)Wo#ARZm>t*0-h)||M^aPGYy(P4y<_O>0(kS* z@K`TeuLX&RYx{}0qHk|$`%FUHN}mvgkhnI^v6if5=pQFqq>10PpUZf&H$6nhevJGM z+|0asM23F64fU2D@|uOcdyDhX2uy6yWd7o$hBh7NrZiH={@(xh&sL2we+K>k5-JaR z-&5#8@u1;wC0R5NTC?wL<1gSr-0!-!!RP;D z*_Ti^;6YVB>G=fyeZ zu8}K9St`7na@oZxc(Z+dae((yH+SD4ZUVGhY2`i0 z2v2gplcVne@Xji=&V|qaI|vX-Z)-K7)%e=v?t1hJQbRA~rRI@z;wmKWSnJnv4LkG- z@=d?@7uE#E!&@8C@eU(DOa1_FjV$`{-oBfQnEHi=PwZGeZq*Wh#PoRM#Awu^#crTuOgOp{%E3+0*L8=d$3X>Y}(ER7ZHx^jn zNh`w_2*Le7VW-<&xIsGGTvKy_UkiG}b2PB&9C`)$4Vv4XGVc-b6%uDF$u0PJDS8EY zqbJJYlC&Sgx%YQOM?6M;=87{fo?W0HZ`hkTLxp$44!(~Ryzlm0mO{f@)zF;_ZjctdP$J*n;{E;8tBU~d0rSolr|Wp=Sn;Gs z$d${Ez2GeMUXhbQsWPc zWzdV0hliE(d=waO_I3`@@fah&?i_Izt#JC?+wy36$~783PK+~s|7XmG{~uX_{$HNTgFZI$s{hM_Iz;8sJm^JDToYVDri*ElJ;?H|k7pfd zkX)j~GZq~pK%Ck;#ah2vk>ZNt^+U_fk5g^&!agE{Zc+!@TkY{lJ-;DQI2KWE>4dX1XrD#HGg{*}0kI?ZB z4(=p+K@W+lNZjc0q~vAF=y><5ew@6$*N5TojzDybVB~k9_LU5)A^muFXY^E=+@PWV z@A&qsVkPt6AdNdaLYofWk^tr36Qt!-c(=I_2^74=m**}+!+ZMnsTVNbj}rEhcW+gq zE{~=Iyw!`{e>9vSKr>5yZ@rYjllJ;$3c$O!+wkYMr2@Q{3O)*x?$U(%PdA7~>Y+DC zD`gjEjJG}{_EO>$zRmdH&>N(qd{w)MRg8!C8bpT+Mt*ETJNLK<(2sY;`C6H{&)6qO zaXu*vR1}sn{rn$iPn!;@kyq<~rIOuy85Q2GnuCHAy!UWiT8f5ulK;JDFy2Oo!wuo# z#7?%O#t{H-`AekvQ9cAnsdF=L;5u-$NRu5i{67;z6|HyTM!-g82Q~#$xv#Rvm4}kms?>+1+hVZ1%>oa=K0=%!R5qg*g@IF#^I$F9_6Pi45 z`Z6ycI^MISlH`wwr4h%FIJKg{q`X}8;sj^=_37>>jE6S|qJtA7ziPGhjSW)t<9#LB zOwn!%d-mq(uOG2gpZVwio=vpr7>qge0U!Oh|Nlp)&6q!e{(mKv2X&XO`NNH7FNRxU`w<;4 zF!G!KCc~s6iI?v4|9kiBtJzVG-T!-L@p$$5-DUdz-}449O*#(W_R$M@K&~K_sPOK( z_TXPz?9%g^mC*1ukX!NtUSjJ*LsVhB9cN0`xdOapzg~SRqYtjw^=&JB{nd)3cyik+ zc!_0Q%$AxC@XoV2+Tm%g32ikn+cZZA9q%0q->;B%r4Y9uaUG7&>ypgT@!sk0wnkXX zo8j;_LUdSQHV4z-xYs(&c*0>&t0EY($$qhzH30F64@Y%Jg#q(O0_ zNQHN&PT?>GZ%bDXMKrt{JHslmM;27EV&Gvmz;J zk4nI|x1?Boce)Mm_HT%_7AV$)Lh5E(mP(^HNSekQUTB=ZPrQo6P5uZOTk?m;i8S3D zck>7{-f%(((Xj<1zkYtG%$tLLycdq?)V)-|Zjf+S!;C&T%QAg&f|CiQNyoe;23xXz zKX0i(g?IbUjGq*|s|~dk(C`-HXl;Y>&J$cmzTP6Mdiur(fcFOW_;mAq1ZZ8Qi_hnF zE7Cs2YlYqb?-K9r8g~KS0dcBDxCu?@kz&=W)?{?N!@c?Dlq`5ae2By)6k8-UX`^p% zJ=L7K*6zu8cwa|!Jj2K@;w3r5+Kc*ZQJMlv?Bew&!%P#Jm@Ni!pd4Dp~)&sRt;#hy)s@C=b!!<~c5gmLO`Ne;n3Y48ge}i-(xG^qv3t)@MiM$7F}vn zWV{1K4puY+ydP(Le$!b39!M{JWwc?&id4(dzZrhsQgQx{u1bKn!^KO40}T)~9$cw2 zp^c8W{|-lqQ&1A|7ZPVFEF|c+0v&JPR&y@>Ii3uMcMzf@5F@|S*FA1}*3ggl$NLv< z*`;CQ%_VVl-jANeOy3|yBwnFOhse(dg8RW0JHWkFsPO*0NANBMZ?>;-s%Ut}cNdDl z?p=P%MGgt5dcsoB((`tpC*|?LvSK9|#A>OKmN{TT#gPR*Vh-3g%nE)4+iz@wM74ho85&v)ZE>e%_+aGGvAG z8ZiHF*QtK-4jpe+Wj)r_&^_W0Brc+@=}7rcboX9i9@f}%mhon99Egt982R-je_P_w zML*ti*^*U*v}w3|tNuq+CC@^p@BeWdf6}I7A%`b?_txM3|KB=o#{2rAC-pj)@r^h3*#-hQ&U0!;GH>nVJ4~{Ja3W8 ztt-)DMKWKtG0qa;t)a7Y?puI&#gGSo_%2Q8a)$eg{up$;ZOhb1x18=0Ly>;~%=<%XuFy2{jJe~^yyag|H z)EkWwpn8XaZ$Z6Qq}^wa9oz@-9`WJnssVW4d|r{(YOD#dN`1*QxP*@P!nfMB{Oxy% z^N=|8w}(XK2GHGmEL+N~OyoSn;Vq8nz~%foKS6D`ZIzt#yZ0KO;A2`#un$OkhIKCf ze)bvj<6YTClMdIP9I^|3!gzHwyu~@wBw+W}_`Hm~d&?>4_gWm_ zy|`S~F83D!GVY%<&wkvB^vDF=^v18PctP{I?-@@t9ta< zR4zC3OGM89psxJiO%)9qJhQ^$m2UUw=!# zdq)_R=5IH`zTQH^2s-rX7W035D{yHeO**_@?zm&~_x^vhnwGKt9Q6O2s61%mp@JOj zL2&=Cy3?E;&4bkTo+O_^>V0*d+#oGiOIf4@_8@nBQ8?K=a{7bfi(78?X4%(USsYX>@_a)z8Iy?^b;gDSK4$G zJXz~7|5+S7|JR_xdrXt~hJv^Lz|d?oyloTnf5Ldn4}Fz_@jkQnUgQOUx3}q~Z%Kg! zs4GQh;aIU1DRq#&)(YS)xGVlpHNe|t6H(K&7lL#jr8m52M6V#nZiu{)u}dIsrNkxO z2pStluOP3@(TG+KWIVioB0AzR@_YBIcVG`Y{q8O7%Of))gx&wo&EOFuvS~6s-aiUy z(~)Q;=C}C*`FP6)D!jih9{onaoA|DZ1r6_$9))w^{+}ynND{`|NxAD#KEPW}??F*$ z8UZ@!kB{gmvLZFyTUcWO@O~Oilzs>B=CuqAYi)+0sFv)3tXy=wTX*EC?|GF#yotnZ zOTVk>ScQ)FkGG~{OGVun&b>Pj9kbv4IlrIh`nNsVNdNAwtj$A1+j{KdEja#*tQ;v2 z)8ma(rcFnD=$!R-G34T8Jr&*~pGqbuc(?cl&qBl7YTR`ZjQ2WU#YHgQiSm~u7J%)o zUpr00-n9~-bnS`H=bl@UBrdjVnFGA_-uH+%0=(bL2lPcLYC^*`iHEE7(TkHW&h_@Q zqV5pKkhoVY(pxu0qwn7S47(_H3u3(4+X$kAHT=){&FedAcA}JiyxG~#>=GNrKHf5_ zLTH%HR>AbMx0c9#H0h`qs}wc^cW?il|1(yr|KDZk58w*&Dm&+L*n@0ei>Scw|1~U`aoNTPuGl%XMEZ^>o}^uIe8L`h(0%A)b|LT} z`HXONHWy8ZtCj2G(;)Qz-{8UdTjmGiiSv-SA5R;Uy_TbYgG7uoF!8>1hT)c2V?;+8 zMt=9W_Tm;ip}&GOH}FiwzsIg1aTU&+PVxpYfB!#qk|rH#i$i_X)5uG#HWl8}_TH~3 zOYFv{LUYmZKD3IE4dZ>M!jU{6l{6CW$p(0@?=$&&O_BiZdp_@60}Gy%UAD{=#v9ty zf4&IdeO_lb*W+WFP_$q`fB7+Vyie&ptBQXTPmDq0Zi#oOTk@mhy|~hedp*A^!{P0U z=#ay|Ht-Mi0=Bcv7J?KWN`F0g_C*_a-8uIaWS#Vd%U z+5x;9Lo;_21H3yb?9P5W0`Ts9@2I#79q;$&Z0f(W-6qB$aW{ln?N`r2$9wDd1J8E{ zG9KP-hz=u+{JMr4Hcutc@7`A(Q`$DD(cs>}6Gx+b*q9z~+!NY#EcbFUb_O>{gW^P! z3h$r%N#zv0vwmf8qTwxRDOm&K{q5X5GTw>DmoDZ7{r^$U^!tZ45ujHqb|2qeW<}bo zxElxKt*0|BRRZu{XEP*R>!b`yYHBl7EJcx7y%jiswRQrY}x7j*Qc!WBAGF+QVna z?hR4lJ=wg!o`N^&wI2r>-ig~6k@4PP^6z*%Ab3~(1Me*e-p_R3-@dp=6S{G#Nqpig zdjCJWSvUBbC2(&fZq~%=jG}kw{r>~ghKJQ`jE6S|qT>lhe%YM*5iREQyZ7m9^Br=Z zVIObt{B=Q2WU~&_d3a| zL-U}1^O0nDiH%Y?MLz$p;R1ygfC_To}gEWok z(8tJcam|_Ay3X`_&`3Vv>P2DfB^GzKvtVncGt+wzF29>59V|!t+E(uLg)7J{RCv#J zp7y5TotMndi-z~gJevd&9wl8ElFp>LPI?HXZMeccah$>jz|hCR8yV z-VKP3HjMn@;{~EU{s$MNmGkIS32(s0drW!#u|U}&rpH?`dJ|1La-u^D-(DtHka|>j zvnby#q~P5x*s=f(Z^@e}F)-e9&Ki&#r2ER%m0p$Y5ZTCCeo^azy2ew%> z9Rqlu+~RNb4B&m^z2Sm#9Z*45%a$c7q2nF*^1g$M8_NY z@}F@sqteUt15zm&XPR`_ww-fJ z4JPBQ`(Jn~&QweIQtm#&Y-BP9;~idX(UH0dTuwYxsmjBSj`!}mEh*^&@kD(jE?HjwS7IbO z-WU7JJHuBp-t5f`(Qz3gKduLg$}Lm$<9$SSD%W{}hHr0&3Ys-J$C(~)TuKpbI*RYl zTlV++e@5%{|NDGEgJkeu9<+k%?(AHO2i>}~Lm1727DmMQz#jDT-g@^V+3D9~D)Erxj-}%BUs{p27`v=I2k=g>y^{|=v11$T{Y_j#6MFyQ>h5j4=y)sG z`h^WC#Soj3xYGT4Blvi9ywlpECnus94{s$zM;1nYmG6#n2>cJO*sg@D@5@Z)lN@hZM8YGIQ@+kv7-)a-RWs$MydRc>?f`)LOoMmbfO=_d0IR!CB~d z`!qFwQ!a@i_9Jm~`AU<9E~Dc;eRkE$`q?fF=idH^4z_cD&QFu~zT%BV^t<%qvO5#<>$p$tYe9;NZb*Ju{6#^biCgYcb(Qf#dvscLv*xa>1IC28u&9|{#E(hR!N<@9? zzNjX2(DK9k`c6~SySKzb7u0u8#u9CiIM33Wa`}Vkcy~=jo_*cPcz7>DbPQtT_j8-c zlIi>O<1M5b$Hqg;(USed5`KJB78^ppf@~nvd@L0h!>E!w6ite`cD19gQ^m?q~eb= zTm?zd(T$N`?yTS~*^TsngS02hLR*)H2@-DO{x$i%``MUeg+c}A;{o1=(T~Ge!RG*9e5*r;`YS*guE#Xnbek6|5Znsj689Lr9++#M9 zIgE$5Dx!lGBR|9ZCB>?u^e?g6Y%{Kr^4Ja1;jo2AZE@vHkGGu8a+-APP;hCE{XIc4 zrowx^m^?oP@6wJ6F*LmUAGz4Tc1T{?+-2LoEC^C?nmMpTs|DY?Lxz9V;>NbIZ4S=!K^rZ{aBkv&zpjOpx4s%e_Xx)uqh-&lexsbm-P6to(g@ zs}U96^Lj)KDR|qSxF(8*ci^urM`674Hdv7H_V;mCI0x`ftVmE?-gnZP$ainuh&@;Y&;P9mCxVl{;~|Hy-6w^9 zS&_2s6{I}@-q&Vtb590%-&flsL+FB_>r3C;@@JvDcd?$?@ldfF#A`_0fGyW@twrc~ zD`aLaKUd3mc$XqNR$}BQQ7>dI^gnR#z3*);LD z|7Vh=8hDU7l?N?6d;eb(q))y}WzjrHT-jR?_Mq&~bClsNc7AK`SuvnN;<8;XeL@Ia zv3sUH@;$g9-Li1DBwRthm)QCgt{~^0^Gfzk0u`k4!y`#m=pHmMobD&u6iM8V#Jyc} zMl^2&x(8WQX6|eBbYi#)lA^;3Bfp;bac*ZP`ul$__YfI}A?yYTC*F00o6Vm2E69DH zY0^=CsO9z1RPqvQMuoSa{&YNLi5-&rA%lkZi&*8QFy1QRt}9@?9Sf?tG6CKK%K zd&w* zmL))@+#5J&U9lpSXuRU_2YBB)Q!N1R-ab_iZ2Eo|f;czYr_Rej$GgW=)G#OW8j&4| zOaAPziBA|E?{~IJZFzXc!<(X`0VBWhIfJK3!}Q~Q{XuEg^m7_2$OtDkj>Jl)#~bJG zNSltyW%aLr_y4=8@a7k*wWHv@rLSBH4exIiE&4Ft(`nbq!wF{#T-z*gL7F+o)cZFu%a#zxXHg9n;{G5nB|JQYXndYi^ov4k( z#jNb}E?ABJapL875i|3$7!PlXjw=}XMGNoqO6sB??^m2`eNHXdx3}PAU*WQ1TA05< z`qWO7j&u1rc2^Gt!TtX(D!h3gZB?b<9XrQr5gOj2igS0ucw3)7NXGkul5G|2-s^1V z?|8e60IgWtGk<}L6-jl?ueY#!6DQkO-Gtp+X5fY!nitb0 zr-27m$}U+8SCFv-Vh>G#2d(svVTT66`Tvk=^X@`$LHehxlW_mvBJOGj_y3=gh;9*q z5TrQZA06=ty@HfAciCdt6;51%#BGhVk&oDe?m;IHxO5voI?8Yj(o#f+D@J}l1HO%^ z%+SBY&iyjQ_9Gj6iyfDD_GCS2lKGd|^RBe%Sg0pbY(suxXD=1rV%yvnQ1IT<*Sj1I z?~mX7dtkg169{TB-t5s14VD0JJIey%uQ5C{=S|>i=_V^uf6gAoivaHx@^iZG0KDhA z+&Gik2tkc=cw_=}(3e>V!MK9)@E$>QWMbrJ zzxnP)(XI4XkUa)|M%BL94bpgB_@M*FBTSEXUMg)m%v~Kn+Jg!b6eku`cni0(JfYw{ zIu@`L4e##7W#cg3s?|ZOVZ7_|-|syG@ZP)6c3vDe0lE=>YDt9pA+}dyNtQ;ZsMji<8`uAG77GYnZ+`iK+NWla8r(_iGRrR;1bLUo_$4 zExC`vdf?+N&F2jG7g|8jcE^PdCmhjhZ|Rv2d5$L{iTX&~4ZXN|lG*5Zx6g!%)eSHn z-V_~O82KH{AM+4+Npb1j|YOFycETPKmR_FyuSB z2W^tK*x}A=&u~ku8=^xSBfo|?-Qa_*^m`Cww1&gQkA?|SNLsr?HXGAdkhn}5bv)#= zQ2jkYvZlgYdcBDxWr?le>rq0(d(Dz>EpP?N;ZsOnVmVYZ#=8LCI#sVCaF6hiYQXtr z^5Isbw8-t;0RV5Cx951^Ep|64`*GWF2zr-xz&}qCy+O)0Z_@ec4Dd$c963fdb|s-V zNDn6XDnhR_9^N^Kjz<{zJ(1?R@GG2typ5MB_o?O6aJ>bqQrmIyQ0B*5f;Jsf8uR_c zACoIc0u|m;xIrfh-h@{VR-oan$?ww$UQE<4< zH7k;DzW7i0>#dKmD~#az|FP_&nnwWM^SQ3R`N@Zl_pvLhKaac)BU0j&RX_EuypE1{ z->(gUa~3%;oO?SVI)*Uv+b>si?6?{I{r~cP!Ai%wu<>5*6Ce^-JI(ZXPXyAYW1DwI-2!+=x-1HHih-cg>|oBFf52O8CTO9RVmOf!m!ICYsp%Rz z-qRvi>K-LB9^Mj&j@hDr&TrkZkU)mFu$yz7T} zY0`0Z<4RrCxC?*h|NnQl&3JzT`v1dJ9<%l`lmVr;;Cw5Zpr_Tff50V@-(1-*cw3n5|y6*iZD8X>`_#G$o z{$I*u;*7<-5aJyqZvCq8GTBGy{r_^a+W}UxwhUK6QgkR{zW>ACn}^l3hyDLsb9*&wq>(g|1{F;!B1sdaQoG$C2}w$tG-yyFjVd82C5cEf zWpAPkkxFPFrBDf>LPfu|wzZyXU+4F%v-W=e+WUK*^Upc&uDk2H-_FbZ`P`prIhe^p zc%S1vS1I@mYLIlU9k9LOL2Z9GUUnG5d$aiG<+%{vpRZPXh2J*=N1n?F`>nyo`=rBM zS4EEu3L1ClgPq!iC~UmNGOrNZ@>vh>BE*LzPJVswcYd6EmwCL^wT)tr1NcKM;nD`z zfQbJGK5yB@pbxIZ*E)Zfw|wdFUhsAE1{CkrZH0PRc!^Znu_qtgA z>I@1RckA4ya)Y3D<@u z<$NUA|NDQPjQL3MJN4bYoVL8Ri4Je&XXZyxyf5Dg(Z#}Bz-0UlJUQ98wwQ+ZMhQ3l zb_j37byKUC7m>ki(Y8)fp$FB@Q0(g=2yfkjZ`<-AyhVRJZSw{}(B!z)ud5x{cx&v= z1}2G_6g19JG@Y7if!!bhxjCV`vsn-Cg@_MfocsbcElM{ViQ;c`{$qLzef?Q^BS#bN z?=4df5}pW8WP7|vS2E_~jlI^$$!OZ~79Tpi=NC8p&)j?K!gV@Wc-!6)c?;wHX~Pih za^iL4@Qf-5Z{L)nB9}BW=+HDYxbmW9zT^sOvcy>}x%igEJenXm9{$7$xPcSFgd zSpy&NCnvRivHnUv(`?`WJ4?qgxsF;?&CZOrQpdH!WSN9oqljbjil?9JE0idIzx2f@;v) z4=*^gpc-_4yrxlD9t0OH{~`P57j_LASnRwyp)!rK7>P^pkg!FWGPDxF;<1cE0XJ<9Ov#K!yO$X0>?v=Dz1iOb#KAT6>S8}HbZ zBlEvDvmV~h5g+k5`R$wXD3QIy{197dS=HP28Gne4OTB2G5X=7ke_Z}0hJ0Lje|)LK zNm_%nl@4#s&)-K-yoZ0~EyKe5MxoqO7;pEL3N*au+V^N$KzN^DeaYoxI~k+~eRn-` z)q@%<-S;yC!W%qO5S0z%EitY+z8`9k9xo`G*p0pa&uQ&bqSbMjVv59_UE#L3QULpc zbj0!V8yrpjSgv}{LVWDS$#4GH^-kgc!~Or_2Ntc3;rP{?kY-jNAISda{|WVs`ItV& ztpd*73!ne@r^8$0PDnf&^X?AQg^LZ zW8?k8)h*rU66@g|h5EqB&oQK~d~Xx;lapr&j{_6+@caLZizQF1-I-zg25Itu6hl7h zZ`YHS1mwebZ=u6meSb(eTD|Z8(J{oryIS3_%%YMpzU_H84B3f1<~r9?6{HM*(R6I&n+TmbaRXTu<(U@b)u&H#>R<86=qA{U!9)gX;4DTnO*~Z)S#a0Ej>5+=-z$$yu(0_pJ9 z>G`w{#e3P@QBEwpJDi4^;Qs&jimx=hCFD=1G(&hBD2Sxb1d%~;0m`=J)gIKd5lfrl z2FW43|2f?Mo4Q-aN3I0H5Q7hqg$~$wpRE9@oOlmW!jL$r&nZ8(2C(stHoCsAR^ON9 zs&^UUBNivW(E{V=8@idV-cq@*;$x39FoTpHh}FF|&h~f{%oy|W;(Q{}`|tA>JLvG% zK6lv>#e2h*TO3$;_sPxNqb+YO@7ID?Z@Z5B4jDrIf6qnZChbr%xK^(&Tp_}PdSl+< zgV_+?PDX8~G9bKf+;}k<;sSzxpD!%y_Qb~fgyOG7EAtOgwjyy$#N;er|H8(bv?j7c ztC02ZK8E-p`0w%8@|W`$@E_uj;Sb{X;dkP< zXc)s0yetfQc)_f*>T6~IpVtib@6TE}G zUA&KZDZCeXi+OW+_w$DHZsR5K+VPt6>hdb{O7imYO!AEI^zgLs)brHvl=0;Ar1I?L z3FPtOSPAVxGT7ib06l8;|}Kb<#y(_;x^)5$Suz; z!p*@o#`T`7gXA<;ya|x#kr!*&#W18bLM=wVk$32c(j&hCyjzb(V96=mD98MgT z97{PgIAl45gue+72)_`1Abdl(Qn*k!LpWY|x3HhEtFX1OiLjQiqOh1Sm(YaJpir04 zVPlNJ4f(=0dtc%0iMte1emLBZ57GErRueHG*Y=`GTo}dj$gp zy#&__t`sy7R1=&dC?N1hU{v6(K)XPrz%_vif#U*)1>yvP1$+gZ1*`;&1QrU&H#L83 zMW^(FoID&-4|gnTmfofU>_XM!F4^Zm5USvKU?-{`?KXM=1fuGp-Oeyz2dW+{Iw%bU zpsH~=cN*A^s)mcEQNT7--HYS<4s1o$-3>P~0Dn}~t82^$wxH_v=p|dg4^`ABBIkh3 zsG=M?-wXJn>Xz4T5nvOl>NE$J0Y0d@F}d>~;Ek&5ZM8vw7pku1wDSX=sJgo4=^22G zs#+ah55NOeHGl3J10+;k{&2Dsa7R`3asT>%kFWJv=XQFU>h_+`KqRaL_K#Q_&o zo$q_v1306q^4!8UU<0boMcsTCs*}eaI|A0IDs=0P2G*eJ zg#HmvzzS8z1>Y+Jt5H?(K&BP2MAgxghPA*dRON3zr3I`+Ri4SI{eT6ka)~_?zzS65 zJUy=oEJsy#34cCdj;gHC$u0myRi+iF2biHMLpVYQFh$kju7DkY398a=?w?hs)M$~a$p&%Qsq?)fTgHP8ED!E7@{h<#y$lwK-K=NCpmyVs*+q&I)EjpN|g6j z2lP-C|9R;LKo?c}8Y52tI;e_E6O{+FQ5EY+lm-@~D#m!k2hc**-k&o&fkmi_>Wo(d z7NRQh#J*dACaNN~G_(U6s0v@}b_P&KRT$@j*MJ(TLfht80;;ImUG~rfP(fA5?v-l5 z0#pTC8O{L8sM;kYVh7Ae)z04SIlw$r1=cK=1e8#&oD55H06X6=5fU51%pUwgD zsMM4g5a>;;16?0QZ5}s3NtPE(gR=<$fY|KOl-Kx9Dw00TEPf zTHv-^5l~sD6 zCol_Dt2cb20t8f9Dw_8aXHd0jmXA8|52`F$X2}wNqiRLg_cO$4R4w-zP9sjC%3QC= znK+3mkXN;p_zP904~qneKT%~;*jPaPfhyxIGqZ^ks4~(oH6o6qY8jC9hB$^Q!}ixz z#P6swxS7aJ{Dvz12=x@=S5(34?Zi=3!ON4xFQ|f7bBLc&1vkIMPpE=>1>y**;8T0V zkEntVIT43Z1)m8a4xtL(LMINQ3f^%fen1s`_mB7_HWL`}qY8fI zlGueR_)$P&C#v8#)QBCZg1=@&e2FUf<1fS)sDi(hL41xX_|pQ!c2vPHu@j%63jQWC zu?vViT%( zCYFm4AE65VDm?Kas<O=~vegr*qB;G>R zggNCYu@0L1$)fYWfBqYZ)S7qMOC7j|Dy6-X1mG&F6m2z=fm&24EWWi3xPmIV!Ck&U z4XR|X&)E!IM%CO@*&jePs^&Oy9|SI;O2));H*gVEQr~q`fhtr<-U$ML3#gJf(i{Vv zN0s>IH)TL2s%Ebe)dtR?O7u5W=POVp(ljp*IEyObVmE7`992SoTY7;rs1h{0=L3|X zN`Q-050s*c*tx9|IE^a)%F$w=1XX+?wZT9!s(9T#O#r7*#UsLN1Qel)t54}Ra1vFV z*A}b=3Q@(8SojAxfvQ=qVky9JR1p-W9s$P?wdl{scqyO&RljQwy#tP-YWhHRAdru$ zDYsRfKpv_lAN1XVv;I4yx3R83?B>H*oP8sB_1@1DUA$ zHlv&dWT5Kn`<|CTI;uts{ulsa(G!FK`G|pSa4ifP<*|*frn+q@rrL zGS&<@fU2Q_%&kBQss_!SPXfuP`k**h57>{YcVF~vfh1H7T;@CnB%-Q6)#@OSfU37^ z{7Qg$RQ1g@9Rc>C>diNg79b8)JvSrmfLK($&PvY#Vo>$UyRHC;MpgF$&RSqEsye6M zH~>+o>Znh+3`C;pW!`FWAOck{HW}Xo!cp~He~u0ihN^a8$tPeBs@h(Neg#5N)mrjp z0@#hJmJt2pKnSXyF70^%1Pelc<+*2-5(JfqD|k0?B|`uC-#@JOCjjmLhtjPocSv>8K1au!E$({#QmF7u(}aFlErk;h^uWe@|}( z)8P#-q@Z|vq*M5?@D5n9XaKI>wxauKcs~VPyH`MXmqnOY{Pre;Jy)96CCHJf)8(G? zVZ7JGyRL%qw$f`hU+iNB#=q9AK4FWEw*{Ai##8SDltd(Mv0U4n;7Dw|b+}~juCw)F zxyi|L#D^YEevY%L>t(B$$9vTtYO6mO;zf?*V61Qu}urcFb?%syzyt=K) z&w7UwPa;0{;N&Nj5Es>~$^7J`VAh%APp&fX_IB=^S9xLVf4qf|Eyb7*LtZca|K9&+ zwNC$k&j;%NBk5`oyf=c@phsRS#jt9S&?D1}a1FZL*GqdKoe*_5Q55>bZiV?sn(A>f zDEaVcJ80%X@oe4UIa7T&kI#p+yV|B0PLJpC#& zI_y7#v>NVX$cIRN&FziZG`z#<@P>D^6?f~g4icW3mM@(780CR-C$ybt>X>EgNd{CY-SELXizA6hv1DQxLE%Kejhyz~7(CCm58QS}W-~U_HSyupGPF$tEUq;Fc1iLSG=K1ww<831= zv1Q=veo7A#Cve*Ji2Vla%ZYDDr-~0BWIeq9#|KV+y${A*2FxXyo}73L7rxamc#8Xb zAB)$j?3wz;_IT%|Fy`Z~&;1S58-?)w|2=eg!{>`oypJ_S2x8&w>smOLenRPQ|Y`JSi`maQGPG> za{EC&>)mwoe?vyahdU%r%A9(q3$aDGexG~@Vx5(H_TgKzR z-s&eyaa#Q@jP2*%)gg5Z`S4mp9C`$8PW-q3|G&4~EcH{U2F23VAozqOT7!uriAT4Y37Bt`dgtkwKS}WX?eg=mzP=>(AjkNK;+sgWx+z z7sj}ENh^ckrMd6ZqC2sN*oy;u4ucC5DYZ!4_Cz1oG8^n6wnF)a4?)_4#(WH@I8;Q@Hb`UW@P>~Jqj>*p zvZ)7EJ@|vp5eV-mza>fz zLwJ{aRwjQcFaxX4mYn$^f{k}hdD?H$BZ-u&NF3;-yX!#$_7Hpj@#?PmRjh}1HsYfm zCqKQ!%r4n7<{P9@s^>)V75wEb4X4o`F9Yn@9&c;eFAVvxJ2IGB5J&6(qv`O5&%mR2 zhtBSlz`|SD&an!{JJcdf53b&4ES%?cKzK*q`4}R1nGAL~#wKkx@SwhoaV^b*@Xq1M zyKxZ0`(@W`Y4=hy@N)6T7NP_;-iFzc1wMZgDc6y>ZsSY0M-O1*EjTxPV#<=ta@8C4 z!H<)l(PN9I9iN!T`+BmzwefNW`u{%;4~}`UKi-6T27TBJnHv24yv1HRyx~h7DBg7^ z3dOPTZri%C6vq2D*t!J9d$P?@Ybmrjp?v;ZIp0NPT*Jn@H`(Ru;HD%>1`;QJ#*H zc6l5;8w>BwK?h9r=cNskI9DeBTr4iWtXldT{Oe4 zL1EFv^QW)wqnIFZkz+R&ydz<6kgD{loIR4Zk>zHPp@E#9hqo!>gAXUatFw8Y8=qhv z@7^md%QX4%hgib;j*DFrscb*Q5?tFE^3ir#E%!+^-2dlt(BTc=q(||V=e|D|3-1Pp zedl1jdm|$aV7yOPlU6oDc!!Ew$hSNtgEz)xRs?EzQ15IKu!VP!!p(^y@D7sH?EHud zc{9)oxUzznkB#@9=(9W4gv3*9k+^T)W3OK9#KzlSVErYv)Rt+h~S-gr;Q4I~}3nJ&O)+_-P0fZ>3#DbFlE1 z3|GAcb>=wf#ofujKB+J?2k9${b9y@#149@|DBu==B6H;WN@B__HENO9@OT@sC4-C)_H>U%JAnc>?hVr zwi|-rh{PuY^%?Btt@@qb-p}tPP`)8?Wp}iQNq*SNTN*C@zuv}^SPpO0hbm5fQ5Q{= z9Lkx;Tm0v>6-DpxFDDYT4x3a-_p*KUCS<2EjBm zYfoqmitbWU#;QR|-UnjfA=cFD6|MibtDPMRKs6{TgVcFb)e}s0kDYP@J*eQ%4~6g- zq<5YdNQJ*39kzVFMo)+tXmdSaeW^8e4VvRJ?|P|A9K`{N+v4FKak&|L4N`iYrZ0Dv z3(M6Y3B-pOPJR-D5j7&V%-5jnTkYONti^ATDx1plUut->eGS^~UdE6Q5C~kHd5kuL zyjF>F|c%<3sUw@1ZDR;jI`*jDzux@bWQ(@!lo9Sm_>wxBoR={okWxkpH#G`6+05 zYkh2fMF6x&CULE<8&3Ar6b*my7e z;5)1PBBC|%R59n->^O2e<~RB@namk zw=xSpy_L&Dhd2DdB#QT-QnDfz-hRnTXn0$6n1e9h$8t8t9fI(tW_oI+KOuu;^J2dn zJRa1r3JHxk2=C&albvTEycfGIbao0e1AWZe+c)W8$xAab2 zdSL3gkJ63AnRTmvew~TEymfoBuWPOl>*1}9__&Fa-}9C6zP2Rh@vb^KHR7@b|8Qc^ zzBwY)Jzv-!@5Ab|8S+8eT{GFg_rLz1CHwtrOq=&YHBy{_6YJs+%xzQ7`Z%LVCaOJP#(*D~#sN>H3XL6t+_PM3snsjK0O;WGj z$Ds~Av6DGGPe>elh%HkwH};T?rtC-JMh0!Os^hSS*qx%wzdHVLVz~yX2=TEMC%=ZJ z@`~y?%-5jsvQI%>!uUgMApgw9`qTDoKZ87EJIRobMUHD%Y13Yi$`z!;8-4^G#XDtu zPz?)jCyBjLFy2iB+okXfG6&38nt|}1R(=q5sS&zj=U^PFnsNz=>-Bi#JkJjs??m^rwGsO^upHi@h>sYY z{F-n1cpmx4Jl>75{kL9SV_*j<$4Sai&6(}-CKRn_%tt_)iN@a@Bmp|S;aB}pyj#9i zt774OHbZnTjQ5$TF52;y#-49u@lbDD6nx36&hJI?fLnfSq|?!#77%W zejnFg&c9I4Jl>nWwqCezz`zbtv)QT+qi*)cTLfgthwhB+r1U9Tg9Omw4S%Kr#XCLX zfC?7gk<><7_14^*X$)8Ik;lqr@b~}LuPyl|;@}CoRixLPb@iZHDP~u}c&~aK(3A$@ z{iXhwA$&o)p`dhm=Xq?r6;Es|9A6nrd4$B}Zwl!JTLpYerFjDjadf32OAHn;KsbVObG9evl}zA zAiT$Sc18fn(A;}#P>}jgY`mqYnsa)7#8UPnaf{Eciwh!P+QV>AwFbq z@_Q@dyM5*>^VK_`(|mZz75u%oxX5Zfz;=S|@s5kVz>trgo$X4u3;*l?|JiD@q=x$c z*>p7s{_+%BgA8-TwXteYC1(O{h!v5tq#dzaO{5$)ff}Tn#Neq8elqxHaR0&r=mn`a z+7c(>`~TlFj|{{2|8=~tMUHxzfyC5jxm}sqHE5yYz^daF5fniruE{{nX}ctL4dT~( zDYP$sJe@YF-Tky~eEiAmBZ21!b53w>H?`e1|yKtszLwEx+JmUN?p0r5eu&-l?YNhF9RBkb#i2UQZp&KP9`7|zv>EcD_Nr#) z-G15(Qj`vF_}hRe-YfOaEyBXv>z7nGjCcLFJlg$#i(KUfMF?-Dbn{&s)yUw)?^&Jm z13jn@6uDDjyi3)7-i4pHwEJp*Rql-`IG@;ksNxa!4wB1kSIR2>D2gf)S2%d(YnBZ5 z@)ob}vz_EvN0zJJj);$0IQeO}Jq+3mFpu{}iCy=#{P1^>Zq$0X%YVDg_IPtnkQnkY z_OUknNeQibi_qZ>f9w*)dt`pxLM*)fO8P=!ybEu+&@M<9XWY{SAiUM5UzG@(K+jvW z94Yn)_MqB~%JRaiw-v4j7QlG(9^Ng#Z^9IeBfR{%s}CFRjm1BOmG4AR5|Ow#-WKb3)j!@u1~=T3 z)2@K3x7W7=8(_SB54qof_ufJ^UM;aSHUk}&dEc62h&?&s|L$-pfBRmF6B5_klT`ow zA~xO|3bysXj$u8#xeyUSQi8G2Ap%rZBE@m@41wFt)B<4l8S|6Wt@R3iT#?j-CP zWQNkSt5=KmP);LpqF%!8@2_CvecE7j&*60rEQfa{;-d&Bzx&&+9bSCo|FFE}5o=?) z1b+v~MpUo#gYrYR$NSLM#SHm4Bdc8gJc-u-OVZ)(eKbi5#ryuH5@+8p7K<_}-HtVKS(<#_02U==IiXMQ66ac!wSOycNbf$h!Ix&vsMLzU|ej zZXayCU)qJg0*%8c>ybGAZj;;}`?2wUfAfIUpWCd5H|papPJT+KvKljbnXlf1`HLMg zrtnX15v(PmtHqzPJ>G;y#(X4SYB;^4m{z?d=8bF04l-z!zDVW_^z|0)S^IKfyx)W->%e&5k<9)sxziLBw?8E% z{vT1iS8=S?!NPk)p_+Dj z%l>x_?d|Qa-3PcWA-tQYzH6I*dw>9M{XuT%aN_X%tJ?71TS3-%2)zG)>bbqohe=Z~ zaz~pY8H(NiCv|=bECyI_b7BMHBMv9OrnTW(Ykx40 zcjVMNqu(DHIGk9+`@U&jJ^T0n6{3v!xGR5N3tHa#@BP1jHrp(yq5fZvt_E!#+7SuY zAj5ujKM_uE0#*&W_TFj*yu>aLAVfR=Uo$Cu%nmw1`di%SRJ0)(ET8%|wfQ}Xsv%K6 zc>=0I`3J{>5}_ItYh4nitpwGeuVcsEmS7LDt0e~}haeNPN(R01?#Z?4Dw(iV?GWa*tF>H z61yxN-u^eQ#-T&({LuSGSa=7$5ORX?=99fd+yB2Rw5CBH!n>w0V_wt}GH717&LZ*$ ziTZi$LDNwPZ>tgO9S0!1Gxx;pb-!y0nkf~(o&>O$*q;#JF$mY zx$*PQd6R5e4)1ovha^sZ&31F#VqyRSN;ENLPB43c1O9kE@B!v1(`tYyfDS@G9O zp>o;`axNX-TaqIF=YVuyUdA#kyp?}8Y=QBXbNfx}|3kMZYD++Pzo?mx7}X|&9^3nF z|QuwDl1XR?)gHVGsFDkm{ z%0e=j@Jwb;;d~Ej6!54YejtrX-O2|)kQUPk$_lref*0m4EIINoUvCkfmcM#uTPUR( ziM#bHFFkb+cJ&VXTGSvizSoxiX6Ef<Ukfdb@@U>W8h&oIXyXYN_cTD}#nu z)q$NlkD&h`N8u*7;n*0Utbt+iYMQ zF46jbMLN89B)$Vsyge?Babn?p@(q_fjCb7GG8*3H+c$?Cfbc%YZ`f4ew3Y<5FWGy!qZ8zH-u>48B@t^ToH0 zMEz-ZSQy5;(BfwcjJKeyqH(}+6Yw%&K&Lhj8*lRZ^R{F{2&Ec{%MvX)v1uzd-opwV zb5{7TWx2_T7vkd`PJYi_ohPmfG2bBN-c79ka}U4&Cm1I193M4d`{gad55|1(1f{<) zf-Xoyb8mS%ythk#I)~z2P@Fak3vcI%aUB@%8g)(D>n-L+>FPcZ-mBGgP}mQl+awp>1<4(HcZpYbAhHgVrn-pO}VfP>za(IlRPf zyQpB&6RJT2q2e`hj%2W1GpH%npF|Z^KVu7jVs}Dm*H8EpyQka=*NhjKfc3LAj8?qH z9%B0s%{McM45FZM85Wy~OB=C=*o)b!Mt=8Jv)m9nfcU`6Z{A6>3wK+YpF!?(on=Q> z#6KXt&_+1r)hrISuR$lr_!;tHIsM3c-rob#Ds*`7E_-N#;(atp2Ef95sq?4bFy3N= zF|;Rk4Y+LcwnBIp#`<(itS5s33k1Vdcaf+M(tJVqc*~plszFH*-qlujzQ{(HfR3Hx z4l$+Jc&mtPo3o-Jh=Rub88OV<5P^;N{8gtWPH9`Q9Nwyk58V7XE+6|zWFBvocE5MW zdl_humYdIV8VA@OZ^Er*4EfmgWAa098Epo+fDZ4F-7D2lybZ3r=f}cZT5S#wJcHC3 z=%T&2jM;BF&tvC-2`kp zr)v>#02}Y?RXgwf5!*#U<6c>(z35txjdz;Etr|)Z>*0L^@qw3L*_@#?XGiAorYv;j zJ@f~^LFx|>Pgbc2W_!GyR7Du_G5T_#WeB=K3QbOw>F^G=GMqv2UYA_UhlTfcpHd+h z?_HoO4R5Kl{ZEr1yyGVA`J?T~VBF`=KP8e$RGX!bB1#~I=77YGo3*l`a zP_g<*95&vk^N7SFzPl)PNL;1GkpW;eHr}mPS2F!2*RWjmE<=3a<>%3KsB)-~dAx5M zwc15g;5SHw0R9Z?AG_EdZ^CIl#(exz*3tdDIWeCO?_EM7b|~J5BolbC@cxu}ObW)E zui2Zn_f~yHmkNJ-+vex-Pii(~aFxHdO8}G8XtF;B$tcSN1;sY!OgREL$ zFNRfv)NX%y4mU`8sw1=piJ0O(cLh{~o}OxMD9a&(^KNKDYsM|6j;TS8CvLAcYHw>s8oblTeGj2I=zb-Hr-nOO_jA zMG+r(`6U`}Jg{zz`5F{GTla|lApZS-tAwN_%ImDzeu!0e+s}{>8{hek9Lcm3q?&Yi zN1oVs3mszHWoL_G;cXkB+XLerxM@CZc`G(IWAADR?{S?qjcxH{@EK(%`E&w_TKBnG z2gcj(-Gw7C-sGqx{i1g!V3^a}dX;~sCpQDYwOv2FKcj5F~2|G2&xZ>bda|GY(@)G;&@q&o%pM_grzaHX4BW%zIqcz81qrwZ2oHG*gm-bSEs`} ze68CV6z?NDsX|zID>o*7hVfQ)IZ4C2)~nRO6~en)_wRx6 zzAL8a1>>E1*ExMU%oNPg^x{pBcE+5Xv?yO~xor|e$wuNpPVH51BC+unoYHxCcRTBC zPP8FD@bb$G2~AL6$@~WC_UdmE9FF+cTRc3^D$38=#r6%-Q{~eP`B>+b{h&}Y7sgwS z4(~9|1+P)O^Z6nKvG7)1zn_M8v>0=ECv&C^f2W#&AP zB2ze}B!fLU*)K#0TR~zyyp0hbc=oxw|oAA+X{9{2P+v80* z;>3^-E286h`?CM~f2@|9rG5_8ARW3Iw68Jp1X_bCmzzmr)u4tge4X$RTlHbci1t95 z^~zRvJw5ZPFEye=lAhpwr+0Usj=EF1&PBAtFGxQiFUW(R*xk3gta|2?33w7*7_;;Y zb`5HN^u;)YdpqSc634S-Y?pZ#b`7%HUwKq0+Jfc!|7VDgH8}a{DTdiyOlN+GwZ4*5 zB|*ktgCyvbmfaFu$Nn?OK?Z&7d-{3t-z9c!I=ti3MCDPuHKRGCu<%~0I^7QAU79;Y z`+}6(ZR0BV;TjTQc8t-OP(8rW8 zQEh=egRE4!d%OMoc8VVo=k%lWVfJP08Kn1)lE+aKtcUj{#K$I_{1z;^8zp4LJl_55 zhoV0|$AABy&|AMg>p(C2EZr@Q(E)N~3tsThuCng?EessRhP+ zw;CsH2Wj$pe_amr1*z{-LYp^_kiq3A?)bbmf$)B^%m%*yKd<{l6MX-F`KlA!2+pRU z{MzP9D-~?K*RQxS&)YSCqJ+fV-ywc$(LrpySII^th3{I)a@E@f@nMOR-%+r2(pZrB z`~S{AO*5+fALHKo5;(B_q{GYxwm%?!qmD5jfc`=0lZmv|TP-@gV~j_9P`o2O&xm8; zU6ZZW1moS4X+Ycm|Mn#87zc#6*P|t6;jLuQ%X~VIcL#}@ec*v`E`+zQ)PipK`+x5a zh)CaFV+vB&w;sMIfQ@%z?W;9ArUNKQQN`Vv#68GX-a7&UR_UkSC#4<)TZmwdv>fMU?z{~H! zJ-MXULlU@E_@8~74(C|9Iaf38@10q}7he#+f$b+J$#?k~@*#iR<&zw>@W1!}{s{~# zYN-D=psPX2HTEfJ4XP8-l*g(;CcNs?a1FZI*+_eX^fdnmNjqqWt>g=v5EJnP1$=4+ zd4fq)|1b{2V^9s6a1G2$hH8+&bxrAz8zx|#hAn|F6}$g$J@%_;!MQDz+eq9j`@U!W zRoMOiOEIkn5@O3)t_HOuKDu%86E(lu>eJ2q8sx%`qnuJH3~Z2kbli+lVE-CKFzsQ; zN6MdFx+SHw21%a|@BLX%{^xlM0&!QR84atMiA ze3&3J6NQbp<*T&ftSr{UdpY968Ye$Jm&&yfQq0dFQ_pmVHih9YZ?$PP6d5$K{|C|( zpFUv7$9c2ejb7O_yqD17o#dL*fmUzOC+e)P>S6w(tgNcg2E@@C@?oH^qzP&;@CqC<&!udu+THcM4^Bi)^KA zLE;P(3GZkB%MH@%xP^VSvsbWO^vC(3)Pqj*1<&YgpWx3Gym?RZPV*3*XY=7f&Qv&sd~ z>h01Z-MFoap5Q)@v4k!z67`a3G6*kk1yfwQ;N`7?NYV9<+@>H;!WxgP4s5*nRvgIT zzrU3NAaTMnJB3H&u>1d2_3l1Fd8~)GAmYOcCqL=3^4!;=%;RmBx>1QklY!S;;;tOD zS!Bch{r?%pd<@#w9QXuXkcRNqrNcY^^U@C}-Y;)%mchc?zV+%WcyjXc$RzFlzaaVO zxnc5UGCKThnYX){Yf%oM!#am(DcfBC%S zX_-sHWdCgx3KEyN($PX*6C3ZmZ7*uXsAV~-NVZ-?T~ zy`8G$P7aS*uzmHGKE;?1i%+uV`Tu?Yj}^Q9|9?(U4Kk*yL20*l6rwfgx0sePRt@sH zX?OvyL7w5Uv?X?44d?PN&>H04;&zFe7i6$xrQ^bjRU~R6Ir9;GgLJYs_hTGXgWL!N zGm}UY@XK^)eYhL;5G$4VIN`C+X37{6w@}humLmYWLF#h|$R&50vD^$&2Jtb7li&P3 zQD?qzFkgeDivmOPJ}_{_Zb`u!x0Mgs{|r+0DaL$Uu|ID5cLr%hhxehVJ=`eXw-{0Zv&f6wEh3V?_c+iPrw(X zS45ShrN1@-ua@nz``V3-x0&i{*`Jx4DYuX~8;>WC2NbY}Sgo4|`aW_X%i(Q~_|V76 zPkxSAL}P;}?o#r+a#@yE;(1`bHqHVUR~bYuG=mSFafAs?e0=N61!r_CUj(cyj2 zmROGBy=df?5*FU?f^=!eTW&u6L2Hm=yn=qsg8F~mxS3j>Ph?P>=kO2tQzUBcjOHvD z@A9M+AOXU=sy(hF`k4th7M=a#S_3xT4V4vd2A^-HOd@es`)x}jXJO;5Cph}eJ(l(G zet`He!pZL3{brJT{0E1@LrbibqKEBziO8)f%|_yA?kKv2=Bp=d7bK0WH54Uk;1z?5>;y3 zTH!(n@3;F~G~kaDb=g1MarvnUc(jA?WZ^Yzyo>op97k9AQBERpass#NB)?!!P99uY z^fXMwoaL%_DdM9EC%*?zl2z?Hn6KV%vJ+E`YZy2ntx&P%#;SI<$D81HmLVS_vWL3H za%t7ukPh#Zfu?;Z-mfCu6|nFQ7HXLV-~VsgEvF6RP2tmisRZHOE?GP-B;W~t>uQbY zIYgpP2Xc$Uj}w_04LZS(6FHX42Z{8XfC@J_!m1x(<6SCeXV(44k1`*LGZayX*(Ln>XbpG{+j)#unX$k7el zA0FgO*@DE8<()Pph-25Fbi)Ir4^gHpH^ibovT*Vv{ZQba{h9e8*66~E)<3xn^#9Z6 z3^!I+v48)6@hoFL3LPC({`UVM9o|`?leAClz@N9MT0EqNg?G&v@-Y~1xz;(f<*f}~ zg1&|j-c9^%7d(5(;7#i|+wV|=w8%GHg`Hjw0 ztiSO!eJ93s+I=Zskhr~fUOhPZ7#r`>Q&XN4fc2KQP#@(u`B~qw7FNE*Jl>C+f0T?d zFvJpysm`ZoOxS*iCGb3E$cIKM^%MUo+6>Z+4)07WP!Fx%qdv8&Sa@%I`|vo7_d4}T z+6mJAex@Fh5Z-@I{2uRnNe0z}J!E<-NYsE~xsSyV-XA|%d&fX{|JoIPJr4SMtFyf8 z=j-dS@irBf$UUmDnc{}THQimn<8v1q?;%SiACDB)!`lq;F@lrdt?Zoh@^Q@1AXfkj zU4(V;m$ycMc!!gRtJogzw=J0r`Di+OG1wxG*8iK*;hiBIp@ZW6M=M4J3-83Az9(S3 zTbFKH4mU`v+qZf3OCJt2b&EtZcQxI&_)NlX;O52TM?APmC~q}yD%m$^v; z+W(J^xZmrHjd#xNvNrA=n<+#jZpF9uD=81L@xGRs`C4_5_3+L`eB8pxZ=|Hxw(&Oe z)qADwg|KJ8@i#~bp#1e3rPb^|Ia$h>k6w%RHJ2)B)!T#)@55aIJ5aoD`>tDnh4)^r zZ8W?mU459sd)s+iIpPr$@MX|U{MO;cnL1P&Atlk<*gXW(%zYL z*2CKy@sWs=U&Jh<_V>4#$6LxVXlz^!AMc5?vhyr!Zn8bzWv3YPQ6HNt!jt*m{eP^< zKTG`_>i<{K)u5v%4QtUFG&(R_8>N5yGvhbVc|`V`5Fe}J-&B7twAc(9**pU@NR5!605iI z1TUxTZ@t$9y&!cnUKW00_r7SF3yk;5(bTW2H$tDc2-{(s5Q>fW+G26bhxtB~MkFpT zuZ&|N4SR?s&ErWp{EYSRwnluAaq=tVN*<1vVIJ?V;W1mMU*IpX6U^*nHjS-e`v!@S z;LMN@%kSEEKSEFJLe<-X4(~jZQ~Oc8zkjS)goU@}CXF~4Z@-`uwEO@1B80cMA-s8Q zqB$G%Ji$J{kqvn_pbw<&uFHn;P8ka9h=B0cJvBo7X=4J0FMh!hMZ(5g`@!9tWj#KW zC?w9Lw=unJJ2u|FD+A5fFEwVl>b)58u>~i;G{5So-EW!4n>)Cmy;2Up|DW2UAtG79 z{?}Wk$F&*qp|^OpK4%K8|6f6ecP_DK0>yice9S^Dytgh`asbA=ZO(Vv=`Hi`ZO4ls zyjw)wTwI{XiE7vHI8Q1gQRhpCiJXD(J}9ws1B~|#HL-02t4zQnPL^^Ptg-RF!+k8` zi~c6cQ6%o%`}_v7BR1YAbng-jYgrF()JG9cemh;v7HP{ekN3pHt%F=0_ze;v+$=$O z<|g}B?^D(c`AFa|ys271tKQ4$@XmR9UK7RJEv<*m=9E#%&Q6PByq35btxIQh9M-uHiWmU+B?ediAs|ABuw@%T&6 zE}iINw(tMv%GfjHBcfCHjYZLa{Xa|f`B=$7Ge~Q?8g%m5V@I?GiKr6|uxijX<3sLn z4I25dpVlCG%hz`XL3fbykBW15kvzdezK)riS4q?*Zg(20p&E4eWs>f8s0K|hzbfHp zWdh2{S^Tk0!>&Ou?Z=Pa9QLBfBXJt{<0=X&v4_}vIZx1P%TkuBLC+B%xj6ax3-X3g z%b2f0`R%8r!}j5yARRvFoK%`+$@W8R0Lg(NAKI3`_IIVzW{_*>@Gf-gjz;n3o7cJo z3vY#?08bci-*H~r@|MVkp9{zk-oEh%99UDBhMa zC3;wR6Z|AM!FbmcX4CLqb|lZ&62d#;t+C>epC{PR8QJ0tEpJ_o*}1$D!rS=9t?$7Q z-r~B+FIuEb!0B&#OEwx|<4q*ml}(;R)swf<phOi09cj??ZAysU=`Fo`k<2$`6L?o^@;cfdsXe36?~RMx|r5AlJQ zpZX!redk{=U%g2wN1Gv>td&&{{M!|$903dJ;CKwmrKbXNYsYmDie6`EnMH$ z8a{g~UShuCro0JwSyLiVZwWTuorNMP@v=UYS|o1CepTKxy4ZN%9?g_or^tGn6CH?; zJ2?5(T|Ad%B*%R9ww5xzdG8Z`|Nms&M8>i;7uml5f0Xf+AsCLyhm)QUN ze>ZGiGvwnBKjm=r-xs9q=6%mo<21=2;p77 zX(d%o*%J&*ZQBVXk*KjpW}d@%^A#NK^M~-Zt&2HN9y114cf8$PWr&UUSG~D&#^-uc z&^Z3rHFma3u<>3OaNg87$bjYW{*3r=z{w9d@%e`5DduO8dp&PFe>#OfgCsa5YK`|g zvi}V7{XT|#Bq~|D8~uIW(v}YIl6j|GP`pp4FkSARIWTR`CmNf83< z|NXyv91RTl2#-6P;E_dZkZkDiJ~eUm8H#uA4gaNBcu%{|IKgXdU}JdC$of%cy*5Z;GE7H*S<@CJ`6`VLB9FJ$dsUcq=*K2uGC@lH>X*C%W@0R_r7tl|Ba*IUwMti-tT zy(q#+Ts2@!3jT$S_p!&VV?VyI9^Pq)kE1yGm0fnca-g62>V0}pd0Wo~{JA$la#wq% z-y^o~{|Rwh81mtjQS;3t{lEU7rTToVWT5`viLM5ni@rY(u0e4BFFm+{2df6@d_3`c z3aUXdjZIeY6}vVtf7Uvv23;7Byzjy935MP|I5*jeM17?5d;UeJ2E|)kEC_^ZP`BnU zr-}gRi5=?wxxWDHD|Uz0w69-QM4}u);&@(i8ymY~pF#5P+a%Onx`gG1*kr`V7M%RP zFRC=Cy~BJB$_krjR?d&V|4%Th>zX~=f&GWrXV)3>(P*;NJ^c`E2I)wLcg5R=Sa>Uh!3PEHudsRrHsmlvdq94LE|kFy@$Vu%mC z{5)^O9Lz~zeg@fED0`4&4*nOUyfll?wz@oId%O)lpJ2#Gt3+M;+#|H(E$ivt z>8-e5TTKJt2I;YA@sm1Z@TryEDg}P*21(SfZzR5sM0t$FHC#{Luk$arw>(|6uPWbQ zJ-mewA9(rg{qP}F>=N_UyPS_=So|G-2kBzerNZU1?0-OdK;S$>K1wBJd-gyxNN94h zjt=iL{cqo))%*PYI~-Ve3%rQXgYkZxI!tSjimx_0ghO~&yuLXT4|swXhcu42_>-tX zz@XA)2=8I#kU!fXyhW}DjD5Lf44%7oQ%If@8}BdNr=BQ^dr-=exT}=bg)4@!FDLSD zmcH!pi}mmxL45Gw=J6JJZ8(;i&%oux|F69_4X3jE|GzgfR4RmoG8D;J z<|zx6p`;QSGS5?*go>hM%8+PQL?y~BskF~T$&?{;hSbJZ$rK53pIhht-TVF@zq51q ze{%1A9M|_r-^=xR@Oislz1MoLwa&Eym5Zh&#)zN?c7jB?RM}B9Iu6OQ#`5!HE)6~!5 zA=Z+@gYr&aT6jU4G=n_%)tnv8gHHCPtt5HSMo+nIq#5M7eU*bF@EN2d%cNFIE5SQR z!4f4}x;D_dDNDYGum@eguvXg__8?nUWyh*#8emkbSHI*hCrAs`%{r{t9l(zubphjy zbF;y#GRI)N9m=hC5Ysh)!H3r&>sO=CAZxQ~BU+0N z;PsF?wF6#hvVYk@dKCNgQo?WA!}~3w;~_?WqfHX^TuuLu_d$!_+`e^GJdh?hP#J5g zP4{@?B31m{~se1#ifbU1dCVnoD_{l$NO>)OO}|L zHJ%lz15W2ZeZPl3gZx%|^mz0E+6zeWh>ouq{nee`QM)Vp-|@B-?fD_OoQen1ni523 zTHn$?-c{7;=yj<~N`0}A|Myeioz+{{O~!k@!ecfxygllbe~~sP_NW0v65j1+r;;UL zyu(u~gnQxd|2HMIe|Ci*NdKl$E|3l5ou*#ntI@h-@_!jNq9f;_7h|wR%uWtjxRsW9nF#@+B(8NC8!nme$ zwrgTN-M{~LUYt4|5jFf;ivkz$Hlx7%(L?D*GTz%&BUsV!#tlY%C*j@hrMr`acWYYQ zhyjdu#GUzLEo^qcqxjIasNL33kAt%k>EpzrtGv%hA1AI1Q)=Z}t_ddB-1=yH5gqT* z2k~1bv#s&tNZpMcTT&wb^6l-5!oe8-T-w9?8=|8Gqd)$Pl&f0ood5iBV&Muy^{8do zb8npeuWxlb@${enzmHR=!<^N99XvT%1_xbchI_bWB1?2xofd_{|M$QD(b{hS&i}R) z9`wYmE}iT_cl&g?&^#zy>+E*Y4ASOxw<^hlh81wDa^Zkix8FZz z|Kxug3cQOpv)YjHu3xr{6AkZ{=5$RG-hP)^7p~a3mFV!O7{=Sg%we-Wyu9`9bwXf9 zkS!!2kx)&#LAo)wafoz5x=3u_2kTx9kPte!G~+MVTj161Yp60>;4dR}Rp*s5Xa5qA zCK{W6I`7>~b9g^Rbc|v27c#xl)jR*+@m@cDOMBP=8}CnS-lvN<)Bgc!0}f}Zbc{() zZ`yx-VFqbUfp_6tnFbl}^Zp$x(C{{?DUv7QouurraQ;8T&@iD4#`|UZF5*5F`1TfG z6HU&|wvYz%Kmh4^i{J)_X3`g=qpUo+9nBhG*NNT7?EKK(JLl5tRm2$!Jh@K)d)FDZ zFm(4GyJ=++$ShBDcxNIyhB5lP)=Vs2GWPFy%dUPsl#zrTkZ_Zki-xD^|NcL!b;!5q zUiRc6?f)O3z`I}|`5qZ>MaM_W(eNIHA~ull7TYtnu>XH}U0H7fjCXjrr|Andc!SjK z{Ok4>8|eDYHeJ&Ff3jR#k^^A8H+!xxiK){77b}Cu3|!Ii=HU&r@a(a~$0BvVpOx<9 zJdBR_rjYj^6EbKIZw^F9(dF z;GVeuiP_5rIwmzEl?mfLMp)tBAa#!q z=4hq*qvKs7KJq(z9qnySd`5IU!|2bvdXw;ehksw*a?kwwtK$q6?wu*Rfgno%=l_F$ ziBP5Ed`|5W%Y^^-|7k7i|F8YPL#z{p2feWOcN~%LkfOO6H0a4E}wHwG#J> zQ6*w~P;kxNl&Q1&biacX{4t3t9R+DZYvVE(0+J&I-X&5*H8S2Uk<6>m@V=<62S|8V zjXqph-dc6!$b(6Eh~2oVp>(&fJrLI%P{?qwhZK(#cN~ZDmSJm9&4=+;es;I9=)MNH zfM0U?XQ!*S9yhqnTv!xE!E=~%)*&;P~w z|M#bQb4uB;@y>Hr8sI;gPxpA6T5qCC$IP8a%&*}mc3}5*puqdt^q~u6ywk^5F z!U4+*O^EzC-eOOI_tVCr!(_Y_t?zN8 z;mv)7*(M27-K zf1$nymsgzrcf18{OrryosrW#;d~42SUoE=N|F}TvbZjETT$lN?dTU34cX49VVlv(( z6Fw`^@Wze1?jpIjC}*!S3GW!6r4ku1-U)`uxS7rH=Pled_K&A*A*ZRM_#_zbpcisA zp)lU|r^hl2L^MId&y*9#C(!Y}_`A18glj)O5vhAyoo1z_^cTD%&x=d8%F!I&QHTx& zjQ%#auJ7U2|M%BhrJfG?c@|^iJu$8^dE&rUx}Th6HY-x4gU3akpFKM9zy1IJHE`3| z58)Z4JB0_8nLWEm_8`GUo7SRvP~^c>W|9ZB^J*{LL241|`!W*tApJ#?s}7{tgZ1jE z`KN{)AgeIjybDqA6}z_T&!i*a`~P-uZ%96`0R(YRp9=gXARUzF%h6FV!LLT@Cf9se z-}IM&^l{2yTdKAs&3TXqqN4|+zw)U_8+_=$53y3kW6dmIshB~A?h0{uUrzsLkfije z)1kxVg?wV?MuGRMjgsrgcqd<-5k$lLu6+~-32z^t8w)!~gE!wMB*SN1<;4s_)b~o8XCm=4x-~CMt`$iY)itn{yW|-y~`Ol6krdrxU$BNnU~Gzeu%|2 zy{AgY#Xe@Kg0zMF?@EF9%aOcYWW2l1RSBTseIdY0kc4+@ZRNuL|Bx8F(Q_E@(lZ&a zwujn-c^&29%A*d@P~A!HW*Be0S@)T=Z~}N82`}JwX@EBm-gBl`q2nFmAW=T3Wr8n9 z>Wbr%!>6av^MA}tzf`;l?YValqT>Qaf8P7wU%a^d-)E5Q?ltj;g0XLJ2{nw0Tlct* z?(sgkggPB--roB0{M^C@sS5?(P%XzpGTy2iZ}6kx&0M)-BMEPJ^V)^eThB(8Kk9+; z7V(+TF*<4w0%gKJX^J^O>?=k?jz<&0q($7X&tU{G&?~LJzC{CE$$qVl7Oo2B(I_o1D?@w@xcsz8sH1Ru=vBj-2YdZ zt)HURV}k#N)CGNQJM?B09q*<+8QbU7Xm9VW4AIeu(O-Q{ez3B@zq|L6>s|(%#IYwQ ziWeU2dT~pG?(tS$d7CO7FBA!l`@;Xr|1_5L|Mzy_{C|+bgDQ;=`I9~9UW4R%G!If? zZ!aKygJiko$qv#QB(&Da#vJybmzB!L>qH%Zh1u=W@l?FKP%=d(|9es%Pa>(AbGQw)NK!ssvC zUzzRZk$)dzm*fyxbZ=9U{|g>qn~E3p-xATyqD^q9VBlGyx+=P_@C=7 zB;yyaL&IBrMyiU0_tO&7h3hT5e|9bxf$=uze=Km6!2v|~xo*o%afEyx9pP++@m_lP z^Gdg90$`|(Sgo$12`rkjdn5w>a=qoGgqDu03Em8;^Yu^=l>dQ_x1rQat`%Xlhj%2R zLl2|BU`TL}lH>UvOGPQuKw1-2ZSLO9WQC45KmIiMZft^ogVaeSU(McIfsQxtM0A;~ zEA8RE3emxh(Vx?+P3<}C|2~8C4g9cbS`8cTfDuo|(Y7mekGJE|qg3f|%oXIZzPOP8 zJt^>hox9}}8SkDik-}(rSExJ8knon`tz0-Dolk688vx_oM(novo@o!HT#iM!2suLg zS5LBOM-su!!TR#zC<2fzPaIvYqzQ^=Ojaq{pySQVi z=O`-;=6^;+2NOnr+^X}Q{QCdy-tYl+d8;|>(_6SLwd@gMTj_suBKr+hI<9q0ndWCK zse}-*P|*4exMO=LNj4M8Ez2;63r;R=EE|dk|#CU^}qZ5xOB69P$Ci zTSBsE={&sm7C)kYsOpXeP<-*U&@T>s?mf_TTk4&d34SwDXR!AE?!gT7{2#q#zsGrL z+H>#Eh>j?X{z9#pZ8Wz1JKhJFefE8m#Kt={ZQ}*^p(47+TlK97RXW17k5`qzx3~WH z{XZS#DtHEYl){7RRJ&Wq9%Q7-D~aYoro8b6q#;)CZJZe?|Nrvt^$v#v(r)=S6Q5=W zpghuWkL9ZqMD%MKk2yyK{X&oHL*fZwM)cRO+n?bJ(&iYMOx4hbSQFf-URTb2cwMCK z>jpy}!vgdnR%7$2FXP^{w+6Wf(V>db-=6%A$U5bJ_n;Zv-rvzW*d8=p`QVw7#J;C= zK;&Orl>0`Vj)baD2W+AihS(z%c)#QG6er^i?fEW&hIfR;ZW|Kbw-n;`k?^j*!5A3} zsrA9D5NSVr47KLc2ALrR(Md=Raw02Du;6F@(`y(Taw2#s3TUX5N!Fb8jj3 z{y%QRQ>MuBX8Oll@)=b+wFw*XAijk?<}~ zm^LQieMNES{kt&UUfmKbLKY4nJABy7f1MN5|D~s52*&#`@0?0@ECCoZwgzeVX#%kd z#g%6V(D4>+>(Q!BHo*%cb)C-&EC!6w@t&72UOd=Hdw2^YI(}pHxB2ZY_b&`wsDFLY zM(m3pR1%tauwQR^lzEY5mv%heZ%(wh#!#grpkl-N<$oS0_MyPL%2)k==H5K^d&SW3 zZf3l6n}oOT^>0Qbyr*~Zu00Fm9sKoCrvrc|C(rR3gTEc2>#jrZ;=_o*mr(fP3%vLC z;w7ihRHFuXEfUhQ#UYjsy|An|bi(E&t_zG-ITppTqgz zpTdKhmH7YX1u47iWt-4ENblD93)8R%Rkp46C3%pT6yJkUc!^!fE||gB+!6Ff%Jdw3 z=nQ2uR~P1-CIYp?C!&n55NE?m=t032V)VP4NRron)ni6Y&JP z2URs>yBW^V-WQ~Th>o`y{e3^Xc6(dYzkARUfvoziJ=jO=>Q3PmR20MLeg^r*k~$qm z`uLiIkqbLWeiV2&Ema&M2PFNF9$7TJk43L}O2V77`I8q3Z}uyGH&?<#EbC0#Ooy%` z&`{n*ER1!Aw63e_ygWk$cMg9&#CC-M%JRho_2JK3j`bgT&i0r0|J<7sdEHl=;twHp z*Dnc#S?xl{`|#1*{>krY@B4pOM8`pl{v^L}NvD_m`xQG%%8zFQg0Yvkg11>nvsFjZ zJ>EE8>U3;-dRor;&-wr36nHnbaE_AkHaL(igNCeWkecnB;RhUOZ+VLu(b0&}A5W&FzZmY{-8(#O>$AG=*zS#sXdSwv z`IG+fwxCYOMcWh|`MV4G-bGvJCrj z;$W?nGS6Orp?kb>R@CWGXWgbU3LkIzFaOg}&PQtn&i{cF9`r$ssfg@BjB6Q{(LAUc zJhlD>dyq!lOa{q=igW!Vm0=J1ZnUR#ZqyO@^UOH*&pShJxzgiSogji&9f_w$Z^2jW zzV4pwg3ln``yqOe$pYPj3LL)I-jh3kzl+pmFLo|H#Em}0UaAUse87PA?jX%YbX>&f zkMGXxvfxfm@bS6C9-g4-}1xLFYmZ=MvZQWD;QimR@X@cx)P!om;Z&3sPYR<7O=j7)KE zTsPqiajP*`Xr3g3$6WGZmy_W9pPleTB1HpOTIzm^(MQMoEFWIh(bf{bAE^Tuek8qN zLdUyFyMOcb#k6;W^ch4)BSwFXYO`|qR4&jqb|p4>z!Dp8t6H2vbs}UXbH9CEKK2aq zN0O0y!e_Q;Xf8)DKi5s8PKWsVz`2go3(H$4De!K4b?$$jw>08RRzSlW=!MUa@Q#yf ziy`67Hc@u#2fTW_7K%A6_P`Nn>+Pt>AUZ<|qW8WzoFanOf{L?hHwj>jxp9qOng(d$ zcV1$wg^st-HNMOEL34Z~Qn%S@^lRn_`V3Md*S?Eu3GF>^A&BTu!{{$%o8HCa9h@Lt z(PlQ1VLv9`Mx{)Ip~^%EL~ksAP=q~$#ARxGWE^Iqd%STEsnb!&dA3L9!9xB&L4kMc zRsH{Y-cokkA$c^st*lOJke0VxQm&pQ;hkx?)TR{1`$7Ex`-%WZpgWLRJ=N|Eakb2= zMg$VUrf**vJFgRf_sDh4U(ez9|AJcZ0sGMLzE`~pZ@btWZ-msHIQ)F?b4GOcW?aI3 zpzJX1Jx-L0=wQI;Z^wjzOPnwlCf5I_%gP7xozC5XjW>sa!Hz?gKj}UoIf_%KZWupDWD@gAMAwwZBv1UVn) zg|?MDLr*t!yto-e1d2`jt|wk204S27F!!zoP-A%Dvq&5r?+-d*2VE?@agVfvq|~j*OGtDA!h617BZ|5}Ur!hBW;#X$+X=bf#O@KmF*DxcE5_H5V=r6fGL&V5LxCuuGEH%M+XMTJuq$7t^UKe7&2jQ%DH%6Piq z1Jd$$XOdA)4c~hE2mCJ-PwKZ8Rtkt z>{T2E-aTVB_2eP8^hC8f8s6h2hrCI6<5wS@BMq^eytxl-hw;94t18em*a?^z39RN4 za)HdZPKW6F62ZNa)WL^o1mG|;D^q5u4o)%R2KQ#8<1KGn#~^(*5l^nm;;Zw%_9F=O zKl_oyhc}{kd(#}=WF3bw`g^YQ-MJx`6C8KmZMkc%2vsN94w@G&3fTeU-IVt=L$$07 zvmPg#HpFh4O!s)>RH@YAC)c3#=luT}3cS0YpEM@pJ$~Sd8XDfE^N)K-c&jcK`%1!l zV{v5aP8e^U)HkAX?oMFj@H?IN{4P+D{@D{j$BBUdvKyqFN&q)Y@4gR8RR`a8X#H3r zjDC7cg~h1-+o@tifI_9I?){7%7~6CjQ;Fh1#baYPQaQw|Jm27 z029|hS>y2($t%!Hw-FXFfIWi@Ub@V2x#|Y`&;RVy=}_3vhyVWP^_J5Vcz0cjOC;kh zpz5iLhPPo{?9M3|Z=Dr7?IgUDi$#S^VZ1joRh&Gt(+ON@+cdU<*9BVR`qHMr55B#n zJpM>U3IT|1)a~`nRtLisOZ-oWqT|g{$f&fzAOugY`>J~~qVq4$Tk0N}(_Q_=oaXRm zMs(<4^p`!*ZX=e)3F=O643~PGi-~vtlR3TDrk5f9uO4~ftk`%@?M%JE(RP;Z@n$!o zP6ys)(|pCBj}wC^@a}Xdxk1L;?6{^18s4{;?*D9J}J%lIM z4fph`ZVEup|8cPgz6GXlr#ZYc5FN1?{oN>6e^@QT1^N^kTkC`#VdCuv45!b)c+XxX zHry?y;_j`@9iJWn7W$u@Xj7@ig=ySM+#|K#Z`4gU!TBo+z}8W0vxAbAie|7(A- zVL|ht%;fXie!w2&XXSl?l>fWSu5|OmYmk;XMZ11&b_Q;08{%Jkxj=IXCd{*5M9{80 z%y2x50J0Ll%7koD2ke*LM(&wG4@ip_hac7}&&MxC>WWt@$t32Y&mi@;pZWYYAd==h zXepv&J4SyS1_s?{B{{+Ch-XLOPvTvqjiT?7E45a zov71s#xQcGDtjUSGgIK*H>|X9K{^TV5TY0}8s3TmhJ7TwWriR7knon7RO>Z>@y;3X zAo#Cx25J{g77y9DK*dCLp|FEQP}IEkV%kFj&|ran&nc?|vx!k3mtJ(d1&goX?pWvG zO_92jxx31L1ft{3`N_5>#q2!I;Vp#dSb@>s=G|UD_Z{K{^Gx1biz>16Jfm^L(&0rn zpt)?9x7PC5e;urd#!IZzR?__p(sGzO9RsD!4}|j;@LoiLH=%%O;evD$-rprBn9%T! zxH1?v0pne7Jh7LAxA7sjnsYGT?%P8rz!bcC8?u6Fld%irr^ntl?n4A@d4t~L83eGX zX3NJ3b$EHp8}z(yLC3q=rqtQLGXsATshbMB!!c`zj`t29>1gZJ5Sqig7SUmV(VwQA zR_2`|P9VKgX3}_DDdr6F?o*v+6BuvR82iwkK`LgD?|+H!isz$yym1Xw>R3K_YvaQ5 z)>S47ygx@7EIe;X!rP}2&xnS%b%E)oNf__4r9=f1-eoLG^$jrI`^0%1rQbV&8z*BY zM>Slaod$P3Ee{jHNRq-+qXz_VQEIXIfg*L_dn|P$emRLL@H+kDO{I>JLx$xKQWxBtkpk~ehOTMkxp!?#1Opo0v2ToXNq83rM6My> zZD<-XtqJGD>Bv_J)H$v)Me)xtCn4;soW%uTZ*LeXnhqpVTLj$9~_DZH@+`G8|_iWC` zS4PzDy#>X7dj_4szP$y%oKLZB8U1fg^sS*z#}r%9fhzcL;(z&{hI2o;H8}q-rSPDk zMGr2KJt(h7pB>GEg!<}Fj=~;Pwcm?F2=*X8>GK&Z@DOVtFl+e!o--&k7<@PvOjIpoG)Yw-GkyFn|JC4W%!LqUFHg>s4NxqBX;6v z8mn8ouG5?cT|{(X_17=?Hh^EA3*;Yp!g;Qx26KqLa{P(Ov#DE9s(ZF$u3cSB|5X{MV@0$=@iiUTr@)z6~j5l89=Ok%} zwVJM%WrXo=u&|hXbHN#WP*@xC=DZ6e(HdLZ<3a>P4ZF^aLIU8mmFtbzst#(}-yg?o zpyRzF{?w@-BBgk8-I;Oy<5FAEhuF@Sy$%73uhJae9Ec9A{&rO0ZaTVf0!FhTj)%3> zfk{bYi6~Pp}&iXrEng4&@Vo zi}lmv5&P9a^R^S;UALp-ZO-@f@DWBlz6q(jZdt%(rHzjFo?9K4Rn!t`4sT0D2UdT- z?Ru9vKH>yxR`;)K9>aFyjXARR)<17S(MC)2^R82o|F<(m9~r>WJ>Iw@RO(RKb$ZjE z{Le;#_u!3q4>I0-H*?w0@U|H{qd5-a?UNt!^?qO0ys2tJcFr49lWVmpM5fnj<<#K(ce~^p5b33b&>-*j2%4a zlM_{q?z5kB;%N@=1Bec+{@BbccH-g3iP(&cU;FuB=XsThozwc3Hz99b;l0%ZR9tUS z<+`SsTY&C2Cva`l=}3VRDpb-J+?$mGZ=&}8WHR2HE6%Z^;q5=~kxs%}LN76$5^t_o z+$XCIoPkGd`x9J%3sjw1CF1Kz1Z|T%SGML5K+(IV>f`%h_jYc7At{ZHcTq**p&i0S z_$H+8facC>PZo6dJ~Qn2D`Fys=J0-s=m^5-&p*=UipUR6kdSs`Q}i9|y|fvgH=F9V zCPC+U*0%_3#{TONbvV54<(U+^$D8RSbvll_cORDX|1bZOBQ{O{2?rz&3J)5aUmrvE zpn*ofh2}v{m%kZ)hdt<2{HttI{%5~^$!}_tg7)OjiR-+|E~n)qqsqn2n!5`VNxP7R7ymXW!vvk-ASO$Cb86qVFILv*+r} zs^6tK44 z|2Ifq`a+$KU!@tFmiR3Uu`4L>9_{aLCF9*2$jOO@xBiN;VG`cadsoGh@HXH$a7qK7 zLEig(kSS%g3)t>FA=pvl0%=A>A9b@Kf==%P{mFP3?}PJOJkF{CLcI-J;$QIYIwODa zwpb0mAE~>M7P7ABI6B^IH=b_X`8bv4@a{%*VD&fN#B9j(kQ0>k=qrgNW8*#9`7VAH zjQ7>f{^R0bu+IzNv~PZzztctcLo6ysK-y~wiU@dUbi$B0?>%?(uI1(3R}+_L6Bgwbb^p&JgqZPB?yb9l!hIrVgf~xuS?e-*^|qYVCZzVAGiY+T;0F?2 zAjA3C=1O}a=(!pxcmEjy>~k-9RLZ0doV4%%NaI2eNX@z{1cNgx@GeLl8&ms}HWhTd z&!l>kb6roSIlNmC9a#N^?3#UJs=@{2v@IN1w_xMV8$?)q7}njO*c zo;z=@C*u7YUx(BMevz$jO-9H2R?6u1u7^o9hxa_9<2FWrWlw6yjXgQR^g36wnp5vE z-8(}*{j8*iNB?!=1S>2!}bu9!L_UzqkbF|JbeHufOPb0pf#_b}p@kzSJ8>dR8jxGTiWP@}i1>TdFeE#R_ zExn0)9yGiyJombNgYg#jE?P#y+kA^ZxB}zdmnCGp_Nohz8L>{2n00}Se<+?X-Vfj2 zk~(HT_J#liS1U<$xT=9gEHwkex6$#g(R-%N@VXJthSWKL=c{)yqt77CH@{chQ2c=A z@Fwf9#OQC8+qa|}a-2ZYXX~dOga%B!6-)FThNe@X@=G;=pPo>$L8_YXc1YtC{pbH@ zc~t3ed`xgPU3mZRDi;Ob6E05=k=`%$FtKn6s$nUo2Z?4=9^|Z&EcJn=orN4@5O{~su5-6PNJNcZl&g@rmDYo2Yf+Zel$|2Zk}{voq6jEr~vBcGLMcoPLe z?~?G&ZT7Dt;T`i$6E0=wvVo;*jK8G!F{dVDMxB_Mj<4r5Vx;Qt?%0gB!eqRNVRaNZD#P z;C|rl>nwr`U0Fnru`~hxFG%NY6`r67e)7x@iv~E5=6sW&E>W` z5yrb$`FJY{?^oaRvbMo^=NI*Q27hq{Q*CB)cRs=A|0S~?NbewmOZu%3);1Hs{-0@P zqBW|(vbgGqk3KryA8%AC&Lp+tt&zIxN9IAnI&{3Xu9iecrsUEb-k%X20HeQt#;?v@ zlN{jvg@UU=Vc2+2q&l&NwB3acS6!;nlg9qU4o8eiZ*k@d0W`eLMB3I4!g%+c{*h0@n|n`gE+34yV@~(2tp%Cbr2^IYC5n_vI2Yc_FaLpWnftY*ddut19 zGkv&i*>jqnNl?*TDm!&Lgg4)ln~zusNUJFDp0V2APR84<;3hvB-t|7msz`Xt#J;*n z!aG=EHl_y-Ncmsi3Hlsy1u3CRW9PbEpk9G(v*E@>;8^k~Z*e^VJmd4Pcj{0D&!kFK zN9EA*UOj)uS4h1Tk4Nh6nn*qJtU|}zeV=MxmvJ`D;VppZ@WSX%uE5~Q^`9J|Y$=C# z&UtLSmvp?V6N2&nb>Af$=^Q6YfF6+hzZ-Bx&#M;Tl25=gh9)^u^#6FW|X%U)j6IxAqXh zk7Wlg+^8i0WBr@MyX@4!{TSyQ&1Q7G&16Mi*mpgI^}%>IoLJ&P!uz5|^p-;~ z-p+2@mkRxG10Q-X9yYXeg}f|Pv&OWEz-;66hK?Qr5biTnE8V6FZuhcYpRGp6yGJJx zcd)h_pNiCV|2*UUxf&gBudp+D>SYBqhj$;M1FOGv<~zo1ra3@$Cyt9Ds1?(_zo-9< ze;9Qi+LQ2_fw%{I2Z`6Fznrato$dpYkq31;uEf}V3HTF`1S#-lu;7Xyn#Baym3M^Rb;#$^4SZa;k~_j!yF0kyG(dt65dftwRb{cyq~Y^vOcQo28{L$X!rHI zK-O`w*6G`cpfp0n&#{95n1>X?H*~?96Jmxf?s4e(zwkf}OV|2NybV$}oE}(3tVGZM z)pyh-*d=KX@27~48jSurdpC-d&vAg{JtmHi8k;fQn`fzJ#vc89ko9vd_a+r8mbb1? z$}auML;sVLSn71FuUoCC0l(h*-~E4R>6V6m4(I>%6dtss-SZLIgFHrgB+)#Gy`awI zBkVz=SLZ@SVGk;~KJt77UV}VzfWb?By(i$ewCk1bbc0G>1f0o~C4xP3SEq0j@B``N zNN|@ail5Tl5Nn3$!0N9( z;06C$3r?_a-RGri+&VEmsF(1me0NL+bTP2CV*eWK{IBa9m11D4NB1679Y~#yecxYM z%Y-lF|8*32FMc$VO2*s&7(oIJZ;Qt#`Fml!o5LzCNqA4l=vOnqL+n_GhDT|K2e^b+ zNb*c~gI+-*S?-&OU<>Ps{+3Y!;9q01v?EysxNqWXxV;x0Zw_}SWATd5cn_p*w?1#K z;Y;)xB!}g>JLg-AX%25*LwM<0GCfW!+IPO|5zfSFFq zpafHNyzk6)T1?hE!(^X@=aP7wF#xYJ-!2c~=f+U(xM1mkU-^Jd5In^b(g)tkOe%P5cT@y3l& zsbl^!qvW6bFHC_q3kRz@8SiyJ_lTk4y)!r{O_-Lyt@YQY!4CO@6|96D5{Pej|m0q19nse{_hz>uD{)()0a*kDSfQlb(d;09!G4UoIHNT)xo(`Q( zcUAD3pyKPT)lM5kK8Vpj-a^#rcy+Me>_Yy3`JaYTK6)!~{@+O9K^)bhSIHifZOFa} z&4Yx>rg=MI531yDI=l|{piACXZC0=cNgOO?ymiqFWYinZ)!cB02DWqSJP;xRt~+O} zx3csB-l3%8`?e||sd(+CG*9#)mUC*DwN+*ie+{XVyIfSTvk2XT3O-opx4gsCoCmE! zbYS&&JC)tc$cGbn?@fKX*!Ux+2i=-lyi7|p3;N8sW4M}%{I9pFc->H*I^BDaEH8CB zro7Jt+s7>Ae+de_SEO3)Amgny*ei>MH|UZ7Ny0mD;t?R>eLFMyxh9Oa)>C}}S4}U_ zXSg|!KH8T-Jgz``Y052^qw(<5Kg-O%wq>m^(@u#1Q{N9ufL zohu~6(D5EMe4o1Z;|rR@I|9)$hS6Vy$_91r+Z^DnmuAmL7HquN)qU&UE1U&|kA6fk9Y73>U0!;ztWfe=LYEw6nHOpb^A!h+jrRm88p1F*lToj!FWF$ zv0hHX`{pZ~a9$YiTe$-zp>3XEJ7M?Nw*gC zns;Sr3_{0yz3b`23`Yj=9Z20g(QZX%2s+-9xZ%9G(Gr@&TN2TM)n5uPx1Vzt2MCOL z{e7=S52kx34|}(1=s$$!9()m5H-er2os*;V4Nq%<1dJP!h%bi;VNZhzKI%Ky$jPp*F^eIUKzd9#$gCm2=yl5e!!9l9h{ z=>JWE2!a(ie7-#cZ;&czZm%v>0Svx#2~Y2%<9)@-HIgl{A3uNWPhFDIA-}LBbi98W ztn#Xze@=6FCm}kfF#5YvujlL{#0hT1NbMs&>c+&oH&@M-sP_>1!CRwoJ%Nh+&vx@* z;0AfRKOl`;Mx_q_QCHFf>G0fJi~?`=Mb@v#co!FKmqNpvU0yb{2gdtO5=%ZM-ixI7 z%6mF_f;;E3Dqbvchl=KY;$KP;!SEDQi1ic!yuwSyOTv3^+m_$FzWy{i-kYRncUs%` z;dPO^h*fn@7VkmF`-iKv*|(HuG>5k`qGJN1Kf(^LzL0Aiz-eD1@80cQn0R|OA z&xA@36#c}vQ<48;wJMiMR?|P;SE$obb!zCB419abfBXOFv72W84eUX(6duG|dUz?> zgLJYMDWiE1af;cY74{&)*5ttT@DSU-QcvhBJj7mJD`4KqeGuqGUe6+?ctC5n^BRgQ zCjwRlv(%mZeIT=oBlMn;GT0`5+TKsu1VZ~g91=*2-()p}*Fx%E4&AM?NJ3v?|MFpN z^XrgOn)4uELUY3C|73#m3OXX4_=-v8e-v?8|q z{BF9RL2etNPKWiK$Mt4m3;AD$0&kwn?@p8P-VoEQh=w=Y#HpQaFy7fY$Ms2gHwNaF zF~R{UT~nsVxz8JXt^2{uaKZ!1O&IMeb5vR~K2uW!QK#e_ph9 zEGripIDa;wycs+H<4Tvx#Z~U7d%SUF)aj_{8}7ON=LKnL3cR^pdhV0)25EN`(D3fe z`>NUwAw6R%+UBrw4Q>XVDdX9wHd%&hTEx)d%>} zjkx1IltGNwD`n?R=y(fy_8g7!|B8=7>O6(=)vqg{q00 zEIQud9esmiT(pNbKcXWHqrYuJix?9hbAZa4JvR-!u<^bU5pi4q#yh1h`ogb^ROJ6_ ztQkj4pU^$txT{p^*gG4r?oa-gq`;f=_x&<5-fe-Jo6+!o6riQ}0ml2S7DE~d?}2mo z-H*X|Th9zbf^A+v_=P)8AMXw|3^3*^3c_!1)kjXNEa?O7%dFcpR>{4TR&wvL3GG9t*mtf%o*h2ApUmG=sZZbJSW~; z1Uvt~a;ccN*t?VNhgd~t>U7lY?H#;*c_IJHQ{XKSCHRv(#8$XesH5SXvQ0kXJ&d<% zT)!&`Z_$knL9b!FZwG?NXEzUmq#6%qg19FnXnnrZYJLE?>8G*sO7#Jy@uA90US&{q z>!bcFDRjI=V}3G;e;dJ@lw7I>jAHqT>cef0Lg4qnF?vr2TyAf~-NF(8 zwgl>QFnucNxb$cLe-j1Xt2Om}$#@q%_fbW|dyc34ax;uKhrA+@w7jLY=R{W90wLIj)Ser@(!+XsG&weLyLQwE;-zH-n1 zvb=>mIv`iK|2y6Zshe)@zts8#eR=EMO2R#{IojKtU`BM*V)SR^sOxIGmjfKiDe>K# zhP^p)cRQ=U9VfF3a-`wgTmH-cG?eqvT7mPw zDuoA$7T9kjc@Qc8?_jWILGz%_T>%GbVGrUweqvM{9%Aj3+k%+jH%QNA=xlSm=mWZ< z`qKvHJfVA=ZkTC2vWy( z_Q~t;!{{E=rB}kzCiI5phS*v}#|Mo5*w}{a&+Ov>%J~^F*QXaQa1#x*6>h9$NSXxyM7$$uW1f%X+%c=Mt@gy%nH%m=hz-1%u$l_zv)37`AL z;Q_Gz?6!y@%|37!IxQ7uqXb-tZrK&b_M*Bs>+(SUD;Z;WJEYDb%BjtH5*_cf+f7rU zO04mV|du!l^QO z81MJXo{PK5`T!ZeNBQ=do)GlY`|P#x0l>a-;=O}vAMmVuqW#bN6I^Kh` zauqycWB3-NF8%RW-|-%Fy!8mYRs*H9w>dF{=-7(U-+21#3#*toLHWiw)`##TPGpSH z{ya3iajs!$KBU8ZA*jM1`+~H!J}V2fMvUnG{=bfc)alSxjEmy%TiBdXq`-R(@rW}S zZ{OgH3}|>KdR;iz0OP&6`%*t?^|rk{FboebZzYyTtk<*lp7x^xa^ z&>r6V5FH5^{nZ2;T|9IczP&}?_MK`hHr~!Zbl%0mc*k&@J*U)0MgC7yG!NEqr2qU+ Qr4F`x@7{faZ*Td30Fh2Dvj6}9 literal 0 HcmV?d00001 diff --git a/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 similarity index 100% rename from planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 rename to planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 07f8f3e30e659..4bb0630d13942 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -38,7 +38,7 @@ def generate_test_description(): output="screen", parameters=[ {"lanelet2_map_path": lanelet2_map_path}, - {"run_background": False}, + {"mode": "AUTO"}, {"rviz": False}, {"centerline_source": "optimization_trajectory_base"}, {"lanelet2_input_file_path": lanelet2_map_path}, diff --git a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp index e951f11e49ab7..923fc53055475 100644 --- a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp +++ b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp @@ -50,6 +50,9 @@ struct VehicleInfo autoware::universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const; autoware::universe_utils::LinearRing2d createFootprint( const double lat_margin, const double lon_margin) const; + + double calcMaxCurvature() const; + double calcCurvatureFromSteerAngle(const double steer_angle) const; }; /// Create vehicle info from base parameters diff --git a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp index db223663f1145..2dd5b19f2f523 100644 --- a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp +++ b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -85,4 +85,30 @@ VehicleInfo createVehicleInfo( }; } +double VehicleInfo::calcMaxCurvature() const +{ + if (std::abs(wheel_base_m) < 1e-6) { + throw std::invalid_argument("wheel_base_m is 0."); + } + if (std::abs(max_steer_angle_rad) < 1e-6) { + return std::numeric_limits::max(); + } + + const double radius = wheel_base_m / std::tan(max_steer_angle_rad); + const double curvature = 1.0 / radius; + return curvature; +} +double VehicleInfo::calcCurvatureFromSteerAngle(const double steer_angle) const +{ + if (std::abs(wheel_base_m) < 1e-6) { + throw std::invalid_argument("wheel_base_m is 0."); + } + if (std::abs(steer_angle) < 1e-6) { + return std::numeric_limits::max(); + } + + const double radius = wheel_base_m / std::tan(steer_angle); + const double curvature = 1.0 / radius; + return curvature; +} } // namespace autoware::vehicle_info_utils From 470ebbaf0c3a6577be34d1871109ea2f8ee5ee49 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 1 Jul 2024 16:31:17 +0900 Subject: [PATCH 197/223] refactor(static_centerline_optimizer): clean up the code (#7756) Signed-off-by: Takayuki Murooka --- .../rviz/static_centerline_generator.rviz | 2 +- .../scripts/centerline_updater_helper.py | 5 +++- .../src/static_centerline_generator_node.cpp | 23 ++++++------------- .../src/static_centerline_generator_node.hpp | 1 - 4 files changed, 12 insertions(+), 19 deletions(-) diff --git a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz index fc916f188e758..f1bd110783009 100644 --- a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz @@ -122,7 +122,7 @@ Visualization Manager: Name: Map - Class: rviz_plugins/PathWithLaneId Color Border Vel Max: 3 - Enabled: true + Enabled: false Name: Raw Centerline Topic: Depth: 5 diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index 2cd0c2f66d474..4bed564cee295 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -65,6 +65,7 @@ def setupUI(self): centerline_group.setLayout(centerline_vertical_box) self.grid_layout.addWidget(centerline_group) + """ # 2. Road Boundary road_boundary_group = QGroupBox("Road Boundary") road_boundary_vertical_box = QVBoxLayout(self) @@ -79,8 +80,8 @@ def setupUI(self): self.road_boundary_lateral_margin_slider.setMaximum( 5 * self.road_boundary_lateral_margin_ratio ) - road_boundary_vertical_box.addWidget(QPushButton("reset")) + """ # 3. General general_group = QGroupBox("General") @@ -123,9 +124,11 @@ def __init__(self): self.widget.validate_button.clicked.connect(self.onValidateButtonPushed) self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) + """ self.widget.road_boundary_lateral_margin_slider.valueChanged.connect( self.onRoadBoundaryLateralMargin ) + """ # ROS self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1) diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 24ccd7d660edf..de89cf4d12a87 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -251,11 +251,6 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( } save_map(); }); - sub_traj_resample_interval_ = create_subscription( - "/static_centerline_generator/traj_resample_interval", rclcpp::QoS{1}, - [this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) { - // TODO(murooka) - }); sub_validate_ = create_subscription( "/static_centerline_generator/validate", rclcpp::QoS{1}, [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); }); @@ -325,14 +320,6 @@ void StaticCenterlineGeneratorNode::generate_centerline() visualize_selected_centerline(); } -void StaticCenterlineGeneratorNode::validate() -{ - const auto selected_centerline = centerline_handler_.get_selected_centerline(); - const auto road_bounds = update_road_boundary(selected_centerline); - - evaluate(); -} - CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route() { if (!route_handler_ptr_) { @@ -572,7 +559,7 @@ void StaticCenterlineGeneratorNode::on_plan_path( CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids}); // publish unsafe_footprints - evaluate(); + validate(); // create output data auto target_traj_point = optimized_traj_points.cbegin(); @@ -714,8 +701,11 @@ RoadBounds StaticCenterlineGeneratorNode::update_road_boundary( return RoadBounds{ego_left_bound, ego_right_bound}; } -void StaticCenterlineGeneratorNode::evaluate() +void StaticCenterlineGeneratorNode::validate() { + // const auto selected_centerline = centerline_handler_.get_selected_centerline(); + // const auto road_bounds = update_road_boundary(selected_centerline); + std::cerr << std::endl << "############################################## Validation Results " "##############################################" @@ -730,6 +720,7 @@ void StaticCenterlineGeneratorNode::evaluate() const double max_steer_angle_margin = getRosParameter("validation.max_steer_angle_margin"); + // calculate color for distance to road border const auto dist_thresh_vec = getRosParameter>("marker_color_dist_thresh"); const auto marker_color_vec = getRosParameter>("marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { @@ -806,7 +797,7 @@ void StaticCenterlineGeneratorNode::evaluate() } } - // publish left boundary + // publish road boundaries const auto left_bound = convertToGeometryPoints(lanelet_left_bound); const auto right_bound = convertToGeometryPoints(lanelet_right_bound); diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index 42033f7956bfd..fd2314d42e46f 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -133,7 +133,6 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node void visualize_selected_centerline(); RoadBounds update_road_boundary(const std::vector & centerline); - void evaluate(); // parameter template From 222d3199ff9fd7c7d52b9d6bce47276cbe7497ee Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 1 Jul 2024 19:35:03 +0900 Subject: [PATCH 198/223] fix(static_centerline_generator): save_map only once (#7770) Signed-off-by: Takayuki Murooka --- .../scripts/centerline_updater_helper.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index 4bed564cee295..f3d908713361d 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -162,6 +162,13 @@ def onSaveMapButtonPushed(self, event): msg = Empty() self.pub_save_map.publish(msg) + # NOTE: After saving the map, the generated centerline is written + # in original_map_ptr_ in static_centerline_generator_node. + # When saving the map again, another centerline is written without + # removing the previous centerline. + # Therefore, saving the map can be called only once. + self.widget.save_map_button.setEnabled(False) + def onValidateButtonPushed(self, event): msg = Empty() self.pub_validate.publish(msg) From 5bed858794e5d88799d9dd1096c333d884ea3e45 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 1 Jul 2024 12:45:46 +0900 Subject: [PATCH 199/223] fix(pose_instability_detector): fix a rare error (#7681) * Added an error test case Signed-off-by: Shintaro Sakoda * Fixed to avoid out-of-size access Signed-off-by: Shintaro Sakoda * Fixed the test case Signed-off-by: Shintaro Sakoda * Fixed test Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../src/pose_instability_detector.cpp | 6 ++ .../pose_instability_detector/test/test.cpp | 58 +++++++++++++++++++ 2 files changed, 64 insertions(+) diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp index 28398588809eb..23362dd13c6bc 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -354,6 +354,9 @@ PoseInstabilityDetector::clip_out_necessary_twist( start_twist.header.stamp = start_time; result_deque.push_front(start_twist); } else { + if (result_deque.size() < 2) { + return result_deque; + } // If the first element is earlier than start_time, interpolate the first element rclcpp::Time time0 = rclcpp::Time(result_deque[0].header.stamp); rclcpp::Time time1 = rclcpp::Time(result_deque[1].header.stamp); @@ -380,6 +383,9 @@ PoseInstabilityDetector::clip_out_necessary_twist( end_twist.header.stamp = end_time; result_deque.push_back(end_twist); } else { + if (result_deque.size() < 2) { + return result_deque; + } // If the last element is later than end_time, interpolate the last element rclcpp::Time time0 = rclcpp::Time(result_deque[result_deque.size() - 2].header.stamp); rclcpp::Time time1 = rclcpp::Time(result_deque[result_deque.size() - 1].header.stamp); diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp index 9300984967d4b..482e659e7a13c 100644 --- a/localization/pose_instability_detector/test/test.cpp +++ b/localization/pose_instability_detector/test/test.cpp @@ -163,6 +163,64 @@ TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOL EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::WARN); } +TEST_F(TestPoseInstabilityDetector, does_not_crash_even_if_abnormal_odometry_data_comes) // NOLINT +{ + // [Condition] There is no twist_msg between the two target odometry_msgs. + // Normally this doesn't seem to happen. + // As far as I can think, this happens when the odometry msg stops (so the next timer callback + // will refer to the same odometry msg, and the timestamp difference will be calculated as 0) + // This test case shows that an error occurs when two odometry msgs come in close succession and + // there is no other odometry msg. + // Referring again, this doesn't normally seem to happen in usual operation. + + builtin_interfaces::msg::Time timestamp{}; + + // send the twist message1 + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the first odometry message after the first twist message + timestamp.sec = 0; + timestamp.nanosec = 5e8 + 1; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the second odometry message before the second twist message + timestamp.sec = 0; + timestamp.nanosec = 5e8 + 1e7; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // send the twist message2 + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // provoke timer callback again + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // This test is OK if pose_instability_detector does not crash. The diagnostics status is not + // checked. + SUCCEED(); +} + int main(int argc, char ** argv) { rclcpp::init(argc, argv); From cb3e7588a8c4ad5ec5e147815c6193467e0ff4dd Mon Sep 17 00:00:00 2001 From: Zhi Wang Date: Wed, 3 Jul 2024 14:28:38 +0900 Subject: [PATCH 200/223] feat(mrm_handler): operate mrm only when autonomous operation mode (#1377) feat(mrm_handler): operate mrm only when autonomous operation mode (#7784) * feat: add isOperationModeAutonomous() function to MRM handler core The code changes add a new function `isOperationModeAutonomous()` to the MRM handler core. This function is used to check if the operation mode is set to autonomous. --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kyoichi Sugahara --- .../include/mrm_handler/mrm_handler_core.hpp | 3 ++- .../src/mrm_handler/mrm_handler_core.cpp | 15 ++++++++++++--- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index c908ca1a62ee2..7d7deb8c4a504 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -148,7 +148,8 @@ class MrmHandler : public rclcpp::Node bool isStopped(); bool isDrivingBackwards(); bool isEmergency() const; - bool isAutonomous(); + bool isControlModeAutonomous(); + bool isOperationModeAutonomous(); bool isPullOverStatusAvailable(); bool isComfortableStopStatusAvailable(); bool isEmergencyStopStatusAvailable(); diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 326fbb392fd35..47cbb0ae7d016 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -396,12 +396,13 @@ void MrmHandler::updateMrmState() } // Get mode - const bool is_auto_mode = isAutonomous(); + const bool is_control_mode_autonomous = isControlModeAutonomous(); + const bool is_operation_mode_autonomous = isOperationModeAutonomous(); // State Machine switch (mrm_state_.state) { case MrmState::NORMAL: - if (is_auto_mode) { + if (is_control_mode_autonomous && is_operation_mode_autonomous) { transitionTo(MrmState::MRM_OPERATING); } return; @@ -537,7 +538,7 @@ bool MrmHandler::isEmergency() const is_operation_mode_availability_timeout; } -bool MrmHandler::isAutonomous() +bool MrmHandler::isControlModeAutonomous() { using autoware_vehicle_msgs::msg::ControlModeReport; auto mode = sub_control_mode_.takeData(); @@ -545,6 +546,14 @@ bool MrmHandler::isAutonomous() return mode->mode == ControlModeReport::AUTONOMOUS; } +bool MrmHandler::isOperationModeAutonomous() +{ + using autoware_adapi_v1_msgs::msg::OperationModeState; + auto state = sub_operation_mode_state_.takeData(); + if (state == nullptr) return false; + return state->mode == OperationModeState::AUTONOMOUS; +} + bool MrmHandler::isPullOverStatusAvailable() { auto status = sub_mrm_pull_over_status_.takeData(); From 9f31524e84f984bb393331be71e89f79cee136a0 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 21 Jun 2024 15:14:55 +0900 Subject: [PATCH 201/223] fix(image_transport_decompressor): missing config setting (#7615) Signed-off-by: badai-nguyen Co-authored-by: Kenzo Lobos Tsunekawa --- sensing/image_transport_decompressor/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/sensing/image_transport_decompressor/CMakeLists.txt b/sensing/image_transport_decompressor/CMakeLists.txt index 2359a327abb8c..2ecd3446290df 100644 --- a/sensing/image_transport_decompressor/CMakeLists.txt +++ b/sensing/image_transport_decompressor/CMakeLists.txt @@ -24,4 +24,5 @@ rclcpp_components_register_node(image_transport_decompressor ament_auto_package(INSTALL_TO_SHARE launch + config ) From a28bbd2c49be8666650e0f90dcc91df40c652849 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 4 Jul 2024 10:34:17 +0900 Subject: [PATCH 202/223] fix(euclidean_cluster, ground_segmentation): cherry-pick bug fix PRs (#1378) * fix(euclidean_cluster): fix euclidean cluster params (#7662) * fix(euclidean_cluster): fix max and min cluster size Signed-off-by: beginningfan * fix(gnss_poser): fix a typo Signed-off-by: beginningfan * fix(euclidean_cluster): fix min cluster size Signed-off-by: beginningfan * style(pre-commit): autofix --------- Signed-off-by: beginningfan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(euclidean_cluster): fix max_cluster_size bug (#7734) Signed-off-by: badai-nguyen * fix(ground_segmentation): fix bug (#7771) --------- Signed-off-by: beginningfan Signed-off-by: badai-nguyen Co-authored-by: beginningfan <103237402+beginningfan@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- launch/tier4_perception_launch/package.xml | 1 + .../lib/voxel_grid_based_euclidean_cluster.cpp | 8 ++++++-- .../src/ransac_ground_filter_nodelet.cpp | 7 ++++--- 3 files changed, 11 insertions(+), 5 deletions(-) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 6ec706a4aad32..57d4b209efeef 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -19,6 +19,7 @@ detected_object_feature_remover detected_object_validation detection_by_tracker + elevation_map_loader euclidean_cluster ground_segmentation image_projection_based_fusion diff --git a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp index 40699fd6e27ab..126f877afddb0 100644 --- a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp +++ b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp @@ -106,7 +106,7 @@ bool VoxelGridBasedEuclideanCluster::cluster( temporary_cluster.height = pointcloud_msg->height; temporary_cluster.fields = pointcloud_msg->fields; temporary_cluster.point_step = point_step; - temporary_cluster.data.resize(max_cluster_size_ * point_step); + temporary_cluster.data.resize(cluster.indices.size() * point_step); clusters_data_size.push_back(0); } @@ -117,13 +117,17 @@ bool VoxelGridBasedEuclideanCluster::cluster( voxel_grid_.getCentroidIndexAt(voxel_grid_.getGridCoordinates(point.x, point.y, point.z)); if (map.find(index) != map.end()) { auto & cluster_data_size = clusters_data_size.at(map[index]); - if (cluster_data_size + point_step > std::size_t(max_cluster_size_ * point_step)) { + if (cluster_data_size > std::size_t(max_cluster_size_ * point_step)) { continue; } std::memcpy( &temporary_clusters.at(map[index]).data[cluster_data_size], &pointcloud_msg->data[i * point_step], point_step); cluster_data_size += point_step; + if (cluster_data_size == temporary_clusters.at(map[index]).data.size()) { + temporary_clusters.at(map[index]) + .data.resize(temporary_clusters.at(map[index]).data.size() * 2); + } } } diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index d7fa777dc58c9..aa224e7adc5bf 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter( no_ground_cloud_msg_ptr->header = input->header; no_ground_cloud_msg_ptr->fields = input->fields; no_ground_cloud_msg_ptr->point_step = point_step; + no_ground_cloud_msg_ptr->data.resize(input->data.size()); size_t output_size = 0; // use not downsampled pointcloud for extract pointcloud that higher than height threshold for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) { - float x = *reinterpret_cast(input->data[global_size + x_offset]); - float y = *reinterpret_cast(input->data[global_size + y_offset]); - float z = *reinterpret_cast(input->data[global_size + z_offset]); + float x = *reinterpret_cast(&input->data[global_size + x_offset]); + float y = *reinterpret_cast(&input->data[global_size + y_offset]); + float z = *reinterpret_cast(&input->data[global_size + z_offset]); const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z); if (std::abs(transformed_point.z()) > height_threshold_) { std::memcpy( From 777763267d213716d75f5a4df6c00bf8938a31b4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 8 Jul 2024 16:08:47 +0900 Subject: [PATCH 203/223] fix(motion_planning): fix processing time topic names (#7885) (#1394) Signed-off-by: Maxime CLEMENT --- .../autoware_motion_velocity_planner_node/src/node.cpp | 4 ++-- .../autoware_motion_velocity_planner_node/src/node.hpp | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 5e6f9619e75c2..07e496d52764b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -83,8 +83,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & velocity_factor_publisher_ = this->create_publisher( "~/output/velocity_factors", 1); - processing_time_publisher_ = this->create_publisher( - "~/debug/total_time/processing_time_ms", 1); + processing_time_publisher_ = + this->create_publisher("~/debug/processing_time_ms", 1); // Parameters smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 8debb9cbedf00..4bf24cadb36f2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -97,7 +97,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_viz_pub_; rclcpp::Publisher::SharedPtr velocity_factor_publisher_; - autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; + autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ + this, "~/debug/processing_time_ms_diag"}; rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; From 4e18b8052d720f5d026c1538e15d19fb0674a71c Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Jul 2024 09:37:21 +0900 Subject: [PATCH 204/223] fix(multi_object_tracker): fix publish interval adjust timing (#7904) (#1400) refactor: optimize publish time check in multi_object_tracker_node.cpp Signed-off-by: Taekjin LEE --- .../multi_object_tracker/src/multi_object_tracker_core.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 97c3d93d191b2..0a1f5f2344ba7 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -222,8 +222,9 @@ void MultiObjectTracker::onTrigger() } else { // Publish if the next publish time is close const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period - if ((current_time - last_published_time_).seconds() > minimum_publish_interval) { - checkAndPublish(current_time); + const rclcpp::Time publish_time = this->now(); + if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) { + checkAndPublish(publish_time); } } } From 992b4df18e3771d26f49889a00856791b108da72 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 23 Jul 2024 15:05:43 +0900 Subject: [PATCH 205/223] fix(velocity_smoother): float type of processing time was wrong Signed-off-by: Takayuki Murooka --- .../include/autoware/obstacle_cruise_planner/node.hpp | 2 +- .../include/autoware/obstacle_cruise_planner/type_alias.hpp | 2 ++ planning/autoware_obstacle_cruise_planner/src/node.cpp | 4 ++-- .../include/autoware/velocity_smoother/node.hpp | 4 +++- planning/autoware_velocity_smoother/src/node.cpp | 4 ++-- 5 files changed, 10 insertions(+), 6 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp index d4094ff08c3f0..29bd91f5c5b72 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp @@ -159,7 +159,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_stop_planning_info_pub_; rclcpp::Publisher::SharedPtr debug_cruise_planning_info_pub_; rclcpp::Publisher::SharedPtr debug_slow_down_planning_info_pub_; - rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; // subscriber rclcpp::Subscription::SharedPtr traj_sub_; diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index 03e536ce238cd..541a8281b2f1d 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -29,6 +29,7 @@ #include "nav_msgs/msg/odometry.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" +#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_planning_msgs/msg/stop_factor.hpp" #include "tier4_planning_msgs/msg/stop_reason_array.hpp" #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" @@ -56,6 +57,7 @@ using geometry_msgs::msg::Twist; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using tier4_debug_msgs::msg::Float32Stamped; +using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::StopFactor; using tier4_planning_msgs::msg::StopReason; using tier4_planning_msgs::msg::StopReasonArray; diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 210577d92ef93..cbb3f98385774 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -425,7 +425,7 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & "~/output/clear_velocity_limit", rclcpp::QoS{1}.transient_local()); // debug publisher - debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); + debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); debug_cruise_wall_marker_pub_ = create_publisher("~/debug/cruise/virtual_wall", 1); debug_stop_wall_marker_pub_ = create_publisher("~/virtual_wall", 1); debug_slow_down_wall_marker_pub_ = @@ -1977,7 +1977,7 @@ void ObstacleCruisePlannerNode::publishDebugInfo() const void ObstacleCruisePlannerNode::publishCalculationTime(const double calculation_time) const { - Float32Stamped calculation_time_msg; + Float64Stamped calculation_time_msg; calculation_time_msg.stamp = now(); calculation_time_msg.data = calculation_time; debug_calculation_time_pub_->publish(calculation_time_msg); diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 26918cce24549..4e142ca8983f7 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -44,6 +44,7 @@ #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary +#include "tier4_debug_msgs/msg/float64_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary #include "visualization_msgs/msg/marker_array.hpp" @@ -66,6 +67,7 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; using tier4_debug_msgs::msg::Float32Stamped; // temporary +using tier4_debug_msgs::msg::Float64Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary using visualization_msgs::msg::MarkerArray; @@ -259,7 +261,7 @@ class VelocitySmootherNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_closest_velocity_; rclcpp::Publisher::SharedPtr debug_closest_acc_; rclcpp::Publisher::SharedPtr debug_closest_jerk_; - rclcpp::Publisher::SharedPtr debug_calculation_time_; + rclcpp::Publisher::SharedPtr debug_calculation_time_; rclcpp::Publisher::SharedPtr debug_closest_max_velocity_; rclcpp::Publisher::SharedPtr debug_processing_time_detail_; diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index ca7526e9adf3b..195288dd9c896 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -76,7 +76,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti debug_closest_acc_ = create_publisher("~/closest_acceleration", 1); debug_closest_jerk_ = create_publisher("~/closest_jerk", 1); debug_closest_max_velocity_ = create_publisher("~/closest_max_velocity", 1); - debug_calculation_time_ = create_publisher("~/debug/processing_time_ms", 1); + debug_calculation_time_ = create_publisher("~/debug/processing_time_ms", 1); pub_trajectory_raw_ = create_publisher("~/debug/trajectory_raw", 1); pub_trajectory_vel_lim_ = create_publisher("~/debug/trajectory_external_velocity_limited", 1); @@ -1090,7 +1090,7 @@ void VelocitySmootherNode::flipVelocity(TrajectoryPoints & points) const void VelocitySmootherNode::publishStopWatchTime() { - Float32Stamped calculation_time_data{}; + Float64Stamped calculation_time_data{}; calculation_time_data.stamp = this->now(); calculation_time_data.data = stop_watch_.toc(); debug_calculation_time_->publish(calculation_time_data); From ea8f30124e5c3c8a84e923318a43ab1ac82c1353 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 23 Jul 2024 15:01:43 +0900 Subject: [PATCH 206/223] fix(path_optimizer): revert the feature of publishing processing time Signed-off-by: Takayuki Murooka --- .../include/autoware/path_optimizer/node.hpp | 3 +++ planning/autoware_path_optimizer/src/node.cpp | 8 ++------ 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp index 6f75c649e02b2..cad3a9fc89340 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp @@ -22,6 +22,7 @@ #include "autoware/path_optimizer/type_alias.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" @@ -143,6 +144,8 @@ class PathOptimizer : public rclcpp::Node std::unique_ptr logger_configure_; std::unique_ptr published_time_publisher_; + + autoware::universe_utils::StopWatch stop_watch_; }; } // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 7c73d1ad1fee3..f0d101a046206 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -223,6 +223,7 @@ void PathOptimizer::resetPreviousData() void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) { time_keeper_->start_track(__func__); + stop_watch_.tic(); // check if input path is valid if (!checkInputPath(*path_ptr, *get_clock())) { @@ -270,12 +271,7 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) // publish calculation_time // NOTE: This function must be called after measuring onPath calculation time - /* - const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog()); - debug_calculation_time_str_pub_->publish(calculation_time_msg); - debug_calculation_time_float_pub_->publish( - createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); - */ + debug_calculation_time_float_pub_->publish(createFloat64Stamped(now(), stop_watch_.toc())); const auto output_traj_msg = autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); From 4d5789b3ebd0e88b2d3257a0fed01ca5032d3737 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Thu, 1 Aug 2024 17:32:04 +0900 Subject: [PATCH 207/223] fix(tier4_perception_launch): set `use_image_transport` in launch (#8315) set use_image_transport in launch Signed-off-by: MasatoSaeki --- .../traffic_light_node_container.launch.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index 79c99398966da..74b89e9298da4 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -88,7 +88,7 @@ def create_parameter_dict(*args): package="autoware_traffic_light_visualization", plugin="autoware::traffic_light::TrafficLightRoiVisualizerNode", name="traffic_light_roi_visualizer", - parameters=[create_parameter_dict("enable_fine_detection")], + parameters=[create_parameter_dict("enable_fine_detection", "use_image_transport")], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", LaunchConfiguration("output/rois")), @@ -172,6 +172,7 @@ def add_launch_arg(name: str, default_value=None, description=None): classifier_share_dir = get_package_share_directory("autoware_traffic_light_classifier") add_launch_arg("enable_image_decompressor", "True") add_launch_arg("enable_fine_detection", "True") + add_launch_arg("use_image_transport", "True") add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw") add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois") add_launch_arg( From 1980f02e8c0a4aaf63086e9bf8d856b10bbd3ec5 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Mon, 5 Aug 2024 09:16:49 +0900 Subject: [PATCH 208/223] fix(static_obstacle_avoidance): remove invalid small shift lines Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 5e58466fa4229..57a6e340bf853 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -827,6 +827,8 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( data, debug.step1_front_shift_line); + applySmallShiftFilter(ret, 1e-3); + return ret; } From 488e744545aaf6ac0cf396798dba07438681c9c5 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 5 Sep 2024 11:28:24 +0900 Subject: [PATCH 209/223] fix(goal_planner): fix typo (#8763) Signed-off-by: Fumiya Watanabe --- .../src/goal_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 92e15c2c4aee4..f8195ecfea7ec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -459,7 +459,7 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // extract static and dynamic objects in extraction polygon for path coliision check + // extract static and dynamic objects in extraction polygon for path collision check { const auto & p = parameters_; const auto & rh = *(planner_data_->route_handler); From 6c278826c15b6b4acecebc8b5a15867a871b507c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 5 Sep 2024 11:48:57 +0900 Subject: [PATCH 210/223] fix(pointcloud_preprocessor): fix typo (#8762) Signed-off-by: Fumiya Watanabe --- .../launch/vector_map_inside_area_filter_node.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml index 21eded98595ba..795234e185cdd 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml @@ -1,7 +1,7 @@ - + @@ -9,6 +9,6 @@ - + From 1e34b6a35d9a1c9d976bc16ff3de55f85b2ceb9a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 5 Sep 2024 18:00:54 +0900 Subject: [PATCH 211/223] fix(goal_planner): fix object extraction area (#8764) Signed-off-by: kosuke55 --- .../autoware_behavior_path_goal_planner_module/src/util.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index ecb0b1be4e83e..49f70bb8e661b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -191,7 +191,7 @@ std::optional generateObjectExtractionPolygon( constexpr double INTERSECTION_CHECK_DISTANCE = 10.0; std::vector modified_bound{}; size_t i = 0; - while (i < bound.size() - 2) { + while (i < bound.size() - 1) { BoostPoint p1(bound.at(i).x, bound.at(i).y); BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); LineString p_line{}; From a7c1dc2bfe06c45392c3661f879ef4bd8dbecceb Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 5 Sep 2024 22:50:32 +0900 Subject: [PATCH 212/223] fix(goal_planner): fix time_keeper race (#8780) Signed-off-by: Mamoru Sobue --- .../src/goal_planner_module.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index f8195ecfea7ec..dd37d1b30a2a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1243,8 +1243,6 @@ bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -2360,8 +2358,6 @@ std::pair GoalPlannerModule::isSafePath( const std::shared_ptr & objects_filtering_params, const std::shared_ptr & safety_check_params) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } From 0a1e15ed3a1ed477c9962ce42cf6924903bfb644 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Mon, 9 Sep 2024 11:22:06 +0900 Subject: [PATCH 213/223] fix(autoware_pointcloud_preprocessor): static TF listener as Filter option (#8678) Signed-off-by: amadeuszsz --- ...uffer.hpp => managed_transform_buffer.hpp} | 139 +++++++++++++----- ....cpp => test_managed_transform_buffer.cpp} | 96 +++++------- .../autoware_ground_segmentation/README.md | 17 ++- .../docs/ransac-ground-filter.md | 1 + .../docs/ray-ground-filter.md | 1 + .../docs/scan-ground-filter.md | 1 + .../src/ransac_ground_filter/node.cpp | 6 +- .../src/ransac_ground_filter/node.hpp | 4 +- .../config/concatenate_pointclouds.param.yaml | 1 + .../distortion_corrector_node.param.yaml | 1 + .../config/time_synchronizer_node.param.yaml | 1 + .../docs/concatenate-data.md | 13 +- .../concatenate_and_time_sync_nodelet.hpp | 7 +- .../concatenate_pointclouds.hpp | 7 +- .../distortion_corrector.hpp | 19 ++- .../pointcloud_preprocessor/filter.hpp | 12 +- .../time_synchronizer_node.hpp | 7 +- .../concatenate_pointclouds.schema.json | 14 +- .../distortion_corrector_node.schema.json | 7 +- .../schema/time_synchronizer_node.schema.json | 6 + .../concatenate_and_time_sync_nodelet.cpp | 11 +- .../concatenate_pointclouds.cpp | 8 +- .../distortion_corrector.cpp | 6 +- .../distortion_corrector_node.cpp | 6 +- .../src/filter.cpp | 26 +++- .../time_synchronizer_node.cpp | 12 +- .../test/test_distortion_corrector_node.cpp | 4 +- 27 files changed, 269 insertions(+), 164 deletions(-) rename common/autoware_universe_utils/include/autoware/universe_utils/ros/{static_transform_buffer.hpp => managed_transform_buffer.hpp} (54%) rename common/autoware_universe_utils/test/src/ros/{test_static_transform_buffer.cpp => test_managed_transform_buffer.cpp} (59%) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp similarity index 54% rename from common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp rename to common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp index 175d1934e973d..9d96dc9e6b133 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ -#define AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ +#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ #include "autoware/universe_utils/ros/transform_listener.hpp" @@ -29,6 +29,7 @@ #include #include #include +#include #include #include @@ -58,12 +59,69 @@ struct PairEqual } }; using TFMap = std::unordered_map, PairEqual>; +constexpr std::array warn_frames = {"map", "odom", "world"}; -class StaticTransformBuffer +class ManagedTransformBuffer { public: - StaticTransformBuffer() = default; + explicit ManagedTransformBuffer(rclcpp::Node * node, const bool & has_static_tf_only) + : node_(node) + { + if (has_static_tf_only) { + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return getStaticTransform(target_frame, source_frame, eigen_transform); + }; + } else { + tf_listener_ = std::make_unique(node); + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return getDynamicTransform(target_frame, source_frame, eigen_transform); + }; + } + } + + bool getTransform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + return get_transform_(target_frame, source_frame, eigen_transform); + } + + /** + * Transforms a point cloud from one frame to another. + * + * @param target_frame The target frame to transform the point cloud to. + * @param cloud_in The input point cloud to be transformed. + * @param cloud_out The transformed point cloud. + * @return True if the transformation is successful, false otherwise. + */ + bool transformPointcloud( + const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & cloud_in, + sensor_msgs::msg::PointCloud2 & cloud_out) + { + if ( + pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || + pcl::getFieldIndex(cloud_in, "z") == -1) { + RCLCPP_ERROR(node_->get_logger(), "Input pointcloud does not have xyz fields"); + return false; + } + if (target_frame == cloud_in.header.frame_id) { + cloud_out = cloud_in; + return true; + } + Eigen::Matrix4f eigen_transform; + if (!getTransform(target_frame, cloud_in.header.frame_id, eigen_transform)) { + return false; + } + pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); + cloud_out.header.frame_id = target_frame; + return true; + } +private: /** * @brief Retrieves a transform between two static frames. * @@ -72,17 +130,24 @@ class StaticTransformBuffer * Otherwise, transform matrix is set to identity and the function returns false. Transform * Listener is destroyed after function call. * - * @param node A pointer to the ROS node. * @param target_frame The target frame. * @param source_frame The source frame. - * @param eigen_transform The output Eigen transform matrix. Is set to identity if the transform - * is not found. + * @param eigen_transform The output Eigen transform matrix. It is set to the identity if the + * transform is not found. * @return True if the transform was successfully retrieved, false otherwise. */ - bool getTransform( - rclcpp::Node * node, const std::string & target_frame, const std::string & source_frame, + bool getStaticTransform( + const std::string & target_frame, const std::string & source_frame, Eigen::Matrix4f & eigen_transform) { + if ( + std::find(warn_frames.begin(), warn_frames.end(), target_frame) != warn_frames.end() || + std::find(warn_frames.begin(), warn_frames.end(), source_frame) != warn_frames.end()) { + RCLCPP_WARN( + node_->get_logger(), "Using %s -> %s transform. This may not be a static transform.", + target_frame.c_str(), source_frame.c_str()); + } + auto key = std::make_pair(target_frame, source_frame); auto key_inv = std::make_pair(source_frame, target_frame); @@ -109,11 +174,12 @@ class StaticTransformBuffer } // Get the transform from the TF tree - auto tf_listener = std::make_unique(node); - auto tf = tf_listener->getTransform( + tf_listener_ = std::make_unique(node_); + auto tf = tf_listener_->getTransform( target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + tf_listener_.reset(); RCLCPP_DEBUG( - node->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", + node_->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", target_frame.c_str(), source_frame.c_str()); if (tf == nullptr) { eigen_transform = Eigen::Matrix4f::Identity(); @@ -124,42 +190,39 @@ class StaticTransformBuffer return true; } - /** - * Transforms a point cloud from one frame to another. + /** @brief Retrieves a transform between two dynamic frames. * - * @param node A pointer to the ROS node. - * @param target_frame The target frame to transform the point cloud to. - * @param cloud_in The input point cloud to be transformed. - * @param cloud_out The transformed point cloud. - * @return True if the transformation is successful, false otherwise. + * This function attempts to retrieve a transform between the target frame and the source frame. + * If successful, the transformation matrix is assigned to the output parameter, and the function + * returns true. Otherwise, the transformation matrix is set to the identity and the function + * returns false. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transformation matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. */ - bool transformPointcloud( - rclcpp::Node * node, const std::string & target_frame, - const sensor_msgs::msg::PointCloud2 & cloud_in, sensor_msgs::msg::PointCloud2 & cloud_out) + bool getDynamicTransform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { - if ( - pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || - pcl::getFieldIndex(cloud_in, "z") == -1) { - RCLCPP_ERROR(node->get_logger(), "Input pointcloud does not have xyz fields"); - return false; - } - if (target_frame == cloud_in.header.frame_id) { - cloud_out = cloud_in; - return true; - } - Eigen::Matrix4f eigen_transform; - if (!getTransform(node, target_frame, cloud_in.header.frame_id, eigen_transform)) { + auto tf = tf_listener_->getTransform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); return false; } - pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); - cloud_out.header.frame_id = target_frame; + pcl_ros::transformAsMatrix(*tf, eigen_transform); return true; } -private: TFMap buffer_; + rclcpp::Node * const node_; + std::unique_ptr tf_listener_; + std::function get_transform_; }; } // namespace autoware::universe_utils -#endif // AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ +#endif // AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ diff --git a/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp similarity index 59% rename from common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp rename to common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp index 5200378e3bf52..9df6f9bb2ffef 100644 --- a/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/universe_utils/ros/static_transform_buffer.hpp" +#include "autoware/universe_utils/ros/managed_transform_buffer.hpp" #include #include @@ -22,11 +22,11 @@ #include -class TestStaticTransformBuffer : public ::testing::Test +class TestManagedTransformBuffer : public ::testing::Test { protected: std::shared_ptr node_{nullptr}; - std::shared_ptr static_tf_buffer_{nullptr}; + std::shared_ptr managed_tf_buffer_{nullptr}; std::shared_ptr tf_broadcaster_; geometry_msgs::msg::TransformStamped tf_base_to_lidar_; Eigen::Matrix4f eigen_base_to_lidar_; @@ -54,8 +54,9 @@ class TestStaticTransformBuffer : public ::testing::Test void SetUp() override { - node_ = std::make_shared("test_static_transform_buffer"); - static_tf_buffer_ = std::make_shared(); + node_ = std::make_shared("test_managed_transform_buffer"); + managed_tf_buffer_ = + std::make_shared(node_.get(), true); tf_broadcaster_ = std::make_shared(node_); tf_base_to_lidar_ = generateTransformMsg( @@ -91,109 +92,91 @@ class TestStaticTransformBuffer : public ::testing::Test ASSERT_TRUE(rclcpp::ok()); } - void TearDown() override { static_tf_buffer_.reset(); } + void TearDown() override { managed_tf_buffer_.reset(); } }; -TEST_F(TestStaticTransformBuffer, TestTransformNoExist) +TEST_F(TestManagedTransformBuffer, TestTransformNoExist) { Eigen::Matrix4f transform; - auto success = static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", transform); + auto success = managed_tf_buffer_->getTransform("base_link", "fake_link", transform); EXPECT_TRUE(transform.isIdentity()); EXPECT_FALSE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformBase) +TEST_F(TestManagedTransformBuffer, TestTransformBase) { Eigen::Matrix4f eigen_base_to_lidar; - auto success = - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_base_to_lidar); + auto success = managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_base_to_lidar); EXPECT_TRUE(eigen_base_to_lidar.isApprox(eigen_base_to_lidar_, 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformSameFrame) +TEST_F(TestManagedTransformBuffer, TestTransformSameFrame) { Eigen::Matrix4f eigen_base_to_base; - auto success = - static_tf_buffer_->getTransform(node_.get(), "base_link", "base_link", eigen_base_to_base); + auto success = managed_tf_buffer_->getTransform("base_link", "base_link", eigen_base_to_base); EXPECT_TRUE(eigen_base_to_base.isApprox(Eigen::Matrix4f::Identity(), 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformInverse) +TEST_F(TestManagedTransformBuffer, TestTransformInverse) { Eigen::Matrix4f eigen_lidar_to_base; - auto success = - static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_lidar_to_base); + auto success = managed_tf_buffer_->getTransform("lidar_top", "base_link", eigen_lidar_to_base); EXPECT_TRUE(eigen_lidar_to_base.isApprox(eigen_base_to_lidar_.inverse(), 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformMultipleCall) +TEST_F(TestManagedTransformBuffer, TestTransformMultipleCall) { Eigen::Matrix4f eigen_transform; - EXPECT_FALSE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", eigen_transform)); + EXPECT_FALSE(managed_tf_buffer_->getTransform("base_link", "fake_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("lidar_top", "base_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_.inverse(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "fake_link", "fake_link", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("fake_link", "fake_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001)); - EXPECT_FALSE( - static_tf_buffer_->getTransform(node_.get(), "fake_link", "lidar_top", eigen_transform)); + EXPECT_FALSE(managed_tf_buffer_->getTransform("fake_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001)); } -TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloud) +TEST_F(TestManagedTransformBuffer, TestTransformEmptyPointCloud) { auto cloud_in = std::make_unique(); cloud_in->header.frame_id = "lidar_top"; cloud_in->header.stamp = rclcpp::Time(10, 100'000'000); auto cloud_out = std::make_unique(); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloudNoHeader) +TEST_F(TestManagedTransformBuffer, TestTransformEmptyPointCloudNoHeader) { auto cloud_in = std::make_unique(); auto cloud_out = std::make_unique(); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformPointCloud) +TEST_F(TestManagedTransformBuffer, TestTransformPointCloud) { auto cloud_out = std::make_unique(); // Transform cloud with header - EXPECT_TRUE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in_, *cloud_out)); - EXPECT_TRUE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in_, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in_, *cloud_out)); + EXPECT_TRUE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in_, *cloud_out)); + EXPECT_TRUE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in_, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in_, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformPointCloudNoHeader) +TEST_F(TestManagedTransformBuffer, TestTransformPointCloudNoHeader) { auto cloud_out = std::make_unique(); @@ -201,10 +184,7 @@ TEST_F(TestStaticTransformBuffer, TestTransformPointCloudNoHeader) auto cloud_in = std::make_unique(*cloud_in_); cloud_in->header.frame_id = ""; cloud_in->header.stamp = rclcpp::Time(0, 0); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } diff --git a/perception/autoware_ground_segmentation/README.md b/perception/autoware_ground_segmentation/README.md index b981b02e0a844..08b8a4f373bcc 100644 --- a/perception/autoware_ground_segmentation/README.md +++ b/perception/autoware_ground_segmentation/README.md @@ -33,14 +33,15 @@ Detail description of each ground segmentation algorithm is in the following lin ### Node Parameters -| Name | Type | Default Value | Description | -| ------------------ | ------ | ------------- | ------------------------------------- | -| `input_frame` | string | " " | input frame id | -| `output_frame` | string | " " | output frame id | -| `max_queue_size` | int | 5 | max queue size of input/output topics | -| `use_indices` | bool | false | flag to use pointcloud indices | -| `latched_indices` | bool | false | flag to latch pointcloud indices | -| `approximate_sync` | bool | false | flag to use approximate sync option | +| Name | Type | Default Value | Description | +| -------------------- | ------ | ------------- | ------------------------------------- | +| `input_frame` | string | " " | input frame id | +| `output_frame` | string | " " | output frame id | +| `has_static_tf_only` | bool | false | flag to listen TF only once | +| `max_queue_size` | int | 5 | max queue size of input/output topics | +| `use_indices` | bool | false | flag to use pointcloud indices | +| `latched_indices` | bool | false | flag to latch pointcloud indices | +| `approximate_sync` | bool | false | flag to use approximate sync option | ## Assumptions / Known limits diff --git a/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md b/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md index a11a35521d173..37388e665eb2c 100644 --- a/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md @@ -23,6 +23,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | Name | Type | Description | | ----------------------- | ------ | --------------------------------------------------------------- | | `base_frame` | string | base_link frame | +| `has_static_tf_only` | bool | Flag to listen TF only once | | `unit_axis` | string | The axis which we need to search ground plane | | `max_iterations` | int | The maximum number of iterations | | `outlier_threshold` | double | The distance threshold to the model [m] | diff --git a/perception/autoware_ground_segmentation/docs/ray-ground-filter.md b/perception/autoware_ground_segmentation/docs/ray-ground-filter.md index 9b80b0588f851..ed4f5833b3b3a 100644 --- a/perception/autoware_ground_segmentation/docs/ray-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/ray-ground-filter.md @@ -28,6 +28,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | ----------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | | `input_frame` | string | frame id of input pointcloud | | `output_frame` | string | frame id of output pointcloud | +| `has_static_tf_only` | bool | Flag to listen TF only once | | `general_max_slope` | double | The triangle created by `general_max_slope` is called the global cone. If the point is outside the global cone, it is judged to be a point that is no on the ground | | `initial_max_slope` | double | Generally, the point where the object first hits is far from ego-vehicle because of sensor blind spot, so resolution is different from that point and thereafter, so this parameter exists to set a separate `local_max_slope` | | `local_max_slope` | double | The triangle created by `local_max_slope` is called the local cone. This parameter for classification based on the continuity of points | diff --git a/perception/autoware_ground_segmentation/docs/scan-ground-filter.md b/perception/autoware_ground_segmentation/docs/scan-ground-filter.md index bdd46cffb7df4..392bed89ac902 100644 --- a/perception/autoware_ground_segmentation/docs/scan-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/scan-ground-filter.md @@ -35,6 +35,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | --------------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | `input_frame` | string | "base_link" | frame id of input pointcloud | | `output_frame` | string | "base_link" | frame id of output pointcloud | +| `has_static_tf_only` | bool | false | Flag to listen TF only once | | `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | | `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | | `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp index 4d45f5df07027..e2f96d862e1a6 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp @@ -116,7 +116,8 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS); - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } void RANSACGroundFilterComponent::setDebugPublisher() @@ -163,8 +164,7 @@ bool RANSACGroundFilterComponent::transformPointCloud( return true; } - return static_tf_buffer_->transformPointcloud( - this, in_target_frame, *in_cloud_ptr, *out_cloud_ptr); + return managed_tf_buffer_->transformPointcloud(in_target_frame, *in_cloud_ptr, *out_cloud_ptr); } void RANSACGroundFilterComponent::extractPointsIndices( diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp index bdc217e80650c..b36a7f5e55fc4 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp @@ -17,7 +17,7 @@ #include "autoware/pointcloud_preprocessor/filter.hpp" -#include +#include #include #include @@ -83,7 +83,7 @@ class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Fi bool debug_ = false; bool is_initialized_debug_message_ = false; Eigen::Vector3d unit_vec_ = Eigen::Vector3d::UnitZ(); - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml index 5d38186840057..449795c328402 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: output_frame: base_link + has_static_tf_only: true input_topics: [ "/sensing/lidar/left/pointcloud_before_sync", "/sensing/lidar/right/pointcloud_before_sync", diff --git a/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml index 3afa4816271cb..eca08c37b6458 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml @@ -3,3 +3,4 @@ base_frame: base_link use_imu: true use_3d_distortion_correction: false + has_static_tf_only: true diff --git a/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml index 9add0be3f8809..7e5bd0fd96bcf 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml @@ -3,6 +3,7 @@ input_twist_topic_type: twist output_frame: base_link keep_input_frame_in_synchronized_pointcloud: false + has_static_tf_only: true input_topics: [ "/sensing/lidar/left/pointcloud_before_sync", "/sensing/lidar/right/pointcloud_before_sync", diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 74b4f3df17615..08f7b92f88975 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -28,12 +28,13 @@ The figure below represents the reception time of each sensor data and how it is ## Parameters -| Name | Type | Default Value | Description | -| ---------------- | ---------------- | ------------- | ------------------------------------------------------------------- | -| `input/points` | vector of string | [] | input topic names that type must be `sensor_msgs::msg::Pointcloud2` | -| `input_frame` | string | "" | input frame id | -| `output_frame` | string | "" | output frame id | -| `max_queue_size` | int | 5 | max queue size of input/output topics | +| Name | Type | Default Value | Description | +| -------------------- | ---------------- | ------------- | ------------------------------------------------------------------- | +| `input/points` | vector of string | [] | input topic names that type must be `sensor_msgs::msg::Pointcloud2` | +| `input_frame` | string | "" | input frame id | +| `output_frame` | string | "" | output frame id | +| `has_static_tf_only` | bool | false | flag to listen TF only once | +| `max_queue_size` | int | 5 | max queue size of input/output topics | ### Core Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 549a60e49d748..977adc59cd7e5 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -64,7 +64,7 @@ #include "autoware_point_types/types.hpp" #include -#include +#include #include #include #include @@ -146,11 +146,14 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node /** \brief Output TF frame the concatenated points should be transformed to. */ std::string output_frame_; + /** \brief The flag to indicate if only static TF are used. */ + bool has_static_tf_only_; + /** \brief Input point cloud topics. */ // XmlRpc::XmlRpcValue input_topics_; std::vector input_topics_; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index 9711025b713df..b7e0e86ca1d3a 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -62,7 +62,7 @@ // ROS includes #include -#include +#include #include #include #include @@ -135,11 +135,14 @@ class PointCloudConcatenationComponent : public rclcpp::Node /** \brief Output TF frame the concatenated points should be transformed to. */ std::string output_frame_; + /** \brief The flag to indicate if only static TF are used. */ + bool has_static_tf_only_; + /** \brief Input point cloud topics. */ // XmlRpc::XmlRpcValue input_topics_; std::vector input_topics_; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 7ba419770af17..e786bff04b3cd 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ #include -#include +#include #include #include @@ -74,7 +74,7 @@ class DistortionCorrector : public DistortionCorrectorBase bool pointcloud_transform_exists_{false}; bool imu_transform_exists_{false}; rclcpp::Node * node_; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_queue_; std::deque angular_velocity_queue_; @@ -99,9 +99,10 @@ class DistortionCorrector : public DistortionCorrectorBase void convertMatrixToTransform(const Eigen::Matrix4f & matrix, tf2::Transform & transform); public: - explicit DistortionCorrector(rclcpp::Node * node) : node_(node) + explicit DistortionCorrector(rclcpp::Node * node, const bool & has_static_tf_only) : node_(node) { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(node, has_static_tf_only); } bool pointcloud_transform_exists(); bool pointcloud_transform_needed(); @@ -133,7 +134,10 @@ class DistortionCorrector2D : public DistortionCorrector tf2::Transform tf2_base_link_to_lidar_; public: - explicit DistortionCorrector2D(rclcpp::Node * node) : DistortionCorrector(node) {} + explicit DistortionCorrector2D(rclcpp::Node * node, const bool & has_static_tf_only) + : DistortionCorrector(node, has_static_tf_only) + { + } void initialize() override; void undistortPointImplementation( sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, @@ -160,7 +164,10 @@ class DistortionCorrector3D : public DistortionCorrector Eigen::Matrix4f eigen_base_link_to_lidar_; public: - explicit DistortionCorrector3D(rclcpp::Node * node) : DistortionCorrector(node) {} + explicit DistortionCorrector3D(rclcpp::Node * node, const bool & has_static_tf_only) + : DistortionCorrector(node, has_static_tf_only) + { + } void initialize() override; void undistortPointImplementation( sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp index 789f377e7ec95..b39be3cfaf9e5 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp @@ -74,15 +74,10 @@ #include #include -// Include TF -#include -#include -#include - // Include tier4 autoware utils #include +#include #include -#include #include namespace autoware::pointcloud_preprocessor @@ -174,6 +169,9 @@ class Filter : public rclcpp::Node * if input.header.frame_id is different. */ std::string tf_output_frame_; + /** \brief The flag to indicate if only static TF are used. */ + bool has_static_tf_only_; + /** \brief Internal mutex. */ std::mutex mutex_; @@ -240,7 +238,7 @@ class Filter : public rclcpp::Node * versus an exact one (false by default). */ bool approximate_sync_ = false; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; inline bool isValid( const PointCloud2ConstPtr & cloud, const std::string & /*topic_name*/ = "input") diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp index ad5cde3056ef0..b02860a6f112e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp @@ -62,7 +62,7 @@ // ROS includes #include -#include +#include #include #include #include @@ -140,11 +140,14 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node std::string output_frame_; bool keep_input_frame_in_synchronized_pointcloud_; + /** \brief The flag to indicate if only static TF are used. */ + bool has_static_tf_only_; + /** \brief Input point cloud topics. */ // XmlRpc::XmlRpcValue input_topics_; std::vector input_topics_; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json index 916650c69a68b..19044f851bda6 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json @@ -25,6 +25,11 @@ "default": "base_link", "description": "Output frame id." }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, "input_topics": { "type": "array", "items": { @@ -40,7 +45,14 @@ "description": "Max queue size of input/output topics." } }, - "required": ["timeout_sec", "input_offset", "output_frame", "input_topics", "max_queue_size"] + "required": [ + "timeout_sec", + "input_offset", + "output_frame", + "has_static_tf_only", + "input_topics", + "max_queue_size" + ] } }, "properties": { diff --git a/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json index acf67fd2746c4..75579227981ac 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json @@ -20,9 +20,14 @@ "type": "boolean", "description": "Use 3d distortion correction algorithm, otherwise, use 2d distortion correction algorithm.", "default": "false" + }, + "has_static_tf_only": { + "type": "boolean", + "description": "Flag to indicate if only static TF is used.", + "default": false } }, - "required": ["base_frame", "use_imu", "use_3d_distortion_correction"] + "required": ["base_frame", "use_imu", "use_3d_distortion_correction", "has_static_tf_only"] } }, "properties": { diff --git a/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json index 8954fcaf6d814..90c14b50508db 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json @@ -31,6 +31,11 @@ "default": "base_link", "description": "Output frame." }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, "keep_input_frame_in_synchronized_pointcloud": { "type": "boolean", "default": true, @@ -61,6 +66,7 @@ "input_offset", "input_twist_topic_type", "output_frame", + "has_static_tf_only", "keep_input_frame_in_synchronized_pointcloud", "input_topics", "synchronized_pointcloud_postfix", diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index 0a051d780f5f7..d0911f769d3bd 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -92,6 +92,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); return; } + has_static_tf_only_ = declare_parameter("has_static_tf_only", false); declare_parameter("input_topics", std::vector()); input_topics_ = get_parameter("input_topics").as_string_array(); if (input_topics_.empty()) { @@ -137,7 +138,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Output Publishers @@ -361,8 +363,7 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds( } sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); // calculate transforms to oldest stamp Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); @@ -392,8 +393,8 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds( if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, + managed_tf_buffer_->transformPointcloud( + e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, *transformed_cloud_ptr_in_sensor_frame); transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; transformed_cloud_ptr_in_sensor_frame->header.frame_id = e.second->header.frame_id; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index e9078cbe717cb..5e1911c93409d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -54,6 +54,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); return; } + has_static_tf_only_ = declare_parameter( + "has_static_tf_only", false); // TODO(amadeuszsz): remove default value declare_parameter>("input_topics"); input_topics_ = get_parameter("input_topics").as_string_array(); if (input_topics_.empty()) { @@ -93,7 +95,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Output Publishers @@ -237,8 +240,7 @@ void PointCloudConcatenationComponent::combineClouds( // transform to output frame sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); // concatenate if (concat_cloud_ptr == nullptr) { diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index affa6d901be2d..d0119fbc44f24 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -90,7 +90,7 @@ void DistortionCorrector::getIMUTransformation( tf2::Transform tf2_imu_to_base_link; Eigen::Matrix4f eigen_imu_to_base_link; imu_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, imu_frame, eigen_imu_to_base_link); + managed_tf_buffer_->getTransform(base_frame, imu_frame, eigen_imu_to_base_link); convertMatrixToTransform(eigen_imu_to_base_link, tf2_imu_to_base_link); geometry_imu_to_base_link_ptr_ = std::make_shared(); @@ -311,7 +311,7 @@ void DistortionCorrector2D::setPointCloudTransform( Eigen::Matrix4f eigen_lidar_to_base_link; pointcloud_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, lidar_frame, eigen_lidar_to_base_link); + managed_tf_buffer_->getTransform(base_frame, lidar_frame, eigen_lidar_to_base_link); convertMatrixToTransform(eigen_lidar_to_base_link, tf2_lidar_to_base_link_); tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_.inverse(); pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_; @@ -325,7 +325,7 @@ void DistortionCorrector3D::setPointCloudTransform( } pointcloud_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, lidar_frame, eigen_lidar_to_base_link_); + managed_tf_buffer_->getTransform(base_frame, lidar_frame, eigen_lidar_to_base_link_); eigen_base_link_to_lidar_ = eigen_lidar_to_base_link_.inverse(); pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_; } diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp index 822bb2ba5add5..8e4eaa6ec8f11 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -35,6 +35,8 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt base_frame_ = declare_parameter("base_frame"); use_imu_ = declare_parameter("use_imu"); use_3d_distortion_correction_ = declare_parameter("use_3d_distortion_correction"); + auto has_static_tf_only = + declare_parameter("has_static_tf_only", false); // TODO(amadeuszsz): remove default value // Publisher { @@ -59,9 +61,9 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt // Setup the distortion corrector if (use_3d_distortion_correction_) { - distortion_corrector_ = std::make_unique(this); + distortion_corrector_ = std::make_unique(this, has_static_tf_only); } else { - distortion_corrector_ = std::make_unique(this); + distortion_corrector_ = std::make_unique(this, has_static_tf_only); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp index de6549463e7ff..62495fc8b70cb 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp @@ -72,6 +72,7 @@ autoware::pointcloud_preprocessor::Filter::Filter( { tf_input_frame_ = static_cast(declare_parameter("input_frame", "")); tf_output_frame_ = static_cast(declare_parameter("output_frame", "")); + has_static_tf_only_ = static_cast(declare_parameter("has_static_tf_only", false)); max_queue_size_ = static_cast(declare_parameter("max_queue_size", 5)); // ---[ Optional parameters @@ -114,7 +115,17 @@ autoware::pointcloud_preprocessor::Filter::Filter( ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void autoware::pointcloud_preprocessor::Filter::setupTF() { - static_tf_buffer_ = std::make_unique(); + // Always consider static TF if in & out frames are same + if (tf_input_frame_ == tf_output_frame_) { + if (!has_static_tf_only_) { + RCLCPP_INFO( + this->get_logger(), + "Input and output frames are the same. Overriding has_static_tf_only to true."); + } + has_static_tf_only_ = true; + } + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -269,7 +280,7 @@ void autoware::pointcloud_preprocessor::Filter::input_indices_callback( // Convert the cloud into the different frame PointCloud2 cloud_transformed; - if (!static_tf_buffer_->transformPointcloud(this, tf_input_frame_, *cloud, cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud(tf_input_frame_, *cloud, cloud_transformed)) { return; } cloud_tf = std::make_shared(cloud_transformed); @@ -298,8 +309,8 @@ bool autoware::pointcloud_preprocessor::Filter::calculate_transform_matrix( this->get_logger(), "[get_transform_matrix] Transforming input dataset from %s to %s.", from.header.frame_id.c_str(), target_frame.c_str()); - if (!static_tf_buffer_->getTransform( - this, target_frame, from.header.frame_id, transform_info.eigen_transform)) { + if (!managed_tf_buffer_->getTransform( + target_frame, from.header.frame_id, transform_info.eigen_transform)) { return false; } @@ -321,8 +332,7 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( // Convert the cloud into the different frame auto cloud_transformed = std::make_unique(); - if (!static_tf_buffer_->transformPointcloud( - this, tf_output_frame_, *output, *cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud(tf_output_frame_, *output, *cloud_transformed)) { RCLCPP_ERROR( this->get_logger(), "[convert_output_costly] Error converting output dataset from %s to %s.", @@ -342,8 +352,8 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( auto cloud_transformed = std::make_unique(); - if (!static_tf_buffer_->transformPointcloud( - this, tf_input_orig_frame_, *output, *cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud( + tf_input_orig_frame_, *output, *cloud_transformed)) { return false; } diff --git a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp index 3f6f37fd31720..e34c165383867 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp @@ -58,6 +58,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( std::string synchronized_pointcloud_postfix; { output_frame_ = declare_parameter("output_frame"); + has_static_tf_only_ = declare_parameter( + "has_static_tf_only", false); // TODO(amadeuszsz): remove default value keep_input_frame_in_synchronized_pointcloud_ = declare_parameter("keep_input_frame_in_synchronized_pointcloud"); if (output_frame_.empty() && !keep_input_frame_in_synchronized_pointcloud_) { @@ -109,7 +111,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Subscribers @@ -320,8 +323,7 @@ PointCloudDataSynchronizerComponent::synchronizeClouds() continue; } // transform pointcloud to output frame - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); // calculate transforms to oldest stamp and transform pointcloud to oldest stamp Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); @@ -341,8 +343,8 @@ PointCloudDataSynchronizerComponent::synchronizeClouds() sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr_in_input_frame( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, + managed_tf_buffer_->transformPointcloud( + e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, *transformed_delay_compensated_cloud_ptr_in_input_frame); transformed_delay_compensated_cloud_ptr = transformed_delay_compensated_cloud_ptr_in_input_frame; diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index f90314a001105..047d021a4c6da 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -48,9 +48,9 @@ class DistortionCorrectorTest : public ::testing::Test { node_ = std::make_shared("test_node"); distortion_corrector_2d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get(), true); distortion_corrector_3d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get(), true); // Setup TF tf_broadcaster_ = std::make_shared(node_); From 5f5d08b3495db13af41781bcee143f6b643e6d35 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 19 Sep 2024 12:00:24 +0900 Subject: [PATCH 214/223] fix(goal_planner): fix typo (#8910) Signed-off-by: Fumiya Watanabe --- .../examples/plot_map.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp index 6b750bc9674f3..a51b2fd337512 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp @@ -258,10 +258,10 @@ int main(int argc, char ** argv) const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info); - autoware::lane_departure_checker::Param lane_depature_checker_params; - lane_depature_checker_params.footprint_extra_margin = + autoware::lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = goal_planner_parameter.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_depature_checker_params); + lane_departure_checker.setParam(lane_departure_checker_params); auto shift_pull_over_planner = autoware::behavior_path_planner::ShiftPullOver( *node, goal_planner_parameter, lane_departure_checker); const auto pull_over_path_opt = From 0726690521ead842bc6a8187f9c7ae67c71ccf46 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 19 Sep 2024 13:03:00 +0900 Subject: [PATCH 215/223] fix(intersection): fix typo (#8911) * fix(intersection): fix typo Signed-off-by: Fumiya Watanabe * fix(intersection): fix typo Signed-off-by: Fumiya Watanabe * style(pre-commit): autofix --------- Signed-off-by: Fumiya Watanabe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/util.cpp | 39 ++++++++++--------- .../src/util.hpp | 6 +-- 2 files changed, 23 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index c48588bc5386d..a446493793c53 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -217,31 +217,32 @@ std::optional getFirstPointInsidePolygon( } void retrievePathsBackward( - const std::vector> & adjacency, const size_t src_ind, - const std::vector & visited_inds, std::vector> & paths) + const std::vector> & adjacency, const size_t src_index, + const std::vector & visited_indices, std::vector> & paths) { - const auto & nexts = adjacency.at(src_ind); - const bool is_terminal = (std::find(nexts.begin(), nexts.end(), true) == nexts.end()); + const auto & next_indices = adjacency.at(src_index); + const bool is_terminal = + (std::find(next_indices.begin(), next_indices.end(), true) == next_indices.end()); if (is_terminal) { - std::vector path(visited_inds.begin(), visited_inds.end()); - path.push_back(src_ind); + std::vector path(visited_indices.begin(), visited_indices.end()); + path.push_back(src_index); paths.emplace_back(std::move(path)); return; } - for (size_t next = 0; next < nexts.size(); next++) { - if (!nexts.at(next)) { + for (size_t next = 0; next < next_indices.size(); next++) { + if (!next_indices.at(next)) { continue; } - if (std::find(visited_inds.begin(), visited_inds.end(), next) != visited_inds.end()) { + if (std::find(visited_indices.begin(), visited_indices.end(), next) != visited_indices.end()) { // loop detected - std::vector path(visited_inds.begin(), visited_inds.end()); - path.push_back(src_ind); + std::vector path(visited_indices.begin(), visited_indices.end()); + path.push_back(src_index); paths.emplace_back(std::move(path)); continue; } - auto new_visited_inds = visited_inds; - new_visited_inds.push_back(src_ind); - retrievePathsBackward(adjacency, next, new_visited_inds, paths); + auto new_visited_indices = visited_indices; + new_visited_indices.push_back(src_index); + retrievePathsBackward(adjacency, next, new_visited_indices, paths); } return; } @@ -263,10 +264,10 @@ mergeLaneletsByTopologicalSort( ind2Id[ind] = Id; Id2lanelet[Id] = lanelet; } - std::set terminal_inds; + std::set terminal_indices; for (const auto & terminal_lanelet : terminal_lanelets) { if (Id2ind.count(terminal_lanelet.id()) > 0) { - terminal_inds.insert(Id2ind[terminal_lanelet.id()]); + terminal_indices.insert(Id2ind[terminal_lanelet.id()]); } } @@ -292,7 +293,7 @@ mergeLaneletsByTopologicalSort( } std::unordered_map>> branches; - for (const auto & terminal_ind : terminal_inds) { + for (const auto & terminal_ind : terminal_indices) { std::vector> paths; std::vector visited; retrievePathsBackward(adjacency, terminal_ind, visited, paths); @@ -311,11 +312,11 @@ mergeLaneletsByTopologicalSort( if (sub_branches.size() == 0) { continue; } - for (const auto & sub_inds : sub_branches) { + for (const auto & sub_indices : sub_branches) { lanelet::ConstLanelets to_be_merged; originals.push_back(lanelet::ConstLanelets({})); auto & original = originals.back(); - for (const auto & sub_ind : sub_inds) { + for (const auto & sub_ind : sub_indices) { to_be_merged.push_back(Id2lanelet[ind2Id[sub_ind]]); original.push_back(Id2lanelet[ind2Id[sub_ind]]); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp index 6167e7a366295..0fac44f6cdf97 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -105,11 +105,11 @@ mergeLaneletsByTopologicalSort( /** * @brief this functions retrieves all the paths from the given source to terminal nodes on the tree - @param[in] visited_inds visited node indices excluding src_ind so far + @param[in] visited_indices visited node indices excluding src_ind so far */ void retrievePathsBackward( - const std::vector> & adjacency, const size_t src_ind, - const std::vector & visited_inds, std::vector> & paths); + const std::vector> & adjacency, const size_t src_index, + const std::vector & visited_indices, std::vector> & paths); /** * @brief find the index of the first point where vehicle footprint intersects with the given From 3c230ebc0744cf93e9669f87f4e12cf89cf9b120 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 19 Sep 2024 18:46:22 +0900 Subject: [PATCH 216/223] fix(lane_change): set initail rtc state properly (#8902) set initail rtc state properly Signed-off-by: Go Sakayori --- .../src/interface.cpp | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 61daf1183e993..7ddafdbd6c935 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -125,16 +125,21 @@ BehaviorModuleOutput LaneChangeInterface::plan() } else { const auto path = assignToCandidate(module_type_->getLaneChangePath(), module_type_->getEgoPosition()); - const auto force_activated = std::any_of( + const auto is_registered = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), - [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); - if (!force_activated) { + [&](const auto & rtc) { return rtc.second->isRegistered(uuid_map_.at(rtc.first)); }); + + if (!is_registered) { updateRTCStatus( path.start_distance_to_path_change, path.finish_distance_to_path_change, true, - State::RUNNING); + State::WAITING_FOR_EXECUTION); } else { + const auto force_activated = std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), + [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); + const bool safe = force_activated ? false : true; updateRTCStatus( - path.start_distance_to_path_change, path.finish_distance_to_path_change, false, + path.start_distance_to_path_change, path.finish_distance_to_path_change, safe, State::RUNNING); } } From 1412557da91d3d6f8b5c9ec8ad526424f5a5b7c6 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 19 Sep 2024 14:32:27 +0900 Subject: [PATCH 217/223] refactor(start_planner,raw_vechile_cmd_converter): align parameter with autoware_launch's parameter (#8913) * align autoware_raw_vehicle_cmd_converter's parameter Signed-off-by: kyoichi-sugahara * align start_planner's parameter Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../config/start_planner.param.yaml | 11 +++++++++-- .../config/raw_vehicle_cmd_converter.param.yaml | 2 +- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml index f93800450a479..a71c202b05043 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml @@ -69,10 +69,11 @@ search_configs: theta_size: 120 angle_goal_range: 6.0 - curve_weight: 0.5 - reverse_weight: 1.0 lateral_goal_range: 0.5 longitudinal_goal_range: 2.0 + curve_weight: 0.5 + reverse_weight: 1.0 + direction_change_weight: 1.5 # costmap configs costmap_configs: obstacle_threshold: 30 @@ -81,7 +82,13 @@ search_method: "forward" # options: forward, backward only_behind_solutions: false use_back: true + adapt_expansion_distance: true + expansion_distance: 0.5 + near_goal_distance: 3.0 distance_heuristic_weight: 2.0 + smoothness_weight: 0.5 + obstacle_distance_weight: 1.75 + goal_lat_distance_weight: 5.0 # -- RRT* search Configurations -- rrtstar: enable_update: true diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml index 4eb9f0ab6d442..e108de527ecbc 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml @@ -5,7 +5,7 @@ csv_path_steer_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/steer_map.csv convert_accel_cmd: true convert_brake_cmd: true - convert_steer_cmd: true + convert_steer_cmd: false use_steer_ff: true use_steer_fb: true is_debugging: false From 3ae8633a7e87457ca110f36c072a2e66758e3899 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Sep 2024 15:19:37 +0900 Subject: [PATCH 218/223] chore(mpc_lateral_controller): consistent parameters with autoware_launch (#8914) Signed-off-by: Takayuki Murooka --- .../param/lateral_controller_defaults.param.yaml | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml b/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml index de194a8902a7d..b358e95f86f99 100644 --- a/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml +++ b/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml @@ -47,7 +47,7 @@ # -- vehicle model -- vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics input_delay: 0.24 # steering input delay time for delay compensation - vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s] + vehicle_model_steer_tau: 0.27 # steering dynamics time constant (1d approximation) [s] steer_rate_lim_dps_list_by_curvature: [40.0, 50.0, 60.0] # steering angle rate limit list depending on curvature [deg/s] curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m] steer_rate_lim_dps_list_by_velocity: [60.0, 50.0, 40.0] # steering angle rate limit list depending on velocity [deg/s] @@ -76,13 +76,4 @@ average_num: 1000 steering_offset_limit: 0.02 - # vehicle parameters - mass_kg: 2400.0 - mass_fl: 600.0 - mass_fr: 600.0 - mass_rl: 600.0 - mass_rr: 600.0 - cf: 155494.663 - cr: 155494.663 - publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose From ed81a555a3eae4806c81296cc011cd3ebdc1ace6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Sep 2024 16:02:09 +0900 Subject: [PATCH 219/223] chore(planning): consistent parameters with autoware_launch (#8915) * chore(planning): consistent parameters with autoware_launch Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix json schema Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/adaptive_cruise_control.param.yaml | 4 ++-- .../config/obstacle_stop_planner.param.yaml | 23 ++++++++++--------- .../schema/obstacle_stop_planner.schema.json | 5 ++++ .../config/goal_planner.param.yaml | 15 +++++++++--- .../config/behavior_path_planner.param.yaml | 1 + .../config/out_of_lane.param.yaml | 1 + 6 files changed, 33 insertions(+), 16 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/config/adaptive_cruise_control.param.yaml b/planning/autoware_obstacle_stop_planner/config/adaptive_cruise_control.param.yaml index 691be53a7470f..73e7a578fedb7 100644 --- a/planning/autoware_obstacle_stop_planner/config/adaptive_cruise_control.param.yaml +++ b/planning/autoware_obstacle_stop_planner/config/adaptive_cruise_control.param.yaml @@ -10,16 +10,16 @@ obstacle_velocity_thresh_to_start_acc: 1.5 # start adaptive cruise control when the velocity of the forward obstacle exceeds this value [m/s] obstacle_velocity_thresh_to_stop_acc: 1.0 # stop adaptive cruise control when the velocity of the forward obstacle falls below this value [m/s] emergency_stop_acceleration: -5.0 # supposed minimum acceleration (deceleration) in emergency stop [m/ss] + obstacle_emergency_stop_acceleration: -5.0 emergency_stop_idling_time: 0.5 # supposed idling time to start emergency stop [s] min_dist_stop: 4.0 # minimum distance of emergency stop [m] - obstacle_emergency_stop_acceleration: -5.0 # supposed minimum acceleration (deceleration) in emergency stop [m/ss] max_standard_acceleration: 0.5 # supposed maximum acceleration in active cruise control [m/ss] min_standard_acceleration: -1.0 # supposed minimum acceleration (deceleration) in active cruise control standard_idling_time: 0.5 # supposed idling time to react object in active cruise control [s] min_dist_standard: 4.0 # minimum distance in active cruise control [m] obstacle_min_standard_acceleration: -1.5 # supposed minimum acceleration of forward obstacle [m/ss] margin_rate_to_change_vel: 0.3 # margin to insert upper velocity [-] - use_time_compensation_to_calc_distance: true # use time-compensation to calculate distance to forward vehicle + use_time_compensation_to_calc_distance: true # pid parameter for ACC p_coefficient_positive: 0.1 # coefficient P in PID control (used when target dist -current_dist >=0) [-] diff --git a/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml b/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml index ca5869bce0eb6..8e215a1bcf236 100644 --- a/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml +++ b/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml @@ -1,22 +1,23 @@ /**: ros__parameters: - chattering_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] - max_velocity: 20.0 # max velocity [m/s] - enable_slow_down: False # whether to use slow down planner [-] - enable_z_axis_obstacle_filtering: True # filter obstacles in z axis (height) [-] - z_axis_filtering_buffer: 0.0 # additional buffer for z axis filtering [m] - voxel_grid_x: 0.05 # voxel grid x parameter for filtering pointcloud [m] - voxel_grid_y: 0.05 # voxel grid y parameter for filtering pointcloud [m] - voxel_grid_z: 100000.0 # voxel grid z parameter for filtering pointcloud [m] - use_predicted_objects : False # whether to use predicted objects [-] - publish_obstacle_polygon: False # whether to publish obstacle polygon [-] + chattering_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] + lowpass_gain: 0.9 # gain parameter for low pass filter [-] + max_velocity: 20.0 # max velocity [m/s] + enable_slow_down: False # whether to use slow down planner [-] + enable_z_axis_obstacle_filtering: True # filter obstacles in z axis (height) [-] + z_axis_filtering_buffer: 0.0 # additional buffer for z axis filtering [m] + voxel_grid_x: 0.05 # voxel grid x parameter for filtering pointcloud [m] + voxel_grid_y: 0.05 # voxel grid y parameter for filtering pointcloud [m] + voxel_grid_z: 100000.0 # voxel grid z parameter for filtering pointcloud [m] + use_predicted_objects: False # whether to use predicted objects [-] + publish_obstacle_polygon: False # whether to publish obstacle polygon [-] predicted_object_filtering_threshold: 1.5 # threshold for filtering predicted objects (valid only publish_obstacle_polygon true) [m] stop_planner: # params for stop position stop_position: max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m] - max_longitudinal_margin_behind_goal: 2.5 # stop margin distance from obstacle behind the goal on the path [m] + max_longitudinal_margin_behind_goal: 2.5 # stop margin distance from obstacle behind goal on the path [m] min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] diff --git a/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json b/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json index cb2765233c5a0..cfcce06d519bc 100644 --- a/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json +++ b/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json @@ -11,6 +11,11 @@ "description": "even if the obstacle disappears, the stop judgment continues for chattering_threshold [s]", "default": "0.5" }, + "lowpass_gain": { + "type": "number", + "description": "gain parameter for low pass filter [-]", + "default": "0.9" + }, "max_velocity": { "type": "number", "description": "max velocity [m/s]", diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml index 58a8f5d074fca..5eb71126bb838 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml @@ -41,13 +41,14 @@ object_recognition: use_object_recognition: true collision_check_soft_margins: [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] # the maximum margin when ego and objects are oriented. - collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker. + collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker object_recognition_collision_check_max_extra_stopping_margin: 1.0 th_moving_object_velocity: 1.0 detection_bound_offset: 15.0 outer_road_detection_offset: 1.0 inner_road_detection_offset: 0.0 + # pull over pull_over: minimum_request_length: 0.0 @@ -101,10 +102,11 @@ search_configs: theta_size: 120 angle_goal_range: 6.0 - curve_weight: 0.5 - reverse_weight: 1.0 lateral_goal_range: 0.5 longitudinal_goal_range: 2.0 + curve_weight: 0.5 + reverse_weight: 1.0 + direction_change_weight: 1.5 # costmap configs costmap_configs: obstacle_threshold: 30 @@ -113,7 +115,13 @@ search_method: "forward" # options: forward, backward only_behind_solutions: false use_back: true + adapt_expansion_distance: true + expansion_distance: 0.5 + near_goal_distance: 3.0 distance_heuristic_weight: 2.0 + smoothness_weight: 0.5 + obstacle_distance_weight: 1.75 + goal_lat_distance_weight: 5.0 # -- RRT* search Configurations -- rrtstar: enable_update: true @@ -130,6 +138,7 @@ ego_predicted_path: min_velocity: 1.0 min_acceleration: 1.0 + max_velocity: 1.0 time_horizon_for_front_object: 10.0 time_horizon_for_rear_object: 10.0 time_resolution: 0.5 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml index d94d4e2e8a8a1..41f8f53a8f17c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: traffic_light_signal_timeout: 1.0 + planning_hz: 10.0 backward_path_length: 5.0 forward_path_length: 300.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index a4ab065539bdb..150478ce268b2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -3,6 +3,7 @@ out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: false # do not run this module when ego already overlaps another lane + ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: From 05acc9e9355c63ee2c8596ad07b56e82766a7317 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Fri, 20 Sep 2024 14:16:30 +0900 Subject: [PATCH 220/223] feat(emergency_handler): delete package (#8917) * feat(emergency_handler): delete package Signed-off-by: veqcc --- .github/CODEOWNERS | 1 - .../launch/system.launch.xml | 28 +- launch/tier4_system_launch/package.xml | 1 - .../system_launch.drawio.svg | 6 +- system/emergency_handler/CMakeLists.txt | 20 - system/emergency_handler/README.md | 42 -- .../config/emergency_handler.param.yaml | 12 - .../image/fail-safe-state.drawio.svg | 239 ---------- .../emergency_handler_core.hpp | 143 ------ .../launch/emergency_handler.launch.xml | 35 -- system/emergency_handler/package.xml | 31 -- .../schema/emergency_handler.schema.json | 65 --- .../emergency_handler_core.cpp | 451 ------------------ 13 files changed, 5 insertions(+), 1069 deletions(-) delete mode 100644 system/emergency_handler/CMakeLists.txt delete mode 100644 system/emergency_handler/README.md delete mode 100644 system/emergency_handler/config/emergency_handler.param.yaml delete mode 100644 system/emergency_handler/image/fail-safe-state.drawio.svg delete mode 100644 system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp delete mode 100644 system/emergency_handler/launch/emergency_handler.launch.xml delete mode 100644 system/emergency_handler/package.xml delete mode 100644 system/emergency_handler/schema/emergency_handler.schema.json delete mode 100644 system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 1e6e29dd67051..17ac4f3f94f57 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -231,7 +231,6 @@ system/diagnostic_graph_utils/** isamu.takagi@tier4.jp system/dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp system/duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp -system/emergency_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/hazard_status_converter/** isamu.takagi@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index d11d00c43d55b..07f6ae8d4bdc2 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -2,7 +2,6 @@ - @@ -26,8 +25,6 @@ - - @@ -97,27 +94,6 @@ - - - - - - - - - - - - - - - - - - - - - @@ -127,12 +103,12 @@ - + - + diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 789cf136f1152..673596fad9972 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -12,7 +12,6 @@ autoware_cmake component_state_monitor - emergency_handler system_error_monitor system_monitor diff --git a/launch/tier4_system_launch/system_launch.drawio.svg b/launch/tier4_system_launch/system_launch.drawio.svg index 07a33aff8e30f..987158ba00c2b 100644 --- a/launch/tier4_system_launch/system_launch.drawio.svg +++ b/launch/tier4_system_launch/system_launch.drawio.svg @@ -287,15 +287,15 @@ >

%c;{O2cJDaS2oD>7Fw57+A7a1F z?b<{9A+g{$NVibwV}skas|Sw%##^5P?-s|3-xs8lPH$xiedNZ%I||<4u7KdZZ(~w{ zBZ7C3y71@@1n*V7BRly`LSed(TgP}BwcvY;Ig-zpi~@+TXqtKQH83l0Zyr4n1QgOt zm68r&&SG$CzfdJM-bxcMlH4n35AS7U9|}16F}=TB{6&obuK9lZ zTK)nbZ*R?3?K}kU@q4f|I)TL75KraOR*uPqrlQ7 zCP1|PHCX1X9V=%N4DQFDA6aq&`+_tcqO~hGod8@-juT*Cy0KChdvc<-^^W7#UfRQ( zi|j)gC%+uAVKdHOJYbnia|8cfe7wu@iz8ofHNi>yHPS>m@%R7flA@-N7fBZWPz+ID_(;J;o`)%I>BIqZ}rWO+SqtsPRGDl1Fm>MD__aHTB@x?WqqzzJy`Il)Txe>6gyRfzEFAJD6*ieZrZWKt$vpw}F z>j3R{GGDjz2Z9l%8(tL^?l9Kx=Eu~fM-L+f;Lqf^MwtrsR88z57HDxL%3IUk6T3gj zK6G*N+gxavo}NnpE3y>&*_0qXtltaz&%5+)p1!rL0S;^Gxc>YseuG4}HS69BkN<)G z--=2fniKEISL~Qj;N1~uaRMD;-BlO`u<(wQKKtw{g10KWZRlRE*!jYVOzuE%H2`Sy`D5elZosee#zp`x zBgeH3>L1tqhCRf(KCaI=vzzwtMt!*8=ByO)aXn;#o z9-O=I7Jq~Em9ndu8mr!dZ;-yKQ0K$$!j&4KKPN~xP~iP~{m=I(-U4MUOR(@hp!0bQ(6^ht~RwSBB9Z-ezPU5jgod4=P+{ z=HdY}Vmq|o5b*JCl{M$Pj^KSg&?`nJ62E#!sd|U^9{nHqKw6zT9~Kqa+XeD|H%P`5 zc(==+os5y3-1w@hYB4C-t(_y6i9fVwi+CnM>a?Uk6kkJ=Lv_m{<4s>3pRrp zT|x+xr$@n6y2?1AJsp5sM3K)xB@nn4*_&?B!p8f{xo-nZ&glXf9^!!Ebk zhY-AL_N6;}eL?o#m^AceQ;guHi|mq<&y0eNT)!T_GwuKv_2+he`Wgu8Jox*8xCiFk zd-6)I(X%K4xQQIMTefz$%Xe(N-{qC8+3ZJq{r?xTkGDAam6%$%-tOlCi|Z9mwfUbW!+e>z(#eJt_qA{|cr_xwNFtf`_09GUZlhq;HoDSdTAiS-;AKm#djJ^!Qjn1!i#^1O+kHys-7N@DlH+({f?Nx7 zvHSmeD=!XK8QL3SCCEM=;pAsiHeX?~lK^C&Es36q#vfwGUQftz&ey|=lYEY{6;vFM z?q};dr13v+|KEEmeaP;cTKQ)OX)^`heeP)&P`tBG&5B^*-D_|%&H%yt!Rx6P&IsO1 zb++Y5BSS3z8@R-pBML52H(c&eU4_ z>>+ks$vY)mMG&qg$5mMUvTb~ejdx6F@qr9E+Qa(`*+(=^e*8oH7I{Jh@KpUMSmKV4 z_p{lzs$WeTV0+e{!s#{mCrIf=fn)OVcME@rB~s@@h4(>h)WzR3NHYq&d$rCDqj(Q( zYgmef_tB^8n{5%iQydMYNO;5M_a^)iy#2RN_C1P@ge|VsAKxu)3m@`X*Z3s>x!%%M z$ZjVif_Ld`=i=c2FdtT8v5$a_H+SZ`?qEhinBm}`xYX6Jr~S&X@n&`_ml0E;J-ksL zOgQpNN{(x~|UzrD1eyT*U}f^U$jsq|s9 zs^@8B%Mi>k4^PiV-dLwwVX;}vEMezP))KTAp;GJl`^zri6 zL$JQ=D$ODb8~9a?uHWU*QQ#7CR@~!b2Y8qeD>W_-N8l1AF%5WK}B^o|$Y zqT+C(h_U0&P1Xw@Z#pV{tSs?O6#esg%O(oEySgPkQM}u^U4^jlex0>ycMO6zzwz{A z(%zfmN42Xa$m;Dtw^X$j{UKPSg?N`y$O>lvMCaoWISTG&Pah0<-T^{tId$Bm0>K`x zo`~+{r?@+XAo~IWBgavFPJqY`jwsEN}Z@Lwk6mK2GA~cQ@@@+#4qXU}5}T zyF(WrZ+6o`?Dmwx8I=l^NA>;F$` zNdIq1QG*6kO6AcSbakDW3|0-2txX&PX6smEuyhvf)u0x#k1aU)wa)uIIP;DG=<1&}yWhjFL7R=agv5gC;WwR% z>A}(XN9-<7TbqPlU-(~;#!%@aYbD!uy@cO0NDB(Q2i)v3P`ocnPDx?mz0-A$z6-%y zYE;dTgg1{UbmI_$cY(}Jz2)qO;eq_cUXxBc;kT=}z8Gv91(%-PH0Lbp1Z}Cq?UMTg zz>ADN!Z9A~Ay)CJ1tIXP5RAsnwcC4$ZNbJH*8N~yR6=`rE0KLv;pDe!D{pf!a{s^S z{tmn3e}MO(Z*m_~8vYIv-EG2>uj0}Reg;{8i#i`h#SGGrRUGL9>1`Bv_pgQ2QM_jo zY9z7n&Rou{@fpFpvWg{TAAS7YNHn_4$7eV_L5hRHr+ zaPkv=wRUwavU*#xOsC|)4gBh@Y$CCJ3sSw~3q(>39#XM`7Tzcz-uekif!wY=x@|BhnxZut9HJ5xn^{I0W($y#1bZ?c0zL1xFvL znPV%php%`Q9)0RC3T9Rlm#y&a1jHbhOT$ng(D9!Q6?=n?w|4f^_|q0b@H%o_tdzd^ zrzmW^bJtk#IQx&LEot4@{r~B$DFYtMX%FxFWFKib`I&6sledv10Oh-HCRQKC z$2*Mq)#SjhdU(0->Qf_Z_;_=9{4%JLUHI2qI=EBk!%8ggn^)Su{r`d}V#o~AmZAoI zIx3Ze)*ustfILQYF9WKu$Z`6>1gyTMgg!aYhDZXw6tJm|I1-}NFJw%-kw`VgOI*~U>5xlok;61YA#xoS}B|ksNV&T18_0btW1n)tv zBhNe#yeCedw^)xnv2&gObh7o#VR-J0NXJe;z!u91HKU_+jE11n+%3uJ-N--lqG)lr@q5 zzq}-Yd3Wkzc)yj(worE`*m!{b9wV@}^${?Fk=D+;`a>O*uT|8$&bzB zRQ8S~1TeqnW+VLze7qmM_PAkfP!Ge?+h26u!k>H7ZHRt0;d5u<<4vWH=0kj}UH`uS zhu6Z<#@{0|NJokq^d;ty4O)XX25~51)u4PwlaG_1O7!Rwi#2?a8l=*+Y*qp3|67}v z{jjW#hI_ggI~{(y!69otUZ-C&3belMev^8$3q;r*mb0Gq2W9D7bI0SbYtZ>}!yByX zOW`}@I2ma>0Xg#k%>F-JMb(>aNCfknrvKJ2`vTcV22Os*pVZz6s^kH?Z{IR{W{Te+ zU2)E|%llRfvnv^MNwDMZ|I?+aMrBsiE&Lipr4M(xWf}6tzh{sR6nKwsbpC6Ib+3D+ zh=q6S&oz%(kRet%OyYnKg7>>_!=(VhTW0gOo|lEu@V3)Q_Re+t;AoZu*Y$-*!FA3e zgX`H{;0yEF(5>_V;91UYk3bh}yl;mPqgA<=!Y{~izMI#c(ig|ZTU-BlkLXw0!@Hd9 zLkB0nTOmA*jWNjke@gwMFV^AX{k~h~)G^&UI442&+=Eu{ig(u(u<-uG=6h5W!P{JG_MSI_cNuSo%4P)bIWFFE zfw*Yc{@b3%h32lXPPBt%ruZm$xq0unbxap{zI+n{cfLP3-+a=#WgB*bq--t8QTsBL#>5r*B!aqsVr-|zdI%?Y*p3R~l8@awG{vJZ8f{DjJG!dXlN@Q|pm zYP&jq_2z8b6<&i>?{6VS!e&`i^#30QBCMa^S@8S+bkzD-EyY7V-eO0AH}RgOB8qpa zqsdAvyl49N9^ZiAZS9hyPr`fdyNG8tf;aKN-QB0xMI9Hg$MVps3ZwEd0dYP46q zEyzB)aPqsmlwIAbh6nKaXqdT)q#Uc5tBaN6n$zMH3uZ_|?yUD_z zdsFG7tupD_2y(sUzu*7=MF8#ofb{=+C~DBmfror(4LTXbpn+9`9OjHtk0JfPvMvN{tx!#N>=gYn2bYIpIvxtvMo4Q2%kbPpTWlnwk~;n)Cx~ zSL&qp{mlo`$+s`vy*RuS<{-y8o~q?65yEbep80FikEhUHgLIPY124b9%}`8I2oHGN zu9%URgkOW~<1)f;CDp)8(%3UdvziC?;k8TQ1LU}eTV7>rOkxkQXI>3= zAIzgYyf>45;N{1rA-v^hIS&{$J6hitg^zdZ3HD!45WHvdrH=Z%pyGgZ-QiUM9#TdBY8ois5j;UESa=US-DLL| z!TX2q?c06`-cMCye3_62>4{;_MgFm9_~nIsW7iMvFul9zDlfKCuqg1nO~9KjuzmfD z=Zq))!O*IwJ<7kZ@ebdzPNDY5Qh1mg*I_dd`9cF5?@LSv^Jg186WTHFJHM=^wh#1xgco{Dqe57fAm5Y$0gYXU%hRp^ikvp2{0e~y}Y%P z0`H0Yj-4ppij1bpSa=_PH$(ph!TW$?!B^7WTh(so5Mc!Gya(;3NgdHJU)TCOH-C^+gJh5wq}IN0ro*a1DNjx~?}&ic@^UR@(bx{PCBgb(B6baYOVGprBH=~>+Hqc%TxQYkUxQvsoIm+?>>)gETf8^1k%}2)@Wx0Rb$G!Kv2-ES`EV0-u&(;@dx&+V z!25^B$-j=b>@u&{!ooZIUMGVVf_LrNwQMB3WjcA}!VtWj&aV9uVjcsZ+_$|13iOA+ zSBTwr7$O4mJXUGC&~9*Y^rhOC=YGJsrhD*GF*e?eJ(&SNF#Pk$%Xb&B@hg*8ciX;=Md3O&-h)hX9$AjGhxawI54`*|1PM#OJtly;^}?FOGJL!{r0;zH zf#5x!EO+lSHLtgDMM$s+Ed1*&=&1G4zeI-odW$m!-ru?+{ZYIlPq=Dg;VrARFLy73 z_mB33gFy)1xuPGJj#{ef&DfiIDDQ}YhrfOx=6~{qlfLy!dXE!V} z;5~b(>aWvV1Ut<&Sa`3KGUPsh;JusqLwO*AH{X??PJ&4Fwv|d;vS(uq{PywPcZ+;| zVVS&y>!+rPVD^-Z-Yv~;U}7F~VgvG-$`RAya|U~`@qT^SO6&xe2%JQYtB5!IzU*(# z-YN}m%Bzc^J-oZfKJfBmV5>5l*W>|@z|S<_41Byprb<^!@YTXPavH20(fD6)(OHSB zuJO=b@OabNQ0L>k;;baozvurcyKLJ18R`E$|5JnH7+l`uqW%9qb!%p<8pK^wXaJ9t z=s5_~RvkoY5K#I#e#=5t?`(@7?`5?Z`0m~h4+ED3!z=Ejx*m8;1i+|AjdipeJn-*j zW3BWByjD+pq=T{VAenvHs*&3+0;6#cv@&X!S7Hyb`I9xyKV6s7-1+|>WFG}M`R!R8 znEM?$LHbo5KBuviRSyps+sCd(HEXM3XzD^}G8I?s(4EU``w>g?fE z^t(awpun46RcJSg_gjhOOjvmHFWMB;ir_sp$TuBEnn9-Kh%QEEkg^<$98!?uEyU(b zX@Q$TuyW8E&#C7`0B^WIl+e`;_E>1=GE^W}<+%5Ie%^?Ucdozqmr!JR3yn)kN{Rd& zi;Z_lPlPtF2kqfqK=y%`AFuKAyYL(j*m$DFw1yoYZ%Nps;YL_B9JcDx&U>u*L+ru0 zrj$)Tloovdzc`*c9}KCZv66odNV`+uy@*@%35vJatse|ncuRW8XM8~LW{($EAmLq? zbiywh!F&8UU6B9U7}$4tYiOcY5X|Kd`VO@c!Rx1N;`bZ6ffPe$MSYDgfW#OGaq8H3 zn<_dV0?6_fGdWI@d0AeyBR1ZwWy0y1ezb@87P1e#{NfT#Z~5sEfTOGBO;rYbylwcE z`X&*)+v&bQr>J?oC3|wm{0WT(k2f8)KJF}%QvCCQ^#1?gEj#~i%n!x;GwV}&EWB;~ zi#~lv@ZM2r>KuyT{Y4b2=Rz7JqZsbQ%yluaVqezw{*pjgVbesZKnD@Izl-2qK2)^-h)E0_*(%0s znh*dVj6b80+Cv0)PB=Ew7j%OU8|zFIp7;Tgbm^B2i?GlC2dz8y=?!vRMU))ZA#77* zp%sXE&YeqH{e-G6?e+g5WFL6>9m`yIU4vsW7(XtnJl=zkx1jd55G`cy&EitTxppeP z|5uY=&zj+RYr)UG)2Q^ZtXyQz@z^xLhBPs68LH{HC%6Z=+qoOLE4fR!&vB=4M{@^q zyK>udZ{pVBR^*o8Ud+wN^_6RwtBdO?R~6R{t^%$!u6V8kT<%;BT;^OVTrynzTr8Y( zoJ7t(&SuUU&Rd)pI5RnuIKw%;Ih{ByI1M>9IAuA7IXO6fag1}k=V;@o=P2j6%#p)! zf~}OTkS(1pku8kPlWiy4RyKV$HMZq!f^2N8KUl|D-?F}Btz*5zdXY7o^%(0RR$taV ztX8bXteULytRk#jtaL0BECVdrO^c1RsZa@W48Way5fZQPm$Q;sxR3I6MA7WviVmDOYVT-Pe$lD zszR7=e21Q)D(I=C0Q3}9f#+UHLQhZ?;ICc;Jw}zk@s2L22~~c=^S)3cs(juJ5ugTC zd0#3jgz8b{6{STFJwlbI*?kqL4pklkLTjN~RP7&IA`R7`%B}V+5qgNKeR+;GP&KMt zx9(DbU{twi*bPEesM`BQEDm~rsy&rAo1pus+MW7761s;fr=4CbP$jB%DMj)@6{vEY zPh)|~QRVPtEhlsrRrcA+E1)~5+TrnF2)d0bJNf%I&@EKiE)nX2%1~v~+nfiLqRRSg z8#8nhRaSmNkE!zq zLOH0?4t}r?I)f@LjX8ZN8&zvLy4ayCRIO>LtAR36rEw{DJCuPc^%(Z|P&%sA*0YyD zr%|Q4#M%H#LzQyx*(~T3s+214`#`CvTAkFq3p$A^MN{EZPztIP#G}7J$*5ZSN!JWI zfhzeYyu;9ORLPwVz6Bjam8|*xPUtAAR!HT`K}o1uHn&;_I)W;hM=!deL{v!^yz++< zP$jjyK?aIPm81sq1}F|y;=h*ZL$Rn5d;HcDib0iV!7e!{8dV~$$xhH=R4uhn*M_1{ zCCrq?14W`r@GX=N9YU2r#pC5r1giM`2cJRVs9Lg-aWQldReVzSjzM9lT09cA4hlsT z;o;?U=m4sC5^|nGA*kZs@?|p=j4CeKja*O=syIdm*Fk}(Vt=$k4+=mPTaw%r$RAa# z_R98#QZUIB7L73tI-v=3FJLr#z@sz_%-AQx1Tw$LGGRFQTZp}nXgeftOPK^5s! zDQGvUNMDvfPN*Us#D{jFiga!n+KDRC4MLD3sz?{EKn|!P-A@78ql)x7KePi?q_3YL zJ5-VGA%<*GMY^^X+KwvHEtilDsz{dtLe{7v-Ju3qp^EgH5oC!f(&I0X1*%AIWkB0d zMS5BQ+KMXDP3+JXvXaY9+{X!hM%6hd4+m%rRcF;W1EEn=o%!Cb0})Y`-P|(|eL_`M z-pxnQ2&yujrDUOxsLEJfr~(b6Dqa6I1bskNTAOteG=!>CxwY@0K~$w4UYQCFpz5TK zVgb~TsuT{n3g|tmP7v>}gWjR)_{GuB&|6d;3)&s7may z{{{7+D&cOPH`I-)_?W$^P#3D=%(@Riov4Zx6Rv?eP!&CK-WYm~s>7At$DwvqMWswO zK(A00xubg()P|}wmt7HlV6q z{`4GVjH7c4{M(Z@BjjD$F**HiGRrROOxIt@C^~g=w z9MVKpoviIzXbq}r8QQxb4OBgBo6?5VQB|EE7YC`K3J&^g0I8y?YF9-tq=KpkoQ9c@ zGOF&i7jK1>$Vx76THPEPNB^$!^3oU3YE)H(Ut@w4QB}VAMiHcds=ItE1))`_y4_!Y z4qAz-TNQrOkUXl&;yIHbIaHOpJnM&KQFT+?Ko(kos_WC2CZOf0x>mb33tEP%t4Z&C zAQ@DZ*k6AFNu%n@O5Yhs3RRcBo|J$jQFXDgSq_pwRdKfFHb@**7jpZ0Au&`H>78(e zL{U{p-#-tDpsJu{T_Lm-RrzPX--Luwl^0Zg5fVaGt^tb`B#5eW(8e8*0IG6&pT|M` zs5(<(eH>bXs_fvq8W10#Ii zmxpAp94;dQje%p$8#nfVBX=FQ<{%rSyG|r@iOpf}AVGz02l`iu!8^%u%(0ynqpYM3SMsphW{Dz4b+ zxYH)YW4PegAnCfO^fB^dCHaaSUkbcQ({vPXbq@h{EWF>GjIZ-X@OCU_BpyQW-a5C; z_aK6Ip_}Wka+w&|XZeq_oNGehvn%Dd9x5k-4NZwT#Tq?8jCoa%hnOGOYhunW^Bj8z z>D)9&V<@*6yoVgOdGg$>$4_j$Yv)vUpY5bQybH)a9^vFSZLqbrV44SrGxHq&ZiJ6_ z*0XOGlEP3k*Qyi@D@S+Vfu zEgu<B?u_Zb+OOJ z$0Zkh^>zT%`8aB7V%q-a^p+O|-lUa56z|kCMH+U{!42X)sqe)ry%Dqq1t}OV#;QT1 z;>Y^Fenh@O60Uq2gVdmNPw&4KM21+awAhMmyfJXZ{d4DBat^?{^6H0;bBI9ND)yq& z#U8-leuK`d+81~PUCpqI$8M0EJ?6f9M2W-hf*)e(GO6@o zBp|8w=LBgG1>U61J{0d}W)T7w-alUFPqHFItj~IuMI^k-I z?fe&Pylr1jzuu-tdw9o^ecjV3-GNvsX@AoQRM2(mQN?-UZe0%9Gc*ZB3~- zK}sl$zHV}J;p5FqoexdMA4(1@<4N!T1ybNm+Py~cu3P(t8w>AKYo9oaA$SMoa>zy_ zcpnZk+3bbjJ@jenSc7m3{1`42E}jX2pLAw_d|E^VhXWIabfbH~m#0atZE?+w~^x>{m{*R+>VX6W~*sAne zFkF7-RU|&%&Cu}iw2o?c4RFf4rjC#IjXg~=T;3H6{(^KiSL%Fl`Lu+8i~HUG2T~>>g{{!RxINIn15w)bmnCu_!-^o zGw$63WThsxnvl<1!Unia=5}FEPG;F8J(q-u!J*_h4o;bMZ?1aH$mnX9DL+ikX=ga}CW zKCb?F^zf4qnA_Rk%Je!BaNC8M%-Z*WgwK+pdC1<|MYi79Q&QM?n|PJK_+lXjqjC4j z-X4eQv6r_DGQL+b-lILd&B#6saq>GKGPqxi$ODqxe>i2k;N#tPWl+fn*?YUZsrqZ* zN_@O|X7*O!KDu_nPfq&2QRjoH_Z4g5sekYP|L@IP{=vT)nL!?;s6nI?mVebC&2@rU zHE87Uv`re)|F0e#nn*xukP%ONirhBjiXG>xAAN;lVE&K|Zu|Q~VW59^kxDFb|6i!$ z&+AYxkk%`C`6J60uQ4cP&lx8JyUri5$Jpi5FDQF0nE|c@9(-cbBH%LcJ9e%YjO2FU9 zae`5f^c7mzc)$J83yOwl4{y}R8=U;!4Ie+kB1-_AS5%ds+{4HF!sVa#h6vtGy*U-H z?D6rY6S@6z_ScyOk2jq#l|HJcb+nw9knj$rz?*ai9>rU9sCx+(-g4}x-rhs--ZCP) zF&@EtULd^pE`s;tSjYRPd17F->P4?ksfWVbExk&v9Y=PM>WY6^zwZI*e7irKm-PcP zqBGle61*_`^#tg{`hrn$7>(o5Qm~e3!p3`z%gu7x!5 z@Agwgd{}rJ?`gd90>PV@6Y3v_;5~LuWBe6@_rSGn5oZy+Pt={i3A2a7<#7}7mr{vf zV!Wd9-18prqVCiRT@gQU_hyn^&tvTBJ(D4qN_;2|my_eFh6XO_L}KF|RJ^*MKu>$i zTeD;z0XX^X`k7d2Kx4e3HwZz<+?ZnGeg+fN%Jd z6GqrOcG-*N3m)$|Dt&Z*eC{2a^KbwE54!OGUTB0(bEYrQc5p!Jx^(`2~I+>NS@bCX$ z98H~%BW`jEf$_hG*hmVzNgp2ng?HVY2o~N9u9AgD2;OiU&*q~D-X-B8K7I(^9V7Af z-;o2-tTO5S(K`;pgY7n7`h1Dt>`njotd_li&uGOmIVT^$^AUOP#Sa_rU0fDp8()gU zi^*|mt1~9{UBkv(&O=Mzp`G^dMt#WRoAf0;iZ@4F^HMCl&xlW|*dchY z-*z)73Bh}PMR;yJg16TjnegrvF>ul}ozM-sgRuCCumcT2M6hT~$L%NR1)H>gmf?6viqAE;1>U5)PEfq*`}YZ9;aywHeJ%>Y`@5}hQzC-*+|<2oQwZJ{kBAg} z6^()KC`SiBkq(2GXNu|iL=piL=azT2!o6T=Ocl^i^#yw-^m*?wVJ~m3+fx;JO;iGQ zCdYjadDKH{yoL?h3#<+(hdXt{`}b`w6{-Fxr!-%PKDo$Ofi zgL|o%oOIIND)3+U`~Okx)cLrrWvSP2?%)0&?Y(IFPo)26qNqWn+n&%Gr0*{$gH?m* z_^jnxhD-DwA7AB}g47`2?MC@wNDZ2#e|X9)AqEzL?`8DUN5CrO@F81EBH%G&5wxl6 z1wWLH_n%|-1xXnnfY9IU|9k70J>kD60UssD@gHCF{k2mFW}lmCIPKKBp7v^x57|c= zPJSa37VIW|1h8>HYb;xoO%IQm9Yuo?9x2uEfuZhKGFtd2Na-ZLzZP!1vEUmds(o@EcFLxUnhW3Dmq zp`V8$@>0X$d(JP|WNnFnFL+`*ducDYNw{*pOu!es=ev0u zAMflOc4!Gfe8D$Jg;e^uC%(6!=?H0gE17`;Z_<5yDBit=_aw3KK5m#jKZD?X>Tz<} z2?Xya9k0Vx5WG!1&%~;(kAYKt`NLG%!eRc0ObG&xL{PHq1fy1NFG$@^aDAZY3)(#d zL-(;_&mbROV+oEtD*<W z^@3tEd3E=LK48%e^|e}z*wwpL$>P4!atWA`99JGXHQ>J&yFoHr9>_8HkoK0hUXp#7 z*{3Ax_l zUd^V%7dS<48(qr=GS&`!CJm`UI(xP~nc1SMH#e)xD8DNfc2ii=(Qq^p9`lITjMXLr=e_T{ zxWxK^C_Gbq;f5E8%(moJzJPrP$+w+*j~L&VfTPH90U|!{E^frGK?Unla~65hUJd$A z_EChB-(jilan>mwP_k&H*SGEXLoEBFR=rhH)$r4nYMszM_&Z2ahh#)g$rUa5AvTgq zA9;?}scOHk*hyxkz?*alI*NDTwsBc3yiE<#8)6W=-z10)oI>yxIC{KA8X01LbYvcQ zt{w}Imoc3b5RZh#1edVnS}yx(yjg|-hNjrS76~i9#Au%j^Lf( z6v#xvn_pPj(FVcWR_WF73g%ciDQLgLv7AHj(~-yW zrC%exdp$nh+3k?-m8Hn?7T?J)%Z90#L9W$nuQ{l=;Fq`PsPxg`mKD9Wim)ASa`d6opq^OmXl5au?R6nXSj}|Jjva6sh-1z$?jd5AWRRwiLl$-WpxM zArVrdz2z+qvX3#G{Avnb%6j?|zySLU=+wZ+TfxsgxoLAXtaK;qM+^%--aB742KH?d zUhvg>{3UfhX13~V^-B7UH!}s^q<2?Pyf+KlF2llGRjaPz0fKkQ`K(PR5xhHJ3PMQ; z-g-xZTyoDNtGB0(ELJ*2z;YTN#N*6~KwFaIenERLaO!!IoV&{hcm?@}R7qmv&Ad*+ z{NYmx*qau{lFPzC49Vne^hD^ z5xighQnTMc&FigaDmLewkXi6}(`8fXZ##dV+n|YaFg*xM7~xHy1@ATKb`EA_tv@p0}av& z>U=CpmWa4e_IrrsqQINV@)bmimdc?sBn z9M{@HZ~1c+`~1Im&bBJ6wX}!#O|lPPoctvDpRqTM^ML1-`JU^d@$s%2ajZHZQ4L%C zFnph3h=0B1buM4m@Iu0ZZ;&oi=_A0KRrX2RZ@f7v@Fu+th~jW*~T%rY+id8NoX@7&0q(6$=}~%rP=fQLt02bcwhE5xif2Xw~xEqulQU(#aeY zc#|HxMDZ@Ve|QxZ-pkeak~blEd!M`=osQsrzsB^}6$J11#OKbV=VRdy4;?i33rE4s zdf(*7l#%cMuQ4BfzP=AQik^<;Y48HFVlCbxOxVj?F+{<6-Om!RJUK2=xK%s6?r$b1 zUd`XQd}t5vII<5rocxSUx$hoiC4lU+>6sRu_;|-(-XZQPjBHN)vMhNyL&fCe#FD2> zGOHJUgG8l|wx-)_{qO&--s}{3lU{E{@y@@mzY+^?7N5;kjtJi0k7wkaM)1C%yvC#% z!TUr0n^#9;V&M@*^LuMQM8ZN@AMYZaD!A4)$^LnDALum5RJ7gZ4NR=;pR<=@t-``Jrc<(0rNX5x7-1eyUiv|LaoSc>#{s((+;!AH! zeWv2|7Wor~K9a{4{@GhKDt*X~swmt=uDAGi|NpP?n|6Od`hPx(8bo@(8m&S1oftK+ zYEZSSXI|-t61~KHwX(BF4VtU6iMfufK|bF9`pa-@9Nhe1qCtE2Vfc_-t@RQPBB*7* z*74?PAJ`&P_tbj7CwSU5eD0Mf_6DiNjM1j6`jRjj7pttl=g|-BA@);_tz%EM5axQq zf9pShCE3RqPJX(UeSrl#3E)N`(dXSg{2|uiz~R@1o2%eAm4dgkM)7Zu8k0I>@seL+ z!OtM$C8_gaZF}j}%B0^1q)ODaCeLGXTY{o05- zf;aKN$=QUmI5;oZ(|M=aVK{zFHuDY-a{pg;;X0=KeISd~@3VEE2bd%(Pp~b=ZjeT6 zWHsv7NWxR(xW%5?Kh8*DHOa_$i)eNy?OYXjnx_(kN01nd?YYsEBW+eV*(5v!8vw zzrJ(6>-p>Ly}GaKx$pP+z4u=CUTd$jW6>~jtAN*iWqv2(b70w;z$s6J=h5#U$Jb!< z9)tT+7Zt<+CGLG(jae%fHt#o+m9fL0=#Td|w2t>U`S~o1tTO84MR?CP+jdppckde? zJv$R%_nvXw{{FE&{_8Em2#I*6s0ij~r@sMdCtAmTocx3q zZZNLT&ln1)ul*)%VYY^xgqKrXDKj+TveMM9BU+aWh(q@#lXU>j+vXaZN6D zu6y%R@m^yhoJip<_;S567H`qgJ;pPT_u7Sa0)KeReIdL!33<-AQHrFOXuD< zN(2EPG9H~?0WT-wGU45OvJ<&{@ukc_j2B`kEC2mS9X4;f++BzA7mI-{Xxw}=U!6jI zY~B$Tnv!J#^v8P-S_cUyzZIc%Zw?&fLx8a5^}G~(-aMzQTUFuS+wvS;{g;;byu-h| z;23wh#PGZoXsm;OVc4`w?0@tB|JBU-zxwCG`F|-@57Od#%lW4VN%gLBamjHeVD+F} z`7N8QVGrU{I&XLh_MqmwEt%qQ1*z`&!t|6Y{jDG=bv(t% zFRAn1xg9aQh;@Fk*2-D@9yH{qTqAJ13hduK=y>%h4F{xu*4EYgt1^5KB23X($GqF> zf6gF5-b<)>YreQ&M|s5B={;PB#XD!KbB`5HXHIz0;7D6koWjUiCs)DkZr zMm*TB*t0%35@(OmA8$$>c=;VN8cUEcf;UK!xmzR#@p%icl-^@DSqS42+_2w%20ho_)mb-k;d}42RFqA8$$>c=-tzy+3an&x-_HiYjI4!sor9 zY46pF%35Hb(wx3U8~=cGgPl}wr>zLXzr77~q^%BafsdaHPtWldqT;O{!P!IM{lVbS zS}fkBwfQWkA@9ZB%cCzLsM=`XZxtL52AK3=z+68n!weup6j^OeX z+gY)C(E90^V?PJr5j#$nfn3;wZVB5yh=lJTPf3ps$+?q&`zb%=ZiO)5XRDvx(oaSn zM^~Opu<1f_U)6t8m+?dnsyh7O0@#mOjwMFbVQyl;3ymA?isy2;i`|1t1DD@Fn6!lM z_W#+?I!bWz8#A@F5D(#d4EFd7{kf$t-F#;)Gj{cvaUW@DT&WJi$F{k z4XXnBG2t#D@A2pVbtP_Xw}mtqe?Tgxtq!$_>u=5m%<*1E#e04B!5m8WjyL$ujKzCD z_iDll$os+3HynR>>oRvSUxmEACTa{nxsbrG%IjmN&BDO!{?Go?!(^m7o@FP~hAyPJ zrEXFg@(#9o=OJRgcI|IkV&E7WS3Q69+(|QR-W#nt1BTDjU-!O+)`6GbHtCz{ zMJas9$@)9pKp3C*?USF^szKiOjf)rSB;fNVXk0$#c4Gs>^Cqa#SjRMrS0=nc3NB7W zsCa81x$R2fU8MYo35&N@oaIg>$Xk)6V0jMYeQ09U^D@Z$e1%KrKFGT^e^7+gDGa#T z?Yf;iN=9}hr~T|!>_XzZ*L~Ai?um5mJinT>1Dkie#+2&y)ncFnjSKtX^nI}?Ht$E` zgQJpH=#O_CS_fW!x}(Np*PintHL+^_BOLg=M}O`L^SM<8rjq5CZjHe|oaoI|;-4p5 z!SK9m2(;BPpH;s`aPG&6;)SVruhaN7cRBH&#ff5T+&nDaZRRRPx{$YkJ%`$5$U7k_ zvvwHrb`pEebitMcgaSL>xgH4vpO}~}Ouv(n#Bs92L-8(T)xZs5VS7)+`ln0o^7Yuf zqc2ND=$#S++t9c}#jKrKU$9?q6&3}Zdu>a9^FO5yy!@_j3S=#Wn-j@Td%g&9;`9E3 z@;*8LWwxCU{_8E`_SsJl)~sUqwf72Z+UhX7tz{UT_22xDH^b4z-@`|&1XT~x8((*w z@`(M?y@d;_2iYD`P)djM|K{!L3Hh)G<=kVEjWB~3q;=bC?R6l5<>Dd&tjuA6**;2~ zyOoU0ypI~>Oz1**^gG9)awSDDU z$M8LfaGka~rcbjeeyW%oki@BYZ?5|sMBzOawuBRlx7+RE%f*m4nVIj>b;!GVLS=I) zSx@Bezb4oU9>rA-kpayK+5jCdt@hv&Aa)O zVsvYb7$`>L%t>tpy+zo(U3Y!n6GMl*DRu0}$?sQulfJVAAJRJCq}$U9pSQS`Xz4AR zO3-J-oh2rK&wJF5FnD-@Jj1Ubw;Z9Zj^2brX21U4ASFh{TQ`IA8-@4&o8#U5K~; zhX~2j9!Q`(?_2Jr*u2lM-sE(-EC&40IEPC>>wFY8Z*NXPh3`cA>)w<)ym0ahv|qDE z$e9mOjGaDmcPl>c(Iwtme|VpFY6#x?h=%k38(v9!g{m+-Zvw4#tPPV?_Y zjsry$-V>%ZY*@Uz?tQ9!1$oPQSJvf0-mxi{n55x=RM7Y4q6VD*hb^aDezV6|z00~1@T3}9Y1`AVL8`g+@XD5Q z#^+6A9kmzzQ&iy(q`|efC>3uV4PH?SZ#CiA1z5aI4|Zw|Lf+wH_pp9W{9KooED%|bnZglJa`y(*9dM-EU2?9;lbYj|K(q^ z%r#65q@Z!5(p|sKEXC&iP9lu|2_3$@rPT2TC%+>b6a+4i`H(~DOgHki@p+r4-^|+R zUI}!ovMUuP@Of`AA}qWobC2QI-nE9b)$y!E>D&3p|IYu@#e9#K1nfbwR6WRe=;VG% z56U#&%#YQBJY|BG>B1f~&cUR6BqkhVHL-%Wf`T|4)Pm7(HoRQfKK!h3!J4<8n95uG9fE66)mw8f$r@?Ohr+azSF zsw3xo^zp+TBtST%lim(_Pbx|oylNyP_07XO3AekDpP_6i{$JdY8ybNeKdxi*j^E5; z>qZa<*U`9~{4UvV#l8_L4W+VOaK8@B>1NGR zDP>^kkKlJA zAX??&0(nQ}_Bs|p-q!<@PIyAzKEl(?t9OyWdes@T-H>;vot{DSV=}Td!7@F$vB2~&^YB!1_z=pV|VZ9rMtp1&FGK!Hna{BPJY{` zBd>J{@gW&ZPdCgD$LBrf^mXC_l26ORvaJZ5;_1X}Cxa$#Qccm9{6 z;%&G~U5mo|#r_KdJ-iuQr4i!S)X_gn)wm{x0tjKdSxItR$9Ba2?mI%r# zdCFftB_nK}G8sRwb|Kf_EzsP{d@s0SK9QqdrMOBHjv@SrSQHqMdZff{V8dxCI<2*KMjZ|fV_>*DF^L@ zZ*Suw2&)h6A%U;Y1Uv_(iQvHj!QTTf$cT-_R{^Q?E~HXM&-=Bu2cq3#@IbyDyL+pL zWY#%<6a#C~xW&xL3MQ%8yj9G2`s?ZN?JcDaC7k@ezlh?#sKkdTnK1wU>4DGtra)Lm z4&?3G;5WAEem&-Ezkf!rMU`S>0xFE(y%*D1M{V=EKW}gUJOBTW0Q&s{oc|T5dXUBY z?-wXNh}%(P304n^+>z%y*k7Piv*-nD1?)jFhkqZ|hmY7MqjR#u@+44kAg!Bwj0h6b zxc!T&;RflH!{qkyF2wlci*BN`J7T|B=T*Nxb`O$^*xY(xtvIkj#o+u_Q?e@?MjBe#D3DVY*dlkc72zwo?8p+Nbk>?9s zR4a|mTS>IBa#mg(NTYEtO=UK%ZouZf`FvdYg#r5Gt$@~{i<94t`??Bmy?Bu|8JEr; zuEFQswJAfPI^hPWYTxD1I)uN1R6F+ll_Bd*hUYC8LR%fHzg$!B`}=|PYAW7lA>Yj? zylY79i?Dca2-{J_30IIO@@7TKAny~uTwgBy!~4a9(3}kBJkrT(mNOAex5xe-npC8<{?=Bf(E=`&}_O=UIx}o?idB`2HYt~i^>&NE3r?f=&!E$k6 zg~l~X?O(e<3wwj~)dS&tPA>YJ|LxE^UgG4p_@mor_aOLzbohjtcMd-99l@57wX&sP zUBK4VGtD%7oX9#jwDPnb!_WVO1+>+1gHNdNn)2M@WEBLuR{igE8 zdqv3G=-_Jg639D8qIJs|$h+ZtLEIU*_vTWRUStX1-VUax+bpXmBR#CUPR=~whngMyhCC7yxnq zyIN^nJo8E5NSo@>BaevSx`2`{Qb#tsoW9I`Hz_-F`Foi~}z+yd|iDX&Ao;1?a5r z9*QmkYFf$@Izu$9AYb(jDHUyG_#Q-fPGcRX+XBV@?jR{s@wQHX1^?UM>n&Cr{#=I1 zds6Ct2IL)jBK1QxYB8P8t4=!R8(OYy0?M0{!tWM(e=KZ;xS9 zbl`GcL@iWz>R>lM@4@WI*Ox_$z-VRl{`f-tM=XJqlzimL6UOI#g0?ye-Y9DI{GI=m zsCZi)S{h2>ZEo;L1dI1mHJ#oYkTS!TX^0r;Uj^O>h6nqZ-_wE z=!VhD5;C&bKz(%_Yd2#3t6F(EZE6;(!H>GrwpN6t)kWx2EJu zRbn>%@g7C%z{_uyllFSfAzp-4w%-5QTYTP?Hr!D!-W39~S1be>8h$~luU%);Hd)3W zkRH)khjF0D>8kj-UvE*Q;%%vI^OVASaqW3wEZ%~J!>j8dZz09Wua%HDd6)7DZ^+vy z`)%2*Fua`j!H79WFA>bEIxNmtPDYk|_Aa~5)Qx1BB3+jp+>x_}?Sd8V*u2jl78GqX z5C^enT+fz|Um7=I^Ilu1S$4IO{&=57>%hy8+je?4QJfc%x@XIj`x2k`%UYJ!&mD!J zEA_3B#48%+|6eR257TuSfBvVj4o8b)`_0nk=KnQRytnguMNxQLHM%dw;w_-}-Mba? z{(SZK)Stb#`!T(P+aT{orSh|d(j>6w3AypaXCi30%`2u}Nk%4$yS#>ecOlFN+QyfJ zxFZR%H@-bSfzA8yOQvciJ;)o4>sYfwtNmYi-(yM5*!GP6cppORz{_t|@AK4&Z@h?o z(8II^4fwn#Kk0=W{#^_-crs563E?kJHkRg0%74;h_{E7v1#NY_U(T+=46nENZ~y;) zHHrV<1jG4Xld1>VJ=Wr;^dR;kF-fc*^m}V|kuvN-H(eGyxC48TM&aqP6cbe)w^I*Q z-Yg>l$tLEGyCp=>cqsLe$|W+AqSoYaNUR&NkbT^LW3@Zt-*IWCU=wx^a(F|KEgTmI zhtW72&fRgT&Df9F9sJF?QmypYgY3{cY;f{Bt8=EkyLch;Ff&##S&B;s4}%e@Zowk9 ze89vXKP??Z!~Xw~^MM=lbs4?~5f0N<$NS1V^@$hf9DAY>yc_8r zZ&YSefCEy3#)Z!+*u0NBS!-|kA`aNmxN^grdmrRu^Cl)VulUwSf4l?HIzn;s>*LW0 zG8N`UB1S#L1BCH;zaz41@8T)|k2@|^sCwY<{|m2Mp!Y)~kKuU}*V0x;`#Fik*9mjH z)v0*z_Pjkn;k{kzp%@l#V@(}R8_4^>3YVr^koU{h)CHxGx4{vvJw2QxFp+b4_pVwZ zFf3ep;y^ALnKd0ol!d#I!VQ)@Z#K9iB2nv7->k>x&7HxzW8|YaSc=A3EidqYnu*Pu zcgp+Cno0WO&4Jc|mtVr^p^{$s_IAFcoS7USKJVDn7{z+XySK@#_Hk1^{t41GQziBK zxeU*nAWvf*mopxq=l|8Hc<++CWkcbuaDcQDi}&8JU02*7?^9i$AK!$$y)S6-{CT~# zWdr;1pm`*a8&+{y91y|9E&67ud1U0WcF93Mp>9N_W|?<$jXR?8-Tb`C3^wlvzB>g( zK8XW$G;ZSO{+$<8j$;069Ic(rB=geW2I)Pt4!rzWvg~6OBzO@;m4>pkDf|IRW@cT+ z@iztF%=Y$6?7wJOoQNFm{d)O!4c?-M?*D!01hKztaaq zv3QT0MIAW?d0RDpeo;%sTY!fpm47x8q1#tFFq{%&N{PA zUSvQtfdem+239b`GSM$WVU-Tz1T z?dng0aQojTwWs)IJ?ufvJ+`ymMyfh(;T9Dg z@Q9tEi$=cvGa~TMu8OrwCL^LAdXriz-H7^vjJKz9-H^OM^{O0J>>d=jLHvVfojACP z#+{9fTl;nn%)%{<^* zY7n=(6#pHhiO`iFW>OCrz6Y&XN?RSNsP(+El#vCiMKXL7MG0D2v5gtMPrq z5ad0$GV*pE_`Bm@=Ksq@W{Ne!^v9c0M;1OKYwwB^wkWQ3UpQo<%oZ)#BR?}8TXqj2?!@sY$ z)=}|x+;f19(!EP>R?1-Ue)uuw)i21qckD8_2YDaz;;%Grt^EgqXm*xg&K zW5XM%74*m30j)z6C%>yT{k_Tkyoi1|-?y9V@Od|-xmu?XI3EreL1BQq-uD)<-@*D>KSCjn1#%(E8C6i7S|Wn|EiN)*&DAPi~uNWS=Y_!c^FFw@@9Qcg^KR znrcngz>c8P{X0_e2PDFtFS5=WY7Ebt;7DT~UT+Vd|NHY6YpHnK&nErTy~ED!l)~aI zDf`k#6!IQq7N`f1_cL(qqbl5cv*#PA{2>AN|F66qeppBZG8&G0%d*G__r0by^Q9o~ zH!lOCb=;9l_wTG7@W)A*kU(x-SXv?O^g!!J(utf8%r6LM2_ z-~PM*k0HkYKlA@4svhK4pFT`^#KyKRQNrp$rUFl{2Ei4iZFWgPE`9dD;Hl=7vmZY|;%c#D2sMtga<{ z@<@PRXq?8qg#jv)*pFC^)gs#0Iq9zl4Wf0ZZ)cHOg45S zTe>qAw5)YQ1Y@E<@&;h@9*uN#SD6t90%)A=VtI?a3T)mj(mX6&T=d6#46Wk@PJUXJ zQA#$4c#+RX6bRDJ_`HAGlGEiNZ;?*XZOmjER*(}S-;^$C3&Z9;)AwVMwgCO{rqnToliz(0t3AKRc#)RKfdlco@Oh_l z)ZX@el?y)DA8<&hrs3m6a-w#}Rb|GX|3A@K$JulH4 zRcAg|-G{vQiAB}khrF2+n##)|@9zCiMdq24z}q9qaVD>bfZ5YI=D>M){{M^b!V~J< zi0%v`>{{oBw5MH`>;IRtw@b(LCGy(EK^q#kp||wpVs-5KUtl=N`h+O`@ut+li<6(= zJHM%kQeNa2m$~l`6MWt^Uy^uptMUMg<8}$+I{dXa!O$t=?C~uOzxE~=(^kiX*yEr5 zaB=eA`F{p@1ppth22?%B``VR%enI+%Ad?1G4_cDyaat1gpeF9$xldpZIy_Ppv~Y{6 z&V{oYcO=Lp@M8GORf88{07Tn=cuyiDCn`RT-#70@2HnOpG+Eq`mnA>-#dl&qVq@G% z66^L$fLCbTQ|YVU-u}XV#Fo^2$?oQ+zaDf7t)mzxzjUYbW!cC0kaY6QK3*bz4>~!t zq<}cpo6HW1>7_jdp|WYb+H~xUz31fU3_0-c^J^~e)Q>FG#LpIx?KHX zEByZdgpQfw4_72%vMaxMEjI6q6?v_l77`!{jcYG8{yg;*n|I^um*2VA>5q2`T1Nv; zenTE{`!C++Lkc$+-#&L7pLc4BP@gU29eFP5_p+5VtRP#2I}4g`Fg$Mpt#yeQ zrborwYwN9l=6}m$S*lpPZwxLfG=#jb7GBJI40#{;LXagw-r~nN8&}*Vfso{9Z?zM{ zK$>1npJ@yk*);EX;EYi>@@|}m+i9m8ve@s3^_mWB-n;JzTK?E10hXX~O&xx#A8*HA zL2`Xh(Rs%~f4uF`Iyi9hODkGl;ugY($T1lim>An&}b z$f1XjHjZDi+Cf;H5 z-g&b_R#Qy^AZVO{MTyWVU2NW=zboC=FQh--yU{v=aPnh6vp{nFLq24mRax5^FMQs2 zmb6T`Z_NeBdarxZd+~XX220fF+)8G6-W(yc)iJqPGh$Qh9B*AJ-tHrdBq)oMk9YNy zv3P&r?*Sf=_k8kf!6V4K*r|BQN;v=TQJ=ip97zIl!}ojTwZp)Uk$9c<(`01V>D95E zdfiC<0z#_!VK-!+a>uu=-?4dj-P-)CNk#%t;!2U^#o~t8yq7G}ys=S;{&;^t>kz`p zZPNZwYNAA=UNk8GmuoPGcPl?;J^m z$6NlJ{~2TcH=*i5{u!-ee|nH~?<$uk3-%DOdQeF#zk73Ufll|gjP#eV2U*rLeUpVf zX#TTJ$CJgPfUDWmlJ14!VCBpHk;G7V|G(;{XePUEB&owH@6+ZP7phYwKp`5ZCE4_a=|1-SU!K@DX2(o_yyMY2 z%5d@viTdqU?aPO}VTti@Ifc)ArTW0@r3RNk%Jh%)qLVbt|4jR=J{lA;JZ}OUjdif< zA4KPWBP!m$2D|_Hg0yJKMJ+7edWHfeUm$P8pTw*NH6Be zTz&?5>rPFF?t{F+0!yJ~Y*9c+?eiEi5e5t!BQXOL_;dx2R{t( zQFs%q)itqrYc|c}5`et>;>2>FLf$Kl1FgFaRdq&psEXd1CV>X|&Y|XyVL+-oDMm9A zUT>+mT_R>X{QiGtSc-Rr8*=aYuf4r7*t~h$m$20ylK^#S+!pOKfkJDsc{9})cGL;d zU-#xm>zId=pFjW0<+bbhkfTLg7s-U<^X7}}urid$0dIuAe|wvQKmQZYT;h3_ti|w) z6XGe_>PVX)HV_H+9ejHS(`QuwfjGk)>Rvy1^c^^yZ7|xMc;Epf(#StZB}FR<_|16v+%wI2t(sm9ZM?rv&QC4 z<`VGpdQX46h0r<%aq?T(^GWSDCm#}4l~Sch!hghujBKw78OQ>ke#c$-xB>qWYxnW? znyL*#48MYG`b=9L*+>;tnAUTMN?sbc=;iSK2Am=4aSuoJ9Q)EzyOoD+pfqZ@t%)PBG|lp z!`D771QH+*jZa`4^!1Fezxye(eM ze$R!x^%iUv(BZ&;drRopUd21KoZ)#BI%%wQn%oqksW7^87Knw1VBqu9LPjbuDf{zZShi_tn>?WLTOYS}=Llq1(gXu`Y~@t;N6(N^tmuGx&wo5nhZIxF+i zW9GW|Rw~|yo5dDWcq^}nnTN%@qwK+>TF5(3${?);^0rZFer^bP8$K5(F_w)2pOF2hNstbYw;Vw0*o%|j7u~FyNoIZoBri(c|G(IK(+g`@c!c{gE^le~FBkWi z=QI4;yU~xfI@;nzF8zx8@BaUP+8aIp0S-vkR6U4z=G#L`4~m;L<-+Pg^NuylUk-cF zQ%j9Y9k2(e5W zNu&Z*&0q9-k*AOHQY+VKyu_)u2)CM$Q`fX{9=!8gmi?@ z)jiM^5gpa4lf8+}J1HsS#EE7Juo8`%|4{ECn;EM_XV^L5>9?BS3TL? z3we>n5-P$<=I#+N^rqy>8t|r#`7n`K&9l&V9hy^*uK4m_qla)aMdlJsKCPlm6n{O8wO{yYCq&x1dj8=U`lQ}rNHgmVI=2MOtK=Ev$mGJ5{)_j?L- zm?qdtKfoTeN^yzDS=fVY+>PEo_lg2T_8r|$(qZ7vr^BQ?A2Oo2HZ+svF#L(#d&U;P z#ued|8ei6Q1G@(`-&#M!F<%laK;vRcpN>ZC$L>MZ`VTK(IZ1y#=qXx98BTt_JR6Rm zjpIX*+|8U~>G(Zp(oSJ4@IoY5yV6RZ`6dkqq^A#!)>vvVeh-?Wv5v`y^OXPYAnl^! z9l7;gAcgl^Wgb2(-iOoIMYKWQ{&wWTZpi!S{MeBXFyN%T z$6xpm8BsZxc*W4a8#!2)Sn(|16*;i!ip%n?*sr%#HraOx{Ez@1Xk5eTdz{l`Y~DTt zp5Ftb>5sP>r4F3@I5(#69X91dMna3EyJ?vJGnf`_Q0$BY!JQKQlNvN!vBQ+LKfRdo zf8K&HlSxw@A(J1TvS!V#Aa_#nKCwc0?t05VUvKp=yZGTYGBtizvTtWNc{1=+Grsr1D+$$W?W0 z-kcwk&CYz50Oe@hSVs`MLNhk++Qq~hkLj>`b5rWT$#0t~@uPw;KcX8OEVm#Tzk4r^ zIGOY#ArV+CzIfWR0-yIp_zwMvjT;z#K(Y&_t&YtvMrA^x<_<{jpyD0=^|Aq_d)KQK z@?i1Kl+J4S33=-)r(NxYy!8mCyvdOFz_m7q_I*)cr`qxbkCno}l@^mbckm&mg{QNPY2Y2^-}_J^IT5tWTW|9%r{Qp-G_j|s_y5857Gkv3F>dcu zWso!1y=|y?htb_S5-_eKHF z{@4{s>S4f2>5|9_p|z;Zp8J;@)f})u1LW}_2A}>*u2@xI7NQ-Nq~GbZpZx! z<>A}dyiK(guUn?kA8$^yjx9L(Ih(XvYhK|)E{<)O&Y^*K=)S7QE6yZ?;Om};RE_X? z2i1N2@Z?@1!>_%G_i3wRyg7f=ApXDe{|qqw&z=8wpz1-V4jcb-1_`NBTY}Yt*6=9a z^oEaE(&G540oa2Uk>Vx|;U{*}wwi32;suOQ`3X{#gLT6Z(+ z-y5X&Q1Om6kq)9fVr^#G7Gv?Q&YgZ43V9cv%B<>#ysZmBLOkR>WByU`vtksm;flTx z|CtD!9^V*z4|zYU<~ZyKdAsMNJSbb@hNML~l5+tE<=PmsdS#q#> zFX(;nE}579KC#=1)-fL^zt(fQ7p^z+BU?B7c6eXJACSU@HLSuX?LdrZjh=P`4I89Z z7eY$(`52xzVLOd=OuyQD;qUPldn(>Bg6a+w-bXTCF2dsdHsMz98OS^3sAP2?1(K?)Q@++RnC5UkIBU<7C^S5Q-^EQ?7 zKt8h{0>Zl=m)lF?&;R14iBVewPBJ|2>sx87!-;>#waeji^S>Px@8}NO84B;o3#o!w zybnwMn#qQ|XH=I~_d?!A8G{qs;M-e^fGVpY?L(XR_Y8Ya{{BKFl&{ju< zCRe9s+T8qaOT{~?D(j#9|F;?k1+aK8Of6I|gS@A>Mk;!!cnAIX*i-{~_lm>?^+Dc4 zen&D*A@4|a`PJ!=_rkBG!F}-b*2*lcryRZ5dvDr0V)4Ky-}i%~i}%9KiFs?^%H?L`^A?rWV9H5|1SV_Lx94%-^FH(G-l7Lh zs~CR%Py0w)9gms4_WQ>DH~;@zr=Xj^gZuycsCrOB*y?}w|4SM-tib9)F9jnkm%ttr ze?Fv=413VsGRq5>;0p4j(&LKuog`2iIIy&HFA-GSRxQ2Ck>~}M;AF=K}PphRx=-q+7Z>Xl@1R zOvU@``Zbp*D@aqp-^;LgubUJoUj=#V-(OSp3GzP562W~0@)o=++B6$Z0vCh_dP|NH zfx>nt5nagp9(i5UGsxTB^s)M*E?30aP9%Jt7dG#G8t)oO-IBl#jT3$|+ME=C&3k9G zt99mb`s3|_)?tH_-_9%P`B!`RkelUkMFBKiZ!y{%xTPj`J<<^R$Z=aP{v(#y8!GdR zw}jz&6Z>eZWA|ET{wIIG|97I|eTHjQ4TX2R-y;z$-o}^TuxLZx``*5){s?&oESqdm zgS-hG=KL4RNkFA?Lhar;BG|3ZRw)8`JJ>93V2AU+y2poQ{C%#7VzbJgk%QR0E4cTo z$ahGBRcIXB`2f9Je%QPn9OEs1iqjwOYP1eJocw;@-R1XGksp~-{-LiDkH3OE*0;oN zcbqFy-k0?``3C+0=_C6j3y$P0Wcc}?!-cjwbaIDciyP(!q`g$U@EndG8B( z&)@17dTrblncc9~Q8X5t_wooP*DdXm;0GGlW-wo7Pb4;PW)+sQ8>{G#_e!)50#1Gl zjw@Ps5&4n)p|4TK3HZDhZYK1}M7SckTV9ok((>yqXV$l@c3H^q-J1|YV;yd~E70Hn zbEM*ZI`8ur3h!~mWhoZ#x*t2v*+br&U3OIuLf!+CoCX}QdnccNywRE|3aHe5Exz7B z1O^MoV;(`?Tw&55q9N}CwEs%f5YaT z^rTesARYex-)ppvvpD(f4w1C~u#q3}?U6eMXxMwp(^0!t&838xR6p8GXvE+DC)n#g zw>8aTc;3WawAG;;;_SJrS}d7ro}r3W>niAiGhpz4N$s&yX< zbR5rv+)>zrmN(D3U4}hKFU>-2L4PC&GkaD1ivVGrskyrA<4_8<-G-6{kP zH>C01$`)f0>>iZmQ{SiySCDmRoYRwMdx$#6G57z!U%42)x1avbAYDT1z{~H@<#reC zMSRGDkw@nWX!r%Gwe#m`7DWdEvu`UpQ*Y96#m>Z*%nHxl4BvwYHw%mtq8F@Fvnj^xOofVt6($3kU)4h_w9E}V4ZTrAa z2AemB;DWaz+5As%0 z?=KpGyk)-jasBy$w0Ne|d`Fl_;O_jkCugLI;8fcRw)t@W|4>`5ZwPre^ZfW+ROE_m z@BcMsDTF;BP3%=Zd~s9~Y(?X$T34s}Zo*zcdhUq^cRA^AK$=AB@W9DWC3;oQAx%C+ zG+g+=;r|8iC939322wPvAgB5se6zj9@Vp6EdT6TSM|!@e^xxnAbD`p$^vXJh!u#u% zgq2v``#L*c={V$lE-$C-GvqB4`KZ1X^43?94?ekw1e8p(mJO^Ug28L)N2LC|-rD!N zj0^G>avyZObKey?{rtqoLM?3GUYkAi4$n%0C^T+e+HXYJ9-Fr$ue;wTN&4e`0IdTr zzmPKFwN*>`k$K$5{7Z1d27#l-F~M=0{hyk z6=t^*!D^mbVFdCHTG^%E2{$Kzdj73_tZs|Lk9rdU2n8z{50BP~a{6y*Gl1 zQcC_6CC2aGTWPCfZR6|9{!#zU|CGfkUH>PX|GlYtP==$Y9i<2LJ1>{R>Or!8#jiZ! zBX*}W+nI6LgEVeUZ}_u8DnBg#d+%%{$oAf@98nMo8ltB^Zh`|+koM#5_<(LC?CG=T z&PlFFw~6tcQ~&b&f8x@M2fJ@df(|rJ*wXgPtR8j`l9H=?KATB@1Cj(<2VQ>L7Sw%i zy1qDm>xNK+oq$m)72dVy`tcv9i#_vIHhiR)rcj>vvpBguGkab>7v)x*`(WY|;+*V;`~OVrTZ0zAFiqqj5%OmR)C2!se~) zv2OhHb^7DYjn<)plV3xU-2v?$UPS&t(5H^w_`GktJu+3*=LfpBU8rF0py7(0wH&kg zeg6-xw^&DG9kDI9#Q&}!y{LGnPPMJ4@V5I|BZI|z{N|ptILO<%J0$rVH~ zNfIQWalS$ihbJFk^Oke0d~yF4{qZ(L>sXDG-c_Q-;lHxY~CgN1l{(&pg-Op(K?oVy*15hFNMY1$N9QY3FIyJX~CtjKZ}!+WiS7HoLEb85gbL{*c z3NlFU4yPdRyK?iJ1R?L?#+AN$ui*KA&ZfJp`>}Z^p8iEBgS>^&I78_NCyP_Cd2ba_ zNLt-af4tA5b>QWf&zv7>Y{ZAyb5HT?b;0L-;)?Uyb&&TD`46RQEb-Ug1mpPok4`o* zJa59fINIuvVM~(v@BTl!9{c}E4$l96R6Quim{d%8#C}QQRKn^(#2LL*LD+-#5dy=1 z!5(Dof66Bz9uhpY9QXq)ta}g{xvV6 zxiYhDk0pK&@~=*aAr+c{r)$3+ZK`8Ve!>=F-nzYrCY~t89bZKt>_od=} zS*+-v52OPfKCHpwZNnBkDFu1^i;YG6guKUo&Oh=7@(xTr9pCRr0#26wLCiIwz=5ew zE(-Ey&0aGo03Wf^ihH^SWnGb1Qr63^C1dkGdg^4XsjMVuLE~&e`m&Wh*q_*iugSMa z9H2km$Iv>$aPnL2^j7Gc2p=->s=Tkz3ZM6)Ons{|O%E_^Z`GDzj?bHIK%-svBOAjX zkQVHst&SpoUq|6{bG#2x@y`BKoI>f|ca5(pVDVlpcGp@H@}4O4i~Iq3zsnb3A;1+R zL3!FH*#v&QHMCDTq&O7FB#qvRfxN8<7dUw#@5uaprQ^KPq~$^9%L z2|Um^Y3u15J`b^ZYkrN0<)p*z{Ti)911G-|Zs!&TIPoEQ@Wbsb(Fn(p8NND3m+=pS>x(v6yB~&(&VvtOXN6O8$#Xz z%ZgGbA#dNWwdQh=x3JDe6_N@G6e&sbtjh@nkMstnPeR_J;_L4I>E3sXx>_RTU6HIS zCKbmLv3Z}|HmY$|MG~Z=aWeOd`h(wK^A2j2aM?Odf89FZXOez|8tx|PP^=EO>2 z!=?84ysfj|t}}Y+0+zke(37ghzuscav9tG!su=%zi=?Bp)iHYViQhHl^M8Jv_#hSU z%xG6`3UAgk2CK1nZyh-9y&LkL@i9I%0eK%Y58dbid2=WV%r5h5NQc9fET1a>vDdVM*_PmPi!_eCIYoAmc7?u4|;LX*|8bU|J98;w`PT1 zkySs&rOy(vAF-=8+ud2FB?(reaj(;5&is6f{fJeUKNO)68MF>focv6s0_r$p zc@ewOyj7=k@E@^+Bf?WsN#0;|gN~}zM;dyN)-98j8RWe_%1D!#O#+pRul-2ZAcF5- z#llPeJYtbkJL(|sk1U&)NzQjg+$<{dKG|UN9|4 zL4Ul5(K`BY^1HTLMMSBY7kR`*a@=8n&$~xHk$gREKe$;J`TR2%KJO$`)|dHlObkE& zmu#c0j=ioLkMC#9&HqQJcwhbYO_0KSD^KwFq$3N~*gBu!g^4tZZg>rlqYFT6GVaTqTj(vkS(_^2U1@5ejL3~V#^gH@ec z9O2b89FV@;;>2&s__wzbuFzPA@y~0Le~-5ursADjB{h%2d!oZ%1&g=;`vcdim)J0AF`JX_N_CNpQG{bjqLNsl4_#A(G-1@>?_x7jaeI;VU zKfm5mS+qeJi+3Xbj21JT|4oj2giS%-epX9#6CrQMXQ?XR;N?WpCa*mj8$$u%gL7{o zsd@#`u;K>;wGr7NZgLkTTA|pjD@`k5D?|(V!MgY`_ataD+$pF48Qi~|3Ow2a|<5W$$nI;=J@EBswS z22t@Y=7_sVSwU84H>|_ry~}yLDgg3s)Ezv^40)froydkj-nX{BHsp>a0S`0B?CnuR z;C=S!8BNH$U6$k%19^WG@wroz>4NNNCs}Z(WAip@F5))XBnft*apo-Z?gVmS4@eV9 zec`d~^!JE0K8fj=M-lT){; zj9g=Q-ozBz>Uh1nB7r!$Xh{b(epwT=#Xx1e=2;pA7a z|1{HtAU~4D!|yh$h|hbMNatk1ufsszt=!&eGd^#E)!0i*8-9l8O|YS{j#YzP$$yWx z9Hru&?=QN8!uzA0nkE)+ZUd)+e8_wBC^?h>c^iD2Q2WE1=+PFSTTBAFz8&lL*b)J! zkgR<+#d_@T`i49C5Kwf;AY(l~?^S0qKKZ75gRe45ANEM#&;MQ0Ri| z3wzL==jHp@VGkNELiz^uRdwn`kwl3w61eg+@U=GF|GzpZKQkZppxUR>J9^hbK;cx}`P|1X(^rgx_KQ^iq7@7Ufm-xjfid}*%ZFS^?+zv6y{WBn)AyDxyYiYbf;r-PAJ2Mt6S?yb4lZRMe&u#*C#SyhA$nhb?)V?}-aMSD z_U->STgHtdA(=wv5G7e;9x53^L`gQ8q9S8bnTlwjGK5MQk_u(WQi{w|N|F?jid2$l z_+DFkeV+Ztv+lK@<9i(6-`>yf{;S@%^FBJ?9k0&oI#;_YW&&xD0{eYWM4A;6o( zHUr#_`Jx}>xzu$jz}qp}&Ych$i%jVrZxcTpjoh4xpKJkmPpF)?fdSqYZ`}fk!Jcrq zcYm3QTXb&U!~R%LII;6pwWtp^-h52Q-qe7}$#HVrn+)N^&ezy@Cq~*j$kE{C zL~hgvPJT;DWfU1A_~GI9_6j*kDyp}r*w<+5NaWs=8kYPt{JFP!ze)Z2O!}XD*9=hS zBPd3-DG_{o```2bwA}cUa|1I-c8VHQqioTP)}TZkD{ibBR3YMewfa@De&eeZro5mA zsW8u;?F2PwxB$`NNQ*@pM#QX-Y8*l$^Q?E(gZ^J#A&KDzSc6Qz-&KBKHTX1)bI=!q ze>fm*)Su-v@=OLPB**oP96c=i4;Q36Ebr-txYFJoBt5bZy!_S}%eP2cfHz1K7M0I& z;@6@8AnD!Ii}p{zW+}Pq|S$r!pXw73ol5euuh+CuH?(pP8$j_kf*U|yr z!U;o{z5%?=JANN-lOn>JPu||oRL5RoKYePew@JSYvW6TNe#Ini0>R!vGO4oJ&$)~C z@J=H8z{^kmMsBu58b2(&Z`tp5ZhX9JHt4e@S9-vg15Fiq*{GO7CjaPq&c284@n#67 z(nrLKEq}itmBLDacjeO~2EGJ%a|9c1w1@N9O*thj%&I2VQTj?)5ua63@>v&bkiO-QTMO{k_S~C#0^n^Udi64U91-S$ zV4mOau<<@pXW%^hQ3l~7$907edtLTm;~lossquO^?cp6o_JNn*tfiEgo{j*lrQ&te ze-S?3de53REk0roPhOlq@^T9Q<3v7Zi>~g0ndu&Hg;Uh|IH)#}W)?+S-b!Jn!21sI z*?;EVn~xu1$HM!|Yt?ms0N!DT^mcGk;5|Ir5YG+H-X5OVZZin*7C8CYMG@eAS?P?z zWq|jn+>y=GzMk+Vwm;{Tb+G&Y^OAjB10FJnH91bblJi4cHFp0W^+l}z)_dAp-a13} zftTODdcX3>mHhu>ykFlmT_fCsKRNmT8{W0oIRAtn`?vq6gYKV!0n{LFiW>Al=%q0_ z#QJ-$7r?4PU(<>&6G06kwmezB2-KiurMs6qfFX8==1J{V?l?pwwH&V3jzq#7bM}$$ zAnmVbc=8N1NQ!@q1oszv!W%E_Xq2zSu0aMS4u*HY2~sO^+(cDsu)-Sb1_?4O`#e)Z zdo^ec*#};J8Uj+uv6+0ZtmB0Tb3eHB@!0v&p~qfr?2P=VHu_RCgI|LlKr>&J6@%!0 zh#g!?oeyKRI(TZ~id_m91>SXEbO|WlJ`9WbvGBf7(;RRR;Jq4wWd#7NPHlTL5V*1aHL;hof~ zp_TyfW(jsv<_CE5j6^~Z=>He1>z)}Jj74U>ANaF&L?ZdQOZRmGyq)_t8fO8#m&ZA9 zi4JO+_D6 zqL3RKTD+$K-rYG}%|w9r8Qraie7Zg1uBLM(9lx=w_xJr(%jLl3#2#|o`0?Y}(g(5e zUY5610N%uk zaj|az?*bQNkT?0^ohz{dQ*vv5~$w)?*HR;aWwFA(EsyO z)S$-#*EP`^WO7Mc7^?>TN{GC$2-F~zQ;uxHpa#9}E9T|{4U$@K>Cg4Hafr()ljYO= z5y*F!?_1bG4cb}X=QRn|AoFHgTaIQD;l<$@$!rqXZ;Np)^n$aOhK6en zVB@{BF8gh5u?&L71uxZNW3vm#e8$0Y>4C4zQnZJ+6WNCqPJWLsN3JjE;DcRPq={{w z#>bnbCv;+Vr9YzVBcWcVg1>{rFk+$pwQP+3@qSC456J5e>wMY51}T98??*R(t@uy% zKHVvZg*VHh-SBFFcLR$BpAf)XTi(}YDZqPF1hFg8h(k)%kCg^pj6g2uMXe@%Ank#q z>_%6B_o?MxQIF?{@CMy0B`vMkc$XXOE<08(gXojvjQ#ZvT{XtWJGWN1rC13FIuH94h!flHO0`-)3#hbQZ{k3$OEg{E@mB9N*)zMByMZ)5Im>6HNQkz#Le^I|vOfU)sLbX}4I^k@(7P_mCYocuDZC%=k}@xhjx52_`9!^hiqJz@3OMi0bD zeH&{Q7Zufe;}fpD*lD_NkQkh)^Kl_^^!?71h3d^ifp@)m;9(T+_ow_8Vc~s2Q>=9> zX>!7DDzcaY@BQlcE#?-2Z<}j=OK#{LbGRd+r^WvQsU&l=hal`pG`<@{3)1;8p7$ept;palZ3^ zu=i$D#HHgYieJ5D(uD`IQ$p!}a>9O%Iv*QuZOIQi`|tgKbo8d_UqSybL{Wp&*vC-}M~JAHg4DB@7SpSF5c>3bmn&7qh6?AXR5F;2^rv zeGOvpqSA*uA@=Y4e<^|#c(?YJDx!FoPtA&9;l1SGD$!1W_la!2aZ!Nxj+^$9Y(^UT zURHBH-w($j*CzLmGkb+295pN@;sEb6w;DSe0p7&iSVuQmJjC7vGIPnSTXTF zn+$T39Cz7CA5JpE9%2L3TW$<{(;nV^WFLVz`EgeIJ~}7Q2Y+jeFH`)0kM|TI^Jh}I z5M1^?d?@4-6&s{cKQG?nn52KaQ>gRt@#+KOh4TwD$i)m6v^Qm@0Pkew(Dy#!afr&|%J-YY!V!Ie9jhRKxA|{g_X&Xa!`3cq zIW;2eyjCL0p8b68RBn{2CwuZ{<`l$_x=C4CUri1dL_HEV9E=a3+nx_xQ5aGH%F*mx%lPnrq{$shr6b zAU$IsCwU-(_VA7&`@qZZ#BDwK0yRE3x##*`KPswsYfMvBri4DySLe1#hmVR4QqINk zQ1dRj$D4slA9}~?)`w>F8qw;#&Chcw7T%ndifv4w|Nnknjgf@+Zv9Jb zOkjDd^a;~Yp<5iH$Fw^^y+0fwzEew|1bDM-*gn4m;N9q$dY|PE5jN%zUU72^_VSjB zos5gaWf{bX9Cwdl_3-O%?CQO^Kkr7c5bZ5*$&q~s;^ddc>#*9Vo(~>`P4ByW#IN3i z0v#6IsoRmK?pK#gSmEEjeLz^&@%G>rx}TiLucyw3P4d~N_rc`k-~E4@?)?8I2l{_e ziW>BUX`3EegChN9WUy+G*4jtMe83Q!J2P=d64W5|>87u_p#SeX)#y2u6Ne-#)^01` z5{?8Y@K{HI8Kl?kI~KBF25GxA|5Q__C#-(DeA7=}>>>7cO|op}s5GKRjx%jgJ!X9z zyZ=XY?A`n}(B2SxgY2UoCqK<6`*z=#;DZSqyi5I?@N3XaYJkK~?;Y^`-r$wT&r;F< z-|1C%SpAv)m)NVR^fB#_s`>YTv-EAFNDBi2fCZ(|O-nfBFD+1tst1q)of`s?= zf}TQvw_VijUo2U1h|yRdvzB!@BC4YnKm>UI8Qj@s1@LZS%z3s3eBSbiB=hixbJ%z{ zC+3Tcj7uZYTtIITihXz&f{>`DnTyVj1>R=ffz@e2xF5g&E{h3cS1W&i|)D>f3T( z5)1Di$)Cqh0K5beow39^4d;^laSy&I;hYL$G6C zD8O59=w!uHZX(>yk$8816gJ-Mdu|d3CZ&-Ua@_1$d-&Q{?CSl4>(7TuE84@GiR|Mi zPJZ{=9(~Eb!Uw-Nv*uS&KR(_uzg2&Ri)q8+$M&&Z7RB%XAEuUT%oD%UJ>Daysq;~J z`ch&`>_Y!9Oo4Z2(B?3-dgm~mkif!wAm`52EP!|CsTEz~qz0+PenkPmyJK&65X)(> zIkB?lYoS#*!u(?Nt|7pC(si{(0>JyE&wJh-tVG!I)0|4LA2!}!o*W%G{X-ftBgcJ= zvK@9F!Nyx#H6Vq}iT3cGB>Py4li!J+mOI)A0XCYKsA?F%$Gi9(VbtKg7TmGUWJ2~i zeuEVKiYLW$^$gwP9otxG8I?pSBJ@a=8V;ly4Z=jB*<2fmSaF9CSV z9Pxd=4B-9te7jvbz+1;CdT-2$IK*t8>0GQuI5L*^>?!Gai*G`S9v1-Kaw$;$;WQbm3(m8 z_0UMeA$+{89>3c@tiKlFeo)#ZF^zxrcJ|QoS}$Yz@BhW)sPo}@`k+-)%)k9V9d!Q- z_x~j*YEVD(dJA-jEoqccz^XyPb{eWnKn*%zR&iVw)Sx84*7+X>8u}Nt*p5sM$02Da z1s}{D3`ZW0u39_;YLIxF&1DC021zcyZGWmT5r*HfjOk=y*Pv6%0gvVzr4cl4(xPZz z7y-LM`Z(br-!4vjH7JSf;}cGP86V&9+4%6mAI}QBI^Td_gO(M=76|XMM%up)F5Pel z|A<}Y^^@X-ZF}i{h~?^`&WCzkS=I;e4N|bYwVVR)zDEg8DBcnK-^pX)ZRaH`BMkVdMSP`L<4Yi!?Gvj$^-nJE*A_dx(9tvcQc+n)dLXB>Q-SlV5QB{iIK8 z3Glr>+q1vw@$t4}jC#M-&KlAFeMaFHHT{23p4#4%VRVl-Lj!d_PH_Y($CNDe|Kb#Q zKRcNT)ZeeS_Ilou!@|2VqhRS;fOjA=kRb!`)*;5%l# zJidFc0p2fkShq(2y!RB}9De@J6TW&xWZ#Mn*mx)K>oR0@N+Vauajh#l4{WKz##^ki z{u1j-+Qa)8*@py9eglIlqtUzg;IkY`((?#D-cAAU&u;5Cg$-7%ak;ewzyF__4vAh) z_(J!1=dU?Pm5)zL2KkQvy&%1e0`I4u+3dGtUA_;X93=mCi(-mm*Wu4KYii+w&95Nl~Qlg`!?lo`?<-oK9h^)Zc; z-$^Im2DL{7SYlU8{+37hct4QX_ua&I2W-F+f4gb|zyBA};mJ65YMAc#-tIY5=VR^f zH_k}Zzx_YG^#3a;YS61s^7?2Enmo^^hE;nhvipcKe5xn@HMyf zx-^2u39j%OVOxt`gAO0R(Q}7^_G(Zw*+(o+ezsi~DonN$;JPerzsQUDHOOqa5v$;( zb;#3~QQAve>v3<8GT1FL?rKpBQR7fL?>$8lyYHw3SK#CAneCOc zuEYqjUHkIT?r|y(C$8;JKhf1k_jofDQ0YUh{+-<4!-Q7Sc#p3P zl>DVbghLPR-C8n$jrWTs(&uKIq>(Uk+`HXQ<2IJqdv6K~r+K0zXb~ll7-Fjzv+1dU8uY>6}xQ%I;2 z3wR)%9Jl<>`p)J1uxn7oe8>fTXWFYlNn{_DIQg9sN`LlcJ1@-g)=kjtD1Hsff4;Kd zT!tSa{eW#ZUn>3#vU7I5SOyFI*Pug2)cIKEx@PN}+=UtBN(#J3ZqyW@cyIOX(!|2s zbk~!j!vOEb^Z*l8fcL8q!r^-W@0sn!M&BCa5GZMt(F^l%Bw;Mz=4*g=edN$PIe_=e z2fz1+xPs#?!e10ey0P)zcsw)xIk+H=#`UduJE-G;jknN^8xkeEXb*2QvJVlQ{A!2o zKCkHKg+IiWn7>NE$Ghjo^wxk2en@{#p?P~0{t`PwLWskLf;svhVpjxH=VP+kmwl%o z>3EAg1>VCE#o;L4_a0|!VBvjxub9{=fcMi5m(3~w@BXuz=}W=tt=QUELYB|t5ZU7! z)5nd&kuOk5-V!i_6n6Z^akfgVztzHGV zu@^+>6j;+QVCe>|+s5ezQlEhAm|IV3vk$e;Cv7 z@vfVRR@@okgVgfhC@WQ`qI!#6xCGBw(|`3|O{I@LrfDm7FH~XGzqfH$-7IyWT>yd`d_=1%~;g9$$E5dd%PE3Ev10Pj^pM|)QTyk(ypb+NeX z3G188?&7vVW)Y2+O_ zPMDSNB||E94N?!-Htcm}F+yv9mIVdzJ^bELl>a8Hitltf8HMlz*>4 zqP&gI-<`v+L2nZL0}QIi=)MNM`AD4)o5R`T_fIVJ|0)!Czb{zRg$}Wvye&FdcxSv^ zZ>tLM&J6Tkq6zTcvUA^~g8*-p6-8RQ5^;#ZrZqAB+~LT6x$ODP0B@TI{)-g>-W}-) zcMZVjEwgimGGjht53$$B#@K9kNF!+6#}zKziC)-vH?2^X2`HpJyswdcG~?u#%2U%4 z!pRE@85ONfrULJ(4w0lLHd*ASx|MR*B`S81w5+RkMbQ897Q@_T>U_9$3n>2GK~ko` zdpuOu1;zWP=J~Z)c%PSaeGUV>Pc~eW&;WRs>ssi#0lWwLh5NRE&s#_-Z80{J2uJQg zlBV_m?_K-C(!>GYU7ixiCk7(y+Fp|rl!RTq&&JH`UcW~g*+GsAGBPoDpU1}gW!ei3 zuX5VMJC*EX5GOz0Hbvp!a2_~}(Kz|nKK$zKH5bH8Ow&LPnRN8pGf}aF6n9|Hi>dzw z&s(ge&PPMen*qVUtG7xNc)#1c&KAX6I>ToT7T!nlj9je&-u#Sg3hDrFuk}KYR|C9{ z^{qC0=^uy8&4f2HX#>11Ipa41yo<75NXh}ce-ny|*8cQ_RUW8C=tN`V{YG%LdiMco zM3o%(zGKJ!qEFa(YY`X?Rz09Sya&lXv~lwL)>>RS!c2fm7j-eSgy7>nI6HE0`nxC6 z7uC}r=!TE?a)zsn#_FHxetBykC7&uEogL{;$%hs$Cn{3lJ+{ce8^znVX0oHouzq!3aU7B#oFMRFb2zf7ZjK`o;9V#@+usE?Cu&dn zm@kbb!i3>E4-rZ1_y0B~22RNQmPYui_wFIj~{XAlLi@N7@F8^-Gp%HLe9Uh%fur zIvCWT6+7CCHpIpvQvshp?&=Cdx-#_I+(8Yh+Hvlj2pD49gF@SU`H1j^-T+atI_x1f z)~@o%X)|dglN={nJsc}4k6nYdFt5EhnoN5`Yz*0l9Zr6>hfYUH1QXy|_-i_^IerbQ z`B?1vHEj*N_)#&3%0v7b#J~&fso%Mo?uS?gK~}1KT#kOda#6uT|F1!T_teFJg#*$g zyakR(v0~w!_W5}2OMv%;!Oz|`0B?zv-{k4m^zwt{De7NC9qkK!wnyAHH&#jFyt=X<6XP= z2UR`_F)Ar<@oz83q~3hL+{Z-!_peFQ5+X6#wmAYDa)_oPMl!q;0#)q8p4eI_it87g0| z_zm!`%}Jfs0(g7N_bEmKyeq>M3q~7bk&uUm>rah@A*x?Z!;Jvm8iS_OCID|2Nt<_E zuRP(~aT&dKPS|+AS`pk93MMDz7Y`h!qS@#(_Nh8waxGRx7gIim$@s4Aj zeY7Hv_V9i{_7RVhpQ-qziYi$im^UCqZJifB-eqcR^_!Trk!07Oa{{lasNSua{G8(9 z^xyxV&7#VOPdm>cyIcSE|Nm{jO>6%V^#5xqYS8xw@9(2E$luMJ8>p|qGP60IYE206 z`TA#P?N;E|pj3+?i>rzr2%FQ>+IRP$yrpva)tp|8FmGInS05?cof3-aD+Zl`8E%^=Itqnse z?0#hI1$fI{T&&Fw@IK$65%2`u|DUf=5+Cxw#@mW5{JOb`H1dla_wXI-YmrWDydOnH z25KFry&=|^?4uDUzk{ukI~sQI!3MV_w5t^H@osj4yRK`R!C4MlB)X>Y@y=%u;N-d4 zMfZ5K{Nbm{N3SQ(hRnYYq-#^){f)@xkK&yuILU#9_d7EVvn+sjCck>RF2Ebw^s9R_ zz+1_9AaNBj7SU7XC*(c|Lw@XzNh9GcXyRGG2JjA$e>>ap&=d9zE}6F0#m0M?@|7o7tc8vD9;Ju%PtB!~d*nEFr?|kESFrIOYS%TpK!cML53-M8ocv6ejCSuk zOMq=6<*j`*@$nvfEa#;-x&@YdQ+a&JMf}5wF}W>wHc6|~egA)pN*`ip>Xu#(U%-1c z1>Rp7XMdu2Uwx9uj)nKk|bJr2J9hu2#x z!eym%&d^@<)+GC=#K}*>ZI!<=Cm(F<5`M;g9X{U4nc25Ehql0Zl`X%Wq^LNYIJL53 z4RpVpfF|0W;M|LalIpkGx!=g=C|n!G^(s|IDK-@d2_ zYEaGVZ>tPJ4Z0@3Z`r6mXpkg!CT!Xpi>QRph+Xv!Lu$l)Qy=?%fZY#Uw=EAFf`8Sq zh}_#jggxuJWco$0&mcWbHfXd0caVtWxQMlED;!d=_y4cC{?yp|gZ64r2iXT+elJt} z)yu&rcDo)WYF2RJ*C2_?U+I>xH?py==w1jH{t(O1#&7&n`zig`pb0+ed~DzLRr&7$ z>Gc$N|BOF4isIe&f}0-;@0BOi=hgwdMSnci-vIEwBg*Hr2rO?svOZ#*?;VTy_msOQ z9u7l{*i~j;0lYuhCyvg7A+}_-^&*LfM0j19SjcD>Hr|^gM1<&wh5Ut8sTLHYk8ar(^ z0C=4IqQ1nE7p4+ot5>KY1$4_5QRF+Iz3 zo5b+(j&XdkT3FW=(UaWu^*Cz_=0AIMygv2x?AF-gPP)f?-_A2s`Irg5d*f=v!UpL& z3cTkOxN}gvSAMz9i-mX0XQgBpfOp)RxgGid@Ao_Fg%1O~!`;8uMmfeJ#ot~hIot_D zc*Gzp4uH2P;kil~!26lV?58hDvel><9zx{ub4(+Pfmn7 zE>)B)r9He?l6?r{d2fTW4u+?mge~*GCafexDlKvQ^#^;E1lo=8NL^)jRVdlJ8~UispO*|nSTo#ALIB=RmA>t{0`Rt}$}@kc3h?%YyWQHchuCiWeWMT01H8#` zAxEvMx{a}CkOzpvKlxtM9^S2FA9(q(Wrv4+_awkx4$^jk{{y^tN1whP)r#-wg$v#SO@+-XYy!G4%0=yx7uZP)3{OZj+ z^|^3+&`yMfyKroIClz0BxyR-=n|GD&@n(2Tr4NUurR3)=^eOOWSh3R$#XCdc>S8Rs z!!|pNa)Jiwe$uPO#sKeBw*1<&U~?j0WmDc;6=bz{_vh zgs6+NF9BA2eVBdp4?f;XM=NJ!lPnQo1Ac`FF8teD3?kcGM8EBz{|3p|g(@GLo|Q;W z<}Xxl_`mR8`TIlZf0nn_CI&3R!n;N!MMo6it;6tK+6dsiY`8h62H<^Vyt9lA?EnAX z+5NR_TNvWoUbd?o;B9a%vJ?h*Pv?%083z;LUpv;PjT&R)?aCifdA>v%`9qFtPmp#D zzl)9cwy>C!1~iDb1K9^&ewUWqIlw(afLCd#wU$Bn{l72!kl)gE-blV-bepL@{_@sb zMom#^R4d)%-RfOUm5`J)MDkb3fac1?jhNJ34)p|iQ6$d48ct2?q5D^F;f^!bktQPbp!cub;oX<94fk)Fax%`zhIn4^Dpd4N?c)xC!tM^&*FxkMZ%YU*8E2->`?H`U9`Lqvrd6 zH?qaQ`P|4%_-cY0?HSno4z}qmBZA=;9ZGZoqU@O2|OkKYErUf?M zBOb!V@d?rh8YkE!b?D$f%pf!KMyj^A(;nWh$Ud@h^2==7S-_A4W{^(XS9tW|<1Mhn z=38{WI`UcThxZ9({2Anv!)wmUm*1j$yz8%MQ{_W<>|CfV_<|IeoETH!&9><0cNFiu zw--dP@Xk08%~}oc4zm?~WDfA|9B9R^-gT!J8&&kt9^TK%J|5uZ zr!c_xm4gpHcG96d`2{}SMrvaI$XKMU9IRM`MD_*^K28R=Wi>{UJ{)mk?mrb3?UVt|m_h9>`bFwzr zdvA$JzbWw2^c$kBPb zb)W`GyIxqmg;axj0+L78Yv}7gpLX%Fj6+;)zZwQLgd)k4neVkh4Vq}pEoKBYD9pye ze6uYPULh^y^HC4G25EKAIyJgWBP+>q3b*F>Exm?4#0ve6B23cY8zib^AHq2KMaFtv z6jSAcuP^GaJb4Mf2C-~_W6lq#A~pUm-YgTvuR&=Vy=h04>A(N)^QO+nQfJE;iSdHt36QM^~l%}Qb6&5^__YYFgXKDc`~JR?4weH#7A?|F5Jr?Y9IQ?+o5ONjBcnhzvRIkb5>)?GbFe zbNDP}9 z?=EKkU(o+sQ|F^6ZVBOb;X;FCNr5-d>R&M^-Y=4BC9&`xk-I#%4dC7CcEe>ez+1up zhD9U5yVqjM01=5pRENh~xzC3plEQfmrT}k_b7j*L0PjU#9t*BEAi^F8UM*ExgpGHh zqKuzbAlUyW$Bi#PQQ91hjrYscu7`uSXsvDDdXy{+)*6J^cN& z1Qy=z)=e+=0KDHg1_o>bcpLRP%9BoS<#d^vZ<&upGzqSvr@})Kx4Ft5(&j{p&2Elw z0B=c2)p2cWB0Tp>oU>9M8*d-6gwFObX=I)p*Z-4P=9h+zx8Vw_P|tg`hqnjWhY?PG zot^oaF?9r3d~?Hb?lOG5xzgSn*cutbVNdnazMQ9`|34E`YB{ul{`-GbDt)L9A0QuZ zF{i+r^Vzch;H_!CV>uSy_ulus3Ilj=;H-|`2=JbM{H@;>;4Qo|IpD?TSVWQe!4vz)Rgk#tDqrU*&8kULMMb8l7y=EH^*5za4-TQG((;k2~8V9v-MK0pO?*9u! z69-Lb5bqAMk3yXM4mmt27E&O!E+Vi({$sanK;|1siyKixYI7L(FvygfD~%b3BPW5j_4pJ9un(jCizoUWf z!#I68T{*2eH*jil%5n;Ga&r9SnB*AZ=;nCHQNeMI;{wMCjwp`39PS);93~uVI21U< zICwc2pfAt}^b~pwRYAp2Hk1OzK>Hz2$Pu!DbRiW;0uq2&*k{<^vG=pLve&Ygvgfg% zVUJ}$$i9c&g?$sdKD#=*47(6J#5TwFk!_HzlkEXp8CyQvIkrT$2sVGV9c(siMr>Ma z@@yh(+^oM@r&!;xK4EQOy~|q2n#r2X8qFHS>cP5|)r?h#Rf$!cm5-H)WtwG_rH`eV zrG}-1C5Pn{%TbnK7B7}GgGuLrPa|dyIaBt-{pzOi@gG zncSJ|m`s?~FexyJG4cM_@&n_o|N8yEzoY%X0Ul;HrX@{&3P<-nje>5V>WID&1eKsF zh9~b9bRAXE&(F?4#i%+|-f|o&LRHkkxF)C&Rgul1!KXHd0k(OCpKjjEmRDiWYmsM>M0 zhz&|bm0QS)b5IJZTrHq>=p?GPFO3a>l2PS6_O=H~Le;ir7aQmVs+`if1fk=oa@@?T z0VSf!K~5?YNfnDib=4Dk~z#F(?{UmO5X)Lx)gh0R;p>QK&L|rt=AkM3rgY!%I*E zs!W0+S)p)L8N;!aP#CI=c)U%aP*iPrAvFLUM3uoc-Z&@(Rr(PVuc2U6!6qfG&;eBG zDZJVT?MIdFh+Gr24^```vM)hFsM3kIsDuJhwbqW|7qk~uYvfavpa4{9eTG#ae^jk* zV9SO4P^FpV76|#GN@MFFKjecdb>;0D&>mE&O^}NP^FS?QUMWBrR;^Y zL7u2m+Vti#v>R2596FmI4^*vu9UlnoLY4g0iPexhs^s=net~wPN_O|hIA{l|R`3nX zLT;#%?%%`?xuQy{G{*zljw;DWOFhU1RT5`sw?NLQS}sz&5!!~TW#8_dhMZ6(RwBX( zIigDRcyI&cfGUxFPkN!Ps9Gw`Vh`D)YRQkQRgfL3gxb6rAX`)krtRGW*`R9i-XlHG z7E~=#{r(cNMwI}oB0sblReX<)MxjlpBCWSW8&O4Co`kGWMOw{)EKvm}H))Ussz|*8 zWR5D*sXfRHRir~skSVH2XF?zoRFSsOA!AgLb{ruiRFUrfL58RzU6q11po(;}1TsJs z=^#F&PgV=(mLV8bq!)xBJyek%T!Gf3iu67Oq>C!jb$)0asz|q=Astka-XVt8qKfov zE3^hxq*pE>ZB&sS1%$LvMS4RGT8%2w*Nh-dRFOXZ0%@R%^sNj?9aW@H3qY$-MS6)H zQX?ycqWea>p-xm4rnWgj9jGdZKKCAKN7Xg$#)nWFs`7ultAJWjb)}QR25LdoDnoyOuu5usr7*)B8j6|SDR9zgn{u*jPRd#XMDD((bS>eP?=pm{yjrMCo z^{C2_jn;)8pz8eOMjhxrs?Oa!J_FUEDn0ImI)tDq&4!x;szudV<>24YJye~3H=hdC zpz72e;e4nXRjEmqE1@b>rEE8Dgep;WQe7txx{Io$X&)iz4ysNxmM()TP<1?KNjp@I zszl33{6*pxda5XUvI#ZlNl+tEU3GiK=5oKVLwlWVMp?g=iJ+=0?>qroimJ|_&0&x* zsyfzLhCoYD)y{Li4iZ9DYj3F{B#5e(;tQ3~VpKK9%n+bOsA@7&YlH+)^;qD#Cd5xx z3dP^e9z$K|&l)}{J%ad9_2}lW6%YYc4-Z|lgm_U^ZytCU;z88|p_j%GH>&Es=n^0< zR3TLciy=-_)uw&;4RN6Ao>MoN@S>_l*`gU@M^)7?f-=O0s>;V@IuI+W?k3ED7fMle zhxn`+Vn$WPIxs6?LRC5Irw)h_RkwQ{Ux646x$i>d+vM@RPWsJi;~>tgm9 zROR1U!N~p%RacIzf51MCs>>F!H`u?T>XKxM8~c}k_y1|X$72Bd|27nBkfd1+y2QT4 zMoa-~4U(IvLf^Ij$nYygXxr9sjU{#Ke7Wf8;*!1_?Q?`u#vVOoc!FJX9L>K@WEq`IQ~>y;jckXl;&@V>NSO@Gmj8^uHf$=)p#@O?J`_P z_d7_BiPZTxtvT)X^6v@KEfjc@rs*i&+$|sFvG6t+(PjDx@P3eO4B*Y!#kl_^z?>15n=KOf z;N>P&+3}(Hc(?9!xBl(D1(|KUlQ;MP|AKV%pUW4|e|tdpct^8bp~}a%{D-_vf1kJ9 zOo2CPAqB;|>~y>=7T)RJGtWc;-jB^qxk-437)nNL0C>;ohEHh(#36MIE8lK?7mD=0 z(D*}|oNQD2Xw(hxW;$d0Q#q9g-x2f(gzjSFt@A)S>M}UqQbmq?u}(48b1637y5g)G zHE8g7iw4=pdYt@tl!W=(n)u+?3i8}q$MEqsDLGkVvcVaS+2GBuLB-cwZ{@e$kJ@sN z?l(xQ2B`D#T&dLOL(0POmQ56RlU4>%yqDQnufW24&mQG-iU9A2M|&h}0N#oBX6KRs z-UT~sp;NALh^BPT=~I27NGWUX57O}#9{$H|;{fk@RWFXEfkaq8K#}o#C^p_}wgnz9 z*)5G2k>f-bpA=Spg*`c`Oo`RJcZK$<_bRfFYMlH+iwU22%@>Vjfd=X9#G*ahKn=1%od3TW|B<7Yn+VtHbXpA$V>d{$e%m?34}nkYkmEXid zTt}$#k!+Z|>u1cu5WAHEZ_;KTiudG~Q57t_`HtNtUI%!qE*6M(0(dtMUmkA=_X6N*tvj=!951v;ZU?#$@XDr<={KNZys|&WjY6Z_* zpmB96KbCyb!p2+RPq+K}YT6rORmeW@^4od#klCx-d~m7xtgR1(Kg3qu<&GF|@I@?y zRq~Xnd1CkY?{pp3{{{VjH>KZ8Hxl|wIz}+NMB!jfPE3b+ug`i-Nu~=OWrkF z{w@rA2ANUuh&wV;8j&E!`DYIYuIICEwn&HMN^2&ny5HIx@u_2Yx{b-uigwBsq@kQHF2NE!-eW?M}ar#I0lM$ z$>DG%EW9T^jeEBOyr<{6iyZ*oFE?}58v(qRoGE08Y>z_%Go5y)3WE=%y|{Zv58&O# zVw3w0G)UvgBD>6eiSUoE0~d*L*m!HkpI^N+S{gy)46Iff5XZ3bo>qx{XI)2o)mxeD zV+JQbyDIpi;wpZ4^tJJ_oVECP{|PzG`lx3!(h!>Q>i`vBZ(UqZUQPDlkCUI!w`bCG&V2B0!#j@K4XD6-Y^V^vuo;QJbNr9o zCH($B`ny@%O73pD$2fM7HgA48Fv4Fqie5#!;};fO^&m*)KQ3Gz^*~2-*uXXWoWMk6_S0J z;N+Luv5I4Ck^oP=_TK;gDt`Z8Jo=|b{jdv?B55NxK+O}oxjYgkt(NpZgS^U1l@GHfVbB04|^x|ctq{J ztmwQzh7@QI?^d!8E1dkUUpXeKrNal0FPjgssKUqlZB5{)znnLsJ8)u~zajn* zE6dtqySuEM?(v>&rp`y|&Zou4@)q#kMu9i!3_OZ=)VVwjEWDq_T|@!^-e*R4NNfjq zkMeuWegMl`>5)BgF{<&%-44V#s{J4$E_ydX04#4Expr9jMFhD2-&i^&kmd>V8Kx1= z`eEa3ZPY?w{3(SH$ZoEe~F)?2SA)>7ORTfxmjopgt)a6m^g8@n-l)rH`JOCSB@4@#g3a zQOCl2tD^B#6u|qNT&%7Oz=<8u?6) zYYsL2Q)YyHyyYCynRBe3_V6Ai`$)&h@0zg$->J>~@Wx+nt_b`O_TE}yf@lVW|Mk|5 zVb7L)m^P&Q>dlx%osS{SMHiEbau#OBF0=wRV}Ava7#2;j}F$nNJ3@V+I!xV!`4 zZS`Gb&De@~#Ev~>e!?IGF|zxiWdQJgPA*=>LFpbpUlf9x$Am-JGzngXBhmH|Zuliud#6^tD)cZ@;>K zKnCF52<4pE3Gn6^Fe8)$yl+p>9=@ayk8~-<2=6`=f*f*v9k~PGeQ>{{3m3q%R>s&dY`m=(Eo&KIqP-cU9NEVvocuKZSOsiz zBET=Lj%^+e!pEDhh25Y1#Y)&=u-SWYG!@mG>C~@HwU6n)dM~HW$MUH^S3Z<3EN{6| z;7xiO0>#^--hB-g-piKoBxnG<{TCS&?*MoU+;Kh;5AYWIso1qvEgqQ}yZ;Gk3_*^K z^XMN2c>h@(S>Fv-ZzTim&))U+g!PVa&wNqG#(V$xxzxUwQV1Hy^*G|A^HFTP-O933 zqxfhK@4aLn+i~(6cS^GN2OmghnZ=IlcyWP~%#=`sbp&ZE#0Pko1>}_rU@21YDD*6EL zwo<#P0j+qXRrV2am-sp!A=zjm7!8(aLAAAjQ3Sjm2-}C>}c8UKV#(@UOlcENZUV9?d zAX5L&|7$B7Rt=JsXbr#jyjWlRcVQtB)F8e6OuJdY3(^hiq<)VL#vyOKj6ZX34Mxf{ zcQcRg`2c@O*lY6&%pkiDY!ZCwmADc7v#;!q)RX^V>t&>7b$Z-`jea@;S*fl6` zrfqBR1no6Q^<*EJIQi9`N)k6==ZD*Q{8BDK_%+Dnb>Sc1JS({8NMvzg4HXxpl?)jR z5?|1N4Pv3z$1BOTe|L~}Q{YW{z6`~?a$bTJ3-8~lS^BL2@7vmYT0H^Y=T4n*;Q)C1 zJDcaP{t$;eh|+wxb8j&6#GGa96~H@|@muppfcL)nT$`*)PuQ|&#%g>X8}FQ6?v;;f zrI3x}INpu(hi%qk?;r^*f3rXMBkkdxN%p~wlb?>F>Bn<*;QqgxpO2{|KHk0&{1sm3 z-C$+AGtR==RO}$BNK3vn+e7~ik`;A6S{uKu`#t6eNkK_Bk zy}#pr|9YRp`9AM?KKJiA*LAMz+ShXZ`vqwmGTw{#@sW5>*o`ru@g97{!22HX_O{?0 zB>>(ExFj44;N8B8OYh3B5crAA!H6pp=-~B6Qr}#D|g)?LekZW zN5Vd!^JaaYb@C(Ny%~wq5uGurUyshab>#3LHY)7i%t#$g82Rni9mLfH<00WhdZN5M zHt*$QW&?*=wBh3S`}X3Bv3cv-)JVUB;Mvd z)%0k*jlW#_H4J#CL1}>_X+t2nMBC`_cv?lXXw0b)qWk81Dg|$NE{(<)oUI$blx#vSp!6WQeXGBM(VhP zk>8Z-y+3M?IU$bFjq`MB*t|byGier!YQqOb(^T?`v9GtlsT+BUZR@6a-Z(4D>Uc4s zZuTjCY5qS!#(VL`R1)unsVj77ym>6rJ7)mz-zj=BHh}k;(qD9o-`>)FZCURi5DG`c ze<;cB_JChiM+Gk~PA1nn*$jfkNlmif>dGP_6s{zlZvO_Iw+x%h$k#>@I0A|Ly`DdT zmmi(C;9Z^@wX@X6TN0^bEk=HU&lwM~GT|Ykm+#_@jIentykGH>NB#)x9Z)AIq=n5} z?yl#YgW^`2=Pi;%SsnE;2RRNz{dfNV|KU_m`TuJ$|2vTNpv60*Nj>O^oaS=09u(=g zYSaz%pnDfY#vMQpYPm7~VV4s4{$Hx|K8cJFI6R20B%#m)c3I!eTnu{9?cC?K%HR=e zYt{SsbQTdB4|ZqUK!<(?>AcjrRcz%V@E8*3C==)S=U;vx-7sX4F!PD}dXO(tM=eHv zC(ay@l5fRBTuuX@w!dUi!}V_2_kFdq%+q zsd~nN)!ol&{t=5?M`0cJxH+%?J>FtR#(VKre-dx`m;qKa-h~Gx-^2jk8MRN9?E!B$ z9-nM&aDp_rT;j@>2jCZ^YSv|^FL=OG`l`D>1Ky9N^jkiG738Be*Pc515h3Q8Nw(Z9 zbl#B-2{OxzL|{_fK<{qexsT{?Z%c&2R_K19KHecn9d|MEbGE$iYovvTer_BUmmkFD z9g`BK_QLldB*e&kbW#L+{(qe7k?)hZpXN768-pmT!+El+>t^86{C|>+_u^+NNW7cR zl(3-j9%y;0o(6c^n{iv)0p1xZ6So<`fV7?NhT2qZ2+aJeJzl}u1K!Ux6S=rK@m3D@ z>jk_A5`;%jc@UwG0v|SPj6vre5s^Ezr9uS$gv5EPd3o$acZZ zfII%ay|pFdz4+Y~5^piB;ALpM4|rGR6ae0)IyGS@0dGRL%F5q>w^SMZMaA|ISRwdg zKR@IFkJ^M7dPW}PZ+88Hp2c%c$g1fbJA}iY{|U?a6%354z7(HMpyf`W~?sNF9Y3`Nd{; zc3QG>K|Qago65bgAF-{^yf}mtT;Pijc2C}##6BSX_Uy6YF>c!5Al1K0SshiyEh*cA zmR69b$#^e*N{z%j$$JGJjdxnqrVUDfcYnT};c39zf&}U*lV*Q79Mtt&c zrTO{apGAS9Iz}FKYO>`oz20&n9%jOoHQarI(+YI)P2!;8@i{N zq&yUXNpY{sflAoXR&W-p11d!0E+7P>YTwS60yYFk&O4^$1X{{JI0GvqVYbU znj&-<@UDg(Z#n|r%Tn`8gaPl>28Po6PKCfT_l%}N=Y`|zk2*O6-eyw0Ed_x0yV%qx zu7`U z{*?@C(0EU6`+DvN;GIw-ec2W87GyhXn+SMEWva%6#0A4obsJ8NdU?XL#fdeAfOl&R zUCSKct$%&jKwkJz(a?aWQkRquz4TpaF##X=m4MNV5k;ciG9UR>{+(R!%~AZ&s%jfWp(H? z$gVniW$E>nD;aO)PvQ+E-g&vLtI&9>*H0u=_KB{giIbZ-rpkF8#n;(13ou8&j8-z(8$dv zfH!k};I@|y!LXI;N9AqDJ>f7PhQQB&ccZ@Y;0?eVI>NwwL7WJ^uY(2q_M!8Z=~ln_ zHctd5#U)hNGgSMc^R7@`w!Wy9`gn^Yb==3uPt!M&?X@!=dUk=Sky8b`dl$Sb-Y@>t z0ai}ZNo)_LVE!Mn<~ykHhUU9B?$HU#>d?>_Ui^VHSbLu#(i-uJ~~ zJ~D#aTYdBU3tHIG7bnwALE*KPBCrn<$K_oDmH*3+6Jd|@n(9>edTSi1qZ}i@`uzMI zr}yHa@#9jvc?j6NSFyQ0U8t~zYgP)s`A~zs_lEmsq>@_sjpq0Nag4?k)!`KI-RVu< zfAc@)Ohyd>pa*%A^`L!F@IO6>l)go8S zd2SX6hL3$*GxFBj6F&Dv`#cPK5PWWQ=o{!kS$6i%zjG0xmvEr@ZzB35b{M}0|I%Cp zZbITbq}{~xFQGqTuQI&!Iqpq;kJw(Mj!PK%xsBUYrRH)%Rcrd2^|F?!VbO4;+hEk^ zEC=U#=q-zM#$G|*5bsqN8rn|50LNSGYJPoDL+1@ui8p*YCIY`k;y%1_uC;PN=l$Tzc#60`_3_?;)Nv0ZKaTYs zcalaqA@}$PE47NSdG~IeN`0j#2cPrxGv%P99c$6b##QZ&*0#<_RAi zsOWwPcpE$s4Qv6txewO3dl?WR<82Z%2KDH?C8R!xC)ta@2a!1DiuLPwM$vgk!!lMK z;nc@l0I4GkBfqET_=?5vazc+?6aCyy3b{D_!Fp)cN9{G21b7Dsz>`*{NjY}C*=h*_G9xlU)SoxL1ze^ zvFgcmP{uyJmH2$L%R_A^&7c1ttfj0Dy?Y6s6&IEkCmv+H)qF?$NZmX1lpP-$?~VIb z_Pz$ZFRu8h;0}0iety63CE#re_XgED1;aWn(y&B?C;T~#&vWtZt<9dKqE^8BHuG|W zilanGYpU@3=YRQeqMh?ctI~_$?kyxv&`nl7a2B2Smi5Z}wKA!X_i>~SDUAFQ+98h& z4Lo!~Uiab8QEc7{F{WpWe;kD7vx*NSv16~jalTtd0)KYW{`{{+VI6N5u8D!g$$#hn zv8FgG_&b>Y&y)3_{fa-PNj)fUjf5y#4{G0#^vo3WpvnQx6kpJTVtWE6et{nJeded4 zmQpa>D$1Qzx)$`HV;L<6z!{`Gh8O8`;0zKz`cL_Tb|SPT#a`>ER`d;07v3(mjnApC2gMhv)tu_b4LXrnlIb}WJM{YX!&44#=fxp3a@Q7_5TCL~O z2+se1c&Ps2DmrhuUo4Zg1tKsD64#^4-!NZ>&O5+sdlx4a?jT7Zb@*cBC%om9z0wdK z;*@Rv^6(5c?~60q!FjC5q2qxkZRmBdc^{r)7u^zGLGuGr!B5KSkUJv%dm?#>w;vgA ztq#TSB;J-&PlVBU9~Z6p;|h2W+?t#92E2XGi57PP-btmypNxcqVejn+-OKiP!V>M# z57+>2`@NL}7r2P9lKufFkthcwTd z;yNS+YUBQ1Z{bVETk}@!Kl}eH`a*@!cv~D#T6+=juFJ5HT;#pG!YQx_@W#=+{Y2aA*KJ(1skMx*l#zt?+%;%mrif_knz@V@na%&Z`~Eg1<`mHh|UQ{1KuH) zAtqD?x4Q0?~BrHiK}IZ(8%$8{hO)iueWyQ zUM_oNDgqB9afPFe8_S-c&;LD}O6-cOrn8Yo*Y7(6DbK12^bFx9-N@@&`R=jHAxg5*&~|wO7mKMtU%OPq~!%uE+!a z4IS4H1uMwtPx>9#!2GXr`5_(;K9Ig~&Rajk5B(7NPAkWa3xKyuCTBzz;Jwh$&=CNR*mZ6SW!P~7owwef zj5@(su>X(5CC^?K%JxO){rm-st8)?cJ!1DFbv(n!&vKS^!$Kq;a>EDOac;oo%|*Z3 zH%7}GQr!((POxF~)_*KkzrFVX&GR0DDXSxel@N0#c8NDV8E^fjKn@b`jI$5K(RdHC zz1S-YcpFWwXIjC5Nv#;F%@6d-oQY!)PAH;3Y zj%!57l69}`Hw$#$n+$hvf|5kw!$_Qx%E_KR-srqTBwE^(%BhdH2vSD?Mt*V=Dt)G} z@ldQIPl|ywHt(YH!RD@A=8%iwh)L^13Jyr;F%jeNWi-zlcbCFC_)b@CSvuYlLr2D2 zFZ*0FiMRJ?gcus{o4ql&l>l!k<|^nM;Qfw8&utdW|6XkC{e1L;VH{_~3A%X?m_Lcf z@(kepk&QjR4)BKG9IOlFw1wDTKdjS`vqk-wFt|fdLONRnW zms~yd@g7C$c#V;t#Ls9i=2ScsJ!PU?se#Q~jbm4+z3p;X&vox!F@5aoEpejS6AC+N z|AI6eJ!N&wY<#in08`N7;si&=Ti2E~h{QYV%7Kk&yem1XtF-~|yPK_?`~Yvol#-uw zi@af@n1Fr3@b%gES7+Hh;ay!-NsGMCRyd_E@;1CJ>eBq32z{y$W2hTN@7`Cg#8fM1 zioo4SoTK01aOyI2-V#wgtS6pQAMY@v4iSv}mUA^{MH9K8&gTuWtIe=^`#$L9WlA{; znLLwiin@o*`{|E#qu{pvG~d0so>5ju&V6&(-tX#v`~TR}_y79{(1TdXdXTBO$Ul$R zJ@lMg(0b5w4@tF`9bo={7MB2s>ezbo+5BC66fl=VNTB-eFeE7qD=E2RNBx5x=h|+X ze+P*(d`DRwb%GAke^-z!WV}s&CbN(pu?+3+Wzl#S3rpVa0=&7k^;-e}Z{tisQBClO zHUFIQlzRxAAk7{a5)bo$CsUp8&;j0E(QDT~2fTN?N6t^ZB0_2sQSH_A=qpJ7UD8#B zej+d_PM;@{M}P(W5sRxn)9@^b`gnUGbztSE`ZD`&l`0oxlf-YL)Q`K#}??tS%vZ6#PiHlAS+ zh1!Ua`?2!Xzh}_9_pVQE6ITO8U>79rNZU}*9XfR0_thfDlx|TU?=46jSotN}OkESa z#042_{~hK&j?G&(wd67LkyB6{$G5961z&IRjnS*xTlbXac`K%CQ&h*wY{E$Sr6u0X zWW0@{haE}0A8`3eqwx+3(rB9oyf--sDP07-uOwWSA%fRiR^u8*cfs%fWxtE``^9*` z=M{FD-37eIUn&z10p2sGh}Lp_L}-Rbc6rG%^zL1;uHl0f*qoR|;sVU+;xoC>d8=x7 zf2ho-KHf!09V!_4+2x+i-qgbd?TFwsbo!0Wn@jcJ6=qapYZE5|rrQt z-UF`utjrI8uZZ#4)W@3-se=_Gzp_gwpEZGx6Fpvke7QF}_WW;ttkbX( zZwT$XT=DSf2JHDi6;t~j<@`G{vT_Kqk_MK`F|x@53=M7 z_9XQn$rP3yXg#Qjv$!`BJYp}7dbx*!9#k9h$m-1wd9_DUN;BmX!SJiv`lrmT9xxk= z>0mt=kQ|R1tNZ!&LMfKjCg-aNP+Wh2tn3B!Gf0jaHk_Nj3d0FV9KYzk>`_njGe{>_ zcx1}rsILbRkUFsPvy!^=Y@h`X4V`XYF7J;0h=sTPq^9h!7I{?7j^$atH79%v)+PCMMP4UMoP zp!2I@g_&Sj>XUM_+Y=A??Ck5;cK~mzTW9y@0p9E7uGdAg5ur2dvTAIY&>yiI_J93k z`b`*iMdI?;TjdN+q4Pe?&t2k9Pkp@CA$4HoCzI^G>O?di>c2RAsP`&1Z`FOr_uIa- zh2}U9`#pL>!4*6DtxDIEi8TL+#R*VW$0?mFQOZkSkd9eS#`{R4g&~PIziFyG8t->c zBbBlN@7AI2kzl~P@55G@4ZOWg$-BHye=Zm{_R)2K?s~wY5d%3vfcJfyc;QjN`+`H< zOxOYeTJ;F-T=f+7+#IUy^AT2t^9z_n@v^D&XAefUmc< z5=Vrb0dIq#eKVZk?d`aDIqQ*G0`yhy&83WXblzHKGkPYo!tf{(C#RZXrQM9qo4)qy zh#Uv?@!pNpftBB@Yj?ZfB;g^mf^C}hh1k3|6z|jU$hUx!?~1=2y+y(NPnQ$k%})Eg zal~wj>UdPv-}~a$((5fYGTw&`R?3rje-u#OipJY7WwiJS;GMei*@+;)`)i!b=}5r) zn&_NG_n%;x?a!pEOMnL~?xk_}5a3;7#KNKsc!%#Ec#(LC2)W8WJd_!OzBu7EklQ)w zAp*N0aWe<|;ggBz^M8iJ!h(A&_3`FJ>d3^%FA$tZR@lM?o&SA%i%1PN?-7?tMP+6u zD0p3wV%{z6-~Ycg>!TOn*hcef@4DU|it2d2BJouVczgTb{7(h*Jyr@}{^us^LDt-H z@L~^=0$1#G2@`N=J*fS8@Gf1@gW?okD@1}GR9K@qL=OfeV@>F-?4@A1`_7SyJ@Ov# zUNPba?NcL=$A_)l#lF2zH-GspRc!)9n27k<*=&P)#4c~Y(=^9pVb~stORH`gzW&4u z^`85dRSUAWUvi=T`(gdZ@PF#>w~#uTG4lH%kg-|kC?1ke4e8S1#O^`UJCBC?`dUL) zF|S+fjj`wd0~c9ft`Aaxx6zz{#wWl#lsRL# zQH=l<9-eoTC`IRec3HXD_gZ1N1c@66JQTh14mxk;O4E$aH`K@58L2}NBflxf+1_2b zcxZ0>u1_b|WAkPo8XFHhYYn;3E#wYwtw#N?{XhS;EkBaZTe^kjdE=tYD67Ld3= zueb1IypLt)gMWp?EnbjzIVElv8t-LJCOrheJITGPJRI;|RsUed5b%yP|5B_`77Pns zJ6ZG0+XG%#_kf!N@a}0Ze#imlf5qP~zP@WDKo4gISAQ);ACP$NLXkULgyBjg?n!@N zf=M#^fb@BTO2&hJ>f^l}sbc^mKe23sr}{2<$gbzyV~gF`yagQPYU1L}A?c*IF4|%g z3`k!mdt_XyXrDLh6h(F9-7}f_nX%NpImvh*_1u_9;;pNCTmg;up#EHn3*bE;Zu_O1!D9&8PU4dZl;k@|Rk+>TB{vHP#^a1JT<-`0r->HvxI8w(CjQn=M#;<*~xS-S>QY8#T zY~IJTGS+*)Fo)PpU$q17*ja@AD?APryfB#>x3}tl)4_D-C_$>bZKZb*hx0Mb{ zGl}=e!nU1gypMN=6rKmXzp}e4F7h_APhL|Ac(dpHdR#Id4BvX3W**q>0l)dgz5D~< z9e#?^Mep90aS{HqRJb{z ziqv6&k>Bp%aN`pXDj_{x6^h@sjl*J0`P&#U8Xc|EKLg#EjO1>i90su!9~XuF*Lb1$vOJ z>di+Upa*epc);ZOE(rFo5HX(CaECK`&zs!6Ho+py9Zfqjp8; z15#MxS=U2>!tfXp*Wb}|$~XaiKw_GXW0#1fzDH~jQU@bOe!I4&*V)c+LTNc=6))15 z)Udz^oxdU$7+?$qgvYG7)`s1KM4Ip)wT>_-V*UG4``^R8xhbmSy@#h;)!$d_Ysh%p zw#BR`@eU0VV?yIC>{rvv3wUn}sNTBByLV#dD*^B}E|d0Y{1pVhBV^Z1JGsLZ-;ap| z0^SpBl36DJZ`a3@y{MSC8lDSTO zyycNP_%QN2c<#r+Kvg`H@};un!EJ2b!aXcUAD%OYtk0Jj@*Ky0y@hL*f97dCyNlZS zV&=C_k+M2mTs|N_kX}v3o0zp~X+T=+-dh?c8PIrVDk#-%1iVAN=v^-Z-cW8c&imJ|i>(`TsE_vmQpXHNew@seje|Hmw7(~2gAqCs zbgMe()Ms|=?tS|g1JUD-6V1>6mz^gFl+fn%)tD%%M|b)=w!H@4tRfZ zmauVSCqTxvN4RGl(RqhgKW^a55{Au@xIZ7y45}YP=RGLZwauQEYsKb$PHSefO1K8(>gxEhO0@?2?d^$d58nGxG|wA%HHES|Rt?+{`TO>k zhm5z4O4uI~?_$QwbZES2N>(h&SZ*e|6(>>ee)tb`h987(K;k+S%&b_NW zV4F2@u3CV%-<4LcGQj(g+}VNcR^ap&v#Pi4JUZ`jLwYHx2g2|=B<|jswx7Kt=)A2C znhHiVP#^DMqz(&={32LFzn1gjA=#(aPw~I8d0R+~a4Yhu!`sG^Kd9AUcW<1$wU33{bIr-b|K@+p#U3>TfcbwtSr2mhx%DTh2X(L2T8`F(%vHInn%>-2 ztJ<(RJ{I&Kq6+8OcJPROFyVb8Pbmm4+2ocb+297}S4&NlIgUV1c}>Rd-o4PO>*~FH zKM0Uc_}m98N%U9jC;Vpj<=hp94i<2 zq}P%0c5H5NCh^YB?J@0o0!iP&7r?y7d;f4yAvF5`GUlWnCdZ!y+-F9 zVO8jD+)91Cg^)VJF!HMs+~6XSkB8FyXJT3pWAl!b)VCTQJ_B*Ni))%lWBD%vR51^L+8zPBegSSfckh>A$8y}^0U43*1Y#CC-gnd5Wm?Ln>Tm$ z$1APWu=$4EyYIk&q_abSsT1(- zE8Tcv+j|0(di2coU+>U)JM{6^Ul|mJGm$vv!$n8V*yeRYA;piLhC`dif-~nfgaQ}wQqd_ z=s`Keg7L@T9i)|&PJU@cAS}=X*J)Y0!K-+`^0zsSKyNg+NauNh4bpE}d=*0kNRQEd z%-;Zg{`U+U|GmdX7&b)W&ZUevxhzLNVt1&0OmxDP`g)KvQpZ7z{PJvmweIHRf_8ns zWYtv5sD|-R4QC_W^vN&J8fsxKWKwy8{fNam-#84j$eA#k; z>f`+#sUrv@zwrtB%6@G;ByKmwN%s+(x0{2n=IaS-sBKCxD02<={Qpzm#8Arh9?kQf zSx#9U!zOg0m%Nwee<3p7E)k>utRN+tx;W5yn^qRx&IY`K~4b)&2jVr$tXP~Jv=}d zK7_=zf4?U1wgR2ET80Syk*n0lTMwy286&^D!;_<8p_~w3HEzTB7&hsKiSJXz zfVc8}bGk*|wIerIvVr-(RcuFA4lW1|zaDCplm_13a@?uY1ia(F^EpKT-Y@5G&#nYN zZwdBXr`7l`ysvcZk}CqoTOyG-hFUM@>?(BLu~MJxPvub`??|MMXpH>Eif6uXz2<~u zY%9bQnXm_>Bd5&vyt8+OrZ<%|l}uxAkd~QWnPS)&PxAxPJKtD}>R`C3Xmj}Qj}ryR zcstABCrG>rq32eh@mBs)?N$YN8?~wHTwPpyCs;)b0^TcaH~i*X7XlJe-c7sP$ z_xa!eZ@IN$Q44@~#_DZW>+=bac=#HvKX=f(w^{OsZmwIxunZD6wnH~}Z6G@DpQ3LD z*-EI7w=q)3I7WWzgMD8iK0IVNo?O+o3Y+)cS$^}kfVY=u_zJ~D3g-XIX}=E)-K2Tm zI5!IG=)QSN_P_ZbYlNeYzk~T-oU8|V_nY~XdeG&k+j-G?(D>Kr$A+K>ZG5#WCJFSQ z7IQj_MzDg^6v%U`iwlHDH_CsqD|3ab#qw&eo*sdM>!t2FdiFw$30#DdeME@AtTN!? zcJwQDS7o{nozxJ9*CKKIV_ZBqThZr#nWXWGq(ju#gO($8NMhtyMYrz7fmSX^T0HJ@ zt`YVMvfcPy<)wZb$mKM5!?Wwy7o;=${Mu%iMf(GiN(5zf*zLYrWC_k70p4O{yw8@n zf`9e*=PfLs8P=fjuG@63!V2(aWxU;Y4e+ktEU>#8@GhKIc>W|I5Vm-!lOz4X6`pg5 z^|A%LhkpOu{{ZlQTh@K+$2KCgY<1V<9(HuzKE@?)j|1MUNF3kP^%kK!=)A)o-SOe1 zLf)=O9YGlR^{t%?eZj*GWg70EY9wOwu4kwBSl?{}jpli=%&y1gjT;(iN|-LC{Q>DK zg>^Uu=_Jt=Y z5Wc1J@lYA78{Bh2XNt#%AFG+$;Y@ul$h!8)@8`kTyyg6o9yIJb05yMc zDSq<^`}LMYV|(@S0a+#LSTg+2vuLWPtd14_?h8%Qi>3^H#mG z*U|Sh_3ez*mpRemxv8pCK#OyqEJGKa$x4huCpVnaSEn)gF{Y^`3-oXjPw4Zt6 zG`~0r|3XfW`?|=T7{J;5s2?iu-vL58$88=1hK?ye`1<-nsWcXbC8qk9d z^Bx_)0eaA(v!!AMpa;zj4dxbv1;YLO-0zaVxxf-v?f-~6k3e&~jOQ+R^g@B`xati_ z;1{HIPaNMkqW2(K7exuV1|fI>iK~2g|IqJm=j|`V&xRZ&wNPZ|w8`-_HNo&2!*2&G(@BQp)ORGqUyM z2wqx2ZX)A-{{HiS9$(_e2+*=0||oAPKKCvgo`IpURMFZ4!c)BXJ889Neq_ z<$!dQqu5AE2leqbK| zkk!1ayK9{fLcOK+e~NBnZ;*PGCUqW^+e7p7zhNb1bquu4Npbu=|1U|#+wZ`eF%oYF zhFkn-yk$JYM3n$<-iLIbuLIr-7ABSrfVbw(x1v2!fv}roNB)SOD@=T$ZCeL;s~H*L z1;N|fUY2cw;%)>emrY0OAu~Gf(x>}$H+2ZXc}U#jO@70<*U)*lH+E&E^-&-1+ejTP z82MG@vkuOMa6#ASwbnZFVe@8@Znn1~9)zSXoY{O*nt~0|eY2dZS9a+3R z$nXCp$awqmiwu)^?=C0uq4DOKSocZ;@P4(m7h2@aGd$|n1bFYV_U0A58VKVI)f>y= zU19MOkHmDq`|`TS4^05?>!u4$Ek}var_G;NymLn1oKRlb)^J@@7$(IXu4DH6%!vMZ z%XJC#JT`}^Z~m7<>fpu5&*HGj$HZtZNJFUOA{@BBa36h{Sr2lM|{vK|!N+Ez;HLE<-rMA3SXOG$K1 z*K4qXl(61=6ZD{Kf;#*6ZXu;h=S)fcMikPUdZv;PsYq zUKVee3tVaS@&F$2uFDRwn*+S}ZoY2mrAL6=uWe=@Wk=_|Y{61y{IU@2fy8laeN}q* zB0BH>Tl9rb5~+{({QTcKdNA@^VOAhzI**4=T$Ri|cmbPt&g!1#{AN3-{Nx7tbDt?# zL9Wc+Zu^ix^Sp746xLxnR8(0%70h%Opo(7kG74C{r_dy%o!~Cep#Z7h36m?&?4R0a|yF1MPz<{)K_hGF?-mBE21UG>JiC!hhJKQr67T2$|+TG{^7jCO}b_Kj2uT0gZ z1FyGMH-#kg-y=Ym>qMF+3eb7G?3b3$EE0mFk+=#UzXmZ;bly383c^AwsgJikQbz_x zery5P&z`x%1-+>$m=~_V=B=lh%(Hdc3Tij8iH02;G4KCNI@;B?U+5^!&;L>)l+__R zSC$!cacOfxhK%>c6}O5=yeDfc1<`m{6+h}^2fR}ZzTQXyynV**cBKK{AK7j_5(^E4 zOF8d;+}Ys*@BYEZvK#Q$C7f+A0=(6~KlbD=CqS(hPfTAFq4PeL+fY;o_TJi%xLZZL zM=Ye#c{9My#lf$skGC08$HL=(&+kX8ui7E7IFT(k*(}+F&709aaplcfD`;i-!1>As z?7cT!bd<)7s~PQg?~jz#QL9g%zU=;g^FI|#_t+_b`F{sl4~l$N_|FCD&-hnMq4glq zKU0$FULaeb z&=%$$na?D^6+7#sCuWzU_aMmf?2|PLLU0NaCzBc-&To%CAPo+uaEPfB zF*LouWEUPX6-mkp`bMvY^$#xWCcI7KfEnaEZkTj;5_<{FDN~+vLQTzI4F*i@^y;7rS)n#l$Os_qVE}h4j4Oc#EITa5m1?hjTNF0s#ovMY^<$(7g_SH&@ zybX?MJ0AnQXB<5rToen0_q48@xbwyZ4i(ZNHUZvMwXCb_0q=g6^z{zQ2@u1CyGwT! zI`4~C#hX(P3c;kfxmO!>R5qdWe${2jwekq{@%BRMz{+p>=In0neRv4oX{u=K%riTtFHVD@5vO{F#5O<9D>AYtQ3E6b~8HfZTPouEbOU|_Xtu4R(@VL zlUFmx;vsi?cE6Qdv3ave(0zHMYY2H=+Ug%yPr?2FM;5#z9yHQCZ`=V2>oDIHCGq#| ztsEKeP`b2>B;Ft40~^tJ7ZZY3wF2I^TR(hV+hE6c(>rJw*1inueSmPk2B`F zz)TZ;KQ92@NtK!!>R@vshEDmRuonR;Q+RI@dy|4L*%=t>!H7O4kSTw~vY)`NcOu5xhz zJ;)>eT}?LVL3}}kuyJ{LHPeVv@m2i+umZ1F_&pm}*gvgq`ZSpT;|VP9OTg-v1>Et%b+iuRCoU07^#C7BfkX0 z%Q==!oKUdc`t%fUdNnK?wxe^79qM|}`)Oa5_8-_Q$mSY_$I*XifByH{Oj#W}l*cr5 z|9(MAk&JiDrTvm5-gPH>Wzl%EK2mD_$ zHZ^pGS!bQCT>ossl@2CiCE-L)_nHRzza+E-d@1Eoh?$X|}z&xBMyv^S{^( z>jMQ-+FwCVO;c7!?9tGze^-#Z$aqIv?t4b!-8Xhe290<2Y>(Xqz+0_}$2SY`)=%E- zwHffPRX%ch%l7~{+F~eUNZA!Wy^`(uDZm@w!PWT~@a}cKRg$9wz93b(X<*J6eFeET za&_iTMj@CRiK|jC-N%`R&Rar+!@Zl0`c{xUNF5t7@)K$iH@o(p6FN5RbK2=XHt+an z>{eg&Z6V(f)|eli6zm{<6nM&*(NFuldnv19wu9+$a{ki%uRz8-N>1?>i8rsak2D%@ ztw_h1NWeQT_U7wMz&jJ?rey+n=j?g6^}=)jT+m@El(E4T{yD5sa}4mlJylZm3h-vL zmR}eJyty5}E__8;iy!G~SB)Pu3>@-jiSU$S(3eV|nh$MZi0AMxoA~E)cGE;jb}g za)mk8T^rN@ycZOH7X1OdV{Q!(+}%Tf%EQ@8=ylL}i{LzsG-QR~2S{98xk8e0DthgF|FLVBcA)hjqi^bGwu2s& zB}4d-2YOIfSfoHZ=s~AX?BH8D9{|URj5Gtnz;c5SL`rqbsK&VZ=-qM zitQgLs^gnmfl2!1CEluJyyFd*vyyoCf4M1-#@o?J;Fk{IE!iu4D;MzAwR$`04|v-r z4jami1;AeEQZK#)xWe~;J`BDDc*hT$b_4_7%xn)%2I2`&@n~`2slDjD?GFr>r5+Q6 z?;>#}>dts~Z*<=3x6_V?mQWvWE2NIy82NSGK6%<{85fivuy=xeCpPb)Z_tAu(W;Qn zaUa#wRTQis54~k{Jk?3_ym9&z)=^~>n)vs6OBFKSaWWqBB;H4FosmQ1Eo-J%YXW%d z&~IW~4 zx3{VA-CHo=eRz;T)q|4&)mnRsg^HthZ`DI9tlk$0!c|DzuQ#eQFHfTL{+dF+{8tzC z@!pEmF^rMlyimeO?<`_2b>&p`_>o4qwx~;BE?V(`)_xHJy!~Ny|gZZDE zvO28PbC2B4{%`)r(Zc_L`F|f-4@$Z1J-FC|Hhq*N+RItv(0Wi6CEo}hvGL{`2#&i0;Q|Hg7qZ|6sVaTVtyf(~pmcxBuIJ9ZPzztdrNLzc$fhpZ zwIdY02VF1~`KkLt06vDqg-sSZ*d?R)poBKAE2{R?*Mq!}I^r?%ON<#@^;Q-S$)yz+ z`$y5KVbN)vUt5~F`v`P2b28_0Ed@JBPIcEVH`vqu3i2Ffbv)MM`V?EZG$8FI<9)-& zHktH@&3IR@h{oISUim3@z#rGad;@rgn!2+)YzOE61^itVR9xY#-MPu3 zfcM$WX^(mUZ*@ln3!8Bp=ts%Lf+<6E-Yj8awzk~@@HZsxwf@_ntxo8?@9Dh^t9GG2 z-V33B>nOy?@3(Jpa_}S`dK&YUn>inwx51?k?#UPIq4f&2CBYNeyd!C zft1zp>Gjygw|_54-$TYbd9T|x67L^PS9hWDme{!c%__jV8s2^THsIY}9^%ytc$s^rD*Zu^*YHZ%J=grJaV(cLf zfzf`?TiElze`KdktJW8q=Zy=Ytd51%KWpJzOWj+YjQ4dhe`OMH%gY1>G~PFc1k{88 z?*Qp)?nU0B32QD50p0~_H{PsU69`KYBZ`;1xWYZ<5h_Z6x03g(s~F9jU_;BR{y}-46~J4{cZdcp~s8HgBA{)wOkPZqRed6KA{xDL9bGHsd`d(h(izYuK6jMjr#PJMXrq8)sL zgwe325cD9~KF9s1!8=Ii+vR1eoC4v4(u&M$)m&ijFG2TDgGa1XZLSL|=t27R0aq3} zY@n~oSGsIY|4R>wxFnyjO#uFa#Hm!2H9q^70cpSX7pao9)YpSNkveoR^0PJ)F$p|? zhpukWirlgsy9dSI6O%12wub5DFQp2wVLxJVceXQI+m6$I4;rVij*uYt4Sx?vYm@O# zcNNzq@m}pD#DvD1L7B0n1Mm(dY*$(2&9s~2Z64rVGH~~qhixDnY=9fHv2%e>rsXC^ z0^Xtq59vF>{6FzzwqVaT0wmO4xkaA?{fga{uR{u79T0#8kT_zY)JZR7G zNl_o~Wk?-cG4e~9wEfo4jfcK@)8%BUVDpwromd~oOMqV}EktS2W8WZ!v#>psHS16N z15y@cb$sC)mNJf6T0v@&@xG<>(3QmdUgj7B8gCV~>Zv}!+c@D@=3T(MEpzJU;;**^ z<{nBF9}R@{Z?-8vy5<7!Oc`{Ld)*3iA51TTUw!sgL({q>dzv{FaUBRV49hgl^Zt6yh@v{e4etMTzqGVLs!7KCCih-`5^rPmT6#3z zH?oWkzXINqI)_#)^4@tUd%X@AkTi1EcOZ9ic~kytR-zK4IjioWm45 zAc}{kzm9KyX^qX>K1)&e>uqDmRi@?4coz2gf83Pl5Bg)1G|wA%b0bA{@K<#j#Q%N0 zr9s9!wd+nFiT5VK7&QKVSPkK%BBh@)PwENTW{ain6-g!UV>2Av(f!J@nwJN0Gddu5o`leag zM`@n71&aYib;yOgxo`zv{qOugm5liRng*Ev4aj;>Ud#(KQV+T;puHTe2jR0nze@%^ zNN3%%^kUG1CN8wu^@A0p)!sPUW#9`^*-D?@rZS&_uX&#R&IWo=LsEHg37G#+sI>|8 zrQ1OBuP;G*2hn?woV=8lPV9Pk4vCvSHFVZT1-%EA(!VX~i{hZV-~Vqy>L|v@&vVz@ zD&lEQD8K7z*waK$cb zSvRYT@)Ck7iP$y~94y3St671@B!doavr`{Ba%@H-?9ic+&X zyc(UiWwWaEngZ(M-GkI|1S3C5j!7}WVoqq<`pHOQ4mR&K3PsulPfg)Nsn1?+aKe7Q zrEuccwWGQ9G|zjR31xM>+9uGm_wV%f@EUl>pX zc$aAAmlpuuC*E$B_qrGe=cxV^X7@P*_s!pYwGr^{?;u)|zgX6Ivr0GCNs@ z&Aa8O#Pg0uQ}`m0J^EKO1s9|pzcJ#qyM^X?qcjjCW=W&XCl-k0k{xL*vc+^yG~i!2502QNki`!B{IrWxzX{d+2eSYancH zpgE|!&IN`$G#(fM-iE^oW(t6JZ0=z6o}V_*_jAngS^x5Ri(_-%DwYBQ@F)`Z$@Obr z-@kl&i=oi8&V-Zt=6^G!4myndmc80jInIuUc4fiG3MR36ONMuU|6XJb_Zb^+(on-* zd)J?v z4?4TBmYd0j0Nwiilz!?d`Ua_DO(*Ns`t@)M5?8vFc#}U4eSm3TDX)4SGHcmUpo4yQZrFAhk|;~VF|EB4Y$UO_jy z1L66)>a)kxonaqkmvb_JH($xKKu^GXf7PE81%}{)w1Hy0;-2?}E*5|9N}sdjA~<8t?UV2AuwY zca*f3{vz+6{mtJm0p6}W+3j`}fw02q6()+o&amzlZ900u`+kL5#}mN2?&g{dbz=h5 z^*%aE_!2sAL?2N*=!NA#QPu_@7vQ_ z^`!1Ste(9RjkoEebDm*<_mGi)Z3*B#oOk2RcQ7DDaGlz(5d-G`yYyC1JDlP33Bt*X zyq`|{y{!hk&z&&Zc+i>v?d6P?-I0XO+gem0(}ovpkRov-UsxJsywG_wh_s3SFZSL% zoT@ea|KAz+GS5>gWQsy4rL-t1L)WGu-%rBWzUQKnEdn3^O?l!V6|nrM(BZ9^0h zCDG*f?Aq&m{P9_5?LU6s>$`ogbN)HKb6@AW-jK9}g zn9sobTD86_hIih9{oHtXr@ED>CqulOSAA2TiTC5~&)?TWyz^I!4BUr!7f7sM$qe!S z=&|%EwR#&qXGjjz&m)QPE@%}vQ--VrdXdt%A9fPIoH%ftcV4NJ<*cvX zQ{nXa$e1s*X)}B|@xS~37-GWz_atBkxot)bx*htJ8>>NH+L~f`HAqvd!b2CfS2^P`fg4w$GPNw14pd&8p7F*}=Fx>t><|B+CztauIujaw~ z|Mv3989FSRCLDOwU-T{R3ET`mHdTag(jb1szMrgNQaxuo>ub=cTPK3CKAq(Fc3I z0GHD;%58}EOXkl_VG!?QOSI1RCcB`|gfC0iU&qJ$c&E-*-%3f)LW^4;uwt9FH$L9K z4v82h++sYuV`x5p5ac)dkk#k=U3k5vwtZLJ7Gk^?flEKOIcx?-T0PamlXSddS2beQ zpz1p7@g{ZA=|k(IvE1L+Tei-?yI5?<0mHjBs8tvbZzHA0h87U-vj(;A??Ak#_bZl7 zF4xfgbY6k7B`*@Vc)r~&%;F6W9%(l$fOwZUY7ZtsyvHhy-aVakK}D`K+6+GjEA=?%?B4je$35_eXaKKqi?reiybH=#(VC( z!%M$(Zbf}>s+~1^LA-iPa#fWXd^tAz@lK%6hkd_7R@mR;En8;beT&pL2g7^!!D~Wz zc-ysBtltjt_LSVUi;8#T)!rYz5N|)ZO<7#Nk>KF23v2c$d4oNtw_9dGy#0lnCi5ZQ zd#hMFoTgmRyUNL|3g-BDuh{A-tT-eI?$F}W!Y}SL=EcWbYqJL5lWxYtdpXU=GJ^be zKDIGfq$hyh+_vYA*GFQ!eVz)j`VPCJF|s?BUa4#*Y-ZqWX&t=Dan`^8f3t`_A2K@c z9@QQDvpHcs1Miz<4!bbCTlRYk;^BSLZIyxx#5Ln#XGz5V=L|749w zB)Fu}`_-+$8;~_t%j|=Ai#2&ROhLR$)`-b(gWvyqb%yn!;dgwzZz=9<;=D5tyr9L! z^4=BTug1swtsCXGa~b2!|2Jtq-Vo&X6n$ZuRnCvD_Fwf%kBfNz|6x|$Q84O`GFe^9 z`?{Qt>TT6B<~}$)`KwEeFL#!15rS;^^R=OS1+(K!XVQb-a&Hc(sij! zcn9h2rxC|@dbyy>5?NSG%J2syuGqDQa^_0{bz0mGGp~EUobU&vhDE)Od$}0z5z9&Q zL6o1yBPG4-@D)4mbdA)#X1@s^nJXLTDp*(?1%k>2X3lgRkPdhWR6^C(&H4^^7JNTn z69u+d2Xl|S_X3njE59cY@3W>}2R^|icH7~}ZWl)v^c;(dgZ?Reye+FH*DhEo3DRkC zo=Gp4ty_nWx24l6lBpu&;cY?lVL_0emXNqk;~sw0;0mYOD{o@Fdy5VoIbe1a1f6&O z6#cZ8@UH`@rm`bH!*tf;O^Tw^hxH|n#ee62yBT|Ct)t1yP5N{p||0YV23+nxv zVwN%=zk|Hy+gA9Dt;9R$2*LADhq@%}&Q?f3763ugcQ|6v{U`RGunKK3;E&;I}R8F=3% zsdiy_haWpFfroeX@boqni1);^uJOAN@3zXSoLoQDSJxaQf4wtuzT$Uf0(?yK8eyvf*9K+q<$DT%BWFztBMDecn9|22O%=-CX z$eBJLhR@bIU(Wc0x9tqP@7!wA$MC+lb(c6E-p1#qeY7CnB0^WZsCaWPjuY#Ec-tNq zP&8f?1;n-^&9((z;JKO6GwSlz)MM@Y=OEtG58fC(zwd%>BR$AFsfdqv_KO9j6`7L2 znieV&%0@2ypAPHH_tx@Q0UA2UUt54ngyRoI;TxBt&5L;kK>`{EYEx3*zNK$1yyftV(tO)XZJXzED_7y+cAOCv&{d{7)pZeNN@okL& z`<8lL>sr@L_}8Iy@mJAHomI0QZyRO$e6;+VP}`JsKojOZztZ z%L~Nc5^afqc%Qd2|IP>T9uCSpaZ1(|brd;rxAYr6-p=A|w~n5c1UqPPJ>DY&E0XZ> zKJmj`YT_j0;q6585l@icoc6%yy6}QD*+>IL6IS8@$tZYkv!H7P;Mo{b-LY-W9plr!l;9pKf1(hxfG=I=LJWZ}Z&+EHm+T zl6bx@72>UZ|3RfS$s6Q_EYkf9@lMP;y4Tj9g0?9H-kBHWf<6Zu^aRK8Hzzhf722Y} z1`j9F;#PcH`+M)de4N;k@8oFwXKvhH9BgJ;-~0dnr}_T><-ZRf zv2HVJP@_wLBUXbJc+FG7t3f9g>$q3I4)O$Ba9|aD#0EYtcK3p>*pX36FTxoOo->Ix zFeE_#Unh%FUMf4XUPU4lRz$Y&gq)89v^QC!RI5`Y|5fTr?jp1o=sNO{lm|^P#$( zk%u)Ki1AMElS->{b^;RXL-yP05Iz{9(~O{4x1#QTdDPdF9tjp@ra?1At9p9*l^dqpN1EJq8uE6Cp91^Sz6(fcsJdwLEq@c90U)d5yScKi;I1 zbovNZtf3umah-v8UCZx(4ksobijv2}d#|Wu-3y3!Vd{B=inr@$7uAJu^|pUaaYX;p zXkaChYa*%W4X)pix`V*g+j*;%kw}QQd6~oc9fq!`r!%uc*fIRg3GI`i)5TqLfjceE zjhQ3+H~Ap$LwoVm(>KQ(84vFjG#{!2`AOf@k{#paN5k8NH}NbbUf$XsSNem+BN()= zcURx=vkCXl<(~%jFI(`dcj5=z>C^8R4{uAFk5dHsEvUQ7 z!~-`cmV6wHyX{Df_wTV4i<~PDgLHS6BR=1VHz(3}E_Tl&>CXD*M0*E)J|g{fbYmj^ zd;kBR^2W%&fb+lSj2iUVdet+m2DPr?Qp2l3H*1;VPr(}W=IqudHLwOHIrv77FV)a3 zFJlSUuZ#lcqwYP3HirWee^mkSf}hxFvOab@n1UKDOY}-U?Se{;dUOch!|xz#MeZhR zR7(IETHNx`UlKej_%)~^gYw2Bg^S_VAS-A-stEEM`CJ%X&n$p`P(GMOPq2sye0L!RPgY= z!uPJ>EX4c4QM;{FydAif>Md5+(0%L^+STwl3iM5tZI}1-0>&{NuSsw~dSYK;yAk3o zF5f+m@0bf3Aj=}3e-a<>WvX0UDqRvFh!%J2!QF+P?D%*uWLie4D`q^rRcSsH2=Ysg z3Qek7!H*vBnfp47lXyU?_1_@dcgh?13gx&=cMxxoO7A|_b6_fG*5h58MV}8gcAer4 z;eU3J_Rhfj!Ia$IfABt(w*(LGxl^%x7a`u67d^VFA>JY1GS~P(ynkCaJuvQx0;eCG za2`J41y1g_3zUI)Z@ag~p9kVCpWpq2749Hew(Yl--j9#BSBkI080%bs#kEH>$JkHc zpCE1I<{e0R%XoP2q4{_~kY7o+ft9--AIhnd>^i!D7;krq0I%8+Z?M|>$m5();^nQd ztBsYH)vnHZyh-`=`OqDDVKb2aXFzhFfp>GQbqI#{o=qW(@$io76|%k#@h;ilK-1uT2qjnDb>OD~GI*-K7cmq-b&Bq6V{6g51Vz}<{q59S>ia&IS z@lG|d+yu4+fv3bYV=a**v25DRneLlWw?uR?hfAHQj1MjA^#vBaq zwMFL2cz9M5`>!*5rJc`OXtAjE%m!XPt|*Yb6Pg0&Jgb_ zdqg%|fOzlwp!ZJZs0$i)OuneZ3Lo!~*WG<4#&ba^Elz^jy)NNj&i{vKlW%WOVm!Qq zX+91US?fgI z2UGBC(2G~i4GWAVKrSsVW7t}E&M*89GQe(=pP3Njb&!u}KK2phm*CO~w@~@fwqIe7 zrO3qd|FdU1-)AZu1BzTfNh){gxF9X<3G2#Rb$4e0k^i2e8l67&BpGY`eL>oH2Hwx4 z8~*t~n&IOXO+364wyqEhfOv22i@Q_@@$PI2u6+*izLYhwc~fi@n3I$cH>bc8+&O>x znxf|rnqpp;<9LvQ7JP8}e)66RO454%>g`JWCH9NCT9JcJ5`dW&H-z-2Up|B1K?>gS zH`}MeczBaytjRt9N1!c9LRJsdvdAMv4fPG$lp?B zT=wtm%z~eKB+%tU*SL@^3m&n9)!SzV-mM?jF2<@iNj6gh5AU-lCZt0k-d9gtP^aQu z9k9+7K)l-)9DL}T3J0Xc=@&@7o}gviV*EP9d!v%<;UfnqXnN?rIVUPy&>f%hT7E6T z$6GtZaQ&$e3E)7BGqDM}xF!)FZ>D%)8gImScx%vnuoC3g>RZVhX()hhIP_6$-63MU z4>#P`KE@UWHZ~X=#atuC+iw zitSg&!+WZF!|Di#w?+Qjidu+w%e_GHvk-5a$+T;4a-u*^4KlzX?FCxbb;$9-&50q8 z*FJCd!_Qk>O{vVUcR?>Gj-kxDM$^pPkA0cz5bdyXbf_9^Ps+ zA8!fr^Xn;YZi?hb>qX?m@17>cTR7Hr5&Q2*P=DD>xx9e*a3bm4GE0Ovebx_1VFl`R z`7lsD_I-K4pX%*31MertcK-8ui!=4;QarpLC#)jy-@fIAN{Bri13tIX@C^%;rzxU4kpg!bRAOY^t z;*Q6y{+4QskN0*!W*ZG-JiO1)eApA@_bWMSVSFt=%6{b6)4Nr~cz^Nycxx)+An@-~ zi5}lfjJJ{WCEsXAu35i&tLvLfmya+(AAA0y|IYu$+UN0>6V~MMma+d@T;1)8agoMRt1}$FD)VE(KCz z(>NJ!|Nl4nuaDgX`F$}D8LmnZKwW+bCB6*#PPnFc!b2c}r}PNOWfhgua3`)oVmTZ5 z?Bt7QeFteQQKD9i=@{3E|mQw$$( z@3rc-4uj(08!hf##EbB;fBF7jMahz9T2~nl@7**XRRsCHS*QQ#Qo8`!MLO`|P6{#J zg<>WL7L*+UW*6tDA8jJuASJbvzB?J-o%MK=dg%1gLXtT5_jpU-47^{y=Z(ei{=DPD zN<6&l<_~VSf_R_X+~-Hddq=!khAhPU{LgRG3-&~TC+oI-ly~(6oH;iqHtvNtNSCh~ zIC7YRilt?nHy?CCzt;BkFPX;gASHR7hr*d9z!WX+#?NTEOdI^_%`b3JQ?8!z@D`%^ z5F*HLMEoiXKc4`)1bJdI2N2_J!=I6=eSMO75BoF!2h6~`?bh?B7~b1Id#=F4J20njp&i8A->{8D#hZQ8E3ZK~Ajwvn z1eg0ofh-F9!$2)hAiRa`LLJ0AUG!{A@gWLYeLXF+JlX|4JaM}BHw%9Cu826sTB;}k zj?&`D!RKC|b->5_1z_ds8fHAai)lXE3GzGFC}I7@gda_P{v_*l3o+h)KOeW=hjb5&v8}7YX$ekPg1oz$+`WFr- z?{z`1c<*`nxEjBDKN`M@>aUOh`LsB9IjQ0lrZJP1$uBZ9XB*>4oZKOXY zh9AAqzOB}BkQncL6$e*lxc5d`TIPL-gSa{2$u`rzQCl(V@m6_ApO5P`TR94o{+s{* z$ysHHbR@b02YG!>d7wJv?9L!x|L0mMf+S)*z0@$nrh#4ASb5 zVu=O=ctJWxDof4*FL0Ffe1Ewcod0uLYrzo;`ZY)5%~vxQw8l(}uUHiS5qooD+Wh!F zaZpc-bKIdkb;c3D27OQIuH#l|l5t$*)IBejF%VICZW^Z$-Jhq*r*M*$8` zGZF52Uf_y~h2BYs_m8mVeCKcq+Bcla)Tir$>Ro+&>DRy9|L4^jT;r1~4%XA+9xk%x zZCZklw|~n?%lvJOhqoKehc7{Xwe1oy0p z1Ja*fT#epvyn5E-ZSO&!583VmGAe&BNZ&sL@6Joc$r#>k`L#@Vcsn#c+PnAI`=`mr$e)1H4f7SiHgM%?UJq>qnxYu%n}>cNbM_ez?N7J~f7)E|ZfWC)-Qg%7Hw z6p8UBsedg3D-Q#cfz{3>5_B9+l+wPRw)5VsACO3zbowZ5%HaEZI5Btz-W@@8|Lnb8 zEQ_Cmi}wc2vDFaok2X)6se5k*d%a@LsUiVbd7QK0_&okQvOJ%MV(`le-Yb0Yts z{Dw^sZrtBoZs>1 z#NmK6exf6MN;L{ZqD<@L^5Hi~&DjrIyAGi@%TP9#78=|s^52O8e_GsIsgu*&Bk<4vU&^+M0Y^C)ZvX!j%||9deovLvr+4-7qhqad+jaDb z2c&g#rmD`{CW6&WmB(JH(NTkTIPSZB*?HD?kR%WKe3U0#jCDIj-TzM_&A|H|>*YBZ z-ix@zIq~qmptk(r9QcS8NHJVT#e2*CyS=&)Z>E!^mNmjRg6vR84AqaaRDH*gLu@*q#{g$c83sX0CY9Dmm1$iH<9FZ?F#ts+?+{^?1J) zr_aZmwA~-<;T1b@c`I}V-n~uf5*XgM1^N*@yp^MV{~|-YWrDV}HbcBMqs->}K)fkC zG8Ix*MFFktWclmx>n*#!XWgVgyw_J7e19HEK@pK%cdLInqa3Q=cz)*L(=w_m@R zA0NcKzuUrriucjSe3WYt@ACKLW$NpqKwa*&IE@M~P&07n{I%Uf==Omj_lO7z>M>+0 zdg_1+YWitR@IVy)fKLW?zS55Z|JEP%eu+3z{0mKg6K6@&AhMbSWrd53Lnb|c|l z9qIFXzWX2hW}HrB!2yYFMh*I?RMCOeAc;@90(dp3 ze|L803poF;+-%eN2-cw3s%vA7@C?$HVSl;%98sWogKW{O3qIgdf8j|D$00Pg?uGKI zcnTV3`T6475N9;Vpq2H!9DWD6d`>`1;Z`vaLW>i0m>ZYtjo(2c`tot%J@B?)2Kz^Y z=7W_WzxJzYf-#5qQMWs_>lE)#64sQdg!jb*dP(5X&xc!HmeNs!D%2Z(yV=bC4zh|q zA3swjEbR;b%>S%2@E-iscoD;!?J5sH9^QKHXFhd8yoEQj`cUzH=aeMf5d%%M zxaTUGQ?X|Fc)yFhc7T1F@$mMd`JfQwr|>@AW_+Uns=21yHJw6?_vFZY#ocX*VC>lZ zd)z(5cyqPw57@f#$*jj)vx7b#RvxB@xBt2SFNtLa-XE$m!ZEz}J$=oKhj+`uryP9{ z@2Hzb%v8M7!meH11@Sg*ju%}k83lyi4cRPO?*o)MhIHE?-X4@U$D`sXsG|&y3Btb98n4mQtvyh%3n`G{Rm6f^c`|38U& z2Hx+J4)I`k2lQU&!NYrHs)5W9#QVejuGEJR?~4aQ-@k%*|86dGD^iF8N33pL>qUHk zhsC^)xz0oA1Ty5N7E3`rKaVz};m&A9*X7>1zwz-_stndGEEEGZw76yW)%%=G@bQ-N z`yq15fbsB_qxqOikl#atJC`3k+*?6(gqPrjJ-c$3oT^ughFY0-c8|1sDkijxkU z|2b#Wpw9|CFR(}Kr{OhXcs1zu94@IMSc9D3%>DfY)*$84Ja& zr!0e?e890U#xaL>453kH?Moa}D5y;jOWL~4&S>5{TOL6n#Aztp5_o(iUiu@xjtJzLc9kg6j#{~p$q0Hu2(okK`UERwEEUNqY7Ns zSC0Qn2kD>iuv30m6sXeTG79$=uo&Xwz2%soUe#{K!`qMM!;&Ds%iogo>)rU#>FIWd zTVBL?hoL0idges%=xc`ZNhM;uZy8+wELJ-E4@ieu(dR?#@LLm;tUq`oGw}XY5%TB$ zKWYbAe)g3x9^U(|BqvotysZy@lBVLVXehsQC&c^K?<>2Ddm}-%SYJ=ufDg!-w^!#U z#Jep|s;obWfb4f*?X}s#>)F4|{{@0fi_18~KmaZ7&~NdDmMie_7MoXGa_bo5 z;hj(OAxw~8LwB&kx?+BGmxEKi)CXY_B=QWrN8;+#vFd$g@S+eN-cJSl+U`TV*Opt|dQ8RJYsL5uh__hAWm7JA zFWqLQ4NUAkKH$fbduDfb4xveBta1tyDJZbrIbvt*jHX^!wF@4=ACL_F%KH|nh=H@T zxDhFP(?AV;yk#_N8eiUIJiHBPJ{Az<_r&eI`1TNfH2v*OPQG|zyf3%2z7?#B2c8R5 z18=`0p8u`tP6annDrfzG)L2ZP5B3$C>MCOYRB!efcn{mR>0x-wKMWGY!~2d!eXW(YA z--h!)-;5eGInR4LR)h3iwCCg1p!nYj3GuK7Ii0WPdkSmNz`~zpI@BE`HNL}Q`jNmc zvEvZ4pN>@ADtbxO?=1xJYsog;63qH=Fb&7)B$N~;+G^I z-VJxZZc2rCFV(z%r4`~Wom?)-3h`Fz9Mt=07YUa4#{XC(>}S4xt%4FOc@6 zQ_znKgKJ)9I-~6See+v>;xBJ4RzEVWks=DXX>q6K2%Fzpjeo>0mF-5(Xw-U`q z5mumGL@A0h*5>g8c4{Ui7Q>5<=fLmbhfA65}22YagpOkpMQ? zcNUUO9^n4DVAY=V5DC8{U^46P|D)H(m1P1#lodWyyt!xKJwCM96vO-eZZa<3cSh%t zvLN1}Cn}h!cyHbOeAh;Z_miO`YBA>`!GMRV6*}$%7F)!30f@J3(9H$wPE$~`V$W=| zEEn|G%O64<6?<@-3GL|nlbzk7fTjI!TztUeRZ>Ivcpur-XESWUczCa%`8Z6FUnR*$ zvL!+cRU9(@#bQE?_xRD&$D=g~V1ZXj=0g8gLcGI#dt3VTw$J+NT@XT_4`HDkiEZOK zRJ^%n;QeL85@QVS(w(m2c-6c1z5jR~#C!RP$h|EPZ^fr<{F@=(4s*jb)vrZ@fWqb0 zWuJWjPuMxFD!U+mp%B+iO|jE@0Q*X1MO_-< zT^6$*?+gw4d^~$_D<&l5)PLvy|9N~f@GoEu5}r|mev96;#A;CTp=GjoHHh;uU#$nM zLDeN`3!lRpv`fIGv<41HiX3wyUe!f_N*TNGb56cMV?8gArS%Z1eTsbPT{Z~lvMGXPuJfWT{RZA@9h`-M=V$CoF~^KM1dYH?%uK| z$a5`xy!V;zTPF63@$lxP`S2si&-c3)BBdyV8hXkmrezc3O|Dh{ItSvt{kBdO0NGp&DsCyxR^f5I6|&Uh`nWh>Ca3 zxxCN05bu7@XtwdG2(aHrS8k($FNn9R%@^1@gudgLR$|JephGnwCy&2$MiWNJbBlBF ztM_WjZJmC{ML`-ZPG^(1RTc#w@A3DSvqpOu4{vRnk52^oF%NxI^?5Idnn$LHyu440 zciorihaaYrfln$YBwQ99#UuHkv()9V@I52K_H~Y`(t-uVtzlW4tV0iO$ zo|eMH`^$kBoJSzu7unBuQ#U6YzS|ck%1o z{7dI4Xo-$(>85w^^%gDHMPUW_cwZenX#FWs6xh<@*4a{wE8pYet=#)jvS@_y@V-p* zp+Jyd(X)mZrX@mX?;1xQ<{o0a)s`(gS#~EG$iL7#Grfd(K&p{E7-3nxb=KqEDMX)- z(9tHA4}U&yk;Fd(?K?yWF>`g~0Lf2du5{=fVG7jnAz)My5AT!3m2=EI2~Kl4K}ixdk5Q8UNHubQUBcpo{JH~gde6c|X0 z$uHeV$NaDVL2pC3<*dh>M6Zvns(y`*fA;^yX5c+1BR&PI-ooEX6!7rwH#>UJ2I6hQ zSF(kQckR$b*gDuj_PsYBYf6d$2GM(-m8SUufkz`zB^EE z-ae1e2~YeEGKN3n!c8Yp;6saJHo3m1x(FX{gNSd>YcDb$-qAE4x&--+sFWgNsedpkVIMl?e{1sblj_fBKi-z~`B-y(MTgvmBh=Mf(HVG? z&bt3|IWd=Xi98zuw)Hzy+Z)*O5Y@#Ya)=<@Dd1SsA9^%zsXW~C5fyytT)dQ)6<3UsABDxJHVc>ebSU!|>= zj?el7(r@zV^Wh)PBwTcudV6b<$p7H2G_6_j7OUQ?c9_fI;cfFpb^R`gcl+8mkyN~m z$G-(OLA*7;t>gP#7y(v$3Q8t=`hsWUFJDGm4WUv$U-xU~Qqbd9cBM(gIHUfr;u^1O zA zyaV}C^xi?dQ_4nvm|r5E|HG0Jn4T4qW_|Sz3!%?PdQe|ZhUk(1_W%E9%4XbO!5XyS ze`=62GPe0ER)bcA@v7m~pfhe(5sP3AQdjGhZih8!^{t+3!Eiu&ts^zB(mDbZnb|vy zc=&;Rx?=tFOomWytL_DJir^WfiPmC2iW6EZai!Vp82*5?zUY|o_G}SQO^aI=v-o^V zH~tx<6R)#_vMbqfkL>;5`X8{C<|Bq6zpES%6Ly>xK+pJPB(G|iAUra6fAs9}{|A?Ja6Ma4&3V%Gf^U9z3fBp=-$&FwBdByIO$vYK1yzgy# zA)yBG7BTB8e+ltUbiQuq1o5tL+;TD8J_7W|{J6nt$k8bT)*eL7)zgM!BF z{rYWfw-ef7Jz2Bw06yMEou#$`_e8)eT3mMcjb(1F_;~M;99gCIhVk&;K=a{Dkl*Nu z?h&Rh0_bCzC&6iNi1FTHld|{{#Jf1BCMlw>mhi6w>E|BtF;S;k|A-}hr_)EkMDgOk z`~UN1;LU!LtcX=_Nv6XbV(JXXlNQ2^cisGwh!hq!~h@8jlCUY`ae$>rOohw11b z)7F1raV)1+M#&w($6NcBw(>1`#=|?A=0lSpzsGBmc7BophG^QY+ZA#30E;84V$=49>+yjc}9e`0uF zSY)7#hqnv=uz)_qyET9%j*7Rg-CYwyh_`HSe3$yc2(YEx?`gpsU*O(U)F=S=-j+-E zzm2*E=l^1_gcYlu(J#4LpPi=go0GHJi?l9si-NDTxKvx;hEW52yd~~NE)&*eJiOCs zK70$O(OybX)5sieH2HPc;P$pA`mJ+*TpgoRlp50jZ9C?F;QxHin!3xoAEBL4NL2 zcg9YX@uO-5ewW3phzF!5^IwJS;^#oBlK#ug4mx&_oE)um>_TRL2T7+78QtXNqXmB+ zu?uJ5%~N64h~d3;bBiV(-u5@A!+9azevNDIyn=WeJ@ND14Dnu_S09qTIRdE1rdaGY z^#^gMc@0i)7(y%WOn%#Wmx3A=D3;oKIiWw7#)jAl;NxxDbn(Nh8^QpKGrm%KBkNzj z|EHi@a?rMr@$fdJ`B+Gh-~D&?6UHY5&^4EeuI=_B#(S51uS3?IbRcoF{J6a;}Cj+pC`=!4h20VqPHU3*$F+O{N3Qk zzuf;fkl3Dkw@DaaahHS^GG8>tuin0MNe3@JVm!QiX+As%^3#;p4%^VmkEVeakC?)V z@fPtvySl6-9kiIO{E^pAJRp&5I0ECVf6RKkN!IlFu-N~*;Mlc4)mwT7-duLdff(L; zC;Zj%@K(4uxLXq9eaVh8MBSWtx9QXcG8~Z3yQdYeFpdD@^4k6@Klp)17fSgj42RI+ z3cj$&68QeVn!m-EyA!(Vo&5WxLHrBSs<%J&rSu8|ZCadY|LN_o4Dj*ZaokVEX_)cw zuAup_A;|CL3r-y?IRTU$F7Fd`mKbm8mTwnXdrpHj`d`A{j}mWA_ywE$T+*|d_19a> z52DY9Q%o*%Ma&<(rDovGDgSF6!+XEw+NF4Sldd;T%0RrOcREH<@orn5BpL(p9#v)% z*#xWiLdT7tl8*ZUZGVIBLdNj?zsB|DMYkxZsnfD8bt6vbdb@Myx0m2ICk0Dv8aE#o z0s6GK--fzP7kKdJ|CO$SE+$#*4A*<-(R^qS@N)IIy>|7<#a98PFh^56W=Xp{c`o)4V=7tN?a!kt{^)Ecw| zUXYdpc98ID(DX({-oe&<-QRuw%$=|Xy;WFoeKB>3ovmhahh7B8zw!N@s$~FRGuT^q z2pvLg)|l~~XrQ2qF~|0#taL&>W9Kee&x>D!?jL_|@m5I~c+leRUT`#w3deuMPTkz2 z>`rF9M{G6C$0R|1Qd-X(s@C(Poe3>E$g8h}8=h>jT@TYAW`f8#QPkoU9rOPw_T4s_ zp|ih(OsCIB+qsk@A(#I=VijlLEmX*#gFRx8Uc0Z2hj&+i@3K*d_kQwtb_c}!xg+<| zDL5c?tTfeMzaAd36Gl3cRRh4;=N3_4bm0fmGrFZz>L_UM&FWwJN=|4g_Yb>J3VsLK z`n+im(;8uLn-;f1s%vz;IX>Rqe9V+@QjCXpGtI|ag8cN)1qwY86hMcc_a(m?BgVVF z&hli!;!N;u<(!dfapL)Zd5`mheBa4gk9XNS`h0ZkF4P|XJO3-pz*}(th!ckQe*RM{ z@$f#ne`xmv#Jhe^mmU>wd+7syB@plL>#UNPj3U7FiYy*K)&Nl06{Tgpb_lhvy6N$$ znu2Ee-QM_Wz7txVrR6Vn7awn?KB?nxtc5`(EpBX27Vj2$e7w`S`KR62Fdp7NdjI-J zCCD%R-GW0D3x1R*DC~4EiMWF_b^o9=|Sg}OPRa(3I)Hi-A_Px8xwSp+c8 z<^R6vnLoI$>(Oz0-4Lqj`ZVAMprC4oE);t?C$x8J(MV}AKHihPd8-$A3xjT2+{XBq z9Pj7jd>Zexo-2TGoHU${L& zJpX@ul>4DXYx}I9|E=isv8~bzE&F>pvD^&2`4_g|#PGg~pjvo%*Yh;BF;SPdgc3uk zcrW?V@aUDQhVD0Un-6VUBETsn!3VLa{vf9GfbDmE_?j7zjyKmKl&g) z>*NwYV!Z7PpIB6nWq~af`yUU^C!YV0$2bnwNqnF6c(IStN9Cz_pYOQ6WDUfdOV0STo^k|8oyXjI;cfuXisN3< zsy&1rek433{g{Hza}Emo-Q|c@%)M{(AORomC8HvBrTs#nk``AyTCo2;FFxL5CY~{^ zMU02HJk7^vg8XhiPruJL#D~^@^DrF>BgT6pC+JIrc%OCKTDXXw`9IG&s4t2%>j$K; zEA;tbb_M-ze^+mnXW%WSBgll|ec~8k!o%A%Xzc47i1+oxm^$j_#O3CNg46@j7HPcC zfkp&qG!cGQWjwrh(R>i)S0B_6TfU4REwJ@GpO;FExBQ~>tW0%TAjWa* zU^*T1fBQse=OK#StjD|Z3w=JU?;lJ|`uqJqr5SjO@+dH4cz@lOI0p~!g3N5B58{2$ zP~3@%_nZ9(GOQrpnKhZ_bJs)wl9=f7YrX-%tZLeqWz7((HQ2pltdW8`pEB6V`OOg> znyj9)=`23pDm^=oJrxrMgS5CZ^X3!l1o821i|`VX7-KxV6=^<*^1G{EE&cu|Kf1(b zYtGy}V!Y$R$!o%EVfA)wZfQ-TWB!k$Z1vkPGW+NMlXUt}PZXiPoX7!Z-EpQXB;L=w zeY|bFjl5;N`Ml?O6L^pC2Jr6Uwc$15UCpb)E5$3o%fd6k^PcB5&qJO{o*O*bJg0b~ zc!GJ{dF*&hdDMAic|>@~+~2uBa(8jJaMy4bb6?^<&3&9ZgxibTf!l&xpL;pCBDVxL z7uRpDQLY}Y=Ufe3rCfPjXSq&t6mjHoq;kY?9N_Tau;(!6Sj(ZwA^Io6*-x=Yu?Mrev)i$ovg@*|v&*uJu#?%ovwdXi zVryZmVJl|4#CDqPI9mvt7n=i{1)DzGayCUa2{ta)->jpoJ*>}J8(2$O^H|Tao@5PU z^<#Bm-NL$&RhxA&>wH!|RwkBlmVTCYmS&c6mI9VcmL!%4mLL{47F!k*mNhJDEHW%Y zENsk^%!ACG%#WF?xWc&nxLmllaBbw$=32}(pNo%+iF2H@pR=8_nX{a;fHRXbi8F#T zh|`VJmeYiD4W}BX45tt$8^>y7Kq`7?Tx~0n-W|Qzj)QNgiD$9&EvbM|VyU_G`xaH#ajI zlW3Etax0(50MdY|Cy#&MKYJ#WKrZereaJ3A0o#v z6)oMo9f`qI-5igN_nDWg$_7(}kl+V6RCP*Nryw_IABLSH5 zlG;0h_+!eWr~WPChpD}Hk~bp0m~ua|Yb)Y|sXc~yuMlrcxk;;3BVL%=HJW0Kcw)-6 zy4n))z?4f=SR1kzQ_i--I}mqFIcZv^A$u_8@a2^{;)bc6_ht4WyD?=SzbOLQg{d8T zzTZb&F=eMwIf}So%J%2cJ%}@=wmm(27jeRr&FOu$h$E)927bGSIACgvUi>7o6I0eA z>n9Lqd59$|7686S2e8=6$v(vK>?A`nmOpEvC%oJ&r-PVQSN0SS4bEDU%y# z`H-!cGLCqjhHSxdeblL>*HLd`>S#mSSqY=G!Pl4O8>xh^Zs0n4+$?BPy7pE>9v$FhyO> zK^9|*I{YHan4-=Kh!Uo#r}mIVn4%tXLKHDYJrjZ`V2Zkhj>uz*y5oq*VT$_hA0mq> z>Z?-7LQGNLEJ0*2MLmd*NMnk6ZW)on6!iunWC5nA7p@@lF-5(f0-1*?>g)W7B&Miu zKO=K7MZJd@k-!x7+EzpyQ`B275iv|rF9k$IY3k1%YKRD?s9!TegfT_^_zNP0DeAW} z5J5~)KP`X=V2XMZJHk&>%6ERMzeR3h>UN7h4{`%jC0P|BNFk<*y%i>q0!-an$F&Z* zj;SK9`NK#)rf$5<=SQw#sxVKw3CY7$fnTf`aurk8H-8*Nu3##kYhE*Q8B=)!MF6>k zsjIgg9g&Nex)LfsqDy*bmRi2 zvMjX3k@J|!lz(v&Iftq9KlbJ$XEAlI&UQYMfvK};hW1E0rZOD)N{};{N?#Ip9661t zGfZXQku*%DJ)~G7shCQ=plX4nU@FDWH3d0^sZ*>AvLB+`@; z^$XVsAEu}u1V(rP+zQ%A^{8n$oKL)bC(QK_N>VZ+qmr^bs2E2chFWrQOvn0lXdhzDWD)WFViR)h&t z{c5U($Q(?)W4$~FAz`YwDP4j*jj5gsPi)D*G1cvwbb|Z~Qxv0768R^l-g5MNl7C?8 zO}lds`8%dMFBvD3r!dtKRM$g9XhSn^j)wcUFDlst~9 z7YDtH$X_t^JW92X{F$bd?`lpsBSqNHo=G>Tdg!KVj<0v7L?N z5llU{UiFMTjHyRUoN~z@G4)_dZZCNVQ_Z#3A>=_!HKjG?kUwCm(Ivo<{2o*Hm+SeF z2QbyZa@c{~kEyzr-)G40FjbooG)?ZqRE_^l3b_|k)hn-zl6x>!#Tt-A?#5K*z}Ocu z1ydEd)~CsDF;(vGeumtIse6_cU&(JURmLA}L+-@XU6N`SxdT&oZZ+wXUt{Wa=vQv? zD@>JGwl-7It1MSg*)8%Ym!$j>oVxMS}+^0WWm|7WZ@ z_kYa>?*D7dSc9Z?HP{;D@TZMjcx#Z=y;++J;2LCNuTSk;xCXf*=!?M$cn9g{;{hUr z14qG^%L}XJoC85_PkF*>)gd(6C9#XtYQb6kJAc3cRY zp~V$HxxG(D7XKZjb#otvW@a$n8ss*b52F0M19v9Jz2ip>CnwJHbdM9B|9`mWuy>?X zF1XUt{vwTz@Bfif^-eF@a%k3Xkdl(<^KrY^Y*oO?KPO1lXW&h3(=oi)3(x1o!@E^n zb7?WeJEeWdm5TSGrG+XJaEV=J~j`nz9`CH)6c^T(4fT%{mvX*16y4eVOt3WII5xD2uK>ykh5caU7T z9w;xo&vk!b%e!Z@IhU_=R=~`lek>9beI<6SMQ=5tU}y9jEA>9&BrZ*{0uMIs>W#vpl{op?j|S`<9#DW z|JEoe2h?3O-p5~kpRk!Bt!_?*JhA|FL)H;Z$|)}A$aD@8MH*yQ zAt_m!Q7ZEk86s0M&t%M0rYIswkwk`MDwc`{N}7qvkZ?#8B^iGEXrK2wf4uwM=fB@M z->dhZp38Gz?{(k$JojGrUVE>-(`L!AB69xUV)0zIx1Heprcd1RORa#m;klg_3fSE{ z;pWfO&PraWi^d%s?uiVp#qQpXrYGa--RX~a6k5kqocwsL@4hKgAb>-h=~JozpEprB zyd(~J_EznDsWhh*KJQJ5@Ojy&9m99;)D+t4IQlN7#xDKe_y7LuyiIREL@u$Lsd^B3 zZ-ml=_Ab~>!0JJb>)S*Vksh>5$m(1da*1t`9qa5xF0m$Jq|JYF!(f*C6OF^mz2Jk| zUmj9ogJ5>&@CC%1~3s8r1B&abUBV1LpJkmoF3_dVQQ1QsN#~^5^HS3B@sV`TzI->(_n}ts@R6zcq`O-B@!@1aO}T^<0~WKOpUqQR5BUp95nvjO&8T zUSj@UD0Tb4B^`GRJHrTx{Cf2_IR1%)ds@zVu+LX8Pm31FgdgCqGV>>wIdi z{9w1rv%`8c@ZOE`uHlXdS^MBQ=I@2VTlVh$pHt~)7@qg{JG9jyCR4kINAVJw_a-Xd zclV(!hHc%G>FRN!TujMqJ)Ic;iIAI-X>B-kdbn zku$mC!;#Rr*IN{+c#|K;pzs#cF5$%DUG-sSRyM*rQkob@=B@ibZmAor$)PK+)??AMU%{cji{<6x)={$fX+Fa{>CH~@s<@)TQFZ*)f{cH9d z>*{DYoG9w~1GV%149}a1#yW0R*Cv(c%+3D_RJ_U07g2a8Zu95B;=L-1(=89-UA0C+ zl+0VfX6U>F!rOe3d-1xCFvxO4V9zRlPiXJ`$0kx{5JgI{`AnT(-`aMVwsvNf(e~HZh$uPtH8#Jyp{P?$O zGwdEzvUj^WX)FEppiHz5y!>2Qj=Jf8=K}-TzFB)Gf8eeNWoIIXv}f~SB-0zA&%O_E ztz7`_KFh0s_>sWH3a-yI|sD&FKrhAF(4SFkL_;+^v*;)@@``^*Kq>28Gg z^tBQBR|xNpv6LOXAqekE=Yw8OUNCOK9^3UR2EpFa`7KYTJAu*m^P%UstN`ID>0rtv zHt!xTsr%OLypR`-YtO9ikbQ^E+r2T;o>z_jcz2_9;N@pY(t}ICzN{i?_#_n|!Ab-sxisnq=OGyqa^H5Z?J5;w&q(!=UH=Y^9r0 zUNBGPWKEjrAZW9y&A$7y6R1Rlrfl0_1z6AKtP9GiJam|8nxZV0mi&B@pL;+|sj&QvW~mt?>T zpQCZ7gaq7=r(kbRu-qM9E%coJZf~Wdbu7Ti@1T!jVonnu7=3f+&VVmI?^i70E$VuC zu<_Gus9BR%M{#3EuZ(u1zYHQpPMmsfKN@!HprCE0SZ{~#@Xq@<9cApG8_9Zsvx&ABP zqx9EP80n0B_vRn$R@-`9HjffBxv*Lb#Gdtp1^b{|u6Ff8=^KVK#>E zLF>QLRtHDOx1!mExfSGgD&FK5k14!sbbc?#;@$Ci)c6R(+tF~g>NCRooZpmkI>P(L zq;d{PI1F}-n{po@&0pog^>foyWaNPLNf1(ExUy;ARDADT*uuO?G1y*hx40vjd{VJSHA>{ z@FTakDgz>yEban1=^r}v)RE1J3zGBg>#=!53E>l4j_|^xXq;bX!Oy5t?Cz~|Zso9h zF8%SQ)S-=&-wI~df!05~AbiSn{g+mJ-aEwaIsQ6Y2+I~_4fpHQ(7o4uz4}u*iQ#z% zOVUuGa~6ICkS)^ZeB5R0^w~K^QVx!_a>APqeZ@Z%h9sO z`-Wo}3@`2KVoLRb>z6fe&lVU2GImRqI2LpP^>WR=PfeDf;AibZiB#;nw~BR-q}Y)C z{}MDV?1J1*mQd`q_u;XiZ@cJl?@b=9124aF{meYpLO!r@WS>)1KR$2EJvTjrkiEC- zL)RxIH{jpBHIHl2+>J~r(TE57fp}!U6N3@R9IQb3T>yd75`37-&E@J%i|C#)0t7B8^RKCvN2c&mV@g^TI zN#Pyg7PAtIw_@Rn?FSLw3eH#R$(s|bUoU1UD9Ed=`}Ltmi6snH`d2I|zUmEKPH|q? zx)^!?KWw9-|B5bfL`7WSMzbZ@XtE;jqbN4-Gx<_>W`(>^0gb!iY1m_{fz7+D(l<=H zk^Xp7>L|v^Z;jcl>_=JrK%Hd2yV4tTn8NPcT zWfrBWjJr1}Zg1_R;!Qp=mBRadr@06gZ_)jPNIiu2TSe$d&3on{mx~>97;Kht z=MT+Ccx#>;X=5J*`^zFO7%uAqr8x)Hdvz>9{5F5Z-*VWC6Pe1z_7(EH5P1h-F3xF8 zOmXub?8Ql+yVX>w0sZl&)X{^JU!0Z8h2%s&5LsNHq!fYAd!@L_8K+A(;kO(8W{EfP z_uiP^y)%5!lgaSBnc8WqWB z0`a-nI;00#9;iRjk6dCOuM7==mJ#vTSIekk5vZ{!R2l2Ub;zmq_`b^hqU z_AYQGaR@GaZ2^KKo%LM)VBcbYWjZPQ?i3M*qj81%h7RuV#_mCGp;p#sbmv2Q`;EUr z>u|xzPwR0CkLdzlaBlCY%lg^xxX<%PSwB=>7E}U-uZW2~WT&AA^*$9-Gr7e0J&49S zyyXk4B+t#w|NE$TlMg|s@P6=(B#y;e#$zx^El@uJp&-3aw)rC%^mlm3NFBc)`B;4TqT)<6mO$3UlP@YnMP*v4=ti zd+~2?iI;ON`_i_E;dhXh&{#*>`LKw|zdJ~pRJ_Tj`crss)V;M1i}z2-H@DX#yq9-a zH})aCLt;%>3lQE<-fdym`x6RPADd;=3;MztBcDxT6C}WS@RNnk<}SecALlPnG@CPD%lceIha=&%$v?~5$sTo)4Pk9R3rM>2pf?LXdnLWJtyt5n&p6v84hILcvlE>xnyLZy)rxNq<0EXwSPGcQ8w$~p1 z@}66qs8jJKe|Lq#J9xMLS}fkRZ{O_Qg79vPh!P|7HrN+f4v@_Wp?>RifkUD2seQPk z-dP`*^isHT=?n?zS_x0hm+Jz7&z9#NH9@}KDsE(UISzaNSNoQ=$J3S+;oCY<~PUkjB>#PflXsBrBIqWHX<^-PYv_bP^J_IbOS|In~G z(f`dkN8=CUfB$co#yST0)#Z`y{crxKw`ugh1vo8r!fu1qJwJ!srmH7Bc)F!n9>HouO66h->G#9l<}XvN7d zJmvd7wkRSvoOkV@!U+ESA8QLdSay}cYhI5v?ib-dLCW+;t8}y7DaN1wr)jHW;pR8o z_x_&$e~5}V`BQ2X-s1~C%VP0XbI=GQBD`PL71R$PywgIhqwXQRODo;w_Ad*AyE+HQ zty6sAN3VO=>OPY|XI%H!D1$DLQ2AwBL%Rj=nm=^0avwHt(=Y3rD~pKG4~_FXNXy*VVdE2pZZ2y9R-_Hrw8Kac90HI@g{#8kiwgH$4wb5-m2r5jtd~Xe=hSmLFOIc z@e@3y|c(c@@7{0Itbmi>G_A zc^C4lok@I5ghVuszv|K1X%hAd(l0H#Xv&-Zc;7_p@WIJ%!M7^Sf(Jx!HQdP^2aVIytmf4 zOJni2eEd#-1;X2gcwdmr`(5Wda1`NfrBI@q%o_&x@v;i@*!e=qOZsC8gCuZ9YK(tu zUl&MAlABUvwgem#JAd0A!{$9v@xm>*hX}dRxO9nn3C|g9-d0VKxfd_eAMf929Y=8T zJHg$?>LSexVxEKsKOMv8JxdBZo${m(OSpt+k!Dk zfpfgIsCbjV-b&%EZKx@Q#ru6kt;H&YHydcY|95lZFK=P@Z9E$ZVNmP~_`LaqFXVY* z`lET61cnUycJ%E*p1ox|#(Vy}1z5nb=7&}y_TAgOUEf3eJcy7LjSC#&EYah^=55OQ z%cfb0{&-(U>oCH}uRyi`ZJPuy5I>PKu>U7M@1{j(9`-*jg?T4u`Kw<%z}>53l5K~? zkDQF(y=kq(-hP^V_x9iX|6k^9dixPF{~J*CAoBOCDLtrZ_rgtBJ!sj{14n+gAOq6A zM@@ssC01C(H149Dyjtugj*6 zK$8#>6EuR|gK}-Z7!?2_)Ij6ZTOIX-XR&+GsL^?gomZIYZvX!pTE{R>ejbMA3y$g% zK}h02@m&`DdyuikzwW80 z{vbPrxA>zL1uWi{lY15aAiT}ua@@(h?ehD@8W7$iuP%_B#zLXT=CP{=_P$U+P(eZO zB?(lCg^SO+bpd`w0iN6UEdYoA^YVvT*el5Sg&A7Whlp?q8h6oZuP9py_WZw@Y1uP1 zNPoOp&^k8Ze7B(P81i9UV>S+`Bm)NcMl8uOyWpL!y#r&38{3l46IDbx(EYlgE z_Y&IbC~HvmP5b+Liyjqk4Uyyjd3r1O*j0Hf-d3;LS(uO&-r z*%rpLhQSQ`B^e*$e4*inA49xvNnr4u&C5;4yMPO8_{GMT79ii0ug51BoA>9|%$~K@ zL`aE~n1H+?SFw5DC)E{ce4szxy=WcxaPs5Hhir|DctOk8*&{D$nEz$=$#x!_D1*0h z`7?hrHQ}xxz4-Lye#$Lo_zlto0&R8p*C%gP`TPFAE*0;+-=3VNbnl$!ZX2<97geji zU_p3GoKI~aZ%#av5MQp0+`Sz?1Gq&*!=Sj$5xA+^7xG>NK5yDc;QBY)WXEG&z&AHV z)1%JIECcigi($Kvvb40_K=P`cwwxX?$#;~5#k*Ra@zYZ1e zJvCp)DZIt6ZrgyxTW3(YVll#7&N<}-nfJZEQ~KrzZ|QMsPe^Wd$hGVOg)Hs&m_J$ow-MzN$4_DNPR=S2&x#^KFElP!B6VQU9Gf>+bD=?z z0R7GXDQF#>IQg-3Hs*wG<^{nHSDk&n;V(|&1s=P2AbW3l>vt8Atnk0yl0ENBThU&| z|MqqgGi`Nri8_Yph5S4JpWa6O|C$dn|C>_vAZ>3GK<+`ZJrcHNG3HEIJ&3SGq3i=P zAoVNGKl2soLGhtOk8jD!tNHJI7j0u03M;%$sMQ?sfqnZNY}4@AceHUnFA&(HBTrs92YMROE|x9x%p%2>R^hx!Wp5Z({Q8s7~e zyoc|9vs;SH|99o=n!_?ep}4&D<;Vu)2~xQxsY?$?Ag$FwGd{WtY-}{)EakBP`YK75 zmQmQei_U$v&)_3MT{P~l)ssSvd)T~ZiI3}a4Cs${30lV=ocwO}&%Y4&o&c^mjfK6E z#^)`*#I^Gm!kaX;x%FK01KjS-6dEgY^fZa#dDC3S8PeU=fA8KJQSsIy1=mt|TOW7W zjK!NzPp*6j;q5l_CxFcRMR6WSh^Vbb>45S&*a15(|kp$#?hAu!IWFR5bC3$|_9Z>4*K1g6)p zaYWwi0v@CGL*o@kz_%q2zP5bAUP0bDKD=3@g8;vxak($Tqx37VdytN{OWgMR^B}$b zdaKbo4&me%tSxkV{~IEhS^Kst}mY6C2^S$r~!X3ub+J6S>6ph&ZTR?*bZ96_=)~kAU%$%Qv*c6&uzYep7H?;^ z^1)_=_c=}9bTaQ|lUpSR5Z(fj_<|ieP2SjJhEmU!|(r>%Ftu zGb-M?9|XE6ye-eyGh^|NFa7-B6~a4QZ1qkuZz+9~GFODRprY|AzqO&TTd8W@`ybx$ zVfUt^rMF4IzTVr{@A>4 z-?~yQ_=o;@Uqb6B#mTS6S<0=cj0k@2c>6+L51+S>hqCokgm;$F;oKXS9^%gbOnQxb z+TQ>`AO8RvKgw0qFbl$|~4S&Ac zy6hVP2BUE)UX>Zk#j$xubgJ7Gu+!iCe-EuA6equV(OahTzY~C;h_~;io%p=ZSnv60 ziR`^~eqH#Oo2J;=;{ z@)4y6IhbiI!RkR4MnMIINDm?kSuY+%dXVD$FNv`-@@f;Gudc7E4Tdq9M^0R_@Pzwo z$CZ6kk#~?r!#W2VyTJEDheOI=ngh-|p}8xauzOJ3@9-z)tpvCPjSE?L^t@3vb`Scz zX=&MvC;eSwThThYaq`oY`5k`jI1v#1zr>%*!S6w~(MJwu#omUWGe7Q8UxPpYr{6AK zKI4$Z@I7c#8Eth0g&CTtoSK{ek5chIEMGf9;eDn+kR6LRU;T>Rr3i27%jzW~2=Bw6 zg;(YwyhS{XcH4akh9fI-%pwXsVeZ3@I_(S+_&O^kxVE7SY*Bn|FVtoZl!fgceb&R~ zt=Yluv$2f;mC(4lLs17+Phj(&G>D9Fi=aQ=8fYC8IQfnIex5 z{Ekld0+Z%IG`{D{t!&7Oi<8-HSasS`b zTdb&f8^6q`qVT?)eU}xBcf3H2!ySb81jm~BWZv!a2Vy4?-rpQzeAgZbffmt+;!<6_ z;QqV?rZZPapiT97(fO(_AmH7z^sL+wki>SmCfpC3cgwlm^(h|-FcFPA)~HqR+5wxl zQwqzK4|(**yBV#+0Vlsc!D|)Yb`Zgu*ZEV^iTJz^KAER;J>oW$&ghglRYt=BX;+wA zcFLb+{P{nJ#yXCD`N;A2@fJ%e-bSh34=B8k-40!Z#rxR>pM!Pe?#;0`kG%KBmV33H z4VnKFc;0RGa|(fr);33*=6k_)e+oQGuaUs~_?wQ*WnEy>_pl>t`4J%IlgSPK$JyJ* zz0EsAkiECHXxwTSkMQClY~I%g%4*`u=#RG(T1OsEevK*c}Lqa#SAwxBt%&f8EIZ??BaqtWCa} zQF>6W?RElI4-!c^%5@IuL5BqPy!?*zAeZe?ldF+StmLaVtD-o9;rZ#A{BK{~q3L(` z*1&M&h#k?Zon`&V`TsuhI&r_uz=@v`(}7Ibm)Q8(CuX092=F)>*Z5Aj_+&bE56bB9 zzP&`5{(4X%T1OgAe#{!)8()MFfoQ@?Ao&`<2gxQr%zAUQ91aC^FHFsDz`eyTqdQyW zxif;{d(gBFZFR^EN3l$vnj4Vpsd!r{=*}H)L4LeNR)dEJi?_e-)z=pg-e#B0JjuMn zvn~-75Z>mlBnx4gV7T#kNr8yG2iy%t_JlRYai5>I z!F(J=b}%C+cz^)4(YT#CFKx$yuz7#$lUt>}hyHlWp>+)5y$J7FL7}2tonUCm)@|z&<^iWi7xtbyO#*H{6}fp$oMP>5n(1jyE{@ zwLCq^;g~@L{5Ae{@9OZo_j*EMk;m?GXcE|RhOYsC|DS2?!UFCe91K7I(^|)d&GA{^ z|32PwjEeV>N2|Okyq(t-b7JxC`*`2^D#F|4(&Ibi&53zw(J4m|-WM(#2X>wehF6Dc zE(vvez%lQG*TWM?z$0lutNCpg__@}@+VG1x_+&DcYE_HPyX~9XflOp^LWvWspDcL2 z0h{+(GeP5R4)n*n6|Ex?C%+gH|KrF}B3PpJJkP!wpSO|y0%E61Ib6;W`5+)xI29yr11)&v_l;U9PHUMdr=a z=kmcF;ax;5G#SeXhRk7_OOLMbgi`PJzdo5v0uOBXoI6^&0LS5n?|!{E2hA%=zW1KR z=KY*UW$$C;_SRE04)V&#m-S;WPCjXjz8`R+Kin`&XnTw zzH>CsJR9MCMfj_I>LdKSw@lgl1k1&ob`N^U)O6_j z7!&5e_5bT{;s9F5eVqKFXCLn9<0XQqc{R^dSjI3{%9J|xn>k)Pc&;2?TvQ4A`x|iM znOc6iy4+7;{2ug_wmRYr*&dl+ox8+3Q}MPFmAyydy)I($QY_xAKR(V6LwFyWvfNAN zz3^9cKbbePo&F_$wUe+#nN)Ap>jv*GxYwKLfxO3D&Dpu zDf=kA2ee=EVeyWPx&J5<;VsMjW8eqE`|ZuPEu0AN5c804gPteh`4b`*Rg&(I?^{k_ ztPcqoI9EkkOm>0G%JJdSPs~8Ww+$Uv#ISiksP%5j|4D!k(72J~JzO#Z*u2FSW(2(F zra#_~&^lJ(7XvJz_}r zmO$eyDiUw8i(>O$y>!~))++kry#=j91Sh{Y^W7%I{t%J>?0Z(0bl~&O-(KhZT&5hl z#H!y>{)x|4I{5p&(!k&5@xQ^9X3yj_o3eUPq| zi0~fbwvi+A)(TVL<41VAG#p#0(t8rxJ!%w4FL8&4!x0~YgGpeOcx~;);Vw|S44O24 zGXvfB0wTVA*u4FJ_@B2LCBRNJF4adwAm$nN+WXfo$BQyD^v630t>XtyeigE_!;d!+ zL32RT*R5^%ydMozN3zP6!>}ze-JIDp%>P6D&KtHaXL#OBgS6FgYQ>8OFEjq_|5Ii) zy8aWH|2?RB(1{&&Vw4{AQBO)3s|Vfu9cg8Y^q_5WP5wWT9`u#7q<<@N28qy`291xO z1L38#y5xb6Rr@b$@g5ZMkh?ZyFuCR5D$?11TNI=Fl{6Ly;H@J8`HgQze z6zooMBprN<%{!7yFpqGW0QaJCGZS@FzXp6UZ{xU}JNn8^gZ_9&qjfmp#M{W?^A@_oF}=8~0)9TWWNI?70rU4lX|1obR_!`I$@niwr(L40j!vPmgd3OU z1|&Bs-cH>OpD4WlWHt$5@n*TQy5j`GJ3OSTb{ygTsl7MG4dLxV+;+}wM-U7O*l$oY z&kYV%yF>{cC4oh(Y`zu(-QYk%b$GdkDX@p1Lf^Jx^RASh+&X-Q03FddUBggz{+HOi z`H!retT&}U-gnSCh&cIuyxViTqJscFJX|d-D2C6wu%bqL`g!ev?Obaq^GxZCi z9ms&BKL2w5hoB&+%0J)a-WoSJu))Po=7TSE$Ov2FIt zuy~7nNU`@tcsKk}TtMdS2k)Dc@7@O8_+rsG6a-% zS!orrg7izh8|~^62uE|?SLx@v!iVWS+eLRHUy#<;Ub1s{H&_wuvh!}RDQG^kpuP7c z_9fOnP(JC?2m!XBar=Y)&-FaT?m-elvFfa9^w)zN(K^=QV;-+YsW%)7h4vVRcaeOUV@uV`c->{uV|eE*s&bY8x@vs8lw zO6RlxxvAO>%sX#gvW+qYcS;T4ysyUQz0GUs!VljG@Gcs6*{-yF>I^pThXG8lKkCpQ zZ-CZOkCUIew)24jZ339F+NXcY5TEz?OrpYNgtxTuF{z^W_&Z2U0eyA6_5TM3B!AlK zIKAnkX71kyq`j$lyL}9QN8x>Z@SZ3Z?>w*9Ta6Ijf+5SYej&VL|%@V`5xf@7woQQ7BF$Gf3dYv}bV)L$)PHhrE_Wz~P zIL-h+2kZZF{-3q3bk>Gr^vAmzt-}H*zdk0OcwY%3D9jj5*rb8a`$%>}%3AkI*krWo zMBWPgH%Ph09mh8w_hk41>EIY`b*Q+n?~Mtc>)u{eyj`=R|8sk5Mmc&V7H^jQ+d0e- z-XDLrZYA^9Ju<``ityGspg&++9|(E#e=}`Iy7z9?$uEy|NFZB_(i*`Z zrof}2!LPdsn|Gd0wNlnJ0eYcvw~|lIZm`Dg-bp9-2RodkKi>Ih9q~B%eHdAu!QxH; z4k>TD=WWO5eJw9Y^@dv|6np2X65D}4ATd3?<-~2hkl_a;rf0O(!EyU_6U?5Q|2?UA zyLfBur*!YT29_dNybG;@i!Bk}Z&z=APu`rM@E(-m9>3VD(evy=@< zK>bis!Ahxapip095sK`+J^xv5_=X*ucS;hIo?ILOzC_~=bCsIDvckT-)semGN1Y`7 z@jj2%(T0=X*a6Q-F&6^Z_vzH@5=DI8<2tXFyCQpU9(%oQa)0A*P6!^bxt&+w$MC#| zXskmkrGrx==->W7UC;fLP>F?50gOP)_Pw`c2ss^qc%n zVp@rP4{|o0D>+zz2#3(PYTv&2m2a^hu{(an`EEB0{q-P99S%78y;~tzxf6MU^qMwX znagSX9yIh^vOGGu0$OcoOqKPc;TF3}q{WD44#W2#rcJcfan7Ka$D(BJ5*tXx+jllW zn!-EyR-ZT)Z+-TNwJHd2FLS-I-w5xA@AF=(A-r3A=Gm=V5eRogr9Iex-xbEx2%mYm zkp$vyRyq40=>{i8_tk$#Hb|?8!mYH~+2$ynTWQcme}&^M~T|z9aPYh+au0EFb0kG1G^?f~*f;5H?`Q&hP`0 zZ2)a`*nNm1ehr`F9YDp~r~P6Lg|~v-gLPQEJ^Dm$s3E+C8-&i1c?a>yN$MlKH}94- z?%x;)Nvn%awcK)r2GhnH&6JR@w>C`2%^G!s)iZ;pCdZK5TP{s6X85srx4b>3L_|Js zS&PQCYBmW*oxSs75znuPfzeMXW#K~`mi<)Xe4H1y?b*#SntPIbaX^6%;NG@j-|L*_$Q}OmLEt~s5I(c(qSxJ-_7Vp<*=c(={ z4@g2sHjsI*wfM5?1j0K(#aXIBD-a3;(Fldht}y7axaYU6B;Z`quIZ`M4eV`|QtWKl4@mPK4*Fn(Y>+ymak5h3#4Wjjm`^D=2{p~iNz)&1ezXodocvyvz1?XM zO9V0TY>L&6_`I91eSC9gsuDivwr1aX{VC?}g|Y@^vaKFFV(|{`l^NGSc$+9SKP7KYyls_dNkn)Tr1Y1?n*~DSgb54b ztFF*y@DFpG8VU4%>u7(ouNxR&tva2ddKiH0?F(0Z!|vWHhvwOiBk$gBN8=VGWNPYL zWAh&Cl&c?5qCeiMXdR2)eO=oA6y&O0)jeFvX6yI<8KOP>mOn;qV@Rm0~U zY?{sN%T&wwytQeoyB4!BEnEK?$4p!XD?)9^Iq)v+|IR;{&+7z>zId=-$hfFv_pnO@OiR%>i8{u z-q)4xZ>U3fJ104A%P6kLT|qLjb15lQFJ|}^Boil%b%b1OlAoLZ&oWW*4osNGO6lGg z>V2fKcvt_rmn4hu7Vaw&BJ);x9c0gk@K%?|FI+Yf0PmhzAW;3m74p|x>XfcU9&a&O zd2Fp)Hz+CH{hg)J1e9s23FJP;=KX0yQQ@i$L|Bc+JzcNNp__@#+n2YEHE)3acz;Ce zaL36noJ%ZDZUqs<8DCvfa221oS%|Ms?CT2XqHLh7dm4X(^mXouyB`(V8NPd0UZSlI z@m{?(5ohM^-kzl59bk3LnZlb%Z=VzvZ{=OS1bKva--JRHdGD?LFkinY!h4sZ_AB$L z04Q<8_VK&7u2AF0k9v1JF##e=r*>@2!{*Jbd?+Ax6%npM z<3wcMemJ9x&AajUk}-v!^v8Q1T1P!jehOdBzsp)7PjAV|cm2AE&->g@mJoY{x91n> ztl1eF-rn+ie|8@0QikWvTf0DPQxpy%)*H~7m*(&NlL5@@P; zUo&yF8_0_?9jj43y;{hvbM5>fJ@O#kEOVtps=t^i@)!e$SpN1VIZbyDMyFteP z#LiLL>R>YxTBbVpfwZ%WsCY*V^r}*LKWlDLz~U{@*vY|#@Rk$0(>0Coma`ojGDLXq zwQQPyJ2n7nRV8N^?R0~iE`0wjxsU|zEjTS5nb{52Z5mm-a=-|vZy}t0}yDeQwHQ@g6o7 zupuJ6$9ug3$-E1X9yBN4y=CXutpRZX&_dd_t4-bw-YPnIp@j{(z4bWt%feLT4N~XR zHm?^L13sRe^Q8}C^S&auT~Y5n0aD`RgdTJECSvpcc3UKS#Gd|mQ|cJR$!~#g_WI`p z0?pZEP{|7Jmix6=DR?o>yq!7GCXgl@EF?a_yS}l{?7jksCb9P zhW@8}*D<+o#NsVka^}HOg!fR2%rY|XYkCQv?GfJlxB5R@ofH7SrzigWB;p3Q80YS_ z=OTe5zwbv=61#yT%R_COBx6wiI`dD=3^s4`3d3b9Ith>xcXEGF$pRhh0V!lOSbaAeGvrzF4)jM5H>E55qRX1Sq_UbGF%MspLOrB-ry|?J2_9{*Y?+GcT zgpS+*m{K>i@!6Csd@n1*xrmnpLgfV|mc@1hiLGUl$4pE>yxG+7#9i$9U+RF7a_@d3 zOhDrf4F>Z45XRpB@0*R2R|ufL`JYlp7fybo{m1x!FCqe`ZEX2m_wacSbT=$dLH6Ea zi+3_tl;HC&dsVv3I^_Vv^LC)I4&K2MpoV;V```SJHQmzD&yo3`gQ^Fe;YklB_aHgs z5xcO&!%SE`D5`(!sqyCpYBEyk+nDBkS39`0|78Yp28l+!%!<*304UwWY~GgZ21$Wo z!7E7vfGfg<*|z~XK`N?DX;HipurR$QAMA>KiDlRS{q@0aBBaEzwy)0My@-8@Eo%+? zy^N3kF0l*II!bWz(}|npxU0hh%!5L;UXA1TpoceSKfQ0RgdGP$f1GQ>ACQ=iiOPTb zs>tv?h{=YwI>Zkz`K3Phg7n!XRJ>!6qbVtu*s{-$w_x$kTF_el8{w@sz}hy8Tw*_` zXfJw<@Q!2EPceuOfVnrnpD0LhgU9?<1hotgfVhPVxMpj+K}aloqnmF8cy8Hj*zJkU zd&c5k?rr4p7A`bSdzIL81%GVblgvh&UMkZc?@6?dUpV;{7xw9lUEl%tHl8@aGK$aJ zyS2E*oTmyJOx70(jN|VhY4WT*+GUZ!@Vsj|X{&?ipB5{WHMfFfr{Wz`vd)ddJJT*z z8H;!8ft!QV2=AKcN)IycX%TIeS%i0>2}|uBWd2_zIM3YD(+z$xF=#mRV*os`N;WuA z*$tkpS6p}Mr4h*8r|~i*2Aj8K%D$#O2=6OsT($4#!?mv1ye0PAs@}1nKi=kO9cys% z14`E)JAdH;x0al3aTvzu?GU*C^-hHMvm)cyn#nZG|D2T~UZgaJ=gqW)#yUzm*NXj} z|JkT`M|-aU6yDkKM>b>e{%P}Z9Wyc@@hezzlX>ss)hB2m1Coc1*vk0`?_l$5Y|A3DKzVj;r&Ku%pgdGC$F zTR?Tz$T>Oy2EUq>^fYmUNm@E^cxnJhO`prKyU`66m`|;~+GYgOd~eirgkpDZLC5*E zmyykhR5Z@Sv8H!)BX;+;)XTZ=F)>Yddv5}09fxu9YmiXRcabN6(RW>{r#|8HUfQ;~ zWGAxs);8=D#k3B8{&$v{UGTxFli_)H7}8cpeb4aPZBhT`e>$4-u~R|je*#qxI=jf- zf!u@0^S_Ol&O)pnBw-nC(uu4fr{41IU`FQu;gvgB4UrY(gvt|f?Z^PQUCm44_KX|s zKXC8rla~WPKx;+Nsorj28I>nmC1nVv10Db5s9Ry~|A$Vx$hGzm;3OJ%`hG2|{eA2m zB=7kTG(MC~(OnM;K??I$$-Kqi31pfgykk6NUzQ;&NcC422Zx8;;I)FChnIB>fE^;5 znGajL!GraJBO!W*Kyjt=TJVls;GzNTcI zP2PK3tr+px7vWucHJFR#Yyi9-=Czho=?2y9j&3^9I{;#@owFTnLf*Y)xo_eeVFXqm zPu6^W3VZ&y*z-ImZ!ZywqH*uv*QojRVDt8qmX|L5PJg^j(K@_v@{2UnH9NhG0LF!+ z4+;Fn=e@cp<4X#%_qHc4^VbF;{Q3X%RHyMHW*LU>-sO|D)$y`O_=pK|_V&O1f9$cF zZvG82|1YKLL21m@lawAL#HO(Xs|V@w=X*XydQeUMRcRKa2bmhIm#aZ~kWTUbc6PA< z=n!=$x_unkAgy6B-hXERgt3Zs_$=rFt82Fn=^Zlwqrd%LUv0F+od4~1s~J}g6W|CM zH?VAJacUFx3R2ZVrD$Ry{jDIa&^lCb^5Zkw5hvl!4N8^{M8Dz3UqN>ChI`l?uYy+$ z)jv(su>T)C$jx4{dJDt%Af|rW>hKiR=g=>myTtNS@jm~wbM6b$qLQLb^AXiT&afD5Nqw))m$^WJ!U{Vrz`0j8mG@zS2@HxjUU%M_;SepyR@yrt1Pq;T>Ze@lEy zxWx_Z7RS|n<-_M~WoqN=v#|==J>UIm@EiX8|2ApN|4%#P&;M=-wAE4mC&TE&+!v(I z@=@_VcS&yU1SvA_#4r7ev3M6&Djj%@@ct6wJ@m&r7Of)_C%@!*06ZM$2E=>2*9i*X^Db+0I0+EmBd$>m2DHropZT3~ z`SKaRdw0`VNBZdFRe$GyUMk)xZZ;{D#mN@#YE~@XyaWf8R)qKW8WA=!@4Jiat_2{x z?>d<)C>{%dDrr(OW%JzOk<};0eV+_~1xZ%~wtVjfA}J;Hdu9y)S{!SG4|U%W?YS&4t!Mz{zi!qwBj($mYbx)BGp2XyC1zAihks zp%QL4S237+L&N+Zv-v>xe3}0P^FM8Mw1j&-9Qu2D3z3R8Z<07J z*@5sTEe*&g@4Y3p{$$ldcsq0@-PS?&-hx9bZn(0zLw(l3ZlUG@5OuXNZeXw*M4$Ff zTq|t|E_d1ftaHHTJ!b#YC%vBlFQIW;=bc<&w;X%^U(jFoVDLQs@g7F&V8+QW-d}se z)o>o5xj&};8x4z-&GN=-0%?_SP4a`!+{^Lj|D(#s*k&hW8NPcz-AY>>UlL)busf++z5L?)Lv9(K`0vRyU2Sb_|fBvVnj_8v+{1`yuwR#n-YJm3$%#%=jv_|px>f4d&^{n`Mid==vxFVX|v z960lerCJ~SxSnWyWDhp)JA*o_ea4a7TWFk;Ma%5dY;4{dMX%?Vc+ns4O0*tK;C<UDyVk|Je#6n{@3z%dsS?BmEkY3PyA@BBWID2#l62P zNI@#z8Rs?3DZKMWKXGC4{*WzSS%>iE>uEJ1^M02X7toFH9@$)|RTkk77p;9_+=p~; zSNAp1&kF{?$zuU)7cT1o?e0}xB`@>=&#DpAH|p5DJ^90YZ;uinCmQ#9QT?ZF0oc5Q zj9v@>IZuDQUC}!Haq?3>BD#2KB{yh)9I)#v4ZKIw*&?D4-WTV4W(m?V|L;GdbgJn8 z!2C~Z9aE`hqJQWAWmLS=ExB(~co$Y&=fvX8xASmTJ;M9S+mmDD%?UI9#geTE@4X|> z&CWmahfWCxUhEx19!~U;FS$`N09a)r_W2QdK;0cv!z>j8kbH&^5b_+GcXeM=g(ULz z*0X5beU3xR>%_4Kq$LxIXH_8m@xG1L!G@Ec$B;v`D$>3AJ-eT33gItKINK9f$R4VK zr?xXU9HeFbuN(I3x%huz{;#F2j+xv?A4`+w7AFE!yf4U{j-l{w*yhWD#XElQhSQG` z-tuw5ab(_~e$Ky7emU`ocmY9cX#jLFI~pN0>IQY^e+vvN9{_wI!>2~rdqBopn~H}iL}-6Ai;IRqS$})|Nk1h z>E_=d^S>xn54!q&@g+(Rx@WE`fYpNtGS@?LkRGIX{j4f0(u3}3m~lNqdXS)VFaLsC zU-?|8GU>h{MT`?RA47XF3lER?jt*6UXmC8R{K*=7Voo`BPQ1o z-me$Td$kDRz2n)2@n(egdZ_v~=eIBX9CwGuqsk2m&N#(9j~@VP;+v(PgB~E-IguZ) zs}F8uZM{FNi+zc8SaG_$ijN5M&^Vin*!#Sx*t|D~KdYJdf&O^gp>-(YR|roR|D z-h$ZPIO<0O?=5Y|ofXO}Vdr|WRMQ8K@NaKT@bw&6Q^)wcX{>|WnB&UszpuB5Q1Q-= z2)IDueX6B}4~uuX#!Zz%gm(^?&M`9Ybyr@lCl5%kpQf+45By+rGwDosqZ_>QDO2up z@&I_WCF!({at}CsShFO`P9HG!Df(FckGr=ep4W?~*obiY%ilPj&cLJ7$FO;8wKjfj z`$>Pii_khWaPm9A(Weoczyo;u;?~Ma;&*RozV{BKG=C5V= z4bo~F>u~$fD#`ly_LeXe@5?$$%P739Sh9GrcsI>%lqo@YXBB^(ByUcva>%mmL3nq5 z6m4C7)(>)-cg5I$M2@$xQ0R0?8vyBPXIm#X_JE|$rN5q?(gz~iZPDfC*xma?wUO^P zCL&yp#vQk)+Lxn+&0F?U)od$){str`v<^v}{B+tj6a~EC0czeFR}$9Z^UgeS=i4@f zH-GGw>Q@kdbAl;rZ>g5sYKG^{luctDi+){6b>Jg^oM;6V?<}!5aTMNCZZ1SD-pgJX zti6r!j#PDuBlGqQio7_A@b>V&7+UXlQ=6M4A40v!iuz;pBJD^3OsQ zb{-&njQIN@4R>!}CWW|iA$xC5zQ5!nSK#meKmPOo*t_$1s=D@Z{71$zoMQ?hgp?^6 zN+k=)oFNp7D09ddN`|5$LrN+`At^;k88R(J1EnYxDk+B$MWtx++eiC6pY!{?zWdqd z{_mX6>wf;}x!uXC3T+q(2uY|2zLP%#8ov53#X^3(_bzNQFa}FU0CWC1-A*IEM6~8D2|=c}NecbE`Oe66rxNmzMj8AB}*k z@AO4)M!ti@QpYU>1`mVD3bhg~&wkLdXx*}Mc6*>4C6T{55W5F;C-92()(XOIHH1VvFGJ) zBFp3VAnC-NhdmcuX8IoFn?PS3(*ql)H|@`$JYwZ(co$c?xltdn>kt2uz~cQvTFfyM z;ca$*`omm=_qy~f>jH!~*G@yj{O1vHPJsRJcAjA9!sX6U96k&p&dbkl+|~~sM*6H? zC29`}_2(}*;)~6Dd!&MjLAf9-K;v$_PM0b@jLmy*?(UkV3C82?iq;Wv8AR}tQ)HCuSR6(iw|)aCUe=E2ae z{!nmQ)G(0DJonVhu^(*jno~ZcZ4dmvy{RAAi_QCrM7ZqnVnOJG#*tfFT}MN(dEa~Z z>iq_O##=#_pmj9kB9XyaervNXIe7%lRl@)qhnx&VuJ^0&ReauMF$YF7j(ynnI%SlEd0 z&J2G#$1^Pww%ri29>@rWx$+T$E^)))ZqQ5CiH-fBb=QjD-0sNjt;XBeopZ5ybGmL( z4$l{apU}AJr}VZqIQePzP05B1^Mi+@i{`hh;q(5oZcI`I z;a$OY(=WJ|j>8F?6Tm1ekLh2KMzE%{j=qyd3V*M+ETZ9EB+|8)%6q|54>2s>MRT>w z@)6!spT#aw&fciJkA7%a{x~TTerZvt(8xv>Cju@mB;?b$8jx4)J|~Ok zDt+G#gKmbibe06dh38b<3!H|**~LX)Y7+W^ldqSGxv?G4_PzIf_bcoklq}j}d#hIv zYN2s_S6+Ho)nY$llZX4?ELLH>9+ZgIk%W_9k^;NDN*F(|HwMHx()c}Sx83@wVU}um z?X-^$RKQFMqeE>Ik)@a+1UX}k%srxOEN7~-Y-oi7h&;!pAst? zkMOR4#lb=09kk=uw_t>Kvi;j5`%J^3JF8aPo%ew-u-8}Hd)qMBpCY6mAJY$(?seuJ zceMj+R^GU8OUC9cS#~|{P`4n|M&nYuS%)1nv3b|*J2q@+!+5+GpmkK^^yFdlC%v<@kp{LcIR-kuwc+}^qz$~CkWpSRwNPN%DDtKnhkW80)I;P2iNsw-Ho zmI*NZ{7-KkifnmV@yfH^dkGEiQk&5cD(@`i3~4Oh4^_t%jv%~QT$N z|NiZqH+-cdV1$QO{?>g#Ffr}AL$~)Z*s-l3Nj0P&)AQ91WXAUe6SJ{-_s+0- z2qWD)1C1L#$ad{kAU5ykZ?#TH7Be32S7;rbIQg-5f4JdmEdbo}l^<5?;PZ}lUwqFN zdA-Hj!ldUr&a`6w+EdrS-o0k-?ZwPLAceoAuMWsIMjo!8J)BUW;a$Qb*-GVIamPst zi+ARmgT1K;?{{-#n<-~+gkQQTsR-}s6RPptb`ek@QY2UALJ+k0@!`r7|6x$XHd=kz zuOB?-mpt6`%?{*{pAYox!R9^V{Y3eEiy+KG)^x5 z@Ak%~PO)%)aNwat$Tm8)^ ze-?zx(YW;oXC9tEh~0y_$KLIl37TfO`~N{`9WQY5+p?B_?8S0^khERUDCGwJJ4nA> zBH57ntKiRirCs@=_%}!i%eQ=V;$r?UNTauodr?PyKHQpJK`x`=U6EfupUPWbcz6jG z@5n!d;1Gm&`>#O`3hzbt>(-JG-Zil+R>d`h!6lLQiRW{6!RmRPk2y?+K__3$s^_`= z;QC}|F+157vy`b#_oJ-~~{eYxJXB{g(ZnhFU zIm=s>hWCwK3g4)_O;Rfruz26RSeUyT;eF}o`$ArXx1`MEmIVm!6cvf|Y0_>u-F1jd zkt-0I`+XWXV}bDYJo$d`WIy0`k132|w*x84Dw|YaVDonPDz=MnOb{MHptFm+Z_cMLNDgYWRcpJ~8_$_*L?JT(1cJ2@=60 z?$*W&1g7UrcO6RUN6_#8Q=#E~eI3s_D(@1lLyNI^*B2PwjzoC-iF+7QcrQqibX7oj z&$CWBBNw_G_K67`i?RrW_P;MFuCf^hIU2#f6Y2fH_=b9bd4wJKIJJFwQylhyRBas+ zNJe;%qH#fHZhJIrVle02Kek8Dog8C4-Z#)Xe&gi#R(B>UE{Y%UJkYux#D_oskKSA- zxjmx_7H%ol&sd5-{}VKaH#APqXa3#W<@D8YSLdR|*^9H?TbYJ;InTl|DsPgtojexr zNbel^eF*Om4)vFm!wH^C)5VU5*4ID0FquggER?g8enJ$3H0ofA5_fRMrTyqgI0)v@=w_0dQF zzWhu{N5C==ev9u5Ng%Kdu#f^;Eb>? zN4_nnYCrhI<_cJS3?I ze&Ffynp+Rx^UhdpMp7)QgmosJuPVOb4@iN37UW#z9ASFi?sV4iq))~m=TznB~V`{d5- z?9v(r4TWvI8WqULTPle$dmkaYw;#_-ijQOS=5cVyIpZq?m!ok9&vC3B_%Gf2;XT`D zAvui4dmdUxD^7k-!c_aBZu0}p;4;?$M||Gao;qCq2yavQGO^KYI=XkPbb0uzDCWN) z9ZzQ+3J0#p{q5fBG`w$We%nFiUDFw*jKw>-+mYmp@D@|xSE1#7;ugR2mU&@Nf#u^R zv&;ZE$3xo4Y4tFOZOSb5zuFHJ?2i{1T(bp^E%MiSpJDSp^Of|v`IjKvjK-~DW64pH z!S3G4n?JU(sWKk#9JG!koc!F@Mvnem!w&|!>uwFE;q!iEy<RslTD}W{WdY!s6ZW{ELD=!uwsG`vc11 zL`ppWBmvppdbGdD`|#Q@cts|A?d5j?ut{BM|CsJDART`6F{QX4z|O_rIqGeJ(`Uuc ztL|d+KIu9o_*QbYSn^PSu^QbK1aoyfe@`zTxEOx+kE>eg?U{b-`Hp zPZ2(Et)a4WXOOcu&CIZ$*Vg0T-ilj%guQD2F{bBzp3XX~p6~iunDp=G{~3GmN3%ob z|J5`-=yq*=4Ydb(&gEQz)q~!O?8x7U^q@4BBl8829;CBFM_wE0L6c?E>GSS|K%Nhe zH*awEg+;fczj%ub1GC-IH$J`W2X+I`XYw32f>h0|!8^aWK&-!`GUL!i+|LAIG8#A5 z3Ixn`uzQe^d~f60ith|}{!gs~FTZo^T!<6O{D5U&{2_glFSzqO_wvwRY)dNO&*a+& zCvxdnL7o-cv3jvA)At}kKAm;^{!**+cLlkMhWD-1?K)K68oceASiH~0KS{7hc%O)N zyUCC6&Tu}yPaNSrCpY!W>klDNFZfRGaJMfcp6lw#6(0slg1<_0o+B&Bz+RWwpp8KD znYGp)_HCHFqaQ9Ib-omYYG~ZUql0zq^Ramw^1_RSWX9u7tz#Wde$IoJTI}AFzy^I$ zTkj}*-lQAu?SfA#pk5tU6o)VV{6Doo>6B;dY3AoGL0=u)GAl|&kI$|kwP|=addEvq zdBg+z|}xt_x3y)(%2u`$BCM8&{8qO}RP+Y_E>%jI4=$^5+O zt>gH@M8&_|dnFBTxJV$A%3F*zKpl&>D_^+d7KHZ=%^4O7?+%MQmiG|e!cQ;8E$|J6 z$GXz92mSouE_b;F(sIK<+jQ=mM-TdeK-Y7zBuiWH{8{g=MFrRc5}W(RcRmh6uoI0F z+OBbar~-TbujQPsD|pFxyjjsY@bWXW&Av)NE+<|%RMdO32cNg&Rzkhsib^P75OX5$ z5B}{f!W;9v@i{!q&zsIVBz`2578cER?-ew>>%aJ)qVhJ-&{>YfJ4Z8Wg$u&Fr{>9d z%Gq1w_5B&`2yYgd)|u6bq3~n9%~Z<^KiK`U-)!HKVK9=^bXor{^64$V+g(?7*n-ub zuk#k4!{*&?^>$O2lMvKK;}jzM1H@vnd6y;o3vh5U-u(X~DTzcZ2!CI;oHK zAAjNV_Me4OlOONHI_vf?Brqo{GSSWIGwzCz-25VGT8#_zp;YC+D@a`$-uHGp)Ked^rTuqSWAT1Xc=6R3 z;r)T@Lj;94`}4A?0|@WY?XT~c3WdP&O%8TfLcC$*!WceI&S3yp^Yk;v`vK=&-|&u) zHejXD`U`W?u(!8PC%h|?t`LMP(6}d4E3h#dT%6Pmp(K_bho$G(9l0NhU2dmo9TE30IykbW8U>!E^-T7`=Hc$|nqH#P&`aEq)v3bjHf~Sc~ z7;k$k6suoam5@tUjtwY26j-bqc-v7t9a)&k+Z@#Mf9~KC2w#oyKD2Ee2!UqGl zA-lIG-MtEV$susw;x$S8kNH5j*QiX1I1F0OS!!+?><7fB$Ooe}HUge#-JgCxv3Wmq zt8-h}CJ5)DacY$wZRuCBdDq>NGpTfCJl+q`I_h!qn|X24L#d1e`t-{)vS#pkgZTdY z#t3hn+0c)zP7?FIxQf+gsMq@NW7bWJm4ZC6AV`#NzE2 zA#>jf;VoeHC78lHF(y*c65(y*A)S5hLI|`}ex_+Q;R7e{ZwW9F90oles_~28_Jg#< zo4cnCHUfFo7q|9(z~&wMPQ2@JyC9TB<4i|(R_*o0=B-s}lKCx>@p#9eb>QVkJ}13L zXN&~&_4_$g6!7PN7S;g&5`_wQ=0nfI@p1gaiLI5!u^$hLGX3Jju$sO)a&LE^SsM25 z{LfHxK2|cw{BKCpgB~^BIZmDbcdrcL!0JJU>mqNhLVD2JXY;lRBR#0_((jTe#gOaOZzB zgRehy<*&o98CL#JPvd{Y?!ere7cQ zw1^#xHz|LWunxl8-N%xT!aH-IWu6McyW5@1;H`TQ)ZW?|x>>;k>WzrX)P5NP$-FM< zja+2FrIT3UGH4A>ZWB&zvBTy~oGZ}Q$d9~13XLoOa5>WQEH-Z&@_5?UaK_`!gVwPL zC%=s?#Xs}7N#Jv&P@sAuK5yR*NjaVf@1h+873^&I0}>(di$bI9O{V8f2&S)&`x)9N zdV*$8kPK*eKeWmbr1BQl{>6&L+ehT2moCCPz`?pf2;sf?PW!%12=A27`z{k|gP^AT zn{TR39x(Nu|F>P=hd_B-xP&wt8K^j~AVvPR1`p;po2~Z1<}Lj&Sa`1#@_Gw2E-p5< zqUgW8Af0viWa!*WjK^CNt%D0EKbbpTb7Ya-+pSL~`!et0^ZxNxPvm3Bb=aED?K?LN zpZA42|G29L%b9-u2MzSq@k}K8!}m2ODBs?qPs96xT@5>xclHfdOy0vE$F}Mry!~G_ z?WOR3bo+s2GQxZAQ?7(R(!o$OIr30ngeSbd{~+&)A48yK(H!D(0vYuE+P9Zg*#;11 zzV`V&!sadR@m@1jR}lXB^EWPDV_C4?b?ok~HoE&<+!*8W7DemO#L4fuy4l*VS|m^} zaW>`HI6m*!CGDlBL$5=U)D+Kn8y&m16*2EL2UVG#H{m9Ibu^L>pKgy$rtsFI;ob5o zPmRjk#VeHst9yriez$lX!rNhv=t2r_Dbc7-R%G|qwN!%bdP6X*F1qvSMZOnQAKP(o z?#vKKI%&|A{R8=WOM4Fc(qlHjPxSfg)~ncOZx8Y#)MfZ*h&T0;!S&?wg8rrm5g>Zynzs8h;%*dpqy(nqV=3KmQ*a`P^K) zM}+AYC(@(z)v=PN{ku-azwr?m{Nx53{v^g4^$r1VgEN($vScu`=cA0D zmo-SA*K2j|#1_o?Kj-H*RXssLn1aTcFYDd9ZwUJlySF_h(7NF(!_EI$XdN*)`57!f zl{jw?3G|u=1&p2jgggJQyr%WlwyO+AT%FlFRY%7S(vGYzvZ2yU--8JB)^Yblq3YlB ze-j$sPrbB1QF%Mx5aY(;{rK~w^>T!_OSMZXg?Db!i-(~I@1DvqH&Ojvuv|c??taR4 zNYI^9x%hSn++Ox(YK0UTY`yf>Xn(#nm>D=(`gT3`3eqjQaE`TtApC*GeR=fqd2%H7 zBX)56^ku`ZjK|vrtz!fyzg53P_9iYTfm`KLyygbuxV$CA2gb!WT!VcP1SyGbI!=)0 zBxEGF6*E6?R{H7?8Ay9`5BZ86q~;Kq#^2#P(grJK$;dLLPyEA&_UjU-RbzGT6|xCQPcq8uamYjK125 z&HM1EEIDh9Abg3&JxFd7srSL=ePo>YvQe4w2BZYEjx?P7SY(Gz~{E&INTP!~B z74z8Vg=>_<+mh}}7Ej@?AnU(^W1UItOg|tEP10A#3$;svArc2Dyp3phcaZ$vQ+aRW zY2w1-&Hd-2lNQ4JnAO=|v%9yiUa?Ogyki1AdnR55!jWsna*cBCuyj*_%;BLS(Azt* z>dJgFP)(@Fi5Rd3?Q46t>epfO-r}G#;bbcaAEI$*`!4Tn`7bXgelPR9(%qNwcsrnV zjNs&F)WzR$s+$0Tkml;ZRL?jg130>azneN)DmB0g_I)5UD-wv)_%{@+Yz9k0gh zzx`dDtf%4q_|cy-D(~8p2RN~KCni5VuoB_j>!4do%R6r*%ANgXAT&Jure&FuJJjIb zXW=}GEKU@U-yG#9gO=W;nLiJ#fkOV4{CoScd0%c>p7w280Lr0pkm>2Fw_5u>Ohq%wVRb6kBHaf3-CKh2hO=G@JOj=hZ1Kqd{r7*2_BVh$Vl8QUP*1Y)U1|@C zWdj0OJ*YUyS8_4ZgNkj&R78;#q~zgBXI^BBU9CZ}yg$bqHfNdXymj6Ry$TYaWjz`K z9~OrGu3bR}!4FTRSdLl&SI>wfeIxAoe{S5!C})WP+=|9^1uA8e&SLkVrKufahp&BM zxcQ$8twRYXKf9EB_Pe){z}<+!wZf~$a0etGcl$O0+bgibQE3miJpO%#;4MFVreg>Q>3wwJ&>(}!wyVD{@K}Sq1H4~5?Xh{+m?+&l zb4vi`pm9a#3ZhASv3XCHKY7OYp7D5BqjgN-i8D-S)dw`}0%yfyiM;Pe0V*5P4%7k#~j1r6^mb;Tko@7M`45sUYU$L$$Q5#B8i zRW4I_KbX;TjzxG&cRE$xTC@|IbcMEmt=a}NG<$cJbPj<)?Y?Y-Wn{2&bR|Nh3)j;4@jHS z@P08zu$IbuYfCX77VleC9DYg&Z)FcNPYUl?uEN~{2=5>2>jXlY{b1P+CAIU&>nl?X z-|%O>7y>UZ{;4TcB7?;ZzIUz#TLaEV!zygMv3Y-0?c(44Q2@?C8m3)+3`fm-r38EW;DE?weIVq@-~)<=EdTjA^jv=1>t@B4|xHFx1!Yf zy~+r0%ajbSOMCp`Nc^Z_n3o$oRMOlz(K7@*RjUf)7094I`aSz2TWc`)Tn~r#G3>>O z*qToZPY?tl8yXj__d3Z?4100Hx@Y6$ha|@1ErQm;fs^0+Q0~gLfCMVuzE5lT2fVBH zzS+EZ3;y<29f$(qR?Po;OJO?e=sUw&b7t?q^FO1F`v1>-kon)1rU&(9gwCP%pj%vq zqF6mBea)FRNu&qWc4h{MAw6g?k|n_lxr4OpYwu0lSKFbP_Q;Hhnmr6XY;Sz1aR>}q zPQ?8&CIj25+@nnoErHAN@mnoUPVoPk6Y@hA39SQ`%aHjWjf=Uy`km}i>>ji~I?+-o z_cO!I|I|7T;p7)!TNoc|LIUn033*XxMsQbe)g z{Hu)k%q%)yZ?Pn1-3jAWJzUg=un|FHSd)j$fZax?SMrT;EjaHMvH2G#8N2?WRdf2|Z-vWF7Pde&eJ(Vc{ zAsXlOQqhOpgU$QVF712Eq8X2OB3ef~PJRhX4{c3TAb|%yLP|3AqqyC>C0M=Hnp^^> zy=!X1rt#0-2wpCpU875xzIzkA>8nHNbrjzXgF~Vb)2NbL{Tgt^F1k;mrBg7@ekjxbXzL zMLNBq%>NxE1Y7#*Aelc*TmSbfb~n@T9@wJxo65WK+Oz}~Z?9ZsUQvYi&TUyX6yEus zTq>s!-iDWFUJ2da2G!f9&ON(j0|iK%e%MzI0oGS**!=9sprLr=CSQvs;7yq-s$Y%G z`~5pbo-r8#$cM(+Ujc7y-->f?4CHdiO*a4 zb%4F$vSJutM=XEujL&=f4L%m#=i|)(h`ml<9XAE0yl0Ni4oI75c$0~SGF0BDGn>S* zc=sLiHxNU3t1et9OX2;i_y@R!@b+DuH7X_L21|CI^HwF}os7pj0Zqg}wDTgfM+@1)IYF#L zcC|y`idW+y+Z~0Vi_gT(V zfa$w8@j88VZ1Pzlyn6TS`M(_v@3-ZxzEs|Bzud*Jc;~-9s3(E&jv-}Urtn^&KBjUS z>E5e#ST6^Sxj_YD&i7QJ9qd?o?*7MmWO34Hrm1L72A-WQ>EV|wf$(75g6rF`c^6iT zBsK{PKtVLFg8jv1(tYgtf5K9oThyEJcvI_`#K~{b^EF}5NhBa0Yb4LP5dUz(_Taso z%L^~TgoLdN#OV2O;*+a=GZD;xy@l|UzBDJZW`!0LdOd7 zo&}lz=ozMe#1ih)SBJAq{I~8)vjfsr8r~l)a<@}?6ZwBH!s0D{#nDj!;eDp&v3Fe;F2dXI=eeo=t9G#9){Evy7ZbSbo9)u2my!4Xy_$RYj~f{XE%(}x=d%Gk4DoO& zk;Hz)a;;wBxI~E`wxV(TY~i{nA{5;MRCv1zLyN=-FT|M|KNJ3%{vDsFX`7cN((O1WO>(Ww=zr455@E+kl^q&J# zY1;-FEZ#9qEC&S<-Z$Qs{GrVMAV~IUC$fU9^C^4YT)GL0N6$RA(ldi|`}nFIONT&O zp^n_{V+yo^O{g zwFKH1hYqOzm&=KIK*v32fFG_z<0d?oeA6$*=G~klw?pVA$r!LpEK(xG0$3l zu*;yuel_=d-0t18Vz&*bFM>AidIzke=(wEd&gqw?z{&h;@9lKfap{ea3Ua;W-}8U! zw8p@HB0Xq3O%M9)_r-(yh#i-cQpD;(kHq~ec#s}s_KrtV0_j1MV+w*!Y8rZrwx!+; zykZ1ZhDa)ATn6y2f1hT{*&$FiZ$hhn7a5$$TIb;W-5mUR^gPV`fCI$(n;9BEY`$s( z3I0Umx?)W){@};%K_49V3x7%f$Z+%j7+S|9PJTr?!>mCr{J?9kjmWk8Z*hCjkEE(P zXQg~7YUVQk^#?k7&{Un8VXPeU_aJ)fI6PfV=|Ko@HyYj(t5fe%c^`f|ump?u&)fFC zya?~`Yx{pu=6}btQPJxV-WTTjN{ob=Lb-?|LTp6_kR>22_h|kQnBf}aJ>^dZqT7xP zn7CPhAQ8imnzh*5TLUgPAMf8yf&pk;`?mI$L*3ZCO+4k1x2Sw#INl>@9UF1-i_VKF zjFsdETT;D8MsB~u<$W}ue!GNB0hCm&Y29+2j``nmYxeEm%>VTk1Ul!#;#~&W*@FBc4Rxf)&;qA~9E3+8k{Y(2^p?r-6G`5b|kh*Oh zoJ&p!ay&N#N*sA=19y^v;F^<3VQCg%Fy`xYg9A42=Nnc}^W>4>J2bA=xlN9>4V$-c zG)GI$A;#m~gVrI1lV5(W~R zKE_N5jTgY)@q}%+`sjH7e`TT7r5()wf^1uz7>*sL1RQ5-ddHY;z~R`|ZQ#t?n!yP_l~gcpIQ~XyN21 zB2ZSy+0PG_DRH(f^}s)Si;cNe!1AgP9-gy1*J3gL;>7G!%4b#445nXux6@h2yY{y) za**!*@BEK7-7?V6kpanzrUy-J?mkNGLC&Q-YFIt!=pxyF!uaU zR`!qAALoOg(KyYT1rnT(v3t;@jSb6Z-BE@ckUpVx{KUymR)RZs2T6(eE68VpR~GHc&SUx>BrHr{9l~{_Z0*F^6{IH(@9)~vI#k|U z)n2M%@jk-(^CpG&g23Jj6yBG40VR8;%(g_?lTYJ-B@gVh{Br~bE#GY;VrCR?C}1X4)lvZ zbZgTOJ(!&S)uSV82%O`JDya@514+|uw^P#00YPT;vu6x8?~=!QY!`Bg@DK8pL6o?s z_A74X9l_>3c0n^3DvvQ-_pU_i_==O?ZUrl^==1!bRgAwq?i@bvqKmhsD*5xEpOYka zo(BF3vhu8z$Ivw)rl0?V^XaQY>B^zrvj=9ow>u5*uWdhusk{$H#VKR)?mSg2&5iK> z{ocld!u#&QyNP>{?X8HXSqcf725{#Rd-!0UKHTU(*Et|(2sGQWU%wYZ2G{-KKfY}= z2fsD?bp#8sdE4%pUv2S&2!Ek*t=T7vUZi02R?}h?F}lKdyq(cHR^sI6u*WOd>#`W2sd+4`4J-2!>=mDEZH9ya_>ZxP-;)%EMV!u03=gm?7SacHCW%59CaySF=N zcz-z~MyB%KEM%pG#anQL`5=Y2toSE=3U3p6;`C00xAW<5J8Df0p+nryuKZYiC>Tjx z!gpo}#2>oG`!t9Q!mF*lWV_5kK~v`@pCoMF_6zqEmCKRfSv0P2(e5AhhSKb}NCI|YK6^H|_w?CGb1n9&4EL$5L(uV+XL1M5-92u-%yZk5n zVl$u~;$H48z8PXAc18GngOd&~)Ij4L$AdI~Hei1SsV0OovV?Pl;Z~5fXdMtIKih*g z_ZEzjz`=|kp%$CFaR(&Bp71ZjGnw$Iw)^d}Rytm>6S=!tQS<-67JCGpbr2WNDE~eG z-$}#!xAd1RD({6G+cmLxE9~EKg~Gcwuy8qrcd_wlk8FfDna$)%7CSqbI#fb7Gth^` z%u|o{9z#};PcL7ri6Mh{ww=$H?=b^x%SKLKEXL-|+O#)&X(lhE#?{D*T!34!AF*b& zD^tIOGahduT8A}Gehpl1mlTUgK!Uwv--Ay*xV*bpK0NSf`)T-U_bJ)9-}sMMf^YRr zLU;kwKVoBj=&PeW-kG%J@9QmmX?XwqaOpqWTOA2!G_ZJU#?%>bBD~YzEnYz3{c>f% z-u(#g!!e2%j$5!ot|OOn9r*O&g^zElOOFqM1z)D$nnxom$V=pBq;qD#WzEr3uOK#W zi(eJ%2gZ3JHBRD++2^K>*u3=;FI0aSWjx*vXdOm4`Q=I<-|F!m+1?uPA_vTQh0DAC zO9{@+Sx9aj5SUo%OX9guuzc>k!s!ba`hdWS>Q zv3RGc9vGnT&YfOIpztnP(UaqD4LqJbMzpf?< zc{!2%TA}G@W*|&F!fVw>Y~G%q?}@Z*;Dfu-xPAO&<76*v-kV8X-JxC|7;bSAjMm|d zliwe0cEboIeoz}G`snI)eBN_(_4@81ynj#ZoA+~+j?0NlQoz%Qc1w~`iUDVu{V&kSe~hduwNpD7fqKf?#9aZ*1wG@oR{ z{&3>d(5?#A4#wl1i`MZ6CqFKUobw6&Bw+5>(_*y07q@$xeEq7-eK`jnF;y}jsKnpB zB?LroPwDwTaQ8NlzB-az`}Tgy{&)Vznr#{C=g9mY^glgFnQi^9*+=a1{-vIx5zYjx z9`p!Yj%7u9kX=-2J>?PmAz9jNk%oreyW6Y!wI)`9h=)a9UN;S3=G(+Y5y?ZKysEZ! z>>wG4gpO|XI&2Dn%EG2x0qjTYDzA{+@58vEE*kge);`N$|7AdeKh{0A8=9{lKd5Y-=q$_mR zVUeyEuK4!`X&?=6R*A;*)JN>v(1)urc|YC3%7*YZa9Vht!uxIY*9$xd@4O9;&AU=o z0GT-Bj^BX>uzXxvcyr1S_;#gPy+45roT|obKj)i*bl)HH{p{GhkNnw@9^SzXsc{99 z+f;QFu~(46gu;0y8-^H;cNSVlBu;+txTRivBnf!xzqYqie2&Ze_N&r)PiNBM8IH*O zO?13sC-!{(L?9>gUvG&mqOXoMpN0#+MOB$uQkj#Md3Z@oZw91eQ)Y_ay`QPfPYJS zmWn(G3V!sK?}R>lVdw z|EF^H99TW*+rrn6SdbnR7Ns|LA<~1^E_rfe7cwASvk95cQfLBt$26Y3yt*D9QG}wa z5{E$kW_#sFNo0_1Vm)}(-2`+A`m8SPw1-$}ZQqp?z_(&9e1^u2pHVvtHemOl6I%MK z3S9>n?h)&c){%{q-}|kLY%d1#gBZfYxUkZ8+#aO5?M*AU(?Mu$xlh)Fj#un#Kej{5 z`fU=^_n_$G^wp81dsC$(adrh6M#FpV0?P_2@6e&e>{z^Q<4-J^gYecC-~EH~h-qgRi5Ra-wn_xV(j1 zLio9z4?-(3=p!UU#|ctwptp|KPK#FjT|tJ@@aF8yw7SNvE$MHIWRKHmiP8 zZZ!dI$HV8x*loh>-d&#t6FT0_g%8j;$2*?JD_XI6yH>w5&|5UfaNTd#lcE0SuE$$%;a`xB{XR0KCn&@8=l=vc>(J>qYO&

- emergency_handler.launch.xml... + mrm_handler.launch.xml...
diff --git a/system/emergency_handler/CMakeLists.txt b/system/emergency_handler/CMakeLists.txt deleted file mode 100644 index 0475cdbe57dd8..0000000000000 --- a/system/emergency_handler/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(emergency_handler) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/emergency_handler/emergency_handler_core.cpp -) - -rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "EmergencyHandler" - EXECUTABLE ${PROJECT_NAME}_node - EXECUTOR MultiThreadedExecutor -) - -ament_auto_package(INSTALL_TO_SHARE - launch - config -) diff --git a/system/emergency_handler/README.md b/system/emergency_handler/README.md deleted file mode 100644 index f34ebcf8d9b9a..0000000000000 --- a/system/emergency_handler/README.md +++ /dev/null @@ -1,42 +0,0 @@ -# emergency_handler - -## Purpose - -Emergency Handler is a node to select proper MRM from from system failure state contained in HazardStatus. - -## Inner-workings / Algorithms - -### State Transitions - -![fail-safe-state](image/fail-safe-state.drawio.svg) - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| ----------------------------------------- | ------------------------------------------------ | ----------------------------------------------------------------------------- | -| `/system/emergency/hazard_status` | `autoware_system_msgs::msg::HazardStatusStamped` | Used to select proper MRM from system failure state contained in HazardStatus | -| `/control/vehicle_cmd` | `autoware_control_msgs::msg::Control` | Used as reference when generate Emergency Control Command | -| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Used to decide whether vehicle is stopped or not | -| `/vehicle/status/control_mode` | `autoware_vehicle_msgs::msg::ControlModeReport` | Used to check vehicle mode: autonomous or manual | -| `/system/api/mrm/comfortable_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM comfortable stop operation is available | -| `/system/api/mrm/emergency_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM emergency stop operation is available | - -### Output - -| Name | Type | Description | -| ------------------------------------------ | ------------------------------------------------- | ----------------------------------------------------- | -| `/system/emergency/shift_cmd` | `autoware_vehicle_msgs::msg::GearCommand` | Required to execute proper MRM (send gear cmd) | -| `/system/emergency/hazard_cmd` | `autoware_vehicle_msgs::msg::HazardLightsCommand` | Required to execute proper MRM (send turn signal cmd) | -| `/api/fail_safe/mrm_state` | `autoware_adapi_v1_msgs::msg::MrmState` | Inform MRM execution state and selected MRM behavior | -| `/system/api/mrm/comfortable_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM comfortable stop | -| `/system/api/mrm/emergency_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM emergency stop | - -## Parameters - -{{ json_to_markdown("system/emergency_handler/schema/emergency_handler.schema.json") }} - -## Assumptions / Known limits - -TBD. diff --git a/system/emergency_handler/config/emergency_handler.param.yaml b/system/emergency_handler/config/emergency_handler.param.yaml deleted file mode 100644 index 2309e7f23deb0..0000000000000 --- a/system/emergency_handler/config/emergency_handler.param.yaml +++ /dev/null @@ -1,12 +0,0 @@ -# Default configuration for emergency handler ---- -/**: - ros__parameters: - update_rate: 10 - timeout_hazard_status: 0.5 - use_parking_after_stopped: false - use_comfortable_stop: false - - # setting whether to turn hazard lamp on for each situation - turning_hazard_on: - emergency: true diff --git a/system/emergency_handler/image/fail-safe-state.drawio.svg b/system/emergency_handler/image/fail-safe-state.drawio.svg deleted file mode 100644 index a9cbb1026616b..0000000000000 --- a/system/emergency_handler/image/fail-safe-state.drawio.svg +++ /dev/null @@ -1,239 +0,0 @@ - - - - - - - - - - - - -
-
-
- Normal -
-
-
-
- Normal -
-
- - - - - - - Emergency - - - - - -
-
-
- OverrideRequesting -
-
-
-
- OverrideRequesting -
-
- - - - - - - -
-
-
- MrmOperating -
-
-
-
- MrmOperating -
-
- - - - - - - - -
-
-
- MrmFailed -
-
-
-
- MrmFailed -
-
- - - - - - -
-
-
- MrmSucceeded -
-
-
-
- MrmSucceeded -
-
- - - - - -
-
-
- no reaction -
-
-
-
- no reaction -
-
- - - -
-
-
- failure -
-
-
-
- failure -
-
- - - -
-
-
- warning -
-
-
-
- warning -
-
- - - -
-
-
- emergency -
-
-
-
- emergency -
-
- - - -
-
-
- recovery -
-
-
-
- recovery -
-
- - - -
-
-
- success -
-
-
-
- success -
-
- - - -
-
-
fatal
-
-
-
- fatal -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp deleted file mode 100644 index b77797b2a4205..0000000000000 --- a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp +++ /dev/null @@ -1,143 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ -#define EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ - -// Core -#include -#include - -// Autoware -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -// ROS 2 core -#include -#include - -#include -#include - -struct HazardLampPolicy -{ - bool emergency; -}; - -struct Param -{ - int update_rate; - double timeout_hazard_status; - bool use_parking_after_stopped; - bool use_comfortable_stop; - HazardLampPolicy turning_hazard_on{}; -}; - -class EmergencyHandler : public rclcpp::Node -{ -public: - explicit EmergencyHandler(const rclcpp::NodeOptions & options); - -private: - // Subscribers with callback - rclcpp::Subscription::SharedPtr - sub_hazard_status_stamped_; - rclcpp::Subscription::SharedPtr sub_prev_control_command_; - // Subscribers without callback - autoware::universe_utils::InterProcessPollingSubscriber sub_odom_{ - this, "~/input/odometry"}; - autoware::universe_utils::InterProcessPollingSubscriber< - autoware_vehicle_msgs::msg::ControlModeReport> - sub_control_mode_{this, "~/input/control_mode"}; - autoware::universe_utils::InterProcessPollingSubscriber - sub_mrm_comfortable_stop_status_{this, "~/input/mrm/comfortable_stop/status"}; - autoware::universe_utils::InterProcessPollingSubscriber - sub_mrm_emergency_stop_status_{this, "~/input/mrm/emergency_stop/status"}; - - autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_stamped_; - autoware_control_msgs::msg::Control::ConstSharedPtr prev_control_command_; - - void onHazardStatusStamped( - const autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg); - void onPrevControlCommand(const autoware_control_msgs::msg::Control::ConstSharedPtr msg); - - // Publisher - rclcpp::Publisher::SharedPtr pub_control_command_; - - // rclcpp::Publisher::SharedPtr pub_shift_; - // rclcpp::Publisher::SharedPtr pub_turn_signal_; - rclcpp::Publisher::SharedPtr pub_hazard_cmd_; - rclcpp::Publisher::SharedPtr pub_gear_cmd_; - - autoware_vehicle_msgs::msg::HazardLightsCommand createHazardCmdMsg(); - autoware_vehicle_msgs::msg::GearCommand createGearCmdMsg(); - void publishControlCommands(); - - rclcpp::Publisher::SharedPtr pub_mrm_state_; - - autoware_adapi_v1_msgs::msg::MrmState mrm_state_; - void publishMrmState(); - - // Clients - rclcpp::CallbackGroup::SharedPtr client_mrm_comfortable_stop_group_; - rclcpp::Client::SharedPtr client_mrm_comfortable_stop_; - rclcpp::CallbackGroup::SharedPtr client_mrm_emergency_stop_group_; - rclcpp::Client::SharedPtr client_mrm_emergency_stop_; - - void callMrmBehavior( - const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const; - void cancelMrmBehavior( - const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const; - void logMrmCallingResult( - const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior, - bool is_call) const; - - // Timer - rclcpp::TimerBase::SharedPtr timer_; - - // Parameters - Param param_; - - bool isDataReady(); - void onTimer(); - - // Heartbeat - rclcpp::Time stamp_hazard_status_; - bool is_hazard_status_timeout_; - void checkHazardStatusTimeout(); - - // Algorithm - uint8_t last_gear_command_{autoware_vehicle_msgs::msg::GearCommand::DRIVE}; - void transitionTo(const int new_state); - void updateMrmState(); - void operateMrm(); - autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior(); - - bool isAutonomous(); - bool isDrivingBackwards(); - bool isEmergency(); - bool isStopped(); - bool isComfortableStopStatusAvailable(); - bool isEmergencyStopStatusAvailable(); -}; - -#endif // EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ diff --git a/system/emergency_handler/launch/emergency_handler.launch.xml b/system/emergency_handler/launch/emergency_handler.launch.xml deleted file mode 100644 index 203c13bd94e0a..0000000000000 --- a/system/emergency_handler/launch/emergency_handler.launch.xml +++ /dev/null @@ -1,35 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/system/emergency_handler/package.xml b/system/emergency_handler/package.xml deleted file mode 100644 index e16c1b60a5be0..0000000000000 --- a/system/emergency_handler/package.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - emergency_handler - 0.1.0 - The emergency_handler ROS 2 package - Makoto Kurihara - Ryuta Kambe - Tetsuhiro Kawaguchi - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - autoware_adapi_v1_msgs - autoware_control_msgs - autoware_system_msgs - autoware_universe_utils - autoware_vehicle_msgs - nav_msgs - rclcpp - rclcpp_components - tier4_system_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/system/emergency_handler/schema/emergency_handler.schema.json b/system/emergency_handler/schema/emergency_handler.schema.json deleted file mode 100644 index 3276ae3fa1553..0000000000000 --- a/system/emergency_handler/schema/emergency_handler.schema.json +++ /dev/null @@ -1,65 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for emergency handler", - "type": "object", - "definitions": { - "emergency_handler": { - "type": "object", - "properties": { - "update_rate": { - "type": "integer", - "description": "Timer callback period.", - "default": 10 - }, - "timeout_hazard_status": { - "type": "number", - "description": "If the input `hazard_status` topic cannot be received for more than `timeout_hazard_status`, vehicle will make an emergency stop.", - "default": 0.5 - }, - "use_parking_after_stopped": { - "type": "boolean", - "description": "If this parameter is true, it will publish PARKING shift command.", - "default": "false" - }, - "use_comfortable_stop": { - "type": "boolean", - "description": "If this parameter is true, operate comfortable stop when latent faults occur.", - "default": "false" - }, - "turning_hazard_on": { - "type": "object", - "properties": { - "emergency": { - "type": "boolean", - "description": "If this parameter is true, hazard lamps will be turned on during emergency state.", - "default": "true" - } - }, - "required": ["emergency"] - } - }, - "required": [ - "update_rate", - "timeout_hazard_status", - "use_parking_after_stopped", - "use_comfortable_stop", - "turning_hazard_on" - ], - "additionalProperties": false - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/emergency_handler" - } - }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false -} diff --git a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp deleted file mode 100644 index b2ee12afc9c76..0000000000000 --- a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp +++ /dev/null @@ -1,451 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "emergency_handler/emergency_handler_core.hpp" - -#include -#include -#include - -EmergencyHandler::EmergencyHandler(const rclcpp::NodeOptions & options) -: Node("emergency_handler", options) -{ - // Parameter - param_.update_rate = declare_parameter("update_rate"); - param_.timeout_hazard_status = declare_parameter("timeout_hazard_status"); - param_.use_parking_after_stopped = declare_parameter("use_parking_after_stopped"); - param_.use_comfortable_stop = declare_parameter("use_comfortable_stop"); - param_.turning_hazard_on.emergency = declare_parameter("turning_hazard_on.emergency"); - - using std::placeholders::_1; - - // Subscribers with callback - sub_hazard_status_stamped_ = create_subscription( - "~/input/hazard_status", rclcpp::QoS{1}, - std::bind(&EmergencyHandler::onHazardStatusStamped, this, _1)); - sub_prev_control_command_ = create_subscription( - "~/input/prev_control_command", rclcpp::QoS{1}, - std::bind(&EmergencyHandler::onPrevControlCommand, this, _1)); - - // Publisher - pub_control_command_ = create_publisher( - "~/output/control_command", rclcpp::QoS{1}); - pub_hazard_cmd_ = create_publisher( - "~/output/hazard", rclcpp::QoS{1}); - pub_gear_cmd_ = - create_publisher("~/output/gear", rclcpp::QoS{1}); - pub_mrm_state_ = - create_publisher("~/output/mrm/state", rclcpp::QoS{1}); - - // Clients - client_mrm_comfortable_stop_group_ = - create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - client_mrm_comfortable_stop_ = create_client( - "~/output/mrm/comfortable_stop/operate", rmw_qos_profile_services_default, - client_mrm_comfortable_stop_group_); - client_mrm_emergency_stop_group_ = - create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - client_mrm_emergency_stop_ = create_client( - "~/output/mrm/emergency_stop/operate", rmw_qos_profile_services_default, - client_mrm_emergency_stop_group_); - - // Initialize - mrm_state_.stamp = this->now(); - mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL; - mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE; - is_hazard_status_timeout_ = false; - - // Timer - const auto update_period_ns = rclcpp::Rate(param_.update_rate).period(); - timer_ = rclcpp::create_timer( - this, get_clock(), update_period_ns, std::bind(&EmergencyHandler::onTimer, this)); -} - -void EmergencyHandler::onHazardStatusStamped( - const autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg) -{ - hazard_status_stamped_ = msg; - stamp_hazard_status_ = this->now(); -} - -void EmergencyHandler::onPrevControlCommand( - const autoware_control_msgs::msg::Control::ConstSharedPtr msg) -{ - auto control_command = new autoware_control_msgs::msg::Control(*msg); - control_command->stamp = msg->stamp; - prev_control_command_ = autoware_control_msgs::msg::Control::ConstSharedPtr(control_command); -} - -autoware_vehicle_msgs::msg::HazardLightsCommand EmergencyHandler::createHazardCmdMsg() -{ - using autoware_vehicle_msgs::msg::HazardLightsCommand; - HazardLightsCommand msg; - - // Check emergency - const bool is_emergency = isEmergency(); - - if (hazard_status_stamped_->status.emergency_holding) { - // turn hazard on during emergency holding - msg.command = HazardLightsCommand::ENABLE; - } else if (is_emergency && param_.turning_hazard_on.emergency) { - // turn hazard on if vehicle is in emergency state and - // turning hazard on if emergency flag is true - msg.command = HazardLightsCommand::ENABLE; - - } else { - msg.command = HazardLightsCommand::NO_COMMAND; - } - return msg; -} - -void EmergencyHandler::publishControlCommands() -{ - using autoware_vehicle_msgs::msg::GearCommand; - - // Create timestamp - const auto stamp = this->now(); - - // Publish hazard command - pub_hazard_cmd_->publish(createHazardCmdMsg()); - - // Publish gear - { - GearCommand msg; - msg.stamp = stamp; - const auto command = [&]() { - // If stopped and use_parking is not true, send the last gear command - if (isStopped()) - return (param_.use_parking_after_stopped) ? GearCommand::PARK : last_gear_command_; - return (isDrivingBackwards()) ? GearCommand::REVERSE : GearCommand::DRIVE; - }(); - - msg.command = command; - last_gear_command_ = msg.command; - pub_gear_cmd_->publish(msg); - return; - } -} - -void EmergencyHandler::publishMrmState() -{ - mrm_state_.stamp = this->now(); - pub_mrm_state_->publish(mrm_state_); -} - -void EmergencyHandler::operateMrm() -{ - using autoware_adapi_v1_msgs::msg::MrmState; - - if (mrm_state_.state == MrmState::NORMAL) { - // Cancel MRM behavior when returning to NORMAL state - const auto current_mrm_behavior = MrmState::NONE; - if (current_mrm_behavior != mrm_state_.behavior) { - cancelMrmBehavior(mrm_state_.behavior); - mrm_state_.behavior = current_mrm_behavior; - } - return; - } - if (mrm_state_.state == MrmState::MRM_OPERATING) { - const auto current_mrm_behavior = getCurrentMrmBehavior(); - if (current_mrm_behavior != mrm_state_.behavior) { - cancelMrmBehavior(mrm_state_.behavior); - callMrmBehavior(current_mrm_behavior); - mrm_state_.behavior = current_mrm_behavior; - } - return; - } - if (mrm_state_.state == MrmState::MRM_SUCCEEDED) { - // TODO(mkuri): operate MRC behavior - // Do nothing - return; - } - if (mrm_state_.state == MrmState::MRM_FAILED) { - // Do nothing - return; - } - RCLCPP_WARN(this->get_logger(), "invalid MRM state: %d", mrm_state_.state); -} - -void EmergencyHandler::callMrmBehavior( - const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const -{ - using autoware_adapi_v1_msgs::msg::MrmState; - - auto request = std::make_shared(); - request->operate = true; - - if (mrm_behavior == MrmState::NONE) { - RCLCPP_WARN(this->get_logger(), "MRM behavior is None. Do nothing."); - return; - } - if (mrm_behavior == MrmState::COMFORTABLE_STOP) { - auto result = client_mrm_comfortable_stop_->async_send_request(request).get(); - if (result->response.success == true) { - RCLCPP_WARN(this->get_logger(), "Comfortable stop is operated"); - } else { - RCLCPP_ERROR(this->get_logger(), "Comfortable stop is failed to operate"); - } - return; - } - if (mrm_behavior == MrmState::EMERGENCY_STOP) { - auto result = client_mrm_emergency_stop_->async_send_request(request).get(); - if (result->response.success == true) { - RCLCPP_WARN(this->get_logger(), "Emergency stop is operated"); - } else { - RCLCPP_ERROR(this->get_logger(), "Emergency stop is failed to operate"); - } - return; - } - RCLCPP_WARN(this->get_logger(), "invalid MRM behavior: %d", mrm_behavior); -} - -void EmergencyHandler::cancelMrmBehavior( - const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const -{ - using autoware_adapi_v1_msgs::msg::MrmState; - - auto request = std::make_shared(); - request->operate = false; - - if (mrm_behavior == MrmState::NONE) { - // Do nothing - return; - } - if (mrm_behavior == MrmState::COMFORTABLE_STOP) { - auto result = client_mrm_comfortable_stop_->async_send_request(request).get(); - if (result->response.success == true) { - RCLCPP_WARN(this->get_logger(), "Comfortable stop is canceled"); - } else { - RCLCPP_ERROR(this->get_logger(), "Comfortable stop is failed to cancel"); - } - return; - } - if (mrm_behavior == MrmState::EMERGENCY_STOP) { - auto result = client_mrm_emergency_stop_->async_send_request(request).get(); - if (result->response.success == true) { - RCLCPP_WARN(this->get_logger(), "Emergency stop is canceled"); - } else { - RCLCPP_ERROR(this->get_logger(), "Emergency stop is failed to cancel"); - } - return; - } - RCLCPP_WARN(this->get_logger(), "invalid MRM behavior: %d", mrm_behavior); -} - -bool EmergencyHandler::isDataReady() -{ - if (!hazard_status_stamped_) { - RCLCPP_INFO_THROTTLE( - this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), - "waiting for hazard_status_stamped msg..."); - return false; - } - - if (param_.use_comfortable_stop && !isComfortableStopStatusAvailable()) { - RCLCPP_INFO_THROTTLE( - this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), - "waiting for mrm comfortable stop to become available..."); - return false; - } - - if (!isEmergencyStopStatusAvailable()) { - RCLCPP_INFO_THROTTLE( - this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), - "waiting for mrm emergency stop to become available..."); - return false; - } - - return true; -} - -void EmergencyHandler::checkHazardStatusTimeout() -{ - if ((this->now() - stamp_hazard_status_).seconds() > param_.timeout_hazard_status) { - is_hazard_status_timeout_ = true; - RCLCPP_WARN_THROTTLE( - this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(), - "heartbeat_hazard_status is timeout"); - } else { - is_hazard_status_timeout_ = false; - } -} - -void EmergencyHandler::onTimer() -{ - if (!isDataReady()) { - return; - } - - // Check whether heartbeat hazard_status is timeout - checkHazardStatusTimeout(); - - // Update Emergency State - updateMrmState(); - - // Publish control commands - publishControlCommands(); - operateMrm(); - publishMrmState(); -} - -void EmergencyHandler::transitionTo(const int new_state) -{ - using autoware_adapi_v1_msgs::msg::MrmState; - - const auto state2string = [](const int state) { - if (state == MrmState::NORMAL) { - return "NORMAL"; - } - if (state == MrmState::MRM_OPERATING) { - return "MRM_OPERATING"; - } - if (state == MrmState::MRM_SUCCEEDED) { - return "MRM_SUCCEEDED"; - } - if (state == MrmState::MRM_FAILED) { - return "MRM_FAILED"; - } - - const auto msg = "invalid state: " + std::to_string(state); - throw std::runtime_error(msg); - }; - - RCLCPP_DEBUG( - this->get_logger(), "MRM State changed: %s -> %s", state2string(mrm_state_.state), - state2string(new_state)); - - mrm_state_.state = new_state; -} - -void EmergencyHandler::updateMrmState() -{ - using autoware_adapi_v1_msgs::msg::MrmState; - using autoware_vehicle_msgs::msg::ControlModeReport; - - // Check emergency - const bool is_emergency = isEmergency(); - - // Get mode - const bool is_auto_mode = isAutonomous(); - - // State Machine - if (mrm_state_.state == MrmState::NORMAL) { - // NORMAL - if (is_auto_mode && is_emergency) { - transitionTo(MrmState::MRM_OPERATING); - return; - } - } else { - // Emergency - // Send recovery events if "not emergency" - if (!is_emergency) { - transitionTo(MrmState::NORMAL); - return; - } - - if (mrm_state_.state == MrmState::MRM_OPERATING) { - // TODO(Kenji Miyake): Check MRC is accomplished - if (isStopped()) { - transitionTo(MrmState::MRM_SUCCEEDED); - return; - } - } else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) { - // Do nothing(only checking common recovery events) - } else if (mrm_state_.state == MrmState::MRM_FAILED) { - // Do nothing(only checking common recovery events) - } else { - const auto msg = "invalid state: " + std::to_string(mrm_state_.state); - throw std::runtime_error(msg); - } - } -} - -autoware_adapi_v1_msgs::msg::MrmState::_behavior_type EmergencyHandler::getCurrentMrmBehavior() -{ - using autoware_adapi_v1_msgs::msg::MrmState; - using autoware_system_msgs::msg::HazardStatus; - - // Get hazard level - auto level = hazard_status_stamped_->status.level; - if (is_hazard_status_timeout_) { - level = HazardStatus::SINGLE_POINT_FAULT; - } - - // State machine - if (mrm_state_.behavior == MrmState::NONE) { - if (level == HazardStatus::LATENT_FAULT) { - if (param_.use_comfortable_stop) { - return MrmState::COMFORTABLE_STOP; - } - return MrmState::EMERGENCY_STOP; - } - if (level == HazardStatus::SINGLE_POINT_FAULT) { - return MrmState::EMERGENCY_STOP; - } - } - if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) { - if (level == HazardStatus::SINGLE_POINT_FAULT) { - return MrmState::EMERGENCY_STOP; - } - } - - return mrm_state_.behavior; -} - -bool EmergencyHandler::isAutonomous() -{ - using autoware_vehicle_msgs::msg::ControlModeReport; - auto mode = sub_control_mode_.takeData(); - if (mode == nullptr) return false; - return mode->mode == ControlModeReport::AUTONOMOUS; -} - -bool EmergencyHandler::isEmergency() -{ - return hazard_status_stamped_->status.emergency || - hazard_status_stamped_->status.emergency_holding || is_hazard_status_timeout_; -} - -bool EmergencyHandler::isStopped() -{ - auto odom = sub_odom_.takeData(); - if (odom == nullptr) return false; - constexpr auto th_stopped_velocity = 0.001; - return (std::abs(odom->twist.twist.linear.x) < th_stopped_velocity); -} - -bool EmergencyHandler::isComfortableStopStatusAvailable() -{ - auto status = sub_mrm_comfortable_stop_status_.takeData(); - if (status == nullptr) return false; - return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; -} - -bool EmergencyHandler::isEmergencyStopStatusAvailable() -{ - auto status = sub_mrm_emergency_stop_status_.takeData(); - if (status == nullptr) return false; - return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; -} - -bool EmergencyHandler::isDrivingBackwards() -{ - auto odom = sub_odom_.takeData(); - if (odom == nullptr) return false; - constexpr auto th_moving_backwards = -0.001; - return odom->twist.twist.linear.x < th_moving_backwards; -} - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(EmergencyHandler) From c5ab77af08e18d009fe462a214758342e66690ec Mon Sep 17 00:00:00 2001 From: Batuhan Beytekin <71197983+batuhanbeytekin@users.noreply.github.com> Date: Fri, 20 Sep 2024 14:47:14 +0300 Subject: [PATCH 221/223] refactor(detected_object_validation): rework parameters (#7750) * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * style(pre-commit): autofix Signed-off-by: Batuhan Beytekin * Update perception/detected_object_validation/schema/object_lanelet_filter.schema.json Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * Update perception/detected_object_validation/schema/object_position_filter.schema.json Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * style(pre-commit): autofix Signed-off-by: Batuhan Beytekin * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * refactor(detected_object_validation): rework parameters Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin * style(pre-commit): autofix --------- Signed-off-by: batuhanbeytekin Signed-off-by: Batuhan Beytekin Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 18 +++ .../occupancy_grid_based_validator.param.yaml | 1 + .../schema/object_lanelet_filter.schema.json | 121 ++++++++++++++++++ .../schema/object_position_filter.schema.json | 106 +++++++++++++++ ...cle_pointcloud_based_validator.schema.json | 68 ++++++++++ ...occupancy_grid_based_validator.schema.json | 38 ++++++ .../src/lanelet_filter/lanelet_filter.cpp | 16 +-- .../obstacle_pointcloud_validator.cpp | 2 +- .../occupancy_grid_map_validator.cpp | 4 +- .../src/position_filter/position_filter.cpp | 24 ++-- 10 files changed, 375 insertions(+), 23 deletions(-) create mode 100644 perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json create mode 100644 perception/autoware_detected_object_validation/schema/object_position_filter.schema.json create mode 100644 perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json create mode 100644 perception/autoware_detected_object_validation/schema/occupancy_grid_based_validator.schema.json diff --git a/perception/autoware_detected_object_validation/README.md b/perception/autoware_detected_object_validation/README.md index 12fad4ad9759f..adca7c0fd9678 100644 --- a/perception/autoware_detected_object_validation/README.md +++ b/perception/autoware_detected_object_validation/README.md @@ -10,3 +10,21 @@ The purpose of this package is to eliminate obvious false positives of DetectedO - [Occupancy grid based validator](occupancy-grid-based-validator.md) - [Object lanelet filter](object-lanelet-filter.md) - [Object position filter](object-position-filter.md) + +### Node Parameters + +#### object_lanelet_filter + +{{ json_to_markdown("perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json") }} + +#### object_position_filter + +{{ json_to_markdown("perception/autoware_detected_object_validation/schema/object_position_filter.schema.json") }} + +#### obstacle_pointcloud_based_validator + +{{ json_to_markdown("perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json") }} + +#### occupancy_grid_based_validator + +{{ json_to_markdown("perception/autoware_detected_object_validation/schema/occupancy_grid_based_validator.schema.json") }} diff --git a/perception/autoware_detected_object_validation/config/occupancy_grid_based_validator.param.yaml b/perception/autoware_detected_object_validation/config/occupancy_grid_based_validator.param.yaml index fc5c634735e23..bb996f1197155 100644 --- a/perception/autoware_detected_object_validation/config/occupancy_grid_based_validator.param.yaml +++ b/perception/autoware_detected_object_validation/config/occupancy_grid_based_validator.param.yaml @@ -1,3 +1,4 @@ /**: ros__parameters: + mean_threshold: 0.6 enable_debug: false diff --git a/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json b/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json new file mode 100644 index 0000000000000..fd4e39f0ca02e --- /dev/null +++ b/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json @@ -0,0 +1,121 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Object Lanelet Filter", + "type": "object", + "definitions": { + "object_lanelet_filter": { + "type": "object", + "properties": { + "filter_target_label": { + "type": "object", + "properties": { + "UNKNOWN": { + "type": "boolean", + "default": true, + "description": "If true, unknown objects are filtered." + }, + "CAR": { + "type": "boolean", + "default": false, + "description": "If true, car objects are filtered." + }, + "TRUCK": { + "type": "boolean", + "default": false, + "description": "If true, truck objects are filtered." + }, + "BUS": { + "type": "boolean", + "default": false, + "description": "If true, bus objects are filtered." + }, + "TRAILER": { + "type": "boolean", + "default": false, + "description": "If true, trailer objects are filtered." + }, + "MOTORCYCLE": { + "type": "boolean", + "default": false, + "description": "If true, motorcycle objects are filtered." + }, + "BICYCLE": { + "type": "boolean", + "default": false, + "description": "If true, bicycle objects are filtered." + }, + "PEDESTRIAN": { + "type": "boolean", + "default": false, + "description": "If true, pedestrian objects are filtered." + } + }, + "required": [ + "UNKNOWN", + "CAR", + "TRUCK", + "BUS", + "TRAILER", + "MOTORCYCLE", + "BICYCLE", + "PEDESTRIAN" + ] + }, + "filter_settings": { + "type": "object", + "properties": { + "polygon_overlap_filter": { + "type": "object", + "properties": { + "enabled": { + "type": "boolean", + "default": true, + "description": "If true, objects that are not in the lanelet polygon are filtered." + } + }, + "required": ["enabled"] + }, + "lanelet_direction_filter": { + "type": "object", + "properties": { + "enabled": { + "type": "boolean", + "default": false, + "description": "If true, objects that are not in the same direction as the lanelet are filtered." + }, + "velocity_yaw_threshold": { + "type": "number", + "default": 0.785398, + "description": "If the yaw difference between the object and the lanelet is greater than this value, the object is filtered." + }, + "object_speed_threshold": { + "type": "number", + "default": 3.0, + "description": "If the object speed is greater than this value, the object is filtered." + } + }, + "required": ["enabled", "velocity_yaw_threshold", "object_speed_threshold"] + } + }, + "required": ["polygon_overlap_filter", "lanelet_direction_filter"] + } + }, + "required": ["filter_target_label", "filter_settings"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/object_lanelet_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_detected_object_validation/schema/object_position_filter.schema.json b/perception/autoware_detected_object_validation/schema/object_position_filter.schema.json new file mode 100644 index 0000000000000..9c35280d403ea --- /dev/null +++ b/perception/autoware_detected_object_validation/schema/object_position_filter.schema.json @@ -0,0 +1,106 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Object Position Filter", + "type": "object", + "definitions": { + "object_position_filter_params": { + "type": "object", + "properties": { + "filter_target_label": { + "type": "object", + "properties": { + "UNKNOWN": { + "type": "boolean", + "default": true, + "description": "Filter for UNKNOWN label" + }, + "CAR": { + "type": "boolean", + "default": false, + "description": "Filter for CAR label" + }, + "TRUCK": { + "type": "boolean", + "default": false, + "description": "Filter for TRUCK label" + }, + "BUS": { + "type": "boolean", + "default": false, + "description": "Filter for BUS label" + }, + "TRAILER": { + "type": "boolean", + "default": false, + "description": "Filter for TRAILER label" + }, + "MOTORCYCLE": { + "type": "boolean", + "default": false, + "description": "Filter for MOTORCYCLE label" + }, + "BICYCLE": { + "type": "boolean", + "default": false, + "description": "Filter for BICYCLE label" + }, + "PEDESTRIAN": { + "type": "boolean", + "default": false, + "description": "Filter for PEDESTRIAN label" + } + }, + "required": [ + "UNKNOWN", + "CAR", + "TRUCK", + "BUS", + "TRAILER", + "MOTORCYCLE", + "BICYCLE", + "PEDESTRIAN" + ] + }, + "upper_bound_x": { + "type": "number", + "default": 100.0, + "description": "Upper bound for X coordinate" + }, + "lower_bound_x": { + "type": "number", + "default": 0.0, + "description": "Lower bound for X coordinate" + }, + "upper_bound_y": { + "type": "number", + "default": 10.0, + "description": "Upper bound for Y coordinate" + }, + "lower_bound_y": { + "type": "number", + "default": -10.0, + "description": "Lower bound for Y coordinate" + } + }, + "required": [ + "filter_target_label", + "upper_bound_x", + "lower_bound_x", + "upper_bound_y", + "lower_bound_y" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/object_position_filter_params" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json b/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json new file mode 100644 index 0000000000000..d7aa970993ca1 --- /dev/null +++ b/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json @@ -0,0 +1,68 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Obstacle Pointcloud Based Validator", + "type": "object", + "definitions": { + "obstacle_pointcloud_based_validator": { + "type": "object", + "properties": { + "min_points_num": { + "type": "array", + "items": { + "type": "integer" + }, + "default": [10, 10, 10, 10, 10, 10, 10, 10], + "description": "The minimum number of obstacle point clouds in DetectedObjects" + }, + "max_points_num": { + "type": "array", + "items": { + "type": "integer" + }, + "default": [10, 10, 10, 10, 10, 10, 10, 10], + "description": "The max number of obstacle point clouds in DetectedObjects" + }, + "min_points_and_distance_ratio": { + "type": "array", + "items": { + "type": "number" + }, + "default": [800, 800, 800, 800, 800, 800, 800, 800], + "description": "Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink." + }, + "using_2d_validator": { + "type": "boolean", + "default": false, + "description": "The xy-plane projected (2D) obstacle point clouds will be used for validation" + }, + "enable_debugger": { + "type": "boolean", + "default": false, + "description": "Whether to create debug topics or not?" + } + }, + "required": [ + "min_points_num", + "max_points_num", + "min_points_and_distance_ratio", + "using_2d_validator", + "enable_debugger" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/obstacle_pointcloud_based_validator" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_detected_object_validation/schema/occupancy_grid_based_validator.schema.json b/perception/autoware_detected_object_validation/schema/occupancy_grid_based_validator.schema.json new file mode 100644 index 0000000000000..918e94cd9847e --- /dev/null +++ b/perception/autoware_detected_object_validation/schema/occupancy_grid_based_validator.schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Occupancy Grid Based Validator", + "type": "object", + "definitions": { + "occupancy_grid_based_validator": { + "type": "object", + "properties": { + "mean_threshold": { + "type": "number", + "default": 0.6, + "description": "The percentage threshold of allowed non-freespace." + }, + "enable_debug": { + "type": "boolean", + "default": false, + "description": "Whether to display debug images or not?" + } + }, + "required": ["mean_threshold", "enable_debug"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/occupancy_grid_based_validator" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index aed0ba5ab85ea..59de872ae9b90 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -42,14 +42,14 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod using std::placeholders::_1; // Set parameters - filter_target_.UNKNOWN = declare_parameter("filter_target_label.UNKNOWN", false); - filter_target_.CAR = declare_parameter("filter_target_label.CAR", false); - filter_target_.TRUCK = declare_parameter("filter_target_label.TRUCK", false); - filter_target_.BUS = declare_parameter("filter_target_label.BUS", false); - filter_target_.TRAILER = declare_parameter("filter_target_label.TRAILER", false); - filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE", false); - filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE", false); - filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN", false); + filter_target_.UNKNOWN = declare_parameter("filter_target_label.UNKNOWN"); + filter_target_.CAR = declare_parameter("filter_target_label.CAR"); + filter_target_.TRUCK = declare_parameter("filter_target_label.TRUCK"); + filter_target_.BUS = declare_parameter("filter_target_label.BUS"); + filter_target_.TRAILER = declare_parameter("filter_target_label.TRAILER"); + filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE"); + filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE"); + filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN"); // Set filter settings filter_settings_.polygon_overlap_filter = declare_parameter("filter_settings.polygon_overlap_filter.enabled"); diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp index c5ecce714735b..7f55c86080fd2 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp @@ -310,7 +310,7 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( debug_publisher_ = std::make_unique( this, "obstacle_pointcloud_based_validator"); - const bool enable_debugger = declare_parameter("enable_debugger", false); + const bool enable_debugger = declare_parameter("enable_debugger"); if (enable_debugger) debugger_ = std::make_shared(this); published_time_publisher_ = std::make_unique(this); diff --git a/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp b/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp index c082b4b0f03f1..51df1929a300c 100644 --- a/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp +++ b/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp @@ -53,8 +53,8 @@ OccupancyGridBasedValidator::OccupancyGridBasedValidator(const rclcpp::NodeOptio objects_pub_ = create_publisher( "~/output/objects", rclcpp::QoS{1}); - mean_threshold_ = declare_parameter("mean_threshold", 0.6); - enable_debug_ = declare_parameter("enable_debug", false); + mean_threshold_ = declare_parameter("mean_threshold"); + enable_debug_ = declare_parameter("enable_debug"); published_time_publisher_ = std::make_unique(this); } diff --git a/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp b/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp index ac0bab404c476..3b88628aa6d84 100644 --- a/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp +++ b/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp @@ -26,18 +26,18 @@ ObjectPositionFilterNode::ObjectPositionFilterNode(const rclcpp::NodeOptions & n using std::placeholders::_1; // Set parameters - upper_bound_x_ = declare_parameter("upper_bound_x", 100.0); - upper_bound_y_ = declare_parameter("upper_bound_y", 50.0); - lower_bound_x_ = declare_parameter("lower_bound_x", 0.0); - lower_bound_y_ = declare_parameter("lower_bound_y", -50.0); - filter_target_.UNKNOWN = declare_parameter("filter_target_label.UNKNOWN", false); - filter_target_.CAR = declare_parameter("filter_target_label.CAR", false); - filter_target_.TRUCK = declare_parameter("filter_target_label.TRUCK", false); - filter_target_.BUS = declare_parameter("filter_target_label.BUS", false); - filter_target_.TRAILER = declare_parameter("filter_target_label.TRAILER", false); - filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE", false); - filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE", false); - filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN", false); + upper_bound_x_ = declare_parameter("upper_bound_x"); + upper_bound_y_ = declare_parameter("upper_bound_y"); + lower_bound_x_ = declare_parameter("lower_bound_x"); + lower_bound_y_ = declare_parameter("lower_bound_y"); + filter_target_.UNKNOWN = declare_parameter("filter_target_label.UNKNOWN"); + filter_target_.CAR = declare_parameter("filter_target_label.CAR"); + filter_target_.TRUCK = declare_parameter("filter_target_label.TRUCK"); + filter_target_.BUS = declare_parameter("filter_target_label.BUS"); + filter_target_.TRAILER = declare_parameter("filter_target_label.TRAILER"); + filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE"); + filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE"); + filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN"); // Set publisher/subscriber object_sub_ = this->create_subscription( From 1f966da9e1a88ec0ead41cf19e3f3c2db0a6824e Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Tue, 24 Sep 2024 10:54:14 +0900 Subject: [PATCH 222/223] feat(system_error_monitor): remove system error monitor (#8929) * feat: delete-system-error-monitor-from-autoware Signed-off-by: TetsuKawa * feat: remove unnecessary params --------- Signed-off-by: TetsuKawa --- .github/CODEOWNERS | 1 - .../src/mrm_summary_overlay_display.cpp | 2 +- launch/tier4_system_launch/README.md | 2 - .../launch/system.launch.xml | 4 - launch/tier4_system_launch/package.xml | 1 - system/system_error_monitor/CMakeLists.txt | 18 - system/system_error_monitor/README.md | 145 ---- .../diagnostic_aggregator/_empty.param.yaml | 0 .../diagnostic_aggregator/control.param.yaml | 121 --- .../localization.param.yaml | 47 -- .../diagnostic_aggregator/map.param.yaml | 22 - .../perception.param.yaml | 15 - .../diagnostic_aggregator/planning.param.yaml | 95 --- .../diagnostic_aggregator/sensing.param.yaml | 2 - .../diagnostic_aggregator/system.param.yaml | 249 ------ .../diagnostic_aggregator/vehicle.param.yaml | 16 - .../config/system_error_monitor.param.yaml | 55 -- ...ror_monitor.planning_simulation.param.yaml | 56 -- .../diagnostics_filter.hpp | 103 --- .../system_error_monitor_core.hpp | 153 ---- .../launch/system_error_monitor.launch.xml | 55 -- .../system_error_monitor_node.launch.xml | 34 - system/system_error_monitor/package.xml | 32 - .../src/system_error_monitor_core.cpp | 722 ------------------ 24 files changed, 1 insertion(+), 1949 deletions(-) delete mode 100644 system/system_error_monitor/CMakeLists.txt delete mode 100644 system/system_error_monitor/README.md delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/_empty.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/map.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/perception.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/planning.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/sensing.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml delete mode 100644 system/system_error_monitor/config/diagnostic_aggregator/vehicle.param.yaml delete mode 100644 system/system_error_monitor/config/system_error_monitor.param.yaml delete mode 100644 system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml delete mode 100644 system/system_error_monitor/include/system_error_monitor/diagnostics_filter.hpp delete mode 100644 system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp delete mode 100644 system/system_error_monitor/launch/system_error_monitor.launch.xml delete mode 100644 system/system_error_monitor/launch/system_error_monitor_node.launch.xml delete mode 100644 system/system_error_monitor/package.xml delete mode 100644 system/system_error_monitor/src/system_error_monitor_core.cpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 17ac4f3f94f57..3367eb9ad71b5 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -236,7 +236,6 @@ system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@t system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/system_diagnostic_monitor/** isamu.takagi@tier4.jp -system/system_error_monitor/** fumihito.ito@tier4.jp system/system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp system/velodyne_monitor/** fumihito.ito@tier4.jp diff --git a/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp b/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp index c0db8cc86450b..b0ba99c98b154 100644 --- a/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp +++ b/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp @@ -74,7 +74,7 @@ void insertNewlines(std::string & str, const size_t max_line_length) std::optional generateMrmMessage(diagnostic_msgs::msg::DiagnosticStatus diag_status) { - if (diag_status.hardware_id == "" || diag_status.hardware_id == "system_error_monitor") { + if (diag_status.hardware_id == "") { return std::nullopt; } else if (diag_status.level == diagnostic_msgs::msg::DiagnosticStatus::ERROR) { std::string msg = "- ERROR: " + diag_status.name + " (" + diag_status.message + ")"; diff --git a/launch/tier4_system_launch/README.md b/launch/tier4_system_launch/README.md index 76cea5a575c5d..440843bf1c3f5 100644 --- a/launch/tier4_system_launch/README.md +++ b/launch/tier4_system_launch/README.md @@ -23,5 +23,3 @@ Note that you should provide parameter paths as `PACKAGE_param_path`. The list o ... ``` - -The sensing configuration parameters used in system_error_monitor are loaded from "config/diagnostic_aggregator/sensor_kit.param.yaml" in the "`SENSOR_MODEL`\_description" package. diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 07f6ae8d4bdc2..19e5120d605e2 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -6,10 +6,6 @@ - - - - diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 673596fad9972..881a65effe2c0 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -12,7 +12,6 @@ autoware_cmake component_state_monitor - system_error_monitor system_monitor ament_lint_auto diff --git a/system/system_error_monitor/CMakeLists.txt b/system/system_error_monitor/CMakeLists.txt deleted file mode 100644 index 91e9e20146327..0000000000000 --- a/system/system_error_monitor/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(system_error_monitor) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/system_error_monitor_core.cpp -) - -rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "AutowareErrorMonitor" - EXECUTABLE ${PROJECT_NAME}_node) - -ament_auto_package(INSTALL_TO_SHARE - launch - config -) diff --git a/system/system_error_monitor/README.md b/system/system_error_monitor/README.md deleted file mode 100644 index e765239f30f4d..0000000000000 --- a/system/system_error_monitor/README.md +++ /dev/null @@ -1,145 +0,0 @@ -# system_error_monitor - -## Purpose - -Autoware Error Monitor has two main functions. - -1. It is to judge the system hazard level from the aggregated diagnostic information of each module of Autoware. -2. It enables automatic recovery from the emergency state. - -## Inner-workings / Algorithms - -### State Transition - -```plantuml -@startuml -hide empty description - -state "Not Emergency" as N -state "Emergency" as E - -[*] --> N - -N -down-> E : found critical errors -E -up-> N : emergency status is cleared - -note right of E - If the emergency hold is enabled, a service call is required to clear the emergency status. - If not, the emergency status will automatically clear when errors recover. -end note - -@enduml -``` - -### updateEmergencyHoldingCondition Flow Chart - -```plantuml -@startuml -title updateEmergencyHoldingCondition Flow Chart - - -(*) --> "Check emergency holding condition" -note right : emergency_holding is initialized with false - -if "" then - -->[false] "emergency is not held" - else - -->[true] "Check use emergency hold condition" -endif - -if "" then - -->[true] "emergency is held" - else - -->[false] "Check emergency condition" -endif - -if "" then - -->[false] "emergency is not held" - else - -->[true] "Check auto recovery setting" -endif - -if "" then - -->[not approved auto recovery] "emergency is held" - else - -->[approved auto recovery] "Check Emergency Duration" -endif - -if "" then - -->[within recovery timeout] "emergency is not held" - else - -->[over recovery timeout] "Check Control Mode" -endif - -if "" then - -->[autonomous driving] "emergency is held" - else - -->[manual driving] "Check use emergency hold in manual driving condition" -endif - -if "" then - -->[true] "emergency is held" - else - -->[false] "emergency is not held" -endif - -@enduml -``` - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| ---------------------------- | ----------------------------------------------- | ------------------------------------------------------------------------------------------------------------------ | -| `/diagnostics_agg` | `diagnostic_msgs::msg::DiagnosticArray` | Diagnostic information aggregated based [diagnostic_aggregator setting](./config/diagnostic_aggregator) is used to | -| `/autoware/state` | `autoware_system_msgs::msg::AutowareState` | Required to ignore error during Route, Planning and Finalizing. | -| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Required to select the appropriate module from `autonomous_driving` or `external_control` | -| `/vehicle/control_mode` | `autoware_vehicle_msgs::msg::ControlModeReport` | Required to not hold emergency during manual driving | - -### Output - -| Name | Type | Description | -| --------------------------------- | ------------------------------------------------ | ------------------------------------------------------------------------------------ | -| `/system/emergency/hazard_status` | `autoware_system_msgs::msg::HazardStatusStamped` | HazardStatus contains system hazard level, emergency hold status and failure details | -| `/diagnostics_err` | `diagnostic_msgs::msg::DiagnosticArray` | This has the same contents as HazardStatus. This is used for visualization | - -## Parameters - -### Node Parameters - -| Name | Type | Default Value | Explanation | -| ---------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `ignore_missing_diagnostics` | bool | `false` | If this parameter is turned off, it will be ignored if required modules have not been received. | -| `add_leaf_diagnostics` | bool | `true` | Required to use children diagnostics. | -| `diag_timeout_sec` | double | `1.0` (sec) | If required diagnostic is not received for a `diag_timeout_sec`, the diagnostic state become STALE state. | -| `data_ready_timeout` | double | `30.0` | If input topics required for system_error_monitor are not available for `data_ready_timeout` seconds, autoware_state will translate to emergency state. | -| `data_heartbeat_timeout` | double | `1.0` | If input topics required for system_error_monitor are not no longer subscribed for `data_heartbeat_timeout` seconds, autoware_state will translate to emergency state. | - -### Core Parameters - -| Name | Type | Default Value | Explanation | -| -------------------------------------- | ------ | ------------- | ----------------------------------------------------------------------------------------------------- | -| `hazard_recovery_timeout` | double | `5.0` | The vehicle can recovery to normal driving if emergencies disappear during `hazard_recovery_timeout`. | -| `use_emergency_hold` | bool | `false` | If it is false, the vehicle will return to normal as soon as emergencies disappear. | -| `use_emergency_hold_in_manual_driving` | bool | `false` | If this parameter is turned off, emergencies will be ignored during manual driving. | -| `emergency_hazard_level` | int | `2` | If hazard_level is more than emergency_hazard_level, autoware state will translate to emergency state | - -### YAML format for system_error_monitor - -The parameter key should be filled with the hierarchical diagnostics output by diagnostic_aggregator. Parameters prefixed with `required_modules.autonomous_driving` are for autonomous driving. Parameters with the `required_modules.remote_control` prefix are for remote control. If the value is `default`, the default value will be set. - -| Key | Type | Default Value | Explanation | -| ------------------------------------------------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------- | -| `required_modules.autonomous_driving.DIAGNOSTIC_NAME.sf_at` | string | `"none"` | Diagnostic level where it becomes Safe Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.autonomous_driving.DIAGNOSTIC_NAME.lf_at` | string | `"warn"` | Diagnostic level where it becomes Latent Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.autonomous_driving.DIAGNOSTIC_NAME.spf_at` | string | `"error"` | Diagnostic level where it becomes Single Point Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.autonomous_driving.DIAGNOSTIC_NAME.auto_recovery` | string | `"true"` | Determines whether the system will automatically recover when it recovers from an error. | -| `required_modules.remote_control.DIAGNOSTIC_NAME.sf_at` | string | `"none"` | Diagnostic level where it becomes Safe Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.remote_control.DIAGNOSTIC_NAME.lf_at` | string | `"warn"` | Diagnostic level where it becomes Latent Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.remote_control.DIAGNOSTIC_NAME.spf_at` | string | `"error"` | Diagnostic level where it becomes Single Point Fault. Available options are `"none"`, `"warn"`, `"error"`. | -| `required_modules.remote_control.DIAGNOSTIC_NAME.auto_recovery` | string | `"true"` | Determines whether the system will automatically recover when it recovers from an error. | - -## Assumptions / Known limits - -TBD. diff --git a/system/system_error_monitor/config/diagnostic_aggregator/_empty.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/_empty.param.yaml deleted file mode 100644 index e69de29bb2d1d..0000000000000 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml deleted file mode 100644 index 9da5b14780dd1..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml +++ /dev/null @@ -1,121 +0,0 @@ -/**: - ros__parameters: - control: - type: diagnostic_aggregator/AnalyzerGroup - path: control - analyzers: - autonomous_emergency_braking: - type: diagnostic_aggregator/AnalyzerGroup - path: autoware_autonomous_emergency_braking - analyzers: - performance_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: performance_monitoring - analyzers: - emergency_stop: - type: diagnostic_aggregator/GenericAnalyzer - path: emergency_stop - contains: [": aeb_emergency_stop"] - timeout: 1.0 - - control_command_gate: - type: diagnostic_aggregator/AnalyzerGroup - path: control_command_gate - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - heartbeat: - type: diagnostic_aggregator/GenericAnalyzer - path: heartbeat - contains: ["vehicle_cmd_gate: heartbeat"] - timeout: 1.0 - - autonomous_driving: - type: diagnostic_aggregator/AnalyzerGroup - path: autonomous_driving - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": control_topic_status"] - timeout: 1.0 - - performance_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: performance_monitoring - analyzers: - lane_departure: - type: diagnostic_aggregator/GenericAnalyzer - path: lane_departure - contains: [": lane_departure"] - timeout: 1.0 - - trajectory_deviation: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_deviation - contains: [": trajectory_deviation"] - timeout: 1.0 - - control_state: - type: diagnostic_aggregator/GenericAnalyzer - path: control_state - contains: [": control_state"] - timeout: 1.0 - - control_validator: - type: diagnostic_aggregator/GenericAnalyzer - path: autoware_control_validator - contains: [": control_validation_max_distance_deviation"] - timeout: 1.0 - - external_control: - type: diagnostic_aggregator/AnalyzerGroup - path: external_control - analyzers: - external_command_selector: - type: diagnostic_aggregator/AnalyzerGroup - path: external_command_selector - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - heartbeat: - type: diagnostic_aggregator/GenericAnalyzer - path: heartbeat - contains: ["external_cmd_selector: heartbeat"] - timeout: 1.0 - - local_external_control: - type: diagnostic_aggregator/AnalyzerGroup - path: local_external_control - analyzers: - device_connection: - type: diagnostic_aggregator/AnalyzerGroup - path: device_connection - analyzers: - joy_controller_connection: - type: diagnostic_aggregator/GenericAnalyzer - path: joy_controller_connection - contains: [": joy_controller_connection"] - timeout: 1.0 - - remote_external_control: - type: diagnostic_aggregator/AnalyzerGroup - path: remote_external_control - analyzers: - network_connection: - type: diagnostic_aggregator/AnalyzerGroup - path: network_connection - analyzers: - remote_control_topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: remote_control_topic_status - contains: [": remote_control_topic_status"] - timeout: 1.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml deleted file mode 100644 index ff6a85d150ee8..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml +++ /dev/null @@ -1,47 +0,0 @@ -/**: - ros__parameters: - localization: - type: diagnostic_aggregator/AnalyzerGroup - path: localization - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": localization_topic_status"] - timeout: 1.0 - - performance_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: performance_monitoring - analyzers: - scan_matching_status: - type: diagnostic_aggregator/GenericAnalyzer - path: scan_matching_status - contains: ["ndt_scan_matcher: scan_matching_status"] - timeout: 1.0 - - localization_error_ellipse: - type: diagnostic_aggregator/GenericAnalyzer - path: localization_error_ellipse - contains: ["localization_error_monitor: ellipse_error_status"] - timeout: 1.0 - - localization_stability: - type: diagnostic_aggregator/GenericAnalyzer - path: localization_stability - contains: ["localization: pose_instability_detector"] - timeout: 1.0 - - # This diagnostic should ideally be avoided in terms of Fault Tree Analysis (FTA) compatibility. - # However, we may need this since the localization accuracy is still not reliable enough and may produce - # false positives. Thus, NOTE that this diagnostic should be removed in the future when the localization accuracy - # is reliable enough. - sensor_fusion_status: - type: diagnostic_aggregator/GenericAnalyzer - path: sensor_fusion_status - contains: ["localization: ekf_localizer"] - timeout: 1.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/map.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/map.param.yaml deleted file mode 100644 index fa218ca5f08fb..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/map.param.yaml +++ /dev/null @@ -1,22 +0,0 @@ -/**: - ros__parameters: - map: - type: diagnostic_aggregator/AnalyzerGroup - path: map - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": map_topic_status"] - timeout: 1.0 - - # TODO(Tier IV): Support this diagnostics - # route_validation: - # type: diagnostic_aggregator/GenericAnalyzer - # path: route_validation - # contains: [": route_validation"] - # timeout: 0.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/perception.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/perception.param.yaml deleted file mode 100644 index 1f897def54f7a..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/perception.param.yaml +++ /dev/null @@ -1,15 +0,0 @@ -/**: - ros__parameters: - perception: - type: diagnostic_aggregator/AnalyzerGroup - path: perception - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": perception_topic_status"] - timeout: 1.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/planning.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/planning.param.yaml deleted file mode 100644 index aad8a4ffffac4..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/planning.param.yaml +++ /dev/null @@ -1,95 +0,0 @@ -/**: - ros__parameters: - planning: - type: diagnostic_aggregator/AnalyzerGroup - path: planning - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": planning_topic_status"] - timeout: 1.0 - - performance_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: performance_monitoring - analyzers: - trajectory_validation: - type: diagnostic_aggregator/AnalyzerGroup - path: trajectory_validation - analyzers: - trajectory_size: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_size - contains: [": trajectory_validation_size"] - timeout: 1.0 - - trajectory_finite_value: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_finite - contains: [": trajectory_validation_finite"] - timeout: 1.0 - - trajectory_interval: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_interval - contains: [": trajectory_validation_interval"] - timeout: 1.0 - - trajectory_curvature: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_curvature - contains: [": trajectory_validation_curvature"] - timeout: 1.0 - - trajectory_sharp_angle: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_relative_angle - contains: [": trajectory_validation_relative_angle"] - timeout: 1.0 - - trajectory_relative_angle: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_relative_angle - contains: [": trajectory_validation_relative_angle"] - timeout: 1.0 - - trajectory_lateral_acceleration: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_lateral_acceleration - contains: [": trajectory_validation_lateral_acceleration"] - timeout: 1.0 - - trajectory_acceleration: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_acceleration - contains: [": trajectory_validation_acceleration"] - timeout: 1.0 - - trajectory_deceleration: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_deceleration - contains: [": trajectory_validation_deceleration"] - timeout: 1.0 - - trajectory_steering: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_steering - contains: [": trajectory_validation_steering"] - timeout: 1.0 - - trajectory_steering_rate: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_steering_rate - contains: [": trajectory_validation_steering_rate"] - timeout: 1.0 - - trajectory_velocity_deviation: - type: diagnostic_aggregator/GenericAnalyzer - path: trajectory_validation_velocity_deviation - contains: [": trajectory_validation_velocity_deviation"] - timeout: 1.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/sensing.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/sensing.param.yaml deleted file mode 100644 index 27dc4518d4f30..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/sensing.param.yaml +++ /dev/null @@ -1,2 +0,0 @@ -/**: - ros__parameters: {} diff --git a/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml deleted file mode 100644 index f6e13012957aa..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml +++ /dev/null @@ -1,249 +0,0 @@ -/**: - ros__parameters: - system: - type: diagnostic_aggregator/AnalyzerGroup - path: system - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": system_topic_status"] - timeout: 1.0 - - emergency_stop_operation: - type: diagnostic_aggregator/GenericAnalyzer - path: emergency_stop_operation - contains: [": emergency_stop_operation"] - timeout: 1.0 - - service_log_checker: - type: diagnostic_aggregator/GenericAnalyzer - path: service_log_checker - contains: ["service_log_checker"] - timeout: 5.0 - - duplicated_node_checker: - type: diagnostic_aggregator/GenericAnalyzer - path: duplicated_node_checker - contains: ["duplicated_node_checker"] - timeout: 5.0 - - resource_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: resource_monitoring - analyzers: - clock: - type: diagnostic_aggregator/AnalyzerGroup - path: clock - analyzers: - clock_offset: - type: diagnostic_aggregator/GenericAnalyzer - path: clock_offset - contains: [": NTP Offset"] - timeout: 10.0 - - cpu: - type: diagnostic_aggregator/AnalyzerGroup - path: cpu - analyzers: - temperature: - type: diagnostic_aggregator/GenericAnalyzer - path: temperature - contains: [": CPU Temperature"] - timeout: 3.0 - - usage: - type: diagnostic_aggregator/GenericAnalyzer - path: usage - contains: [": CPU Usage"] - timeout: 3.0 - - thermal_throttling: - type: diagnostic_aggregator/GenericAnalyzer - path: thermal_throttling - contains: [": CPU Thermal Throttling"] - timeout: 3.0 - - frequency: - type: diagnostic_aggregator/GenericAnalyzer - path: frequency - contains: [": CPU Frequency"] - timeout: 3.0 - - load_average: - type: diagnostic_aggregator/GenericAnalyzer - path: load_average - contains: [": CPU Load Average"] - timeout: 3.0 - - gpu: - type: diagnostic_aggregator/AnalyzerGroup - path: gpu - analyzers: - temperature: - type: diagnostic_aggregator/GenericAnalyzer - path: temperature - contains: [": GPU Temperature"] - timeout: 3.0 - - usage: - type: diagnostic_aggregator/GenericAnalyzer - path: gpu_usage - contains: [": GPU Usage"] - timeout: 3.0 - - memory_usage: - type: diagnostic_aggregator/GenericAnalyzer - path: memory_usage - contains: [": GPU Memory Usage"] - timeout: 3.0 - - thermal_throttling: - type: diagnostic_aggregator/GenericAnalyzer - path: thermal_throttling - contains: [": GPU Thermal Throttling"] - timeout: 3.0 - - frequency: - type: diagnostic_aggregator/GenericAnalyzer - path: frequency - contains: [": GPU Frequency"] - timeout: 3.0 - - memory: - type: diagnostic_aggregator/AnalyzerGroup - path: memory - analyzers: - usage: - type: diagnostic_aggregator/GenericAnalyzer - path: usage - contains: [": Memory Usage"] - timeout: 3.0 - - network: - type: diagnostic_aggregator/AnalyzerGroup - path: network - analyzers: - network_usage: - type: diagnostic_aggregator/GenericAnalyzer - path: network_usage - contains: [": Network Usage"] - timeout: 3.0 - - network_traffic: - type: diagnostic_aggregator/GenericAnalyzer - path: network_traffic - contains: [": Network Traffic"] - timeout: 3.0 - - network_crc_error: - type: diagnostic_aggregator/GenericAnalyzer - path: network_crc_error - contains: [": Network CRC Error"] - timeout: 3.0 - - ip_packet_reassembles_failed: - type: diagnostic_aggregator/GenericAnalyzer - path: ip_packet_reassembles_failed - contains: [": IP Packet Reassembles Failed"] - timeout: 3.0 - - storage: - type: diagnostic_aggregator/AnalyzerGroup - path: storage - analyzers: - temperature: - type: diagnostic_aggregator/GenericAnalyzer - path: temperature - contains: [": HDD Temperature"] - timeout: 3.0 - - recovered_error: - type: diagnostic_aggregator/GenericAnalyzer - path: recovered_error - contains: [": HDD RecoveredError"] - timeout: 3.0 - - read_data_rate: - type: diagnostic_aggregator/GenericAnalyzer - path: read_data_rate - contains: [": HDD ReadDataRate"] - timeout: 3.0 - - write_data_rate: - type: diagnostic_aggregator/GenericAnalyzer - path: write_data_rate - contains: [": HDD WriteDataRate"] - timeout: 3.0 - - read_iops: - type: diagnostic_aggregator/GenericAnalyzer - path: read_iops - contains: [": HDD ReadIOPS"] - timeout: 3.0 - - write_iops: - type: diagnostic_aggregator/GenericAnalyzer - path: write_iops - contains: [": HDD WriteIOPS"] - timeout: 3.0 - - usage: - type: diagnostic_aggregator/GenericAnalyzer - path: usage - contains: [": HDD Usage"] - timeout: 3.0 - - power_on_hours: - type: diagnostic_aggregator/GenericAnalyzer - path: power_on_hours - contains: [": HDD PowerOnHours"] - timeout: 3.0 - - total_data_written: - type: diagnostic_aggregator/GenericAnalyzer - path: total_data_written - contains: [": HDD TotalDataWritten"] - timeout: 3.0 - - connection: - type: diagnostic_aggregator/GenericAnalyzer - path: connection - contains: [": HDD Connection"] - timeout: 3.0 - - process: - type: diagnostic_aggregator/AnalyzerGroup - path: process - analyzers: - high_load: - type: diagnostic_aggregator/GenericAnalyzer - path: high_load - contains: [": High-load"] - timeout: 3.0 - - high_mem: - type: diagnostic_aggregator/GenericAnalyzer - path: high_mem - contains: [": High-mem"] - timeout: 3.0 - - tasks_summary: - type: diagnostic_aggregator/GenericAnalyzer - path: tasks_summary - contains: [": Tasks Summary"] - timeout: 3.0 - - hardware: - type: diagnostic_aggregator/AnalyzerGroup - path: voltage - analyzers: - cmos_battery: - type: diagnostic_aggregator/GenericAnalyzer - path: cmos_battery - contains: [": CMOS Battery Status"] - timeout: 3.0 diff --git a/system/system_error_monitor/config/diagnostic_aggregator/vehicle.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/vehicle.param.yaml deleted file mode 100644 index 45ede1a4de000..0000000000000 --- a/system/system_error_monitor/config/diagnostic_aggregator/vehicle.param.yaml +++ /dev/null @@ -1,16 +0,0 @@ -/**: - ros__parameters: - vehicle: - type: diagnostic_aggregator/AnalyzerGroup - path: vehicle - analyzers: - node_alive_monitoring: - type: diagnostic_aggregator/AnalyzerGroup - path: node_alive_monitoring - analyzers: - # TODO(Tier IV): Consider splitting sensor input and control command output - topic_status: - type: diagnostic_aggregator/GenericAnalyzer - path: topic_status - contains: [": vehicle_topic_status"] - timeout: 1.0 diff --git a/system/system_error_monitor/config/system_error_monitor.param.yaml b/system/system_error_monitor/config/system_error_monitor.param.yaml deleted file mode 100644 index 63fdbd0081af6..0000000000000 --- a/system/system_error_monitor/config/system_error_monitor.param.yaml +++ /dev/null @@ -1,55 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} - - /autoware/localization/node_alive_monitoring: default - /autoware/localization/performance_monitoring/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/localization/performance_monitoring/localization_error_ellipse: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - # /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/system/duplicated_node_checker: default - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default diff --git a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml b/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml deleted file mode 100644 index c9ab89a8fce96..0000000000000 --- a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml +++ /dev/null @@ -1,56 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} - - /autoware/localization/node_alive_monitoring: default - # /autoware/localization/performance_monitoring/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" } - # /autoware/localization/performance_monitoring/localization_error_ellipse: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - # /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/system/duplicated_node_checker: default - # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } - # /autoware/system/duplicated_node_checker: default - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default diff --git a/system/system_error_monitor/include/system_error_monitor/diagnostics_filter.hpp b/system/system_error_monitor/include/system_error_monitor/diagnostics_filter.hpp deleted file mode 100644 index cbca3ed1c477c..0000000000000 --- a/system/system_error_monitor/include/system_error_monitor/diagnostics_filter.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef SYSTEM_ERROR_MONITOR__DIAGNOSTICS_FILTER_HPP_ -#define SYSTEM_ERROR_MONITOR__DIAGNOSTICS_FILTER_HPP_ - -#include - -#include -#include -#include - -namespace diagnostics_filter -{ -inline std::string splitStringByLastSlash(const std::string & str) -{ - const auto last_slash = str.find_last_of("/"); - - if (last_slash == std::string::npos) { - return ""; - } - - return str.substr(0, last_slash); -} - -inline bool isChild( - const diagnostic_msgs::msg::DiagnosticStatus & child, - const diagnostic_msgs::msg::DiagnosticStatus & parent) -{ - auto name = splitStringByLastSlash(child.name); - while (name != "") { - if (name == parent.name) { - return true; - } - - name = splitStringByLastSlash(name); - } - - return false; -} - -inline bool isLeaf( - const std::unordered_set & diag_name_set, - const diagnostic_msgs::msg::DiagnosticStatus & diag) -{ - return diag_name_set.count(diag.name) == 0; -} - -inline std::unordered_set createDiagNameSet( - const std::vector & diagnostics) -{ - std::unordered_set diag_name_set; - - for (const auto & diag : diagnostics) { - diag_name_set.insert(splitStringByLastSlash(diag.name)); - } - - return diag_name_set; -} - -inline std::vector extractLeafDiagnostics( - const std::vector & diagnostics) -{ - const auto diag_name_set = createDiagNameSet(diagnostics); - - std::vector leaf_diagnostics; - for (const auto & diag : diagnostics) { - if (isLeaf(diag_name_set, diag)) { - leaf_diagnostics.emplace_back(diag); - } - } - - return leaf_diagnostics; -} - -inline std::vector extractLeafChildrenDiagnostics( - const diagnostic_msgs::msg::DiagnosticStatus & parent, - const std::vector & diagnostics) -{ - std::vector leaf_children_diagnostics; - for (const auto & diag : extractLeafDiagnostics(diagnostics)) { - if (isChild(diag, parent)) { - leaf_children_diagnostics.emplace_back(diag); - } - } - - return leaf_children_diagnostics; -} - -} // namespace diagnostics_filter - -#endif // SYSTEM_ERROR_MONITOR__DIAGNOSTICS_FILTER_HPP_ diff --git a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp deleted file mode 100644 index dbb1db027b149..0000000000000 --- a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp +++ /dev/null @@ -1,153 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef SYSTEM_ERROR_MONITOR__SYSTEM_ERROR_MONITOR_CORE_HPP_ -#define SYSTEM_ERROR_MONITOR__SYSTEM_ERROR_MONITOR_CORE_HPP_ - -#include "autoware/universe_utils/ros/logger_level_configure.hpp" - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include -#include -#include - -struct DiagStamped -{ - std_msgs::msg::Header header; - diagnostic_msgs::msg::DiagnosticStatus status; -}; - -using DiagBuffer = std::deque; - -struct DiagConfig -{ - std::string name; - std::string sf_at; - std::string lf_at; - std::string spf_at; - bool auto_recovery; -}; - -using RequiredModules = std::vector; - -struct KeyName -{ - static constexpr const char * autonomous_driving = "autonomous_driving"; - static constexpr const char * external_control = "external_control"; -}; - -class AutowareErrorMonitor : public rclcpp::Node -{ -public: - explicit AutowareErrorMonitor(const rclcpp::NodeOptions & options); - -private: - // Parameter - struct Parameters - { - int update_rate; - bool ignore_missing_diagnostics; - bool add_leaf_diagnostics; - double data_ready_timeout; - double data_heartbeat_timeout; - double diag_timeout_sec; - double hazard_recovery_timeout; - int emergency_hazard_level; - bool use_emergency_hold; - bool use_emergency_hold_in_manual_driving; - }; - - Parameters params_{}; - - rclcpp::Time emergency_state_switch_time_; - rclcpp::Time initialized_time_; - autoware_system_msgs::msg::HazardStatus hazard_status_{}; - std::unordered_map required_modules_map_; - std::string current_mode_; - - void loadRequiredModules(const std::string & key); - - // Timer - rclcpp::TimerBase::SharedPtr timer_; - - bool isDataReady(); - bool isDataHeartbeatTimeout(); - void onTimer(); - - // Subscriber - rclcpp::Subscription::SharedPtr sub_diag_array_; - rclcpp::Subscription::SharedPtr sub_autoware_state_; - rclcpp::Subscription::SharedPtr sub_current_gate_mode_; - rclcpp::Subscription::SharedPtr sub_control_mode_; - void onAutowareState(const autoware_system_msgs::msg::AutowareState::ConstSharedPtr msg); - void onCurrentGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); - void onControlMode(const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); - void onDiagArray(const diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg); - - const size_t diag_buffer_size_ = 100; - std::unordered_map diag_buffer_map_; - diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr diag_array_; - autoware_system_msgs::msg::AutowareState::ConstSharedPtr autoware_state_; - tier4_control_msgs::msg::GateMode::ConstSharedPtr current_gate_mode_; - autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_; - - // Publisher - rclcpp::Publisher::SharedPtr pub_hazard_status_; - rclcpp::Publisher::SharedPtr pub_diagnostics_err_; - void publishHazardStatus(const autoware_system_msgs::msg::HazardStatus & hazard_status); - - // Service - rclcpp::Service::SharedPtr srv_clear_emergency_; - bool onClearEmergencyService( - [[maybe_unused]] std_srvs::srv::Trigger::Request::SharedPtr request, - std_srvs::srv::Trigger::Response::SharedPtr response); - - // for Heartbeat - rclcpp::Time diag_array_stamp_; - rclcpp::Time autoware_state_stamp_; - rclcpp::Time current_gate_mode_stamp_; - rclcpp::Time control_mode_stamp_; - - // Algorithm - boost::optional getLatestDiag(const std::string & diag_name) const; - uint8_t getHazardLevel(const DiagConfig & required_module, const int diag_level) const; - void appendHazardDiag( - const DiagConfig & required_module, const diagnostic_msgs::msg::DiagnosticStatus & diag, - autoware_system_msgs::msg::HazardStatus * hazard_status) const; - autoware_system_msgs::msg::HazardStatus judgeHazardStatus() const; - void updateHazardStatus(); - void updateTimeoutHazardStatus(); - bool canAutoRecovery() const; - bool isEmergencyHoldingRequired() const; - - void loggingErrors(const autoware_system_msgs::msg::HazardStatus & diag_array); - - std::unique_ptr logger_configure_; -}; - -#endif // SYSTEM_ERROR_MONITOR__SYSTEM_ERROR_MONITOR_CORE_HPP_ diff --git a/system/system_error_monitor/launch/system_error_monitor.launch.xml b/system/system_error_monitor/launch/system_error_monitor.launch.xml deleted file mode 100644 index 9eb805b0eb2a6..0000000000000 --- a/system/system_error_monitor/launch/system_error_monitor.launch.xml +++ /dev/null @@ -1,55 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/system/system_error_monitor/launch/system_error_monitor_node.launch.xml b/system/system_error_monitor/launch/system_error_monitor_node.launch.xml deleted file mode 100644 index f5ed927c7d6ca..0000000000000 --- a/system/system_error_monitor/launch/system_error_monitor_node.launch.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/system/system_error_monitor/package.xml b/system/system_error_monitor/package.xml deleted file mode 100644 index 2dda4e462b98b..0000000000000 --- a/system/system_error_monitor/package.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - system_error_monitor - 0.1.1 - The system_error_monitor package in ROS 2 - Fumihito Ito - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - autoware_system_msgs - autoware_universe_utils - autoware_vehicle_msgs - diagnostic_msgs - fmt - rclcpp - rclcpp_components - std_srvs - tier4_control_msgs - - diagnostic_aggregator - rqt_robot_monitor - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/system/system_error_monitor/src/system_error_monitor_core.cpp b/system/system_error_monitor/src/system_error_monitor_core.cpp deleted file mode 100644 index ef892bd01ff50..0000000000000 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ /dev/null @@ -1,722 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include -#include -#include -#include - -#define FMT_HEADER_ONLY -#include "system_error_monitor/diagnostics_filter.hpp" -#include "system_error_monitor/system_error_monitor_core.hpp" - -#include - -namespace -{ -enum class DebugLevel { DEBUG, INFO, WARN, ERROR, FATAL }; - -template -void logThrottledNamed( - const std::string & logger_name, const rclcpp::Clock::SharedPtr clock, const double duration_ms, - const std::string & message) -{ - static std::unordered_map last_output_time; - if (last_output_time.count(logger_name) != 0) { - const auto time_from_last_output = clock->now() - last_output_time.at(logger_name); - if (time_from_last_output.seconds() * 1000.0 < duration_ms) { - return; - } - } - - last_output_time[logger_name] = clock->now(); - if constexpr (debug_level == DebugLevel::DEBUG) { - RCLCPP_DEBUG(rclcpp::get_logger(logger_name), message.c_str()); - } else if constexpr (debug_level == DebugLevel::INFO) { - RCLCPP_INFO(rclcpp::get_logger(logger_name), message.c_str()); - } else if constexpr (debug_level == DebugLevel::WARN) { - RCLCPP_WARN(rclcpp::get_logger(logger_name), message.c_str()); - } else if constexpr (debug_level == DebugLevel::ERROR) { - RCLCPP_ERROR(rclcpp::get_logger(logger_name), message.c_str()); - } else if constexpr (debug_level == DebugLevel::FATAL) { - RCLCPP_FATAL(rclcpp::get_logger(logger_name), message.c_str()); - } -} - -std::vector split(const std::string & str, const char delim) -{ - std::vector elems; - std::stringstream ss(str); - std::string item; - while (std::getline(ss, item, delim)) { - elems.push_back(item); - } - return elems; -} - -int str2level(const std::string & level_str) -{ - using diagnostic_msgs::msg::DiagnosticStatus; - using std::regex_constants::icase; - - if (std::regex_match(level_str, std::regex("warn", icase))) { - return DiagnosticStatus::WARN; - } - if (std::regex_match(level_str, std::regex("error", icase))) { - return DiagnosticStatus::ERROR; - } - if (std::regex_match(level_str, std::regex("stale", icase))) { - return DiagnosticStatus::STALE; - } - - throw std::runtime_error(fmt::format("invalid level: {}", level_str)); -} - -bool isOverLevel(const int & diag_level, const std::string & failure_level_str) -{ - if (failure_level_str == "none") { - return false; - } - - return diag_level >= str2level(failure_level_str); -} - -std::vector & getTargetDiagnosticsRef( - const int hazard_level, autoware_system_msgs::msg::HazardStatus * hazard_status) -{ - using autoware_system_msgs::msg::HazardStatus; - - if (hazard_level == HazardStatus::NO_FAULT) { - return hazard_status->diag_no_fault; - } - if (hazard_level == HazardStatus::SAFE_FAULT) { - return hazard_status->diag_safe_fault; - } - if (hazard_level == HazardStatus::LATENT_FAULT) { - return hazard_status->diag_latent_fault; - } - if (hazard_level == HazardStatus::SINGLE_POINT_FAULT) { - return hazard_status->diag_single_point_fault; - } - - throw std::runtime_error(fmt::format("invalid hazard level: {}", hazard_level)); -} - -diagnostic_msgs::msg::DiagnosticArray convertHazardStatusToDiagnosticArray( - rclcpp::Clock::SharedPtr clock, const autoware_system_msgs::msg::HazardStatus & hazard_status) -{ - using diagnostic_msgs::msg::DiagnosticStatus; - - diagnostic_msgs::msg::DiagnosticArray diag_array; - diag_array.header.stamp = clock->now(); - - const auto decorateDiag = [](const auto & hazard_diag, const std::string & label) { - auto diag = hazard_diag; - - diag.message = label + diag.message; - - return diag; - }; - - for (const auto & hazard_diag : hazard_status.diag_no_fault) { - diag_array.status.push_back(decorateDiag(hazard_diag, "[No Fault]")); - } - for (const auto & hazard_diag : hazard_status.diag_safe_fault) { - diag_array.status.push_back(decorateDiag(hazard_diag, "[Safe Fault]")); - } - for (const auto & hazard_diag : hazard_status.diag_latent_fault) { - diag_array.status.push_back(decorateDiag(hazard_diag, "[Latent Fault]")); - } - for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { - diag_array.status.push_back(decorateDiag(hazard_diag, "[Single Point Fault]")); - } - - return diag_array; -} - -std::set getErrorModules( - const autoware_system_msgs::msg::HazardStatus & hazard_status, const int emergency_hazard_level) -{ - std::set error_modules; - using autoware_system_msgs::msg::HazardStatus; - if (emergency_hazard_level <= HazardStatus::SINGLE_POINT_FAULT) { - for (const auto & diag_spf : hazard_status.diag_single_point_fault) { - error_modules.insert(diag_spf.name); - } - } - if (emergency_hazard_level <= HazardStatus::LATENT_FAULT) { - for (const auto & diag_lf : hazard_status.diag_latent_fault) { - error_modules.insert(diag_lf.name); - } - } - if (emergency_hazard_level <= HazardStatus::SAFE_FAULT) { - for (const auto & diag_sf : hazard_status.diag_safe_fault) { - error_modules.insert(diag_sf.name); - } - } - - return error_modules; -} - -int isInNoFaultCondition( - const autoware_system_msgs::msg::AutowareState & autoware_state, - const tier4_control_msgs::msg::GateMode & current_gate_mode) -{ - using autoware_system_msgs::msg::AutowareState; - using tier4_control_msgs::msg::GateMode; - - const auto is_in_autonomous_ignore_state = - (autoware_state.state == AutowareState::INITIALIZING) || - (autoware_state.state == AutowareState::WAITING_FOR_ROUTE) || - (autoware_state.state == AutowareState::PLANNING) || - (autoware_state.state == AutowareState::FINALIZING); - - if (current_gate_mode.data == GateMode::AUTO && is_in_autonomous_ignore_state) { - return true; - } - - const auto is_in_external_ignore_state = (autoware_state.state == AutowareState::INITIALIZING) || - (autoware_state.state == AutowareState::FINALIZING); - - if (current_gate_mode.data == GateMode::EXTERNAL && is_in_external_ignore_state) { - return true; - } - - return false; -} -} // namespace - -AutowareErrorMonitor::AutowareErrorMonitor(const rclcpp::NodeOptions & options) -: Node( - "system_error_monitor", - rclcpp::NodeOptions(options).automatically_declare_parameters_from_overrides(true)), - diag_array_stamp_(0, 0, this->get_clock()->get_clock_type()), - autoware_state_stamp_(0, 0, this->get_clock()->get_clock_type()), - current_gate_mode_stamp_(0, 0, this->get_clock()->get_clock_type()), - control_mode_stamp_(0, 0, this->get_clock()->get_clock_type()) -{ - // Parameter - get_parameter_or("update_rate", params_.update_rate, 10); - get_parameter_or("ignore_missing_diagnostics", params_.ignore_missing_diagnostics, false); - get_parameter_or("add_leaf_diagnostics", params_.add_leaf_diagnostics, true); - get_parameter_or("data_ready_timeout", params_.data_ready_timeout, 30.0); - get_parameter_or("data_heartbeat_timeout", params_.data_heartbeat_timeout, 1.0); - get_parameter_or("diag_timeout_sec", params_.diag_timeout_sec, 1.0); - get_parameter_or("hazard_recovery_timeout", params_.hazard_recovery_timeout, 5.0); - get_parameter_or( - "emergency_hazard_level", params_.emergency_hazard_level, - autoware_system_msgs::msg::HazardStatus::LATENT_FAULT); - get_parameter_or("use_emergency_hold", params_.use_emergency_hold, false); - get_parameter_or( - "use_emergency_hold_in_manual_driving", params_.use_emergency_hold_in_manual_driving, false); - - loadRequiredModules(KeyName::autonomous_driving); - loadRequiredModules(KeyName::external_control); - - using std::placeholders::_1; - using std::placeholders::_2; - // Subscriber - sub_diag_array_ = create_subscription( - "input/diag_array", rclcpp::QoS{1}, std::bind(&AutowareErrorMonitor::onDiagArray, this, _1)); - sub_current_gate_mode_ = create_subscription( - "~/input/current_gate_mode", rclcpp::QoS{1}, - std::bind(&AutowareErrorMonitor::onCurrentGateMode, this, _1)); - sub_autoware_state_ = create_subscription( - "~/input/autoware_state", rclcpp::QoS{1}, - std::bind(&AutowareErrorMonitor::onAutowareState, this, _1)); - sub_control_mode_ = create_subscription( - "~/input/control_mode", rclcpp::QoS{1}, - std::bind(&AutowareErrorMonitor::onControlMode, this, _1)); - - // Publisher - pub_hazard_status_ = create_publisher( - "~/output/hazard_status", rclcpp::QoS{1}); - pub_diagnostics_err_ = create_publisher( - "~/output/diagnostics_err", rclcpp::QoS{1}); - - // Service - srv_clear_emergency_ = this->create_service( - "service/clear_emergency", - std::bind(&AutowareErrorMonitor::onClearEmergencyService, this, _1, _2)); - - // Initialize - autoware_vehicle_msgs::msg::ControlModeReport vehicle_state_report; - vehicle_state_report.mode = autoware_vehicle_msgs::msg::ControlModeReport::MANUAL; - control_mode_ = - std::make_shared(vehicle_state_report); - - // Timer - initialized_time_ = this->now(); - const auto period_ns = rclcpp::Rate(params_.update_rate).period(); - timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, std::bind(&AutowareErrorMonitor::onTimer, this)); - - logger_configure_ = std::make_unique(this); -} - -void AutowareErrorMonitor::loadRequiredModules(const std::string & key) -{ - const uint64_t depth = 3; - const auto param_names = - this->list_parameters({std::string("required_modules.") + key}, depth).names; - - if (param_names.empty()) { - throw std::runtime_error(fmt::format("no parameter found: required_modules.{}", key)); - } - - // Load module names from parameter key - std::set module_names; - RequiredModules required_modules; - - for (const auto & param_name : param_names) { - // Example of param_name: required_modules.key.module - // or required_modules.key.module.parameter - const auto split_names = split(param_name, '.'); - const auto & param_required_modules = split_names.at(0); - const auto & param_key = split_names.at(1); - const auto & param_module = split_names.at(2); - const auto module_name_with_prefix = - fmt::format("{0}.{1}.{2}", param_required_modules, param_key, param_module); - - // Skip duplicate parameter - if (module_names.count(module_name_with_prefix) != 0) { - continue; - } - module_names.insert(module_name_with_prefix); - - // Load diag level - const auto sf_key = module_name_with_prefix + std::string(".sf_at"); - std::string sf_at; - this->get_parameter_or(sf_key, sf_at, std::string("none")); - - const auto lf_key = module_name_with_prefix + std::string(".lf_at"); - std::string lf_at; - this->get_parameter_or(lf_key, lf_at, std::string("warn")); - - const auto spf_key = module_name_with_prefix + std::string(".spf_at"); - std::string spf_at; - this->get_parameter_or(spf_key, spf_at, std::string("error")); - - // auto_recovery - const auto auto_recovery_key = module_name_with_prefix + std::string(".auto_recovery"); - std::string auto_recovery_approval_str; - this->get_parameter_or(auto_recovery_key, auto_recovery_approval_str, std::string("true")); - - // Convert auto_recovery_approval_str to bool - bool auto_recovery_approval{}; - std::istringstream(auto_recovery_approval_str) >> std::boolalpha >> auto_recovery_approval; - - required_modules.push_back({param_module, sf_at, lf_at, spf_at, auto_recovery_approval}); - } - - required_modules_map_.insert(std::make_pair(key, required_modules)); -} - -void AutowareErrorMonitor::onDiagArray( - const diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) -{ - diag_array_ = msg; - - const auto & header = msg->header; - - for (const auto & diag : msg->status) { - if (diag_buffer_map_.count(diag.name) == 0) { - diag_buffer_map_.insert(std::make_pair(diag.name, DiagBuffer{})); - } - - auto & diag_buffer = diag_buffer_map_.at(diag.name); - diag_buffer.push_back(DiagStamped{header, diag}); - - while (diag_buffer.size() > diag_buffer_size_) { - diag_buffer.pop_front(); - } - } - - // for Heartbeat - diag_array_stamp_ = this->now(); -} - -void AutowareErrorMonitor::onCurrentGateMode( - const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) -{ - current_gate_mode_ = msg; - - // for Heartbeat - current_gate_mode_stamp_ = this->now(); -} - -void AutowareErrorMonitor::onAutowareState( - const autoware_system_msgs::msg::AutowareState::ConstSharedPtr msg) -{ - autoware_state_ = msg; - - // for Heartbeat - autoware_state_stamp_ = this->now(); -} - -void AutowareErrorMonitor::onControlMode( - const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) -{ - control_mode_ = msg; - - // for Heartbeat - control_mode_stamp_ = this->now(); -} - -bool AutowareErrorMonitor::isDataReady() -{ - if (!diag_array_) { - RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for diag_array msg..."); - return false; - } - - if (!current_gate_mode_) { - RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for current_gate_mode msg..."); - return false; - } - - if (!autoware_state_) { - RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for autoware_state msg..."); - return false; - } - - if (!control_mode_) { - RCLCPP_INFO_THROTTLE( - get_logger(), *get_clock(), 5000, "waiting for vehicle_state_report msg..."); - return false; - } - return true; -} - -bool AutowareErrorMonitor::isDataHeartbeatTimeout() -{ - auto isTimeout = [this](const rclcpp::Time & last_stamp, const double threshold) { - if (last_stamp.get_clock_type() != this->now().get_clock_type()) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "clock type is different..."); - return false; - } - const auto time_diff = this->now() - last_stamp; - return time_diff.seconds() > threshold; - }; - - if (isTimeout(diag_array_stamp_, params_.data_heartbeat_timeout)) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "diag_array msg is timeout..."); - return true; - } - - if (isTimeout(current_gate_mode_stamp_, params_.data_heartbeat_timeout)) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "current_gate_mode msg is timeout..."); - return true; - } - - if (isTimeout(autoware_state_stamp_, params_.data_heartbeat_timeout)) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "autoware_state msg is timeout..."); - return true; - } - - if (isTimeout(control_mode_stamp_, params_.data_heartbeat_timeout)) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 5000, "vehicle_state_report msg is timeout..."); - return true; - } - - return false; -} - -void AutowareErrorMonitor::onTimer() -{ - if (!isDataReady()) { - if ((this->now() - initialized_time_).seconds() > params_.data_ready_timeout) { - RCLCPP_WARN_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(), - "input data is timeout"); - updateTimeoutHazardStatus(); - publishHazardStatus(hazard_status_); - } - return; - } - - if (isDataHeartbeatTimeout()) { - updateTimeoutHazardStatus(); - publishHazardStatus(hazard_status_); - return; - } - - current_mode_ = current_gate_mode_->data == tier4_control_msgs::msg::GateMode::AUTO - ? KeyName::autonomous_driving - : KeyName::external_control; - - updateHazardStatus(); - publishHazardStatus(hazard_status_); -} - -boost::optional AutowareErrorMonitor::getLatestDiag( - const std::string & diag_name) const -{ - if (diag_buffer_map_.count(diag_name) == 0) { - return {}; - } - - const auto & diag_buffer = diag_buffer_map_.at(diag_name); - - if (diag_buffer.empty()) { - return {}; - } - - return diag_buffer.back(); -} - -uint8_t AutowareErrorMonitor::getHazardLevel( - const DiagConfig & required_module, const int diag_level) const -{ - using autoware_system_msgs::msg::HazardStatus; - - if (isOverLevel(diag_level, required_module.spf_at)) { - return HazardStatus::SINGLE_POINT_FAULT; - } - if (isOverLevel(diag_level, required_module.lf_at)) { - return HazardStatus::LATENT_FAULT; - } - if (isOverLevel(diag_level, required_module.sf_at)) { - return HazardStatus::SAFE_FAULT; - } - - return HazardStatus::NO_FAULT; -} - -void AutowareErrorMonitor::appendHazardDiag( - const DiagConfig & required_module, const diagnostic_msgs::msg::DiagnosticStatus & hazard_diag, - autoware_system_msgs::msg::HazardStatus * hazard_status) const -{ - const auto hazard_level = getHazardLevel(required_module, hazard_diag.level); - - auto & target_diagnostics_ref = getTargetDiagnosticsRef(hazard_level, hazard_status); - target_diagnostics_ref.push_back(hazard_diag); - - if (params_.add_leaf_diagnostics) { - for (const auto & diag : - diagnostics_filter::extractLeafChildrenDiagnostics(hazard_diag, diag_array_->status)) { - target_diagnostics_ref.push_back(diag); - } - } - - hazard_status->level = std::max(hazard_status->level, hazard_level); -} - -autoware_system_msgs::msg::HazardStatus AutowareErrorMonitor::judgeHazardStatus() const -{ - using autoware_system_msgs::msg::HazardStatus; - using diagnostic_msgs::msg::DiagnosticStatus; - - autoware_system_msgs::msg::HazardStatus hazard_status; - for (const auto & required_module : required_modules_map_.at(current_mode_)) { - const auto & diag_name = required_module.name; - const auto latest_diag = getLatestDiag(diag_name); - - // no diag found - if (!latest_diag) { - if (!params_.ignore_missing_diagnostics) { - DiagnosticStatus missing_diag; - - missing_diag.name = diag_name; - missing_diag.hardware_id = "system_error_monitor"; - missing_diag.level = DiagnosticStatus::STALE; - missing_diag.message = "no diag found"; - - appendHazardDiag(required_module, missing_diag, &hazard_status); - } - - continue; - } - - // diag level high - { - appendHazardDiag(required_module, latest_diag->status, &hazard_status); - } - - // diag timeout - { - const auto time_diff = this->now() - latest_diag->header.stamp; - if (time_diff.seconds() > params_.diag_timeout_sec) { - DiagnosticStatus timeout_diag = latest_diag->status; - timeout_diag.level = DiagnosticStatus::STALE; - timeout_diag.message = "timeout"; - - appendHazardDiag(required_module, timeout_diag, &hazard_status); - } - } - } - - // Ignore error when vehicle is not ready to start - if (isInNoFaultCondition(*autoware_state_, *current_gate_mode_)) { - hazard_status.level = autoware_system_msgs::msg::HazardStatus::NO_FAULT; - } - - return hazard_status; -} - -void AutowareErrorMonitor::updateHazardStatus() -{ - const bool prev_emergency_status = hazard_status_.emergency; - - // Create hazard status based on diagnostics - if (!hazard_status_.emergency_holding) { - const auto current_hazard_status = judgeHazardStatus(); - hazard_status_.level = current_hazard_status.level; - hazard_status_.diag_no_fault = current_hazard_status.diag_no_fault; - hazard_status_.diag_safe_fault = current_hazard_status.diag_safe_fault; - hazard_status_.diag_latent_fault = current_hazard_status.diag_latent_fault; - hazard_status_.diag_single_point_fault = current_hazard_status.diag_single_point_fault; - } - - // Update emergency status - { - hazard_status_.emergency = hazard_status_.level >= params_.emergency_hazard_level; - if (hazard_status_.emergency != prev_emergency_status) { - emergency_state_switch_time_ = this->now(); - } - } - - // Update emergency_holding condition - if (params_.use_emergency_hold) { - hazard_status_.emergency_holding = isEmergencyHoldingRequired(); - } -} - -void AutowareErrorMonitor::updateTimeoutHazardStatus() -{ - const bool prev_emergency_status = hazard_status_.emergency; - - hazard_status_.level = autoware_system_msgs::msg::HazardStatus::SINGLE_POINT_FAULT; - hazard_status_.emergency = true; - - if (hazard_status_.emergency != prev_emergency_status) { - emergency_state_switch_time_ = this->now(); - } - - hazard_status_.diag_no_fault = std::vector(); - hazard_status_.diag_safe_fault = std::vector(); - hazard_status_.diag_latent_fault = std::vector(); - - diagnostic_msgs::msg::DiagnosticStatus diag; - diag.name = "system_error_monitor/input_data_timeout"; - diag.hardware_id = "system_error_monitor"; - diag.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - hazard_status_.diag_single_point_fault = - std::vector{diag}; - - // Update emergency_holding condition - if (params_.use_emergency_hold) { - const auto emergency_duration = (this->now() - emergency_state_switch_time_).seconds(); - hazard_status_.emergency_holding = emergency_duration > params_.hazard_recovery_timeout; - } -} - -bool AutowareErrorMonitor::canAutoRecovery() const -{ - const auto error_modules = getErrorModules(hazard_status_, params_.emergency_hazard_level); - for (const auto & required_module : required_modules_map_.at(current_mode_)) { - if (required_module.auto_recovery) { - continue; - } - if (error_modules.count(required_module.name) != 0) { - return false; - } - } - return true; -} - -bool AutowareErrorMonitor::isEmergencyHoldingRequired() const -{ - // Does not change holding status until emergency_holding is cleared by service call - if (hazard_status_.emergency_holding) { - return true; - } - - if (!hazard_status_.emergency) { - return false; - } - - // Don't hold status if emergency duration within recovery timeout - const auto emergency_duration = (this->now() - emergency_state_switch_time_).seconds(); - const auto within_recovery_timeout = emergency_duration < params_.hazard_recovery_timeout; - if (within_recovery_timeout && canAutoRecovery()) { - return false; - } - - // Don't hold status during manual driving - const bool is_manual_driving = - (control_mode_->mode == autoware_vehicle_msgs::msg::ControlModeReport::MANUAL); - const auto no_hold_condition = - (!params_.use_emergency_hold_in_manual_driving && is_manual_driving); - if (no_hold_condition) { - return false; - } - - return true; -} - -void AutowareErrorMonitor::publishHazardStatus( - const autoware_system_msgs::msg::HazardStatus & hazard_status) -{ - autoware_system_msgs::msg::HazardStatusStamped hazard_status_stamped; - hazard_status_stamped.stamp = this->now(); - hazard_status_stamped.status = hazard_status; - pub_hazard_status_->publish(hazard_status_stamped); - - loggingErrors(hazard_status_stamped.status); - - pub_diagnostics_err_->publish( - convertHazardStatusToDiagnosticArray(this->get_clock(), hazard_status_stamped.status)); -} - -bool AutowareErrorMonitor::onClearEmergencyService( - [[maybe_unused]] std_srvs::srv::Trigger::Request::SharedPtr request, - std_srvs::srv::Trigger::Response::SharedPtr response) -{ - hazard_status_.emergency_holding = false; - updateHazardStatus(); - response->success = true; - response->message = "Emergency Holding state was cleared."; - - return true; -} - -void AutowareErrorMonitor::loggingErrors( - const autoware_system_msgs::msg::HazardStatus & hazard_status) -{ - if ( - autoware_state_ && current_gate_mode_ && - isInNoFaultCondition(*autoware_state_, *current_gate_mode_)) { - RCLCPP_DEBUG(get_logger(), "Autoware is in no-fault condition."); - return; - } - - for (const auto & hazard_diag : hazard_status.diag_latent_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, get_clock(), 5000, "[Latent Fault]: " + hazard_diag.message); - } - for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, get_clock(), 5000, "[Single Point Fault]: " + hazard_diag.message); - } -} - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(AutowareErrorMonitor) From 810a8d75b3a6b0efd695ea1bfcf1554759249575 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 7 Oct 2024 12:03:56 +0900 Subject: [PATCH 223/223] fix(intersection): set RTC enable (#9040) set rtc enable Signed-off-by: Go Sakayori --- .../src/manager.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp index 1ae99cafaceb1..609ff010d20e0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -441,6 +441,7 @@ void IntersectionModuleManager::setActivation() scene_module->setActivation(rtc_interface_.isActivated(getUUID(scene_module->getModuleId()))); intersection_module->setOcclusionActivation( occlusion_rtc_interface_.isActivated(occlusion_uuid)); + scene_module->setRTCEnabled(rtc_interface_.isRTCEnabled(getUUID(scene_module->getModuleId()))); } }

0P=|G?|nt^mwXB6y2fH(_Bu7 zbEeR+)-`Nh%o(FmD)n)Glp)J9GuMoft07wP-r*`sHOy8sJ9>Bud!gJ?n5ld=W4r<$ zqFG30!=&Pbs-5{^skF+TN_DPsr5mTB`b>a97B@;&?k#l@gD{kPOfcV1iC>RPV~He=6L#m!>eOj>a$xan!&-DdgroIt#Fy|)(MYx z*Vb08R|nJf*Cc}XM~^SwjQAQ}mEQP-D6#lOgsR0&YpY%1eSGuX5(gyyjf$rFgx9x_ zAo~8oOqY`_7^`{*p3}P@(~&Lod9|_rB1aE?51R{WBRQgj_aOE+HgVBs1=z{$LlBH{ zv;g+%J-m-YHB8?LUYkqe<(^a-@q8eNb@SUN-uE66C?!zSWj?6H$TYW9%fR-PVoZ?= zGtoGUT~8~ndJ|?f?wpl5-gw@a>Y_WL{rP*EiTZnrWd6Y;u1Qzwa#G@KDI3iJ!kpbC z8lJklV3g*BEW8XWp$*-cw?|EgUnWISTk9snMHIm=39I3`hX&(CMvDk8twR*`2EjdC zCF~BTif(Tf@+`T^30Tfl!?G43q7CR+HD{XX2gB|zZk^+>b_^JSQzAVc32syS29S)E z_G^zqT^4(^8|=x~vLGO;X3R+nEI?ERgk!&(phZss2(?`S;C!{0N-V&OYJ{{lA@J3_ zll5_O`Noml@a)JVfM|=w?xyq8!LrGM{!-c2Cjm~7>b2o&JMUFeBN2cTwaJwg=7R?}Z%}*CwR6AvtL_q1?L?h}T zUvitxA<1;T!O8lQ%Oh`z8rnJ(`rYSG^~3nUzId1vip?nE5$RDNAWrIBB|%<%48au* zCUQVt>&4v1f=!yf>dCQWfms< zQb6cl(N~!ziC~Yk_dUK>NH3p^$~7vvuCl0Z!W>`#44beF(8&hnN(JS;oR``B^ko*Uip$@R*E1NW{DNUO(JRI@7zD>wGR34LCQ17Sh z^BfgC;&)PVnCf$cd+xiGcj9k{Gk_*bgu%l}%<~T*H4P~fs+I!c!ri*7tY;rgp5+mf z^HY!sfY9ziN^x2?yCCcVJjO75t6hy(2%1(GDU=)(dCmr8m4p&<`4SgKps>^~Ydk88 zRBc^TZGKz~;RPab1a%7pcAq76A7onpR9X?W#n3sboTEy`^Ta(oJF3w&AfLW*_M z=btHUFidvXD48*-mTs45IF?PMmd&`AO&GK|(iV+q_Bk3soSqj}*1Ep1HK6xnygQFU#Wl zDJnV7R|1#?0)+<@n1n2a5yv@HFP=;lzc2FP#|xzut2QK}I4&rMlcRh;coiRNq&iQ* zP!yo4NlIj4#=K-)g1}X{C`+jJ>PbyS%>pIK7$l6X>_~GAkOrGjx^w6h>FyZ1kyb*arBoy(q-)**3-@;K?cV!&p5uML<2(4N zKjyygb**cybDirvA02qnnKHGKM74NzT8DcuJK)@-Z;cN14`+@v4Q^}j!cjQTBqoT{ zEcOfy!ZRnGF&~}=$`b8F^b+djE3UT@?xdl~d*ZxS&)$#E3G=)mXFNllZtHW~)?>yt zfVmVr?GneF+7t^dZtUKRgBr96Eok{QO9{Y;jNXBa_gn;S$>d3l0A(U$PsE1qt7l~R zXPn6h_D2lAATdcfmyycH62v;|a-YseB_oKe*_Xk&gaIIepOytllJ$e3C=mx5K-Kut z9q0CaRFd>JO_FuX+p^IV&!A<(z?$rc1q!6Np0N|0x)G?xmD!Qg7ReUnK#(4=3@We@ z4~fcbQ0mU;Pc`e!tQcyJM9IvhYQwe&lpS?FjR(9<)|#=dkGu=*-Eu3d8sB4a-!_cH zHG2Laa(p+;w_pcNlRSaCUrG99A8$=ZY27>O9Tr*Gd~V$Q^~dg^*TtI6{e<>hAY}24 z5{NhYWM<+r!o+fYq<}C))DsoC)3Vig#voG&TN@Gi6j~*c`f!F6Dl8PqXyWG4vPTBpyyjvLeVPck=e=<9J7YQNZ60#; z9*W8jUnx7V%emypT8f{|fF)fXSrogLsMp2`n*-#8iNLo6u%Gq4IBQgfT2C9mZtW6N z*Z@=sC)P*_l+_bcJ9m&jYl~$ymB@CeX%04I%erf>Z_M_7`gTq)<1}r$ixK+=b%aD7 zV;$)&w`=H=d0LPcjPpXH4Vay51ys+A^dQ%1>jU-1nnoK+j3C$NXt`L~+0IPf*w*DV zh45K=y?&Ux(mNiUd}9UQWR6w1hGHBMKh8NZUm4d;46O%ZUsl#Ik8KbtieV-ZI5kk2 z-=CPLm2cjhHf}NwjOG;9R~JS1U(-;xHxl3`W|K( zPttl4a{{vdZS7-P!)Tq=5SHPq5DDQ#JU{@cJY|krh9XSthq}h^lL$jX!U#5UdS|$a zOz!=>UUOk|`sa$b6e%7?G4Y>Jx}$U9dMGBNB0j>6RO6(kbL;KT7V9EIoUJdB5La!`3* ze|qAgY|*PrIp8t9`KLtD{zL)9IQ>^Xy*JOHdlsccgP5zXyJrdu zQCXExVU<7WEs9t_71W2vhqb07das;T@BQWL0*sirZ$QRkt(iF*ZeeCtg`8R+`Vg8{b$1E1b8nB)RZmNj;cc>qnLTS}K1;0wTagkz!>Dij-nH2D)X+^DvjAlufm}KGd zmY0;r-#b{B=to?7C2pi2a|zhIPvh>UE_9Ogrk+FbrKRGMY&W2js#?A6rUyr!FUKDzIG z@TF^Euh}({9x5h1qI-J*gl#MPNVjN3dNonOOP;2qbjgSmWMy{gB=-|ED^OnY{ZCC! zjissI7NyYuHf(?cU`2h7B$^0AGsp9**Z$gRBkba{U ze5PL&PKi^9oO6PUO30@~cTlQqszTOc#us2>Q&E zTM3ABOxlUiGodl2%8Sqe3jRf4oa0CZ`5$I9hnf-qT2HG3OJh68M0{6^7Pb{FB; zA?xNMlMZXvje>?9ivS*Bs7Wd69lVdiCvb_mp9>8Y!i2Q<-*$1*35Bw>NuuZ~i$Lql zKfU1nkp1c9<$HX0x}Zs$p&}A^P*6VZopS&nOsL$|(N8eZF0=?XD1;vLDRv9Ni+e#V z8-r6m{p!kZ+Fvu833jtzf8{pH8PlvOCmw&-zl5`O^2O?PL?5633ZQG|o}EEeTCLa| z0N+zj_0rGmF7-LvS2lTlU&i+O%~J+zd210wH&`$_|**! z<04Pf%G*P|;4v`IAE?~?H?#fqCW6@&SBf=W>3adU2LY`Ium+r(Rz z6&beNJ*hyA5f6i)F->FxPA%SBk>As;2fZg((vb( zfEViVu$?`J(-!ji5_sQkkGfxuzHRmUu>E=o9P=)J{fD|fKasgUCZQ>=Mx)hPcBl%5 zR6@R`#E7&)_gwC*nEM%it1QeW$obCwv?Vrzpgf!#mM+?5{M<5tr1;D6nKaapK zo)%(0n+}?Pa^J>EB30$S-nX(*M>5~Vhl%SfqXbgIz1RK^Wxmyd5031z{ycI0s47=} z=;89K)obNv?cX$YvpS)-jYrihQdLeZ@ai*%a^53XptR_R|2^&Be|6tduxNf!h<=Dk zqJ-|x2aeMH2ls8}Q(`Ozn%UbLS``%0(LcLyJtAhIdGI#YEcb%d=Gkl)3}sku8S29< z=tk_&{IUDC^V0l6(Pz~i6|=?Pd$=4{uXCzq6*8|YI4Z67L3y&PFU^*!x2C^TuMxHP zdB8*%7&>9*wKc#p^zLrgFyCmFnwVY z^=l2ed^t6|Y$(FK>U|bB);dSWWnA%d*@9RvhT73g=nKWg&x#g9X*mU*UWsF(A4!xQ zUCUsA8K6V$_|xbZAi9#xZ!hIHhi(^2Md z+mou8^|RBl_u<4w!nN6I$ZI*6{`NB`Op4$*7gE!igpqyknMA)!b2CXWWN-G{YVrj#2voI_Hp;E?-t2_ z+kE49s_lQ3xiubk4*y*#$^ScJ`$&F|z#~Xl-{YJ4#&O)?wznZs=xyUeWZ`M}A`Y|h zCLS`jy?($QzQwjlj0-{cZ0eDp+wVFhn`5z!v`GH3QxXhQo3UuU)S>q5r8wlf`xg6C zIGK{MNa-N5o;dIl=w`=F7?FaYCrHbcj@YfSMA;wQ?SX!3jtMF!S;^v5>^y*QX>D*T zSqm={gysw5p6%oEKQ5c839tYIDD8h7jK<3m>^@}Yzqai>!(S3D&VlsjLRRyDXprN3 z8Szb6Ti$*D2P?S02uAXy`oGpS{ptksSHW2M4|Gj`DH!8#oX1Dn{2UYS`%#9S^5M)^ zE4Xl^6U?ua5h9E?|0L1=#%SWlGD7jj9T?I5Rb`zxZ~yzzeP^g}X~aHN1R8f-1;$fH~nKxLSj z*K-M!#xP!yJc>U~+HU%Dr~=-ljD=ECFg6A6O-i`Bv6*gz59%bv-o>?NL)kV=2WDCM zIafU&(}~<7JBD!O1Nq1wdKLLoYrf&dn2t2R;KO;NIAV2NID!>t>@@cIpBxor#U1i3 zZ?9(0!WbH&&tvSImU}fP;(mc#fng?ZTE+D?gQdxqRrb}J3Wo}_JeH^)QkZbFNH`5p zh^{fDHz)-WRk6fSw@_BqQHiVp8~Il)pM9U>J#V^^Zk>NMAMNs4bauJoI;Uf8?BOGE z96gf9_eVnf$|GeS8sl|DAbp^Ic>7;Ye`vah^9G1Yu&kK50sW|nP);F!NIk!OK9V@2 zE){R&+}_0r?EzNw2OPK)wSrNY6gQoJEdZ`t1CtI-ao?^NQV<`)g6C z<$cyZNZ)Vk&eiXT+gG@FwHJQ%0EGQrjTZ;N0mxD2ex89*OaBN;_<}(F@i#bXz$^ZpQ{Dffb z;K|e!v^^I&LG*33As4@GeOPJ$)lK6B@*s6s=E;QU_^fRcl6KS7V$cPMaACh4EVF3Z zCo7lxi{$T-jinQEC7J_e{&S?@S=0T_w)HFMMA>Z$MEHNVOu;QY=Ir%9EgV-zHNwx! zh9)9i+ghJqIf|6$jyUo$hpue~7`Xyi-WF=>z)11m)FA(hyISbAHV(?n_-9in`yoZ- ze)%~s9R<`Y%({9YeqI_`QUaYW&U9s)$r~p)wgQQ3&9`*r;Cms!ZSuH5MIuOedV-!s zc7Gxijt2t(NQH!=7ZwgSogaPl44v%N4V$+?ml)LE`N<5^ixCmYNiy8VWG8(b4n{|VvADaGdGnpT9RoWDkZ%;zrbS@if>SA#(YbMA3 zfPP?hF+AjLMt(Hz$R)a|UIKFkNQKX3Ve z*AyLV`M)+roumGb148rbhdkPr8^PDuR+@-!njZ@7X0J3;3cb&-9(c%xbjXe{U;WYU z=Tql}fo}t=w>%bIP%QSfZqZW~Yd!YmQ%em)My>Z@h$~OCgy{FHmRjbfBk3HD8@^xz zv;YLP=jU1R3%vCO00^4Mb3H5YS9QVXn`x(aOgKq2g!F=s(qGECW7wNnw7@Wq>FqDh znB^VA<&p5#l^C4@{R9iFE&D^u*3a-3pS6?9)2m2_!hDw5SO4Cj@GoK=Y1#VOt>e&s z@~`XCM+iS-Jt-M{onfRK{94d0_GU79MM%4Gk_a4++F6imY$gfHK!jdL%F>@c705ju z2_;fkHl`20M1cWC#WAPp4v~W!cL+&ylzPA=EA3Au`a=sv(_uav$*z3?i%|K7R8Si*9UYw**69aiZI!lXcIIy zhA(El*ch>HVc#6RKk&^BeluZla~z$tEpI~1MWZa_8uvw;DPM?#&07y9D!z$OgpKU` zyz=UY@FJ5d4;vyqId*1}BP@4j(~m@@OF!<+=eKa|E))+~?k<*n$ld)|wfS*(sSb;C zZ@KA|)!s@gQ>*Q2C(qK}r|xT<`)hqSt@hUkeLsRkvJGlqzem3=-u>Rv?&JP;wX}j!2r!P3}7fs8;_PDV=!*)kER3iWZWPWc*M>%7a(CGQ&sr|ud`A=ZG zzk)VMW`t5VY7Pn`)&_)Fq!2^980b0dh2o8jK>l;;(P#R#j1n#nv+J})UJxKPMkF-r zL=YMKtkza?>hvDE3+uSh@+E-L03_J;99RHO z0$9iZW;z7Bn7II?H8bJC$z|U#5tIY;L1|+v-3BDsrO=nYG62<}Ktufw6C?m903)Qa z^C4T&?62^U-E7p#f<=5$ibJz$a7u zGIlx29xi|}pbPjSU*N(a*2UYcE&Myrb5WIVV;9mV3>UBqlO>(kZ~Qsd_4Nh*V?gQ0 zj^fWQy)!#hvw=A`j(o9Is85_T+UKFZDCx3+UC~}0Rx09HjMaTfv%hq{29CLRH}diJ zUC-lCzbl{vxB?+Z5rn`ev$2X7cES1$-}R`aGElYtX8ZK+sxwF+`c~WBsXV0Vd$5u% zEVc89F~A2fe1-a%MV}!VdPpC-&n?x9NQ3_+L+?+Z{%xe1+9LabXWu=@hruFb`h4KVBg5?3^xB)agP&+&vo6$@^`5o{GG9Cggf(*_WvtAer~gA&?^0pAUwln>hkCM@P5( z@0lh4DNg^lbC-sraHu`(8UfzR#sYWPZrnrW4fudHC(WEUYHGzVCht|UJ>nX#bvX%m?a40db)yB-lf`dykF~^~Wl|N?@inOO-B%&7A1*O<(YVC4 z@t8j+$C1c^5YVeEzFp?w_$pTrI5%1y7(y5tO#k3h8^)u1gC!a_m#r3EcN;EAjAc)} zGq@xalkZOqD5GzH+r=bxE%RX-TzT*QMV z5C>_B4+8!)57pezN;Y*LY#FMKYP{QL8uH$(XGVIL{t-qjag1)p@;>zUj&1*hT8Hkp!5{0b@U|m{(`+s~y)dQiDHF*7q-~k0+nZ9Y;uhm5O zBNM)s(Kn}@jY!7J=Lwr}3f4Yvv>yTWQOLbwn;PbwZx{@(ZJiF?wYKaF#zC!oGsm4f z?ya^ocIH<9{A7Xo5=doud8NJzLCmBY%ai)v%Z^7{jtwPMzvCfKmeym6_1YeV;Lz0Q z_46|*g*-u$B1TY%Le9(K014Iw(r|@Qg0w+3bBKlpeQ{CAl3{2B44pL`Y=#+v13@>joy{AKKa#s)yMzGt=O8P5T(vuud?DAQZ(`%ii zh(W!0R}*humBN?a_~7Jd+@pY@utB44Z_)yP8gs#-zv%v_1J{m6oLX+S83(%2rtOneTTZ(23AsXy z5vp#GXp$OzJJ^;q#;QWiDEclHSjIQb@Xr@VKKCKlQK89RXrm!C!Pu6px;~bY zYqQX_8_Bf3S&2ppnS|AZ{7{d=I4LvXLZVQJ)bSWeMMlWnu|o_)nj&KVuGm6d#NWHw zbGG@j>2IMyn=7_Fve-JDtb&*P`y$WLT#r0lhp;V7kUH#D-P7f#U<vWIbbjU*}cw zjimnAb|q8gOxZls7wxZ2Z)R&Xx}2$0Hdiau?xHnFS^gmBY&ps3C*YL(rrbtxn%(AR zo_38rJ|@-RCe0fcLrn3YnLAKaXWz4^HqzyVFB{P%85mW4sViN$@lTl>mKV>)i{V_M z>h?|`b}LQnC6>FFVKHPF(f{&AWyZ(MTC1gvH>Y`4-ZqC2-XypMxjK0ThiTz57mjF{ z7510oZuJznkFcaV3wXdWc!nEu%%=^41#TPH$5@_QpHSKqK8zbC+>bB zomJ)Qb&aeS!U)f#t690m^CDUO?Gb{R1k@oi;j7U>nN6&(A$el^cMTP(aONSmUeZc0 z{E9OsRi5hL8|I=J^cZd z_j|4{1J_^ zZDNVF{lI>v^aIDfStMWA-g@Y|S=Cw#1i`v75rZlCvE^+*TI)Fh2spTYr;?%@&vA;I#58eF5FlQ zGi5nCTeRJUI$1&}`T`)bElZSqRcBeGRm3+w-EH3t14BcikyN;YbkSH0p`zMI#Yj)o zC54TOcp@Phgtw$4hBQTt@QQwXZpB;9FOfJ+;yJ7OijQh%B57&sa}K)|Umd(8vKEPE z?&uXiW0@q1f!5|r6)XPMeo2%cBwF}~R|0H0lc+XZTdwS^1Rk0qVoA1&P^`kdWRhu5 zwY7@#uLi;VlIfWw+oaT2gCnyOECMhnZ?IZ~l#;76U7c;q_UBf4+L6qv+*G4nu^N`| zm%?`Y&=hesysR^Y<563O*3N1~9bPJzr(~xd#iz(tnN;qGwoW7dPf^`|sTa~DUzn5e)EZn`?@?c^ViLqD zM3)sl&g{)aHsKvW@X_VD^z%|(@A=Q!k22nObUMPmQBKfE@IqaR(!O?~={=F0xQq;C zeGCn$Xz@}{q}C^tvXt?)UPmj>_T+urx}TN;`KEs3_O z@kd=plSt9FfK-jWQGoB6aV9X_-t0oCSs7YM2M^+{duYqImh=X&FXB;;>!A`zgd4&E zXK6>uBb%y=CuprH0&EQ)_=Oyr7lf+AE6#wZ+vcBdhhyojmm*~KTA7OQzC2rGYQ_0!deqGFI2;)Y&rj@?aUvtyAK(# z5-8wdpT}Mm8%D>Y0gjA@9>DKdGzdGxkrcph<@8rt%dc*-e9s8Sd38qwDCH=`0R!do zQszLOj`u+!)AG&1BFYzunlX2>hf2-giWlFWe@0wxa~5uTHFF*)wAC2P;!~Zh)po#Q zBrW4z9(LRylGa%uGoSP@aMn5KC|?~Y@GrlsEZ|i9AzvStk@pN);jBxZ+Et8OTm|E8 zM8Oi0h3;_ZcwvSM6^yzKc&k)lw+f`w$S>9$RN{9;MzYs$wLZHA7Cjw7_u_N z&sTnkuVOsuPG)q>Kl&#_!2E`0ovW^=Acqv>w@r>% z!gffojlRu;{Q40vEA39J9Z-C&JG?FuO|jh%o9M%hfE@H;GqJf3SD&FTI)^6q%}7wo zoTj}f^(noM9nXq%flnt>(M924-*j#r(twWRq{D7TIz?K57=%}0ose)rc~mgBFsw59 z23-Frc{?k2t0TL1_iQ0U+{#qB!@kwiq`PIu4cYP*>)7VP6b$ZspP z98tI+16zT%_~46Bah0zMcLZ~qy}Z@4Y~X!B>oGkF%h87?u@HjUp5NDRpj2zyi|xr_ zhbuU+xXGM;C^~ROk*?|*xy}4QjkJ|`&Hd%t5i|{m%*&onO=E=4S(ulpFWhlylFdUL zL>M4bbIa3H_boI9c3Uz>tOA7))q0z2O9Nf9+BJ?_Ta&k8>`d;daaUjAi&6`#_ie`N zmot=U8=O=zKI48$9s8`uY17t8Pb!bdNnl)3r-%1bn4TOvm6-69U0_r=6crllId*$c zo@YFulRViCS_(^@5LLKuET@TzbNjT$`=|&}R57Xax5D-`#L?DR-rTU@*dYmU_y)~w z)v%#`Ix@Qt3^YiV8RdX(r1k2l+fKVZ+s_;xZD8pOR9}g#Rq7x`J~As{B`9ZRMd?0!ADjg#Qia6 zTnz7osCSb2IOJ%so*P=YM$G2f)C3xA1+=tg=7s*vb8`>91x0;?;Fmh&gq{?ZbqBg$ zUzv8TnDdB(!Uq*U-gQ*(NUDgeXHJe^NW@)wjMF>)R4hA@70iNF57H|^eREGbqzvD{ zjNXYv5|;V#Qq@9ZyZGaUrcRZrYzNeRR}+8suG$LD{IxC`V{@ z3vZd(o^V*f5Tan7pykxlJWymJbZS7Wn-xuBt>-F}MR6~(k0tFEIKS2za`#$i{_SFM-_4xIuMidq_nZhN z!Ojm}Sn!T|4dj%K-$S~q2?u)i1+eF^rOQ{6>W)QK`QD*QYIkxyD4r2HrCBjHm~tyt zC^JOs!W>l5j$`4uzt-+-LJR@_V*Y&1?o3TffWUI~r#SnS7J=BZaSZ?P;ZGWNxwciw z7q2W$E^%BDd}GUr;L1^Antd`s`!KJ1bLLszmA9X6%pOSLoo5T$TN~DQQ2It=9 zQmxDss|3K#UFS>;qs5|xqA~>6VH_+ugJXR{`6H?W>J98qbjD-ywAK^YExS_VC178Z zXdsGSc4L-F0NreDAgx$-=kiOyyDia3F}&=-+nGS{sI`%5XW0{qmk8GJlxU)*Sn)bE zY>#MdV&wl9y$Ky5iAb#7%wcb0aC*{(zJuW$^)ae>6`%(w13}-C&d&i6GP>c8&uS~D z8Np->e>}V|ni6*tvIi~Nf^~ZmjIB!SZx+)~UUaIwi`#&oop0$vkIDd!n|t(bvPB^vcs)k60KEjk zO-KeIv3!5sAQ(p8?Gvg3e~=TVy>;6M6tfDvcWd`N(~Jd-^$%>sY0kSu#S zBeS09N=?C=DYu-vOB`e)JRd$!pT2NTl(3?gceXywyvowE61P&Q*6X9e*g<%A}JADT^t6xW2wN6bw0 zt}99O!2t#J`|;jTi6l}=5OhW%35`l>z3rZkVw_wlh)p?vMnr@7Bt1}Qn68@4{Dxq3 zwX1*R*{L3o5`;!lBbNHbnE&8KVWLKlSt8=gWK)ujM3~TxkusxEZOI++evP5qFKdp* zD1k~@D)8cm;jOQ%-q4dMrfCVTz6(dmD5W=Hkh^H%ebu7mBrpHGRXo}}ffb2TyHl25 zAnrTCZqf|rMYoYK%UAs-bEA^OR$*^6jQ(|a|Msn?A7aATbq)i9A4VP{w&;5O*r!#8 zlvj__+RBjMK<)S6;8yGM_|Y!WZ$ugJnT8>}3e=)7W=Nb&TQFTy7^XBlHbbsmC<;Tj zcT}=_+9`~{b(M1X)3mH}EqI5H|70ET4DA6ogXz6wC0E5%I~gu6=dLgY5;FRfiz%Vn z8xF!UcKMoW;d0|d?^$WQ-L4zIUkwd5aH@86LYYsojpzipH`H0EV4;f>fkbfL(5aJ5 zFI&h@KQpW{fkHGQg|(=3I^uHZH3D|<_gAz9xRYD=Mha~Kwf-|9E>ye6} zC>F!3*xQ-0db7<@0DtW5tb&xB^EL0>(5dqo3Q^)G!XHzFuqdP{DWZbG7a{Uls?`B9 z)KC{Ebj|0(p*qU!GKECJ@g!WYE!xo~XAV$7eYtH9QB%xm>6}8HRFc(85<3R-#2bh% z@m<*URXW`ma9w=AG{yQ&C(|j;F_9upV{Zl&!qH&*g;{qv_b`!hSO15hJccRK^vJ%C zqm+xz^jqX#D3w~V@H(es*LyV(2q*yt$mfp*QvUgb+DOL!(vR{_{}~+}yww4q@yZuI z)zLL62%rI*D9gW1*taCQNq-50`lHpiADSSLhVW;~0BMTeoA#2dfn@dC{~^WWv-;aH z4(z=};b%7vlf@Am=KnDc>`&C+raA34W4 z_%Ho$LT-1EbLwufS~)?GbnaIm?I^x_0e?UciR}Q`-?w>@cM#jwe{cH&nbN+GR*XN> z`W5XhgD%nU%p+s}5OVrLzQjQOxX(+jl0TpNAZy^ivF80J81H|Fp!EwfYuAvgGjYpV z&4D+s=T;%rin@QMwaNF(O-cN%W`<=|i2Jr;Hzxv{UTRfxW8_cdAR6B;;L@&)fR4#QeZ{0jQj`9S7i77Lfr&H&EOLxUw71?2W)9^IS zUosv|-CQ&MGv(6ifpI55dW1Yyrjlo@gZnu5xfIAn%JhjLpVuBhGFK(6o$8Lr6lKfQ zpYLj~Zkj)jp0nzHe1Exl|0Qu=x^_ZF=T+Q|Jaoi%qm;^fP8T?4^8Obk0CWIJO=Lks z04T^m02>`Z`6elgtODx*Q>2~-D)Jvlzg2R-NRVxx*U5LhJ*GmQo026bbqp$ zaeS!zyAjUcJ>E!ZD4D^9>V`uxGF+#0!JE{JIFy&`RJyc1uPbPEmS-A|^fbZ(AACKyxb1j#o(Dt$8pwwNuuFauY?FD%9tj`* z_51wVHtp{gzJ4{>G=n!hb}AvuRO7`ChmWMXto3x`;K^RtBYnl^xM+m1TdLEI?aXJj zK9;H7>-h2{M;A#VUBu-DG6`%ll_zBFYduWQ z2*9$TMH(HMf|ZxpM@lWvH=HM^p7eb?#NU2W| zdJD!a+@V0I2hS}3WY85RtWElKyJ)sM4IkJ1GOT27AYcD9I_1So=m^do{ebrS)E|fC zT+z;QRPi42s_3+HtN1>Bc$swd8Ao+F^id&_#ICh<=e2g3h9^SXzjA(V3A=}f(s7r1 zcLH;~#rYP;XF3iCyW2d$W;iEW-#BA~HnhcK@Vh5mlkbG9o1`oA4!aSl zBgs`1M#$O4X%D1)5zgU;;fXiFk%DlW*R*=u(Q7YBPmQAUZjMp0&| zZK=`LH7sc{_u(eDV;@Y}eu%Z7ZcB@EI$%kE=C)yC9PdtRHxuv8XMoFM;72q|mZbCt zGP8-n=k$bgV2RJk6pRrG&q;%g6L50irtah2m}nh(*buR+dHasQQQneB5$=v221!TFMWnKthUf(v2v9d9it(qv~V-Zf@1e zp%+-fnlEQ90u#@=c4JN;zYhCswsiv@=Yn-3ScvUh9fr5b~5G@D;=1|t!GyvGeBMdF@x`sFz*7X^u1t>nh%s&(OzzwWLN{R7e zCP8>wm%u{^FL4^-HpoYdddEv*;TH1_DZkrb>-}927Oq+Wfl7X(X3{dXfJ#9C%32ah zjCF)iF7~Ad$VK%8xfWoM#^=FuK53HinfitTkmH)ZuO?+3^8!y`gdeTrWV)Cj7@PB) zpQ{$F88zCej8;q)nMV|F$@=G7LD#(+f@zaHg;>S7<<}ai<`td;>MP~8Tdu?js_ufS zC(bMPqnffRiV5x|;GEIwJ-gmLdAUx6FtDVN>hegGP}53P77f0=iZmm4gl(shlz&v$ zeWTa$8G^o1UGlSN8dcWhEmM*OXZDC%gz8wHL)xX!#K`FLzg6~iAckq1(qmml(8wwV z==&`by{j*-Lo`@&uRilfXQrF%Z*rA@-PxybKQk{ZW1e0>veZuD%bfsng!LK>sd@^j zX2`2V%Oo`2zg4^ACDoA8K$U|nMj*`Uqh@*IiA<<$OWM16#i{jm40v zZXEge#o#bLbTz?+$=(IcyVTtH8HR11^2`29MX&KJZu1EUb_etqr;xCB<_?vt<>Wn? z1YZ>*lk#;y+z*M27ER(^W>LwD*Kxp17yhI98&UYo9vQ82rU;*9g)ju<3=t%%k_g(hjNlH^n5Nq@uv2rh_(r#>^#e_<|Pe2o9{xkfF&p~%7N(Rq}*jN;O$liYXdxv-hBnI7p8r* zglYkzR|Mo%}hk?vR9UHxzG#ceVwx!PQhc_K(Q_c4OM@WiVp zC7s+!2p*HiD}&Tmn#UjHbj&*Hq3Yi?a~GbQo9H@c8SP$V^1^tFm~cbEK*nrrDztgp zg_;IMqlazP=*4_}!cLT@z=J&Z#d+POiosUKO9kxau%2?`M&SV3l$cuvebpRgQ*s#R zyvu7CgtmJXCZ&YnIq&W&j*QBRmzECXe5AXL)~66|P*@$Ie$k$^>!Mla1=*Ns^^Rv9SAI+_1*t;e$#^gD$66 zr!3bs7ZGpaZ8vl8TDtDCMb~XrC04Hlo#gAGv^w+BEbgBF_}&M8tcotz8*8r(BWQAT zFc?Lgy=B;{XP>z8zdC>Ca;B`{oJvGRKSbt1wvgcbjoOOAn3}a*?KiWUo}vSE@+6@W zx?(VnIe&Bn-Ki@ME~cCnsh6d;>AhQpE}ehkr&P;b=-9f>8S=!_ zT$}ZcEH)y&QWg{$i8%W~R%mA+?_i?{vHvkpXzv3jV&@g&V53XuU=uk*{)9jrJaXua z00$D0;_5o-1UX@sIf1ZAH|w0hgH9)SorzSPiEW&93TVm7oJj|rDYu-d$Xuv-UC4PK z;|TMFV%f1W+iIhbv$xtpyll^5yRxXdavQr|uyN&&biK^$dd16CsLWM(&=qRzipDGD zAr4}gbmFGPzySapY8?24lZF$rXF^x(2C=Q-<~RZG;%yJCaSfe-b!*%dCje^gPGrq- z$(XQo0;B;$M**X2=n!6B#Z|O+2l73GojmPYJ$+V)q$P-5XGq+cy)M{zk(asn40?GZ zw!HkXy{}Jt1*v+6wA$uGfY0@SES6ndA^{K-q*II|GzkI$fB_Vg3`56>mn+r5g4Ti9 znLVHr9)@7w>~7EvW{k^;w(MIcQ(%B36qEwRgu;NthlICa=sDef**dtT`6!(;eu^`` z=VrWXXIuu1{f7qqhg)4n$pVIqZ3meHrd0!GYy!|xg#8mZz=I&1csDd_TtXW{1t)a) zGO;BuhQStY?u7eIU5QLJCQ!_z`yX6Fjp)1S~m&OC~avqA-LAa4Y z=-VWZm|dtPU1-UJ>G^^g$z2$|+%TM7B5&hDmmfCh;-=dO3r~We`5-Fd)7=II}GZb!l^SRyLiI4Z&>%0o3OCL`*0R8+ioRN_!nL}V~= zFDr%uNCQBARoqKaHaRHhG2n=T8EP(JU%0C8hZYl61DiG`EvPD3V24!>_ixdU@(%wAvaJVkAm{6yrnL8hm29 zS&0B3c><=Xnv&8DTC~PB001Fj(8?fd77NP7RuLp-Cl3W#)Wt~ThuTDC^1 z-E8@zpS7jgOGP_Kc_-kcyA7wg@1%J|r#nV_OCSa?U(LG7MWUy4GsELCWFrBE2@sbq zE(cB&8UW+~p=jNha@g()I^lS_xC$_IxpW*coLEV&*jr$XUbU=OL*Ti)@uCT|{n*dW z&QjMd6DGZd5!l8t&}7H)Dh=^QVSt|1PZCx$N4{Z>uaU^XQ_p!7oil2jQ(>1gHk>m7 ziXW`V8Q$?71;w-A#GncDP@Zt~G>&2MIkBXhwPtEuw(~fLhAQiXtqBHc>kcwVJ=It8 z&`t!w+9DrdlQ>6`y)Pi;MWM0?%6st;jIK~XY+rCPrT{~?fC9o#R#|X%zTl*NLbgjL z@nr5C6A4E}!0p~bIG6ON_JVc(qCOTnBgBwPt**a03aRRf69J2}kbvD=FI~|dU;O!? z(xAk$bHy@QMUxT%BiI27yZ%bJC5mPx%DcttBgHckh3NIU{XC}&PdS`8ck{eimShEy z^l$+YZsG0@oUn(?s30G=p3Jxh%nd2DtSq$~DYckKe)Tf{2DtNXsfR|Hdq+A>!8v9< z_-%XmMQJ)lTvx~)Ff7d_OyD$D4@uw(Rm5(2`00vhfeKOSiYSeWbo+`-h-;Q~dG>Ba zZdQb$2zXBFX2@u{@I zK&oG!uI@A=(UJxmfSrKB>e1cmF~sSb34xj^jhc5^j+HTP__|bh1=K_d8%I)Dp zW|g1pYb#>lqV8v_DDqcF%2if~l_pQGMUtwX@OWu=T7xVfdym-Jh7g!PE$8e&&{?x( zPwV3gj`ae=d;t5chYCOlR#1|dE^hs{n*!{dfqEz|4GNVVAt)Y0PB%zhILXMCP|@0_ z!KU(*jD3)A-d0bX)?5mEZ(Kxu-H3Neuyf;mvdoxn+7a?d0)-&;ZbBtWkF<2085bZa zpCmUP9XlV#0t(XL0%43c7DePfZ>cBJ0aHsANY-JfcQ=EiJu&NXP`RX0<%7&`25~6| zN!C5Tpx20cE_9JA))?>cEJ7fYB7t@06zMB0szp9`wG*UwTIpVGhNC$FhQUBK6t+o? zf&-2W?Ic3sa#ys$m5RqOENfTE1`K0?#X7o`nLu58%UNkI}a?v53 z5~7ll(hbr`cL^AzboZjW8wBZ2k#0ngZlq00iFYnUH@e;D+;i^zz5l`d%rV9{pFkHB z1WOPG&v6ZJN(>`w52LycgHwjDG!0{%;GC6q8>4x0^@r>TzB(OFb#TP2(ZhU*1uD-^ z_22d=E=591N37E8eQrClvw(c_xL4&_N8t^my)zJqQy;qG;qf3H(bXxEUmI{`e=STp zc2&Iv0h+;h*eNO7b*~L+>A_GrcVMwz1VSsC$Yj<=NXOB3m;QRB;fJBh$&SRhc5!gF zm}a&~%D8dUxK=?65>xmLf&ZI$Dy?)xvFQ;dg&gBijB8NPQGO{&F(Q6lO8ynRn=(*; z*$&dWln4D(I8a1}t7LJ{Qj!buy@>K-Lh}<{C;fXTV^b!5>D3asq*4gH*Q`SC9c2%^ z1q-GZB%*|CFd`WZ=g?lgZ$#dg*wyv5aazC*{rz3Az|A+PY}3W*h-w2>ib+-7u2ouF zm3_rCgQT+?-7`blr3dxcxCH*_>zG=g1edc~BqLHNNeZHp9;RKb|6^`npOcCjDCqbJ zx}<{t2W@|c!|*IUj~&~&u6(pFwdts4DQDWAApUf?K@Wu8dBoHO)aC_5&4sIu3s*}P zu)`L_LdUEIoQe(-R3be2>##_}7WYdR{SQ4%wU;bH$MM~kXx$bCo>hdQ_Po<@9U)mh zv!Fshd?BFKa~IvuK_XFleKP6ll<;nXklc!(+sZwiMB_-;{3EPWlo#(%R=4O@6?ZH9 zlDb>fD(ZML5Zs)=5@E=wOYn&)a@Y&YMCl*UQgQ0naC=uD4z6Jly|bBHv*myHNar2y zV7tK12@1&?kjUE3-xA-`>6R)LB0)S{<=U{qCYcgyt-h1wCLNo;) zJxe{K&Ibm!4+t$wJZ6|qVec^n2udE73t_hrP2p85)^IA}P7;#O>Eqh3H^L|5p~+y~ zKy1KdB_Mo;MI5s0{H=6E9Gk`c6Wv+ndlc-Kh#yBZYg5!?aQ6cd@uMSD7r{d0?bnMR zXxO1^(`RNq35Ua)-@&>@#N7JmejKh-MB_vd`x((y-OrSFK{=q&JP4?}u8T=3rpy_$ z8VjVwCS3vrRiWXsFk~7fA{Iy>Kaamj%beN57Gm^18W#=G;A-eu@}3{|$Q^Wsx#oU~ zc1du=kA_ti4Iw_n)EBIs~{PPj|qe*|bEk8UB%?ppy#6A?_Kv%&zY_%1tqqEr4k6d6iTnB^n^D#NR#$XQK^s{(!*nnU(=IXXR6KnYDV0xmN09u9+``s|Y&y_gnNwCYOu z(Op$Sasd> zjA=H5(;;tKc4Oca`g9Y>tIw3=6iX!+UN9(b+M%(Tr1Np=qC~Iyc+7ezfnw(kyJwDy z*LJe4i1e7?8se|mpb2uPKkSrkq4XC^(>Zb8PtLP=_=a|qwxSS40vlbmO4ZnAxks&7UPio3&zI#02I%CPWvg+;k#8v}pyUmvAoeTu&-t#&i`*0~ z5_`Q}nRYzF0;e<;4-eWtWuO90BG=||g*r>Gld;3c7uD9_jAD2Mo1hDN5sFKaqm3fR zlY7u3ADVhBB`;%Ve>knn>4aCIu8_GUlw{G1yL03(%Q;<114aZv^{%<^9{EO{9P583 zV*ycb54!J8!UsAp5qX>q2~Dr}$*O%oActeHa=OOFJJ~1-PrhCDE)Em7X%(+;j=DoCp7spB%4 za*%fWmZd+$B*%C^&K(80c0mq}|E-=cwvPIOE}@^Jejrt@qd_oJ=b=F;VJB|IYeeKD zJ%3R@xfLH-WI}oO2e)iipcy-mp-4|zLd^t111IBXV~je}X!m_?vvhyFdb7-M4j%LD zI6P=zp&I0rSI_V>&rb}#Y$)hs%QnX^!b#B zux{y4*!0fiwVse{kIeEnSXbXSC4D-f=C1v8vd4{gVnl8&V$|?xC1S|XW)jcQ_sR7I zhxL82Sf#Y;82bsW=$tQjQP(jNzDBuL&#i8_5ArYUl)dAB_Mz*n`FOK~^X#iPP<1jY znLJB_JeP8Ek2=tx$O%zYFB3RB-3y!$jWs1`Z_#ZeCvUJ zj@QQua-=))LKp_aXWsaTi^u}>FR|=PeW-3zpsBNaqjJ9g0Sl{V1X+n51j4Gj2SQ%Bcm0zQq=nD}4^oSy$`ui)FN|}Q!5F=8%r;ni zWeLAyU6kFgEJROanP8x{^LDCYsI}2D@#?x5PiI+}?Kb6Fb4=# z@;de4l_~#TL8gttWW{ zLX>xTZh(jJ{fh%Pn<~0wrjNgR=Il;#?xl^t07Q$ljrMmJ+Jg%&Fct}?QZ1i(0UnjZ z_3I1#&90Su@3#Q)P4~ft&qs6%DrbnCmn3sFj`-*oeIS>3bODJE$^6W)0}vw2^nEDp zeKPIga`R)DSvV@um=I%dmjAM{lY_g0C8RG_K}-@5(g}40zXK@G7n|w8ZTs^3V)GhCZ4ONC=r26L|K-;C zX)d#i_PHjf)k_(akwopjYG&1{3&CT>It1ZKz>U^Mp~(%w0r3V~@SgSFI>-(58T9nmz51_uB}*@LQKvP2 z29GcF78mp!2DWQ`fs+`W&tRrR-ZVBaL&JBS$^6)ZH@I#C_}y!sl;`4bQKBfd&!nn0 zK{=`w7REtOx5kR~?g!zRmKMGBJmqJkAwH+&*OZHzsaj6eIx>$F6YN>ewRj+K%8=K7 z5Nd%xBW$j(Eo;4rV9A{t5=VB=9t(SmTBfd|M?vC_3z@ZIWfyh!eH*~#B6_Qyj;0`0 zw!vO&964)hZdRG|{XB(GJF?sZn%r1a*%u@#KLJ{ zX!%Tza6%!pNJ5Kd#R1u`{Gv5#BOH-qIiZ2%x%rtE^d*3%O@R<9#UB->P$#LD+}YiPc<}-=iip5j9K=T*lj1$b2(cUfgC{_AeSE({)0{WIbr9&W1T}ZY=7ubj2Y)!_@*;D$h9g{Y#7rhqoyZc90I$&cy2Jwb?>i%Pq$wEKJZa2m z7cuQTrRD-LZR=7@v-raiiv}aH!ieQR1uy>v}3j=>;H}N*7i{ctb5x z@pyLY7$PWLmK|dudG)AVd?H`Nl$4pbw8c9Y1<@=p-F_HR=N|mWl($d2-@fwQ5UU@>d@ZB%t!b5<5*c#)PBlf%S zwsKVTpp4~eb){W;Djh`Z+LvYLDs;T`Tcm7e<)%V7hC@F zBSYQs{7ZTBeAdL1C1eo`w{c@&dW;-AC+p-u#Z++_ijL8sY=pLn+@ zR=nm`MdN0sTa+{PGMluJi+PV3-RTa!KXy#aE1c2XOuuh9DGc>M;ZUD*#{hTe`gq=y z&{w*qV>appHqKv^Cv$^6%Sed9FMecirvupmX%I(}xqL%y?%i`Y95m%{VLbCUtnUd6 zRw89MHddk(#Qv^yNO}an7JJ(QG8-cj#;x?sw2(W(_aQ$7*Uj#c*RT=%BB819&NlEY zX^=b=B0XTnj{%g_>mZ5SmFw{>rR-*@qi8F=s!LTG#)$|4+*lbtw2T(ejIggGYGB4_ z3n5+6Rg0iwB)Chy0{H;odHo#ldEs*p1!xe z@cH4+*}-i3lTQ=vMY;_s`UiU#5)mr8`!VqJ^b9R$FG{eeTip?1!TN7*AdYboEJwEh z@-M)ylzs4wen}243{@EmC)UhBc2!aWECj~}=?JhZHlvc>na$6Ve82NnKa>FHmA;J7 z*F!}|QH%mCH{_dvSWiWJIfKHssg;d|AKs4liJ*z_#)98-3^0(?rXMquRD#?lkF%30O)-Iq=xmBPIum@=qcxDJlo7fY;Iu^QkCWj)?7&?=sh5Rvy0I?h?W~q3 z=&j1*ksJJQlOeD3D$ynF_d<{pkglCC;=(cAf6?4VQo}SClc=m0f%^1EEdNh$K+V6B zzdkq3ylIg5A8NnXnB)L0ql6nS%P;qMV3LFqj;Bi2Zcb* zw0Ti8{ck4>xs`eU4-WxWGo4$NJ(6RO{U3Nvrz0)R4g3RvDe#o&gS^9+t+yW^_VSaX z9wgK>n;KWLGy^r0!nce(F5`0!|E-i=Xk(`f!baak&9uKF4*qZUW*Mv zy1GsxkFDqk1&orji2Zs$QbS#@O6Fs^5#pd`devwUybkQ&z>f$ zOQ68t)1va>79fp-i7rOXWv3_ViH~A5vtCLi5{@IJ1gZOX0q}qB8LLr1I8OV?)hlLt0NCfXZE!L5O5JW!UL?c|~ z!U{jA8da54$3tAWM>6N18h|nzFc*U0!z~y`nkflQl4I{OiNfBgF&5^w7#m6HzFeM` zfINURef-;*l0oi3GhY5O@#&9cyC&jK^efL`wcCnZ``mm{*6SvcUjrnqlL0OF#yxwO`C@@ZIOG1F=(VLf4OmF>%6heBhF$^JrRAm_%8d(*SS`a6jVerYvA^57 z35P$DEn=y&sM-Rc?0rDXUA;5?!v}a84pGX>F?gkA-i?!w+PCp&WNFZ;I#}*xt;M~C zZM+EM8{T&-GFYIHzrz9}}khxl(h!9n0p#LHP(z zI6YjyQBae6T;VuOl|W}MYum6kAZ}*rVOD8>*C?e7A zrI4DofaS2e`&^MY{P6aMio-}wO75 z;w`EZaFhi$*4L8n#)!W&7M-gbwFg@6G00sZ3WZcRx#(;`t5Hea3=Wz?B_DEj#tn^# zpbayjM{+@<0tp#TP}W30P30VTPsU9_>ww$6g8eBlkLz(Md-LZsZzQ&gYab#Tl@R9e z3_l^*<7{<8Fv~CxZFw7Ily}=Ce%7u+)0{~NaqjUf=(Q?@`NfPqlVbI)h^agW1S4@4 zF|`zF)611~E}(|6`MVkdw#n~IiT`Avh;4d=0B}C~++lM6bryi!KfdJ6D@cHbz1P;o zI5-d;AUIn-f=pIOMqsEDV4Mprx+yb#Cy8xVP1?VhkI;v4J^&qz_5k#0ss7rf7k=Ty z(y8YTYI0H35|p0lO#Qx`cd~h}p{>8pcP)3GWUbor1nE?avD@AmLMvCnAXTR|=kv^d z93I0?UT&LIe5JaFaJ6=*gMnu9nq%M5kPD(KMRK!Z!`}M^(cRY=^39E-A34gB{w}yO zL9BN+vB1NyFfWCD1y(Z|h|LJ*P@}3?{ki-3-r!O`0O9$}1>SHL)e64hY64Ye%d9jA z)oKE+7dK65gvZ_TSA&6^&WIvVo;O}Ap#AJxppur`myRHmt;2RuG;xY_Kp`}R#!(m) ztj4>INaRXCOfFdaL2%wsbVu(sA2B$qT+U8G8`%qv2b_KLrCcz;qlV!^YR19gms3L? z&@HV4UDL0Om>{C4-v-AV{n?7-O<{kzLc$z$M;GtLo@)Nd!_~Q*?826IOs_ViGV#A5 zk~wgL0B%oVu}?Pmb<@O$xFuLpraiWKq@#*Lr9Q{xt5-bWV)J9{Z>&nz&Bd@hUhsPu znLn?L?q>1D+z(<(yW(>6#>HQYlDvDc?pGqa>!mI?^>B0FIjKD@{DA8uGVDEFXy)~T zlaFuq#8qTa;Pi%F;H#;wVWIWV=}GQae$cjj3@N~&F7T=bPQ=L$G5|B$AgOzuU7ae39Yod5 zPCp<+q(S)8XyZ?8E7hE)#VxA?p(O5l2MOmUX$v%2{mOvDV7VTWf(RWVFs`!7GRNp$@^@vgJNx`K>37 zMEhe?)t7xb2eCOn&UIoo-(~q+)w3f14Q$oX2$L2FcOM)i;W;1W2Va*@Ejaj8XPjl@ z+?=t!QZQj?Ezj1hd34wzMUXET^qv}Q?inMiB})!<Hx zb&IpLP)ItTF{A^1gc;CJ{CF|83r&B}=DtKm_8OzU#8#9J zP0;C;VR%R@p?DL`q@w3mR({-~&iJ&3o%T@V7i26~f-mbYb8)rWo>(Z&2>9J$KFtog zsoa+H0N3QCR)w;l)a+WAEN|&^!5S;;Fr1CO)i?a^PSbn=we1iCz}r$yrlXLjd&uC3VNbZP)0jKDTRVDaScdH%d$Gd zv4!Ly8WAg^QH1w+e)r+fbynt%G?h%F^UU3r{9-ziF78jH9TZ(KntXX^d@dRSFzm-k zXkZgXgQ|33Nq3%8W3SR&b${ZFf~ zp|Q@oW2Jd@j(kz9G*Gf7Esb+Oh}i&^bhXpDfU0}V`}WB{l;P4a(U7MFslbZ$v|76_ zRKD)|SvAe;ILF=<6Yy;Ta+lYijdvItk*;$(C9j>$7GY`{fKL4)R&iVqBo?tiUvB3BFGm)bI0=gZCE&aWJT_%d|XKUkaY~?22@P zygZx=J z3*i}IeoitNSwq@LebZDM+^Aug#g?Lhi=Q%we=XB-T<7hEim>xucu0kPkhyX#PqcPU z9Wv8)Y2l94c3Jl+tz|hb`!^*^c0z!CIHqd3V~a|gKAzhKSfA!Xd%Ak_cSPg2bI&C9 z7sGMJop%~ObXty!m9U7UiZmG`qiH9-@s%+4yF3pUzGiL`s3FM zJE2cah`2N|a-Ab?^+8Zno^uU|wYMpw)PK=Y$}Luv8>n9}_4L*18z(k`bqTt(J+8Oy z)zKR595DEaxom;0{=ClfzZP@vK5TlwFq|JudENwU^;^!K+_63I&|M16OzWj^eXXTF z(J=31@G0tzSs68#hpnq5(@_r2v(|FZ4UR{(a(q2a$I`8n}km(ehjg{ zmvMkz_WoY50K+A-iEcGW;>uWf=-u*MQCNDX4u!+`^~yQtqzPe(1>TR5#oLI&QGMw% zDTMl@ZWxdGD0A4)pffv182rTyUD^!im0aSJuntPu74EuRz^Fi3I$5=uaySK5RKZj_ zi@Gu|{(f_%S#rzF@>vMv=yazjM!14DkefNRlnN{E>5B!%M*f2j*f&V&Uw$VnqhD~7sQ`J zSODo_fS81ASO_;j^LLa-_!d*qw(F^`D%@ze+q6Ynh~m0wF0|2HU=vz>8Tyg~WJvSB zGUUR)T#ktcFY{mU#o_N|Jm`tc$Oo*#dMo2M(t8tcJ$|TMP+=++#3hfM(i62L9h>-! zy+0SQ3QNA@&)-3R$FQvc;)*t=T9)6IE>jj{yk51KUq)J#+0lKg;FT?MUkNF<4InT< z^=1hMMi4`Tk2oYf?;RjFDRlY|@V^gwLPkEmc8|U~{}PqD!t|AKq)G`Dlq~QAdD;C2x#L2_sFuRA(rBLj}cy zhkL6ljll9M$QeUwWnN^@_9hnmO=GSRMmP=;IoIpGMvLP06k|(5jgmryzL=8TZ-WVr zyr+cr`yKTi1nhk@BhWt5Cq(YuOvn^#$%!K+T)qlgjN&$!jE1t=6#&~{N<0x)^uz## z5WJgRaeNr{qhZ46w2(ZPk~;R*V5Lmlc_9mo1)8|{J;Js0eJ72Cv;ZParOO>6403Y# zH^>Piwc{nd7*YQ-77LMhyC3_p(Iq@zBY4y=GzzO8x`^Hq1h&ECP)`z1$bTP) z1HuKN==T(LKR1MHOP6;)y4M>?H3oOp8`(M@cf%v>jK>Z4P}-`i9APMtreWV$s}lZA zt}*X~wRWxHPG?SonvG85qi^tQ-wuiw8~juFWeQ<{AxbUmyM-Ufq~qB-B4rOPw?OXV z{z`r_^_ATta*79c06+OHZ#6=UkkF^CDpT-=XP;%D)vD92?&z3u&uRg{P&kwP;Iq2V zYr|>M;b9N-01FWg6Ze587s)pUd246P1RN~toy#}LZpiCYIC*cQb;@s@TAm!epKfm% za&K`z0rgJkdVJY24VK%ZiB5kucV~S;qGkYj+WP`9ba>z7%yvD)^|~Lffj@aHeP$qa zYCa&vAGS^z#9BgN7|b?KpA~u=*tLY+9bC`SN)W1?hVEmT8%0Qv6&OXzuxuDbDeyBG zM=Q&j8^@^Y6d1=ocvwI!k}^3e$7B?1{zobPBeri&lT-P#4R8Pj_}0*g4-sIYAuT)UvTxn6z3ziE>{t>bLo zI!&9*P>^L(xZaK-e%Ce~Oa8&l4je-(yH0%Fezx=twD?&6jx{h-IeprURWEJLwpBSx z#e+}%>=Vx)^>e;Xt{C7tcn-Yn%qgv5eIydg2p^qI>s(39$;#RV%Bu{u($kiEZ`2!z z*-dv&4f^l|LC{xtepBU=@E~e(QD*lk91v6biG~=c`S2DeNHBjOsJCqDj1p-I4N7`| zC-wHx4(ok0#i!#ToV$k^!)xD^nS8ulg5f2h!fUkpvyme3NtMDu5YY3@Ao!IB(q;_c zv1LpKG&8wgJdi}h%B!==NDst}v{0W6B}C{eXpIb(dajFwE>o}o=a(8j1T1&FCXPBPob(>Q>t-VQW>eTbMYIm4h!COVT+kTL?1q-XOL zn2&n7C}l#Q_Ho-3^=>-6L#H4D2h_uyaUpFAi`kW-7Y|%JuNJfd9u_LZg(K(?kmJO7 zbCLyFUQA;C2qXAhhYcgR@@niutNBXRnOei4 zN?*luJ8A{Y&Kz7P3`T|e2*^;hTjFj!`b?F(X4 z|8HXip!P{Su)?~3&)PWu!$>&L4%LHq$8^5mCj0SBBNpIEyU&IY`EAoqxAOwN6qKjK z(U?g$bg_D{1-Zz8(Dn|4gmZ@LAC?HaiY~nZt8~9~hdy$vq0&K?JqiZNWJomJ&;sG; z4Fw<}fe;8xq7v)+6Gy+~c2^dBCQzlmK_uehQQrZP7zyKmhLN`9qpWoggV{YIAt~q} z!cGxdm;Pe>U8?)UX81@^f$O1?PZw84Q0RN?Ekp?nVmI2cL|OTlbbQyzMl<5f7;AhrV3tXKwH z#nDnvmsJ*~gYYHN_vT`~iy$1^s2KvZy#9U$tEWWMQ)kT_3j8scJ)quc_phqyjNVK_ z)Hl25k-yY7A(cFe=o17B8)^2Sn@4bMy`a7$Td!%M9GA%pMZB^=t5iB*ZMvDW6MN9O zCi^0)kT-iqE*IBPJ6m^8lfIvb!zww;M#r4y!Fvp&@JD-$x?4o^aPMnge2ua3dW@pJ zC1I&jodUoR+vsivN;b;&mA-zYnY~3ojdly0)t=_YG>-V&SCs?mw+B82lMr#%^~Zqw zkl$)8%F$9GXt9Ji950b=#d{)O-7XlDHu^$DDD`#pK}6iM71~=zJ^#hf+jMkaAaXYKuhUN} z^Ia+;5EGpF^8Mrsdnz^sDm34ex>Y^bZdzr>G#W_$Qjy~@U^(%~rvrC;&!QA1R#SSN z23vT)?9NqOlPH?WK~?*QsZCa9S`AZgQ>!aID|YVcPf=u|*KEI%-L*?b zujp7l2EFiGa%ubc;I^Axuz2G#`B`oEP5wvWQO7H^XK8))sFCl|%HKJk-U#pQ{InEy zi){hp#+UZsl<);U!jaqqT`F}$V+xycM#``3 zNQ%7tgV*#XYTvfY?UyArZJP-+OuZi5uWD%8v2r+k{?1t9g<&w%UR-Ssd+?ySi}4X+ z+fy6(lTx9+yHxno(n~w9Z8JDiKPIq;X9|Zs>dl+^6wm6k#`NN7(D1>8+sC7ReT>-X zHzr?{9MH?x5tw*89k=;x>bDK$UDAi<_N(Zecl`%lvUyMTSJBGzPMSXQ4t3giTw4WE zGHFXd;t0;bJuD*{y@OSP1yZ27 zlTU3RSD}#1#)k8b?u+70QVFwE2PcYJC(3RoT6HgaR5Qm|zIr>?bchqxqjgECSyXnraZvTD)d>;#>serk{NxL)5zYWL3dtjf{ zvzxnsOQABr(a+RQy5>$Eo@FJiLo=6E zi-c7%UPuF%<*NXTmo*+Sj#$yuyu={H9b4`Q1=E z;*Y&QVs@i|P_dAV*l^9Rajcv12l)Fhzx8Iohup|@q>2xxlkhsu4`)~pC#MVSUB_Pf zNNA)8MJkiLyBInzL9{#as9wddW8DIa&N9b8I6y5Toin1VJDAiwq?I7@<$45VPXvty z)*!A`MH@7%E%IssMS6|x^~qp5$w(@+NX|3KC~oekyBbkk=8?P`QMU=X4JaI$jv^%j zDVXxGs_3Kn63D0zOji|MmFgne*Q3=5qczc@A2`LR8)1S`u#Y%mzlz10XvCU1#abl9 zTGhpV=(I787iH|R7A!M=ENP*IXCa9eW zOo*RyQ^8u<>`_O2?pqI!4f4clEW1D>J11!)32Mq%I~fB{MKe5w_ymGa3221Oa~u-J z)d|&bNv_;UF9?(7Op+>{lA_B@8=aC0%_*w51Le!e_2?rE3Gllnb?_u;a?Pn736mi& z6A^@H5fo^3@E#fgki)=~$c&VQ$&~4{jg)1L)J4hEcjl=}38~w4sk?!x?+a2taHoCJ zNZXN2J1|ev8Aq1FOGthKsWZ1MIJ9b5OheYRM4Ix|#7?MQvqn27(qC~-Pg2Z4aL#B- zh{H?FATG=x*vugLnnB8wNvWAh;hagHn29R|Sob}3JIG`s%0i%nKH+w}mgjRl-!l^5 z3F?182*v9gDip@0{~9h@=yk&sBKg)CDb5f2gqbD(hQOLXmz0mRqmN2Zj-XkNP;HJT zkB@8sc0rf_)iPH#wcAU#v9e>H8Y;4d8IVmFvKhtMX{qHcndK4t=RI-GdzP5zTA$}e zl<&cl|CllIn|>~9g~L=H)6Cfu2jpBmC;S2%o&tZ$f*7d+kbePrRzdJo!EsGN98sY= zB~)xfGg%F~_|c5lG#tMt3t!Udo@sXZRJb@#b_E!E(p|k;LA+H)8tieMshonhoK~xx-o;}{DiEto zTEq@ruoS5VOS;Ssv*fH*0gaoZ&`%1LyY%W2^tnB|77v^h6uX)Y$>a{mnEbil8%GzU$K{?Dge9LABx>wSWn5i7s*VJY)5=RQ24~Ck`8ynAmqCV?YJBDsmo| z=v5kTfDtFZpzFM{*#Y5RZL8o+_Mo2;S-~&J2G}gpu&?Z%F zG;u(zOF$S`Kq9e6l2%`qg_{93u!KERR+B_|KarxX;;kNua9r?F zJSSer)qV&Ap}Jr}6RzURrxDc@4~TAR2qo1em6|72BoMn2wzo>Qx0ttQeN1YjNMhQC ze)y(IHbuvY7ZUBT-Z3l*_yhN3y&UZ+Oax(;D3G$C>OplZw@Ps&4Nm5o8s5b}Vql3F& zNOn6PC%Wmsd~+7u6w=ro_N*zK1iPIZde7>WHhkBNS&!x;Y4f{XJQVSh%WYcYlyIto zIX4orP`e2edL3tab3^c6JXgQJ5g)(Nb9b>lUplZx-$>-RlgY_cVw<{p8G^f`+;R-ZaW-NdwV}5>Omp=VyyM#z|8T$9LeCq-9dA-xH?9c&s@2s zaeiU7&Mw_{+jnn0SIeL6&DlTBG3KrQnmjZOj!m(u%h9q=BOZ1}bx5}yM%Dhor5_lU zKC*e2nU5kq!tOl6me|U{So9h78Pf3xid7MXbt@(FDCYK~GDa+gDKkRxoTHm{{{DkW z=+)oOo>g9z$aMSLcSLCI+0V=BGx*+Q;8O5HRjsa>>-lo!v7E1u#^ z?84{y1-H4+?ldVk*VG|4u^HV_*w z98$(SncLFJ2;K8g2%Dmif_|8IofrLSO^ZI3=zuk8Sp&8X;jKB#f!SsLt$9KImAS=P z5jpd@*+(dmtiq|H_>5R6qbuTrM3>jC1;7}K<$R143DUaEd$aXufr(pE#~c0sq%E8^ zwd^>g(iCtYavIG0IZi_B;xo^;j+Fp>YX*RE!M2Y7-lN_t@nWVLS|bOO6*U%DLOHt{ zzf=w&7;gZ}6aW9m;JK62pmRJ%{4L9ed36=0A?yM_2?s?wmhW}f-~0{k^Lc;OH* z_;ZkdE;zq6*Ei_8vF|nCU`bO+qwovi0Hw0mF_`Y@w~wE<4g%Z-?rELkUf#MD0SCNy zF{k|Ze=eN-4ka3FpAPtK|349AW$6dme`b6RfZtvsx*=Q_fpL>u{I11G_QU3s-(iR4 zfNuK#0CxBTCYtry34VMD;qb4lgQNhz zj$vQ?Irri#L6RUnm@Ko)AcSm^ z9Tdco>u(@Dy~mZwcln{gZt(WS4MstgA^)FZaN*(7f8T!o-+4S}Tl~VO;Mby%OF~?1 z>Cm}O+=x=Q3*%E*!epmSV|M_++KCeT#_Rn17uft#{HbrIJg`;NfYSN)^IzUzKznuY zyJdn_;ER*wYR9NkWChxAU?=q@YKU{2$@WC(5Z)T?6>AGcBr`UJf&$YQhT(aUmJc=9 zOekcpM7>Ev*;|dV!jwD3FjWudq)*IXdvl^3b)gJgh+qJ=qJ2111#b4dA$YS38uD%= zZw|ykG!_@Suh5OWjWc^9~efr-cq%Xe`OjrH6eho^G!Fwm394>a1 zmrv&c2b5O)aO)qzxqp&aH@W`elg`WF9P~_i`l$>vmqFJYo0gHgC#z|g4=Gqb;Gdld z3uTaCfzC1VozzIYDA=3RR(%Chan7;43?-t{(J5qAAvv;Bv;f65a5A_7BHnF@uoLm6R&yiD= zpl1Ne-{B`R=TCR|#b4~7|MU)DLQdT&%q~<9p6UhIKTU8-^+BO%dH}xS!olD_yu(D| zz#Rri&=;hzrqq{D0s=zhxcFof) zC1A@bKu-dXEILyN8>4aw#JYq>C49L!Ne8gVAAZFmd!AvD{d+c~B(02-jb2|gu<#|R zE7uzcqtl=e7y(z?_&xMcxEHZF|S$h~zTD*KVYf5DhQTj+oK9{{|bM~W( zLX50jh_m94uMtR#%qGN&_g9Mj3las$YSZVQ z+m`|KU$)M35Fv~zHy(FQ2@OqEKTJ?*&k#C?L^w(>_VNje&>GEm+7*r6j4`4|)WHmU zD=V;6hQ=Y=p{;n|0~>|Mi^{>kqG7LAle9V+Op?*tdT8Pi7R<3yAG2herXox+yi13_ z3=u5_d4U!{c0ZrhAH5d?4_JQ2C-7bRUkWI24s~M{l(rv;PvtV1u+o$6+Il6YAlh)2 z1n+4>4+D@I$i4wyM|X^)3)L%N$`F>_iaO`o0?)-$;U^Qm!bavuehymkmT;{s|AkTb1-7^p}{jWsG^#$*7V;=>}H?y=9J_J0X zI(|6T-9X}|^cDP$G#6~6_0^`vs*tU!^FWtN?SdURRbxvB4gefHgj9Dl zWeKr*N_10puTFmy`APQtGj>OX^?jJi>0_o-n!gz%q%uK5ug01=(^GX4?h+SdxniksY*reOdJxBdM6pX}p5oXD^2V*u5| zb^jR|5268ZB5z+mq5b*ZLf#-Ohm>7@3uOS7YVLPf{58fed6#mvsBg>9KQAza{=J!y zHIX?dm{N#?qq!HZ_rqN|7dps$NzLyKZt5<)+6F=pm&A&XGJTz)ki{=j`gm1P7lBq{ zw)YKnLHKh-mK~|;ZBP-i8tg3?GI`~A@zVrU7tf{}I!d)U)x4KXB5QF=-m3W^=U&Y? z$KD^$q|dO8N*hoc$0n4B%*^>S#h3&-otH`8$yE}xxA9#ywE${<&R+?pKO@~aTzdbUV9K!a9l|$>6mU*3HL|z4 z%V4a$Cvy(r+lbFqyR64fTtFo7EKUoLUefwTK?DUN+F4``1spWUxMFc8NJ zlf8=u1e2Y*yVM94$9}D|6jN@6p95B2=Uu=rRiL1AN`vJ{_VqSrQt5L-_iHlTqF>0t zj^|nGp9$R;3O7H`jx1$-PUv;^&j!S>&pyBzXh0Axf0hT94{v=)`v})bNGt9}QrG_u zd6Fj_qbdE%)*EvZ)@E&T`^|-72iG(f{zm)HGi^-xga4`#{38w2EW?n?cV%x#-z>wfc$xBok*WIM|6` z7%@~8!i-23X_WeyjI`Bxo; z7oDpp{M|)Q>PH;=gW0Uedq9;|K3T8_Q6Xc6+b%e?>(J$ zbQ=0v^I!Gw@xty>H}iG*A2XvDZ%w`qy0=to{^+=aAN-5odqKEFrcc+O@>E{%fG0Ck z(8QtvrNg6&nPKDLq}~?wC4l{2JUBK%#BEzHC|^s!d08f*7+Af1xsyu=?(%1l`)@y- zlH?y%n7k?-hUW#NC@+tioJR14B5(hUFrJwt9*^}#(qWPj5-`%#p8(#!xI!`yWjtK| z!LxirwsXh|i!iR^IH=jnO|3v)9^{7X!pJm5PZ|{?SAbEIc=qv!(zPLszAFLnJgo0V z{~B@pjZ9sM0|ppk0vR zFNcUIPVw)XnahU=(=z&7nz&#@0mW4?p!@MB{>}F^aq(*Y$Q4&5dZV}4_D{tX&_&8l zL%)hUgEriArPJ^Nru4SFUZ8c7aV71wP378b**6i}+f25YqtpyE)Y>e!Mxd+7kyQSJ z*&Od54)KC3{)ckcY=RHrt#^_aHYx3IQOFty@;{|={-DWWm(lcp(v^P?^8Y9-2m7Cv z_7Ire+z(BT|4w~@?~Ip=7dH1h=QBBU**AMf6*FH0Ctczm|35#f2yRubsCp{X6p=xC<8M?}dJy*Hx3| zza|<)AJ#_m1=0Zc{`UmwH*K;%;@;vjb$Oz3x!nAt@gdRAf9Id?()8*L&{%U8G@Ly1 zx?E4BgMvVx0O~YU^{F+>Jvy;C;+b78%k&{M*|Rl@fL^5&0bSl zi?g-0=2|TGb};CBXdy}BP*1W0oocM)=G-^&_z&~#0e5IA?n%KhXeCu!86?-1ull*{ zOiJNA5#&ve1NtI~icr4h;t(%Yp8CB-RRm2*jg9*1)uA0X$pXuUntAtPys6O{mZJB| z2A+OZZ%R~lJ@q3l;%}D*<``_$|9%0*cKSWZzwT61I|&cwf069@t2+NNhajthpSExD zP>u?q2vS=DjR-j?1c8g!Glgzs9vTSU9Ot4E;&|zp6~wbIu^h(yHGm4r4(?g}g<$h{ z`IqmiO#c8$PH|i-c$fO@rz@{yy>Pzx!IQP2j1Z1ZGsl-7QOzzt4_F_(eld3f2vz5y z1p$fj_fSps^ z?WidM(-Lr1)XGY)YbLsvqNQAOM^<&V{@~usL-Q!}w-_I$qFZP&CEPw#+Kii_ z=N{iJ3-JPACrs{u3fKQf-COuY^>y#x!_XblDkajPf;2jVNP~b#iiC8DfPjF~Eig3F z-Q6JqO1FSCNJ)1$zXPJ8pSbgTzn&N@)}s+S9{x}#lf|L7!s>AIuc_!`ofqbHm{2&9t833`Ddl=_GfelZw= zw^|fG?uKVs`Us3l7Y1=YdZ|YxPm~2Yo? zp&?+XqRCjyZ{=86Ea((VQaLqLG3Pp}W*Gb8n=CNrR&3XzL33UK67(KR@8$Bv;*5au z<$7C#()C`$mCDu8jFtC?+Y2jIAmqcKY6K#q)fyDq%+(JVoQta;afF%HYVj3}*6IN4 z+*-XLBH{q(qnXjCII1sO>P>VhnYSDi2z%C>;V zy;P3L=_w_iA&*JL+#bq-Kiv`vxOn+aa0&JLGqQ?=`ZUQ@@ywhWZT7HmB+GA$wV@(Wi^TV37}sT+2OiSK znL3T8Eui6NS8xgEV0z&jnpTUPjlKH_YQQM zb237`AgE#%@d^*rD9v`VUK|Y<9puEx+XDn_^swEtS{3_84zYvz~TS z{&0~nEg6jlbr?~a+aDlRyjRc34X5ll9lyjk=f(*&wvmGA2-EtXHo#v_DVH-y6;1kV zJa9_QCcyqG$eB|JGB3EjYo0F1mwifZ$VYO~$oz#l_YUL>>N(3`{*_eavDyc9$GGW4?7OGtTdOtv&&x&IaN|FWYY9JXQRw5)oCY0JY3;2f1FhD;eRdw0epiaL zcyTz-ZQw%8a5B*C1>D$R#m58rJ1t)&J;1MC12;DMfh>cl;;0IaOa$Af_G$Nrg0jD4 zoPb1Lwru5$m!IH){HZK6ltQ(!#f3-}*9dL1M6}!aU_DbEkdHLPrC(!4~R~ zI`zR9CoWZ#Z%eqxBU77R9V&b}RQ+_{LedTr&{8w7&TkO9yF8KithK)jKfJ!rmhA*TnLQ|aS$w2MbY8gQAM0a;uqXrRtJSTua6d8PJfSAVVtqg`=L zVP|qqLJV&I#0F;?#N;cv`PZ96DKvb8L_4)xBiNqzM$SHiJg`NkqtEbd=p9zfn`sGVb06g^XPfPamkE?N z=DDrxoK0$?xoZ&H^aR5esQ)?%r<|2i=cl3ycArevo_eevUvHacis2<^xmoQn08iaR zz%~EE$+1`E(Mc`(RMyw3*>3YC;)>X1XDGrT)TA#i$njFo!k4>wnDmauTnKWuIf${I zCj6elBzjTAQ+_h|LAuIHE(8`|H1GRQ54vSUO;fsOy+Da~qY5FO@T88{>$D&8+#Cg& zp!E1bi!kI8M6W7+mVSc-cS9Nt+@{8lH*dNhqT%6716CMHnzWpD7O zqktZ|_Zq1(KHw25oN)EZ#^z@TqW&(d;Bd~cWOI}7@st@?U?oI_3{Iq`77s|fUh?@I z_#y%G1jHDZfv4^LLQhAyHzr|!&M?{md|(*!flz!gDsqbhM1r=@1>uF440rLP_teEt z0Ozq)yA}^`h^upl(97U`LF+*b79C_uESJt-7*<`VAIg5WQm&F($vx2$@P4&@;aTP8 z=w*}4%du1KAQ7XvAj=v+O$uc-DAvuX=P+8!B~o~^R$ncB*Nnn=d>0@V9Purls zuEAKrXco@gfU(h<)byCGjWyv4V-A5g62pC~rNe?W;&E3Zdyxz=!gnk)m-D*~Zyptv zOA?8~3ciM9vOGP?U(6~;l^H4Om-N0`G{BS~x!v+b28p==^#Q^6b(&?~FGEN)Oy60UY}y`IqBiv?jaLZ#lEqgzahDLO;ca zn(RL;G$Y9pOv9FLp37}uIan<0GpUeQeL&r_^loSL^YVLSR=&rJI``+(T+F==*9ABq z?02@_wLe^?8i2=L?a|HQ@7(TR@3=cc^z20^Hlp@>Xg_+;F=(O0{xx(t;p7f;xh#dEht;N5o-$o~%T8YzjgXae_bj zi2U&?=_kgDk54cQ0$mP799$MB)iL};>by%kIPp^BaB!^!4j!#}OAlOCG$=*AMIA@5 zG^REik5bPeR%eUXU#l9u%Y<3J=KCbC>uxfIt2_+b&jH_4x||cFQh3if3-*EVSfc^L zgU9fGt&K3?MxC&77o|Tt8WsA>CaEVb)cQvEUMFJBMNeUrqb zE83zwxE@m4n#5w&)beD1J+vAl`G&h_t7d$|-FgfytiYyL9iEN1l|!l_v7&7T${XSR zt;rlEO>HJN8xdm|DO?Sr?PlQ{k+TvhJbg{=mgO5!t8Y^HW<)z|1~;O2TT|}rG;wsi z-rtA;VWvWm#X6lxH)ByGQw4~cJFS(4(K-!g%9UxOl+*oMQei4sdBSh`;Yb@GH(Wp)vq%1u!LlyBlU7{!m#cb&;RGT7e_@R|KHr z@k5fcHiT$;V$hi^=Vs2+8Kj_7lH=N%+7jqCL@7oPWZo?VqQMpg5^V70?y<| z8{+AR`ZnK*y+50wca9!xE}pg_vb}&25HO=2D%@Eh*B<&17<$x~PC!4?oDiCH=xx0; z*i~>(@D8j3vI1ZI?BuS#LaWL&@)2yaJ-1yT9aA-90`Sf%A}k zeS)ji0zwt>fAV}>qYuXsZe1bP9#?iZ%3)jsW!x3-PU^V(RWm&e!OJ?t@t)U0L}Wb~ z?$lldp(eYJ*hCklMhS8FqR2dhzZwR?GiGiKHs;Hw8TG;2L+BBOP>&@#%>q*S06D_1 z*I;01)7Xo=7hkpA)Z9>~!!$!gr{C%%drpTN6gN#rnACG83822A)m5NEo1%7lA@FuI zl4ullCf12iY&OoxOK&Ki;8wa`0_+Y0y_c^nX-eSFXpp=GUW6T?+j`R`w|vo?2$+P0>x1%L&%e0On!o^&U&bYOnZ8C0sr4 z^t-*mA=dYYNQ=wWu{T|=5Jk^t+{kV>5fH=E?w=ekI%?w0ts`Es&8sJ2#aOK;J7K&f zu=M_b-0Hfaky#b(ko$Th{pnH4+PApg#yr!yo~w)jQR)B>P(`=#?SU`PX}OS&z0pKg)R~Jo5Al#b(UJ>i~Xf-V@c$S+CyX{V6}} z<%4yrQU0UdFFE#ydmHvAv$2<=K>WhhAR8&s6KTQ{43u=I!UXPMMhXxu7X&FF-JCF! z0`Yok4VKxeGfCp(QNA!Jj!Evb{w|T4cVNCRW$mua_)k_}r{J&*JQG>?NV#Xi_5Nx( zwkr2x9Oj9A>PJc>e|Hh;cpS&skJlJ(dP=>~yp*CR$Z#vqOYvPiVa~nUz2|w}oSRfc z=5+P9+}7TxOI#!QR4Q~^0Na^9QXE5{i;sA4+4sepAXHK74|mqr{A@9_P?6_^p~sSs zpGzcC5j8am@dQvVQi@O`-x76{lYN9-mPo_aBmlVBG_2&nQA)ZI)+i`@87p7HnZ1CbgIa_g z`Ie-koH?kkm4>ZkPQpZ>JE9AL_I91Vq?u-S{zmk2 zEiK;`eQAdiyD()fx7rK2+no-0as=+!a#3nRLS^O+r_!JA806nX4^L%Bs0LdVezof|)Mu zF4hxIx|J#-nJydJ+>^|+l_u?zE|((qIbC@xU9l})zNGncw#`*F>VFyqh0@AIThPO3T7X8M<*-X2H8h$BILy6nR9DNK z4i3@G2)bR4fgZh0?q_K%xid*hhJqjJd!W(Bq1%(MCsSUyw`K$!=A8NCjf8O>rPlPl zBXrk+K?@HF_(ETFH?%G6>eErng<$bfD=HP@N6GI4?-q%m~q~y*K zkKP>UJ&`-htDKjeBbTU2D3VH<#}JCDbO#h>S3==IxP-43#)U^;$JBAgK*mVihaFK~ zhqxe&-c(e7iR+ad3qiYq5^GE1Wg#vAV!9m%5#78Febs^L^4P=cIi~}{#&z5f6D|Ri zr`nfH1cdOi`X5H<@Zu%imn}ZLRzu^PHQWE{{w*X8wZuaP%{@M6pTK&7m&tno^QZ);|*H_({)*Gom0?4$B+PDf(EJzOY;KCK|4Eh9I;H#@# zPm@`Q^TzLaW6__gr^Z-qPZI4cc5@S&0&(myMJT?K*9VZuH1p}N5W(Q643CGn3uZ)B zPVi8S2Baxki}~y_&NfE~rWmLycF$EK1l*DLDJx9iQKN3KXj%7@*DkxwpC_=22I4x@~oXe6UrwR-?3)`gmg? zquTc&?CJQ!JlY{ar{qlb48M#ifRFw6J?THHr}ShIwvQfmJYVue4!pZ|@n-xE6bX6= zQUJczs2}l4D3=%ncQ4RK>Rd2^a*p`swFbYx(0X1VXSX$plt!GoEm41-=(ko-S{v3^xs?v*d#VSw@h#Ih(fKWt#JTdahzc*J5 z-&6>oZF2Y)0CeULc?U`X-2+Jgf8FQ&uS1<8uo!-Ch5s3^^KkdsnTYr&$B|ucCA2zv z8)@@!k8!pg=p6BEa(1QyoulvH$2XDQw^{#pam&xCCBJef84 zJ${)3GRfI~i_G}_7vs%+Bv55Ha(tOj-4y!K6&3l6o7Vt)PRLC92l>r;WJX4Dlleul z#|0n8A0foRaAt&M@GMW^$uQxL-^F=VHYg5s`|K-m{jnqvjxH{VwTq&AWCEuvqGoZ8 zr>`+;(P!Ep=~zzNeSbD;{^)%QSq0(>{z5NM`O*xylU#xW6}cBLRjY~m>$qHIqd0rP zp8Z%kpac**NE-ODoW3t7Tlf`{UzXE-$0Zg6qg2yxjmS(r!=I)Z@lX`CKY6mYf#>Hx z)?Yu_)rz9vR(ss10WUnaXIcHOtDWzmv&TvWR{33!2=G|GKfW*&#C>s~A9l|T9edw< zH#fe{8Rduk?jA?0;%ZDI;N>BUjL%Q1wuPrF|MM^G+Zvh=i0A($cI8iZ{ZgBn$)uAj zBP@Hkf-FYtbIbWRcUGFb1GYIM=oavZk1ssp@nvh)e|uyLp+q94aQ#}T#zKUo%5W)- zIpo(DObv+X>>sNB{D;WKU$R$lScV4Rwd%!Rn{7`PopAlFC=`J0M1716)kQ?Zu zLmm|06d;LoT~j%4d7pA@qOzy9MZ?RJGN%U3)g&XtVFfY347ySjF_lNcKd1F(i+>Y5 z|G6xUP>=_f1F3=sq2J-^S0Ar*xpZ0njbhHZW9%(+nsX?o4om4<^%=()L^rY<i$n*Oc`8@gM2Q=@8y!L{e{anWL)K8LN>rXh1|KS+RcXGbu>Zm#ZUIQcw-r1aYhkFwQDnwbFW zLeE9dNH0E*0}HeQeyw>VLq133y~BfI^fOi+T^rSt){q`(!<#dW+-kdHDC3zc?Yn2> zRM4yHc4bdIueujWgDB`#-wV~DvTBOba#SU&U^lYo#n}oF|1X0jt;grCQsW!Cns~5 z91i>tV+9IFc;YY$Cp3=6F=u3<(pVQPS(I@XV)?LfS5iwr+)n6L8s|Y)EI)3AJD5Nv z&6w^n=5@{2L-P$%yW*rLmw?_iN8WG%WkwI?*63Cwlhdk z9-x>#7)_qAR4YfBw$eCl3q4JypAOeaAE1fQ`!J^y`K(uTCdz!8ekR(|X2#pQq~F|+ z-@aIn&hOQ_C!G~4)|6^IY$7c++FzDIKPgZrJQbp1*_?DnF-sjowZ5K~knA;Ye=j7A z+Eb+bguyVg@PolZMrpfE28`LnN}T@&1F=z7ju*Equkd~;V_x}m^I}1ZkoQ7*y1e*O z(RLbfYSGf$LAsKDH$!7p_$LP0NwWqv+2wPZ^ULKc<@(-?Vi@>{35fo1Z=uCOLoDIP z#of)&qvW}qszsVBIUiOz4s)U-ofz{<@$GpWK;WX9CLosW76gA0#fBDJJ9!w*+t|Nkn$yF*negK+?wRys1n+fAr8y5ng$8thKf>a22;P^gd~5X{WgxvmBYu?(K;~sekud>O?51d-5TQURd?P^4V)9l zT>(l$e-HfHK8I1{YMR&S1hT{;c#WNT2&>|r_2M`ut24DMz6?4Y=-2jpIfZT}=O_+= z<@xQ#y&!v3Py>lU%q4jtQY950~b}$`ZN~BVF#0loP z<>AMqNlnkyBqp#P5Kv2f{kDFSgpFBX%px_NFnzPE*?JJG9cjLhWzw_ju=}J_<2br6 z1(j(&h2*hMFdM!URLpJK_n`1jFC*hbS3%LQ6ObnSw5u0Lc1z z1u^}by3X&fcRC?$#&)sm3E+xJInxw`;ix7HUK9HyUCGQ#+@_~xm+;BgW|Qg4QL2bA z&=zX`%GE52WiB^=B}A$r>78hrgaS`@NbhD6=j~tGLg=@0Ny!pZ1^LrueVTg`If5xf zT<2w@#2%&H+46l@Wbi1@=8>adaE8j3fxNpHeo)tDCdYk7sn4Vji^FecnW`E-9^&aM zY2M1VsLN2@XjbrXv7kU9#W4c6T&poN$Q7Vx(!jOtk7w%5^VH5%ryNrJDAk+q<-?@S zdZ5@6;GG$ZnI(G6Fj)B}kv8!Ws)@WUPH#w3QSPfOBlHR7!P@%X;sWL@{TD4mqg~WR z^aB~DF(3QJKlGGxZyD=5c;ii#2bZ>IF8sz6w|4#*N?;LE$!C{npj zM6F{;yt_3xzPT>6660tpyB~<#bKN*w$FXd8KT=@jc?e5P;6?1#(n;lcDYQ-yRw&ls zTIao58pkH-=*#1Xe&%D|I!Si0+rZE??S5XQozWzd2QI zy$Lg=`ql05T?_YrVtWT5tiQ=F=dwP0ld)2y!EKR>FApuRo@$Z*@M1f6I|NnX)eCV| zs2e+#AWsvP+Co;oCi$DNu8)&FQEY+1%67cJE!MA@*qasc%s+4fKF0Gz$RFNm!^Cqd1Nd?YsC{ zFD)^+3+0D4ieWxA@k~naO&fKpG7+=8t(RHYYXIbfOs6lLYoktK)4yw@gcz63VABAe zGh?ZE*m7a1Wb7NBGh!fOdi%Cvd8j@bZuz1w;g7d()zX_u@0~2{f|H!Kg99B=zzJhfd#pO zB+?qTJR#|Gt*?mo_xu0!qQRMU3K+l*E@?RDpx4uI*{T~mmLN}!zJhTsjsm>c(5sQV zrh|3<vQR-Ws$T{decN{8q7RQp@Po7CWVbpe>K~JVFeXVZmxPn|8 zV-LHtzrVY(pb!&t@_PFSZa2mj4v%Y0rz|+-tg4Q64m#QxbKw%zgSjGVh``+7pVPtI z;T`BEpx2&=OnA~Hhf#Vlrk7HBvzGT$zF}(?89xu04*%Q?y-SL(1-*wSHw6LgXHy_? z4%DeY0Rhp(AR$@L#9%Saro<2_p*iiB*Nf?N-aPG9oOWlA*MI7vpI@dErd6+>9BB|e zmmFpKfi}jjN_v_$W{qC!frazFs9ucS2lv@nFVaE1cn1OH)I@KxdA-Cpng;Yqp;F;# zDZ^WI>B1DgHbJkBlNe&tk@C}L9Bn@|dd;U7h64+dYp>fNi~6e)ZIl&w!7$gH@E{|v zmdx8wEY6L6vA|g1K&P-LyKM1~3-Xi~d)Bj^e`N5T7yB>uYyq*}6|2Ry28xy~lSb-L zBQy1n92Ol-I=5TQ9=g|M4z-q&2(y{KtD|8vyS2kt&;dDNvgj1VHn#XALY`&OCBd4- zE_m@0jsrCI(BXsrc#XK=3;c1~3cH=$(ZtY)X+Z-KWV{~JOKXdV5U76m)5e5m+P6Gd zz%&pJx`kvdR+KJ_00bcaNn_$5;P>X%e=TD0@)mz$6(-V(-|xPJ~L7W0qG{j>IWRoD{CL|6eQN_z?bCwYH)^}Zq{7tn974*Ba*uXrNs`)hcIGyuD2l9 zNSL*e}jB$pZRjA?&o44>6k7!T6vK+SSvm4nNQAcLk z9djY_RlbZ&X#$%-yeS2ngom=grr@PbUQUFuM!%elxI6lCD&_&1&DR9A?7g|j1QTl| zEM23#1#wn(E`OjP@f3RZxW#Z$1V?!c4B96P9)5(7rb-$&woO$2=1WE8GR;-Iz8~=?S zj>nnER*e3Bf>-aQw=OV3VgiBC;vjlx1XfQPB!+`J0GiNT7y#M15@e8+Sv*gz81&(U z2a-uHBL>TYA7_ANXK&9N!jkat7lo^4l{29Ygh5PZamV{gjO}OTj}GyC5weE2QPFw% zbD)ykGDt8Y{@hS=;ZIr+xbow z%{v9*jW;`m(X)V84re8M-2>jXf?64L$rp8x*rHx^DO)n~*#k+rPTc^J7} zYbZXvJz((hsAJHgMU}JGs>66^)OzD2%j%263A6R6NrJKUu;WZt=@)NWvW*rOw%1%k zfkeJsUqe-V_ol5P=wWNGL@ z@p3h?-}8(o;+WgL^|XG6>ve4Qb{l+OK5l;OQ1IJK#{S5-@wt~bhi`Ml`Q&J=7@Otg z>~uoM!TwCj%AJGx66}+M^*-{_>5VVOhH^SH&+ZzHjm=|4SCgF^-69sr_Qi!Xr`5xGuj@97Kkht-72yY+QTZ`FCe) z?vn=iCrc#u3hwgOIJO7Jcz-?8LTynR%nvCwN@8IYZc)|A4h=e}LoA}8WbScxE_Rq? zl_Drp**7y;2mmc|A-AgW1cvq%>agUMNgBV$^hm>?WoUTWY=(5xd&jg6qzHFklKrM; zkGB}XBUE-I&})N_>Es_Rx>vQL5~VH2J7>`7d>J20Gmt zBM1v@YTUgBUcnLCM+{0QH8qZcjs(nd;Iw5u*24G~sxnF$oJ-|>@1sBG*zhxQ9h5z= zAuZ1Jh#I{sPh0u9#_+{jYdqJ|%Z^;!?fk>m%=Kf>PwfUh1-NZ`dQfy}R7!IY>l<2q zg@b`!-(pKxzJZ7?@KdPnQqCGRm=Obcj-C%{$;l92?dzJ|low|2_f zeU{CILwj?Pw##+uvXu*3MwV>)%101a6!sMQo{r~cJ77M0(bv*fRZdjlJYw)@#{1De z>7(~sZ7Z(|n$-?CimLXHa_kdG)xnnup48r7%|x^Ne1uh61J=3m`YO}-vAkGnPFt=X zXR9)%RoF))mq?E_j)|Hr|5{JpwPCqPg-a>Bbu7L&M-(NV5_b@rCK`qLHUv%H*|Khc zV3`^8T%V%4yw@lql^@{#^dmY}Y*R?wY(UM&&-5yL&5G^$AtjGPQ9n#KIHP^j$eeYy zt$<0H7x;HG^50H`%R0$_;ogz`6g>V7R!Vv8iA2V^MyBt~Tz`%`_&E{&j&1q>(;M&) zkdS{2<@x;$s5H(jM8ge|e0Z}dF#wGUPTToGfObdFx3sA)fY3k9=lIFfEc&d9H=11-h1?A-Jm1^4pgcvUpR3 zH|DSM08yV+4)Exsdbc&Y%bmZQOl{thxeTt3*5tr5ITzZk5b3lcL;%i8l1)fAc%|sN z9!dU!Q_xBM>ocawmFMT^H|Ai%ZLW8*vd#@Y*b?nmN`EmtFBml>9AJ@sIU9kzc7M4# z-R-Vm56nWgR|gV8W1^8`cnXbjT;83m=`4YeJOY`&wB3kyL?la9cfweAh;>F6=pS>& z7gE%4ve?8W)ymkTm3D`v(TsUe*Vn4PqO0fp;zgf5L*>m-j56sxH?FI~%Q>w$;mfCt z5X_A2MWp2-5Fk9|k4ZQ;3d8J@aW|$gL(%q=lP8hkU8eH=%;`j>H$guUExQ5K_~8sr81gh??E%jxNY<&Mnb!`NsTCgVMB@g(~^ zf)-C32A0du#fB}TPzO9`(5DWJGDDkBeX>5L6hg9Vu>(Qy?F0wI9JU=tnURl^AcAgD-nGiwrs zG&Z!#NaGfW&+0QQPO9vUV8@ooXDTVlO*^}v>9Z=mMz6m-o2t#y5c_}tFkvwYsP2a^1%v39f=&SWFPNSZjy@4YnJ*N< zqLhxZ>3gFdg}8O~Dwy<5jT<5S3PczQCHH1Msb;4J1sG4!qzr>k-M1P8sjG&ITt&#* z;GU#0t^!{oPy_$g3L?(U1CM>S;ci< zn#D)(iAqWY&`3Zca9yldC~$|EWez^Rrrs)~G66eWv*=((MPPl804eN}TX8e@y6RwB zfZgPRf5;Xik&9e{lsrWw+X*f$#c_RYA&3?bO9C4Fgv&xVu0m4N6(Yy(+-j_^HmNa8 zY6F8qX{8jmg^XKmtCP7xL14C6cx(y|rd>K^wg47A`S@8<%?y;>M-GO5KGfN*bo8BqK*q1fw5&CJw=?JDM>W~c$FC@ zN`ZQOi3;3*6Q=~Xo(y%&MV@II_b$&Wj8sXK-mWj`77h-JeFY*(4=qfVx*CRyE1xF^ z0&x)Qi3A<^&Vq8?+Mo{D0SDCBbhKq)fWwWV2#;{1+L_x01eeMblD1n2OYV0M?2rX&!eW2lwLFh9l~?@YAdcH4opjp^(5t?6Jbef@r*w zxePjB_a}KV3P!Px@L?Vl=0LR0vr6m-bE`s6Ao_W=;UNP~2>Wb!NL1^wIB{qsz#@DW zC5{H^Y$nO*$Gzc&aU06#Q-N26Oh~0pI5*&&wwmO6r_%`&*OU_TRy7*}iV@~?Q)o4g z^u6$Abu~sGVq3D{7!gTC7Ogi45SX<)>~<1?s0TtlsMY>XM9+RH`+f@U+702zjg_*qNe zx=}+dfXwKhJp6$$LBye_XW*uk$e2&bShYNYfCS?m>gRDEIv3o)meNT&~|gn z+Or%n4I8h6I7|m+Un7U4UjF!jxG(p?Nw9$>#z6AE#QNPYUztG=Q+*Kir=Xd+;M<*V z+Bj1bD${Qvc)`oG5%zq2k17#D;kzl!O;1w1on=ljhW3FFr^^eJ`;nZcOqfS44kV9J zeHD!Y{%)K>r?-)SI7ctLvR8WQ?}x?t$vJ(Nz!}E?GZs ze)wES-s3R?3u+?;Q_8Fm`ZlqTu0+Da&FuB3_VNx3io^P=>Suw2y5D zD1zv3;OtWhi(+V9LMs)%Ovdd%&s1;{Mf7PZZ(8~T2A@YTpW>307CQK0(G8%sDqz%R zgm23Vc#_KJmv5bhle*gNjriOZ)a%a)cV&Z2%X*46z~M_eA2x$~TrxD*6Go>bgeF_s zkRXYtZ5gr=36h+#a&LyC@JM_xjG-Gr0Kp!c3-+qca=-gfvuzNQy`1UON@&#~dU?^k z$9SMV3sDVpSqcY_ZD|L*S|W#iS7{mYQMgG83ZxFz{yQj*U~EAzIE2i2B<3r1X!X_L zu;psQjqPDQVVnt)Y!C>yBG{W@8z)NC5#P9RrXkTtu4MRAC~B-4<6s`5nO^6>r4&tY z|G1Z>#4shqxrL^&)0d;VD{kzB*LsADCYb(l7eQ9)0tlb?Hna7+<|AGoC@776?>ZdZ z@*~}ku2>+ONFN#%j!*fa+3NJB;`%gsmrMHh;!r_xDr7a8DYf_92_V%;K9{4Ags_} z_GujZpS}jcs%a9_=BbUu*Ad1c$i#65_<{D2yogbcil8nrJ3Z>bR zydf0SwmG;He4T1j_RWXN?zL(uzR^!dnKT>%x89;<(*vCX(1RRI?3S zB^>bW*w34mBiBqbJMeOYo#X`+i4QO)_BTpt+FM~g@q#e6!Yg^|B`VqU7m~NG-SyB8 zr@|XlKswkC#XA;$g(Y_dDb<{Nn&6TQ-Q}-zg#nBo8f>Sb_t*p(@3?642RpQ-;1Cx% zqUqrnI6EMIazu!;D{+^hOeKVe+;O$KB_d5sH~aAVEF*%V^8%4WQ~fL9^;gBg6nv#G z2veQSX~kX$<1XI1+#29QD8nqQh->tm|Fb!NyNmN>CrS7)A_YBX=Pi8BJaxiG^^dxY zmr}3KQ<`ee(vA6R-ii})+{TEd|9s3wvrx-KmmS<(pJlE=(gS;w@&l ztpWxc?)DyZxW@iZtY>jVPWr{IQ(Zn#OXT^xo`iZJ-gXafyrfWMl0+rTD&WXS<+TO% zn$hqgAogN#@{0CwWS_l6-H-Evi&&w^vpDQhSd!ReiTA5g_xHOLBu)%D8lLx|Z%V?h z>T6>+mA)~Jd(+nV<~f{CJF!oPqEC;tPdAs3?S14z2XgHRpOJnaDFO81S)WNo-w6-$ z*_!{pHsD5b6Cf)BLeK{js_Idr|PX@Vp!7DEi=CdjkXLUIx&UxH9OY zvorMI%NK`3E{AG|p6WR-h zz#B?|57Po4y$qD24_1B~{8&HuiD)plXrO#q@Y8`{bO`&Q0wBw?=MGOqHA{LKp87UCy(~O)AUu07JeMRQpF5&ZDWdpg zMCsdza_&n7r4jGcE@Ich)Uep*#^u!5w^psNc^vmekx6$)u(TfAo%X`tQBr)sUF`G&;+b?5w-^T2h z#T*XA9Pa^v%CTUcSOn!*B%4^2@L06+Sd76~to>LV(l|VxIDF+eLYp|^@Ho=)xGRHk zWczUxr14Zd@zl!kG&b>c;qeUR@l1p9Ec>THF6m83x0Dk&l;bT$@uHg?IR_K&>?c4- z69sq@1(g$pY!XGn6UE9CB?c3v_7kN^lVo|42N^u}RhoPc|q|HX2Me*-thlO)=w1u?Q#PR!-S3ORz3au~QBQa$6ioQ=NEHjq#i* ztVujrJ&)!eZCC$j^$tWC*LFL5RGS48y#Yd{iKpf9NfXjrZ%mhO-b)VzZhi5jH zXI3_6Rt;triBYu^`}d^3seCEYN18R5o^<4&HME~KW^*}{G}{6|7XB1J76O-eJ#gXQ z&y^f6uvagVKJ$~rgW!mZZN4jnd-NZ~W;vdqln;ppeQkwHAPm=NN=yB&5H@JAf1LS! zu4IK&Sx3p#6niF`mPZ{b3>eK9WGn%u_=ulI!CrmzBkzH`8JS&3?iuM5OGU@w?uW~% z`O1sAWB|P0bD2MkU?w`q@D`_0kti@Ujei>dB+cf66w!&~*}c}RGo-P?38vILuD0=d zz&)@`%5Co3{y@lHs**=w6zr^7^8V_Ch5wglJSW(sqvZg5H7kUupQZBPn-uXN=G8i6 zZt&o9;Mnmo{E-68;dqTR))5g*hvNuecyII-wgB-ME7Fnzr7Jv{*0`e`)cOmEoP+DJ z$DWU#+7ntlK}}2g5D!fkis*i-SL`hE=mNq7LD!(XSUm}lyI43=Fl0njTz@3Ww5R^q zBuc@7w|}22z3sAj@*iB{|B@B)`xL+aF-uD29ulzw8B{$ONiYci0z(H>9VxX}SYW-e5NGtjee71s6G>=NT#Qu{Vnx~GuE z=AcMa8QTl5Rk_utYQFTMU)>Lg1l0?T;utV;Hr^UCZD8IRw&*k7iA=l_R06dnO7G!> z+GFFFLY%RscgJmL+e;>1e;HBmA{V%G&5oJZWbbR3?j19$aI59LnOJw0{n>AA?38RE zoU~+lf8o0U{IrdoeX#s)XZc{I8kzNQwU+4F;aVeY&f$71=gQ$mr!ec$W{<)%V6LQ_ zbF@8dwQ{sGFOPM+TPUk{44OfwE)c$za<_ADHG$RsaI@o?{h4d=_;6*#{seRwbE0<< z2-pRJfOx_Af4_abi2+we*bP)+_o`n!55G;J@P;XGpg)Kry!Vseb$#{$MQGA*t_;Qo z)blBnQrN@q1V+V(AL!)2@4@XQ4Fj1658q{SUz-UzdE>Tx2F5-E0*234eL_&X9Ha`f zH0p;po~dVsajf)O*kj{J9jdPl)H^b&Jt_VSok5Bt3X+2DLl(e!*q!a~{&!>H-cvC4 z?>)F*lI3g{n>;2DZ;6@`X6s!)0z*=Oo|uvH}$|;{0LX@57#2$ zaNG~r>Y376CR_ARC!(TQ0J`|E98-#c42|Dupnr4-{pbh3*nO6x7W3+)7~^m~dhDYI z_V)K2l)(dSQ#0*mL}uN332AfPcKF*v*RGU(*WaA8b1#6B0ISq4%jJzM0AdBIFCO zL}H5;9PA-KiOFXp1Qj>DdJ{WcLzPWkg`E@EUZ0WXp6mRydjf zp9*>nOD-Nliv^qTLQdKpzsU7JJ-+0OXUPAsWO`pjK^}1YHbj5>C`iWU-yb3T^GoLc zy!v2`8$V+FZnI@86Fudt-KfC0bIw+URC7*_3cs7SF1W%}zlgei=Z7Vhrm-yeSFmhKDl4df=svUvw$5 zM!o39B|YkW26h~Yg=&Vrf(>ZJWLXXx5xEo(9c?XcomL;5MP}$hR$9nQHcP+|{qknX zm?IH;>9|$*R`D~#k0TtDe%OVjQ$F{WcfW?vX75c${$72UERUxDyVVDI_tYTz#cDzt z7}R8e0(UqJFC-|!`i}wt4Sz#wfeg~LSFbW4GfwtStP8Fadz`D? zUP_$E71F{ucZxfyUtEZ=YJ;G(gh5pIX?(T1sv&CY_4|kK6|%pfSTj5HL<{2wKM%= zJN^~!@Y`iTtt8$P*@p?%1RtAe*2I+1pYO$bsW88VGJ%7wm3=a^p!H^8BwNSbgLmeF zOFc%LpNyM;%YX#u(q^}`F!ODld;5A@J_<8oTfQng9$S6N526O&A8n!MR_dLoSXLXR zyeb~N8IW4oe|i}hkqpF47%8~)xRYHUBsgQ%{EfuZ~!=qz`T=p`^^vP z{N(SB{J)fj#Yoc%WG_yhrf0lAIv^jv)N>bB1v!BS(Tzbt6W_Pde`xRfCkmmjA&>vl z!T8U&n%7OlU`RM&4?Q$S6Bvx6lyf?yr3Rc)Lr<0Q^;*9bLZ{Twe^aZ;((+Ikxsnm~ zjH*?Mw-dQt8A%_pk?MUn&lf^GkOa72V_zs4D(QEk4lA#xI7Nk@0t(+QN z!sj?eP<=nYpYBUtL_z$z@MizNSAqYh3s3B`8H@}+4H`%&mnIURBbJuzOLH-XQWiLM zQo(`$#Hj<+(olQErJIMYt6!jjWPdz$eq;ljUcZ838y(-XlU>cl*AfhX4<-D5>U{6y zotlcbwPl@kTYi`0uv^vkcz@%M5xrn2{j-<1rycr5l=o>y){kreVovNJ%x^#b4s~Wl z$umE`*F>%itD}(74?rg`nto&gD3#3i1E;%lq7q^X=uGEp>-1k>WW*O~vxNO&(>chsYx;0IL{0XmWoY z4d1ltoK?&;ScP`ZD$Y|CAeDPAfbrmm{o#TjHFLe0sRZcc-DqIiXl3s++GyjN0Xlhn zJ7={tzd=1$v=;jt;g&FVAMv4ni%$Z=%v;?ovXT~`MRcaqPC6Ukzd2c2(eA9$32JyODEhWon*0P+oYlk_d(ZwZt>KSn>R+qemX+=h+j{7gBI|(M9xkGhF@?%WlkpiU z%kfdbjRTPz8*-GmYakF7v$#;BHIUYzbsIaeU`K1lXWMHOzO8&qcW{J97Xw4)<@jn$ijR1VNyww-_YD3q+9^12H32<<@ggRbFLBZ% z12cJM&+6U54wF^&>C3!+h9iNt$FG3K{s8nX3X53gCGU|gu&oANV&u>`=*C_A@6QrE zP1zG3ce~=$E9Fjcrt=ol?qEfV3ZwEuOzWreMkph`_6EL5QO1Ct%w^ICytm`$2f-6#^U|teSt`aHVE}Y|2FX?)GKXk0-s}tLF&ts>0O|BxkN7cP2BX z%YJ7%Z@%PO@;swYzHlW*t5s|b!_V5_Cm*l2@nrzp3hibwS!ZUsL}B{i)vV1fMVkho zCid2|=#f(}-a0j2Z1q02S~6CD@^f3IWNi-`Jw!40;i-?B9A<7-#g1&p?dh0*w0We{E}#PM8K< z5Rjg}v5tdPemF=CMCP*2>SXutb+U$xGAtWm4M35A;dmW#YsusQ3&pYlQ}#Ey{tpM~ zUeR+{G17AtSP6n7FRT>o&+AY&Ym#A7vY`1LvZh!h2CIZ0XN0|nUtL&%o{-|3LgBxN z=g3PC2Hk+7WB24ju(5I0YLR7(V0CB;cBa21j-~@^)BK-Vo5QoKM1P6@`ZIFU1#AcX z5Rggv?GAUbn)(+?X|jc9rwNEL#iWO<005A7M_os;Y~6t(;+{9sTXmqCdXmDP==xAB zDj`}1$fS(WoODTo>ltl}U~wD8UVtO_?Yj05=TZs6BZ1R6^oP)UF;5hQK3;XXZHxi= zUQL~s(g*D#=gsWycl_1ShXA65(I=~_>i>3a{=MHWE#djaX7=2_&d{e9*j7CgH#djK zT@W|_9ITXQG=6~;FvuBZ-W&BY^xIrIyTjQAWPcbuT+C#d5tN&btk--{zu5^IAx_k6|?klzgxc;G297A92X> zpV#0iFs*(|ez;<9wa|d%RRas>iKDc^b!EVUHUDg6b^Dg>GCr&)whL?D`tlPa|Qw3U~!rBHj*PMpe=^z=3$ zeH&j&b~P26E$}QW2oID8%=Krea6AZ7866W6)32u@KCNgyy$vj}p`Aq)oAi@BHEu7U z+;0P-*`5uYyauj~^p-a!RXkN0@I*ZbakKj$C#{_^ba^X$FW+G~Z-JS~ROrlcVPc6^_Ugip<7)yE4q zf|`iC3_xv^@a=pi1UmY|W$06oJnl<6QJ}GaC*Z=NV+NL52Bqsqygp%f=P*x#DkR8hTfu%d@);UkrRvMvw-J4RsfE+ zq)%y+#GzZ-y@Ka69n8SG!TBnIQG5I>$1h+cR6$T`iQ|PNW*4cV{<CTLYkMBS0SURZs z3`>5q+JzaoCxwdI{=PYb%y|Xa2^~0qJ;V|vvOw`ApUJgP0p-D6IG?mvIm&f5o4*%e zk;Omug5Vz*Ykgn!tvssc65sMkGn($===hU?AM^2a;tz77^MB#iK3YlneKW8YQZQ&L z;K;T$KZp^uR(o`76Ub!%VbCK0n;+k#0__j-dX827r=?8z3_RgnZI;hi-n`&)_45pD zZpZ#<24+}quRE=^4&p!OX8{tPa$4^c;%>?965}`g&?PVb@!38jqmki_!ba-Rz`)Vc*|8eH>)nVUknvlYjfd6kt(c)tAow(f73^m`uODRVE?8ml9G3jS~M5E`z(37Pd+*En9+=iTQj z8G_w}_WQh+Xi1Me$i9+bkqM3s60LP}i{8c_a=1%*=w!N1ZFhn#lz5&zZx)1%5v$1K zlNHeYX$>-99>a+}6@6qgCH3v++=ujc0g6kXBv>al7UTDxFbmcsK1PFw;1*`R19&#& zztp`7pA>?wsaV7=6KJ=P;IU6Q_+6epz+J^Q#jkh1R?EvIo;FVR={{h47<_97O#|## z58j;PS?RIDb*Su+xx(I$be;1 z2#}wzUaWO~Nw<2Z^3Mr}M;(*D(p|HPM@#XCsU_2|{jmFq?lpEjaBz%qAk#UVb8p;~ zrEW+rAhEf;**4af_OWAP(eKU2^-e|te4_lX4tC)*DBj?#;*xv>9TQWce}9KwBx_mv z)j@>wAo$At^M2RFPB+rRF_YVQ zPW2s7MvTQRb_Ew=F?g_6=*|7AV-HM|^Ts}!Cfk5D6c(>Paf2CP9#H<38&L;y!V~|A zlu3e{uxFYFR;0amBR4XVGV8*Jx6*&zg7uP1*oyYAEwXbfB{IIS~zy*ja$VR zJnp{Xn-ex~M=%6gbRv>-fIASGML)a(QeBb2l``JT=|(bKY3op1+p$0p7i5;`Lrr+L zRVcBE0w&T@{6ax!meFdGEXCZsn z^OlngoZvMC5U1UG7pw6rP`A46Gf=;IImg<73tT2W;$>{JHO++obalR9X@6(AF4Er= zO0j$`NM0>{fR=w&OQ&Q1? zh_`~xtyq49W5&%m05L!*LhR4qCT_}`#@~=7VMT8)w1g4}qjw!CABcTU9z)Hzw1G#c zS@$&7gYYy}?1Aey^HmibSQhrwZst#v7nr+V%W`j^ktr0zgS^C$i*2?MEkoN!`^-Sc!J0E+gk7t z5j}*czwq@mn_fxM&qYJ8`fcl1Fg=mY(8_CknDk?& z^DFh=ujQ!!dmXL*LL;lLD|JR@+~aVUfZT)?3xC4vb1RSpQQ^jFpYW0Ryi0IdNc2uo zA1CX;*o43QzBwL^s@zN*{#{drct6$?c9S8JEblcD1O-;S0wrDxYJ{QzvT8)FX>V!c zS`5s@1=vqM!iz@309QwHQErb%y+qHg3HMn=od&pf%p@Wq0z;C#{0Jo$6}-? zMiV)dYhlT=p7({oNJJ3ogQqa}jT?hxOUQUEG)%WmRNjmP?ufJjYgt$jrMJNNtfIWAbVOa_d?*k zcXKfzBb6b^6;vn+3?-;jk4&nr-oaRL2_>Ugss0#t{MCSFW&m$^vq5x(T~|R&*!VfX zYuFNNEwoe3*{zIgPtEkU3GlCjxUpq&f&3>$)YclRAU#mj_gO zt0d8@dJ#V#q;AUq?bnEX_F=%FU;+AN73kfgskDuuryIgYOedky=BO)G`sSDi>*7ZN z!5^sqegK}_q!cZYKMqcQ`oALn%Kx=#tlIF+|0S(e@`L|N=kWhhT#bY~!KbLbE6)8< zg38f;#3yj_Ka1^qdcIa?{qDz6V1Vi58|tH7owH#tkx$GV zx&Chjf)TGIP56HPzmj}>5mj|Rx7rcmNbrC_&(E>Ue+*9M%WM6U`w_fW#t zS6k78PUh>ITMVG}^F!QO+e0tHL+Kak-s`X#$@q#V*T0f}eV0{){$UuDf|5m$n=E@t z&bxfx={!3r{Q@17`tHaf9b>QE`XWC0y&l0IH?Jn&B66+!x^FS8r_hnqV`+6{tSc-m>b zJ-OlRF@Ev8k`v0)6AD4eYP~HWox+t$4tsI_981Elmz@5hPX4vlKPb6OLu-PY?4PBk zf2GrZ_5UF?g@}}s$V`9_?JqTK_zCde`^w1ae$s9jN@I1s4>(*r)KXHx0v~nyXz>b2 zZ?=L#mW@dopHKATF4m{#N$jUjl-uopwfzhD-6#5&+rP(g-p3*5UpT7&(N5xbAJs2( z65k%x!PBhzvwzi}Kh5I4?4P{vJ|ZG{XDtp_svhdFJ6a^`g>NpY%0E{*Wr>-xoKmj> zZBIULXPNSa9r&_Rg<(j5Pk;6+RW^A!iJGkiXS()z?q+^dajtB+vuo zCpgj(Ap}kUr1?JIlL5*DH#Gh49W7`pKX&>_Mmi*x!%dF>=Zles7W_ffLijF*^EkbE zoCZ33!5kFm?-$A2jX~S_H=LI_UKOr-L5YY=Y~Aj}96)Py=-ApeJSD163@K zR#_GCCjt8LMDQHA<5KSf0Oao%u*&^+U#ryrniufzS^5j<`lDr+e^#FP3oqayZFO|5 z{!XC}@Fymol6k>T?(1@JdFCPMnid0iDlGqX2Yhga|K$2}o!6hg)rVZ@A(MZYmiqS? z{qSZ@(uk@7<@@If;0KG{m;`MlBG3~h|LzCJ1n%1&e{L+ zUg1ZDHY*bkNbo74f}9(e1CoN^$DPOpsUx9PGcHSL=g56<%KrLYBgBf zkKb+ml%fG{&txRmkl=KLD=p15=kxS#9Y3=EHLtjUt86piz?d645GNx=4ON(cy>3E? z+w3?~02Zk|N2&uXBsrNKD+B<~@MQxiN*E?RqID<@ zvz&scbOt#ke8P~lD!EXk{8GIV^@JhCP{*WHw{x-aEDE%sf~B%k={fz$Ddc&TW%^Aq z&~4N?&Ly9$7x<7qE+M+Kz7Aur0HHUj3{zODr&3Q{+ZE4A!^q^tC6XUhFNXGYc-G?@ z_@vjd?Zf3C<+<1F@TGK+rkYQ_F#xyN3@NX*vTcN2Yb<_EyxNY3h)F?&*sgos%YY_z zxkG~gJZaddGu`2a?71FOkP03?6sUem1`5zlcm{@x?lGYQ_i_RPa@>0i@md|;-P;g- z(n-vaG;Fc9w=r0Yo4zsf>>T5x5j(<&!YttD&8%Y&lj+a?E~NjvIQwt^UH&@Ca5TCS z-3<_b0jGg!_?#wv6w{N&Ic4)^COxF~VzpkHwFYa+SVEJgJS_*t6MStEW+CC_7>d;4 z4(NIbz{iYwW3eVs-6RMz%C>myb3V5uSAVhr?HDhcfl*OR!(`e72QIb>(TI?akWo&! znDK<%-G=R$c!0s{)YA|;Eq>49_}fl?}dqEJa{aw~%5 zJOR3Q(t=YraPDnA;rG>dCv=O}VAgi9FsfdmD4O4DXd;QUo$~Sltqe%DF z+GJf3taW0^X}75%WCK#T04WK@F-{-7keE2c%OkoFcTa0IIv7RNEFc9g5=tVmbZzuw z$kf{O;)u#-vqKVGF6K=mwhRH{BI1OeiLH=xo#QO^$!Y*VfN#-haw(OfA%X@g*lD;1 z?0~dxMY_>!rM^zM)`(&yIbe+K=0aLVzF8+hIS*ZX$^utCO(|mTniqaB7QRjyHlHSW z`Y@J=i6i3M4!0^~no?%R{JyHiY7A`BE4B8>UzvLRwU*^iJI)^s;Q#SR&&t2I`1}$dRDu1^UQvHe+5D&q{^Mbo-+e`W-MIb&4D$~K zSwCL|NnxR=U5yFntode>5}v9%ar&`$$l+&;<DZsP7_(s#;!Dl#IVhGgDyj5RC|h@W848_&m>|Gjg2BN47F-xC)D^(%bVK-J zW{2fx`N=U#>8Jc&4xH5gyqEc}m7n~7)zDuD;o^Ub^99*I;x30zJ8OO4!Tc?G`OlWT z9K#L&(oy}7wiLgcd;Eo#;x`joKN>9m_c7Uero=;vw3KjpE0bZY;$k_`$;Xe~%%<-|yOg&2IniKB|9aIQylG@lW5iAGP^^4`=_J%Kxk3 z?31&U^3P)AaH{R6oTY^RVBh>>w9$U9E?6Iwfn?|)TAw#jo}<&U+SPdAXKgax`2TC3 zvGMO6sgFd4AARZ?*PD(@=H+N4eUTp=nrEmw2S*1Wdeck>e_r@`93G5VF*6xv(W5&R zj+S-<9Kn9RdJ15RGD{WVNU+@==}h?t82Kc1A}I7@rq<#u>V#NpMcTv!Yj|k+r7a}n zk61T8+^DD&LFzBm0*RnhOu7Ar(2@5*W7x;ca+ZbBA9xS=!?5^n+{{z$N=8rECthwE z>Pc5Aa(nhq##}Z3i(SSV{@-c=;&K<$Z^B#T$Vrxg;g+4hjMm}$1f$}M%ZGLsNm@_T z(vPt2J9+*fD*`_%&=ah#1fZ>FoOZbMXBg(#G#~XBPWSfz=!p2cnT%g}N>AK?1m35koR9=Hlb09c^wxucoPPDdxi2LY4g^I^$ksVM_yI`P?B)F50$ ziY)!q!pVUL$+!k%Ntq=1WMKRC?l24tWjXdm%((R6-?5PKR$7H?^LN7JS9yMhm962RMURZErnX_JdkRCF@3 z8-21Fh;Ue+Mn@~~YR1YDNC(O0UbOOv4w3`W#RFfv&5tn2ho`RAD8Krn9IHd0U;!$4 z;Lc$P<%h2WcRuv09(Z^^C=r3@SbYrK`NoDSWzvfac?#*C+;Of36~19!{qyUI@Fy^A zQ~z6Y#akU0;pU2l=%p@4kq$q40=4$6z$u^%AVT1C)%A@H&gy_!~A1d^8b*3 z)Yo#QFEsHdtJWlq=jxbUU;NqL`%`h;vJ1F-6f4Q7*PyA94^GmOx|}u>FMi-x3eYXn zoe~8YWc7rjh6F2wpaCv9aXehrofd*o;7muku(;ty2~vO^BMjNxLO4!7&;!RKn+kyw z5bbHfiHKm@;H2{ph;?ysMcil-RJ~!e`ti9&iuwr!HX-_nC7uKNNdW|1wKD#=GV{PX zbiers6o$EZP#X)}K)Zu2m!7AMi#7>jJrFY!+#{tVkvs0DpITHOlagB89H3;FSv)|? zl)hFgyz~k>*`)t!XY6f8S=s8j%yPuHDR`Lxrt2wbXt}hyDN0dJwA!ai1Q&~z)aDm! ziLJtnYA>3TWY^6(C}-DG`3|Pn^;$v}k_Xctin+T!gP4VHC5~8coW}k9QL&96Pv@j zSOaj)s6f_MRv{4zed}pRg37-CFoH$2Xb7h@0xHeZmYrxlqEBfCF`jK*cD?}_ zEj9?^CRxPMMA7Ac52LKFBy$jxzI zsE!Mv18gfoaS2-xM--LkR4lFB3N8&!#-lhjcNq$@YYh#eV@x7F?ibb#2!*6PajjxR z;%Mlke310ARbiR@^pP?`GU=-U`OR@lVnxDNk~Cd(UQ8%DDA4BM;JMXZpB%Dz(X2^n z9@Ofgg&El(qA4aFQcx)(5Y`T3J2eH^+VguJ?Z;))#s+3RsM=Mx24bEcS#=CW=5d@!}1=?XD^bXU2!uaCbCiI70}M`EK~gGib>rZ09FiK1{h^lPpt} z+@0m{AyrE>MYeleHs9@Gnu(#l@-S^L!{ajynp3&#`WqxM3?&V%xY0G?qg8X+hhEAbx-x3EFW`|Em7jV0s0LPqZd&y{# z@OJRMBBA0FS>ZPN*ugosx+Ep*Gliu}M4WMT^fwHtjSC#Xid@iF!A{1SRCL3OJ_T%H z;g_E*H4U3z4Jh9|4^kd2IAA>pkP2EcvH4h&bnYuIA-}ZDrCkjzi=X$JmiL+R43}MSO zAN%$juxBoWN_0j@X}cq+H8-BMWk&4Dc4rh;ULwEftW@ZBSE5*6vV6;|T*-EKre|KN zw&o+r1T7`I#;+NpIrq^wo>yX9u>-Yq9V2w|nO2CWtQRDeVmO zwdUt@T+c!<-l0CO0wjdL*m($Mf1#D7_}&g#@H;!?9}cZ<|FJ{szpj;?-$NL4txn?| zdqMp(aWpeM9EknoV*qucgFSEOT(~C;8C2XK@c|7u0MUf#zz+FE2q(tOg#Qcn7w{Jw z8dXI3T-kaihyg(`OH)C#cxy6(wSQF{!BVSXDvIBG^%RcXKu0Sujag_qmScwf7CjklV5xP!N>QHr3awIxTBPk-SXWJVRPI(EGn!gxG zqi$^!QVl3dE^Y|Vcr%b<1rvy#%S42HXp3o*+mQ^dGU7VuXFJhp(x`P83P}WMYdE2O z3R3>DK1~VP1bH+KOliB>FOWW1Ci#Xf&Q4R7D(yKK(YbXL@rJ%}Mjj~Ni>WmUrp(jz zV!(stIN_JOzFn?8Bk5uETFsRHDv$O|s43k`T7}hm`fHBN#bhDftIeo2PcJJXWC*Xd zqD0TFB?8t;4H|Bx#AUP#l#>{i2;?;5wSrhV%(|q+@4+|YLRn^ePMW@x?Nx=Fsmed_ z<;btprcz)T(9*8X1>Ps*dDvso`>e0Z?4l#9p!G)DyPV<2Fos7Xj%yr+qfXe@H+bFO zeu`w>nlN2RyE)>jZL>8RN)ycQYdnl{7yeNU;C*^j z-z7nK#0fUO2=k@U6E1k??t4g>s@I-8&w0Dl%7nihibJ)|YL^3Sv*wlZoVL2o*BLE8 z~qa3veY@LOi^ z@F@Af3*p693&V)UF#hu^a<$Xw`m#37cdlxzER2?T83)@u*r|U%m%$miTRBuLc%^~> z_MXp&0WlLn5|@%;LmWY>kIV@{8bc=99zPF35`;=Tp@0y&ToX*^L_^xH2UvCCG21wg zG(b=e09OFYbInyK5H;fatlrsAse1vn2q6!-&8Q~4dB}nzpX^^j>N}4{+0_I@Mb~<- zrgb~0+5@qjMS{Tfv~&2wv3t6dzB&QHT9$hG4U?f7l}Yaap%_sQY%znc0@w>LO}zJE zAjow>sKZ=8g@aa4UBmg%2ely#979NB>mw&L6KAi+rW+q-G^-niOmj0_1rkIk#Rz~YHsWql@(^fMWWyB}g+r!&Fxy_~mZ zX-H9y;m=>O#a8$X#vlc4uf{Qfb}S2+&9T`DO{-$r3`}dzazD+gB@!;psyjbb2U3S= z)T(kdu~8UjN21ZSd(7|pIwE1ThB@L7=&8{aPeJJ!+cr^q$L#WjYN~5%hebzhT@*mR02& z+jz&m1Zy#=L}yCP8?k3SA3u7U4yjOUpN9byjwr$);ZligvpI~WerI#cMf<|!`^YC^ zh3{jeNw!C#yjo3W<5O&`N8_{^X)+(F2$A`(+Ec31!3-`T57Of;k>$d&SPR>GhPD{N&dXIq~LB-q~)4voCCHX8{4gU1UvWn7>* zL3GZSPH=+v5mvC7c}&(W(wOl$@AX#^KuN0r$g5ONn@jd+_M}`Ck8se5s~vXSqfn>{ zL8-g3XY#3?=!`lkc6r~kl;4cvuvzg^scvzU?SIK3BzN_!88S1C#se%#YA{znnD%;D zG>(J*CU5!nT#7vl7n#D@5I3lzNF#BznI0ChF=P+nHi&ff0TTGoLN zX&x5jvBV21v(GU9NI`pOMeD8ka>!?q(TF=*(WXx%2ansLji!VMwz~^3&Qpx zTVpzbQ;jHa-XrYRHTW`M{>0_N;_IW`oRU<)7;B(@Z^p?=`tA?--7p@5* zB-KOuKrU??Dtb?#)K}~|q|dKkur=Jvt>KXF%i+a0G;tVF{m=)+BT5yxQUics;@1Eq zFsa5I4fZtLIgF4-#3@|+xzG_1CAIqPDV%TcBAg+>2e5z09TU3mgJIGH@Wue%e`yNh zMFFICnTIp&4@%+rm_4h%halZG?uC!rx7Nl{0AQAo?3YxKqXAG{0nj0Kueoz739L+V z!u(F#@n~f~)OOn6p0-k!#E60<_O41|ZSbV~kM z=Xw(o7q#Jv@py~5v=%7+)@kL5pc!yhtp!*j(T#@fFss1;Ah)EGFT)NkI zXqk2NJ|?dYgECNF6Rgw9UF!2GpO2Ph2N)`){}x(ip#TCJE`5Hgx5fN0{OWdg>m)qX zP5iDUJZ3Z@<;l}liPR1IVPt36Mdq^Gn`>ileC3VryxRG&^tLLJsr=5)&PvwYaOyKH z7)%BEY=E8mX#pHNM9RBS4kw8d??1<2>>9Sgmph0VmAi2XG@p9~K%}~*M!=h|p)>Zv zW<~~uXFzo2zA0j#Oc(+rRU1!X?wO0aHT$GMq}T2JK5|bsbX^T^fe2O#@EuAbh_5J1 z7rC1Z0tyK?85TaTBg#87(z`Hvnn`aVpDm4G3EUTxA=>#waiMyZ4H{u9zJ}_Du$O}F_{j|c4%X%a6?%^h+AM#5Qi=noehTr(N92v!KTrA zE`0+Ul2W$07`jxx^nxx^I<_pq2y_A!X_~XV51+?F^YRriF0wb7u@zt=T2^C_*$s~&6hz-yQ1+b1y3Pcl^! zJfrmHxh4u>fC-#7_I$vibUjEzHqD|#N&nuBUX>@|H+tli;J}oY`#sBEjmTG)eTFFu z&_Oe4;`Mh|{BKJ%B5=S?sy}2+p3(yW1Vj_-T%VVkj=9tAUl{^#$i#MEk!n$|QstY$ z?hi_7z`J{y65xmrRUX`&@k(edoZT5Xzct6jZsBFgj6k|gVEh{1;UfA)tS_0sa<=+Z zRNh(S^40B#BM35=*Kl60yvMSvBhC40y+_+?587>R`)p&xmZ=On>f5%n^(g$*{WU=W za5X_(EE8<^Bxc0vuI4G&o%QvNB~JcmA-kQRsXK#3^R}oWq}X!;`l}2pLDG9KV2qQ+=ZQ@I5xD@%)h=yuEHAPF%2} ztY;;@;&N-ep2M)9Gxyv%d@fDsc!@!CcJJw50cELDCC37KZhio!WgC-6wG+qc1gL#QayuRuTu2$=m zXMU>YX@zkSO-dXOR+@%4j+)JAA38!tCNLV+(7g2+DLhj}riQJlZtKQ$(y^FQ(!aUY zcDDyF93fi!)v_*3+zh%FvEQYAXXloL4f=ZI4hA*ov|_shNmtmY$Rr&j0!d)M5nlds z9hqsMWXVGx-$*1~YEIflsgU(Rsxve+l8sXS@z-P4s@`*xHhRk$a9QyBa#gA}c6Ju3 z0a8rrtN5}5kf>i@+z$e-VX)ev<<@d@yo;8y5d!0)0P)x)g!tkR|*CO+;By+54aTev8@^yCaz=S+ln1VX<< z;FwZTc!;^#Ri`D8rM1`=@uMPC8%A@&u#ri&px5Y(Ov($wYz z5gwd87o^DOS9IB9{5>qd)jI)?mZ`7 znkT$1os?55?#f6Flj0FIatbJZ+s{`J(%G{3uq5>Dg7Zd+=6Pf5Hl@xFwFP+_ElW1q zS{{ZX<6K>=fF)Wa4VlihJr?4o*p zu~nbY-3eG*O1{CqG#5qe?t5mhqGoMRGXD&ue)ou_Skp3dKKMk!R#23s>v<HT?n)5*kgT*fd$+B)r(n@I^jh_tGImK{oftGbbZ=fqykwxa6`EhN zw_xH`GPopHUyQf9$dU78Xl4HzXTC;=Id(oPeA_n0%&Vmg82PYf`Nlw%4b;AR zkMv28b?jUe+5^%RnJL+-nxd<)I zif-y>4FAh`H;Ko%_*mbCnt2A_gy**C?~n(-D%qHOR_+eFn4xG7q`_Q>rfMsDHlLd} z*c2IQeX9S&20T>SwtuLcV!B^VTxE1cd&J&z&liBB=;s8FQYVJ0AOHr)RUOZ2Z3a4^ zQQ%Y)AmS&Ex>6X)wgChs1TMKE;NBf`XXdJD*|BuIVzfg4Zu zbd;9>C6O=ub+#wB6L(02MHR@-9A?`}-T zKlJICqC^yg^K)qxXjBP_=z7sW0<390LECs3Eu9b90CzHj+jc=>d=8X&JWLV2FD9it zXl5?!_N?_x+~y7U`JCGXN(PD@`_~vU+O^zCb4nH)6Z1#-&Q2A^)!wp;M)1a6EXIzh zAyD#AYg#NFvq#HN3`WPNd$p@o*IBM-XeC~bRB&=hF<6V%_%%i^yF>uy_fhKA_)qCq z>nV;xrN0WUU2C~HmHJ(9?N1QW8i9s?L`WBO+fF_M5237B-2)FJowx%Y*5*1H{o0n}($Gc-~&qfy9XPeE;*)N_?=u9u3 z%VQGRS}d)4II(o{1oq7G17zddE9&P}Zm%MumG7=KTx&~SeZxI``$O-B*jJ7VR{=7B zJizTA%^O&|8_R*!?q{#*4b~s5xgHyQzm@)ckH=9nkll0Zyx5sQNJA`xo;NF)B$pGg zt0|r$?;wV(RwIO?FYj=#!RB75#O$jRQYd{n0{(`wd1g%nxq-mOa*D?b=yIFbf+|YS z@d*8hD^w6jpPdoD@JPF27zq(qCz-upzt8?D9yRlAWDD)r`(Wy`L8^G~I`0$hxcl%_ z0?-8UH_tpGfOfV8=wmCt8z8$s%%_i>&;JC7O9S2K<@DU0$rymtW00z6h^EMyC&_2_ zq79Cu*-Gv92*cV4Lm*HIVFXT9h&2x*06Zo-1RZ}f%2QOU*i z1QW(z3hY(&>)%G9(GX$5ItbgvdNHab$TFkBCxV4@5Ia&7`jyOA!`@j-nSXZUcO7+}@Zv2NFUrU?~c0^UeOp#mTwI>FqI zMuz5ooe6J~t#~BDjXth$jOL30C^@=CEgzF_#A&xMl9=&gi^9$lnf6El;LqVZ*#-lL%09rdj{BLzoxPr$d z?D?M`6(`qu>kM^SdtST&yhLE~VG80rfb@b=$i1eILepnt4SnfkqQRzX2XWrU!w_QM z{hjw8a~zx~J<%T>q_l|}y)-b_QEv>ora#oYrS`7%OO{rh7-M0G>YTlj%C#_(mB@t? z`TFBS;l%~;ls0x7tS@oi%CYkYh{i#L>BIMivp#yZiJw~8j=zYXDNa+>LPj z?hQK8350f`7ul3^k(}k=4jdXy3}!ybR}y}j+_QO7@%V7JG9mV>f=Tm*XTMbg3AmzI5mY9YS>Z zj{>(QCREZNZ;gj~?QcD$Te`5GBFTjFK^eOuCj=1*jH8HhLZTeFzcx&X;uH6QNa7i) zNF+jkK}B4V7x0PH+45y5n=4NPx2$jH(DlAD3~R8V>v$9@=h*@*2NQGh>Jh|Y^$Y^J z_ZPBul;vn|+J&XnKD@C`5^i&%>d9`b%k7Cbb1-M>YJ%EYS12vnX%`)y%aqNzf~4l(D6(`1B2+>baI6*rKPn7Sh)o&r;AJ>MxKJI)agKvu?{@>rMvQ zBngnMHyFo~xH=r!o(eQ^3&%QQEqtMw>dpqywKhi#m#`(>KuJ=mN_+x8$LQOmD5u@H zoEc@JDQ_pDpBNyKkXnx!-iilhQ%HDNTQD7`D3aj8@-u+%9(jZAMpAAU%u{##&U%mV zxSu(Bzbi;`gwN~z$*1^4W{?IS>PyKo_1SSvf6Sa>ZZD}yKIcD0dAZO+RoY(sBu}_r zF0E9GP}bG%SwFh2bW}mi^BE0;VhudHd3U%FTRxOV_j zOlYE#bpJG=+-{($YURsIoMNeRneUr|t`+QB$)p~5+{5T++e}53=1~U8bxu9#=u&cT z^b5^#?qVP{VIl5Y0bVxO7Ba2FP1ZK(5%mO#p>62K7C@j z*je%%R$wFFU_3`?2my9kN5f!=V z^;RAAmp6wJ$1R~@(?RA}UMCKKh|q}wT`&8f#`p*@22c2k@!eA46}^%B0!W9YO5vo= zLyZf{#Kd{v;CSPJIpumBAEGOSrmAY~e+7uZOaoW0A-?p!q;K4Rt3AR+kbqj#k&#lz zKK_!mPK<|9J+3ytDWyLo7o>O(Qjq4NYvw1$rVGiIq)m#8@L@|%jCRP=+=$&ZTCHUUi}|D@Uc7cqn+8 z+VJU^;p~j*klU(A z(JN2qG}I2#=U%NEG!VN)#N$@UAiN^XW9Y{fRn9}mVaK7(8w5n)!1IfHBf-xhQ;9|) znb(AV$q?LwY$^)wMYLxC_wirkf%a=9yvl(o#DgKQy8pE zu^VxM0WClSd;NOA$@A%|V;<)qo8vDDk&4E>+3yvN29k?yO$P0m6(9-18?|XE=E04b z#5OrfxndQ8z95Jr@yV%e^n;mq$w3~ao zE z)e*tui}V-)K3ybqI13s3^N?vq$=HjB>b*m^5U#Wpz!d;B=A|m6^E8) z!`)X^2BQ#tDB6{}heV6*5N&hc8)qN^)J~$GX)ZM7@v$bSg3c9YYdUT03kqaE&gm-; zA3w!RZp~AlLX5)e#YPv;}UD{p3E*mtyLT@vKJRcI8IAxtnPPmqL--xoUY+xyq4-xG>O3;2F&(}Pj*1c+2KXFF5w z=IFg^^iOzmLJ&gC(Vv(4F+zo5b56yfK-w$)(>@rjtrI3)O>Y-9_Ri>exETIHUfLj~ zBpB%6XS-m4S@^Ip8~(g_OA%~7G)5>Z!zgYPDbAhgq_f@Hp?{Du-hhFJv8;`kxA3;m z9I-v6!u+l%n*U()yWBG?{OZGJaA)vyqwcWJll^3oPd=`buW7t2GDc7XNQFO2%9f$le__-+!yl#X`!pK z6%flHINkKE$?Yf9DGceKZ+-&c|@3Pfm$%mS#FCQ5G#BnuRF$a=*X^}M&Cs~rXy2|P#Zp2UtFvzwEQ?#9$?79W0;4# z8+Y`KRn_gi2!$g=g2@%02hzc(%HRj;q*4Nc0A^CNsm???mHfb{d$YZnm*3{_>H&16 z@+`31j&{2NP3a$jb zF!NzzpeaSA4X@b5AN6ETr1-Gu>$RD=x#70ei*~kod6MUBkq87jG$BPSc8^e4rbl@5 zch|((Ukh%IIGt5QvO|jT4j6SIWyFtmEN>tjdvUR&r_rr28eXm)uRiT=sDluQ{m4BL zadTt6IIz}Z!65YO5N}>A6Nrx>$6UMr`Pe3eE1%rKo6J zL49);vF}Pd=LW_ycB)P{x}Q#rvM`jkN%Hx0lOLp2EniJaN%rxe|*U z!}K*StH_lqY^5-h>a*m{;MY^Ql&@p)&-yihqA$2Raz?WR1mg=~;M)O9`LuFkSmi^^ zGubyh*4o$*TXNd(oHSf-=U!(PE~TK55VYPQw_ak?~NS7Vtn7AbG1 z+l|^h?rU@!!W^|^O2X_-+vZ*jKp^{IXFEdZ^*2wKU<<4rc7*324L^r56plDw70p-H zkh~{B1IUz?XvUnWFCkXt^5O_~~fZFPERj%9GlWv&6q`SLB zT9IxfBn9a%MQK#JMJEVIN{1lb9ZHEvmq<5=3Me25^Lq&q*V482-skLd_IF+9uRrF6 z&-*-MjQbwj(=wB|dxmtJW??pbTdC$P@#q!z&c`Np%)FSs2>(^$S>QQ&-^=GGv zm;?(V;vHUQ@s-BOSb3CkPVHw2w#&b{9lw>htduQ0()q@vW-IB_gX~L7@;x4Jx1R34 z&KBM2Wazm+jB0m?nIndx(CbV3IR#aDS;#iKH&B7z9y>fo<_)8o+j&>60uVij2wv(( z3vlSdw29WN47Fm98mI~kC=9Ys#HC;50~o}F7c1KFzS3P}pl zX&mYZ-k8+pd8d3F#<0N%B7z+s!wDZZCnJ^Pod524fiBs_=0+c{ujrIVk+WLYmD1pK zRqPiskx!_A$XUJB;^id%xK8P9>B>M3hW55d%I(F6g-C5zm1`^P3sYbW zoyxaY)~A~M6r}~n3O>zsJgz-3|40Px6_wVa>_z|Nv;dIB?ZMnD>RmLJJ+R5E4R_s_ z1n&64bguIoZGD z`}YO9r&Dk9kw1og&lZgXjQ>eF$LKP9&mv3QJk8xg+`6QiQQW@e>!PR4@XBKBPvso5 zqA0daj?w41C(EE6%%SDfQ*+c@?VuP7fGkcta?(u+WL-US(mgZjUR}*AYGXJvwiNZZ z2Fy`c*9x1E*`7x$a|pgK?qI~w(0;W|dNL+{tlcgEaxM|P!jGGi((D7n{%5q?C~rx* zOD$giU~+Nr84{oyrz6@B*`mP*(93pJy0Sp9R!V4d;o3^2Gw^amuc0r8fY_M9oBjZ0NS)s zG)5m*pNg6H(=TvfJ5N5Xx^65FEETloM%QcQ=jH-Ax2*B)m#wuWcCGiTi*#^R0FxU} zKd6hum_u!Fu)#R(3zq31mpGIMZjLP9C{-Z2OU}UMynx-5Ao>{K=KMp`7e~D!#|vEFj_Z6yF=splb%_`+ug6uO0dWCXH0Z@1t8)rnx?Cg zOEX6%|NW!c5_jH`FiE)5dgO=&uwKtj4-`GhxtydXDI@_QD_Qhdr0-1QZ=c*8*662C z&pephIL~g*k-hu(oAbWtC86!}P-;q`M10MEw9e6nz^2UPeDJ9Qt`G!XGGXL zdEF--M;ih{`G|)ld`pPbv{4D7axRB>5HO|utur&L#iIfs_~cXwpsyV}Ge37@e7Tfg zw>P?$)r|#iEqs|Pe-wPquF$q?dr*lC#$XXTi_v=g86gS}V($SOOK|Y?$9D+{m0S*L z)ad)qjFLcMh%e2SKW3h9ES*AtM9?p~o;DMt&Wy*6rB>^k&*cjZx{tyU$DoVDnS;q( zjC56{k)f|SjPo7YRI04#=lF*Nj($i^HRb4t(Tg&RQYC#b2`KOC+@fs_ zBVITDl{x@#uF?DZGH~FxdV${p!84qFE>-IMzy4h6h}1tLHm*I%UA7;6Kox&=#KC>} zKTg|+k2)M1&e%){-}y;mPvk;yi|g2MMzox%vfy+_tLytle=l5Q&RtjT7fpO#V~TY; zVkYhPjy{+B^xKm@;D4XV$cWbD3lst-XWcsYX}+GkM&;Y}`){YGx@0NN<=Iytb`UcB z9~YWYegjVZMG%ZoJ-uj`|>Ch>LH{&2BfZEhZG zz?lvNpw*j8k>lb3w%z+Yi(E`Jc(q7y$A2^qRzr5hsBU+2IUm5b4fXpcL9(&oV1E~= z(0Uph|Es&W|HhZ#uPe00Gdq@_?dw@m?iioXdC4GZkSU1cH0OP`?3n_29mgr~OtS|J zllB=y(PWDs=04xxXc3K!A1)FlM1GU96D~u}`Yo+>mxA(jBZYp%qq2#g&N_s)HRUpk znn{UMXJl54l7MrI6e~W{)$~XQ8H%CR49&blonlg>u)L81qsCAyG8ZwC2+Q_dhT7pZ zal`HDSK)f9dCig9(vc+s{nHZ>2-1fXN}D&Q^6tY?G3vX4re4BhJbaZflFaxb%1e!K zSH)}zPE5|GLU_;2x=&lhvm!fS1N2zC^3#OUe#R9LljQKE{r)Xe`B(wH?N-knu6J2s zY(4vN&bK0pwuveK%HQ8)BJ z?#uQT3bKI#zT*LX05Y}r$B55knqQQ5-g+ZYH&J`fZ&*zFrKoj0^~|^5?(soj-c9i% zOtVz=uf<}Dv{^$Vp1u7Mm>KdN#6q17?TXMD_s7X~qX=5tV1^QE8@o~ZQgU_}fZ%7C z$iwNzjNvUaUFBs6F=3gf;dUbLl_Cti8CMOTV#rH9P=mC?5(^Ho|Qw(EwYHhG+nM=NR_ z?yoek6$ZO&I;)FpNBVQ!wBCr}x(-7h{8)!b^c!YvSy$-h8H)x2u_ptxz7YrwxSE$h za6o+jG4?dm82E=sGyCEpwa|S;?nt9f=qc%|7|mq(>Jss}(3JwTG`QjIPw)D*D(CLV(qr}drHDMa{{tC;B? z`gdB+;O-XX_ndrTnjcxum~%9A-oiJYSC3Nph(*r1mS+Gg;$9mmGVOW_fXiRxh{_`go75z!+U!L9;NnvgDI~s;4-pLg)!n@ zQIcVl2dbel^r0{Y5^8gAMh*m{7mUDHxAM$CWY`^fRq=5u?SMw>()0(*>5j)E2YLI2 zn@hcOlggMWyP)2_Qd@!j9<4iu<3Lpp6HeN_@jkIV&yXrw$k%IntSfoS$<29hcZm7+L(FmM$<0Shz==+6Z4oF53uqyU26SX?8R)6$3^X&^JLR18+{ zD~pU#lXt=F6*>53$OnD~4>*UH$sVxISj|1;o0J3-T|yR0en{NSJRk82*Bu&(`Zaj| z@fb-p_@Rb`b*4uP%Y6D{ZI_VDCr0q7bipeD$9umzheDBypDiZbYGYxN*4)zsKgQK$amg|(~X2X?6ZGNY4_+8y|8az&vVzytX#68Uha`SD5-@mQAm2@Z}GEH@( z5>Sd^?Qx0YsmtSGrqlvTvG|77p?sv5S~psQ=oAf}nTtVK?j6X7sK=#bb*4zVmJNNN zf_kA!=NZ)Z8BQQtpp^o_W2UfXTWLHWDCouO?rrQ*PL3BijJFK)F0-4OgOx1@UhUdrz=mpcHc0s4Zg52xzM@R@Pbdkz*MsHrPcAd zdU`4^#D@?{iHuP|-t&xLIYk|MnVCitRK^d?z5(D+WzYUQID|OMo$?C?EQG0H>}^)+ zu84iHkHar40?ZV8oE7aOF=Q5cLGX8w(J zf!B|g(@+21U*SzzKVosu&r8)O|6MI+kCWVH!B+D{Y#c0I8Fzv=*M>!dMZS+_{uyrq zV+%(@MhB`Z6@kc`KyEX<>4I{uEVrJRJ1fgmJod1TmeZMN8+~6+w+zLui(u@%jCaCa zbdVXK`nW-Z5hF&y!N> zM{3&J!eqG&OBpmDnFL8ky-y>0=4^npjI3o%!(kOIq*1^*=Vv|eK$Oq1d(E2+I0aOJIAUqKE zcSS)N**{+u{MW)m=`U+R&9#q49RAzeK%;>;J<9hUhJ#Q}X3=Ra7&p`C9|E*!$#*uJ zJrgCv3fA0#_hP7+ZqO}kXViowjvqBqb6g89aUQ6Y19Y+H9w7V`eDgXkoXwDPK&yG? zb-E%-+})E}aAeHpZd?;9Epp8KF=G!`_%4qzY|q{%BAA+iSEsElrdml2)Y3|-J=m}yj|q!}si;alXS zDh{jhd;6{NQ~~o>z86WvH;&3WfoPz2PJ%QXcT?TJg7SeNAm}mkk(TN85k`JC=ZYOE zp~{vq3ZDx7V+V*5#q6vD^n+ip&{F(i_xfu=&!3BQEt{3h*s~50!fP35a7qlRdO{Yk zrZwd&&ETqdAwRZYgxTB}@2F|z!))6#UvpX(}8bJ6!+ynjv6$V17`WMj9za#GbfxhE_(Hu8e+o7q4p{He0qlOZ+ z^hl^1c7}nm*W6F)1cSF8f5yOqA3EFq^6b?9NjGJOLx@uk&?YuQh;Rhe40Z(NptS~6fGxdu5a=z&9!=o`5nHND?JNh z*3xN+Arj8ttFZ$&ob-`=02pGS{&3E20-EVyc&?LgeMFE0G{-;FgZQ;5`@pSty7w7S+xe)&KScE1uQdmx-nPam7LmjGt%r0_JrmD>lQ z{KVOPuYrGR?ob|J)uH^{NBJe{V%?e&Pe+a*)OZD6DTHf$FP(%wMA`Sf2L4_4R{Tw9 zE)9iLxrxoSh5WhgWhzQ3DEu?(`W?mgtI+(_rt{5Z_mkUnd>+Lh1`yc~SSELCy3q^i zr+W9N^EjGdwcemU2?XD(8A!;jAAO~s2tKdxO2CkKz`E&}auhyTQaQy0HpK?2C#gz{ zDKFRjm~yn2E<0`mYO}pNBA+H~w_=(K?;gQ2x4DTHK$XCmIR9}LXamk6u^+XRby-Z0 z^enxZPl0gDagFzvl%v{s*KeL6(s;STDE4>C@ibN4`3J(Sm4Rv&+V`E|YU?pjKO}KE zs6Vz)aIZLVJR+&z?^?<_h@|v$fS$!_E?jUihc1XmcyTW1j1Bk+y!`J%AfS3F1_=XK zf)aQld;dmaBDKQiPLbw!2=r5{@h@2DzeVaxFW^xo_m$#j9`@&4 z6`CWSjudg>;+}02m#0d)a5+=i4}$ogD30CiC|TeB0c%vE#qNKHHIK1(mkP7`Pg)&( z&l*!SkLK}!0jH34@ck2zETU~JeInCm3JpI#BK?usBNoXpp%C%S0YK8uydeKVd!&?| z1p&YskjoVg9LeRj8KguiWJC7uA7$L^u_@a;*E`)C;IDw?MV`sj@l|R%n|5~^?W-|T{XnY46 zr%?Pm?)nN^|F<=SQ!8wpi*EcIa2E_U@KDKv=Ft)EN=gOPKM5c3hTZK|r^Uz1ac3Q@ zL_Rl8HQjrZrF?4aHX>9v{b{l5Sdr_|?wMAq=XJJK@27RFnn z+L|I*1*3k#r{^bo8p(=RK%g5)fX4KgiTBGoD381~-gGo{@tSxR;vAO1aEF#8i?b&AiZ*u|BNo^k8Z%FQNw0W|8uF1 zagWQ`-2VxVg^SzQBc4Gl?9lFJ$uH@tA1ZZxJ|*ZbXs#{bd?zJ|X47{hFAwuOUH%jB z{=fb`paS^M?%$UI6$tTnnjUj^Mun<>j7*8C#%IWhiDqaE6{4n~fSQ4`FwW&AtwW{ys<2=fbDv+*el#fW2yJ>%*q8VMPW45QElrUE}nf(Z7IajG+hnmaTa*%&Rt83}jZ+nD;MyJG5j?5O1 zryw0NX*KRctHqbFqG74btm zMjJpM`6;?U>Fr?G&T8vD+>RmKrGs@^T%HqZwttc`9ajhUU&p5dZvk zDqa(pvFjF}W1Q0%6p7N`)vBH{&c`^W9>fR2fu}nGo0uT#za%k#DlZqeSFg7iR?u{Zly9U<^v-aO++nD zdl8IBLrU(=O(zpZiFH3w5YJQ|O3x4<<<>LO^?I^5U6Tn_ubYUFSlj$xk*tWK~|anLoIcj2H6L-u2%=ol;pB~wil^H zAjXejbw4u3Ii7k3fVeJ$w#%rhQU0qyq%6v!>n65Ag_=zH1Q)ke$E$4DV(f*P^+x3H zAQ0SlD%(hD_hIa*(l^<9`8q;TTlBK+&uH2Aq zV7?5QI+_Ikgs*pfKw1F%kueS+`%G77FyWgvcqBC622uw_o2p(RC76F8buurHrWwv0 zuAZPvfgaTgihEZ;WKp^o z9}N^=NyEE8m;}om5{Lkz8G0y&yb3W@TGZ6`g@X)*rnsG`r9z{h!t?ckvX!J~7j69& z=INarhjJLzE?c~OXx4ZS){b;vPw*vriZh%?yp$fXFi5YU%%saI&tYt}aHaUmu%1(X zO>)+;xhnT{H4SULgDQFb1SuZ1%OP4?BqDf%POEC|*aSpHcwdDFO+kV$vG3@;w2i7I zp&^B&$s>Y4#;jVrd{u`)PmSA*z|7-a-=n^EWQ_A5jscXJT-;#qmf9o!91?P`K(|VxhkL z0&4Y(8=4V|?h{Z|!ASu@XD#UWpq7fsoSD+m_iC?6zSS#{>ceoVFhhNC?RIA-_Q%8h zPXoGh*?0$$JgcH83m)ov{H$sm<~GuYzA+3wa`^;rHg)M`(s{ktZOlo&VxdS4hgOnz z)95iHUC+v9`wYEGE!V44V1(a@7yrqh8@-EVSDj?Ie8#uHO{oTPv#e3N(?!gfLiJsW z|FZq8dmru%Fie55;+lKd4Pp)LuEmO+bfrR3<_Bqz?2foX@&!djcg1b`R_4Ret4@~B zu6{%h1eQQBFspY^eYj9Ub9Z80KOwBE9U065Vhl7UxRex!&CJAl+MV*(8B#ERUkWO1A@4u8DF%P=v-YMp>`8eghf=&!1(fKmEZz#!|Tq%uE ztcaQWcyPlkx^!798oe|iGA$FkKAIbwOq?~V=4-+b_JP4jzGMUlp=9T43t@b-lv33; z%;+-9BmYXLsSEkH+wi-Q&9lBzTsPr+^J1`-o1uoGS9P0Ee+7sC8EtC9YpbjW#4@^T ziP@Li>0v$hR(Y=;Vls=NyjAhtlu1ESUKYoCCFBqIS7MnnCsGUd1zo?G23c5=W((~L zw<$}fUdWNVBHZs~F_=LqZ7nAcY~+X;Ol5OkksZs3x_TWcGT(y{Y&6oUJ;d%N?@wj$qJq1qPc?LVLMjH0M6l!gt>F}7eHpTMM1q7h#diF=P zmMj-}hd(!CQXG4AeY-@ad2J3aY%D{pqEzh$o0Y8M+kUOwT(YmvHPj_XQ*LdS+xI=c z(a#FDgZboDWOQ;kFi7Zmeod#WqySX}=IPB4YFCtf3AIU1gErAiF>8f?(9IqvNyBcd z!D=b6{<25FAtix<(AzSNymR9dHg=ta&`q^EzIM0=0(2h(;+(gd~w~gw&R$~Nr=Ov9l#(jr#f{EF&o;vsk+%_jutggaq=DB9`nt=3%F_1C9O#SX{dXMN@QT*)W1- z++fk0Pod%*tLj0SGzI+VK~$GaQj17lcgXM<`d;R+xM`l??#O>lhIXA~Xty-@!|UuT zY4f#C`^;JgE(PWBPZVkQ-Wl9;mT}-g@6y6IpmqDCTC@cQg77h992AcZwDyGLk*t?Puk60?9{5| zs;P#&Np$Nfk3tZigN%AXB+y0C6Q^Ly*e1FB-;#=_i|viJK2nl zaUZK*ic^rL7oWgQL|KTQsvz?w>2?|+utQ~X4xEPPt|$&C9pMcxu9r`QJ0c6Yt_>M~ zq6shNts$;I$AtSu%#EK8Ty)V)!Ogr-TL1*rDnYs}<#G>p>&io^YqG{%D!h_1sl4Uh zx9(JW3q@Rxo5Q)v@1p{D>tiL!z!nZgv6J|Q)Ds$3u#V}Dx0c>#Py0UecmmvPzx%{6 zLdS(U@Pdh(G7U-P!o7Zc2pJes*lwne#AzF?wUF(!1HFqcg<-#~TKNgOzh^&KSOLW z5sbUti|pND<2T?b)egQNOcXy9A>{+g_VrYWQ-P=Pmvm$uUjla$;kvbQU(~YDvewLY zaTHS{4UV)ykA0l$;-zOIE zbC)M@)Sh8#7Y=*T-wFvQFuC7$*9+XZpy+6h8UryA1g+n>tJa4cpBb3$AB<2WkjR85 zQH))5$0%s~iB9`At~W7ZnNUQKj0Ap-Q4s{!Rv;`tAb=Z1S64b+3@+Tu z=c#D6jykDdrppEOJ1OuqX%aK&X@GO{l4~6agp(NJG^Y7L4TA)QAkWd?f(0@Zb$3n| zBCsRnN|Hgi`czhp^KC4y{o@ohTowVQ`cVJ+VAXXD6LE=WS zJ0v`Co}t;BiS9ky&B=!(t#!tE!%?=H6 zT{u>z7*`KuU>KqAG5B;d4nj=pd@qAQRXDD|M!(AgqS{eFY;3#T6r?i4$GKF{SnXMW zX6Nl_o+%Fgs*tJLT(~C;`G#)hW^Vh+#Y8KrKttP({FR9kVXSgQmMgAfJ7H*Rv?fR_ z&bR&MYilA_nVdoeZxYK`F6}smiW}O+x$GEzu%?)Mu~wu^mg%sp>zQA1&0@3+XS~PU zV#iVMh`RV9L|hk)zkYQI@6oWSP!~Rr8QD^KejRobaG_)Vbz?A1X9jmG zK?wZWb@QDVNH2@sAX=HC zcriw8-TN9R_}zq8imvMW_q=CHTUYK}@gcA;@);k`c(-3a2_tJD>8r;afdn?A&!N+p zHlfqa;82jx(;;O>5i;f<@j$ZK@H)w_00VBU)q0AXd*??cTL%nzq$NOQcB= zzaDN)Cu-5{b0u8S7yf3kkw=u9U3P7aB!4=i&$00dQlK;}HPybkQKq;JexnhO2jL(A z?tO3#FEzM|70k+w65E9klh}qp-N_XT*@gG1r1lCx0*QUPh)Gwek{Z}>0hv}yCoRQN ztnY-=zX^vYleB1+w4YX~eqO{oqJh5^an2}A>NvMS-OC?GI=d!1Sf zFD_mqmfxohr<>`Rq8kkwcE_c{?Wc*WHDSj+0O{`ZK5giz4AFaqY^wQuh``#}PGq9v z9=jHuF|j`*;WiX(8%}VMrpKVK;uhurk-N{Z9I_{J-7T_K$zp^IGN{P(fVdhjUrOHN zOAz&~5$IiGxZ(I%VTh?BQkC6}bO=k{ZA(eVt`5a4Y+M#I$BV@+H4s7VJKeTCNf4{; zx@&v`SB;6Unpnes<<%@66%$9Xz57f8u7>wk4SX|-!-NqooJ=MYb7fNpo)043Cb1)- zd736ElzUjhm|5Eby(;*YXKYBrb%N*jda@@fNMN|mug4);7um+^hZdA?8`_l9*5}`i zw)cv-=bl3pM+R5N0S?TsPT6nF7HI)~lN#R$aa%p!V1!q(anY#vEEwOpA*BP`=-q8P2G)daZ*&cuuOcI&JTv-uYe zi`44M3R96jklmydxcS_rtc2nEEskE}=qqCMY5IIzk;$7o#H-A=|>hkdOxWr_ZOc#a|`lheSj^O3byb0LhpZ zJq?h`7vn(!(eX=cM@002(No6W-JJ?3$9>(QiHxum-GcrVNmmEUBT;Pr%BsK$-%#OW zzxUmvu5kEk#6%abk-dj%);*@ogOe!`o3m?ezBhwj7z7ee5&rB}=i)e}((L#}bFiU1 zRJItK*oQEI7cXGz&J%Kd8PY6lpY`hJA4aN?Xso%iP2B>05M4`=eBmeL;qg(f3vSUO zAxl2Lm{isLj?Rq%ssHVVa^`W4_JYF;py}BJ1N?Tc4@6|`BaXWF5SpBc)O@H?37>t% zJt)%5OyUzwUlHej>0LZ^_u*`8SliQtK04Ulnsi$t2CrCC(GK;#uKpInO?NpZ-z5fH zFgmnBTMja^gOPUUi9~7=Xqvsg7R0o2d*CYsoa0pSw0Za4MCWkbz5)Lbm6KJ)OPHGs_G|pf1LQZl>&efkOhNuwR zxz|2-S&?uQFDu7Y#wsFO#*z4dvytB)>6JrDgZmjw*t?7_AzNra!)quA-!djVbkFguSG;OVcCV1rC*>pE(mJY3*-vD}B?% zeu-9rn}*NT0NOwpaEka`dYb8A=R#3jg7_4gC5&&3+*%7NvbNH^mA0tEM znFDzt;n+kGtIx|tGAQGHYc;2q@kQ~ItE&v4R`dZOPHs70OQZKMpjRjF{Ycdvup@KT zI#_C{|1qNo-sc@#YIqO$=shKqk0}W;jTc2JKqV>4Y0BMCr4zK)uSX$dC=j3ur0G;p zu9ZxvaThk#W9@HJbeI}VHTrxki1yUkFsTS3xe~~}xl#ppfl5!N1D!^@$azd!gT&o< zi4$Rz1W9<>U^yUtn3RA*Z`*Fn3C4i)o?NT4>0O<`({HSfvNPqphzJf=6@kIWjKFG7f>fv-0p7$)H?;)j&(uGAe_zG`cz2wPiZliLUsGgJN z!NrpN!42>Qf}v|&rB^kzbpyDxg02TRYw0FkD}T@m3Ahz<-`2 zcrtXh)phdjgnbU-ec0tr18<`AHL7)k0~A_6FNBh7zVy^`SG;aZ5EjUy+4P83#$3>0 z^a@(q<_M^Sce-P{vl?>NjpTJm(Be`49-zLXp!>amiY{nYT?n28g0^&G9E=N+1L(QjF;C|-BBx@4&s zHixbxAABx1q&nPQ@JinQx?WlDaj>)0=mmqJ7=e&d{s@&^)sHmYYHcMQ6_W_Ir9pjCY@M6rmloV&9>R>P_{L?ZgY}w1Vr;$EJR%>_m z1`1%t54>^ai@1ftIQz9@kTFP-mas3_#=2+xy%}CUL|PROH_-&!ijac8H9+>I31N9v zYnhbeP1==fZh;-r7h?LnBx&SJXz@zl1|SJLTI=a8Zoe#I##A9;(Y$KXA=H=HYk{{i z-SgTi5*@oAI+Qn?h!;m2kLYM-__CwfcQmo|>odA1m=iR(kpjvt7uk_*|53V)2im1-7FEy3r|x7G3grp4#JU&1SOrF|-{*e<8^F zb-#OmTs3e1-K%Nd9J_2{2r%%d30_ksocA*tGb8BDek5*Bs5q@MDG2Nqh^u@_O%6Uz zg`;g($z%BOEfjZhA(Lw8cFHwst56bj3f`AqbqwzGCZ^`pNId~MkDX>CyDoLBUqr>C zPlXrv7QY06^K=w%|W~3q~J7qIaUICxaEvaCETD-0O$*ib8c76_pnIf2vKqvBzcV6^Ods2NOQtg^ILj||%^0wzgwHsE;3+~y^DLxU_X|3mV z59Bkxp3$3)DQ!iKVTB4q$>P77k1kb$S{YDtZGuvno7JP|(jOlN!w>uPK6FWB?hLGBj7Kwy zVIxj`50VQ>hF2K0!dj8KKXC_dJ8Pr~Wl{UiJyWfy3>1_6NDcFy?dcwa!OUWR47*+( zyu1SX#CB;@e5x1YaJS&##-!x5Wao60(EQoNhBEYUFPYx2m!MTtAibUieF}OGPxEo3 zor6;(5$ta-`>08nUknVn_rQ^#{2wnc>q0%?(F&u=nBRV>obPsz4HMnL*-muVj0_fjvIjDzoj%fN5hPFh153=n{&lAYB9E z?QY*(yOB2m={C00QsPazE~qn}O$?!TQ`d2NWuGi?|Khv8z{-U;T~+Q&LX$g`cOduF z205>_aRG0MMaqm z#l3^<;^t_um5uAgR2)-D>()=Io}>eBEhL?7B1YaV3NV?}J2q_L=SMGHLGkDf5Oqr9 zdb6Y|V!ZunBxj4EK0NWZ$3erAXzoDa>Td1cV19%1^E)@zZlLUsw0=<7tgc(Ol=XZ& zgx#Djo3;L=i$UBd8+v2thWoQx&$Uel*Seh>AMY>iPa#pcwS1iTAO&&ZG%UYBT#nndH|A!D4X>gE)v&nn)az+ zx`@VmAJT)r6w7?k)mLu+@Wjj2s)Ax5c$T2u+dnAT6zzt@05i0VZ=CdXFeTq>kG7Xd zS)+{AVZ4_)TST`+xLHcm9y13x8DA7_iF+s*j7mqgnM02{7(QiMWkgE0g$hCVEY|w0 z&_|UC)cXJvfxx^vR!i>URk9GG{Tk(FG~c2U2nHHMQ4zj8W~qX&Fj+7Oq|Q|swOX~f zd^ZS96`mlEceJZ?Rj)-*q@IafjM=PZKV5>wsfGDl6Ui3%(6l6ym?aVn3P>s9WC<49 zZ*gu$Ewu^I>P3WkRiUJS!Ro{>pn&5HiNtDfFqUJkk19)TXUmmu@yQa6Js!*fu`JJ6 z(Wq9r1E5?wK22og-XPWNX}{87ZjN_k-fg78_o3)=^r!=*w3H7}k*=X4#rpe*p{pmR z+<3+;mdK;25zLv0=Oq@(;+XQSC7)BHoR1BaZY3NZB7Pd`3*TD- z=9j?!%t+RuCBD<3Zq^V`5uVnHp!R&*o$Acb+-w=aB#h|~SXxl&iqW2R6a-R34c;cq zZK9Ow(kZFKdx2n?SMgC;niA>LGVM^E zHpR*xhWPN;ni!Q9IcV;pdsXqv=({Bp?6!O9>L{H8;qAq|S zqpKS+R*zcl(YFL4kplWpj3^jrNRf!`MVLC|!O{-Qdiclk zcgcMR*=N;rkVrsO`%=`UidWcB<5*G45*zsC;Cab9M{jk*HHGrtm3gqo?!+3vEv0zq z_ave24P1R86ej348rw)8&wXUs7LIO3c0JW6}becFkxbQx*1&ZG4OB-QAXwg_DwN%A)(Oz=Q z7yX2F_SwqN)TyI|8M}p4m#K=t?3TM-6$ zIf5@l*TT4^2l(s<>h26&G`}Wv?^qDQ( zK|Achus#3Lup1l+IVe>|DBX91D7uz0ECu zo7ejGZr9uVg|`KKMOK-^$pm^u<-^4{P$64y%K#aS`FMr%c;&iiNvm!tmR|K2-P#4+ zy3FyCq49=t-NqY?RRr&v8Q!(2 zVzPSzHq|;Yy>Mfi!eHjhgc8NX{DB5k)8MlC@U?(Rb4@Kv`(e}k$)#umGyBPIGu@bp z$&b>Kar>7s-^)Ekn%XLV3Rf2=c7fpP4URHt!|^*Q5#dvN6tTTUXi>BZ{#GoYkSIrZ zkXYDDug}aM%MG7~jRh73xO`#+8I?Rlh0kUUWA0$hxIA6TYeZi1V6vBmLM^Qbiovs7 zhru}G9DyFifl8#`nWn_`h{L#C@xeMdXv9jS+ZWaH?hN@u{A_g)IawsZBw_T>42{+U zEhy2~S2@)5=<`Sv*Go&e{S0Xdg5H^kqVush7lXPLR8^}Vm3Tq&Pi&NR3>X{NMo_I}+=m2p9he?djmTuo*{ zQwuoBOohM&otOpPtcB|p3wmt}`fc)yLkkAm3x>#xMufuhA54w!o9-OM@$xS&^65ncQQ z#BWiYd@Ggrto>8qeTgqLqlq43(@Pk$NXnhDeF9COX(; z_FF8gDdv2NiR*i`N}Wjt*B;!vl;<$66$Ov@JTwBDB`6ilg&B^0aqXpaWA-Qk-56m} ztdx_4ScFZsU(reg?P7Job|++;y*SaLiC|&>>NZ z4+2DR+6RM?ImHi~Hiz0D2b90y!JToNopaB0R9%_U zox?7VSC^V}T^zC7>K0sjzV+tP&ik#RigF%R2r=BJJ38z1PCXn5qnk;R1*0uj2P#nK zUtL)*Q-9>7IU?E1Wk5Bd@d}A!V&XEQa7MiSHusGrF?O8KWuuxA6ao`b2fUTy{oSMw zcBbkz?Nx_zhltdMf|;UrXO(g21*gA{0v)St(EtJcOZb-GK9|JPP3RI2GK$lGsB9nT zT|M>P!_OR57m~&}w?F6al%z*H>&{yR{MV*l&#P>YN4bJHLw;qBO`A8{@z^UXv#$Ei z>+PqC$#1Htelk^4gdJ!{)=6yP^o1Grh|U(~u8srCPZ}HU<$avODSDFJC%3Q%j+3x*B;yIGK(839#K#18}gx$zoKKOtZm4<#$xs=(9SW+-E&i zlK$Uw0im#eYWl4aJhA2TjW%-E_Zw#`7B@SYv!8FiVy}F^*~Q(?zV-V2bHTI^7JY&2 z)VnP$8*v3Af@tEhROL3#05S;$-k|alBcB|cM*f#!eb@CbBSt|S+oNXVA)m!`^)6l; z%S{c2Uam;7>KViSf9#!wUzF?i_JwD!kdcDgdEYA_c{{$QMmxRy4YX>ao=|^n&vGk5_{9dj!@Bc*gDdOfEe7oE4 zg(U2@qH_a{4W{&C@in{q!+9xJug;#>=I`!*Qev`+vrIm+A9>H|#pdQXml6X1V`#%& z@=e!17;)WbpDS%H35C`}3HTQqr1qFCzLVub9Sb5P?W=B#&b=-#k$3v-RVfiBH3}Ho6fnS6 zGKoJbaq_+JGHlfSa=5ecr24H+%j{FR)n72kK;1o1AJNxwn>C{r(-<(K(>9XM0Lt?&8Ki81@)n(xuI;TTZe-FUh*D$s? z4ReZnN21oNlnk3CXb*Hd|E~C>Th&Z2CT_Us;A^YO12 z8+BxC;H2WeZH%)Iwb-a2JiXYYbe4aqS#9A_8HnmqtnT|r2L6V+3hBjq@hMup{q-yP zDoFk-x6VCsA0?ahb0H2U$f?I~`2>q-w9zWHkGZArZv&;u?vox!~X zxL61&xrqrSYTKyNDgpAk%umB>-#74`Dxzxp%1H z6|UGy#O>0ELk$HGORk%5gkHG|zz)$Y%GZj72WLVVR!$@8p%j)2Z>gs@ZqP!rmA&3qkWgf$%8YU)2wbX zo!fRJWg5K6OcsZ40wq(iiv&zVfKnP@Gp}GSv)7K(pJib zpu+u2H|POVDS`kKWD%~gPX=svJ(3QR2PhYb-#td+#e{9cI)VnTPmS%5d5XIkcz?(U z4S;3!3E^m!~6??3Nx9yFk zK7h*Fbp!mB6!=%%J^yRJ%C$Zxf=s67D@ak;4CDm~hE^O=w1oA>`riy$@2??SV4zG- zC*319Jig{H{_+NGON%g($L&@bR13^8Isa z8PGj~xQAiOTB*j+U5C!;K!2_Lll~e9^Y^9{^!K(9zZJ^%xKsdZ?~Emm0sXbvaV$u= zJ52Fkc()CnJji>=SLr0+;uRw=$TIiT`hF`)qrUF$`f}kixd%pAq(tYA%P2wop8R{z zb#zbWo63l62>I#I`5SxZ|43I+`}KW(Z}0qPrn%3=@%s51#0J_O_T1V!5d!^Y zJXJd&xWVg82|RTngdj0qpQZY=hyn8EaQA|@7zSzTR|3hGn1`|)Tk6&U>k87bpK<3o z)~bK4ZNAkXgtKgnH7Defa?*FiLKwK;UWIHh{Cg<}+w<3%9`7H`Uw>)fv}PGgiaB0x z{{L$xznf|XA`PRSV!QypG zek$@CG;5}HF^+s6@`pl9(riHy4xxOgphh`S;>?>!{t5K(G_-VRv0e}|tR{GMYoqXD zK6sB0OYtJTn~((2(NF$n+wEo<=qRWJr);}+#gOggw)~gSqkX?+;`nRr<^^4t+ttD^ zzOGMl5|AjsnsFE9`cKxb`1@LP%v`SA;wlnD2+y>aT}7*ioYu8+dqcq~obRZ!fK%`K z&BSpBdi1~k5@o)5iQeEBe6q_MG^t|dWaVD4*DbD{>2!3WNb%CH>&TofA^Cvp77sOk zsZza3vvb`x;Yfb+2kT}MyPL-%z%J<}PT!}tD2L;Bvxk0!Z2m21q%TkF=Pr^pTO!3a*1Z*-{m@hPaf@6rB5l0?bzrHq&!y)J=(kU?PwSL|Qw!EI_^-&ygrPaf)2+Q4^>_TIZCshd7dx+Aemf&~Og^X4|&?{3pN9H{X2v zik2rP)64MrrZURuP5w+1Qb5Qu0qpbP}v zt0ym+X6Qo$BVT`oe1+#*OL?C&W=N<8ul?2q*s-Hil(mQJV{g_g%mHnY-}BRD7lii& zih(IIF9%?0YS()3LnDL0=ORs4kFL^GPSewg+t*MXU4h20Qa5l{WP~%2gJdS_P zs(hbC&78t(KrhhqUcJx>x!@Uoe901oE(Ne(Xa-Gd~ zeQAZM6!4;Fl)5UhpeuY8u(`b7Ck7GPtF4K(xwPISx){m_y|hH)3W=2o7Nqguz6Pgb z9NMGfLR8)lxRT3iijgcG*AO)T3@?2}SXz3`r!U^9xzYImuT1A8y^)^OFv@NyK%wNq zp366LTZe+wZql(_9=HIg)0Da;Lql&`ed3osHjGai2{Xm=O95B%(H(G`-AK~t6UXK8 z(Wl$4rIwJ3~nVin+^Vq4LKRh3cPx(+V zh5lyk^W(rxoqb6vJoRnh{w}%A)WWxVfp4~?+u$~XZ{;?jX3On{38>``)4b{BPRlp^ zD_yr+%~rbYMo}w0jw`pPS9%cy0;_#)d(2n+?{lTCZiCwfk!J<4avSrH!;cKoK8{4# ze)u>V78~00JRm+HZEYeo@59<;#v6h4sT>MgkTlLQZ3iXmaq@mp8Yz36S0UuM zjs)x08Gql`!sokZ>(0(xGiKpbD_-Q>?e_2#1Ol;uKM@qa$V3n1a45;Suu})LtqCKe zU;a=giq*XhORGS(;Bbi>fkEfcC*I$#`id|I0+ASA)iqzQPR&EBig`Pz8mcY)YyzCO+F?LO|BPcv*dBgp~U zm@VI9u`yT4m0r{Z8hec72W7Y*pVjb5y;Hl1e(5ESzHdh&;YEE+YYE~8fA;~m>i!uY zrhd7tby?+l(T&Ah*6q+08r&Yxy2B{OHjZSM!utsjy4t@8UCs@T*Y%YssRFlLsZh`zr;44?|XP{ZptUIeXKGr^?4L_~qm2G@Z@BesP~em-Az`ppuIjhM!-y;t8rfT+kN2bGb@$KX@BGM z6L$ftXnbx~i*A1XX5~n-ZTEqTp}H!vFWw1;ua5R%-3Oj2%HPe~b{{wZU-iW*yzeDy z{w)e`y_MVL$OwJ1K6wX7?YL5;ecfY&Ck~9Sm89;1wYZ<@^B;H>J!0BHD!P+7O3m zL3$e!e%R#0awKe~f>sblWfq$HeD#ze#q)SJKFTa+|3>o?T;VYiK1j^+d1)dZ?b%oJ z)1CgMM9QXfvP1@sN-uGpI}dB`lRPxWDXA;>f+f$#mr08Tsksc4J`* zx9U#4XIf}AT$jn!qj&B^%U(|4x3$0!ifIK6w)!LS9<;Xi>%=>rluka<`lT* zT?pZOj0M`+s)yl>3q$iDs;t7u-iNjy+B(3&2O4k*@m}n8a&<^Mb-A=ntgLo6{>=N- zXzz6;sZ@pd@`=bn$1J(hjk=)5)57Hcx|9(uvldLU-EG$OKtvS2 zXfDjgl;aYy&ofnHYpU$F3^9?SXXLjkUoo#`ctSUxQDSa!zd9hpp-avrOZ|E&h=aWB z!SGQ4ek%KVFP!&4U15(TzQkdl)EaNzgFW<*xhhtim94I)L^HNl$}m38^tJREM7X_S zKNT=?w>b0qCS#L_>!R{Q1ZgZQ0lZRzaUOYJA@;zYs!Ewt^ZrPmSavRWm7Lamz@yq& zPT{I5MJ)W3G>-c$KoAX^4@y*sX;A7uZ z8ZYDtuf4{&@TgKD{zxbme!B3u!6*J$0{pEp7JgbAeAm`gsa~@v|o&2B}n`}ITx&tcQkvZk{4`)9Jsm-oszV^(_L6ZqwlN2XvFkJKs$i@+Hy8`<3Yo-q6a6Yh}rlCFB!x6fP0m% z)b=Q#Rn+_}I6`i_n&V)|x77=;JSl%`tEf7d9`-|x2lJgHkZ2EOxfT$F(f} zS{J>R#|_rgiFwaQ1o8_FQrt@oezl1EOU87ceQ17Wvx~)G|HF?L!vESah~ILHlICnn zI9u_j<=M`dF2fMIcc>ahL>dtyR@w&fe+9{j%h1j}9@ij7wqMVWANS+Yxi`yIB=ePH znzfmd`<^PyEACd?JO!}=O-IwGu^sK038EASkKlK{SE2n})Z(bpj+t z@&2ls;i{h=hM48&E(7uRZ~dmRokanW)2{dWWMext`5(JYL;f}IHT6qxxSXX_)vq6@g8AooiEOKEzABTk_AYrdy?{*+MK>>YRZPOk zg8~O^N3!3CfM0zA72~!P&Gf~bSo+ouS&08aG9Ofv-7LwA%Pd{y*zJP400_BufYG!bK3jQTh2c z{f{1f{82UISKF5Vubqkf$@HIFZDpU{d1=2h9b?f>n-b%3k9H3olU4o5Xm;oNgK439#1MB)jFU0?u8My#bN&3;$-Z!I9tE3 z#VJ|j`0DJH01Uf!a0bdj$NYY5(!^Kiv@Ov7TrzgfvV0wO71}LK{7I3^lXHd3FOHzM zhg~c386~bHwuFwq)CU%PbDzCyPEF8dtn1)DLs20tQmV7LwED%_>;LqZEAX2y*KgkR z_UP41_VNzV%a}jEa4AnHveUm{YB0+}xUmrr}tBMl5Fhu&`y^}@yLi)!B z9-dwv8}x(X^ZbK^+VB3@JN=6mn^Pae_O~AeRnVsgt8Q}y(ir_Ng^F|Ta0F5V9two( z*MK;lokjvD|Ix@g$or!RKJeVW1yv3TrA2tuaka$;;QaG;-2OesvL#i;&wbV=Y$xzE z5D0kX-)#+v9A^A@3!w6 z(7@N)*fW{8yWN(5Q{wSicXO11WU-yqu-IJcYrKF|+{@T3wyeIp zwZn#_(l0`Ci%Ey14BQoD@2z2frBAF5g4MWY6Ea=W`eOw0$q=ZAmo9BliNdG4K&S?W+k)jSRFe9 z&T95D#B4~&N$WYbk-IZs#}%9b5^^%=T!Vey+}IiLs`6?*rx~qOg~Y@=Y~oqI!DI$r z5-H=f^xq38YEJMxLX@_tHyEI0$A^HBJgFXx-k=$g?YS~;cWKN^iayD=dxL;aKkUhR5chSwFT*@XW?S!&$-2#b#_swi%>v zE_d0^Y_9Zq3T~|qg<5QV97{;wTARwlS|Pp>#B40KT3|L;N7FG|8!Iz_ri(NRL?BxR zW}HP3DnxhNnsui1iNfWQeL+l|ra@oJnkAI@g4}-Al{KO>UBZsR2|4S=t?-PP zYZOVCF~|xNxi5)-%^O5o=Ei3#r%0Mb>ANrX0OQ9CdHeg|+ww6|Gg8pj|D?pr zQ`RSs`dF_n5n;LASj}{1p*r6BeiV#8S7f)zdj;zx9&sY`3CH`1UU~<#ELF~W{&p(o zquZNLm*fOz-^*fnEN8Mci(kuu41&$Mpicslrh?#UiW{@5(E`Jx_<`FEzTn z^Xx_7(ys>Iz{nyyT;5!+Xup7uP34CoIbT~5cg)v&(6n3Ay0ZdGyt5cte_RHLEX<2P z9GO`K3R^lc;B)MuVL!cf+zBYtVHOS@UnsuOewVHGY-wusT$f-+i4)_o_6gFl?I7xl z$5ge>-$>HGJ*Ro`N`STp&xnPb;z_8ejoHfJBU3a{ha(x?$VkNPdm%TZtp8Re-rppl zwPIczd`T?q^AA$u75)9+4Zi-WjfISENU_?UbJ*_&0ngoK(F^t4-;I(a6lLy4R9#T3`|4A0K zU7M$Za6weyneRGKPSd!b>xRcO=p?@-s%U0JR^dz=e(gY|D>H)m17#>W7(dtMct(w! zuOd{lcl@Fs%f7m|QwZpx&{>aZ_&%KjWsNBZp2ZW0tI136Exng=AlHj#+X`NutY&ot z5$J`j%{5~?YJ|Jhw@-y#ZTx$VPpoDGiasimE5-Ci6F@-6nANUkP64&K`0Lsew{*LK zfOcY7v+BWd@Z`H%7crsL>6dZ>*jubgz0392?yb8ks_QJwW{Z^tt%(D=DI&G2CB+Wi zrTFFNOImx@*H=|L*Yc$AZDBx)6+QNF*{E(11Rto)9j8M8TG<&+ZRZjmUC3<>ES}vpA*DI5hCnJ(vf~Mf_;v}f%_>hGp2y@E)-lhdmQ&YKAin4)sG^>HTHj)P z64qx~r)Uuwm0GsR63b+=rdiw4T11i|KWxI+3zYlwy~Pu6!=goX&K~GW3-*$dzIrGT zve`LgF@s3KYQMLFL!ku`GmXley?90FJ>mjzZ#gj zGfpiOnl9x(Q`orEEy$P+2kV>{k}tcDrNi1qcjFMv7MOPCW4ndkHTy7)sGyh2=1H~N z+Cd4p|9mJb)TJ^~xds@gqR)ojp@AySYi3Miv;O|o`rc9pYNV8G0PBMx>>?=7XMNAY zBy|LZk|=h$X@N1rY=(+eBc|H(5CHE&?7|!m=JI}IdC2Pe2Vk6;uAWhWflQOIz3Eru4SX}`iAUQWG9GJK1@ zkC|@qki~plSeqO}TwOsP*>~|h3OiscG<{!9e<9fs4=c;JdgJlI^zEj7D^`4Pl;qgQ zbULl_Fo5?_jP5U1zpC0>&>4!Y%5R}r`Yg(Hosya=fJN=fTPKX^W}wcDx^cm>>H3wr zqLXi045>^{ZrnjHOtxiH80uRRU+pIfpv0{3Qck6JbTp;ZD|)b9U?rk%ORLr|-drzv zZh`-ly(nl1!X^Y_TBS3Lx*>;imJZbKp7;97JTp+0Kb~vVp{8kDh!PxA9_#ni=eVfk zL?p|41>EEh29kJ5@FOUi)biN_@{U0g1pi3lpwa>2+x5@^Jk3yZQF^1;^AzM6?zTeY ztT0+Vp946+H{ggfbZN|bDCE+7P`N9bo$WQ~uniEO0>@)}udI}>?zh$EesS3c9t~j8 z_AVXo^aBGFNnMnzGS?F~dV6I*2mf{exSDgcjFXyFC*oOkXb9i8`#J!rzvo7a&R8hn?%UsH3U2z}yhd}SYaKYUL zK}-X&13h^C_tAbyq^}p`1i@@x`x&E4>=gTOgKqUV+4y#waap>^q>A6N>zS$jMR>pyGpk%L6f20F-d4V=(^FM-> zWyH|1Q{7t^*yC*C43z9e12^1)yg478fxhS)Y0EaDkOxH56`g>R-*dVlx0#&^NZALR z#b)LJCBM`2EBS7zn0b<^Q&?sw9S7TMPCa&5H3)@l^x_Ad0Q7L^jf2jH5TGRo1u5e< zyY92udqoU0Ytu)sk^`pFW{FRXzG=F8U0xJb#{HUJKqe2khO5B8CQ5oFUz+wLK2NNX z7`Ym|t0ZUAkUpyUr5wM!3=hZUH3mHj*Nt_M z5P~?xhPg(jcE_{3MFwdg79bAa{~``A&a(V0>;6LW7x8CwDZ%FO8uY)?QTuHqe7>mp zJVXCV**bSBuDJ1+lE3`JqP3spQTr8(euv25D+P|CfSiAAwLecZzgGw2f}x`AgF;5O zXXxLowP?3z=-9Q^f3c1__Kz)Z?QJ@Y3awL`1P4M)K0If5;$g15mAZ44Ix2<|qQ#X= z!(~l}uWa1Z67!*pO@l2R8S&#EBG)-zw!E4pc(xzSWGO{MLJLqHNjGLIta5AS-l%b0 zLh?f%C{R{$Qb-+v4Mm?u)bO|}DD5s6GeD;SU0>e!5BKz{$xqA0zxLt&VT!Kf;(qKo zwWOIfG6&X#r%aaKPUn?UHn zR{reeic5Z}5WpFezv{p+1B&n@UjqufIdDFw3+!o@*C&UMk{+aQR+4Ox=%j>=dvtyy z+Dij*0UyWO@88%Z!=JY#3|2J%x+VF=$$s+u{`bG%Q0CAA3-)CH)1@%>WdF;@@pL=y z4ubHnVQrknSlA+qU<-KfXw<}!#jC*1f7>Br6T4spcK+Ct{r}SnEc4&?anxqGp)5%T zC)oyGnMJjjuLl|QY@h50Fye^rhbyPae}E00mncakq0I+dub-EkA1Q1rTw5k-7leRJ z0WB6}N>F-tel7;`Gw7H3d7sYDpWt8hnX}xvb5h^nnhnK{w(oIp02i-?s@na))M`el z;2wm8g|x|x4-KZG0lMPDXH_tar?5{@67A{4gZ3-~s1Xm@I=yRWHK-dBRcDTy)`y6_ zO}<`}Cc0*AmIp!jJO=W!1`)~(6Hxm)Z*EYnlMIv*XQS6x86$5SrUSCf%VS()%D-E% zG6QvH$H+EpJij$N)-vu>TVK6!VxQoXjj;_7eqy8U6y2k8+JM(9 z=QY76#-e1Zb3@&5sm%{lnp50JWRu3vN`O++*X04n>IZ1q+*R27JH)+$$D+M4ZSxfF zz)%|Ja%>JzV?%OQ2mBaZL=gON*~77Sp`0J1d}PqqfKjwa)xo=R>O@gDB|o%z(aLCz z>m&5aWr-QYu(Lpzz2)AH@q>VK(D*7{|gtQC48#LuS*_s%!eh&mon60dSMD8P;-kWZGlJm!jO zSlYWVYX197QvsWek(0oVTQnM_T7J;Oe5pkAn{X=tzW9(|eDOJRcF@s38WInQ=*NEZ z#pfJ4@FUIbyO?hzC319ZlFp>*>N~69Jx8CJE^q)y zDk9UvAZr2u(xTl+hJ;e@xp%gkA6F3=LaDaTQ@9dcZ0mDnb^$J6;AEa`9`u}|% zUjl6@{_&@{@Y%{3@R1SjAs|ibBmGDH=g<2oc;z!$p>rgGAu*aggcgp>d_Wu9CLza% zs#OQtQs8QvmYlp{P<*QU*5${R6?dp4$-!u8>f9;-(n6>IUQSe5t}n{Sk=~eFy)=U% zKFF5LvR=oHg_kGdal87#D1XIdqsJNTU{0NI5Bo9u)d$8CNr~|j{o#4%@lPk1{TD&F;~!e00>r{G*>$*IVGC zLa{v=NN0(v208la$$IaB2Ee1!93iG{^1dVlm=}*Y>X2BaX@cuLK~PnZHKj#3pw z;XTD-`|hz9PTkkd0To9o2ww+dAi7!jaY5Oi&!C36czxvz4G0e1zizp@x)5$^jVvuY z0pSorAc$C7$r)mE2A&;r&fd`PhS!q-WJWEwa9ns4 zH_W8zxY~fXkV6K~L}5k0-{4Y=>&{L~<&68=w2XK0&(htD$P* z!E_1oR^y~x8HX){R2(601mBX-vCydS>uzh31?@JJ0ZDJ}bxdTnnyWjAa+Z%kYlqE6 zznKv=0Nh_e(D%NYE%KFsyaFc=*Zhub=0K?zRxf2}QTE!GRnlu8{D^K!0PE!D+6sw& zg%h(_LHR1*jT)Sl8%NxTR7YQh@R{HTk2kTNcMy9(f1JDd$~kA@TLQs%j*T}vbBUo3 zyidNIl72Ov+>i&4r_sqUNuZcWinu1*sOic%kPeB8^GVTrwBh9_e!oM*igDqr54v$= zZ^=c5#aj0BW6WRE@jbJmCW2A+`c$=L>R0B82ySXT&kCyXculI>COi;&S-ItEe>SR2tVDf8;lrW8p8a`X~?BY zK*{FuTW|=1)8AYd3ZP}n+Ad?Xbu4$g_@&C<{;V+a+b65BL7fL zz+u%VwRwP~O%SswC(5|Zv{Fs2?U<7+^}VkBr1*KCpr<>@L778^HY2?yu7V?74*53* z%lt_M>mtw-qYbL)Gd+&>^A+ZC8(G3(wi1&yks25-fs)g9!((q$h4&X1J3PsNRV%Q% zXWV@i+zWK7SL1q7M82?h7x1NzP;w3Hs_nOp9d7M)rIcy&7k53ZRwK2iV?Gd=GqEy> zzPgjg1Y_g`f$lETq1*2tQg0jZ7N{T`^f}TZJLr32gfPbKbTa3~J%q7mbz!y&L%QJX z%Y{BMC;&V2ci?s&f%{;8$`%X z?i~pQa{ypKSpmDJp^kO!36BtsJY!E?Jsuz<3^{pQkrfYKa9_s5xj;!tW@OjkzLx{( z7SBzt6c!!j5ytJFCp5$+5yF{BdH)`r95SAo9m56#Q_IeE-fy$!x#s@-$n(kc0{qF8 z3^wXcK6|fz-ia)$$fX7|yyr)tVvHPo2>@#@V;tSlNWhTs%0oLf|4j%}%=5N+`ws=< z9|*a#XDcpLfEEddZb+_l6gDF-9U4j2$;3|$*L9Z#$yFvfomU?xWXSHz z?IWFC01?G{DWwcCbGoA-vd_xJr}NzGt{c$M&@y*F*V^WK z(&1uzQ8HOlr=GalBb0{O0T^FH#}XP)rDD2Qdh}z+@_Q{wSZw>8_A83?x^tPY4n9m- zTN+||hFTtOxd2ykL|Cyr9t9uf&F06nHF|lV*)yd_59cW^yv-)k0xjx zTBy;<-btZcd7$%+)`tecm-T0mVu`|LDGD0Y6iLC2gQJ4M?+yGmmz!^u#x8ezV#KC% zLrYu4e1=6qYxrWk@63`;q?dfuXtKb_J<`5s*H)RpjGkK~(dnHxh)}QWFJFrrp2dE^s7_>Hb=LJY@_VZjkI-9*U) zXFbA;XFOV?sT77}%j=)432W7i+`UfC01S^*K-t@q%1+X~vX+RlPgm}`FVxBRle5xg zeq()2(?J5iIVkSSMH4TTpQTe1z>D!c{gFEUocA%zcv02Dfwzwt&T=R;HVq-1N)72R z7tAKq#weL&=}jDtD~^R*%Q5HEJ>zs4isD?%Ta2Z3IP%mc&R+H9g;+V!0N=KU{0M%- z1+VEG zzZhw64^xvNqj2hg@(@ti?V(novv1JSdu?TVR05Fg?CuAW)KO>Fx42iInrUZY?y8qW zT$k%XvYErdnf9{I=Xua?0yBp9ymak3I*$%6N(-t@YjQFbz6-tkQK~da zD^}9Hms%SC+v}u%^BRZV`usJsZMbL;VY#OUjCQ}LL(54nCtREYwcVSJ7|bK4 zN?FE_5EFTX1;-|BtuNIZ_m=}x=o`iqlY>=2qcie6e{KZ3=}^#_3+<~W5_CGlbP*87 z;AhHx)c3Qx4s<-DJ(pYeziv_4dPZLhT%Hx>9>Gt)yPm%=8iqr9@gWm%2W)R})Z$^W zgYBCq;og{Zmg6``+}I=v_L*X_8Fj+`K#oXgHKGL&u00ipN>CFK$wu|u!==x^0EQz^ zKwYvKfK~bVk6gO?52xR-xb4Lc?!zw9Wkj_t9|4UHnB(=$<;|vt{2b`9Yx0=dmTI7j zVeR!684&^cBOovEPan$1yLXD-Xh`~y7T$h8t}Av!flBn{2fX9Y-MJcc@y26HZwOAi zoap??q~S->byB}qxOQUVGq3Wu2-lW>+Z6gA4~~@_)@ZhU0AG54aThrDt|_?j!R1g( z;V`mLsCo((9NTNE-*ssB#a9au3KKXxp+K;WZY_2JQyc&^od4#fpTYWz$WNY7=D{gg zp*I4UhWk(v0--Q%4zJCh>#~1%P+lO#a_8cUbHk)e&>>RX6My<~&RAp2*`ujN&vQ*4 zpy(^^eYf;`hbH-h+v@+FrC&zH;U9&9JTu6HXflWoym{SJHI*N$;XKp+7}_Lb^7(_h zJvrL_L7o01AJpAS;9vWoegy#k5;IOeT8akTLvkl9fSt-Gu)>S&oyzHXe%(M13hY|1 zKfMC^hV!Aq^P9~!xRZ}@O`m5Q#H?KM*xI3pGL>$=u?J1QM`pt9(yC zGdjM=XH1rRVTHGWQ!=Kxp0lNnzz6B)ShrpBnLo#p{){1<{GKKK-@hSdqy;^UcGrl# z-Y$v7x=bYUL#&dG&hK8&#sLXw610<$u%D8zb@xva(h<|+QI}IxaFxl`G&9JO+yv+X zr1q-Dz6}?-C1>iH5iI6VdJmjyYhm~<3g4B5PUIMmYOG8Q{^rTtai!$*?h>ei3nuER ziZ8C@Rxj~srt8)Nw|3}Bt(@!K$&q|{CKB4qvlDM?Y}0#75Ex=|1-p#?m-i|76l?7= z2P=^Kmz){*o}!P?nC9M~&;#FX!D5J2ht7nR~rS zv6yMutULb>!Aj(M-rPW?JA~p~#`~espl9-aigyc^Cfd>k6<292fPXF11G9fJvZ$d+ z{9X8d;POamWvaKv@BCAXyQ|9!gT3Ncot(B-Ho0^Vw)zH9HUt3F--Y;uU8H_dJ9URy zI9w#0e`!NKh=1C2?4j|Ua~H$!zw|de;LiQ<(X|JBPZ9^b54{|_=5wr0q(K})W>X_} z?|pWRgXbn;n~?+6c%MHh=YyeuKuxs96|`wI5R0HpX|WOoDi8<<#3s#G($+)_(hGrm ziL02xZ-C&ds&e4))uYXi&SY|FIYi&3zlLyJYvn@R!zUh#f)HzQ-@6bTItIhrwDzV3 z$x7h!Xv;dc(!w(&h#BCZhC2QS?+Ow7;Wk=1Svy8>04bE3$LU;@piWvqG#vc2 zTF%58($8y^Msrri3l~DAu-Eo3PKG-S9l<#&sG?>f&!-LQyOgL8j>5|_1|tzU7Ss`L zv}rjwpnRsD@msd|x-yiWBOOLL_iRf-k2RbfY|m*tf7JJOvxA~pt}Pw8?`>y$-|<6N z&Di^!aQV4lUVhKaRgC$DJ6y**>e>S>#nMPK@OZN2-UPPLu3#=__PXSX?R6XOIPi?N zKSW**+!vxC#|LLGdnn!wW}6mV^0}0i%XCdUm0y2q4JDRWt}P%z|8mm2C^h{D84b#C3{P zeKzvGYFwz{Tz*LEYQUk8v>+-JzqQ}o>L4mAscb#oD+!tjSskbj>N~=pgQ32rcD|Ob zESXLSf$3BQQ`wb89amzdxD*9(;)D^Z2)XPnio(aqhcy!VnjqRG67)FTwerpGEDN<& zfhmuMzLx~U3?CDuHqVVT1vbv}Bg$}#qpvCJ;Bo|bwCUGtA3 z>My3;9(j3?HWcr5YPY1}A~hjBTo~4HaTbYzu)~C8kOJiA{O{}Ou+i{T$tq?A1Qo?{ z@>f+U*iZ*Xb?Jdk-nn;uvBa2|aMe`|OzmW=u_{QSjdfmk5%0V>uX0g3f0 z#iuSH?{JnsA$(yVHV(&7-lfLnA;d8}{SzQ@b^U{X7LfS+xeEX!-c!?7acVge>6@y@ zCEs4HwVd_nZR!o-n)W*TfR%oWye|V~v`QmV)Kn3}2L~fqZ9&c*in2 z|1HYgwx+XZZ8@)uEX~qWzH5MSCBO1q+Rf0Ku8~tK&l`NxZYRihPcZHw%-wW9fvV~L zV6PD$yU+AfzrS6cVj=ejzB^CHbzmQG%)bs+_sb`fR6%+vy?&~);=_~q64J95oC z@41Vvpe{c*m7R(S!1kCwybp?eI>i#}S7RzBq- z!Aj$I`&0OS@cpjI0S?uE*5t&sR%6f8KTr{)F;v{+tO%Sbe5q&a#lT{-ijI{{+KZHu zCzhR-G~+=tFf`5?=tV#%4RxFeSrTm0K0zY*|_|D;Fus-HTNJ=c|VW9+F7KJNZq5sho_b+2mQ|A6Ad9H=;1^DGT59V zccN-2P&%1A&H_nxyGC$n^*V(l=F;OhF%05)+@nig3?q+k#6K7bGe%d9gqv3ojYiyT zfsaPoj64{9Vn1Ot7=$1ft`=Nb%^DUX-JGWg^)_!G6ZhqW zP4G?^q2IMm71s@{@XjUBie5ULx~J7^ zvLfr|>CD%x*Y{;rFozz>EW%4D(n9EMO&%!|d;`q#j}(67a=4Y0dh{wmcwwS=%#miH zgc*9W^mnrRQMVfv1gDRoxtW^l>eS@lSC?tC18lzIqF{H&)hu|4N119zjtd5^$w3V0`-%n7JZ{Pd;y$AL z_fAga)vI>JMyRde_E<#X@<7+$D)y-z#x0u7BSg^Kjh2+2{=hE469uNYdD2rajV_m4 zTXduUB*=~24A)8;e9Wo{Z{Gbb3+XeMzC1sj>Q{ zsOxKLoMAYrr#yl*=^*W=-AUOGWYEaMR|y#(mHP*X-U+?EkAco^8tFfAi*%7uqPi-0 zJ}6#+gI6P|T0QH?O+SUW+j2Z`O>|aBPEnkIvSy8z0Cf;*aOm1bAPPr;UAe+1LW1)q zO7G0g$JMvv*_j!r^c2m*0v4~sgznIqt>HapXb(6>MDW(&p=w0G8z<50JLhha_aVv_ zqr_zA}F_0Wi2E= zEEpNQHgN`%Xcg%u8OWQ>76`xVyc9F*1`3P~@gL$^UBOXkrp3mdLF3TK}=mwqzc=&fOVa6r7Vv9g8! z5%>F3CBD(u;}`jOue*4a-aZCrd687Rp}24zRbZr^+5X-Z?V8+f7E#a!FU%euplRtktP-86^6Le?`rIR8W$g8cXpOK>Wsz|#8x2U1$5+R6xLzi39pAD2N z!m@`NggXP*by>D^1-(Qcx7lzZ0YR@*vyk<8vL>sMl4l_N#;*#Tqb+3 zBdUQLhvP21wS1Btn&ACdSM@C)8Y$s?yGY1^9Y&+0z$SSkG@oDJtQ{IIK|2BC)}XE5 zZvkMVs=bAL1&<*hm_;GvbNkD+XO20Olif7dln+?GNspElh(E3ypx0iMOd^r_?|}s%r;Vq9{Llvr^AaIYS(tfpC-Hj-#>7cw<38W&6s2cEr>9IGZND z{$+gK+jAO12wEMuf!r1n_fi>gn*m7xrHuSp;``CK`_JBeXG3yH$AjgJB0-}T>0|L?=(%qn-h>A#e4&B||sibtHba$sT67PU|4(Hr+?mg%J z?tAb1e&#>;&fa^iz1G^#BMgP&(z<%0(O(NNbymV*=##9T#h!4rsl~%*(ZhN565W+b zq~wb=dx6U*N*|PDnXL4?z!yGt30`gKR1-+ND;$7VH^p60-g&UStK!5j84^41@vgq> zn}@1xi$+#lW;2SUx#aQWE`n62FiUGV{tS^*XN%7|8hsuo&Or}f{!=lZAYZZuC7&e! z#8m%bq9+gde4g)!?9nrChU24f;ctg~?3TkAX50?HV4uNg&Ze-5DgsDa14ttRD2D^6 zDgvmF0`_qN=`#XvEe9|w2eKRmuyF<6c^k;S97ubv9K`Jz1ZfSr9})DZB8cTEh=(hf z|0qBpBABDqkD!%lln@k&15$y6D6@p9NQcN9hdg~7q8I^E84gj*KvrY`X>)~YF@zXp zAZtW~%2tFb4u?K}8*0K85;+xWsvKtM8D;?ru@(t?-x~JzD9nZ{%%LL8`E8g}M7U!` zxLZc}y9{Lf;owaf^kf)vA`W=kAtEv&BDx|Xb~qybC?b(KGMOtfRXH;KZDeLdWOhYl z?r>!OQDh-;R73F7{~Dlk(glOfMrjz zQN`$C956{_LTzh8LTy6gR04!Ck%T0XhC8v|GqEZHv#vFfX(W;5IFXGckySM5?n>hQ z$Ry6nqB5CZ5IWI(WMn-amk8{Srxue{<6C}9{ zqPa6Fxl7zRt|VCu^|2&2aWbOV#1-IGDEjVHdPxs<77NxY6kCP}JTry8o)2E>$@{8| z-cyN{1;NVdi8|fFUI%0VzhTc=WPYoN@bfB2YAsNXEP$-Wk%&c-s}@qfE8O-hj5jW1 z7%faEPSG~UWtXsg4Ib9Ep1~iJrZRZ1j?Mk&gqHr9f=yW&UqLW&`6TF z!UD*4NccRQS_R6MdskxSRq`ydMD0U~22+VTdZ{K;nvQCz-n&xENYJ`y(O5w&A`J9x z8GX+prHUAd{)`AD`gRhBUZA5_1pkSJj%xvz8 zK-G%ul_+p)=>%)mOOnJ)7C=dS@f{oUSW)c#T5v)4z$@lDe#tn$-`V+CS8qrqvpMFwLr%sEhp?S$0;76=htW6%X<( z4bc9a?&7JQ1roBCS;WktXTlk$>|+N9dN6cX@CZ7twoTtux18pM}xtspq6 zBlJT@s}HD*3y?1=eYo%h#@0EYCO@dwIrOn}WURCAq;vRT(d)U+XN(h*J+v!5_?W%dn0p~!z34GLgfYE0a(W5YdvQ;DK@x2We2Tpoou~nyZ&iK1&3x|> zD{028qyKp^S$aoYZEMGVdrjJM6q-yU*R2$thke>=eVXEZPt5ytA2uPWwGnzXbuPC) zx5@e1k>nYj5b2YwqMmdemt1!i+h?p*C#O}9xz#{@!07#eNz8y*)xfjy0WI!0IXB#1z`u6spD)n&cFM-Bh3<2V(7m-c*nsL-+Z5 z)EV>4AotAq`x$D#89MSAre`zEu`{>MW|%c*n6PGVYs}t#Hp`wn!&W^L;5pe!$x$%m z&q4`9q=b1n&uxq0h;+?~`HiIediAPtNW?zuj{Xd_yYaMzwAW`;VP{sE{KjglpoZR@ zfz7)q*M)Q8MiaYtBl4z29Dp*&6H|=^Ysn|);ft@UeQk3W-&8N!O)NS*TC&$za(cGp zcpkg-ZsNh)>W8lg7CL)j1U4iuHv~UAdl4@^)WTZ+gey|O`S{S|AvV`aL6IXWA1py~ zE?$G)z|J#uLp2Y}ppg7it?(-Kn^h5du1fON(pZ-|#nfo>WkZF#o(*(0@iGmuYmK>U zoi9e~{BCUFtDFc+HW$%AcZ@%xX}A?~4t_N@_M>;Prgs^{>ECzQ$#`^8ejYpd$yVxFwYwf+@=F-=(u2L9|j}Rv9B#pMv?6<&iTNs*V8eN+o z5FU*4gAopmOQC!RI8a?_?An`_)*eP@7Vf3BSo>+l^SbuVfx5eCU#W(^-a7xf$u^90 z{`>~;vuci(r^_eg-X_i*$ct(RBvonLRqyPxJlv_l<Sp@*=^!+`U{K+U6I`y+5b zg@NV`6&X>FKqTRCimpK%IVevx3-?qBO)?HZ@D4zepVOGmeEt)kI`4j|=C^X}{j$7o z6;k^j&%ae~e$%fxs$;c}yhf`fKqQ+F@>k*jK|p7^_NqZfRJ@PN0LN$^EM_i3YUfFM zvimOuP|hYP&gOW}7V?xuLeFOW&sL>GS2WMou+KL%mD!|D>ST7zue(aCq64PDfL;>- zlO|Mn_}eu-aF$B8in&Nn7eyGt-U;TRp_C)7{XWW=EKZ6-mdZLC7Ic}FrVW8nwa|(f zf1xAfp5{ofXV8K~EZ4h@U1EYI=@>zKl1^jqdD&Enm`AQ83M=xN3OO2$kqWDdx$0GR zIVMuedBNvrr-iSX01+}WIE=&mV7>>%AnKzJMtR~6Dtr3_Uzau&fvjh?Z{_0~CwM=J z;m%Nx-hI*0%EFZPag1$8w-v_o8b#u$XsIXkNz`rM3fc&3E%h2VGSz*vk&<(BUGx4X z%O=e-TH%0v5es5!RhZRDh+eynPcrc7TyX7-jw+Z)eiuy-getJgU?y|&o;Qe zdAHjmd_AUEM)*z$K?)I160U?4FY>)UgrSpwyUjhvFFxLhQduKsL4}4qlrh}f=uc}( zzNe)Ax@x@&Tlb`>hI`$!s7w3iL&AD(INM2r_?|k00A5;1sftNn$$eF`vi?%lXEl5G z$0S*2O4MF-R-^NzcP zx~S@*Q;ss%hB6$&A~|PL8Qu1EJUIr+byHc~LT3F1Q^WPVpX`^8qgX zTj-e*Aye3&685@UR5R8dh5LzSz({LBM6&OF@ieR3mCKPa3#~?qVW~FfCRriXDkj-w z1C^%f5q6Q))+QL0W<|Yn2WBOfyKl|QCimOOWs~p-7K2uwtr)zhvQ>Cq{+7mctOk{C zEHl7*_rsRDh_R|=GYEC3s-rm6(>TEc>w!sn98h(q;{j@wNp20{_-eNp9nUIDv&4zz zV83FShK*rZmG#K;GM?9CuLrAMPuL&uyqR)$58EE}zjHE~rZJA6#4BS%PNNyGX>uzj z@5WR&?|DRQns>b-k?BIffuH`@?$-|%a-r2;?}P3N)$q*DrtvN%glU2$muhO3$Uhct zPMjef@|+7IOP(Ui@0%&quAS!D&67rrlXKR+Pw8Zk?ZFd`q=wNJIGxiRK>T<%3S6me z^R9tlPP~%kpy0zcm z^y&KTiJP3&o=)>C0UW(c(P{~9eQl!% zr2-VK>4e^T;f;9%m0B3;1VK*}ka&^e(dm+!Mup09)FKR&J%nS9RdJS z8*;~yhT&woRkge>v<%|R%pflZ$*<=K!0`bJQzHA7&%~a+X%sr4^h6q(xsHM>^O^Ag zA1uxMIF&g%LS#%AdcFM_k^KDi1KwM;}({KAI6b4UspYFXet=^xUzkX zANvz>wMQd4b@Zy{SA2lQ1iv>qB{Ja9tIIB4AIR*RCX~!F2xQRqHUiZWE&$Uf1+?*z zMSZk)*_vbyTNAG}Zn@rz*2a21^yx+uHC^`uoeisE+A{|lJRvw78KA|5IOPJc=E_7G z3r1|t_(HosB8Z%wcymqxfV1R?qu3TmpoiuFgq_RN(ZB*}5|E%w4}pP<@AZICBEj9; zuL*8HA8r>|W(%+JsbC4>VxSf(daa|w*E;kVzNVpgP4Rft-3oVcK!!*YyE4l}uR<+N zkb$3tv)z#rQdH7W?M~$5ob|fnK=EI+Lh8pkfmA6t= zW`oIt{6=+2aVmIejUBD=+2qgy9ewRRlm%zY${^nrz4b!Q=Q*gh)?S}anO>Dejc+!U ze3-@DeAPWVvDZ}gQMuX7uBNHs>sPW5l2jJw!_3GY{t@a$^^dm_&4oI!Iqo*JKip=O zQ=8Ep2=n+>WtkZ-_(I<@D78tBK3X|y%vL8n2C|O_LTr=FG3e6n075o;Guq?MZgmM} z?MS~?>Ej)Ys3UwC3L9^*z43%wsgG`Jd?;&*D(?E1uu=<9ub4(h?qE(}^{X6CQlXn= zT!OPj<`~1KGb8GUn@Bkd@hAMrcUs>vU_}krt+QlR`u&DUQ;1lJD^*k0MWyqG4yZeX@X15zf0bpnX zP;><)?&VE>T;<_C?rXQ(O__YiBw6!q_~1PDpyuHHmLsq2^!2#IW)8cr0h31^>Jvxw z#HvhYxbIcVXMI$STnTJA?<)=QgOY5dfGtd?1rN_$w3%=u6VM)*%RrJ#6YyzlGa zI)q-j{@q2X_h*}v=bMAPfHhu(lNtbfEyBZEpg=9Md@TxfEvh&a%?Hx{uDZ_IAGP&S zFg;>0#GT2LH`K!kAw6Hll9gf`61;?tiHAl-iKk#u4-tSl;)H<13m|3*iTCiT z#U`?a5fOL?1Ne6=@LKj>G`9S-KKyjI_!$N286NV}XV>2fu4gvm zznxvn;schXLT0gaM?iC^MSr;c*z=q<6IoFQv>n9VfNKKk>SN z50?Fw5E}T|8&tR&1mqh8^%{h%8lJc`2nRQaBsYi_H;6Sfi1#%}%r!{vHb@~gN)t57 zP&dl5H_8b#%F8z@=rt-@H7dC@J`HYEPHt2wZd7e(RO@S0pKH|EZPY|+(jsWmrf$+< zZ_*WL(vxq}*K0DcYBF?bG74@oPHr+OZZd6XGV5zHpKE%y+w>f%*@B?ilDhc?d-F?y zW-IyTS9;CXR?V+nn%@LBzfEqoDQHpv6VL z#Z|Ax&8o%SrNtw-#WT6ZtGLC@yP?IWuf=z+#c#L8AE^~a&>BG98pz%nB+wcx-x{LV z8fw)V=F%D-+!~SG8d)sTQqdaS*BUd|8oS#Xhtw8N(3U{mmdM_gB+!=Z(u%L=xv_)B zD*(DJ+a?qpz8=w*)zIc|9FslQ7Acry)f!`<8=H7^QxWed+ z17HIvfpeGRj;jBw$=QEN3;QD=PDjNL3C{0E6aLH4CAPhGK+VuyZP)86!U=9f&%&qO z$=!ygJ#K`CYl}ky-{`o6fUIEND0NR^K1jWsaMjb4$4&45sp=^>;B$`)egOCakMQf8 z>*{|!Is1!D@jt}SZ8qr!U{8Kwkw}$}XKo#1sW`Ky+_K)tHa zf1I|t%Yi^9`VWk!e>M#M|CJ@Ju~qXGE`!kQj-APK+*BHUz&WXP>U02FpeWbWI!8D! zNmF@%ifaUOM5YvmIU%yr!<-SJ^l*0kp8@c?kDRDn7juM1d6~fkaY8cXMzg-0aO~{A zXDH9#G%EX zMfvWus`mJtAS~h30qL@PW;+N8}CTC|B611#l8_C&KX6CFzW4NBO6(T<#2@ z|AzVGv#-(ilgXIrlTq|T{0J@>cX%i8-D@Q0ndJBAyHJnWT>Gb=d~?*DR}{NL6Lb1b4AkTgt-ANIUU?_{#-RSG|G%L z(lTy$eVabSue$#;E)aSq+dUTXAH3Y-ohJ4aSkYqOaHJWo0h%B zWdug91rYh_EvM=qxBQvcDBwT6B$+lp?hcr4R{aX0Q9ONuBP+~;tCs;HC9xf zI=|t7KG?z?|4y-GGbCxwxa#V`nFGKC^dc-=u2SWHoeQ8nalCP5mC`i5yRG}nD*aWu z@h=Zfjq~rQq@rJhcx0-VZ?Qz}ks3!Xc=`hGSWYjD_F7f-9{8jE$#DKk**>{g?8&t| za9($jP}lz~7f27G|Hmh%ltME-pRwQDoPL>p9z{%`!*>%;eg;a11)K4@J~DvCe}|kP ziSI6<{7pU%tl(L|gVI0JJ|4wupztljQAx3T=)y{(%KBEaspT|Q0Nc0f%xe$re)Qq3Etw&&3x?8^4mtj^o1I{_qt|q()4n^~$o4xh*67;FP5m z$!Opkrprw4uZLx2JDoQ!GZR~S$wWMFG6@Mzk#uRVutWp0QSR z!iv6L%pc0yLq8D6=1|&KI-pzTL4zw7C+ZM2ti6z$wNbftRZn_#l>$(2ZCyw=w(8L6 zuB_7Se^J&_AQ2W$hDexBT%P+*<&Kg!0zs@h{M1^>iImwNFWeoFi&XpEwWhYQca@9Hqb)c81IpfifRd_dm(R2W zT~MvLHf6e!#85R}L-$-F1@t3-J_kCds3~DS+PO?7&JuWi21nZmjZM!)Z_7LiEUNh& z#=modd?*J5#>#8*t6WQumyWyzf2xb4gQE4@WP(y``~5GH$jWOo0{HyGqGG7vxu!Rp zxP3GHJv7C9UU;}I8V~N!Y{PhJw!(Y7CdONOeb2_IdXx_!#>sAilE(9o6*MwZ`1Q<& z$(b~;0MLKOG4c0ama#ILDkB&P-~grkjIwx3;bdl}ezGAZ{yjY-fBOOEV5LHGMy}N& zk;bQ*K7s}!8dnFvvjG?YMZn^ZRdkCcKmONMFb zw733@|9>$hRSr6>HNZ<>{%$HcB@vY`MMyweh>0xQYb%(TWy03=ztB!o=i zON~>$(zYE5qpG=cvJyg9@G-+85(p-M{pcfu`6y~h@UtxC46{i@JhXH1KuBxokR+@3 z$V}eH!>`~#Bg6ixj9|F>OhEkWYTUW~S^iA$o&BM&{&spWHV3EVVEChLpmtd>Z^=}d zD^Cpu#1*rX&6qT_!@ zu0&4P>wfJmkbJ(yOr$KXo{c^YnWj#4PFzA+YhC*P?c0-pM|68;RQwcS#64)w) zR!M3@K2=7%nqe{8Y5;CR_~8n#2yvkhl$R!zis5n~W~iw6Ea^n(S{tS6ladY%G6+r( z3Udoy4z+`ytO8&=nwhk_3ZlQgWtsl1_>V3ZhRV|_?VGw#oKZ66v};~ICz)a{4J4tS z05~w}OEK;By;A9+S-Pxh+NITIe)`+h`rk$)Z8FsS+ ztB?cfo8yxrA<*ZO!;_zfDq+D=WU#T28UTSUoDR-nh4-hRhK0NOfwZBm>OPeBhf<<) z`-NqZgfVcE0ykICE;?PcaYLq0& zco3c$RUkA4Zv5d1v5Ac4EhQ*!)z zBH#UCcOWYqxc{tKvif9yb+ZQ0&GGzuWXE>&zR+p?k%^;&rG%XHxS!O; z9LDFNNI>v#0d6kyH+^P408IW_r)}L>Zx`zPJ>;Z^oBjSzKoEK3kAmLFFC-kv1>EW- z;>2+K74Y}19uudk!g$J3#c?{7Kb5>1{vzwLAz+wfUOJjk!i+y)F_;rCOcfGbHg4vMWxK8U$NGYGiyQ{fM5W8pgH=u|z+C!>td<(|SIh zoy(Yq!QKD`W&HVtr^3h_xIs^QWk^}*DdkGVjS>_zXx{uF|KDgsy%1W{M|jYt!cnK% zWGyq^6#9WM9~8krX+oCog^$B9`bQ|nI4~$!U=AQi710_XblYRBiB z&O({A6yQ0UX?F25WjN|o$Uut!14*ALUkx6?8uSxbehttpM34bBpt@&j)P28s1^NXn zzYZ8Qh=P?~4~R6#H6n~KN_^y~!cd+s_-(Fi$%$T{FIb36_rtBW54nLtD|)x9YV>EG z^PSy)7ZehY_fR@)aU_xjZo%x>`h@!AV}1jc9L9D7Xy*gooA<_R+sy~&i}5dSI-9-7 zrOyoe+Ip+(W0Wlob}j4Uh)T1a&Z3fe^sa{ox6}%;ahG;nNwC(n@r2Sm5+9dQU)pme z2(HU2ncp*I)y&x&Pl;#yg#HDX1+gcl$NtUVs>|4X~4Xh`CyDRl%L}j|F`7Y z@!V_Yon>YSeL99r_BRa=q(EqWR@2!Pe7M)ZA=5pyK7%xJ^JBxZI|BGnq+NiFmIm?I z^>yZBa~EDDm-jf0;>XJl*S>MDRd+tD{fs{S?AE$RXV<$fyb_v^npJ1B-!_BE{D16n z@)WH1+TQ3^hk!G6q}X+kWp~}Kf2(rO{M7%|p8Jb5@4G!0BLVG+a6Mk+cYCf4jCbmdic8xW19K`QV-5&~00>Ed4$;+J8{$J+|myF0i z03j@hI^O@|n~!|PkDJdch(qSn-$07srwM{o_l3RdUwK6SN@oCjeGsQs!RZ+=J(jG( zmk$|TwReI{NtDkXv7B>l5rtB60%w%6o7<$~WwY_!YCB0DvmIyQ9>oUrs&`{+6Q91F zU+cH1ud|=|g6fx8{r;&cq64(Jq_OHW<)9dU7ui;K_Zu9Qul1@XzKlYk8Ut<80pr5w zgCnF5zxfz6s<;vfg$Vxeh_DGy@ZIE=*YTjY2?p^qr7k6kC*Tmw^4*n{*Y&-#(1Pd3 z2ImI}FvZe00qArZX8nb+nq_>R&@NN+&j=@X1<8MYIv+yMI!qm^_NY%MOv`{kloO;r z7;qmY0MEcpGw=;1U-rWWKRA{ip0mELj*t#OEEa*qy&1XQ#YobLZ)Av17);OSjn%gV z@E7vxNy0GCpz==GW{7`=YH0#XLv|E}r6UG#J7lCv>Mti0BY14WEUIEnMmhPtgMwZt7I^j4j8nX=a1Sj zJxl3D5nA9|Bnf`Tw~E)d0o}yH+5Cvs>;0_iFjP#b#C|yQx%w${@Dv{+sk{XrDupl$ zKM1>T3xNHkW2*uE-1J9h;2N0{toerfEj9;;zuDJT`n2q?ZMVug6jiDvf*sneyTo^# z(I=v3Xt@`Kjk~!9fV_Lg^#5M~DdS|7OnccU|0Qw7WiFG;&#bznl8IS}H2}=MUlM+S z=)h4-JAvT;Ao)Zr0*Ftd*;PTXv#1fk5sXy@r;??b$ArAO-^vde`gG@`!_y1H9&f2X}FrN;g#;0$>Q-xf${H09`fbaRsL0CKV6CrY%O5f4A( zyCQ1Q<2d44!%6AT{=0!5kkAXA=0*CD>RAuRFE`Q8`mhhc`zE@+PP2a4uJyD2q(^Af z{g2-YlczKvE4)ut53Hn-Ru#4ZFF?fm38?SE(>JKJZ1_ULd z(S;LvGQd*9;g{63c(;r4-z9!oQg9slxuk6+3s`YZ!jz5JqQaC@y5O~%TeNSJl~;Kj zxsp$pYZ6#cQ<_Ry&@r;)o!=>R0nu40HY)*AdBaKRKx<}VL_x})lJNm|3cLA#UH-$0 z5xFS;eI$1Pe-qUFlv{zCD~=rnjeh6SnC!k#)=Xxh%{2*@oEpYU!!X$;1y;$HAd-7L^ptA2;N(UZqObB=ZZ`}R zCV9x*p31pWeczVlWN#QtmoB#D8&ztM2<4A*e_{Ew_l?K%K~R@RQ--x3Szr1?dY>78+$!f{EEhJ<)>! z#A%|teRDTW?7h;$_?!vl>G|BTg43biSUpBbuaHGy$%rzHuoOhCOk@5il0IX;I7t(k zkTG*kSOzeG+aWWXw$DVx=E4^O5F6lzdnKa=?dxTqZlfo~_Ij=AR4mwtWfvmxjNXQ0Dn8)QBKC;k zRPDEYOS}WxW=g0zMmf=QM#jAb-Pjoa=tH5a}iGqjp+A2R0O>Ev9@-hpTJYdhV4P?gs};bq?I<82iG zu`O{cY!@Se|v5Rdv<$mYvcNWdR8;6DKz<)EV_o}<`J*)5G4fzJo6HRrz8!!W?gdSdI z^$nc2U4I-DmkE0^oWx)Y*tv30TojoJPhP_k_}tM+MQu4*sRUgwpzc3f6?kS!FzVI- zL`f`mWj1}W5TJ6R%W`09M+ns)C+x*P1)Sfn|0b`vO|k}^5778eDnkf{i%{1S)E{Ww zf*%wa{1~JcVxb=pyvdqJ{XoKH>k9$r>WFCe*7YCP|BCM@#h=%IZ#ZRS*Fok?JWHcf zC2MNnia$-aGx(8rMp)jrHL(WUdg?)ImLRX z9!u&G`zCzu;pY9UY952;4QEq#-}m>_hjV8ZW4lK*0!L;k`$V4w6_gAA?o_-$=O=JO!F`OIn_(!0fO4q#qjzu#q)P|j z0HA=`AAc)>(eqz=2h*1zcq`5yAYiyB<3|UIp@86rz~-x7)*prN$Ot%A` z-ir|pF|2ZwMgJkN`B}RyjEMAVBi?|>`6^X zB>QegINPvbHt4NqDXWLE@l-Rss-t+cIX&M=X%4#9*`pwzfDlSW`O1Ptau78MaF5Gk zv#vY-5cRq6U!2tH2oe(hw8C!SHaW5UlHC^8MrO zS9`55J+G}Q_+>W0G^73}r*#GM$P~_Lr7}ezS1Z0V9rK;A`Lniogqi-{yT z>ofiPgfkDl?^($Aj~DW-uFssSoo|xv?lk!Y!f3P}la?a?qgA@I&Lc0j+!fAdn*neC z&uZ%PFFU4@?Di?j!PC14p19U!4<{hjj>A}P-I6tSbNh|kqmvY>7aatR0m=8tr(gXo zQSs770NTh)kSFK2!pV$-0|KO<0&S_oO^F{p)dWUa0uuQ#ZRBV4OW%0lJO_#hM`+8y z1pK`&F9-krP}N^X7V8_vgg{KZ$uE(`qBj9x8EzccynEce7GC65@u`7$NG9p@dm&G4 zjISblGvION;CFEb@r+E~;|H?WtR-Jd(CIp=0YN$IbiF^y11}`wfVqa>Xx&|gaKCH=@D}iA<7XRiLKC? z@&-R%6^S7VW~8?q03PhbMlBBw-#1~NXbIsOwA7_&D)+5L;wRqSB9YfsWg$<7zPN_h zrz_5ZN1&&|(Y7=b5LNP3&TN>~bIvH`@W5L`@{uu(D3Qhw(K9?DWw>Z&!bQ(UsTm7b z=Ih>%&q~`O4l&3)QO=du_pmA5O$&eD#%^SfVa&HEX?|-Z9V*w<2y#e5b3u~IB|2UT za(wp7J@HwJ9(-h!dnFUOE)v_eAT}^|Gl;hvJ1`cIkKbL_6c|q=12} z&F{@5Gg^n0DiH3Cl`51Xu*Hj`+YdEAA^#Yyy9|#709L>-p!V`$`d4L2-DXvA(3`8R z&6LJ>=p4T`J=W-7{=RC_R-7T{4T<|Ppz*t^#XldddvK2jBPD;L)dCZQxbT#TQpYLB z1Rf^?DdyV=1hpqRj;N>2Vm9#x9>T2P(kNA@N9Ek`gNgBOU93b@QO=0^&Dp z34cvh;i32sYRi8EOj+a z5OKUNb!E`y{~{m%BZo83yXTiU_gN$=3vaEGBqE`V!Jf(KixwnSt0TnW!fY^cYiqJW zGy3tx9pr*^SYjg5S^272I#;*-HrlAx`f&Nn)d^qjFMN|9or6#`dJfE|KPltWmEWk? zS;X8E{a;52O_mb=E{Ho*@n8sp zf59hjz=YALP>AS?)+!&s2iKYu!gv1ql{}JBAl>*+@XEj6`M{#Ohr}ko-}zqBV-4a0 z0eI?deTy}}&eQ#^oA_JU(2VW7a znCfc#pKTMkD#IYvobBuxoA`!0{ z;R?PZPff?y#50?b;=!{h6QKtr)tkh=qXE|;K2%IPSPuo zWI{C4j)k2N8_$b|yWn~9W*cdT@~Bd?LTO7nU(ZKSzUm8rmJaEP@t9*xrSh1LI4{Id zpX&Pa?w{OsxRZm#4dpqTGBy&a8QOtA>N@0m?3PfF_e}Va?G`yNJ@{e}e|Mc^zKOC%rk6b|9 z;l)|%uwR>`YhT-0ns4oNun)pVF8*n8_KWlrcyU%<>2LH*tP!*hc1H{n~GhN;R z(c{yU>6tKn&wG4p1#jpy+T4_^&f#n~eIhhmTPa&S#gkV?9!>i`Dp+sEGZH!7l@}z; zs^f`bCw$W|(TELz11hHXqbE8(yeUsAq^|=M5M|SGL8LCHHX!2nsD%kCa!TJ<(n(2{ zxeE>!@Oz*_lqw%Cz9)qT6mdX`e3F|n9BwGdHWO~GNLvTMqsC1q;LaRg)WZ^Dfg;HW zXu&ZN7?2rGcau^OF(T}98=;JmqjpND2zk3v8S0Z$XiWX z8J`4C!f-v=+){6bU2oo+p`=`%Y7BxqkI&*qpB5s*GB=at9-5x($imLyamSSx9hr9PQ?(l<0$vGZZ-_33!% zXO<2ihrd^1~PFr zy(Jh!F)Kq8cLxBuuO(nM_ zY&aA;5dqZkJhzMJ$D0ahkJkNz(^q@*&hXQtt&L?`iXNO}zEaf+MEK%ZM0;Cf<%k+D z^-I$Y`07|f{*q_sJDEwavn>Mg35cPN07-+#63IoBtVXgh#laAYbB>*vOqjUEs>gxL^d4iFBn> zc8ec|FYI$^#R*-xiGgW9eoI0y52I5ve0AdxdU^ZJ8zsw3r7%QLC;1d2^F2L&WgyE0 zCh&VU?GPs7hN1bpOyb zgD-C4Em=+#vYy`;6j!Y5R-IO zu|#XmMEKLbC{89aA89~ABe{Ti>VSc1Psx~xs&v_?jaW|!Zh<9UMf2}UGrxUj_FsL$ z^Bb|)KX2iavEgu!V(3UQ*`VHjGg3!#l-AhH|~zp z`5NXHM?8gkmNJS-!4ne)LMM0Rb6-YA`3adwLd|RUdSXLuvQZ33h`h86TO~dnAyPGx z&mqikI=eBpX#yc(O6C&}r*>9S64*|~0wJCR_ArJ?gGdQ^+U6?FW^#z_q3mqUn;jvx zHzBm6UB1>`)GLz!YLV3E=NV;S{QWgS-**&{ssq9=0lgISXHxul-}Y}(6UQmr^;+~` zLh1m=!(aV*(T;-!{AjDC^1tQF{Mz|opV%8;m{T0FOSZ3hJO*h)6YgVyt+`R|n z#QSEf4$P~;9*NQbgBk3%5wLncms7RtT|WGli&D&E#xwo|vVC{KFg_VV(fd4)G8(x{ z`W|DO)3JF5SteQ$ds#*r6()!ByW;sp7y-j2%=Nw&)4m*b`AS1yF;6>YX}+;L>|YYI zOc!akVEo1KMdp2nw_}Z5JyA{z)RMZfmP5n-#P><$Qiw(r4dX)>cF{Fa-XFI^GJ+T^{{xi(d_k$nWDgZ;b!Xmdzi+OZV>;gE`mNM-Jn!YYlkZd7Ao`l&Gcd}-rxsc@9)e`I zKXO{?esTrTg?4Zj>a_baJZS28`&GX?f>#M;{B7}aXR=(J+bveHbm?gUS7(WLrRyW* z&sV!T;Vs08T6=VCN!xO`)5xDms>_y(*3)3W5 zkG?L|WYN`}*?!wyoBa@mZEu&plo0P7#7t^^K2&<)G(tL7f;gaDIE@e)hak?VkLa~s z2)Lh8x)2(8OuONm3{kpAY|RgQga#Ptc+$tF>v-MDUDEMpsixP3JB^HV>~QsgQ}&&E zv|c}L>NYT(nOkO zX6Q$$RVxPZajVdSdCq)vAWWzEFUTCS4~x7w6S8;wdCzur(H|swB#QF7Q>}D!CU)G+ z;4Sf?0w)Mto6M!fx`9nz*fSvY0`#C$81?RKaJW14w-Mq7XqW(PDKJ{%m z-%8p<^QurnMW~~4cIZ|YKwMpK?&>o z<*=Dg*}XLT!n&?x zB9QswK!rZD4-OAoee=Y>@=SivKYMLS1)CuvU3QZ`QZjSViem71uq8=YZ1NrFWcH5j z!@Wkpz?C_bvFK#MvAMs~C8o9kNW+r1Tv$0?$;zJA8xuAA zNJ_plz1M>A<|t9zMx%phP`A5>ZxiGEgn#f(&FS`{CV3co02R*XQ(Sl67MZ9gm{5mo z2Vcg8-Z-c6R*GaIpCyL#|3W>UqP`O}5xA9|rN+fVol}@$?zHkh>Vcg_d#quvCfr zJ9uYHs83GUxBcJG=|+0phmlxsL$#@4MA!G@1x!3R^N4Sf&}9fM7O+z0l#}c5yf(==zAB$4s#q#%m8+)DU;8_6UbW>l-%Gl z%)p8!suhx)%*Na*=B(!bs{89)lsG7ydDvZCu8sE1i43;JPee#1dkU7w;+?f^ z>~|fzsrNe>Bww%i$BY!Gai3E`=>5!`d}d|2f~6 zchZCfsU-}$a;D0Cv8Ba%r>Le%q@%;0=FDc6A5_QNN=s|!*PpwZj!wK_rA#Ku zeu3CNR#gh5dKm)6Tk{&4S1GF)s>-!4YFG0dD^BN@Fqe34qB5XZlD0sTr})KGZl6&B z5*M?VBtZ6?<#~QKoLsTz`FA!;zW~K?JZa z=SiwN^7XK}nt8**d2Dv{$djM5e0LJW}EdcuU44=SpJKa43U-*_3dGDYpeS@5PbKbEy)k!Q32!;{lyX88P+ z1k8~DL2#QOu*XX=m=A!4 z9n<-o3@fFFa!6(~gt^dKfONJQrT{{wJAVN)uoi`xx;8Zj3V0wLZ4r6wJafH_vr+E< z;qEQ`qWbpz{|yW^C=4kjC6W>rDKJQPcZxJfDcwlt(B0h)LrAxxD2Q}}bf|R9Z}3x| zbI-Z;J@-EDE}4g=I9YSz6UW@7c0aF1=l_`8;68k zk5x`v*LMc&-%~~}*4RIszQenVUpKWhnF`<1E0Pux1lfY*ITTzDGx6*_{*sc`IQZ&d5~HDf>kJJ)RUSWe zCXYRF0W=!hL@|3kb6qA=t!D$8tc6~y`8r1u-o1rd)>x`%g@Ja#-u5Sf4w^x)T!NBJ zf?R`xb`k?mzP!|!(D+Ootfm?4KcL6BuD1SI?U}hzCqmrFtjIqG?jNfe66X@48Sfe- zsjdhQ$uJMj!qV*F4swSFF4Y@5ojl8%2s+gWErW+1V1{`O1XULWRhow}_jzZ-!!jqr zT2IXIg{=egAXxXqDH$Mrnvyur!h3lb2ZO`k7KM-SL>LiA5FQYLsv#3hkZG6jo}!3_ zlZd4x$gE~0`9XNVXQEAbq<}rkfvM)S3yT76)Z{?K;d;crX_S_EHTQi!(HM%<~`g2hgd1^?eiQsFPJ9k60ygGoX02G#j~HBt*f~T=ivbd+baiUsr;;wO$ z$#K$6ak7(f@~3f%Wbw+p@v2(!>aOvc$?@7v@w$`o`ls=RWC=#R3C3CprmhL*$qANC z3D%PdHm3=8WQh*EiLbO0om>-Lk`vvU56{jgx zWT`d0sdZYZ4X&y1vUrKG(E?10S=%GrRR@h z#UF=hBBo8l?tuTtY7+r9uHq2UZ@_7O(uU#Z;=kAOv|?|HnOF|(U#A)rR+PBa8_vR! zz-e#s;5>_*^f59ohNqz2trRrJb`8`;YF|hlaD(?d6r+%0Z@8kW0gWUnp0i3Q*Xg4T^a&)00&n}1gOLq45em|*<5IGVwG56gCx512#>G_->W zUWe;qw(sA#k9eb9og%)gjld5E8ZcnT@7n}M=)nt&(LTmu=jSKRETrahXB`F$tBeai z%uRH9j;NF0Klp*T)@h{AqlH63c@s~i$;$J%I|T5MD!#bRL@brn#_YGn5GHk`VY_^y zHh_q2%IE_JGtw|3OlLX~N~C5#RQMzCMqbe2jS=ZsvIaDL z9|hBpc_BGJ?p%QtGF~V@>f_?o98BDO`nuMP7>12un)Uu3r2P|yt*y@N`E&-@iCs?TCs1d0Z;L>7@7 zTly7S(pw0dh9X#4C5*{ct%Ms1;09t?B`W((Rge*W$-xGGt!N zzbHHI|AzSSdv*8af3v#lRbH2GQ^Y6J)5dfyk>z$7-8Gp$T|`@kCQI!p{Oj?)5?}&8puGJ#4F8gr9OUfs=?XG zpcBW`n*l+VWeDB$KD=-=*t_`RV{kNc>t2*Lq2tlXqzqFMeQ4YTVAD7c zB|wHG`0k+>(b$yVpzmccz5xvtD2IK@^1w0WNdc)`JpTYFcbLg|pm`Q8h9pWI;4vd) z??YLs=Yp2Pqb5JS2X-F8(IcMl9W6#2B5TKy0wj}30&Noymx9H)T)zZi;My6mHt<-i z>VBJD&Impzc3w?XJaWbPYo9~X_{{s3gE z6Xh$v>SM2)l5?%iN;+tHsW-3y+EWmc+(HBH6#>l1aH1jP!&m_b|5G(_5E=N{VDz6{ z{NLwgDg-ck|3tfgGngR>%75R$I(#=NVq*SX`ulk^^#CUz4Rj)J z=I~dr>Jh1>p@=UYrl>A5VoEF!lTrT<_fIHg)BPN&AbJ($F)XFOu?hYM?w|M)fl%!d zg1Y*u+oSaNWi0Nx*lzojq9Kxri_}@C>dh8^M*RHZ{`nV;;m9_F!bSJIUgj$zkMs_Zx$VZ*$`s zE{)8SFL`ug`_G@m*a`=XEv$ijp`>WkU&5Qg^M5P7D;t&WjUA^j-|i0vV6*E_vJwEv;Lpad4C)1 zeV;#g-=F`t3;A-g{d_sI|NOsL_@UARzgq_W0SAI@Py4%v>E}%QN6C`JCwqn;v;R>t z&F}7!KRitTc!%b?^;Df z!=faG5_S4w;E|}pVMvG(@8SJ8tUsJYMbUKqK^P+JvL_#N;ZYEgfbZP$aT30ZJf?)C zLzzM`sAdi~l6NwRymL|gyPA}Y7?cnMq6g03R{Ir`ukH%(*P48MErCD>vf`Mfv!CXI zWn&f?nUzG@7~ZKq^n=plCltJai)9g&qYb9a79C~^=m^G2lClaD=ts71TgX9S+XV*H zh^5<<(1T|YF2p!9qT*mO_j1X4OAW2u6~K8%O6pr>x1$A)xR-lL$E7&u=?yfS=8xz6?so$t2gQUX;M{|p0Q!b>c8>M4?6xrNa(vu!C0nCSXV64Wv zlFmHTx)T|Q@p?&wdN+YTDUl>9jgHM45d{}fcV)tL0SDt|c~K6M{fl{G4vZkXTVo>!$lM?>Qgx-q7ZiilcA4 zxQz8Abd*&JzLbJJ4O9W4l+l@V8dDUAD3vwNoU1j?G5K1BC62|Y#j0Z;4NM@hM>WpB&KJo)-a4ROIAjQb za~PrgjT3|hzO<)icpf-?+_VA2vkymvz${F_>l@$|+8`ROq8xxCXZ<6`ekap%09&(p zbl^Sdft&~`JsxC7j{r@&D9#PZJh8pINh{XSGqjaxMUu7Wap+URtMM0dKC1~u0wJ(O zoj((bkpqS#asgdH;jaNR?DWP!r;+{J8M*^DeJ2T9?)_U*Yw(}W(El*|)iA&a%*r|4 zA!{fWK*!IS2GmWAyXkG&#sT)It8Ry1@hYK>`VTK-KiSTFvCbJelY#Ua6!l<;-Hm(V zkp0HDRCbdsY3Ei9NZC4?V6}18G_erf|11#zmfLLWhltbYgyt*8aAFA&$ zQRs^hf=HolV}ekUOCtD0gSjcifBs}?2Xjj@TRzI930!Er=WVxEI~vZUq%Mu$_WBkrjdXD2e8 zMP;MTps9Ol$ZZx2=Ylzzbu{f+6pKOCp_^(I6~ugs#no-(@wuqHp^%D(BR)tGJE=Tm zjiu}-pq?Tck~%n=#o!I(!S7Ah7BQjF5YktNs6Y!8QL{*mE;$x$c4U5i!QVHRz*IirnE#I4MdSmjS93^QS4ljP)YXF! zx6K*;o~lc8lTR^&nFUNoqEb$K5X-%!k!%-QJ?T6%0kHu*!*_Y2-LA^b z7JX2m$BNDmEC$qg&K{FWbLqP>WkcU=WCz~pV7~KiK?ie6` zF1+-Bs`_mZwADMTQn z9kNs^xbGNfVvD?$H_MR>(OM_+`-2i~WE;nj3RMV1PN`s$WK;_bxsdOfK1dk+eE7ggTv-*7Qb9;Qa zrdrdR$;M1@5kjy}_DD3rR$>~tx_)ksZMz#dwDyXD)v4eTW!H0rs(2+EG3ih|m>HLp z+oP=3?-lD@;MH0iqODP?C(t3K@QIK|u&HP^n_G`j=)Nk?*~aI71MdNoJ2XCMbdriZ zCwC?BWpKrrvi%5u4ZqJ8H~*Pei%M+tN7V&{G{fF&K<;T|0czwt2>Ce=6b*~~u9Ja_ z_G!9l16#zMpdjm1W?p$SaSwbL{za~P7DZl6sT5nLP3 zn451Pt1e1`0`62d`CdI6&A%fe5FlO8BA>7R_xV`0=JiwVaCJju+MdZ-sLZW(9h6^d zLfHTxK#kh?bC&M>U#SWG+a1?W*Z6N)fXLL46n=KAqjTHqz8<+wxaHNv8=Vht6bQn# zA9szTKO>A2fE@wTg)g^A1Qs&)=Gr}-NpL+}_Luu&ZyCt9o*pC(rBlqyU5EMnmKySJ z$=lx(KQk5D+b)q=fLrs|sUZjegK5DBbRFh{#ZdGg8*%;!^SSq1YRDg9KK~1T-T$%? zXS1}bPx)U`6OwnAL1uZMubS@;{khyAYX`_92#|=f`|~yX(-w|>#RnfT?DoSWevq~f zqZ17yV6|+8-@nrzMJ0k8&O`8gFcSL@PyOH54v>@JHTZIJ*HG!T1P;Sp_$xydUjbwHDp6Esiyyo}O-J>Hh?zF;#8cg4Y+(^;^c?+n3{&~LSKSbG~GlsI?6 zbGZJ#RN+GgpS@KgfB`~CnzuNge*HR(so||}c;>q|TNxx|;B|hw{qak`0>aDV3hAku z_d*a$F8HF&ebF<@3#Wrw-{j&M^3Q$5gAq`sSoC}3)U=-E_`t2aVa8_b zMdN}Os}1}W-}$zFQt*&PWxfqLZb9~@v_EA-6sW(VPv*kC2{%7k3-^Y z{d=KzLYa)ryY5fqgnz65Vrcd4aO!UCw$rp-I~#XSq`Ieu(t&!jywK$dLPbG9Kd44} z-v9jjV}UDreLMjJ4r{v(m=L>bSG0;?({h4YOi$%C2J{vG$dj?{}Ly|TJ{VE(|coI$3eF@pDeSFoHCfd>Dn z_d@!FEv1z+=QEzw^R|1JCkwG0UZ?Asm2F4cj8@y{DtPnb0%#wF6d63ml@%JU>T1t~ zZnC6KbS*Yo7w1ryks9ukoU~v(sB(6UrPdn?dgA=Cn+gr9_sPWpUf0KEWp5d^f-@z& z&lVL9X)TmsjiN4+jFAB5G2QMbjGgrtU0$fzw|m+93bg4XUtehkOd!S<@zje@o%r+g z8bm)vX%`LqDtZ_a6=Kz3jYHT!r4r}ExWVdU%hV<~{TQ{HrEU{BYD?>w{Nl8AnPNK; z0_s-i<%z zIyLf6BnZM2s}^B)iwVuTSji}Jk!)Of5q6dIh2`QS_-4(wS5>NF0^9b@Z>k>z!i^Vk zoReipH)|4Gb!l(PxRTt!U7$YRGERLejOS$>Ms*26|KXLyqaK_~<@r5`T%x*r*0)BU zjL?Ls|CCDsfArqKBguohfqR;4d+E7ZaZ_{HLf`9cwfb=81-6nAZJwK>o`{}80hA&6 z^x=1Ec>Ii7;mi<&8}v9U7p9`UQXgYJ55mAVaYWD^q;)>Z>hJKGO9ZJ`8b;TtT=DT8*>XYX* z3K4S6x_yL?ERw!f3++d}Lo{=G1X^8jOYob(0_m?@x;y#BG?KJXjeMZ*FA?2f*gyDOp z+@+K6HxJA0W~EglL>|f-qY`FwvRTUMOqu47*Oz#{u+nLn8b!1U8^=bOTGPj@bw-QDP@5AR z_lsrf)k}1@;THYFgyYr?Jr0kZMg60`<2O6;wq6JB21jRIREWz;p(2eqdPyHQEcr^$ zTTkZCxHQ`@JvqHMaGrq`COXgcI0NsbJ;SzwcTqI#2OZ$d)zD`XugM(Ul~U%yUMK7 zG^E*9lTiE4K^|;@Ew$;bxnOO|=)1MYElr4Fy99^W{-sEid#CTE-hWSj zK?|X$r$N!_sLeW*T^FWk9&ye1F5iC72#>$H8@5)JN0GjGR`P{}g7{(beSr;#J9$r5 zn_ZEF?52dX+gL%tk78oB1ZB#z&%x?7Y*)0tAW0f*e4sAs+3=R;dGnVl(|XNMZ`XM! z&W8v39^@jdAonrPCPw5N>T>0FEK0Q|44A=H-oq~_@fOAjP8xh;A?r4&?$hgnjSH8mpG)6)9VQwSfU8mn4gs`BbcQaD7TMrF$l{jayPf?2p&6v$Pf7^@hW#Ay zh5gqui*D<0`h`LxHoXl~XcjXLT_prpBQv$fm=GL}d1}Mo6bhewX4l|tY3v#y!gJ}} zV|$J20|gT+&;rqjj+p#3qF%Rl)x!Y%-n3(4Ho`4LNMxUotKhjJQx z81Y!ULB@qop#wA8N>X=j{!-y&@L`4pZ}GcJqem1|D-(7I>t1;`;hrxefR&qdOq2sN z(g4xy+me20ALT!Bi#sMkndoY_XMf>q-MKtZ1r+eU*s*kP`<{jHNSL3CC!Ovhh86{} z64<>uV?hx&jyxM9%)<7bc@CB&tzttWJu6b405`YorU55 zczfkYQO7y6(zhcn#g=XFyD&2v5|%bTM0~f+2C>n2f{BAp7_M+!gGE~Vr}~{;8v%dy zdl?@&k9jb5I$ssjXMVe%=*`jSfFkL`@WlaB)2CG2Q}ZJ(lejB8gX73cydrLyb{~*H zBf63yjuaH!$cZ9+>?_m%D#Zs#UBFXr#I7F!*S&s4h}?1k07})X%09D(4!`n!JY}e< z5Q(QClc$im{tZ$h`uonR4Ys>qy;2qRu{m+uN5I%V?uQ+o{)L`Oig?@H=vaz)H!wZ+ z#0=p5xD{C->;)Hn5|h4h+*Ap}v~m6HuuAO})25iFu{MhFjvIgdF`3=Gs@h=W9- z3<^L&U;UJPUQqz(+>CxqMSw4&(5So69Xj&d()qRQaR4+aM7StqNi7Jf1YUmZim=1U z_W`y$ERIJ44gny~PQSbgo7Xhp$6a)A$E!T3x38&-P6t>PlWZyx6zPm-q8QxcAmot8{4*92g_;RPp`B`=K4qNYPOtr?n7)C!bu70@7jsnv~g-aFB4LM?xu#TKMD3fWQ#4)7V>Nafd~*qAn)KFi(|0Sg-jr^29iqQ=A{_ z*33sRRkCPxt#~!5xHA_U!BZnW>^MW_I3r$T?NdVB1Y1S281oGebtjy)yYU7m0hYXp zDpIlUToONM#_}X5x@?4dStO=wCh*utJl9Hk=9(0^VdQ6#fOTIx_c0;GV@PyU(r;uD z=wmd4JtPuaErS`7?kcNys4|k}>g<`o~hLEFcxUsnyuF^@AxjuBm9k zsZEoqNl3D2&@z@8ANOuD`~9?T3&?;gBNfh@d8Czj(v-S;n)0JK^RhSt zF_^iuL14TzYnS zoiZjlNv&c(w_)7A$OA6ddic(5SnoG*2 zN-EAus>n-g_)6=vOB>uu;VGrf&84kVrEO=W9pq(Qd}Te_WqodC11V)g&1LVV%HE%q zjgXgr;wvB1E+2O*pGYa6YA&CdDxW(mUm&ko;;UHEu2^%cSWl_gY_8azs@OfN*e9?2 z##i}6yYk4b@+775thw@Hs`Bcr5}>F;<*x$iRAIPRVWn1qTdHnMSK*#lK`5#T_^XL@ zs!80dNmHxITdFCitEtYbX((#w_-p8OY8c#Wm{Mz4T59f1*RY@0a8lGh;IDn8Q_Cgd zUdxkO%hyu-WV%-HycSAP_msa*RHshdy-qTiR%#;~mTY}w z5w1n+2)uJ0J|3w%k5n_c?`Xf)7b~wFYOI)VcX-psmNb~jqx8BHRsUVm=4>6ZJu)We7^$!1T%Y#_4FBH-Ys*2I!d9?1LTqk;|-~@`cEdkdC1_ zo`)ai8z;`N4Uf@UN=C2jM<9|0(>HlvPKl!K#%aV*Qy+}0o z8tM6|w`U_WqwRo=-Dal?PBP2)%p{Tag)Vn>P8+u361;P?MI0)dQj4@{0^ z(F=X3DqJZ0GBmV=(6Td6)k6L*Tv~TL?Q-0tCIzzfB}~0Mbm-^M0-wL-svSl_%MpSo)0LT0oq9?6kQS4&lFgXT>75{kQl|K3pCUj$?y|c``r$v zjnP=*C}#>z5+a=Prw-#QpTKo#fSD^suafaFmjRuU=N5P1x# zkM2`9E$+H1&S}tk60;{0VoH(5b;N=qlJXTA_f_w}jK1~w2Ar6TttGgey;8{V*sMdA z<#vCVWv#HOGXA%!zn=e+>hFKX2mWMB=!)hQQ~NVzI3x^mYs^mi*AIF&vIDLiGN|ub zHT<(seBGPKF1yGVkK(svg1|}kKf{UT!+Cu224a~WhmuQtG9F6g#55*HesuM6<+Fa-PL^ju^h26W+@rX!+-|WfDk@)M%fje)KQssI1mc|A`uKyu z3#bW$$ux@tPsL2EWMKAwazerq8DuOmM!t!6A0>R_P?`FG+@PK@`ewZ`K=>iZ_uuO8 z)+4snsHy_q0m?_((UxKt@Tqw;Cz%OVUB5V#BkKSJHO~y+nD@@rM}|Y&Fe3HA#ME2b zUeMLqhN=2b940bHo1j5%1KER1#te5hnqVApzt+`r zeY#me{5NYJ)?aHL5;;*cZ276j{Vl=pE7M7oY@9b3ODK`8`(Gv)a+53mMvB-T08B?q z%C#JR_NyV0%f=qhNpv=lm(t8LaB-w1SZ{ZN-`WcS*? zx?lYfJ@;Sw{^iPCcfa~u#f$sD{QZkjpOpV~FVTh6_~n3Mf{J{)W)~ zJNb<05!wG>s zl=|OO0DnH(4uAqs0_c#JaQO8Se|vYYlYjpjMBEhmlfV8M6Dbo#YcQ0?{D1-350$Oq zZ~LJ}9ogKZRNE`Mezfd2XaL_aYNzybL;UH~t! z|4kYQf%V@ff(N!T{(CW`jGYF8WLL|QEKFV5;+SCi;789?0>xsb)yO_)zbV#aRe#}9 zZ#wD&{IyZbMCzwHsL{xO@XKcr^NRmB{S;eVb)YIoBn)z2dQ9>lr$3yUJ8&DTCQmZ< z-`7w76`S^|9o3pMnV%EwCa%qDs9HHn1;KT54~IGRgzH6%m)XY`peO2iVz=+pk7|`H z?%7<6WUqN!@CR(5tRQS1^n@5r&JEu-91KPtO8AS#{t!m)D;-1ouWz%tsrS>|UTuw* zTD7+c@E`BZb>Bf`Qnj?6rj$!d1uK^lud$Ug+>qs@L1F&1`@N;H+}qn5fjIb*>2rpk zl<5oLo=}_O&4@F>*vv@Y-Sy{D&?P4ND3L2oW0)v|MP7^~`-X9>A{F!9SQSAnlQ>ld zvZaKoXzr140{TucYdK9ex+%2kDP3qi4Q;^l)8aLK_m?q~;Pmo|n9PjbgXFInK1XEh znSLbF$fGs`Ur|orgV6OH7#I0QZVXZ@&5tw%GbN_AjmuM@iPFFb@T-lUWm*kA}7?H85IAtJ(-~wyOqqziiYbL^DGG_{|P|)~%+m z(x^Hx$xtFF4W!gPj|tY}xAON{%I>#oe~^<*yuqE5q;G0McKK-+M4id)I3tnb>_Cv0 z*>&B(Y_00PiFZ-egMUl+eiy_{*8UA8b>Mve%T4F`boaSs|J)gtcpFnsqo$ukrmk9&y1eeA?5&+wpX8{Se~kJ2Zi5F8Ov@j) zKEa#%?yX00=IH&5n(t^*zmTnA%Ct6Ow^gr0R&Bj%ThSUuFLYZe!3E;VB@-)WKiL{mS(%_`Zdd&-EBRI!p2P(|MGj7KzmUn ze5?HgDR5SGdwtj}U-shPsu+!Q->d&Xb+OfsWANmll_K-Wx2A`97YA(|)Sll*g*Yzv zKeH+b9L^J#gQg^CC7z<99liyKY@Vr1$BEARV}yraS3F6u-*+IwxOlzF}{@$~XK znc+z`((}#(Y396FrxJWr_NA44O5S6-oA#zNj|lp=5my0F4g^ul-Ltm}@sLC|_wbhN zVQ|;n?|4`SeX_Zz^roUa zT3Uv{I1j)~Iueq2&xk1%YmkPZ+9yHQhy^`~=OEfPx++eZRh;Xs_T1NmhIe<_or~Y< zfBTl$_Rb`O{Yz-z{u*rH#_dd>!FPsS-;>`^no{{b7}oq&nSypI1~@nNag86O-nz%I zh3#e%; zBs3Fc-D5M8RRJryy^l-l?V)GHq(hOys*1=`&1b%&HJI&YoBK$QSvIj`%wa9A7-9Z; zNmBZAMqHE!)o_Wr09ZNT!7GP6-*}LZPruN6_S~qgP4zF$Bav-2C3g7?I$!xT@=)tD z%99r4Z+?@%KMwP$SZ=Jh zssIX+d82svs!p&ZreTkw~x@7xnyu|U%3;pDM&osC>`I>AjkQ1ySfAf z2;-dG?bVFs4Ao%oAqLZkd9l5FHs^HGO@({F`uHAfSo#@`GEKLglr?M(oY&k(J1A_O z?W11bMV+67I!kF0h7Enz3V#tIi1WZWv1+2b0p`OX=nPphhAr(f~F|U%+8x7eS(1w9ewUH5C~eD_KYR_0`-Aov)-H zjYuSi*LQw>ZV>RW4Qp43m<^^A=S;JOzMJ)#Vn*lDx9a6LuiS|*@y^KoGwxIrk!Z{C zKL8AGY-7ddNv+NT;ePM2i5Xv--PULRT0da$-tj4xGzL9Z98Rv99zjDDj9Ip0a2diB zoETwZ8U?4vdv;%VsWpVdb8w8HXn!Y9QAsnqZ*T+^$|f0&RGjl}09i$-H258{yDFz%lx@ML?z2;P;i2sO0%h;G1r zzVLu5q@rEcE^aDk5kbRkOvnj7pQ8iH5Q;}SQPcC2SB_pLwh0!ER#DAO8nSF!y*vaJoZUU&FR zf*;6bbRb~lq1l18A5;oY0(zTpY2%2feuK2RgZ!Y51Hq#R9Fi(xc& zC^dw^enRT;-`vC7=HF1wbHsF{wsK>3lQ(##_@&9cCcTJ{&ww(-4Np&VtWXIa1rgDiq4Ht43k8I^ah`sSU@MY zE|#xqWgh5-vw>?r?tOojD^7H2h)9JGP@k=s73ycn#w-BVsDAKOX^I>2)x{{E2@<>xCIEoCoR`LScqRZSR}p+x z@GMut2ruY4s$mdX2lnb3UMdVQQwHO3dJ#h17IO5hc=T0h$ahJ?YKin!vK$#*@hX!D z`X$T^5pZLiY!?i&u=*?zSP}2a4)5ClShpkUU8D6qE*MjT+3tEI(Oqn-F$-fD2ry(Q zcXaSQ_S!L1P+0Xxw+O{ja^4^blQN5!f@0i!MjgSx0JAs$5*&spX#<4-7Q7J0TY!v& zV~(;>wllK1y%N26!U>OWzM8?&nADw<&^i&Dg9hiD(J%{fOU%2J^Bqe%nU3UGd&aS7xQ&1yVIH(UQ>!E>m{q9B>St; zX7u(GN*rarcS>_zPkkR4Oxc+^kLfK%oCO?4J+6l=zf^0j*A={<`YoSegDj_+*I@pX zAiyNMdd-&_uF1-nUGHchrYR4&DJH5Zkh-Ptx*0&g2A>>nozNTI0Q=)==TUOyN;eU> z)ueG+%AFh0pB?1!`q3z}&|@x9Tq@;jpXHK1%W`?7FNR@EGevarBd<;seCk`kXT)?QN+o+f1N8b>G#k5Zkm+lnaW?PZpfY zQ@EL36v3yvJSq`ARLFk6DDX9ZaEf8jRI$)Oan_K6h`7Ll)XS+cgU2V*T$-6zCVID{ zB~qGi)sSa%q}bmZ(m-mgs`aJ!?w1m5mbUUK#|#ygPf84&2@Zu8$2XS^S-uVcYozg& z+1)K0(|&QdCmrz(N-N>rT6bG}N@R%Lxp(bQC_nTtPeswd>Uih!b;h`*Xdr<&Bg znw;N+s<|pJ#fydfcm4EEszT{zb#;#+GIX6y<|X|>%>#V+jpVvO6s1x1t?I@`!h~+0ZaOO&_mX~=cdtTCqUe8WZU*T4-o?5TgQm;B)k65km zLT^wxuQ$eVQ32-^nN3LX|sAeB9*7t*_Q- zr)U_^Y1L+Jc<0_aMDb>j|ILSUb=ThJsvg5HOm>nZRAn#_HiAY{LJGX26m(S;HTo31 zaIO`f!b=ccu2$bX!TM-`r&R@la%zr)LIZA~07#RRKa(nAX*!|YO)pW&{wS5rUf6Nt zN$ZD=4xAgEH!nJfC_9OtbdscXlD2k^Q_$d+C3Eq#v**1*v&W%autFH)U}xD;GRK`a zMS+8O8ey(F&Jlzk6?aNYnnFt(o4W;Px}mzIc*R~(!NhteGT_L zbs(e&Vi($r9vaauSiUV*m2KYrwpG@+bF9ALm;87MQSpd7MV`$HUng>*W&PCt;mz?r z+Y1w^x%x4U}&i zb>G5U-!{*@txJQ`s5iwt=^B34)yCD0C+>(=9lj$ZK zA0(dOe@PwY5ba9rLvLf~Ch`GYLNQQ$T5b$n6HD-xuA>E>@H8GjaM8Yu+QhvP9p(1! zWV!AEzM4DyN*?^EVxLeR^ZOoZw0{?JO8IcI{oxo9-h+@GJ)8N!=Q$e8Ppb@thsMocTOEJB8Spow=M{x;^*dO;O$DH0AQNTiM+D zO}ekcgbiE-ppUk&I4ETs8kCe!G#fexd6HOw+{@{WHWg; zb;|DbVYWgD*!w#9`-lYJ0&5N{=9yF#A-8dtsNXN%p~|H5TB46!V#rv!*S5s&rTaB+ zp@PlC%PJ*BJSCVSQ++AMgIL7g+-lk5lOdzLP0E6+ zs`@JIDbtegnUiFS_59TkqF-?9bv*r$UQm6t7TnB|-^{`pe?qxIo3p~+&yOK1?=iQ6L-|s!Ew{m|lOSyi z-nKs*8s~<6 z9La^@)-O-NS$5g3Y-OBZRlei2j)7YTzuiK#-#T&r$>luWyv3@u9zUB1Z zI~G2S==i=K2+RV)$EQBa5;}V!dzP{1TMkg; zW@q{voH$00y9jwzYK8NdQrGX>)-MJ=!?19zgbYt;9y|9`Ajlshr0q$xSI~4N8o!@9 zx6PQ^9CffXK+;fUf6&VbA~21YV?#s{bC+VfmkWr?TUOiM2yzR7?gbp`d??1}@vf_d zBLW^bh4pV$Pr=4?@$39|R>PicxiA8qLvw&1`b{d)B*n$2fj4gp`jaXxiH3p^x2@Hb zmc=7)3wVLZlvgBU?#fYJ99wmWy>8&T3jj2Or0&MR#5aw#0wDvm0br0PE8QOeV4~*7 ztWvTCdAj#anx$5y6Ydog)SXpY3YTj(+4O>sHis(pyHjqbs#$B)m`xY3ohOuQ*S%c+ z6mRv|rjrXz;R>BnbKkHl;3itbtse`juaCierY=zjz(5e2L7%LWt?B!80dI`kDa)1N zw`$w&uJ7H~7(!D`72o1>S{>C!Sk>OOO0Bo4Y<;=Rbu(@A#ZpVaIj(-|vHjYRH~&0k zs$ppy2$O{*UGLm!cUFYqh)Vy-`ug&4rbOnIo#SgaHICK^6)vsQGVCiqU48GaORV$U z6%Hr@1hRvo;fPiVpb|fUb%M04dNT|zlq;X&aP%nNaks9vuDKyZ6wU{cpsyA^WLSaF zowC%L^`4QJ$kK!5-c{Y!p|6V+zwNy8@qzo5MK6i6Hd&1%oeuM=f~~ER}T+WbQSN)yS~7|9J3@;q?W6F4YIohjLNMDF<1{+7t_kCG6w_)bU=fqw*Wd zsrzkcxuaWkJUc2cTLf{$9wC&($XH@?ztLI#$dQ@(L`z(U@c-Xp28M7l&UC&u;Px&?brP7!;(+wxh=j9K%G|NI) zOD4oU*@7pZC#J_~bY|6a>AYxs{&Ku}_q=*~vu-n1&f)H(M1hyfqRvkpmSw-F^L>ba zcu&5O*jm$hx~I{=o1>dV^-Y?bx}jh4W1h+9#Nr7H@wn;}l@^Gb_Y6Zh`r!0L(-!&2 z{vjBX&vivGcn4ux_{qlcQdF+UBWNJ6X|h>ClWD5$6;H9o!?mWbQCzAwxLT|qsF=c&Cs${Q!hwiUHhePD8Y&A z?Ps&5ulnm5I&&3ax(O?)eEDsc&!pFa)JJz*+h) z9EPdqJ=i`Bhr(<=N;os!pP;l#*<38EXfAD6r#lf8)ByNWf z<-;4Q$^ywZt77C+EPSIfyf?>=5oXR8#i7);M-oiJFUr|Lq6;X*=1>fh5npU;8W43+ zhh_N(zwx0VClf3m4hLl- z8X73rdf+z2i{(Dh1aiw5Gl~)86I&rGjN^5YzV#?MZSmD7`_v!wOhSW$N`WzPIijn~ zY8KM!37_oO-zt%tG_j5n_mB`scEJX!(BmiQu(2mV(e!{%7W^qn?taj7RgqB8SU2^% zd!I-E8g$I+JYoO=gK{>)0Qxv7Fp6ZC`|f>TrdDP@oU{er&&l#m(j)2X9$)!(R64cB zRpj=TLfKA&+b3^A!NZRRKyivV-ZOMS>AHk4hSbOdkZ+c@y$HabOj17c6wuOK0(Og1 zu#rKkDvHA#1&Z<&t0NANA8p)t;qocI-Bnalw=^4mym8wH#Qp zJPMY5PN$NLw(bw44Zd@$TO%Qab|G*-p`%xIQ`;^*MJ?kCzy=%%(ctLl9w{oy*1}-Z z*{3t`B$bAokVokt7D&TLWT|*vl;3%fSUsnYKur#HGYY*3non%}Ob!uNQ4muT1SGBB zL+yDOgwXQteCKqc0(K%up%XZztg;xlPaC#o5SyO-7?@C3`1pmTuuMWtMm$kg{(EDV z|Btw@46ADE!rgR-NC`^UCKV+lH%fP>(w&Ngf^tI$; zN)Ad)%TqiqkODj?Mm~9wB|RBlLy`<V@3mdnXw+FjxQ1A@dnIRH+1#%pGMzN zjExx8MTLWmfv}q}Q|QQ$^`GbCVi)1K2;#o6Xo?V+YDKjR*Fp6T4^EKvA$^1ZK{2NB z04g+W@N^E7+QAyiHa+L-fG2>pKvV`pV2hN3!(hzf*DRKN6FGaLp~Q}_*$)#;6@qI% ze8qkCnqeN5nGik(R~#asDu=B{PecQz=z6{sPlU$+4{FmCrPANP)@GR)i{Y9p&EVa* z`$Hk%LV%|TSRikK%zj^Lo@0HAQXYEkk^FlX65_0;c(Kw&Nd)#wQbbY|05dw}3_zdt zl$kuxI@O$dR&z&JK3Br+Ww>W~o)GmtxaYSdD*kT;rHoSY`Tjy;@Ew_HuYIt4*m{NQ z59ZM-2=I7Y66S+eLza2~B*x}#irw;oB(1_RXz4b;L+$A* zV_91-&|bIZ>@dudc7dBk&kohfylfH2lI~M42V;MGq0#3|1<6}_l8Ki@C}j`=qqt~&neLE&3iqP>MyV}NktnO{BN&di@V78Wj>u(H;2cdi*rHdW7Br$Ze|~FM~}tT zeh|xhk6a+y$xg?U!lH{@G>4Z8#trKO?2He7hzEtV0GZ;9pFl#@tQ#^4NKZ;sa(+6H zXzcmBARZcA6{v=q@L!q^|H`&eEFN2zU7sk>AhY@%mnql0U$8|-Hy(6@d>ZOQHg;bN zatT?Vt4`W=avto z*Jy^20R-rG%ZL9;+iaiUUm?s0qVyxMC47t+;l&}fI81c)B1jN(NM2CAh+Q@k#S2Vj zfWLyG$Bje%SvKZPiWoFWYdAWA2JYhnStdAFVJK5N&*5T5v|;W_X1v`mljca%RluY< z7ocOGn>3TJl9i#P7BMRtgeXVo_;g3l4gEf$F+`VOJHNZcs^r|k5v zprI?myJSsy1%&*epX8_|0HFgAPw|B9Dd7>9*!&cd$>%`>K`N8vWd7%%A;6%(MY}R_ z2c4Zx{t%6j8YjNZS)>!_x!gEct>G$`rt0*71C7s_;!RgXJN|;isj6 z?CUh5Q23pdp&|m^#GAEy&0`hZkq&W!WM;$BR^-P^{jpRmz2j8x zy28Bfh7v(~@WHJ5TNr1e>sF~x=FP*PIv*#dp30x1rnv;f6n#njr=+ffXNn-0($G;y#mHe#Bh?9qlpV z!9$wWNvdXT$KS9)4)MPhvY!fB0Cc#S(23{4IHM3iO}l zI9D%2-ZKHn`yt5tXTsyWjdEq|a$tbmi~n@u6bn&e@J3cWN3GFFP{V1l2WVf!F4pR~ z9LxWb@G1)?wCr|PC(VW6{v#h7Cq(><*b1oDQFOdg4+aG-r&3H zzd8xiVc0V#NAN@T#n;u{J7`tqhJ!v3W{@ZA>=uA&=!$ZyDAV)DITd6T2$p)clqM5J zUg67IU?Vz6hZItruB?oyjqL&VB!%LkMnTyvuWgfEVnK0rrNxK~Th$+y(k4p@&;P-B zn9lMcuV18psB+J8bmXOk=O-JRDlDXTDd81$SpOYhOp5^XT3!(|ZqQ1H2oR%I30j82 z_9fbwma*oG<%^4=r;9O-{G%(qL#X&x{eidsmiW=)+EybzIZ9CpELPos{f?ct)#Z2h zoO$u>XBd{%jGddE5fGFyD3iY5DY{^x6 zsQe)8y!QPc#8lf&E)1~OP9JhcYtJ;jQX-M=i=Jlzm}e(Mx2ua6pnLdQQ}NqR=RITZ z`+JYBl0w7M6ePa#9F(n&U{By7J}CjTnBh(ZhSA49Gr6BW(ORU?f%G(^gkCROl6bxv z4kv1X!kf$?pykAr+Trxp;%!3-n)sP0tFwd^LjV1>pm;K|qkXXobSMS*WU(P5EdFNF ziz3UkJ+?(GvyBh|aoF@K)+Rz;1miKCGf|yHrf&vD{vMGZc2q5|f7Bx(kS{9{6ZjO- zhT^SL&YA$UrgGu%^2g6+MD_IVxk=`dD@DA7>$<1Ppii~!k1PL`2H`%I0qwOQJT?*R zFgkXG>3|LN+msI~Uf@0oHyRt1X4rVtonh>B!k%d`d4nAiYgDm9^Ju94g<7Qb@V^Pe zXvzDAvJ9aK!?lgdX>W$js=opH7+8{R`ptka zT+G{QINmc`;^f<1-D<)T5cn)44$7OWzRb7C1fhX4Kwdx7;W-=3Js*CY$e3Zq)e9Bt z-}PV;UYO*30f!}-Z~Ra!S3h=N*XxHVKs<&YFTF^Ie&IR)K^#u(e1cS(&-Ena?M3m{ zn9j^%9KGFaY;bI!Dqm7A6l--;XesX_OvX8QmEr-@Z9?( zDNetvCxqcXiuyu~N-;xtA02lwf|5-i4JE^F zY(ngP7v0jJ^jh%rrr>&UAG@QRML#n)#G#Y*{%YO`s$+8LNBMB`tK*P8W8?{<81Ytp ztYIxfy{@u_>tykg;xMkrY4fv6(A!O&%F#)~Cqg}+ve`920ThIgL6AJ26vOK%_0>iV z)Z-I9Mxh-RGI)z!yQ8hdJkS}{VTp?H{+E`sM+h<$3tC{9azwJTN=K)SISuhs@*89e zk+>RruutgE_DF6xib>j68lWLt`rmw~5@85;TUi!1lra(nZp3ECaYGMj#rA}4&<|!h zgG9UH`s1n2sQaIU3c^wbb&>0Zy$Gjx;O4|R^n_3x3NONHxt#28aANqDpW0eb7dCD> zTRGq^%}k2cgP;#&0_6Ros5itujv#`wsl}AF?rhS!;lh=r#z*Ks<{Y7^DErb&gA-j% z5v`}An#r_L7TShy9=p2$`V6i_h?@T}W+?E4-aacyXWW_^0XC!*l z0~t{~oKS{|D17xXO1}Cz^T+e5NMu<5PUS_oRzdgOC1OB$LL*`@QgGDZLye+J1!MVv zaNftrG8)*Knl|a`Wv=q|kQHx1CXAZP4bheuTP$punlNgZ|H7~)zqr;YV9pI4=0@P3b=yz%&QT_Ir&5! zZS#F5bPqS8uD?7D{3^p>4~~SuYM|?DyQ`ecO*~$shI)F4i9$)ev`^;x`EN~C=-^y) zAH}nW(^pOPChE!5RiOwqCf1wBaGefN)j0@;mxmVnURa+nYOhPKka58aa>~ipKoDqt72gyG-rcpL;zYlUPL!nxTQ#dh@;1=EU zp^bMw1%K~$E|Da)CsDw!xG@!1(oqw<&s*f&`HU!s^T7P$sqRoe4@}eylk=wRsB72W-x^B}@mbAm+Wrh?X~@_6aF7rNWtyzudo z#H^;r9x8v|QIuI{cqP&GVcWp}|7X2e`F(N^RdW(RZ^37IJTg0c*R*bl7 zZ47Fe*c~@3@x(g+trz-@6t4Zckf!CHqtJRtp5wM;F@8cRzxdJm*Y}X(5?RfG2ajdn zZ~Rb_{=q#*2B!a)CXd=zO&+gbqp|V&`QDGoQeF&^0B!o@ZXXzQ>+jn1IMf1?t`}() z410(0?s?@IEG`CgKni}362%k#NBMo#%^x}hS91q3oZLv>?B8B_&!(mOm7{42gaCJ9 za^uMwiMt$}WLSkk)KD~x{^lfW9`Wu&t=A|uBwfTC_;cv~Ea8~9@|Rssol)wtoSJyu z8XHv3NI!)->@Fa*hiSbfG1~tKSR`1v3?Cn@?#!I3J13oLj4V4vCPCmb%adMi9})np z7x-*#jUypr85gWf1Z@utOWKCBL zLg8C{=Awlo$Ec$vonvTXjS9{sA+5n<0eXwZG?7-yw$Wz%Q`MT`*7CN~{1u@4)Q&6> zaXxv^w<83M8`iA;uY+% zYZ_Nyi>w!p4?gkGM4hS(K zWWxs50%iq-CV{q5hJDrpt_H0$+>XUEI$rOdpQ@p$;3Nl zcXszaV9#CT%S2Ywy}$o{pXsz!t%dXG&}fOBtCUZHpRe=HwnX;4-Ndu~qfL(_mxD)+ zUlYc3Zj3y`F7cv@HkL+p!(9uvr}Re2u{&i=Sfi<`{UA5sj%Tio$YPx9Qr3!3YVNhC z>D7#5I^cOzat2Z5)dT#*&tCMBF%LGg;}X#mdu8_< zONX7fY4j}4PO*OLScO>sM~nCQVf$=rb`qSy)I2IJ6)(K0kg-g%c=zv<;R`ukPdZNT z<|2e84&i*C05b1xhBXbLgI?z~jtBfa{^EhA0`24NGX8IPpvW6DSIIR$pD8>SZ{b@DG0qDR_gsq4b*?+jk!d^m;EZ;3!t7&fQxYjyNtBaP}B+>!x$P!K)|xZ#5Se--XCm?rv@C zt&jOCpPkVn9P11XyzyD!gY>Y}C!V0p%i7g7eS!br^Qrn)#nHQO8=XnEu+&hHGaLfl zwAA{wub_RMu=K?6?U_tAP3Lz%HWfN@K5lhoV`5fJIMUqQ!0a zHmUt%dXr)}1PbKUVMzUq}IKMqvCSQCaZ&`p;7 zw)1xXDq&${_YW}yqmq4K1)qS=3g|M6#R2j3rx*}#70K3jH=viguAUW$1hC%h-+-k;W84h>4sa8|sP&z%a0*3kpjW!TQmLbun8{tO2D> zT!7sge#WU#5xLF#$3X6)EXn|ZfD`$P=?zWh*Fr$L`G>*AWqAsKRsVgrM%4v$f^OyN zn9orjJ5A_m`6;D&buGl;~*(dEEsM_nOLG5b@V z;#qly=5phnFbp~rtMPPdA7y*uNP|8_Og`X5%vV%Gyl@RUalDB%haUM5u`OwP zB7|h?JR@}%eMg7$G&@!JS{)tK7bk;GPpD~(wq2@nT_jCh4>w%TsdbVQ?}4!VJ^fHN z)|D$(>|*hOaMjNjLd8;-Gi0lMb8h+a&(2TtPFvV6g3PhQo8qtY84V^}N6-!dJ)i1Y z63+OFWS9&_NYM;ID91$*_rk=TcR?mIy&g0A%Pj*yRulm$2lF6{Ul;Mm^y}uqB|nDC zIu19ye;xZD7ZH|tmTK8*Nic!Wqe7BwC@VabR)hR}AD|GLkw^ni4~R(QsnVA8^x!Sj z7ihQAXfdzHYFlngVT&J zA)gEmmJ&8(w6T`VwFCnM|LW47zQl)d<%~6DD{s8g%xzQTnDRDPH`IdWUwNIDI2 z(hg;sUm+kCKsn}sxO`KqykTo|W0b%hR$lm)01mRgwrBPU9EpI~S1%poW$HUkG&trZ zDhwpfRfHb$pwTFJu6IZ&eg^LSpL6z&$ss*&Cm_l7Wo z&P1CNLR~EmWVpdN;nWfSWA9ZM#GmGj@grO2#JlU(AQBnzp%N;^0&6MSr!f7%J^=2` ztEI$eT*4{|FA-}#hP$&0_du-hS840bzAGT`k$$P*X0N>2S)m1*0^tzu&P0S)d;Irz-kFz??L%t35l2%DW2q{ zxQ(B30lgM#naE&d6BAYzZXHquQ)ecBM$HF0`-_}j)1F&tHBoa8(vke{MOnbGK~l99 z8xvOvyxAw_*WK5t=)dn57*v7|2;4}>yanub4VS05DL9d38tPtbJ$ZX2q~r0r-6@dM z$wUg#Mde_RPmIoUIwweL=l6RF2JWTNpZD@nHuU->d<@}TW&I4mLCx{PLG2%>(lU_% zRhj5>9vQ6P8RFD+RYkqQBw5->A{6S?)-2^x`bR|R$&H>Md_<+(^4DsyQg3smVj`)A z%b(17zhtOn?#nn|7oSgK8vozh<%KcWPuf*0*Y#f@p4cY;Qp*c1^bjI-xxd~Fnt#7l z@#BF!!(;j7kDu!=vpY8`F^ zuF&u;G?SoHyi3j_*6wv4TC4Th7*drALy?lx;jhHm|e#ejfmTanvBOn@Z7BM$nzfb`NZofAq zw89b0PJbVcTgO8MbCr@93QcWQ#Z$$?lr+je<|_FK$?I1Re|yD#eu@T$fqyF?eNddxK$r$F_BbyfZ^~JBXb?K-n8#O>7**~|vrs>SrW$>KlQc5V+Gbmad3~=& z9=rIBg@>H;-_#`kjtDGd_B0mddTF+UEAj%1teEGU`zG3WTB3F;zdJH~hl@<&zx0oJ zp7_0hd^PC?7<*V|>iGO_?BT~)5&hBGvpG7}zxR#koFO|aGNnTUHK&kU!AH7zs7UwT z)FXr#{Yckcq08&EWB}Or+jtEC_Q72v`uiC9S7jeg2h;tVD%B5lCb&t)A>Z@y8Z#d3 zU$4OTI#L5Q@V^02}FtNXUKK~J_Ir{5*ksdv-cibwW zu1_i?WIsvY1J5@6X6%#5i}-hAABDzwd*EPjGQ}<*42gHL00aIIg#ZgCZW`n+rtDlG z+Dw;j5YOgvnm;e>p`M@fm|k3f$Y6AOpafC3ZkQ||IKy8~{yueplI{!YPz{_vFBl}H;sSv%1KnxT3@^`8&ksA{ zk6CIy`fn)CSy#{xH!l&l_zNkn?@hzc>aijog8k~d1X=ZU(1oU}RJZAW3u;n7YxY{+ zS}61qTU@=R!7*1~fBy~_BkFTX0*@0i@0;M9&kqrT-t{0blKr@aK=t^mX#m=|-!$zU z_3Fn-jtYX@iI=oS!w?Wvvc0CCjMv`z>tsmpDJ{7s+paKKWK#w|suM zIE7hd{nB(TKGgkW-FWRHm#UJ$!c#9#d*WhJ>v$1L8-zjT(P>r9E~6xpfdBjX(*K2O z=eZ-Bk^jSG`lC807iqpg>v&}#idX$y0Wzr>p8sDV63L!2a94(Onz*f+|A%uOva8zU zbD8POZL($gKD2PEk?I*NiTO6k?>cvyy_hL1o~MYX8qqh3X1bG6Lcg)ycGd7g;Km9s zdA9``NvWlPAlFWZ2bAko-pZ~KvcpQ{-Y*YV3INGa?)!0}Q(U%f)&YyK zGyIeGJD-JGIU59&L;vxu^7q5g$Ykgw7 z(kkuIGOuc=dWIOXf+s$H?!F^Y{N$+)^v?w-@xXxTQfV0gKgfMs=xCJ|05NH^~~K<-u$nSkb@F#(oH8TVqPs zJ)e2s!40rZsqgE_)o~y{ntJNKGbToZgr5WX(k>6j>SR)9Uw`L(Huigg`v1flFI6uO zgAC=#(6;g%;7oWi>Asju<^krEEufBzzh8+?_?JxicVYt3F)iSo43qy;`f>lqljinF z`Wzr>(5!LoVa>~I0{|e2^q8s4=e&NQ>IJ&kuX?lrLVp1yEsxpAGQOu=)X=<g>OTD5Un0l9}*70Jp|a;JiG&kxu#qgny|$_+v78Rmz?9zuobB z%Kg{v!TD`dHleoc#ke;W;WKHcW%7G=Bn0Zsk)OBa`*|UpO8m=4fW7Q@jZ9L4mhXU8 zU~ZW%X8j{O`YF)7OM^c_InKZZ_a>r<-A@o_%aC*9byAw_v7PV8eBA1{OJDRsHM!B@ zl&H#XWej*C{XFUSX(ww)w`M1M?I}hZ@YYbus6Vp^XgR=8O0t4nXFL5WA?(KNIfAWW z)S=x0@;wkcsw9}g~RL)gJ2SUw|o6L zx6Gtc`mLQa(G1p&JbdR5n_{vkxSan&LqMMfmon0#CPyyb4#!3>@!C^RTjEPrPZHi+ zFCwWQyCQy*O(nRWwVXzqgOZ^~jerCIS})RFxIuYKq6YT|(JAGmi3A%f;Zt8tMk0nh_7lB*)bj zf}^2R@Ia7T4)MZaF4y+H8HA+aiS9N^F53|pt;_(+i!295eNyJ@%S#P27qG0u85(%+ zbVxTyd8R8(age-C420`@Fei!Z?wJb7hd!l}=8G(*6aw*FFi-v(8vOPK{}<@}e*y{q ziN(VEBg#-su%SO9<;VMR2Q&++`#m3BCbm_{;{G*I_dL6zCHkKu>RyngT`s>yr|doBm(#^o@;+)yKKW z^FINBguY26Hv%Kp9xr6=g2%r5o2!$K!+8Jkh_&FGoy~YfCbg#IMV;lZqQZy}XNVnM zVrJHtUu!>I*AUo%+Fuq1n*C=|socM6uKpJb;#8W&%Y*D}K&$&BDD5Bq@*SPLf6SZ& z-!6p00~^nQ{ugj7qytp(vgO_w;lJvsfAyD>?!V1_e7S`cOSju0QcS)WWN&0*T-=98 z8|2=3&;L=XJ@>UVuvd&_ni?(=X)GA!tgtBBr=jn60&HL0cAXze=5f0Af?FtwSXATE zap$|!o+U6%F3B#*7pOFX4Qksoz=ig1`_i{zuF9PM%U_=TkIB{-_d$m(>u2m=WT{*b z1c-gfzn==WPM$I%Df@T&?UnDD;Ng~b?`0@t< z@M0CW*%@m&x?CDZX_^Ba(M&&eF?gTS>KwSvN{2~Qj^<+IxU`lMa7uT+?OmS(JIvZ`kXb6%DhA<7Z0rQm73#|*=!02=mk9Na}`(ghCM6? zY>N<2cMN4tS&53WFraT&%bv2uJ*D(AAz>%{2$DmHn(?J(Js9$@C=1o`r#}5cq<3#I zd+r~G;6xd^Kbe&O{ymdk5KrI~@LWoSk+#E1V*mZRNdX7@@b3p(G}Gb&N5*yOVDF@~ z1^tHNt;U&c)FM^8cz#-4_8t)h+=php0r*{-HiugoGATfzlCaFW)R`ucCN8y#Ln9ci zP--gVS8CS(N~6`!Ky4`ZU7k>9?qlK-lXnGxKtuvJutQMJABVO~m=->kN7xy>CCRDV z->PYguPJ#j;;OZ${UGsXOz}dq?={MXz85CyZaBSs&WEFk`JLG*cA8SVc^bn-?Od7W z60<9Ad%A0w<0A!44QJ`uQ&RD-XUooTL~lTAt9D|!{1@Sq;}3V%AYrs}m^W(eV>S?} z7DORV)lG|^-iPrdXdmq@EPv?j?7F+Zx4o6$iB$Wn!Nnt}cuCXogOc~alQZgQPk1zT zI=2_Y)O0!zv+j&0!XHUxr#uuBEk?N^1|5{PB92sr3T9%EHPiI*BF8Y@h^3nY^^TQ$ z;kveS&Ut5zvCh7dH+LHk5=0%E18Gpn%?D+&q0EIzF<0v|RLFwQDY7}#A=Ttn|BfPS z8|hB_RC5#XF+tiz`3@RSXt*}tlLAm=vlU4XzbvQQmORKYxcP`k`SREx2e{HpSM9ZK z>k!LdT<768Nvja<$&c|4Ot@Mz5cji|zO+1=Aq z8bk_c;k>RD8*Y_Gb5p=`W--<1w1g@Bvg+w{rx&GGLEVd|i;X5&o~p8T1AZ|afVL2&rMgx< zLgFwjWjN-J!b+#(iTl7<$5mU514;}>MK<7Ex-f(#uq#v%=be)x8gEHoq59Z{mM=;- zpz=*uY5?bOG-V*qRQ6mj?#C5F^n-*evuh#!q?%Z!y$JY!mm%KnB=odmK~vPu>B&^*9E7XHre@H zs^2}+YdP7MqV$J8lq}OW6Fv@&yi8$C%y%Zv+kx@QS z;mcHkZRu#9IrWqwqcXymJJRknBX3hYY0+qmWwRwNr#63T&Od+JFm^QO+uqSi!w1-P zmc}zo!0NnjGq0%mkiz^{Gd9cmlO_z2zRzuN3g@I5y*>tmEvD?H%C=DR*G05ZlGKWt zL_;N_EZ1@Girz(2EQJhNgx?hyV;~ z#jfJn@m=UJoPPbTz$1dT@)6j;TYI^P+YEdBB?$?8GNwMb9OD#kZq16?@!RiCy{tT= zPKF58JZ2yDB&K>k;uVK_bJnT#tNk2x`2$o}sFu^gkh-JOiv>%A#DST_>+m&?V$AyQ zKPt1}3t3I4Ox#_2oy5oX>iAuFIj{a*<|C0}mZ76nEtepN5%b1^qfM3X zy>AKXMt%JgpO2)~WJshDSu zBlV#Er6>D1qDWpooEY1fK1?@tv0b7eg=4d%I0rsVBnN2k#kT$LqwC?eBe%1Df%*wh zb>UB|K=Q%bWCoy{&dBzhV)6Md+jq4Q-f%!-K@e0-Dl*jVY!SZAcduSi&69spX}Hs7 za zB?Arm7TXvw>!36}{#Fw8xmHi02|kq!JKaMX_ZD)*eGruiW*}2QCR&Er8$6;d(umjd zMEsm@ER}cSrqF3QJHh?d(p&Nc0`RB{z3dcV&I6efEnhC-zi zcrc&A=W>6*6-P1oRa*S&EGJZUc+nF!1QrENT+WlC$YX4Ni64pVt%t)P zt>eVU#R@Z(aO1}nWC);*;mS@aORI?9iA4(g>H*sV3#FrL(x-FA6~KGj z`eyNK587`B6$cne&Jj%+L)!$osx^Jaff|Eo1eXY*aTgaxMd&%&^r+A)s+w? z$9TB1a%tZ7GyJ0%;(}^n;)~E`c4r~ zzcrrnF@Yns_*VHuC&{LHmRfZ9c3*?j#(k3Kdu!T_VRx-;zp*{leUls}j<34IFw>r* z&}g&z;hE}(BArl*QPVxw@hZJF@3E?!c^7?)Tje8;)60`xQkeLXT-7_!P9(tWO@M5B z`E9AcIR~gI^8I-0!_K5cGBMk<3e;5mw|qKzFc6&QR{Yz%z=(ZAhDK;n>+p-bwn&md zX9QKU1JW+_paYp0K%d*DE^2o}sxXRpzH$;J_~JS~$MgfoJL%ful&MrP`imKKLO9pI zDb4uY#)Qsz-xF`r4d7%>*9F$g%X0!NW1;}V7^;f~&M%|<7%W+09LyvpN}gsb`7K)0 z6+pmw;i~Pa8U%Fmj`=a=i*7%T)@q4Pd{Xg*))&4lny|#f-RVkY$5Ckh=$+LVd?fZ)4#`Y(O7okqckD>3i z$UdN{lnLNw`KEARQCrTF)df&7_)0DkMC60mPRBa$nyrE){l@f3o=T{8tvAzw(rdK> zV~I%Wyz+cVx!$KtA%=Zzc~24WB5&1x#$+Sn7Ah`}YmrV9%C+m^-J@ID?LlZFmNyCS z7<31d3mf;G@10*G?qM)tgIew2jtodfR{>ihn#x3Ky4vadAOg14{+e2jt%}+Oz<F7oMiYe#+p`iFUDDR zpe)5(55LfgC7fz85J1>lP;ukJBop&XDHn#Oq>oZihbyr607wR5qJ{JzadmJ896UXR z01~E62Fo54Mo|2=8Y(z5Gt+N1H>$!R*DEgZOcXm%_pmE6U!((B=T&XcGKE6D@?NiW zD?Y;qmVI(MYw(B{HHIT&nJR`%CzvYR-5ocSCPFosD(C&yEUFeu zCN`?J3ec>ow{y*`YIo#&SMz!S#qGSaFT|glPVvz{tEx7y;b%AA<^*L6P;kp0s_w&hYf%}!nGIGecrI_f`|iliyKguq%s2ZvcV0hx z3pr!7=@&eDWHTUwW$|^8ieuyJd)d~#;1UHiV8f^)lD|9r$bN%uXa;9*cT_*@xzeyf zR{q`tg^3-R4}inZ*f{uP=guVkiXq4N^TspbaY1j)&-PLt?}vJ3UQtf%OJ(1u8kAGo zE?9RzF|X} z)Jx32+)!4KuKU(hy5)G(^Q^)7XyrYBV(0;det(KMux&E%0C_qeRXf17*7pb3_Tg|<--Ztej_Xu>^5BPn-H2sRaAuOAP>0P z*95$E#e8g@c#ta2e30%Im(3iE$PO@INaAR2WP0nM^8Q_7o1r+<{U<>PkLFqK-tRk0 zmx%5fx^*Wkr%4<3SxgV(qI)!Fp1Wd(wNSAf8j7x%l7EClu62uRS@>#66ot$r`j1j)~-hKjde^!40G>4$-yE7Y8R< z!ohOCqZr^ve3Fdsv@ArNTOH`2m_~*$C#0eB?qO;m8V;|{!e~g71qCGjDYqXgT1jgC zD?xvXm?Z|l&&L*4J9RUCNqXkKVge3ZWCf3ooJ#jlYR8VL5I9FRnCm?iRa5SUVzOK% zmr?&8HAsg|06`F#gVs{;jD) zJBfl1t!xWEeo^b%8WS8hPo>&!G0LbX8H}%LBP)Bci_*F_lmA$+^7C3HV`lL|jb=Zo|8&y@G)x9c@1+$Na z+#22emJzQeH=ewZm|RgGsjLrVwl0tR_^?IzB{s~KxNaQ$SjBq);~UE-ChX@D9)+tf z3VUO`*h>m3ps?~7*?Gq?bhJVN6=dqgMAZ4IAb*%G^~eX;{9UY+D5PnDp~zEeP{9$o z>Q+9~-Is!A22-VtI{(@&S6)fo*jJmbJW@C~LZyr%R1ZknWhE{MWtNqX|@H!s}_84_< zw?F^Xj?%Rq$Xj8TTeucb8-e%ma#)H?&|T0-kw`By?~%>MP$f0a2B!lJ zPK^qRv-YeVD;!7mez?AE6W&CUqUcwg>)nSLM4|LO6Gz59GQ zrOj?}mCypA)SA|tM%%NIvyG)st{@ybZ8v0+Y;9L`qET&kEE3fOk%4*}34!-aQP;rm z?>Hd*$RWcY8Q@;SQalhKOz-x^CXe!zIvCr9`Y__m%RGa@zSr{tfm$0I`=rch!1fV3 zRXZ-C&`ct9Ie%#qy2S<<@hJ+cQNIAhwihC?4Uj{eaB`IWEy}KO%6h?y$w6_&zf~p~ zTRq4oiU+X^8pT(=@lB4aSXlualNWC+y9i@K{1QibvqnMQU_~em!pX2NNLE?=R_NzD zT<^lvdq!5WG_C1ZJ(EMZa}7bVccXU=PnIbp>lTL@5N~4Tf$q1d)U@#H5hm zGCsgK*%>V=P>;Gu1cfrl65sMhUaWzQxC3P>X|R(CfGeAm&}+254T(d8 zJILfEFp?bLZ`6MD`k{S;_Z^p8X6uVxv~lKldKmK1X?s~Z!Ma`9Y@IM55V{Se*=zKd z&}O*#*NcJQ@Q0-HLclLr>a%Lr?v+R^_1w*oJgyS;YP@W< z8+PXA4-8!<_a;=5-q_WB758UPAtX23|A=0Hw#HG1yCTKZ?EXoLb8-L^Q>&X!k8!du z=%J?dNC+_|;~a~E@|OpM&zN7#MJw=CF9v1Zs_q<>E2v&hR+0X;oaMsIy;j;d#kHO? zp;8K||%g^)ZQCLIGPCmcZw=P}({m(4%9>-N-WR9DMdjk)d zop!$o^*>$7Vxw{Xx?Z@|u)5KD=6vv_Rpz#IuS7V%Xb-7lqc`!)h^)Fm6D(1YtA$#) zX5u2@3JBBnm=ZO-@%J;fOtpZ$V{Hn>14 zZyW?GQ5E4sMedD0H;okY1uzvN^Cq}YGTRxz(bkL-qV}>_2iB4>sp%`Gi_rY73BfQ| zdRQH__Y=tijL+NJ#IE`Jz|CQs?6aqENKq>i^DBw^ASksyTN?3}yFv@}>gBqOTO%SO zUh;OGKu3XgixM8nQryIu72XR%hcB5a$*?1&iPcoIqKS7Po5jkjNT+M z`Sdf^0L%3>g*fFmFUrkA^7RxdqPEwSCX6TP!#Bp*tOgpurMLJZmm0P92swn&;;VL+ z7)}J<(k*-%TMNuG`=n``x*1<_N__@(KhCv=38+@-Gi9?l+TWaOO=4-}J2~3hnfp}O z$bWWrijaLxH5P%aNx|Z|3D8Ojav$vh&h6f>g^o;k(tqx5?QfK^Bcd|&j zR9~vZY+XM_pfL7hDIiSKL&2t+)YELvP7C19#M2C%Bj->IzKbt5AHqX3rfbz0F-&FJ zd`E07?6s5$wE#Tk-lU(jCdy6CSs1ljmK86?GQy3WO=!Yb%f+Dhg?FOnWcX=9Toab5 z?LS6ZE*|JO5`-cfJGlXBCn?@EL}SUH@oMN&gXve7(>;~PjRm#w*!&!3kobAWu)HkRIcl!j3aka7IBt(Q2|!MGb*kl{-;(K@%U*dSMH`#CmZ9&BR(s z=AB+M1H?fZY+gEcvyIZx&D@P5K0lw;ggKau_3{ZKZp(^~TpG+JLN{{KYb6@|_3OU2 zm~GYV8@ACl9QUkk<=~{#-_9f1(u%na$wogo?_8e`AgDPk3ISM#N%%G;yYX_TxHO$b!pzLaW8px@@=DRu3vM*rn8`Ss~V~C zXsZ;9h39hzEf(cg-*u~_ZF+Abe_oDCigtWvcC3?~9)jTG{VAWfya#jpCZ~t6W$&N8 z%}kTIrmWQ3$Z`B_5bMS9Uhn_m?XBaYT)V#SVHmoRR$=H45h+Cn6c`%mQa})CkPemZ z8iwxfPLY;S1O!B+rKLeYQh|9+FfRAC_qFeR-Ou~HAO9Q%#x=)r9>-eix4yqyw@#1W zb9(S%p2XCoe4b<1@~{KgzzDO1I{Y)E)ZnAznmfP_X|f-_<8 z%b=<4AVYf>7=%{f3Qou<#I7-$IJ?Zso-spr6#^!b8 zFmncV-T%77Xn35%7a-I7faXhlmwYaN+#C7YuJr^9WTL<$!J53LMTT!XidSVwe-fPl zKW9=DGfja@&{BQjU!rI6npyB~JxV+fsIUjd+Zz$GrYS_qNb2Q=sG zeA%n%dlSGoi|LNFvpS=A44jL0RQjSQ`kMt5bU*0IL=HAIJ#CyRX-Bd8 zT|4{+vaY?)SxZbc&^)hzF8-zX3o_9eD0y6@OG;Vn&x02~5_=q}p_ z9l=z*CX-!}8BKne?9bNO22x+@qf}IwWCqgTcykere`Ed>C#DP1sH}d(?-lLAYY(Pk zx6gm)BZy)~+p^D<^&=+lgCJlAszIVceR}5P`R&CQQR)h?eU4rvRg~Rjt@j0e`FF8I zOE}64A?(tA=IV)18GX>RiPaDJBiWE#8K(FrG+)xlaFV*1=)Xj&6-7SAl4TNA@1{ss zK^|KKT&2HT5bjZfUM?fSnQU+c`8D8uWeJn+dQC8nJ>W^L3wiCJmAKnF$aFWhd8{<% z@f7Z36MsUG$lh9m=7q_pO%2Ze6)l_){1!gw4*@LN_rTDe2j&Qb4g_X^_IqG}2(^PS z@d!h)w=+6JC@%|M$|nIpwYb+A$b#-N${?@^Qt!NYH`U_NqH#a;u%EdzoFBcodQZu_ zNuR^s1On~MRg5KeWdSi@cbh++sW&3iue_)4JANa}{n-)7Nnm@(IV z(jSRyp-@>6zUB$>k|_pb6bQ(GThLBx!y2v_k>UhIZ4DhcW=qtFMIq>!y`s5QtaKbP zj(E$&+*5TUAH1>eY2{YYDIkE28gYgt>dKe}JLST3!Plx%#V8*Z)zu0BB<^<_4H_G^ zjADTe*9PB#GxRNM8b!ONhIvI>ev#*YMB_4u9@w%I=h67NOaKFPPyi8@gfC!#-Wj}) zX+l;97@$XxUQmIY3IBo_<#Izu@6L9ES_~*|xDHIoAqbgAzkNWmcybGxF$__E8BvJ1 z<%7!%CtG|McnOCE8v#XA_E8d(9ZPs;C?AQPhZ~K6n0lsC=CQylW4V;Gu&R(TbGvEx z+-m{5peh+KyKc5lP4~Bod!CilQOR%RMj0eiO2C#fq%RhD+g&*2GAss%Z|QEpP{_=v z+*wdMdUZDkBHG;BN+${j=C5WM#qFAU?1m8P&cXUoH9y}L?C8LD0RDlnAs{pe9r&x~o0anXTiE%-nuHHP+kIQ0 zH-`l*I;O1yZSn*O+10L5Fg= zeY){s)w!^kl69-dL0Raimj_90RcCEXG`AP!Y0Wj4Y%+Efj78(@%Gn+IUS~6jc)hDX zRQFnG2!e6cgL}pQVW8+-nFrHLq*UN|nb=T`CNI;Qq%4crTKii97d`EZnqQ0Htxs%M zO+?YMepAQ(0Mxzdk03x?fuToY08{CTCUSm${DlgYr_mXa+2KKY6}S3lOXE+IAcY-l zXYk(t2Sot9K69JzDpc#k2$q+xLKx+~4?XH%Hkz6oPAx%0-5@&bd{I5FFCde2|K9!= z5Igu@RVu;oa0^7nbZwu*4Tgl2yMLy&j_I`mwW4Ym`jX9Or(1H4EAz%n7QIF=Ot7BX zHXLlu5IjRs(lyVxeECF|_qzH1x1KMnZ+fI{%55cZS}uU-3_R$c?0@N$p7sP&U_-sI zSkx|y;}H&}!-&G2lzqt*O*6#FAGjEbQ`^?<*x06lIcjQkU&^@`CkK ztf1Nc1dB0T++PfUwaLcn<&HhHM8PXCJXBhT!^Qme0&){w`j`xp(5t@yAj@k0d#S$N zz9cEA(ZOKujZtJrlAqKnsquS1iV2VeDf>z;v*E%@RNFfEs8l+L`sgI6PcFo{& z%0z+%2j}eoL5f79tiHlEX{wS!j+}~34$G%l%x3E)kdGqkm4Zk>08nI}z*yBjJRYAi zWKu+2-tSbj@x0S5k;(a`x2{!T^SJqD{Uoz1xA9=5oK@K>n3K1z2S;tO`QTX(qtDRE z1aCuHH~G)|3$XsM0Sk^mG|B(8{$!cD%pVkak+c4BbXvymlr~q*<#YDWA{5ITeXPg7 zMyKtnS^u{T^FI`!@b1e+FVD0GUf{fMxgTek63Qq?cw_^N`{8k36gXB2hUxlW38B3= zFzg9Ql_`o{A2qOm=3|+&9NGZoY_Bsx+4XCi)1fjaa!Aj*X#EXBB)IQMnb=1hQaImK zquaEH@MA*WJ~2m&wVAb3l>4cT+wKbKlK_1>O4j9#j`_StN_3kpA61a)lv-m>C#Z*p zLY_t~%g@i`Lxx1u+0{Ffo*8ItvzjFchGd8?zJZe4slu|M*67a3+z0Gfu7q?mO+vKWhym@vGzcjN!l~hB4xL+iq5bSfy6BMB)dj%rpAw9e*iIYG#BQDKOwE z-R6=Lt9~p9XPnk`1Gtc}7w8!l*7fV9Ynz@MZQn}kcZTIYH*L>dw`o4! zTq|oj0Uz@kW4De)HiKD1x7wU&-OQ{`2rluplWG=kbx`Rx7NpoIn{I36oPG7{*)8`!m(b2DT5PJWZn}SN{las+*@3#*xZR1B zcD#+=IjL;g$H?2X^Zu&M&fw4^o0FYM&FQ9nzFM@rg9RV`)BPonh~}epo6n7~MC@!o zSW4Eh(bvQ0Wv8b{WuI@M7~hZWwXwj!`=KUS#|iyTwalT|Ot_RU0wX;Q1Th(Gz0h~z zXhQKYJPy8lMr~xiYC;k({mN}w)%0+ys@h012OPMW5IBbLcIxphKOr?kg2!FAFMBW0 ziUws6qnwx9X)BfQaSsub#+ly!KyW2M+BXv~1m4L;^Eeo_MhB|Ozs2oV5wd2YL4&<~4F0XG6zKd{!7+=B=c?~<=M)=Dc zQyv9&i3?UD!qu3VSj}EbYp5XOLbF-e6J9HrAdxV*a78YWHYw^2a@2XXf#EA*WVv7vKCO=Za53kMS$Jghopi{xog* z2coL+qtPZDMFsK}idU0*jXzy$dH>2T@ow0X0PDr~Z~7eTFQj}{W4-ZWt9FKMUv%VHSg{a!TH>DbqpVMK+>-h$B?bH1iG=@JJ5H5@W2a`L6FcHa$k zi%z?EvMj-iI~W?glWnm=ypNkX7)#rcgXzUCr!V_He%K*b@GZNdvusk*zFOX`PX(4w zMAgzM)bo$&%~itc)v`+k@|DHR)sjR%rcb-q9HQ} zSehBq`e%K3!+xYfl#fxkjtVgEH@3tYMXSF8a7KWle?qV}qPr8#5qi z=}q=v4K67V+8k;Pc=}4RIR5cWVgx0pBL0hth3;@}RX}Z8^{6LiI~dcvs5McitG*UNY&djMNfgz)MLW}pQj;&pl24KqUH`s zNt-@^r4jX@hzK>>chwE-U6f1ogy$ZV)FU#IA&vi~0n=3a^(E9Lj~3J^$b3J|6V1eA z#tKryFyoBRb7xW)yf+BgU%{CvZ>t(_(|ACfT%ac9PxJM?=wq?xf*5I7-hfI#!%&}5 zoCRF*TuWgX%SKG5rynJY5JKx3f3~jGAwiICB%HKhArct&kM|>LhR50FZwSanpa%*K z@REI0>#;<)nl*}%F*IY0e-vJjd(X7?g-L>0WkGKARHP8Gog_|c91IP+V+wXvYC#U9 z%H)vhW+Irt6csA^B0nowO4KmX;cIUC1D*RE2r-*I<5*ru&HGod=HshT1^6Gn^vLVs z4!s1?d_}223j^Mb$Cu<~76J#tgI7fb&6o|NWgWP>MHSU6^#(cJ^jICRg=2dqMb+{P z%*Rqzk$? z9NLIf#T+xm-!t2kRqjk&8{zl3M^&^XQoHu(eQ@#q2u;Ao{&32$6#v8{AF+dp`}0=L zQ_ctFDMIbqSc>o3UYB$f%mlJ-B6G7Mk%)P)_)X7+Xd*S&h1f^oM~hJwQzA=o9z1T# z8JyN`IsJqVhbzU;PX`9|YF59lSGTZ$2+~e z&)wz-g?LYPo1~S*)cZYRnr=_%e?B>w3E(|FT!^zdJz6e%`1I>K*0XVdLCA|b-W{<) zog6Nep-zv9I$Tg7{B#f&wlJ86kMqX_<#|?t1KjEu(0GAOd;q-sSLOHep;iqtx(B^K zt5U~@pABTZ_9;>?AqEY4B7e-6cX&J(Ev^0m8F1QNipn4O2Uc9#z85hTZ}il1t7TsQ z_=ClV9tuoQ3K>r}|3VGXI@^i=K5zWT**45$XTXXp|C6=s+xo>@IOqn?e`h;BA0AZo zD%w@}4T$q|f>LxeZde=ZdzO1n!NUQ0gDB5qvGtd+IA(ne?fk>EilvLqchOj{%VXva z5AJ*C^7+?DL9DMmKc-czaR8T|y8$KV)_}j+qj;B<0E`8~@Yd#r30mnHH!u!7p0?#osFajO&m%|~y`Z2rk$0luwzxyLz zmW^IMCnWv!h@oj@K4-%Hi8_H3k@-tW{%1JjzYs3p7sQ*wuyeLf;Kt>lP(WQ(pM2}g zAJIW0Irlr&Lqh}Iz=A*lQM=|ZQ~&#@UO51u6ahe#AnfZP)L**_KDYw~PA}s+>mQa( zA}UbHC?=v)*(2f{aSw7Cb$sme^!$ABU;~Ti6Nnr5eVu<5H`!#iEy{n7+hA5_@I|HA z?{TC5d`9bFk&5|a+=kL%XlIJUbCwXPOk?Tz|HB{+GUzM#-^9 z<2~PLC>YbY3ST)_a+8z-6ie!@z84<;zAE(B6&s)`^k2OIIV;HiSMT^=ekxM5auD@- zb&CjuLZgBcd$xL`6EPhB0vG|Gg8>--4?6!DdXUGDpTWMsaU&3s(H1~JDUqx-KrbFb z#>{g3BQ^e;Pk&yz3I_^TG{B;mKPz3qe-se!nA&FC4rrmdX&gT=1q%T)D<&WEKJfIQ z5fVLq6p`H(wr_b7Wzf&q6~%~V$sR;vBB5e@%8cDwNnW5)0&rs<+RxmAf**~yQ<3Jt zVy2H-6`R7fbd?davjm6Dc;!U7hzVYF;w6rB>84BO@L%V5Ugq zolnxp+UCM&gztHY{=|}UG*>dj-eZHAvwTCm2MY_2pqyET(?{d-1H#t27~cxIx0u-S zHN|8&m#_J2m;z(UeyJ1`AsLdL-)><-(QK!1!^+*Dr%)YsQ>gg!PL z-qDSWf}>dxxth)o(2ZBdfnZz11z87usd_UzD=jdKembQs=RF8|X;!%WO*e%F6cYOm zs_6x+0af?hMt)Hryo(M;z--IN>*yTvnZ53VaXAi@Oc9qyFPf9$LnTSc`Rn|A$C4$Jz+Js#C^*|xfS!5=06NZD6ZaQ~v$ z3iG?*N0N5KF%}!6gW(XB=usx4j4?Z->lCuHh#1Yb&Scs5GB{Hpgcr4mP850WL(9O5 zIu-+^RFU8P&J=EH6GwScn6urzQ~P79oZlP@fO_N-i2o1YF*@qsWw=yVagTGhq0&Bd zc>YYnb_Q?4XjQ${*pbXKaV&&pZ8+q`kfhqJY}XwUIaKUrU-H9?UDgL%qvv<`(1 z*)74ES>_+jw--QVu!8+d(EY;Elm}L#_vC5;8Lst2+fznYd=i})kDoTwJr1;j6Dao$m>7A>2dSQ+*s=_W)R@##K5J#y9?s7C^c9+&2zwBnJm5+^!zz>vM;$YDBI^{pnA#J38`kx<`v zY(`{guUtkH93zDS|sa5-Lny)0W&ccP3)gRm>j7DgY?` zID>k)QM^Dc<6;7OXvIVEj(0-JtYZYqfEWmF3~)(snb4AqNXO<85~u8@kv^Ef$k9_4 z8cI&Kk0PKT$creDxXjj~KWx2jaT>NB9ht{{`ow`qD-_o__m(PKMmFpczB1GwYaA7o zUW_+LQ{<~ZhMQ4}y_2|B+&WCNUIH}kEzRq^>js2RM;H2lg~B9RfF-Gm009Lc-MH%Q z+T5c16u8TEbFm?8FP0K5*zA{SzQ$H=5}FN5t=3xDG#%y^*)$$8_~v99le$i}KC^RO zY|*E+aF= zj@R;E8X4366x1;~ z6uACRkt~aNZ35SSly5y*ZL;FpYR$oBgLv(6lqVU=ljqy#F2=Gbcslx(CvT05Qjd4v zL^0eTb~*JCW-lRDJUJ+ti0;UCQA`#cTlP`9@Ojm!<1Tm}o$twZ!CLi`Z-;9HUk}m6 zZaJM&8q$I2`6&lvpg8WL2K%ATKo5V*3trKC%7SqV*V>zr&^H}3%dXzz(w67tOnpot zcw64O5;zHZo3zUyVu7#Jm+uCysy8dz+*p=Bx+#`tJ$XB=P6x|n{`V|~Oar)IM3g;m z%4fcNwoRm4-A1utDoI*v(8#r|9HgZesAEUj$PG7S((KKoVw}rIn_N+ZU&^8hc@-T% z&*N+n%BVERCM^+9H?MSDOMJwRgYdviVuXxziSW*#GcKUwO4r;h!Pr_O)4wq9ZViK^GvfpVJ?EJ8n~k-8(EceJHRy1|FvNC(!a?t_qWuL5 zi7($eR-xBJG$zZ(CeAnO<1c=pS5H|2If&j-XiY`UcONIHf`O|gjo(HeTfMO+ zsz|xNw0pZfC9S1Ja=+q;HC@_RgzUH5eK`<5+w<@Re!un3fZYG=y!;opd$}pOfAjhI zuTdu7Z>g9kIkhE{Ug)#+DLu-Yt)8HNb+`&aK7ctT*B?$4;PRyxI6(Uc?5+7Ed>{iB z02TQOXBC=~{SP0G+ym{h`8&pQDcChLhqL^P=r?-g*K&4%zND{6(DR;CJB4(8jD~NY zOA+v)inMFEy5Z@8TBhi=K$OXVbbD7FSDX#TYkdq^;7~r9885#J5uv^DGxJ?YRSnuh zVf$Vt9N2Y=b#3DYFPUuoa=+(}61_Q$Ulk-wc+R`ERg$8$uin)n@s%ygpMMTE(TS5rSojn#PS^8Ep>(PIEVZft7;t> z5x2xSl>AT(-~pKhtv&>+O*XiEA+0`8!qu#`+VjT0fhdQygNZqB){Pp>dq?0%@$}YJ z8ucKqBqeicUj5|tp`Tb9*}q6)k34E!NuBS){MDm8#fG z>WK{prPzF)U;lDJI*e|yW$X)%F|F>`yTe0XE%f;Y-YeWL`abwKM`L~P6{!sUFeL)h zeW`Wo=>0GGW6uSW34Tg-M8h`Fl)$ckJ`+OK2J~YnOZOrm=(B8IWMBhdlF&Aj~8TO(B@!dyTzKn_W)Z;NRb*F+|kSrxsTGyEUtbgTvSqHo?jHu;Iv#6_(lUXb*b)JZpdc+ zQmqA`l6t9Y-MHIlVdMXF|1bo$YrA6IbciWm+6vwIqKNFn)GhJq79hb?!x!FQTaw|XAcm`l_z&p)4k^6@8(aF*XFF~)4Tds^uV&J z|HcIS01Mb^Hv2{QW^uK%mE?7U0cGBkFGGHUvW0o-Hs;rcBkZ1D%fp=If-%)ptL(!z z>94#RHgF~|&qgo!us>osQnL3kP4?B0A=V};MQhpqU9oJfBXO#&Vm*aVis#8z$C4}2@&lUa`6o+$PkEmm zTnPUxb~Kw6adNaCM^t^Z`8=)pc<>eu>Uetz7=u|`o4$pbU?eZbgtz7pmkPvx)dLgN z!Ct<#_QJM=LeLIcF-3`;E;JfIIN8Lp%@H;@5JT*%%P)z{5#ChQ1~@XyFVBT@__On5 z@pV*oTmJ0p>G=2Z+ew;j0|a~N54TpOJC>;<-6ZeKkp!?-7qf2%$qOW$e8p@7<(3Bv zRL`MRP>FM^Jodi_oWJdGDV{`<&_|67G$Z-11g#^(Y#in(KP`8PhF=ML+&h11&-68a z+v5n&^?7PMc$Y*ot6-o2_AV@{%bQCD8nJ$t@qk}OilY*V=*VW`eIp}n&W}t#v$Bzq zQPCNU%I!7g5DMznh#ic{dy>OtBqMiwd?&W9H;2dhO%EWPi)+Qt(J!n!p&ooaiLh=k0%$HlIT7fO zv+!IkmNaZH8o#P2#xD z?_d_0ccvDcBl|~=;Z7W$=gcuq0meVTU;h#TFI?V#=DG6&ah*{A_Io+$Whp*Ti)?%M zqYSt9lO**!PychRsPLrS_RQ~mqPTB|CcSG{D@KN_#TpJarW<^40HDK@z7^A7LM0$N zxPWNfAC2vAqa*n}I={4(e+S54dZQ1%iVIr(ZXnEKnR9L+Yy@Ve`H(;0t%+lDx$fHX z%TjP_@QLj3j8@gdirf$Nu@<_>N1U(J**@ui0M5SE6gG_fk4-?;+8-ANyXWPEA_O>F z+j52I-%Qlj>i{hR;{|NcgG1hjz3I1Yd@t?UziiIr^;Qt8D{Aq{%4CV>hQ2f$uCu>- z2lxXp9Hb*2T_45lYNj?bHUa?=-d-BOV1<+Jr|o&P$V*T6HRVSu7()=@qyxcZ?>Cp< zFOhK=M%|ln0;~*6nwy`-1)!`*JOK1?+y-Cg&@&XdDUcvzL#HX8(`SG5B9<~8xV7_` zS>Kz~1OT0A))?WjQ(3dk1>&4MPzq%FfySK+xk!sOA1W|xIv*zdmjs)j36~AFpME6_ z_kPJm&KGbz=-L0E>;EslBGn~8TL?M5aLAeEnIZPQ9tzXVPCiFJ$z|UvIinY^-N`z$ zl<85&Rmm_0EM-DegPYR9{N4}G810d;-pnST1f(Aff`CT(pU;f71YWp!qnLbCyh)l| zE|qI*YR>0w4GRgJ3h=8+|I7kij@YCq&QSeU6S{Tv!@Fd>qErQUc1tfAQl>EmWv7kl zRtuI$;)A@i1*{KHKIGL@lyz$=a~kU%qZ>BH#*0tt4?Z&}y^j3!v0Lcy%QAVrHFJ6l znRoNsytL0LUscgsvf;LukN8heGh76dBY*|Cu+w)Gnirv>DZLBE{d@og z{@3(k0HrDWD)q^g;pM2`z9Kz!_>j27ob*B@CV2r95`!CP=|M!sn4-~TaEz6HJU;=6 zA8^-3iwE(7E}w6tvjSy#y0{mLkmbf70h+`p?qk1-2Swpf93F^>igAZ8Q8mX!vuEnbgoA`=nfDir##^mvC_w39I+-e1u}xjObb58qR)Pt} z1wBhZq{Py(&`#5NFAk#D9~*<_4G^j*85vS-+`F&hF!q_6g5*j0(R3os)emOmy`MAQ zjI|@TL;A|AUQm1SMx#hSiRn_=gsKZD@0C?eRg7_n{p1}hg__sb`3BZh)#V60lCNJ= zN!Zt^8GLr-`-AvgeFy=h!ptCAAVLS6|ceJgK z^tx?yDxo#_pcjI}bVI#cpj9ppD}dBjYbd?MgA@$)ORVA?1;ps^QC~Zb*HtPImdKqb zrZ))Hmq>;v-_RzFY@I8e6L&2X8*W^c#T{6kX2B`B|H?QqDjKG%MC8ou@;F4UOkQl9 zrf!^~_noRPoyHBF+0}6p#vhHqzp3Z{w{40a{nc<_yh-4EgZ=2QdhZj`So$dg7Zjok z66Z*+AQX?e@3PI0HWMHrhJz^c;(Y@L8NL6-TBGnF=*8Zq?F+k1fQccZmaFI^jmL8G z=Io@p7ANrs!%>MK^j1=`>xg1ll_62)y`tI@@miaYf}wKGrT5B!lM1kMvC%Ie@<<>L zbpX&{fiaoaMipmor9$W~M(ZIer+eaXjLs~U&WMl^#&uiJ74JOBpUzr;^v*l)DH_#S zlG`o#yt1d&NRCf8S?b9UqB~4>b69)N$~axxGB2C9pcrZL|8LTBSmI?I{9g28NA5u%0p*$73Nm7G`;ot4~Zr{ERt z{Yj$;-mu`Wa$=g8@f^9ym8*c@q8l~JQCvDKyH--Q_?08iaC@aFt@V_{vb=-P!m^@k zE@-jRioa*E%1mO-vU*6-!m29YKQK*9@&1df=lXzPvuYs~CpUIPR(G>*wYG;R=Jl(j z^~N0uVK$G0!6KWcZ~MBLCH3IOwN@}?DCbM8inNC2|)8NQ= z-3iIpDe0Hd;ddjromt5|Def$yuD3GT@s5tdyxPUeqMvedaAt&Hjl0Z++$^2XLTV}= zeF`?BeX$s7zgf40a87-}ZH3=4Af`n$KuYXociCPiD&W+0vD)VTx9CemYPIPceb(PT zXQF?0-|8T;Xg_pI zq=m-XMc<(iZj{z;FfHIB{^@0((WPSpOtE-kQvY&as6Ym;YF8Uct*sBILk9l0;b3;l z2O#74RuJ5)hONBq(am`hVpJ_uf~vXPM|ziP;U*gbLTv0Tb0_0-G}Ud!KH?xvE(VH{ zu1;?22yX*lgH#=Q46k%wd>k}7aRijfEAZU|B3C1-i%g}cz0cvxcm}lFE`p>Fdnik7 zk)2z^B&FJxvLEdtp$CE0FR43%tQV;0_DrRvq|CzYdYM>OKEVS_ccL`f(%CA6Wl3UH zg7f5=*)`2%H8KZd3N3TE^hJ8K26tj>dzrbMwdL;jvGOzzJ>(4t>M@|PkH6SM$rkrQ z#zZkc3PRrw8ZYO5^Z+Rp-Mh&2+)T#GDJm((_uWi(K%#geLDI~wiSURYlSO@1!qyXI zqi!t(U6Z}%Ky}2;Z2&JYw64muaFhotljyI zCe_<~DcANYZ-;0o-DNo3-3bx7S)R>yEl@@?Q6-|5ESs0yOkSpNFd?-%SJ=@^(Xd`M zfx`F^Cfcf$tLRW>Y7Q6t1TGOP8=vE!Q(%^%qL#L*ma7p{s2XFgo?-r>*p9qNx2aGg z&wQvdaj)1^p-5+>d$_i~ri2>jw{AWQC>&&t#`pVU+vltld44Y<^bk+3+oJndH{Vb9 zCJ)4$#PgT7O$zAgYB;!(n20A)Js$iHE+upPlaUQDmHJ0*+jl9*|FWC^M_J4tr67Nm ze)-VV3c>QX=DW5@h3Xm&?7jQ3q$q`-!uHm%Dz5gYHh%YsB4wReH8|RCPMU}+IMv*H z-SI0A12o|{AY~92*#57>^cU_FLZ^8DpOLZux1xvtI!yn-i0N<0*nh=$67Od^%6S`xISl$xputGM!jV_W{K-f$9*ER2@-u@n>+-Y02tD&c zqrm1XDRGMl1?lllg#~%Z&p6EUvkA%a3z9N%Ig*RrG(G_af~bEZW3R52wPJFfkpL~$ zE9!Q%X)>xX*^8t3fs%wgIQx(N4qXCX}7Ucu@=S4U3nR43~=9%K0sA+lWwETOA~-dO4kdFdRVf zJnG$kO&bup-E}z%zw!+O-Q?qTj@#=yZQSk0{5@Bt<*Ryyr;DrJ-tcL>nt{&9xjS%& zQmnc`o#9^5t#%y?0L3G%z-6uiU-AVBFqAx4fYlR_%CT z>SIR<`#t5SUTzbIsNwzFL=+^x9J_|3DX%(A?!Gm=xu)IqOi+?tq9XWiF9XGMmrkBn zp~3fy6DTg5v}(wwLt6l9K(up(s7$1WVQ&ICb1s(`Vmrj1jFEC%SnB5H-3UUT`(LMo z;0M&C&jNa<#9nm-pPEVBwYfNRL@XoY@gY+Bb}Y=cb~;3wx*I34^1(i= zl?5{$gr*p1gdqn5OKNu`?+xC~E6(9Dd((qUDF1Y&d*QH=S$?O2C%%ixgg>I7*M$E| zLN7( z-TLg~4+L^WKeMA6bUR5xpB+D<{WK~K!`w~Byq3?M3q?TS8RR4?65>eP3UZw4bjS(g zOKY>jmuLbR)J^$Pw`f#iaF9`n>)EoZ-Gkzo?8qGVPZLuz($N$PPGB_#JYL^|Z zNc@nxDO#k{)2&eQ#( zkz1&{?31N^3oRC7#v6O1Q(GDTwAkd6%-CDe*s8caOR=kXY*$6N=3FF_U( zhYq^l*6==!3N_vqOlaKW=2r)U|J9(R1Sx@N!8ZTwxRU~WIb|X2|FP^?ESzPa&NAdOJU3wV;uG|>;lIZ21+V7$0w^PsE4E{HIWseGgG8{P*Yvd?F(_4!A> z6>g0vpqE)d$_xH1I|BAF=X~W~?vej{BZz2foR#cozzF?^-AL(PKQH4d#c%y{D!?}2 z1=#kVtpH%=fpQS{&ljGfe;{o8|M6bv?`rcOY;Mo(xPHo|&;3I!fWq_ld*Q+V{R;S- zs^)Pdcs}$6nm7qaU@=fxL3E#r0uViY_YY-Khml4vz~pd;79y3Uei}Ud?jQP3SAfo3 zl=m|k(~Llt!sSeWu>H#lgyx>YzE&YHUEs93l9%q!VV-IgDr=k@AoatA6dgo-Hjt|b zB1X46UkmhqDV_gaDeZIpADMkH96v(z!*1Rn^&d)5nEYE^mW}5UPj>g@`h01qoTdbq&CbFy{0}&z`0qce&kqm`^e91v0y94&BXe1 zMFTX6?1lM?tot)}L^J00MUrB4wCgdg3lx@Hk}U`%h#2S0U|a@-fUqBlNlJm5ZPg6& zF(JgQATU0kFPfA9s1n3R#OH}7>5{zDE%hXSK9jhH0gaf{#;~6ot$Yrs^nhB+Nwd@} z`zc7!p_12IqP<&~)8;giVPLa&nmfHdkUg7on-g25Q`r z{pQ$D0ry>s2X{JCU z6q|O_o63PuKfAnE-*(m#9O?PtnBGevnjX6rmQ*X~pD$5REJ&byk3?R>lc78hgl^F0 zrtF_gd<6u@bnW9s>3Mu7w?Bxat6>^^%p>&Vccl-+h8bgj zIW{aq4{xW#(!=7UZw-Qswoyd+yca9RVkLyWr1J$7ieK#`aG>IH&$n`ttSh|qS-!;C zdwZVr3cdY;vp@lZFNhP?;oKvDxCTA(1H;j7Y0OmyQxtcxWE1y>WJe*km_|B5 zO>o6wi8NTGC@Fmd5(chnV>C!P1d|xe*pHvOTUpAJfeI9GM~g^8K_-ok-jJ4q zZHIm}7%h^D0W@leV6S~Aq8d*FA{|h~HXv{V#Y>=#Nl7i)8b)06lcjlA*PjP8;<0fU zxnrq4Yd+G0Fvwy-S;GG=SII=ryX_p5RcTW1zfw<{>1dtQ8xhe57_ zC!@U0xSfif$9_y24jn2uf|jf1jiQ6bpAh!%@4sc9k^tTOVhXl4znq`oi!WmvEyZUs zNs8XB(8y)Nv{QwHQAdPCBQBEUaQ&#HYW+nALrd+L+ z(}rH8%e~s<7arbqu%ZX)&d`cDo6Iuf8iQqp^{Fnj25D3q;V&FYQcJCxYqmeGtzo$W znVgO0MtHd=vCXO0fy@mi!uVAKLD%)(g=@&0*`jxmDqBk5YMMx8ce^&o=%{rEf<87LqHAJ#3AJB)bg zSh|Yy&UHUnvg`@g1IH+DUPwc*5GU~s1KLWm)mUGR<2C{{bWg(^TRa}$WOFW*Bm58+ zI*RS^<$CET9Y}VWitv)g0%){NOy!#<6zUXG+of)?@zO5m=_^lLmcTt1yqoq|&QKR8 z?2=)Hy@FI{20_`_VaK5rD5e>sW*fYYzmnT8P(5)$({=}B=ypL5*BMq$Wfm}$TqR=3olUqK8%TMo zFu0S;;szt6K^nv@1KpJ$t1JaHiAY+PI`(2BnqFet9F8~SHEQ-#D6EiwIy;$BB?o}-x0T&;^cpu?9AJI{t8;3qOseFZ&ai1f+xemQ~Tzq9sedXhQ6#{*) zjC$W?^HyCJQ>XId>+;q#^-~=6gCF|IE&CZ_`ztMr(YpAX#`~Ms`TJyhU43Vpp-Ef} z_E^&luyY}{rwTZH=`TF%|Ku>B;I7w5q?0y%;Ls<>K$pPaeDR=V_vX+{R5Y6a&~vAqR9fsk;wj09u649=qpsT2;W)(WY0 z38{+@sjmxZ91Uqc3~8kbZ4(ad&2^$(DfRc!A^^L-HIU>xB_~B2fa`QG%{f!l;BO(HBuS#-eT>MZu_} zB}Ag{Xh%!AM#B@LWnV6ey7_Sa&PbB*;=kQYObzhT>zU3PRC-DJp(s1vvjaE4cBGvI5+n zV==%SVDwyg?kRNA;#Y>qu}kOcalge4qo?Lior4;*@0gT^{non-Ptfts=O_K~?_d6I z0jNU_`!3wNvhm=o;rl4Ya2|Xre^w(1y^wYPZT+>S0Xyb~vw>QxZ2YOW{%4kF)BMut zbc&62k3$P1fDCbx*`~SD;-(E?N$ObpUhH%=KBXMFHq-tdm3otWz9i`*Aj|c5;^h>u zH`b(tev0X z*Er@KLn0XoR^z-FYx=Teey=n;SuqmSq=U~iy*p2;B)!?5Q;zA^T zPW}Q6#&A|65Un=)gSpn&J0#d^^{RpY$&z%le!X^WvtjEM=jX=V zVT;dAhl@p@n~(R`Y)WvCIk#FNl$KjBv000^+VF+e%Nr)d*2_alH7&QZ$!;ZVcWOxK zAznkgZXmkAk@#M3*yy4w#W_8ScY3(m0d}Q8zomT_|GZvRpHM{d)z?E-HxL705(2Mx zaJuMfaXHE%0dXawlHDPB)s5;8%0}FdAN2G;Iu7fjbMKEDzczLlGj(@*G;aBPV}HW- zHTS`!!&RA=JX&`s+$OX&P&dvgkq!%@R|K@rDWH}dD<1fBBK>PB0cTn%}H|@($FZ1tHpg)W{{yc1Q zkp>QoME_47n|~f9S6H~PQB9|Om%>Dl~@<^ui?bzk8ZWxwV<4Bg$`jf5hC zNOy_~2r41c4FaOlodeP$CEZ9PE!~2WlG5EJFz*d04?b~p&z{}SzJJ2Z@4B!22Kjp$ z2l@L?^gNMS#45APZ6+Jz#0u}yR1_Iy#i9Med3S4R{M?k)&xvH9{pE*L#2+8xKhSf8FKiZ=Y+-l#99Uj(Agr>sve+bPBj9M0O&R)}c8CJyEQFF*r1AkICCz{e9o16weDeJUjMk&2O9l z`>xC8wg&9A2?_;*Oggu7sVKlX$aV;c#U%7G-LojMpkPSij@xHlTFMtR~%W(x8`(2 zV4rbb7aa9BM>r4 zQjc7bs(E`{k$>%njK%3Q<;PYs4}gIGmqX@H>+;`dhRXho4=~Y%rtdH1qf-kn7X*_} z6P-0fw>Jb?SBgHVnye^%_#)0`-=@}8i5Dz z8X3H^H(MChmN%Qejj?WZTpcjo>Lkn=f#j1d$V0j_VP2XGpVJf1_Wkbwu!|}9m-~M5 z)s|o8zsD8s!dcqgv47-0@)Fq}nr%Qhv{W150_Q!Ti+t^Wqqg|4^G2 z?au@_+u5=m)@qs{TVp8)CPvdARya%)j~q^~e>-3*z8ghG<wbFuqhJ0m5A#f;6r5;p2Xyv3OF%GR+W&kEF_JhZYd_pUYD%u|Q zT~p~?skM9q=}Z}c{h4+;z+(+Lp_%8n=zCZiQW5<%0O~`QNDe@KcxVIx{FMy>>O(uh zj9~Juk+vCQ-Uat^t>&am5 zgzLGM$7PIHme%<9GuO4XGgTy@>|-{eqm{8v0=l0{*Ajj@dc&^F9C@E1nEg*sRxE87 zTvN4D8Q6P@^!ou%`&-Lv+ABk4HcMk>VdOyA+gDe&^6e{jp?J4{GN}Y|c+Xq8_)B5` z+;n#A0^{}7;;mM9_3>@E+gR_cfgJwwwZ`g?F7E$y*#CD2TAhm=?l>r$TPf)wdy%t&5HZv#=M47vmA0c-wV=OE=< z@*8Uu6im>iHOlYL4%NqudvjIaJBKUxD=xISo=Z`ekmy~4TEy8SmA(f$2Pt?&=i3M` zuq{c0k`+>e=Gy?1zjX9mr|`u|GNM989iZxQ2JZVbOr9vZ_xzhhHXJL?@}!X7gXt zhyI5;hsS0P6k%zmj>Eul)n!#$OT-=L?!2%!N*EKIKQGDYp?x^XGxQIr#ZSprD=aQ^ zF*Cbl(fHAG0zo`hkwT2SS;D2&KQ)_Y$inYY_nZaXCAoz2yjOMPP4S>Cokq!*&@kiD zYnR8D&!D>?8L;{JX@wY09pQ-zvu;ga1OE6kgA2S8cy#1aJo5 z8qmi<-fS;%Jbr9o)Rb)Z%7xhJa9r`$Y|bXC4E%Ax_L2Ga`qw^rjt#+fIKEdc->1=E z<*~$v%VzUG`!A&bpYBEPn7d`hUmi_VfN*#Y*7#*OoUfH&5k(yTYt!ss%Gzm>2E-=L z#QuIBO*W4h0e<2sh4gfq)heK&hQlz8_&k0pXPxqm2h@!WI0{rV-bi`f28!4H1#(WUq)E;_S2f13mD zXotsLwD6LzseXtXBIHng7dLFowEg+f34U5(Ts->e3Imu&9jHd?fk!XVm<+p*3~1=* zF0fb(v_|m|s`grj&br#$qU7)U>sNKB--)kc>_wA(4(qDt(RnyE?^?5*K4!K{*$axr zMrbLgnm6)9aqIosNtVU#kqp;w%&)Dzk(iB!(H%WKqvJk~cnCFDJTY3x5_R-S^P$pt zUW(k-ZeJ0noqAxtgc|Dt%%eVXXm{V}gQP#9h~7R*n{Xq=<|HP>s%*wF#R^F4;h*A4 zPgI=y|0f3|4N;4vP1z}Df(uYwv+^T^FM64uR~VP8ivL&Fu0Jj3>!Y<;E^bF&U6O$Vzec+ z>Ws#s0;=bVnQC5A8Wco)s@nIF3@CZ`+s^i4CKS@&!lX}ySQZ1nUAf|ZN=B#X2siJm z@i<*_I6PK%y)#NAfshv<7ysznnDCMf_HJByY$Djb{;3!=O1=tcRaidM zbO!#EN!*6Mj(1b0J}eAa7#Mefi!gWy;K0hTpN$~T2D<@d^buDa)w8|W@3tys;V%5U z^Iz3k(D4Aytf=yI2qN{t*UP9-#biAZHJq>%h>YsOOr*BgIVMowR1;??Mao2XXg1oi ziFq#8_VQc^v?`lwdI=r`#y}?dGbZpi=E6T+d{|m&gR52@dh$LHm|zt&lW1bSYiE(e zD(rR)PYtm^Fj*<~!tgUo-NpOFE?R3YuuwYX7o%A^9pS$qRAb93@t)EsYc&v4G+#z# z_h?fItb!J{S{c6knH}p$bp1;0tCOu@!QEv!%Nj8GP31BqXolr`C|!t4)7q>iR|;w= zst6dza(S&e1cfZDi9}8}zmkbClk-ENjIcEhjxkhx{2J1SCZ*Byl+uQHiOx7 z2747*WnQeTjCjx9G6`mPhSGX=yccH))f2|*SP)`x z{Y`mCyf+|(mWA&V@`BK8P&|#0k;_2cG3=)}Nr2llAO~fSaoHWoYGv z%GYxSAWz?~Be-<)A$LX>r%KTV$6kl6`~vsGYocOvTqI3iEr|`eSo?Fj`VSFW&OEp8 zH=ol9`h3-lQ*>UOB}&@PSIv_p)GaLMUMJP*HfP=cH+P9?;5SY#AiONV6I_19dk~ayZ8aPEZ36niFA3rHCFEXiU)nTYNljlu=wW^3D9jMaX&GH3OZ$GjFoVl zIAN>?33zpsPj_^lBt|o+sz`562*Z4`K7-k2sM#rMsD?z4+*3-mByL-f#UY}*8y+8F z%<}x;O+^@MW{Kl)daf}v+&H_a-*_pf?9X|6DVm|_KX61{s{tXh{ppCh{sBvhZKDAX zIHEQZ8DwuXk=ZYAG*fxAZMM)wc0_nGz{(A@F_$ieMeG_5z00^4-n!WlAv&W17VPxn zNyY}(+Q46jzL*zMq(1KMl372J>%iAG-gc87ao-k3rUNzffDdjK`^(UpwF@C%9kuP& zqV%y2hpH>6_1%vbgbWxlI_wD5uql)bJrO8Fe>zGv_Hai?Mp}7)5+@AVVFJ_dIC%1j zoc7L?NQv3Ow2G;SB#upqs9#*zon!5>$8z~HBfh0(sGn54yT&J^OShDiY|N<}V{PBx z(jIgi0lrq-Cltl2ci+ExED&xU0=EG}5WVgGIFF-e@e@xTh27F5nz7WpH-FK z%RhQtv^`17HzyqTJnoiDIVxS@ku&b}!necGU?G>owKeFOwD{V)YB#)m8+;}z5j?)y z>hI=J7yeD;AR^#nUIszoiKIEtb$1`MaJp1^!8&t=Nh?o?_+e6tni}3tsB%_u8hT6Q zGTr0{3)r$yHBPqrBH%OVENngzb;p1PqCr5Q&VXyz?eGpPW;-APW(=PWxL_b~%9_S6 zm^a3Sk|c4-&{?jg35LUjN^`P^u+(QT<=~JJr^xIN9Rf{OHHhecJ7EEbY{O)s?YA8E|dN${9XX!z* ztW5-(w%k`W%>ww7cV+yR3!kv?osOjQ?Myw4Jt=`vo@(9mVjl>IY~TR03FK!Y8)pVq zL=%A996UA)*?zaSs5dGt_tn9CYB67I=3zM>Y}!UGJXq6ZX^3v47b!Ig+0aMbMy*}8 zpd$&DgeEV}luzRO*fUo^DroPfpY_nUMIpQ3kX2yKwMT(p!4>1X=(oFZt+>k9;sad5 za$bXHMn76>K4*pkj`R@C=ge@uQeHXP17kTq#S)h+#arasa-piMh$VnIm8yVd4xK4Z zxy{0ybE?5wvTWr;3*RyUN;T;R`+zWC%iZZOL(DPVd(J5e=F&U3iUin=X8+{MGy!QH|kB64q|7IJK8hR@9?KtsruB~ ztEUhm1pA3Dqi|j*j`+!8vP|Ej&P03zl5p#*3*y07&Y~xx@3mUsB3ykji()*u6fjX+ zSG(#azY;h5pSDrRgpe< zTdC$Im`?z&HYU!1oB_%KqZX&%tN#kZ;YQ5gDR>AfNh_5WJ__jo9M@WqBHlGpLNh^PT|99_c|?h4;M;mXdi(eH@6 zA~uXSY@^*9a>JfvCgUAGbC!BusOUlaqk+6f-l2FzMQnEpXzH94qC!oTQ~BK&*@ix= zDlg%DP2Pj$&%x0R5LDezuV$}9O0=>~Z z9;OrFpACI^`gP?34r<*8!(@f;J?&)YVBZK_f9Y5-u)4BbLg(WIY`WrjE*3dwMpOxa z@ZqhqKWqezNIHMQMe8(<09U>bZkWiDcca#|8+{3gAALzLcquvCY@9V-0(Yv4VlF9rB~Sm9KRn ztV&%k%C}~F;^l%BUmkRN4VviJpnt#OumL-%e`RPJw0e|)VpeoP?CEcrR|)G_$m z&i=yqK>WB9^w_8vKS2|Wa{W|NWB#5iD$YEW8@edcYY&40{8}bt<6@Er__xw0JSgp? zCpD=giD-Oj;##N-*-8wfp9@>@LIODY4Ie))EZ7|hYTR)k4Hh~~e+#)mU^D^|Vep*} zmBeAh0~x`?!x5t6r0Kn?efW$nLYTXJCQ{Xrm?2U;B1%OZDe=B~3}wcG{%gyi?bKMS zxciI}Hp4Qfk{Z4S5}X)5pI;Bn95BXv9~y-u`i~8rItI5fB)^iam`yQOW&YwNWxQyV zmH@b+rzSh`XJ({$#VlrI@;WHpg=>YjEM{l*`z_|=%*wLnzF#!X0v6IEOZhc8?Ir~+ z6j^Mhc_euAk!}pE*+or??@fybRkEnEXmg{Id?#WKa>|$@mU7B5O1ME@Oc?^b1o4uj zt7Y3sBRSq%!&x-d(**nef~Kj+>(Q`Z@2@8zqCPOJN8~zMtH;76E2zVzeNa%3V<2D9 z1S_Oe;SD9E>f*F;%`Hv5DiA-+BMG9a`6m8|JU?y?TA15OQc2>RJnD%w zB!~-*Y{MH6pD<188KfprhRqO2B9Lx`wchRwRyFB&a{iS#kP?35CV zGg%6Y8gb;u2Cjevy%aWsgKCkJERP~U_|O|H#C)|OqN1ZLNbdkGooI`<`q3VDgc@0o zNSIU`>6Wi!nEOB&xDwbM?-zZIqf}sq{S1HWX~+~|HJJ;036*P5=5{JxWh%SkFp4G} z%p?E04CPie+32=yN_z546?`A8u+Xgxxj>e~lc(KQC2#Q=*=Z0`SUR#1!n3rCvBd!+ zs?GAOY{SoJpuV<#lE5sVi+$^vTx~p%weOx~Z9uN})LGUQ0TV^q0YWX}jf5}zr;!em zUi8dM^}Nh|w*>gh`u$SY{@Z=4THFc3$v4@{XT%@qp^MdsrpCd#dCeY88PmqU9tK=rd6Sn!XMZ3 zvL7(MXCJg^-<+KhWky1tj?Y#JT;E$6`(O{H#Eg5fyEfMtS<1vuYX`IT)kMjH;^f7* z`Hif!nz$P0^l6-Ev@}v+=`d-OIdhE`jVmKkQ#~JllLO}Nut@d@4>k)Xcfi&1y;38Z) z*~iz)CtoQ_BF}`WsLITQtLg&=ff{zLGm(#EqsjfTk*|7+%E;^agHW(qgFre3sX9^G z{TVY+cC%+$dqK~U1dQ@1;Sk$+KEVei(=gGOyJ9{um=`7EEjf;d%X8x6cVmDs-{Qhs zg%e!$w2%l{=8QC_7#554lFZDk)Ou*eV)na!*^fb17}IU`LbLiN*?9=0L+SOs8q0Z2 z92Im@NhtY^!YPK=Rdc~9G7zw&D*mES4aB!UzSYZrxvV(?b-6rD_Y*=W@qGbh^{P<+ z+)4!!y1cU4DU-~EKv(~?*lGl{_1e;%_JkTGoFj`mFi*B+J%*HgPhl}qa)Ws131WPD zAagBcJryO}yE?k-l~%7t;~s2&pw46CYCvs9+v?cskIn1c8q3}i->A;Y0%s#Ncs4c6 znif@io;=2E-dzp2+I1+(Ufg$wl6@_@=Mjr=kp+uUNHg3$GNM7HJ1?`-N0U0O+EibU z@>X1pVEX!ntDk%?fN*MM@+As3l=(IYWyjcl%yxX`O|OqX%I!c8%{LD-Vqx-ZF52c+=3I<>^^Juj=Ua~R>7`x#Gc5KT2l<8mw;a95<`lmzgSk^* zzk!7vYl#27tFtn&hfd$}zj8p2H|8vAPFBCxK%vK9wT{6^wJ;>>cemscphzvXu)Ua0 zP~3;Z0f+^N8p^I<4{g|M^TKG3Cii_Z2&YiqL2@b$#G3uztT5PDnl0pdve;6i-a-06 z(!1`}=%0vT79~bejpZ%0OpOIKU}~U2*zge-pF)Xb5<^bP_Qds2Sz#eeVSb0@dGB2k zLE-!jnx-z3uXnT#&wSoPUKqfkPocdlDq!oh3V8nI3qyE_s&qpTRjeGTGz_Hzasqx1 zl_&Wgl5{B?x6HFo0ij3w!6`SaJt$4($QYTg^8xGgh)<;S*Ph874o*=buaCrBg(sh< z+YA$f5oW5RXSiF@%Yc0U4mcD`RtN>eZ}=Q_*Y>CnGGGXhi8NPJ9GdP{rvUgC#{kr%DkVDP7RKQrb z83pDtu-)lIP)^nKrFDXWg-b-^w$aih`srL1*u=pLMexG#j^Uo6;;~B9q2#4hFt_-_ z5}(}1m9l$^eN*;{LW!Zbs3x_iK?u%UrYav1apT}?W_1?KfkqNVt&*O@+ezGkMy#d< zeX)mksWDuGM9mKRl1O&ar4=$&BHKQt^6z9Q2WH+)ll`2jv6HFZnW-8NR)MkI$$Iog z?&3Ofrsk6ZXw@m6rRcx+0^>@o`pN(5@=5GTvp-k|Ai=mO{x(Gq zBwR)GdU9hoYv>%e(hsc2El`L3H6a{g?_oDkK8=)|qxDMem#o*l!$QYAr!GLSH{YO@ zzSC@fN_&ddE1XO9o1vgEYH-)SdKX~SVqHkcWbsUo}-51<@22{qs`t*6jdEPd$Z$naa#H( zhdc$>$DhMt7*e^w(>P3kzH%`oxMA@#X?YCZwj1({){%yI65Ewg>r)y>5&F>jl@a@u7$ydhEx8v7QvbIqUN^=<4DiZ7^>VQJgH{f!KHmlFoHN-heoxLHIQq zoJ$yNQ9Ye3;gf}ghzI7Ujvh|TfL2|Qk$$vcT!wy(X)beOB<2t|1P=k;6~YQjht&wm z<};*wW`?ksn&5$943OI?jP)T`E12HC4ZOu-lpMxw44Atr#u%lXtN9rF^@O1xBVs>F zFwZp3%ywEdPS4MU9%g12lsM|Sm)+XecYDtfwd7HylD?FOIGU6|iV#hb==Kd}a5?9L zBr01$rOHxPk@TaCk5?oWxs-_!nFU-zWKpo5lnmcWPANPrZeM+Gaf>zY{YJ0AmCC(- z|GcWBTXzvM(1*$&sUHx0$*V>ptz4@|rp&hdfF=~noEZ@(z0nx0bClRbYi(-PL}fu{ z-AwDuw%H2*%wz^6b9LL`g~c&W1W2gqfi;BU>x;rprq}Y;-TbhfTixQ{Ol^B4Xx~hI zkQZ3CZBPU6aBey)0Eo%fKZsIzYz)+pi&3+D5UFSO%=TNAiz$NQ64t~ebGBU+psE->bu zOs2E~uQ>S4M#dFc|Y<{SQx z&}i|>rJKl7bG`4=O>NaCOJ23k2oyNNAxkWiyrH`mfCxu(a@Z_&yc6Q=ghoe&7%k-G zkZTjjL%y*28Ny4}5Q5;UCqgHKC5zDz3a*<5U2ScZa^wz;kJV#hz0oEY!Tl=jiyn&r za+|7OZ+NoDjF@V_U-*WZSJ{`gilnV*u|w_WB{eD|hO6A`oz#^gG>R?{t_>?ca?iw(7FDND_?R8@ znXWI}_+APYPiovw4sNu*dJ2`Qxk_J-Wv7W4n5qA)&(BA^IhQd|uhKvOg@_IyP{H#T ziz#{qW{Vd!sIr=gf`ea1=v{wa>^wMCP%JMx5Z5}?>*pC$lJ6Zm-*%&~VpkmUav3xY zH#9&$yenmGEFpmOd}J&ry`&o5Tx6Z)%M{68S&Krh_2eQ`Zzes}j}z$GN+us@?#2E^ z<-ne-`NztUBIino-t^*kTv;wiZ+`_-yxvV3apoDikiz&aVVoZ-r>DX=+x=yKsFiaK z`=6db-Kk9y=bN*Hn2y=MY%O8>GcG#q9_?GNr3o3ExP;=$*GxN?#MUKD7n-U;rg zqJtCec#`Uq9%m}2I2e|}-mv?)i9XySd=tWS1hz?HGvuFieaXOlfG)$}mYj>_kUfPl zq21uuV3I>3ItaSP^i&9Erq8Jk+%^qBdMi&3Q;?K?5{BG3tt3x4iaQ{rNuW0_Mrq9q ziG=qAY{5+lh8P@=>4o10@}cZchdWe1ON%q9SeSEaFw;pEXU4cIiGz$a-3H3W^MHGC zogP@bYr?6|MeX0CmtlvcPfT)xm1&+J$LhQ~qF_bCUrPWTbbD+MDS>*9`Hm4wFJ+^Q zWoG$S4iB5;)-aT1(xNz*v7eUQMqT0G%q|Yot7$m%tW^skDS6}7_mRBsgvo; z0D;Ro9*SOTKw&i9sKkH#g6mWVuAqs^z#q#ui4)I7bV^3VvYD;>wFjI}_0hU1U&+x% zCxu$&YddAM>1DB=P<~-Sa23q@Yv!TN;13udmN~OVsgKFKc;_DMe5TeMo$#h~l*KB7 zf7zlOiD>l_Yf#@r!6HsZn%c$zM=WFai+UdWUNvipe|Ff-Dd>v*xC<*W-?$s0;{IeU zjT5`uTAg4m9`!0K#D`1bV{p2~sI|6DOfZtxSOV0{VG4E|k%u^0x<`{Wn>D9wEZ_SU z-@Vf?txt( z!Frd;6Dp1+hp9&e|HM!P&pb#@png(QJ5-Ef70X=6^vfL75lOrm-^xdXE(z7BD1Ln(W znr{pj1UcNCBH!Vof{R%T1}aB27I*z3F`a}Doz4)!W*uCR1y$kwucKthEhkUX(c?$H zcyu&;P;l%OiOtq!6gg-Gdvd>ed-VzPHJLWm%---}vkUN7 z43)0v7`5xJT8B4%O5ygFsgi&4MBDa$(sQ_E2_qF7|GuJBUK^$+cGXv}2euh_YoZk_ z%?o4a>C*U{TNSM;3SY0I8Qko?-+3~K8@St`Pc+ktt>jo@6E}-y$PXP-vc#bJo+Zy* z5%EBYpl2|5{zaDjNb!%G{=ck1Wcp}+a?Crk2>k_t>ibn22U_=QYtE3V4E91a*eJ>G+yMgNg2 zGLlE4*Fv~7u{#w;QKL}ov1pRN@4YA*5#lkQx4Q66Ov--5hxV#2LQdO{07DNt5gcL^ zCP=Uhm_W}@X?U|cLX+hFj4l=iRU-(nRfJ)#f%M9K`piun-gA zg`yVuz`T_*G0uy*CoR7O#h67WhwQG2#>IvVD5CkGTu>`W`j7CKsB*i|oc%M;;u+0_7s167gcJ$)Y2qe5${7YA&xzwnUg);Fsv|{aK`U+FCI`Q;NQ6$u;9s9| z7k7>?Q9H5~nQ3!PE4n7^R;BfzfHcw^XImYlQo=pZ-S*|cZj~y75rjkWemA?c`|aMo zpoklL$JTYF6(R;^c#(`qaj=ZE)u_;#(RE6>wxR12FAoC;UcW$nL`UU{j7A0THqba5 z#VQ(jO&bRXjSu7mok!I2WIw2Cv@-`zd{BfiGM#nlOqU z|K{9VSs7DmWmo7Rx9YR29LS-9!oz)SLYj0R+br(u7|h6)6se@*P5MSoMKRsJ4vJVY zG<@^?s#p2rU{eM_7zsA|hRbU>{Afn0p4)q<5jjOTa|zr-@0c_%PQt)jR{(GQ6yQ^y z8>HeHepk}}dr}3UBlim+Vqx09l?vF~-B6$f$1@R$56TfXZXL~GCXcwbJyhZ`Yp^5Ub8K=x9S5& z(>Z74N2E7%qU`lXprO-V=oOpGA7iaxi4}W_w%mH|xU(}oC=2WN4JM6T-LZ39YuAeR zA-H*ReGcX`E>fg;so+{e08~bryQVs9F152nGOxO3=NL-Wto~9)dXm&E2h!_z|C5X` z3b71?3q*{91E+Prq$TY&TwbwmyYNBCPPaGImamop$03SPgLrsKM<9o;Ktl5yy0*Vy zPFOmrCj3jL9-x@3MzV93yrVKgIPjqpy~eRHt&ahbh(*8bia`j-~i zzxN@YqeNMbydhcrXV75HkE}z5k2{BHO$bhjuKp!~a;1QV0(91ETgqldxCVAxrFds; zV7QV&?(-4j45fCR@(Q*hRimYLi{kMKEN4PNl@=lwrsAp!C%9(NxCCp-_4z z!^6$m0m&!binSwvx70h#emnAePwU`h=%k5zGVz%+k`d`-w6Emt)Zcb4=Bf6*i^IJe zTPkdPeJ9^T0d|>r;8sunc=`w_Vgyaf=e0}^vtpBbj_pEw_spaq&o$}l@Xe*m(D(ZUaKk{5RKC1iI?ZmqAPL}4-TrO~{4cZH<%sWau>1uX`~oHUR#xI!{$gGx zY<5ZP*@%Dy{XygZ1Jd;`vfId)%!{inG2K_!NO=9O7|X)Bt^{oJ+%sK_Th57qE=KWE zN@ie_lY&6<;IKLF#5s+>miQeCfRg;N|1YKLu;t@rt7~d?#q;# zuB#!BhBxKMS$$XdpS_C^s@zURL}j#p0MGAF3aaW~=ox&6i_S(Hrd|>V`72!XcLYNG zre4K)v9Ks61Q{=8q^D+Ps!il9E&`g_2`sEili~b7VcWcnP0ls5f96vOQ{4NeRE)1K zuw3+I(MahsCpI z&8Ums1PIz}5EG~!rr}=%ZOByKKM(kq0GYqAT|FQ0GahyPb-@1)$ov;y?{5dKNwlUG zK%M~xe1QA9^!@8SZ^lq7E!xf74%#mxLB%pbsceXuL5%tee~oPu`wKsqqlXE8$l6KMB5vB?h_ z|M$w~)tQ<<$o?0gUAXwaf_DECG4j*-fbrTTe)KP6B=!F?KRRArCv*Xundt&j1$^F_ zAR3S&xba_n-UUhjeEIqP;(WpJ{bw@Nzx#BZ#rO+-fQ{l=asKy(tzy_GBds+ML2pX^ZQgvS2RY51?yBtW!^(^uvu znz|s)z*D70$3SlikpyAPBCjz%WeCS( zU@fLcMEGT7#3Z$4WX8Qi$;?WshsrKy6s2k`WtNikdkOE#FKQ?8?HEJy9WoY{3Q%E| znBI19EU_hbie~i)HPHZ!rs(2cKlWYAC9~2ACsy;a=^zvH^7*(dz|kdl$^1RA&bK(T zmaf_#%d)6GT3xcJ0cDMJiSOba$<b+XNw7Iv|&E!%VpXR+CKir@-f?UWAg zV9$f{lCSqEN}=z3Qc+Xb`K)RXxYNJ2DT`gIC3X`u_}E_oxB;JjZl+I--wMsRDhxX3_e`!?hLxi#`c~4ed!rsS%v3<(nxGh~Vl3#y70(-y| zeIU#wa$z{S9qeWWgH)UkPlyx>r)taUuCgvQ^y0Q3D4?D)mr4u-=5(Q}%=f&a7st*E z@^CwFdxnli0|)iouceWM_()BY!bCFFGW42&R1D!+^?W>FzKFO(Ns%7F^&+UCfk4^m z&G?9xLgwWj-68%6*5@8b(L`O%*IMiZ3R8Js+)k1H7%>@l3f%5Z+uHYjsm`9^Y_%J=M_E#kHH1#F0fT}NFan-&xI$Pxail^IpC-K zR3vq9$A;&{k$Xj45ekC8$!7?`wyA`ptj2LRGR~pt*0cIi`-98j$t6Cc_!uWqz+$-& zEE6?zo72Ed-TX>4$OTe~EdXq|Gv!kv_>DRGg4I3sRdXsnXBqEgJ%GqQzcN9Eh6q7c@Y}@4qoQ3$P;PV7U_y-PYt}Xph&jLw55W0eCdCQC5=UX%)lptgm01?G>RknME8q5UMr+)M zPl%-92B~Y<1MrZLi9Aao{3;w^7rfmGQ5+Bm1m`k9Vdk)Io;IPeL!Mki)ifZ^wsg-M zr?;V1e1qm*$4!F0%mz+|f&eA5$0Xf+jn|qs0(C0Yv{kz!wqK8#ck&9Vg@!nm8cNZm z8Tiwodbmecda_qt6Vxizd2y$%E*2PzoZSN0_ha*+TMpw zN3`(QbMm=gr}nz`I&G}?9^5D+VsoNJAWd*TD8~MlZ(3rBSnA|Z;>+|b?Ag%h_>3!YtT}T>EEru0sfFos1CZO^gFOt2Pa{8c7~gw6^f~9zwQK|SC5@Wl{(|b_ zT$@f4jkV!{s)*uvR|V4tgx~t3io*&bk4^Lu-w*XTl@u8S&MRwV*b5MA_NN!M+c zMdXn#L*+Ji3wusAM<88+%wVpYI5N8Eb^U!S``XjIZzKC%d-+7T=k6tEW~6zbagZ1Y z8>s6KzVG1b09QMLqNhD^_1^^}=T~*^xLu5dK<}0Z^lmjUA-~hR6@0DN_!Zy&-&}M5 zhj(57tBr(uyx`wbqg5p*eQRQoVEphR0R1f`T|>bMO8E*Rm7HtjuCFPC3-IAdN>${6@Ii&RwVlqtSc)Pq}Ncy zo5WU$-H(QDUf3Mmb_ay`@J3IfGf9JyXb4V`XX-5@*Tsj4D$^)wC&Fr=w79I^WEoN9 zPnjmxca}-|bHGFOb<*Xk70RjAUUV{ID8jY|@8n^udRXDYQP@?39+7@7MB*AoVU61? zPm{VJ|qlNfb0s7fUPil zI=^XKxYrnbqrd>HC#PD1S@XFhu;=A3J2EWgkC^5VWi_-c4rJGoDg>-C!A3c1}9uF34A6z zP*hqHJW-2P#sI_dePW}YXH2?x_t5Sp2{Q(z>&hkP%=!zT5ETvkT?OBpVu#K4dK&~g zQT8}k_+*|Iauee|U5E(Hjbw-nMQd`1%&iQ)SGQ-?Q(mcZMAL_B=q}8JYuf>|AU#p$ z+2|*VM*1--CFL_QmYK|HueFkh)57SR3?b~fVYd+opFlR|5?lymPn~xC=9Bz*+veW} zNun$yhpNh+I_>%`q{i5_Eu_VHp)95+MK~G~o0Hvb2XRDMHM8e6K~a`Y0p?3NC9{4@ zxfQ!@OL^4@sLT2F1aiv-O$`3a@7j3VmkYZjQCEtpDn2#|awO3!6BmqaH0O>FldR@^ zZPQrIo~w>oWnU^mU41`QFPB?6+v}fOwK&zDTfN$}v{ni2Cta_Cozq;eM%+VPuLtwU z=YK$eeIZpk8Or@wgkCwTpoq+3*{Ye!na#R|F4)w%mFbF{q@N>3ZDWITCHF=LZVgvq z=e52Ugx_9nd; z$GDJ7U6`;Coh{952l($O7S8ZIzQxxaBlq%PI>Cm*aptWv$KirXd*uPS>j?GJiLrX) zX3BhT0j^Q|vQ@{Wyl%ATtJR3zHY+#myKLuLBIC+8vtBFmFLp`Q+}!RHvZ&g|Z8zN$ zA*NlenwnsJE;r%YZ7g+=7Z+d6zW5e1>sv($CF|k+x0Ge1i?7FJbMj)x5soHNC-x8= z*l@BLB!b_QtU7tUM_^fZmC>B&pmPvFst$CsuT4N;ZxO~&>~Tjy0)cQKAPl_~bd)HU zrJyEPxWP$uav~Qb+yocivMzMgs9MC)1Q0h_4jc?p5*+kJix_2pwx_)VJUotN5&f`^ zr@gcee0e_5O8}VIY;8E9^hPx64L1$c$GzFSl3dk+0R~rTNe0rJc>7n(VOw8+Vv=fJ z{A~5qKK3p7o{!Y6#e!g$qqkIB(k(L|S^QKCMTlh+T;P_KK&0ss*%4(m^cb~p52J)Z z8d!Yrrl6O^Xdqfj3;YHKB+btr+$nvZAc}}Ywa|(vw1D=t_v!G6swiN zfb<+Z!9|>)*L7H+71K$O-Ym);1}hkx{ZaA`DkzA1PzU8&k^ADRwjV|28ajJXBPo*$ z$kUn%gaQ%nQ;E99v5jk2QYO*Q*;0fanqxMMws2iyu`|?dEBVGqoJhq$v)F8=rK2r# zuC|6$G|p-Y-y0)Ei_E^b%}>Gh(jZQqCkSu>lNb9jdyZ5G_#KB+p&AlRO;^CWR_9C zy@?^G=ZV@@>zX{K14CkXMNR5}h0v19w_U>Xfw(d zX&^<7E4j~Y$-Oe99<7>3KAYLGbSRgTYPyk|uRv?=r?#v}@V=~()2SffvHVx!k+LSf z>VhB}vacX{(7l{|i5nYBi1yZYiKXlYsPKN>c3lDSw`|{ZJ}8hA5Wb(lX38XL@&3sm zy)c-$Xed(i0Rl`|9Y$l0RgBrPpO&dDwDE?CRqU$~UF1xMF1u8lzRixgH>1xQUp5uS zR}p>ntG`Xfb}c4}uybBg;P4|Ps3@87*boo=%3z;P3vUZ~e5A=3C9cHc0Iowz!wLqJ zlfSqYF?d(K&03cO3j|K8tp|m4d{%y#!T4>2O^@Og`H5MXGlQzk97gj zt&74HCZcVz=Nqrox?)(?p+gnkflFLw-?HCJP<$Z<|G=RhBY8wKH+_n^ofDpC#5IWn z34}NX5(nF8mQ$MA1dZLC<2M-@W`YWpw^fm^MmT?&`AATjV5a)8l6VDy?|of|5%83S-Rbi`BTpC3W51bjcHe(OxULMo&M5{ivvkLxbJ0{T zb<9WHY*5?yvMAGi&_zFP(}p{`8LY-Xd!6#2OYCGThR{*l>MF!=)uB6W&T3ID@36n{ zWanDkpz1wSYqc*^zU(D0`%TAnbBsUv=f0i01Yguu(smTxdFz08Bz{TL zl-{-M*+`#v)ox+;@e06!vU*_){bufwz;>PMVg%QoQ50N$ANzv-3y! zJ6B1V18*=X#vNZbc-A-VBwXkK$K~Qr;EbZ~JUie5+IQKUbHPS(-LpsR7RT~{*X&b$ zK<48(y5~BE=teXDlHTC4iPsBqA2*752@BO1Z0Rpp=G|0j&4wbcnXRL)hr#s^xD67z z-Qsf-c5s~VHiS`s7Dwoqu;(me=ppCuOe)<&n#fa`&r_bs^PaS)qV!Yw=4T0!Hjf-U z9uRqI4SMhyxWI3Kqr5$%)4X(Ayp$X~Eu%bDnY?8kT(5A`KBIN#w{sJ0@phWmbyhcY z;q!4*_u+K#VIcJIit_Pp@eY9Q`!GoR_>{S2s-bu@U|BS|`|Z2Omie|wAwhFFkmkDnjZfZhoIf4pgqH&{j%UgqM#LZ@D=5kumvprk^a|c@DZ445ker( zH!#_4Alf1b$X32s_d~cgFwx2hiH$<;>Y$Pxgh+qnrn!Mdi%d)RER-QS6jnKu)i;zq zBb1H!6$kSx&V^7az>Wp$haC&?25JR1@nzgm52y>&0%8W50BxgMA0P{`>6tFk;m0By;1Mu|tWC@$j!RiVPR-2?W!E$bPs5*Zk4gJFn(AGLC6 zto`FhdF<;aHTn_oe0PZW>yN^)K(~dxEWj0i%3G32On8$heF`nX(*wK7#+;e8_oTt{ ztDjx3USX?`-Qc_6EtQx_U+4I8aUtLcP?kI8E#U?&+_w{+to6bD8q1k)*hUIVjT)9+ z_FXN=frw$IGeOKg+u^PO>BsatJj>Y?867ay8qXVv!b+B3>6D7q+i(>yA%YP^nV62-`wfT;iEa`^Qeya68h*?{69gp|7ZIghEF)zm=WU=C zF(uok6)8qq7`EBQo^BVhtF@m7@$hG8zCvJ5m~ui~NW*g0m@TOj)kC^l?}5;`|1dfo zzBNgh3&$hL`R1l!4;WUEiB|eP1{O{1a|yMka9C=7VPdn6XNX?2Dfbbah`MATNrdHA zOfMpE#J!w7PUs)mUSrYIN+k~D@5zWAeM^#lJ)Ey1BzwJ;#MrcCF@izFmfB+>hxFK( zB)WFDe@S>HDkWP`AK(AW>n;NOY$5Qms9DjVzMQ5J;&=Gl*_J342qrifk)MJI_JsOB ziA|L9RECNuL@8(Xo$H+UQv8PxZo^Y=dasU`6?yWn#Jk$7WA59SxV#wv8)4egt_P6^ zq%mfiS8?%~4AnCCa}ZTdTDaLi+L2WJqU!=PfNDdSWnS1>FS(e`J}Nd7O>%TEoweqcL7oFZjXwxR;OzPwzG#n4uF;E=^+9? z<%|;%-Q4eWgs;0UY=(y?F6jz;!%$a*2ZOUwnA0h&R>qe`Al(?W!q8o!(jw9=Dj-OA2ty-X zf^#+%r zABi8yJx3mD=F|jc5>wJtOH|lFT1wg=^ZEIx4mLhP1B?QK;0R%Fz3PW0cc#4^>k^>MO$M>HK}z_{4m<&YT&- z0aLe+7@**^x1KoFL)Cd5oif=%stHawQoeM`&p+JCCMk}6Lvz7{Qr#O zs4}|G{sA6xDcAVjSKi~zb5}ip2=0A0!$`>9+j&)17p!o1!gC)6{1cKoo_Kov`0DNl z`BgaHK^vq8uJAq7SV<|G^%h`yVDa;*)) zeUtyzJoBfg?Udtf{f>~!vu~3`iAGTmV9K=A`v{0%7Bm4{5FTtnc3-j&>|XlAzRWm8 zw&^y^G9aAyZklwM73~;_eQUq)WrkDi|K;>pZ%xz14-4IhZxflY4~phDGGN)qgw$Vg z*RLyPYmRJRwFiV6!^YJEPy4BHQ>~~!0YV0K$5ayJOr$QRG1*u z*)4%@H(|X1KCGSMT_^bVaD%N#OI6y|(mJDnR@cH&@o2l;dCXum@CPYmUiwJk3(~47 z%}<2_KGRe}m=GnL_(2!@v(ykZseJ6dnbWFOOH!apXxDjbjpqt=hC)#uTJYytkACK6Z+?1Re%TL`h5Yuhd4_0G6 z^Km3@RcL%Pe__EXT1D`k&-`hC-v^v(Tos+I^zQ_C9BNNemkT%YhbvO27bjTDaDPkw zzGL~o^lX?NQ+3sq16<>bjC7J+R&Y1O3M)*W6~gsF;IyS>9Vndg59h!$7w7s~@?hF# z0JvFL1xAA{g9ZSHQgyLlLip34X%8YJ8rUHP#QF(>4sQ@jM^X6~OM!J-SN`bG%aNSD|DH}91u#&|c4jmOi zT7wC1XfAi}IOmeN8f)ePN)8yr&DPy(hY7+J4l2MtK))!3!I+0DZr^XurvWh!yS)3- z;s34B|0yTIgH-FlYypst6n1vT>Gy@^nf@mcdPb?W*8?cEce{k&p(uyx$ZK2$zYi7l zsE&Y?e!Qi1^V9V%(gljHqS^)p?RC4==>WTn91iy?HdE@Wu^5OcF0JIgOZ;L!!(WUA z#QJPbf&dE;RuljxpbfZq_E^~dh&iQa{WGM}A1HOOjo>Sfh7pX4I7+2|(>lB-a@M?{{AmWrKJvA!fqN>voD@xbY`+!%byla-ds7_u>z> z7atnhgqulLI(y#Eed5I2ZL}-5PMHfoie_$|>z~eQj9G}MiqCPaGRJ!WD>7GPON;Dw zWRp6`?9s@Z@aKh?5srzk##&k=M3x*{RV#_@= zF9uV*b2*!D1b3G<-wGqMZFP$gS#0%4G30K=P-FLP_3|ZRZ1<_AGCt~8GkR(&U#pe7 z{a*JruNUqEZ*9g`hKHGA!(KKv_#?ay+9CMXtL-;Oxpz`~t5ABNPj{p9IcIjquK?G2 z2|Y)mt)>EbR`#YLlI;64;kPYe;8CNz{nebIb|ycp9)&p z50^^bTOKZ#&*dGiRPC-DuGS%Q9IZ9optoCZW5_?+c+InVwAn4malF-c+v>P0-T#dF>ak|cJrLlMktKGT1W_fImyD@x4;dFB0E5x{)~?@AFCL7q|@9hD^^* z={}1~|7!%C|0yWp2Y^y<#wlOgNaLwf0?rSNKo}>4_;;itZ+>&=Jp(&CQ*c7UfM651 zaJgG1UwjNfDljFoGre|y64#I@{Zj&tMsoXXEXp$&y74NT@LYW8u{%SE;EC$ngp?3) zLOk_Ch4LNOtU)8NChg+9oOg=d+tdj835Za50wS%E2B(Q)IzxneH^0?gQ*aulJesLr zNJ>mdc6Q5Wz4pa~%u-9lPm-0hUwsU}Hv#yeLoeHda%Y$+-L_K)Zt!F%nSTBvn(>N! zK&cs3<;K_^yKI&Q$f}yx^6pB_QA4@3h!g@jRkdvVOxANGo+Vh#fPvPUxOdLuB@!rtY_OVf+hQA5Gjg{FwCt8) zHN)rBp*PB6XUI4scjtSD-uD)}qxN&TyJJswb(eR?U6I-MCOnBO_a=QA^7j6$X1v*_ zNcnxuz;SCY7FSh&2(K)|Mlm(HXn< zGHcG9H_lmas;twkryKR_ZuT?zKkp}2|2;+bpRwM4V;=fP*4uxJK;-ba4ty_k3ufi} zjrC@$W_WIrz;OQoTHjm(%of{N+C@gJDaltaLpp`+Agos?P{K4+fWL<(GdzBB#$P>3 zMM_-e2EKt}2Gy%cm2^_DY5ldlC-}^n7i^%^BpL8A5ZTPZZse zC9GkJ?&cfqj2Sr_f01D=5VS%LGk~tH-5wV z{9AAQqQ^Hk=$qWcRbDr0Nahzl*6l>;TK_+oD11L}in18|KIJ-(uR`v(xWF8a&U@qU zM0sM8rhCsxJ$B3Wf1k7WKkAKB9gCLdFKX}Vkzl^j4Zy zZZDMRQx*-FzB>n=nyWh}+>&-An|hKzl!-7$)Xb{^*HHFxJC>TaXBQT2b1txu#=@?S z5?xb8`AHN2oMvpMQbOm&-$%a_&CKpML_dJ_urrT^L*!VvZ@FquqfftvbSTC&PS043 zxt8)J*~jo|N-_5ODf*o55{$Q<(oOXHvOh3U_+!e!w6-?8e%2fRTFU)&pX>d7%GvvH zbNrw;9$^@nt9@b#H~$n}@L)bUQNdv@hsEOlpY+B=R!2YRjjsj0)yY5J`C!)s-kmtr zNw%)#g6tzDE1n!oWhp`qm)_a>Aa1q>#~th?TGbvMBG0ve*YKoH4kYU&F$-LChJZjK z`y7Bqof`&i7Ze{@Uq3n_ith*0Np7o8X3OzNMg8i}37d1L0B`~FaGzb)kx}pmO@%An zfY>zu_H~Ww$67Z@#1rQ8cJ`b0R=@Fo_`2rH5%}+L_wF-{hQzN2uK0#At0E}YR6QO= zLP`^Y`E$0UtxSLQSpJTzLuIpbMU_evnLV6J1Rbj{Nf;XoH0g# zTS6HXv-+Y#KgtBL-L2UoevtCn*7dtt!*5%d&m)-M`~R8`-a_snRn>&Bfy>}0(ZU_w z@B#q@W2YSSo4icd=dglL2 zetG$`|8E=vfC=>~&zWP~lroB`$h@O&<)?{LBUGW`U4#ZA2r&W`q_1ve=JY|2o7;M! zutR!WlAn$r08Tm33WdNZhgzH$6Ydz?_U{-`D*9!BMCOxY!f3pwK2Pkv2#yb4(tvSa zCcQ_qA_63(=t3WznpxBP5NeK7tESp<&AylpYI}5B){e2L?LA^?IE|8@;0diZSQfWW z-%whD>0`L+EfYE)S)@$5a4_>$n(!Um$4aO2nCV~xq$v6@BOTbR0hh#kEKXz$<<$Ro zA^Mub4$P8L?${k7g!>HP+~*06FfmAidEvAFIj@sGV|v^dOUesrh#{u&nGwnUu~{h_ z4;5j=eb~9-2{q6b=mxZ`@>CxYaztO^j)cc+a|wJZ?pD}gHh9NA zto#yK=+B(|q^5%brhX=%R7M2JS_bFLMz3%z%nq=t&KWv{755Cl9H|#mvh%^~ky$y_ zO>Sg;m5+6NmGW=yzwa&-y^D@pgU%wbq}~jaOROWjgLc0qiOy`L=A$<&q!A70b)gap zgMN|dQeFv{DNCYYWHLpyIafQ)HT`0xLu~^3+q^uF;$Fux0Y=*i>Umy>FbTYrE}&eN zF)msveNvwb6c<*)r5c?MkburO;0zG3Y`v5dx~h%WH(e_AFoKH(rAZhF52<^Hs2sg{ zLz5LsYg~jUNxLRgH7XfCY%Ge8n6~>NbWh}d?eUPf)|LL}iK0eaAYY`LCsxXprFz!w zL~_(hZ;9fTA1z))-{MIF>pgi?PDI{?lbC*>7c5j%D>Gl>xuMWKWX_=~0f4_B-~EPA zoRLqT=^fb>(KdlAC5a?%nn++NlpHTr67d8O1Bt0TWb7g340a|7=?YPrgO#Mx_RA0N z%mgL{JU0tue6>IVC%R*sNW^5|;|3{5mbP7l&MN~ErbGj_EWBo2u}THdN8Ma|-r#k#JY9Pbz>2L?vd)oDMWXqK{v>NU+E(!u-ad^AZ213Rr881I~N>lD8O*80R39 zFI_TC1=^S}RbTWX7Y_AGrWYPE5b>BwkzbwF7k??b44pSbQIpk|{)9_1b8rn3_?S-N zl76_>v6Aq~nz-GD6yy;|Oew<5Kt)wt#{Wn(1h}t*?DZmBmNe~Y$CRfCv%6eSTTn#T zJyMEF6nWSkPvlE*Y6m-KwZh#%jQ7R*>a^BwTyh~)5f{C#WmSj?8_r*dE0_Tmy@NKp zKLooR(hzLYB!kKeZm^|t((;nv7i<^F9%oR4%W(O10I+Omy=_G)jZijh8@x)Pax2 z5jCU6NeDI0wGnZ+$8czf$yUdLncOT*z33p*+e@@5p(!BOb&_ z^P3jdy~KIS-)u-IxFFdv#FE9FZ8H8OSs^G!G^u4i1Fi#wLwkoWr7bjwsS`!HUc6M( z>1hnA*oSf6hE5mNfLz4K**wiV`Ja|$avrkA7Mk+kLUy_j){R$>h|?e~a3|0UjF%pw z`PAQ`F`JLOiMDcN1ThUkGvfV31b*Gmk{WuMdPl&-q>)AgxrgSK-}BHqL)kJnDC5hV z5>vnABK~{?bwb{xYraOSGnD1{@7bE!q-^+NYCd8$RVDmY8YOm8H_W(HQa+F zVY^%L$OIn90TV)scuzIXCgsrnDS!Oc`^(`@`A_E1LxR`Q^;4UzMpiWA_Lx8BY{7Z~ zWVwkJO4`z^#~~j$4C$NEVzyfAr~G@!{OL4xT9@A1m1BR z9t1Z_yW6CNSIx9tS?<7KM~S4!(Pc-z)v3O6DY`mtf+Jx6wV}d;XYU0CE|ooozP6UQ zZ1i00V_aWFhyC@AAd)7{*bm%q4Y<^b4ywj|r2Si56|T%6G{E^t^`seznL0AW-#Jlv z)g4h&63ErHAn)k#CehO3#rC0zc&rBFP({RaQK0MOC ziy?+l`or33ZcfbRqTaa?6ujP8K6nbA3!NjFT1k{kZ*JtG<1VFcX$p55_bjXL=`o(9j!rqiI`i0ZV*wmoOKzalxL)TxQsJJta_ZWPClbdOX!| zc)dP4do>Wy4}#|A+!t+cIyZWmOL)!if}#zy`^pSZJvmlDBs_y|MR4lP@a~9U=Pf(0 zO*!ybvj`C@YMF5Ym$g7e{Z^L1(9qz0?@LqnZaL*4G(zxeQl z+a2mhx^3R{5}NJ?n($G=-0L{Bye{iy?m%TfJh0D>5dhoO2b>#pLaeO6a)++*cd#pZRx?r{aFyI~JO@JZb8aCpRbl;C-;fa~y7 zcmVL$a66I!A^=!YIS41@22m0ss1>xUE22y#zDtOo?@ncr9J&H60nxuiV7denO7rDz zz-QTJRUl^bdE|?5pDzlJNRpm|;GX|vG~PvN5QZ*@nh8Yv%mrE&0i1Lxh*pme3m_^$ zL*&wdqyXYlQFGSNNA+(6N`PckaW3sqA}L=B>@&7xf{4+`3f*HgV^p_A2n-;k3!?L0 zW(?+YkG@9Dh^r*W4;Rd>3_!#Q6$kmC-UTc^^cR8Svf~8h)5|ET;siDF5rGl)xUKp< zI8msS+3lT{?KR-K(Sae)fXdkZ?Uyt~6@}NMrb8gPqE52ger3eW95=#}i1Cl?@zjSv zySzA^3n1=H(5Hz&IAP}6X+PviKJ9+r(Q+PvZCv@6JPOcg00ToB3$ou70 zEzcLX5W&fh+b^z=_#$$p0lC8Ud*W=3@l*EwfKWb>cQ+osn|%vMJ`-OvDYU59XBfc=p7<(1?hCm|Goo&Z4L$;RVFXMr1o&ixoyQS!>)1Qq zvCKoX=Jg)sylU-YAZ1R;Wnm%}U51=B`E(eq+!b)q6Eyz}ADfir#q{+Tmw3$AabiMl z%-AHRt0wzy;0Q*6o(oG<68i)1`XhJ8?W*~eJWHhE!)eddhA+J4j3P{Qp9eXa@;DqI zY%T8GXVvR=U2r(^lLmY3Zb9e^jNqfJ&onFpILQFxwmoJJj}7dc^ot)O36hU zaNYu`<;^!9jL&;n8G2)cu&AI*JZeF8c!$a%BeLI7wz)@Nbg!H$5@)|Y6~nE>z!8V= zFedr%6~*@lZ*s1t@Ip zqbtgSUNo8$xe5|`5>f#v^hxQk{75unp2I`etBI&;X2@!0(QD=fYUZ+Q7Bp*?1wbVo zazn^$zM2#?zQsE<3{3R2hq2d>(1}}+N%BGZ2k3R8Hg(6Ebv*kGuqr8n2T#i3!R_#1IRlHe_ZsjYZeX3qD{XZ)Ra_zP3cL9m`0A zA?x;_8T_dsi<+Xc`Sv>+?g|w)-iw@ua?SFuo64J8;`dr8$y+U1TTL-Y)t8#ti#+)5 za$dWl=joddb3(cw*ct)meq(Rg#ONpwm3!s+p)KgB4MN@?D%c*b)xKz_I~?8qy1ZQ@ zy*>VQ`!nPY68a7@i4M}E_7~(GnSveJS{=DhIQqL0S^3%;-G{qXpsZZ*bw>`dDUL;tZEGiamv)bgrk#d6Mp2_mFdS-Id|Pu7TvzW0 z=8|=_Ml}2!(l_&RgjM}G7(+22Uk&cqHyclg>jZ1xBbF&HQB4TGO;ibij2t4r zROC^gFj$YtAkAvpb@ZY8F4t|co3N3fJe3Xk8{%w(%^ORFsInXJ2!+Dy)J<60>X3BQ z6W1~b62R$+ii3wmIxUEDxB-h=VF-$&u|C;#k&TIE6x)3Y{dh-S>7ZvE0qhz83R41! z%Tt>6poL~}^2Wc5paIZ3soZh^^{0lU^8o1G?RLv-X+lSdB(WP;VE|f*9 zj?&ko=Xvo(e!>BtaDd@V%5%cE^wMY!#b8u0wG%xe^%Z8DWgX5V6K*NcMs^!H%MG#~ z3b-p$G7y|(=0WQZPdqSHQO8e5?v>X35xNRel)tN(Ibk9Ro`}^TN7cOcMW7Oc_EwL{Mb>nG*L`G3A#R6z&c5w zFzFRFnQ$~gG&bq-Q6GrK7DYBid!3TS>DHn46tkr|Q_WO*$e65FtJKoe6`g5r=V`v4 zDc+iC!8fFS7~I6kOd^ys>^5yyK(lKJGcpR~fSMVFH>8agr8{gNlMWf9H)lkWr>$^t z*Ped#!^KsmoV~$5+onC+>NMLCpXF?Ctur>O3w|@pI{i?v`61=>qnZ|*pgPOzEb=vT z&Usb1^=<6EbIuC0#yaDM(1cmy$iPgP?)u=eyow1h3d8>d6YvD!nzRvSa zUGsiAYbaK0_rPn&`D-BP8m{6;451}p?WZB-L-ZMU8g|cvrZ(M{5ZC=U0h^4rWp16qLAlz&+A_ONvIu)OxLVf?TWdf0s7s44NNCI6_c_UO&{QTH99GLGXq z#p711=Om^#L4ofMk0)j6?uo;wLTnc|q69zR)vo-8V!$OrC?Ul_{_ zo_6QmU(H)Ne7gd;51#P41CL2~g%NbO!3!CW`H2*#UZWd6_4N`)oN2KjvTK)?P&QH< zLkL7e@t@&-lnJBb$TCOWr0ckI@_;MGOI~3)(eBH_Q-i@*JX0Ai0ACYT(68S6Ts~1EK4x*= zO-r@bn?iGEDZdnIJl+zoxobIA?F2>A8R)8WM7)e7nV_|AlVY)o@r0f8z-ysD`A$?& z{43i}L)BK$F^VJm^^X;a*ue=^4x0<3`7Yxy!?*qIq4D70#2V+r{o}VrIT*7@v<1TO z*kYVuL}ixL+-^coP7&0`gT^2?^U4WqjH~#*jTk%#g^eH~{6aBY#VyWeoSRod#PM%? z7B&+rR_RI*S$(i(BR7~?Z>F^B!)YXyCl77G3D^QjQ(Ne7w9-3y+O#qz9*Ih#Uk>zr ziCQ*OB+F4d^Ezqa${~i_<+oy&yEs}^FEdxBI~pXh2;F;EDX^ku_L`T&F{rC_c=&-} z!cO1{A2p`UM<`=u30hy01hRu_k`zaDNv|)f6UsYJEQ{hBib9C}ndPr_AH3m4=-tTR zGt;_S%%|yvrC8SMezmViMyfL*)BNMh_oLp9D1%9!SA7TF0trxt(8CS5Qw%*GacdZ7 z$V&~m;S(Es=yOC6}6wuB1 zUZFRIL+E`zm@}>6&1YCpLuW@7Q{B9u9D_MLG#iJvsGgM6di-oI#c5!FKF0BuZGh)3 z=Qe!A(zScgBz{lswjidCr|(2=AP_fdyYagYC!qlf-e>S7W)DrphH;ZxCIyhbT1hR8 z6j-U)lyI=BbsWBFSdW~)*yYPAab(?mK_+g!8PAk_qqR9s@U>eSCkmjIPwEiJc9lp< zpN%MjMa!c!h!Mz#{gNlQq)C+3rqwM}TcE=ziX5g;HRohEZc$c^;I>rnXFVP4Vru*V zRnivSrqbdgf%yaW5fd2>$b@N%dX1~QZvi63)+d1rQrb(!^fAjdQF$H1+z}U0^k(KV zgct)hi*n>Ht+&d#yxAL1G?LoITgQ~vFD;A~er*jGlAI$Yc;8J?!2q;slH)!K?@uCD zN`i$&2X(s!HvvW9Z8-8O@PN;`gLacR9P7x!YlNC`amD8O0!f;AP)Z$UvjjV$XO|kw z;jn1ZY_(fXpb4r;M4mE33^R+%lr(3h5sIn@uS_c`w9?YPtjN98nOHNM84l zO7g(M_l1`%CfoyCcw7VD!%Mw)9iQKaQ9!zH-TD!nwqH-M=ixw2bX!#dqpS{1_AsJl z8=hXpERdW^6rH~S;1PJ&k&QJ)xa#&L52;Daw+jP^9aL55(Qm0X8bfM(`3>$~{I2mj`IMHPE3If_Nkuvk1 z(T2A`v%)NV89Pgsa=horf-WM8yuN>Hg?i>lfy*pPVWRL|e9MzL{z=rg0_!sd4NY?y zoP6QnhCnUz8EGk09xFa5pky=^B+p-^ODC z1wW@TND;)rS5d*WN~Q2x%ovR7a4ucYRm&b~uq6p+!_CdMm^PyJo2|JC%ywl)FjVb# zNPo7|WT~LMs5mwpUVfmT*EwR!WrsXaHCvRW*<~X3iXc97vA4i(+l&>bvcH)$l8x54 z9jZYWkepUV&P|I22LsJMK;?;UKDNU>`IL&X}M8B@;AEZ`PGL9 z21@Tedvjyo-bd{2mK^n?Mh~RWtP#Q};f9epVX4P%xNT+?Z=bf=TwsFC@!zg^)6D*; zxbwp&mD?5LPQDLwv$a=4qbf!$@*Zbv>Z}yKrD#ea~jCn7Rkd9XOcOZPmSP2gWqaWwuV z#r40|Y&QL(xc-?GI!yml&E}(&<=Jk<>qdJ|`1L+v6%zI3Y3uHKj#mpoF~%WJwl-b5 z6jeENs2#V~;>Q9MT^58!`q#0m#>apz&sQ2zTAG4Jwx}yLY@50Qo z)h500Y+5gPkPOUCO1~_zf%tla>`nTKTy>rDZ^5ab3TVhgnGUSx5}tngsvTzMSHx96 z9bB-0G6TsNl9~y5j_NlPny}wC6BbVbb6kxi(RB+~HRO91s$n}69ia1{6dM1bsOzcF z_{ncXU8{C}8RxkCcZJ4bqOL!IT=}qW`~~ESe%uDaB1kstEh37{MuIHCV3A2-$B3!U zrXXr4*%u6!e{`=D28$kGgRfHpXm!p=kjcHAlo&t?VS^0cyt;$1TYjLDu4@62dw#NN_^#wi3FwiwxD#4qGJ$R~jqN{~>2`4&*+7cX(JvZOJ zbBPu@cHS6!X#;UZ!cl{`IaBjO+<{!iZXO^k#$-_(Lf*UL1i;fPeB1d+AF7{0e_4)2 zrl0bjUf~OV(K()hh!Ors=lCo1SIc(c3-tHDs&jmr5)=RUlqe3%du@KX`sIh52c@L1 zOEw=~hq8XA3$&ooBDxCW;p-!TQOPNy$s{ZEBt^o$j&URIE>a4UMctJY+K}FpbJcoSV50yy0L?&{dIL=L;s@lfua@#`Qf+PD zSMxsx_HU|rgu2xkAPX%#5>d@KIKiJMSAgdRTTfB{_bU6Sv- zg<;A|Z(z1?@FwaW*X$zBmKD@O>yL@|8OB}E;dmjgTh$r5Hn~^&C)`0lQU?E7HNP@o zd|u7>QXGCqW8_$)i3ou!mU$P6_ z|JQ}@=f9XT{9gF}SHkG&+vwihTs-o z;8t)!o+p^b7@Y6oFqrR4m;(>TmuUE%Ccmg#?GK{C|9f-xUx@~jPAP@d|H>}@l|aM4 zT>A~p|1Y+#UyEI1K*m2M8lFqp$qgm3Tpn&nrMUI2*wv_h3^ZyW`l`EpmdTQUFu3#| zW%6f51*xx04BvIaZ;A?ku~GdBo4fh|ZzP`IZ%jB}J_Q-$fj8pkfd3R^X;V+EC zFB{e4NJ+g&5~62@>6z(9r8!LRC@fo;&Mdze;&J6jzEfu?fmyg^!Mr+uB)9dmTq2PhUyo{*=GWU zwZG+w{)S``{jKTw@nQ9|(Hysf)vuSzb9cnplPE~F;_l*)*enySe|}i~e2w1- z=}!LTtByOk9SbDRg-N-cGi)!Je#N3=K^pGKmmSpJHZChm zi9LtEA0bZE$dyXaQ=#*PmOgAMjXzP+0b?(tfe9fDdFopI+o6 z1HX<<|4{)lcs@2g<*|MjAZK2_KOhYMRe)eBG=I4daCj{BGyR)?=6!(0zu#h6ik8Kl z8&KmONL1PNi>y`?Be`3?FD z^PNjz<*eiZ>(i|I@yG&wktt;S*L@R7O zK?O$-poSBHeccHFRQc~80sdQG_gul~@0?7(?W-&MI>O&Hi?706f=!)iV2dsWL}2_c z7ri}f_zUmow~H1i73Jl#Ht>i-H>59rtowN#@GvP`);gFtek$N1Y#si9ud}7^1cT|1 z7`{$m|7xrN1Ag?)TTN8Q3qPh@A}L{PxkC~{`Y%uH)E#Nh_4{Fhr>}tufYY1+pr8QY z0DHTNU%op60QR3uFwF@#*gpUY0ssyH;Y&oq{-X(~3_yo{4uAqWlSw_5!v&nY6qVxq zPD}MipZ@b->jSuS{`bPZ|9kqt8vyXx7a;_Uz!6JmHp#&u*-k3@%4IU^4nM~-KP5+25|pY zMDj zGEph&XNODJWd4i8<(cUF-!0N4SCe5TfEF@zr_R-t>y*DU0hBTNFK9c))+WfFX|#O$ zJ_i0Hz3o4&vzSkX{9uOsZG6aCaUYWPqV&}}3gmir8Awjv02+Qa%mgqjt7IxGTXN@U z5t0wTFOyS1LhZ&X-o#w8R7^L?%vJ(AuRCx6Rv_FYfbvXy`Vznj@w9Zo%zWXgn5x5 zdQ!Ygt+_ltW8pp5TeWFNHh8Y7(rz#fYluzf%_e_L?b3ZjDp#3E4$T%hDy8RAQH094 zh*J*?WWz);vr3rO-(Y(3!Y|3;Qu%oTE?*u4XRXQidEBt{V{M0Ya^wLgk)k)UR};aGNG>E>WObuLd9klTv);=jvD6b2%tjO}Bwj;hhC_C(+SdWRMIJd0+X(Kf zWy6(vO#cD2CZxFxEHR@q==>A~)q^iBqjSA8fVnwb)XL{Nn*>jWE*SJ-Pk5p$^`d^> z`R)Vj@t}Y~*se==mXE8j9#09jWdOf;iJab)J+!wzm3?G8d1b(IuTcO|;FZ69=Tpf5 z+Y|X0(d&fZDEK>=RqqyWyRwzZj1_LKVZZi+Jr^mO`UKY?5-@wXI-V2|potKUzvi9X z8vypf8cpi%mv+C2JRpZ#Zvu=fYrvgZ;4;I_mA*w8ad2}fpH`)f#?P8Nquu>B8`90S z(gGlzCi5$dz%`DB7#UiSyv?Vv+D`WDtmeVlL>^UN>m%7)*PxXFR9K#bV3LWHdmi zOQZVCxCita%9zvgP2;huQp%a5sft1xRQUFXMC6K4YI41Xkt|ZK0gHO`-6vLQB_G!aZ4NFo*_!QK-0|ww= zZknPrsD`498t2dxSnxsty#N|m7Mzw*Snx_gCWJH*KYM40dh4GYn@Y|mH+!leoV>Ef zx$7PX2eNrM$PRD~z6eECtq3)6bu5Lwq>c5&Yo5@RTyk}gw0j~IkLe84R-{~vG`@b7 zoh*Z*yQVW8#8q`c=n_F9*27IjaDUnj=OHtDvx!_GU}q#jv}e{xsme(NLHj#-K)w#$ z;31tdji_hYN;#>0hVF>GekkO=*UP7)b++&yk`I*{(x2j{9hnm777R21r$Y~}ipykc zhS0@+e4HIYb~`uC{Jwfw5(`gxEAxJo#spb{t&(V|0gJtBQ4+@q;ry(^=4_tqWKGxy zo>l?3Oi|}efBwm7^e7@NbA{>(in+ekqdaFWft{_DVxi+>q-)y;d+7eP(KRj({aA&P zAm>E_sWIU#M5-}Nc&@#8eXr5`q7HayFO;lMm|rBglg?%kc#cb}C3*tsqe#66xLT=Q z8PUEx@H5XH6hJ<}7f$Bvf&UKOafT2u|IQoaVyg=>m=s?fLJJOqS4LCibA8?k;goD) z<=fQn3g@{!YyNoc{hO#u9=-UcVT=l?{2?2vXb)e!OQHNDx`TxjAHDRqz03Dnjek9z zzdq=_2{W|7zD<5?wgu=-S5DNi$bUHh8LKa_@Xk-(45njVGA9~Yg*bQJVT8MHx+#QA z@y(Np&F9U@EKy@|2M=7Dd{_`piXB&1dtPcnFL2aU?asgJ@=$b1I6hchY+O}6(7N|z zcVk?r7Q5ET<+y&qD_(e4>2{I`GIzMHD+V_Tj+6?Yd5tpnhOPK4FBgNU%xWNP5D3kdXx8KXtIxV|*_}Wx=Jy#N(zv z58%N~tMiN;xVn%TqLRg&6`F2pAZnosomYARe>a0MJNs3ZS$5UzFpC}8u%}9aFk0n2 z%)C}}sfZs_mZGqWrgO=sLqc;|IA(wbf{SujLt8dFB@GbsHuBR_MX!bcTS;G@ndPhH zEEcP(ts=A4yqej7Pc?fRmCwOt1N;ycv;rCs(YD`Ae$6rWQFdcEJ1bWco{%|L)KyD= z03W>d@U$2DQ<&x|jo<6FW`e{Vn+}JQsPWFd=B1+7hx@lLyJCskD**ruP2*jhZ&|N& zUkNiR?ve1S4D}v!N6%}J6FuJQy&;fW(l77m_;Ns9Qhs|t=N{YD!J7}R*}gaMvEc4k z5W*}SkZrW!?o;$Ov-_Yw_tbX8F(1md^WONA)6Rq|-pTHyGeh3a)Xf`9ydA;$am?Vv z;Yi(&@U+GsgIPyN9?wC1-WZH3Fvo>1n1`{`Ej~%qIrx;_n0K(0*J>%SocTV;@l(a_ z3jHVbPwZ8z^~FxOYi*s^1y^4ajX&8a<5)e~%84>P-d28`yR~EXAm3?s!iD3cZ!GLW z&Hi*${>lEQjJGF;E3LsNN6YWVtA&kPF!lEAMwXqRCjq2@#TXpEw zrp8j}q&-x7#VCZi?!-QrM_M1jw7hkl+kpPOcqF zkv8G!a&*kMr9sN28{zq?2CV9QpxXnuk!9fq>?TYg&7Gp~gx5V3!VA)3xz>PKU0NnB zFp^41Jtn+xAAp;$Ku6|s%s|fUm3*cy0qe`LK0pTUvP^la$j#Up3?u$l6NN{waFuI3 zX}y;qZSv*xBDv)rWK-=>DkrQN%xcfsD{%bsZewmqC*;P$j($oW+~LXSH;uv6{K|gx zTS++0#^P5UdVDncl1aAb0fHUMo}qn7Knj2iR9ZR6y)T9Knu)A9vx>39rRPipzW66# z|2xKDwC4rQ*WnhW-Gi>AvWyz5aJ=eEr`gVw@nXIqD%1azUMyT~)Zms&d%ub4cDD9t z*6l{Lfx?)ZImT>e8tqx2!b_fs@RKt)6)SEPzbVRlL{Z14)q`|9%^Dq%^rB9`j9O{J z%L1RPOS%Nvw_Jf&o=ZGsl|`gc?@-uz5!uCR$fK$LMyIqm={U#uDw#$v7D7=JUE9@w ztX{Zoyo|i7Ear%z?^2;MkqJT9EX)u^6yK3Hy?F6_*&zAZh-gIvre#4ZVR(}GM9@HS zjaS}7S%J|xmEBiwotjz8DrHw}`zvji^XzK{#@0f2t7hf%*{+c&?zBA0LwGE1bx+{- zGFns3G&#U|(gCus5m}wxOy{tw>!Vq&n`l|!!DfCx*eSBC8hFdflRBppPSHO6=n6CV zO58A(nQbHTQ)yNU67p+7p!lqV?M=q8s3SeF$m3TT(vn@e$XN3;CJLvL(aiY?zAX?Ysg)dHm2kdCqqJcMtwAomc0 z(*^I4+%?lB)_!0){X|v9gScEIC@+-G%!Frr|J`Gx?F4Z)t!q&+eF-(s9Z5PDn_f8- z=1Z{V7_ogSLQ9j#!@nOC?5BsB6h&p@Bn8B18G(~i>3?bY=vI5&k{V0pP>FMC3HGOs ztD2R)gJUHb`MDOBRstjAE8OMP@+B1j^i29`gKEl<|6e`sNF zF7@}RntAkTul;tyMo4Sb$IJPkqIbUc3pdN6zS zQI;gd;>rW)VaAR#bg#blcs;iEXnwUs7+B!uvsXs7%HRvQ@~8mUI*DqFND6Vj5`uz} z)&V~ug-vZ4HD`Zuz!urf)jQG^qudoM+TH`%t&+!WGD>rB+lp9Co5bFYbkL1_&rL|u zkv$6J!sCE4350jGqM!mjXmvs5V&|E70Jei?>URfH!*S>$aqbyBzv@m^?lwT+Da`9h z$>@2V_ZAwjZNqb0+33f;O^o4f6FRL@~%R zc1W}LPuSB;Bo4?S4)EOb4}9_Dd2~Qlxo?iWzqgcsC2`;@-oTn@-%7PWfBV3u^1ue) zz&CAy?Y{akJWmnZ9uJg19+Z0e{>9TFwWm65URZ@*{=2RyA)Zt3LF2wb)@`8C@~2~M zPuKQ>Hs*u2%Jp9o`*uYI!^~^R4E;-q)!Xd?kZ>T?gTV#%khqV*KobajW-x|22yQT7Q21EWq`zwmJ~4tHS;m-Y)c;ti8~=B2a{?mQSSBJH8t z7Q&DjI=K6!zcoTrJ#>I5Qimy0moL&#J zAtb@`gWzP6pe9L(GF0de5~v+X*o#R((q!bUB>dqdIDawyhsosp$&~&{7fh3>(UOnU zQ|KL1NPt{KX<$|~s^N8XCfZ&aFew~2e z?|;&j_Jhi0k$*Qto0alGypJnq0x=Sc=l)gV@Gaw54>}!zf$?I zV6xShnkDje^u~B|6dQ6&mHOt`Et_9OT4>Q^einrO9h(#e$#~PvHw@odJHskoH{(Gc|In8Yss%%L;{OkOZyi?Uw)KH7It2uzK}sY96e$T^^rAyR z1eK6RQVBsR>0ES*fJk?DsdP(scT3m0FIc#@?z8u~=X~FHpXdJVQr|h}m@&rqg=M`& z5uyi`?NpA(e5~cn*k%}O19sr zf9B8`*)b|r?OhcL;+piCA=u^1(rrK16=!6GP8!sp@JJn(2o>50Cxw7W_uBL4)F_&@;yCbDob-Az_>;FBK`$s!!C{J_vDF|uLk=LVh)#Lq z@u2OVn=it!f~Z{pI{Q0;Fd4%xjF?I&gE+OV;S7isbNum3pG_`ZS?h8V^iXf7L{X-9 z1+%G3){A4Rh1c^`NyqEhS($E;qy3VpSj-N#<0oxVoM`6U^>-w z1~(qCI0u$uQH%SAIlozc?Te=ScmKGr94o{7)Oyl(B@2jcZ%_LL2amY0b0oV*19%12 zdc8;2h`B2bo+p{sVpp5YO*~&6zZ7H5LCIgcv9OTVm*OzN?6fkVi6O8Oz*WsOa}4+f z!B;4BFe3@lLtW5DG{->JTSe;99W&Z)LS&TBCfu|uZo~^9*>+QT>PXAUc@dX1O!}}} zadi-IXjwhdAny*NaYtjgE(f|}F%v5UFBPmE!2WSJ5Q<`nIwOpG{r)9lbo0I%cm(MU zs2h^BI8Fef_?Ny3cC4mzT=mpkd4`yE5XgRDH&|h`C@otVb zuDbv&z}1X;Q7-CfQwqJnQyIf|V(z8E3-6+>Btn8>DW2(nMWdX#ilPI@IN@K!zyq6~ zk8$2XjQ?oQ=-e^>>)M;yJqtHH$#QPXgvm2&qNB~rr`ANI`5a)059*P}@cp<47Px4B zLr{|b)Mpy?2%=>%(I4`_YCG53v7$9JZ~^@m(oBBGn{y5@Ft*0EBa`4y2(+}68D+OL zkPsczbWQk8ah+n!X-?Ef6U)YKL?u9TMN*|md81p`Mzs9%g6#@b2X5F%o;=`sJ@BcH zUyZi24zh9SnY#maMdvse#4{Z$hDV?nC%n?HAYp%3Do)J>!Et`f89t!6mldOQqK@@0 zq&n6W$%$S|?k2k8W1+*9ds-d{#cW_wjM2^}=FBaW2@s*G9<_ob7C1hD5{Wp0)L8Dh zn1eLuKD7c_@HC|(U8%Wy_$B+2D?uD17Ve>Xy&>AJT&i3mQ7=BGXefwxp#}L_jl|B~ zx5AwskG+0!3+k;qQk@vf%hn$i2Q|5r{36K9lEyK_&C30aJxTY1+#AtTz?^PKim%R$ z=d?g-Di8Q;NPI8H{*zmLp zP(+I@cfI2G}mZp_xg z^hAW(+?*e^6=-i%6KH3L$AKSs^!Jfx9^L%N{O%~%6ER~Le$s`l4vAJ^vc$apPGNqR zC{qD#&PV2=@*CAm2=c@U53P$gyqQgkC+qI0LN>gaP%b>zkx+mS(G@fuHuokKEwzy3 zE$r8F2OGtB>Ub0lPh5@GDb{!wBbyO1C#v8Efd(6w-T-@umYUCjd~QoH#92wtC%p-c zG@wf~WKivhjQ2ucOi31;Nfro6Ts&nV2uK8_7ueo=%EMDnqWKu>e1^q13*P?WonV>~26o{*!@5tQ0bJ^IKp7%h5hmqso z?}!l%r2M%#J=+jPB#+x|aNdyVya(E^DV)n)fPsh>U?7q)@cnJ#!6&3;{PgFj!eAsW zX2_X}K&O^?E>)6y=7IKm1Ceut-iobz5@Y2*5qkNyUuT;{o@-9q?_B_d7z9RXDd+hC zWbVa^FfqWXrDlF< zfIy`T@TmJ(>o4}&OsM2@TO-QXDL6ZkE&)?8d^QF3znp^d9{{F{Z!7#Lg?>Xo`48k8 zzrLjYHn8E)^0TOA+gISu_Y1i3%+|Z=mt%YIV|h0w`8}$5{_l;=cm0Av`1!ql`lx6; zTd(S0kLkx=--ze;fc+mFlQhqqZx`!#MKORwgb$Jj(ZGMwHEs!3m}B>yra|EkgwC%gL~Jc6G@ zmEao_{cLg{gWkf){OidbZU~sD`oDZF{9}^XA9f_eUr#RVsolvtD_O_H?!6=>8N6s?|B(IvC>H%4U54|VNajZMQ?#Ju*LTG`Thl-A_(f5zzh(db zxg1Ajexzbh8~MnDMs(wBSS4oaK~lpiNW1?o*#*Ffom&`BTQi!)CDCpoxP zKxi(I;KqGu5aiU+?ZHGc%@>Eve?vfM)kX|(hOp9)_u-Tni}&OF4r&6P-(GF~8T}bK5W`-H=vWg=P ziPNT2j58Ikz4u1reB@iYzBVNZ>y)Y8NgZ=Y4v@s=+0olBd)sIh2yP-^V9Qt^T`uLS zIQlf8Q#4#wKODoX7K~EIC3|@;OYPCsVWX#}-hs+H!xqh#5iY8XIq`+$d}J-m&lMrf z$lk^v)G>1!cjX_^s=s5EZ{f~V1%V4CFVxVVl)f^01LR@+Lf@UKD4)%d6k(VR>T4C9 zJSAB)+&SfMf_T49fN@oyR?-Upc|Ezw_2>1Z2>7>fe8rR-75pU!^=Cq<1q`6U@B$?X zV2!qhnFthv=K+zNsh+b@bRmH6H&%)G+-nYb&$*ZvJI@2c?2#8cFIe1W`0n4g*mVKG z2dBilpd%UxK9)Jv7f?;mOLG5CH~|762Y8d2oxRCmU*BXEXZZCm$WEja3GSTn3J(NE zf^Ls*dSSOVDFuV5%N^n9^q|1mCg4RXt?Y$ z^X;4Uh*3`paQof59Xn%4C5W-mDKRxJ~`*x2xjj<<<(T}9Dkt*cK3v&4z<#!AHm zE7t@{e~!-5=xep@i-;Qb@FSCMVC(!zQ3k1z8&GCAw&`&YN}ckAm=*q39hg*fenJq> zuY1D%tMNN(FF8%>sexlJzLpO=RyDOVW&zRN?{yUb4q6SYfI8?Vum!C_r*P2oGq@|A?T*GQev! zG}+orxG-ADb+SV)1<+pHxRB51ho`Z9O1S``2LCa(Yt?}-F8}$95wNK7(b%*F15YJs z&h_jPf8>W=#<5aw~5x^KpI~+(HX($Hb*q6`x zvcbsqSb@*l`Sw}Z7`o*Ud77VIUT5Jd8JdAx$9^kMqcx2CY2a`JRO8&D<$$t*Ap;F< zRACU@5j;3M7W@jJDe;Ayji0u!8S}a1wS>LUZm53EQqK?BAjelQj7F0>xG^`e6-shp z7V{gVANc5BQK`;G^V>i8@hKv}ry%_4Q=WN1<3G3(0K@#nlLJ?a$(2>SPMACIU27CI z7aJ|nH%YOx3H;9w@~_A8t3jTv^M7TKU!&xIaFBmZiu?c8Apd$Szgo#Z%=iBvuK#RL zex1JmowF9WRZpQPUT~)mE7&h@)t~qS?@##yN0!j(hEs3yYx;pY5@Aeeg~9uQx-CvO zug>BZ-*s$ozGGZV#+Xmv7Aa=BDO{?U;us?raXV!2<~%r!;t#Ng`?)GFb)}+q(!X6s z|4xzRxUfgy6OlZjqIBeqCFdP`B_DpZLeOB5@ziKWnf1z8iPL9-Ro>!_iF$7u^~~~H z8*`0JGL|GEJW8)x;`IF6UY1$Ujnp{6`dBLY)}3~qyi?DrbN630c6|>na*R}8J)BEvOo@6Y|Ilp35c32UZ$9W8_^>oD)-B_#c>`4 z3PkaqH1R6&ZcJ9m)E*4EsE@s`HbEwRxJQ#8dlkKgJoaH3+?(_hBp{v+;Gjm+4wPb9 znD&>O^@w*9jGr41!PNDf301XfoC$m6hBh0n70N&o+(h>0gx}G|RgBzCJhSS_9(WrU_L*Djir?MQ*D z!3wBy?aU9zv}K9KQG*>_3TUrqfk96?o5~Tew^nP{*)V72-T+|LXI@%#z7Z5{Hmlrd`RUD+IjP9V(_+Z0p>>q{o z9&FVKks9ZxT;N*C{)8eEAZ(Y}VuwKt%AcaBgx5cg0R{G3OM+CpKW`1lyS?%-CZ!GTgysByPd^$zWB}sb6fJ=%*3^F z7|Vj&;ScK?;qwJ$_+!>LrJr$ozr zf3J6o21glcio0_W3|f9yjc5y1%FiX6;}jFT7%KOaPU_z1i%u^GBrLPRT-Q;PyI!DV zY*e-I5jVuEI1aJv?nDaxCol!n4|sl1kM}$pC}Ddw*Tppq7pRax5GnzM*lRBeh)_up z*Rx`dy)Pu-fS9hKW(+dOX-aEPriW6OA8WSTnv_eEF~QgK9GLjoug~tT51;q^gn3fehz<+NhaRK zp0N|$VANnVtC)Z3Jr2jGaO+QlMiTqio>1I~7;A}ccHD2a2>fJ#b|Z;r4dKS!uCCX~ zE=hc{x7w|{KF92|=<#ioz+_+c=Dh*+jIkjt%Gx(QjYXE$7rNsN?h5sX2JEENk9 z#;SLtH`$Z;M^a?n8N1`_f|JEK7NtT`KPB*3rpOvEN*QmEIGg2(Eh(ftOD<8$(7lwX z{?U-?6TWh;UqPA%ztR0pMrGsuR~fp-z7LRukX@dbQfab79%1C(bKbI~bhrf3FtCEw zkQ8Qn^ejCf^bRjH3&?@`rfUyc_&Y21Qic^Q3$RJzv|)Y7gNMri2}=&PMiS&Dg`^wa zYaZ+^-MRc}u~DQSH*gR};!;>tz%2Jn5+_{|g%@K#Lq1Y4H~~Mb`2FiP^N^?q6C_0? zeK~&5!j>LP-`*|lwQLe2iXs>&-6k&0~jHd)3ERvK{e!G!Sm?)nNIV*%MyV1PR&HqPLm7 zLbE`DE7ziKT3lZmBvr@tSMf*^$^l97;SeO*)UvYVcs(qiBre*cq_xWOYYm**DxILb z!wG?6uxUHvKc^HUfCM6CPtzgnHwwD31-yHr%}BG~BvF_v=+>fh4THNG-pMq$CK~4| zuW$>(!gb-$bmE(9;a6_*??^r0H>tMJyciyda)-J3QK# zNBx-!2_XP>wS(h0yE#u)NKP55=aeCSQrV{Y@QUIrTbQm0r2lQ={068B{?i)p_cZR` zxjCi(0CqKHeg`dF1^|P*eD~LBO`WSO0R-5Qj@h{G@g;S?jmuvxL0+ygx%Q=f)m45r zwny>ot=tR2&qSSsin7pS@Gks#Gpp?7QgUaLCP%Taxd#I166hK>hy}C>UwAfUOutCs z&kCvD-*K-5D^7n|Nd1Ciz&)~tCU^X69K&Ce6=i+lDNd^+?>+GTwXx8tiwd(v!BQU^ z()$?cpFnd_Yj9`n`2UM-!2g;s`CkdO{vg>WC#Ei@rWc-}W0HO&Aa%bkwsH$?sM^MaSr-trQMhE&WqtAzASz0TjY?v+5>vT7~zQz~$>7j!BrHAMy3l zH|hZ0{T%B;GW^YY+OQ{^>ekUdW2B60yG`UYMLz2AY<=JH!GJ&nDiFJ92%TrK`%NI? zciSE4M&h6Ro!F(=y1E|r>)6#QNctzz&183J|9X#-YVAEvy`I?z{Cnlmngm~C7x0Y0?rRdDQB$-KxOz8u z6U-#p&4$D(v}MtP-TES+l`iN-UfV5F;XEPkdt0AVVEE*Log&`BTb&X#E6+a3-DKYG zQoO@o(4!>wdb>yU@rq@i##82qg<)@fl9WB(?$x_|ywmg4zhZaLn)PIN%3bzke>SO|e{!B_)P8@w9vgPF)|Ykr zcz1}k>SS+?l|LmGBNl`LscyX?ZFS-px$aTRJzXmr_?iGk{bj>ZPb|h!rmB}X#<1S%Mz6g%_4n!5pTlsy0NVYpOCN(BZ z4&#%3dA?Jv1SR)SJk#};G(wSjPZc;9_c&aAn%v!FG zjrbuAA2nHQtI`9q;w>|6eYd^=Ywb1i&F$%HZYLlH5i;xnD z!>Q%Ja_XaX1w%R;rFe45k(45-Ic^A8r{1;ZY-JF=#UrFF(H0JV_&{#tYIi*DcCsg_ zp@MIzV!}aJ3U$k)Yet<|X!LOuk3PI(i82g_D1gFy9#ed#k9B0pWKGqRPTPwi=`D!w z$uLx6RGT|cF6j+PdB&e6VwoymxtX8E8=}eqoAAn207qd8tHKL)c_Bh;FN=>0a5Yi4GHvOE{r7 zqR}B0cV&B)e;^#DA|g55MX>AnB7uY}pm5m2Fr#ERn&jE*=HWTjd!>C!CRSX(!u9phfHA{+H5L6N3Vp;-Ci1KcRb093W3ZDdOvS|>_@M*PdK&Cq1wzMbFW;VZ|cH5l6nq% z_Ive=sRM%hpJcJNbp`khEuEVi4Q@uKrYYag%NXoQx3~PH3S>MJ&&co52Hm=e23e%T)zGJYR-2u>TGpBo@<0xD< z5S&Ug*S@kb9PGVH_XvHEf4h{ zo~9MM)uQ)kAgr%^nk(#i+vB#Uk$FRNEcN^C)>zM?u#e|)Id7HH#wysnbzzb#vg%G^ z*-pKCyr|sH(_57JE23@5BL(Yx!8?J=+9k7@JEd78t2R}3S5y4j-rF`2L_MJ$M;dFW zCbeI8XXTqD%-XBNJK6Ab=bO5+w%4F$zZsUrH_Mf^-*)%pa|8RDdgnP}^*iD~94>})W79hkK%DSA zgowEvhybpwjT7DnNAx}J30en=2B*vYPK^CvG9rPAEoV}0$4ESxcO9IW8ur1VuR;@F zg88+8|JJI7nU&gD(LTPbA~}5q+dv6b%GYh~>-S*4nK`fU+gL|)knCONq4>U(nfdT`#U{J@7siRO3@84ZL)bqQ3(!T$g%Sp`NytHvtS zfWYC1*Crr|>SMrFqo2qj!^I*kcOXYW-8NLD9^fE7Rq^dYg?8HL-|c6Kj_1QDc1Pdm z3)lu{f)LZqFfzFXcEQLH90f8cqWBa#+I4i883qRUt_DN}V+LD+5>Aan%T)x+_b~$OH769Z3NS-pNJ+SNoxl`*}RYIJ6Pj^x(G6 z_SY&v8r2U{-p9Uq>xNUY&w~`7M-e_6jXs(KA&>V%?sM~lv(eC|(eXftJCp(O^t@Ga z$b|bCWR70Z^R{S+VOK;0)5fty&_MFz0U}fA@Qz{0L?FWb5Uqi5?S*ik{qR8Ih*0hz zhwx_s3PIgO(CAxGPd8tW2*mV;V9ag4DHZIh>qrnszZEl)s&^o@4p$Mpkj)0Zg=7$1 z2l@$4$lDIA%nq!g>qv4P*ij1+@b{w|JVR8`eD4tlRY5^&IBME^0eFoyEEY*z5L#T&J_a}&$!%U5;MHecMS=q< z6hU8acR=pqfZ}l!&~eac1|cVMD#=A?+91&fv7nRrc+6t&L58?s@i^Ypw|ob0Z!h}r zh%p@YMKl^D)R*Y=(|gTKp(}tug*{m9d1wWwAP6N=@|=jcV>ln0f0Gch8ag6sEL!0@ z_WEA%qkJT^b$`fUV%Q;M^#vm1KqTb|^EgA_K; zh_LtwZ!2rN$l4z*TdTl2NL3NkoONO?8bGIpSY{o> zX5Ucs0zb+Q&nV~8&9NNPi8l&7Rq`3@sxs2YqEJL~1n{(O9 za@h}aZx$QnaggQ(b#oSUFyQJEMb~i&VB`}C;za zDic;Td(mW;&cuGG$T7{tfvMQZ$aq1wc&V<)rL5S4x7b&$*z2&^hqNTv&N$SrIK;c8 zC$T7cs3g>>D2B8&-iWaIR%xPLsRdkVa#?A58Ns_D`tRNMGnfhs$Q1sIj`D92ZKs78 z#d)vs3g5pb1w`*-CuG1WAi`4>yK2ZfiK8MD#ky)hRS`~J`s^8vcfMBn*7c#y5j!>(K&EnSx%DK8Km^W>b^ z8tb>q%Up`IGg`~8cm-4Ee`LAuF!w3Tsx4-HdwE^*CO~$zU*35&meg~(3Z{1mLT(_l zciz|yaXPtD9Db@AMe0-}kUZ`Jv)qleCD7d)aV0Y>er<=lDmvj2drLq56;-LL#yzIM zd1|$*bwnCo#s$S8zO1wQBhqX;D(WiNrS+zixMjA;Bt>oqC-_OBD=N9k2kb@%Bg@Zr zSdp8|#|5iJhFu9IVGAY-SLGzU5|K(=5C>k9UYM~p&8$z1ei}*~5`^;3nl8W~SG+4+ zF*08}NV-z_s*(FnM1a2!I!ZuX{uT7AudyF7EF?g?O6Fb`Zqus8+o`$+MmXadGKxk= zdeW!*7TT%{rKQ3a2H$CYBuP!qwoOgR2OrtNeP3we2*k4_&?)OWgEey_NTFDw(bR7z^P&mrUrLjyksN1x=~FM?$g33~5m>Gh4b^*_g75nIY=L?FOVZ!94>UQfJ6 z$a}NZp2u)CnOC;?bI)CevW!#%7Gm~Bp((4CwA@J2jautUpVdUnu>)jw{{ehW5R=UZ1qPxDI=k87M=PqPO%-c!6|NOzO zzTa96AO<|0~JbL&pcS2rBH4lIm!Y;${;OHT-Q+m+#SEEoH z+4ViXhj=A9VA#Cfju(AmifFH9!BWO{g7*zNp?>X*Ylri7M9)L?-O7d<|CioEq@U+^ zYENc7AHI8xtq#+Id>AvnE{dXvF=wdwflfi&QVd@XcdhO{I?qM68qauwqK1zwwj17` zOX7)W6yCFSt@|7)P~utF*TKIu^?8mk@Cj_#egvmJR5QLw(CJ$!v1X13*r)9tRW1`S5EZr-|l;9 z8dbQI=&=4AmaEHiH!?3+Z?gCK9eI*ZUI$N_aqjEn-LA=ab#inSbw!9t!Bg^iNR$32 z?iv2hTU)yCoTs_*&>{ZLmF=3j1nR5A1*yez8NsumGxHs;UjX%`=MAn@gp~lUXwJZb=I*wD51^J^{*?`VQ9@( zD4R1%^BCxcbz>B&UYdT_6^VuMT#!%a^SZSh7yciXCs2|yYBH8#tNyx?f6Fg}b z6Bn}z9a;^C*!S*th!*OmRv2y-M)f;aDqHy~Md?*%4DtuX{2>B6ep?T#M3zC*LUE!lHr7#hi>y8ITg)p8pOYP6Gk|R5#ZIVa{I5te*N$Ko#?lgV)JYynyq}`2E(qL4c`@~^bC+1~DmIT?X zQ&YLD^WrY7r4%z+((PU?K9*V%FOC0u>^7_(9(Hn=VS_ICOLlI6jtSgeBNTg;0JQG>0Vw+m7O#21zDbmKDp3exqY zmsE!idW+i%3^X#9#EVM%s!nvMq7H}WWq`lix@uK+II`|nR6ZxYW;=8^y4O}zx!byCe|R_s z!Y-~xky&>pJsL-qEv_YOTX*9S&rCCR@^UuWd85>}ck?e@Tm;%u_vB>1^*TN1Juq=a|Fjk@8tfK3Uu?Z~PHzu`EcJ zL)%s&@9~11e`$A;%yz2U@uEt5X>U>6b|`d`QoRV$kHKc;75tJ?FAOq>l5ORYUa^Ax z+^%m<=2UQO0k5V^cxyE5)%+3Fi=wh|6d0tI^km&b_Q)eNey@)AWCQA7K7Cboze(+6 zGrYZgmaBcg&F-Xlr~_etJoXOL5Hd>_}n$}LkL#1eeogP?Yw9M6mwjF_<$pRlVO z_DFGEbx2`*%R~<8Tocf%7aTY6G|LI{-`I^lz06uzTz>~DjkDT3!v@p9u$CutK(X&n zvX`>BH2c=ESl9qX<$13)PLDaxMO3nfRt~7)PNj5&7rC9_YX}{ZoIZyT)`>WGa^UP} z5HRfVbh8UHqH6QgIlt4zNTZ_y_r z@eihhVWUjz)rjx$MQRF+UCnfN*x2i8am21|01bvG8y|^&G#K2kZ8n@X#~SIA(l<}t z)^j62OW4U(qjnzUKDaQ(r(B7%!57fZBiZA}9L4w~Fu#CSJ6}+Ih%8@097h;gAgWxr z>61teyf@E*L}t^H$c4FMGs@}O+ItT4BO`LX(3uN3$d>?kd1AIQ-#L4&>7OkBivvNc#8mL#7hWdJTsR0 zW+58uHb}#eCa(`oxfCY>P36d8gr+cc?|jkKTF(C3 zHzy@YMVC%Zf6#KftcU;7LlS0@FbPSe!b1HeW9v41U}v%0qjxe-7m9oYZ4tSclxmv8 znLdzfA?=0i*lznX6AW6l0C4$P_U!pc*2gVaib172zT28cqsX0JB@ zYBEl-G-Z9w=J-%>MDP~KpG3!|L#@uKPyt>8j5vlugUbGTc&69E{Qc-*PwKdmU61iB zi}Hm)+da718dAkO8cX}THY2}no066*S^!Kf!h}w zfYP}EMoXttxN_lVcHggVUm-7coAbtk{#B2DV$CJVLgBHI3%K(&a!Qx#l^;Zs0k?FX(vnH}&SYOMLq8C|wi=VNzHbGCloA{znQ+=DK=>JL{BJnqL>Sn}yV`F32=>YA$O|C(G)Qdy_wk9U5 z8ti%nutguGioN^=TT|oe7H6yQq<@r~B67|P9}W{ogcpgKTh5(kpOD(fGlUk$3n667 zpZNsSF&@lG9X#dTNt_Jz21_Jq3X6^QX#~vd=Z@$hphjpz1lb}YoOX`1+V4ETTE}pD zV6vd&gse0m7drXf^aNPCY)~9PjRhJGU!s4{G`7YW`HSJhss8{LI2<4<{eblSbtU;s zVdpggnpXa9UUEaMXb|J2R2&1*BpFY};L`lmp0w|kWR3S;4+jl3@B8cFC2~LvHHUI2 zFq)39T2Bg>GAwoV*!3|y2(xEJjwyvMj=gu5M6PuIW^Q)vIl@dccag?7X(D&BYo+<3 zU2#F-ZS;-fgIx;B%`6Khg)45!rb`qZCPk*66%IEsBZoB2C(bK-RH1_@p{R+(eUdiV zRPqjq4g$1%ei4lO3uYIF_=^K?$d+3oQ6F!wg;hB3m}iBx7a5ElbNoDUnV@-q2YCM2 zK*dAPPx_r(48_rv^KPpim>25Gxq~!XonTnAFB<=@rW2Yt`4?#-L^X0nj6!AwH#3JC za-7}7p)#A#ss(DBF)|f^U%7pg^`Ehj3vEr|SKu33O7hN?;7_rT0G@2=i*ds@EF`%l zi|K~~`!SvHyzKRlr!*%ke`{a> zVRt6LkgL+33fMLM?p3iGWtFX&>$)H+-NN=0IXDwE^JB^XxL3X-hOx?%zR}1R*82p5 zXypUXQEi_lRJd|+%t{r19v5`s_`8TE6_Ceuwaq(|$K8nr6|GA-Zs$`={0dX~1+C9jLRQx*&r&R_VHd}}B#I zGLv$dHeIxWQ2;79=B@QXOj#tFC7g7Gpaf^C zUrxV|`%Fa3@9gsZ@_ktAN!KT8+;A?AdY_v}ni>c6Ur%Iih+q_rIdwPM#e@d9J214K zdA#|KctMA*2VY!$|C#{qEzfYu01J$!Kh-kPEucNRbmPm$K?J`3S`gfIkUJ;?SnK^i zlhm+Q{)+~E=jB#@x7+_2Zv4+@<-g3%LtsK=-xdsD@P@$+eK$Td{=OxEX@UaNNUnlI0&l&(X2pB>l1M`9d zI{xM z+>pk0e0Uu*hs$gl2Ypq{Oh>DL`&j!*KYgIPIAW-UP1^PQNVqGvVx&saKu)`i4kHN> zY3i>qc&3h*pQ+)&bph zQ*iamOJvvhtD@N1QJe>u%8i1EfstmMdo`S{@kF&a7R~ny_^Ud{zkaONJKX;10)D2! z3pDQ~_zmU?8IMWr+-yVDb2yZ8@d_;Tqc$}8L8JDa+W;`(u6VySFTJi_DtS! zJ81~Dv@u;4$}u7gR6ym-6rwdmnJ#F~zC2dN7k3T+BO!~ZgWf&~=KZ1x{C87yxf1>8 zW+J)lD={2=*&C|uBn7=l#skcQ3E#)`8+C+#lZXB*g8JD%MFckt0w8q2yb+wrM$oTc z2IlPoe6~A|qo7k2>i0Vnu&~1foM1132!WqAo?6)HpB@A#7}O7J*2lo^n1np}mq1#= zuc}VOb9R>|Yt(m6-~u-N!0?JDUW58Bfef>Fs*(r;DLKXyB}Pq<9}JAFKiB+b*vSHK zi1fit^U0vy6RQG%qWR$y>UY=NGn2}XpvxdKV04{l27TEYz>5Hz?)zpJ*2kd|aV134 zjV_j-6ttt@KUpNojr|yS0npjy3Z#`_V3EgiK~tEj4#$8)bWDL#wYji6YzIfsf}LLz zA2(i0&V5Mg1UNpT<6MeIe5(?Gyk4-C+((P1IGA@OJ5dZxoVNe4zIRO4O&tFTb&!h> zzd}L`1wP66BVmTSI1;z|+m@TvGwhAyBsf73s3{uym7XT$z>i2t5+V9V%XiS^Pl&Oe zuf+`5`h_8nmkmBjvwE#Wy2UlP)>ZU1q|TNbA8r&_Zh%|=#o!n~A%X3XF-Y+DzH9XW zafbuf526I{`XE%wuL>tMuMl8A7j8t{&{HX@G}r9$?3n$y-s-gBV26`GjBoXC<=*SeQZte53v|RxNhK;b9z5r0Kq}w zz|dHJ=R(kT9ozq*Epi!{4y?23p#HH%E{;k^Zwy1m^>zQ@| zC0r-)@#w(EV*+YOM8FeMzNWab~nSHGQV!%#O#61R=M#;c1og+?Ehb?!m^;4Xh%ZNM`7)Y7#P z=*ltz-wqU}087{Fz}p=Gn_AK14@o-p(H!)#kUt5{3Ho}Lc0CmT7CIst?u>9ymBfkn z0^8dP2TUX7X_df4DQ9L&0!47#iGthoDwKbt(3eLLj`U;m2Dz(+z0| z4g+|SR?9V68fdy78cXJvj~%gl0D9YR(`N?X!9Y z+t~&b=5FUJeM%L=1N8@nG4{B1A&(-;24vx40y3k%aVI4t{BEwBWtr!)V)r-3C{6 zRv(5dXc5v15P4;<7~1}BHF#dEW!oc@wv7Hf5nMQlFaopZ1&<|pai73PJ2W#BfqCH| z0^v>u0`+6gHUi0{&z>{8##FW>@S6M3lu&1wCGcoA3vgQg)$82 zEq;?(v;jxe$~jPBr3Gby>us?GW3H80$TTA{sEpMB+~peP&h;pCgvBqwpXX5G@cd<7mRe5rPw^3=sPcDl ziiYu5SfZ#CF1X4N%|{tCSLJcgui$(HrMFncxzhUSYkAVgBx`xm=gy6KfBZ=F#)qW~ zb;^gkH+;&MXQyGxpA)&{EtE%wO3vUULJUgBf}8Ns`!+7xG*nUa{!Fm)sW^p#74c<3 zUnIg=sg(HW_5nm+sj7*AiE;UF^&s=0o%{qZS zf2+ktC&pw|D0u%-X8GhIlXV6Bp^;4uF7L9uFGaH2e?CW^hsxX7AB%UfZmv;YE&4rzefxY-B8I z*=)`)A-k#Xhu*E{h$O%##|)3;^ce)nFW+nthAD5E2$5#6cd@ayM)T(ju0(g+ittBw z+dMSheynznzo1wBDS2VveeZ{y1B#DdTlE>fdTBMJo5jyLtY7w;vr0#ArG22T4rVhL zW2012)Zd^`kv43am$5hOeYI_G%1_L1Z`$e}MbV6<`XjXlTI;s`IZ7_fDFM8XuqP| zimem&5GWE}bfSOIa7Uq`mVjW^g$3Z;-P6Y*A^6~iSTg~BMvp^*RqYPu1I#Ur=s!^7 zZg_C9YvBfj3tiz1@Z^1_g&)^1#GoAD#iiJC=Ol;ha?`rE`Mx{M z;KDcxb6iMVXizxzM0x5u{hp?)kZ;?F-JT8beTg`Id6yo-g&YX=;7g!JDS-&FZ3g)H zB#>S46qA_U2qcQ8B)#g>@}L^GSzS(uYZ$u!g3qg%(~}2hzS4cL+n#L^^eoI=hLyF{+22l(CL7;b0dLpNq zg;YTQW>~^-BDepuOAmBEg-l85Jv5;gRbb3}o#>OuGxr={ou@vy%Ht~kZsV(9QH5b0C} zYeQ_c1d9}YV=P6TQo$q{r6dI%$oZC66Q~Br8Sen+^2guwYc5V?eNnLc&t{BX=eV8mz z?^%^`{%aENXm_p;^Xt@B8?Z5yk33gf{(WM2R>c!hyAq6Eun1AWl{Y+2vaD7PQ9dn* z@4T(ZJ-sS1Hm(g7F+0?JS0w&76xK;b;_cC_3YNMQnFcoxNDPAEP7F`|h;|=PR(`jL zxX>&ubMsv7CKJ>Kngr1TtCsR@)&5Ys*_f#MkH@1oS&c3EQb(AIr(R&VJ&6be(Da6Kw|OS@-jC0GQ&tYo6>; z(k=SAS8sT|DWrL3`kj;b4=}!EN;$UhA$>!-)t zk3-^|_l9~djBfBy@;8TsKQh+2K~Mq3ap}LXcmmFYNg+FwUrIurKM$k>Nib#;il1u8 zdfq`nbR~K=|Ivp_o?xW7TkDgTY|tOp=C21aNNWkr5~)IhyNk~U%@%%-fFmTFZbLWa z>kr#;<-4C-Q)heHnf@DHx?fhFTh+hVeEr;|^A`NtnI;$HD!zTzvYF##JadKP=xc80 zMgO%c9A+Vk=JOM&;wYDf^X)r2pldAg^( zD-g}1ClZ@dj!#t6&hkMHR>YyRxYkS{CwcT>eS35&==}8G!l~Z7bv`b;l07LuYQG|5 zv&f%`26u@*2!@OSeWc6wTyaeJulo0H`MLF2FWcK8>B(o8*6%3j#g^EbBbgQrubP1) z1(z7!F>o^gMdMVpNLMCW>Vg#lD}hv6f976CRK3?96=!|)zBa>4{O zfdi=E!*_4wBT}&quz`mGut|W8!zKaNp~|=h=u#k)gC9I_AOM;d6O;>q9~eZ|xCgSS z|AE61)HfA0$Uz-baRv=G32pT2WglsA)zQb=SHc#Nx0hT~^2bQ?QnVc|!2F(-J E0ACR$bN~PV literal 416094 zcmW)mbx_pb*T+AsASvA?v2-IK-LW8`fQtwSNXODhDvdNOB`KXt!_pz$E$GrIA|=wX zu+R7T{deciz4x3sbI+OgyymT;sV*t?p8HV`aP?FK001xmKmY&+0B`_60ssmC(Er;7 zg8>K_fPn!x7(jvn6c|AN?B{v5(1zg0Q!IT!7u;<17I)!4g-)d00jfk z|9cb+2Ow|&1_$7900{?BZ~*{!&07n8yB!EH!=>LTWqW}mBfS~|53P7R& z6beB9FDEb>fS>^w8i1n#BpN`W0rdYT3IzjD2mplvP&fcZ0#FnHMFUU(3|6o5g&Fen5Dg~6b37!(PEqF_)o z3<|)ZU^o;4hr-}cI2?+ELs4)j8V&`JP%sh-K|*0jC>#kzBB3ZG6pe%eC@2^Og`l7? z6cmnvB2iEj3W`QS0W=hhhC4G3Jpc0p#XpY0|*F!fB^_NfItEW6o5bj z2mp)#gAoug0tQCF!3ZQ6fdV7YU<3d`fFTG71ObB};1C27f0KtGE7zhLdgJ9qg3=)DtK`>|t z27qC}Fbo8Sfx$3v7zPQ$pkNp@3$H3qiI2?n7V^DAm8jb;w7%&n8L1JJ? z3>=9;A~7f=293l3C=3{dfuJxj6b6pMAW;|;3WG*r05k@S#z4>*7#agdV~}VJ3XMUd zF{~IuUA5N+DoU@^L)eP8tofN;jab$}-)1D4=Y5UWs3_-Hrl|Sa z{GzDcWEg(HF?#fS=}eJ&$`+$mW5vrd?L4h`Evi5Im1?!TlVfS+Z_16n={_O!u0$bh z#~t4-L!FoF9X1=}UKk#mAU#*-;$yFzN20hya?!&G>Po|EQ&#nlzV+L~aP}9u+HDQL z#xtHdtxZTZY)$2>#4_u&BmaCaH>fn5Y;QXFS!XrweeYLqX;SUR{_qp=?(cfkCtQp` zj-=c6;3q!wPT979o8tvfU8m4er~9+DFMM*p-g+N?uMWWc4E)-DbGkQO`Eok2>+bSo zeLV4HQ1|`q_1}Z(>7Z|z2jGFrA{d+4-Xa8#x%H{d)DydxR!#h+CN8mRQAW-bmiF1< zjBFB{kxcq~@1s}}>@E4IW6CX~`I7gxqWOoeEn|g0XB5VX??Sc{Bu^!+5)~h~ixZT{ zrHT{PIiq)y)kOWQQ(npQlqBovOO>P;+D8BS0`>5-Nw-Lb5b$Kf^>#CDOEtCloSOTV z-PU{Qa&w+cIoN&mHPk4}^*PP_of~{fx0e@6t+iJW$SGZ3_*pb&uMjRl|EDO~Q0q@g zf~|B#=@*ZfKc)HJ^!sInU$pisa!aKVh=`h-=}M+v%q>Erwpn?|C0cWDIm=ngFx%>z z3*Os0t|`MTfi7K%_tqt}u|@);(tJnAc|)h8CX{XEQS(Z}=c;TXCGc@oqoFE+i>s(c z3|LQ*Tn(%j$Ie{2{cDk_D8VKY#c8q<;96V^W3}Tmh3M^3Tj#Xw=exjWg?v{ce%B6A zYQRJWXooe;y3TYz)(Mt ziN-03yPUHL$rQE&fl{N{@JC-VJV@H`TP$DJtZT91fHN(aqN(G*mKS`n215QD{w`RG zAWdX)crVwFxkIZaSaJ_HKRu_?Qi8Zl%zGL`4EGMTZ?>cw$Vn?nF$%_+uNm`v3f1~E zfy!_UThE@Z^q0A9!p*LkN1)&D{2;;h-GUVP_TQyt3Ag(tje)nx)~V+&xn5Jw1|Pl1 z(4Vc$-jH75HdX~ibeyP*66BHt`LckbaFA2p5u7ZXx_HI$l6s+qP3^B&Gg&b8p|FNJ zd2#s5G6n+3Yz~7di=wV;4LrH$6dy7dbMw7TMDn2zYmI>K;lK=NCYAqHm*_W^0$d@t zV;&2ey8sjgVd<1B zQqay|)3$FpV0_o)JfO|~^D0h7QL5A!F+Gye*NGIi&%S5e?$WNPmQ#lvq)~!rI8Bg` zjGrgxfY{t=yE#gQWv#WtkG%^dA|^#_fF5dfrN{l7M{k_B08;8Ri6b&%flwY2S z`9$65b7cRB2h7qu*3|z*3vN*uu0Hqm$&sDvBjagpo83-2~6C$vdjw8o?D{0hL( zxSEn&v5!`QHA3o3C=p;}$+rZI48qfNuu!VuV*s{(YAB)O4h?Cs8!gXB6P2EI1ih3} zOxKYJK@m4UIca}H1BUr=eS*Lv@<#s*Ft^)BPbVD9(H0ye>*u&OrJcsqShijNB=@O! z7v^-C)m_7@HmYR7n1+CNN6IZ78>@mJ2A$rWTKaUZi`V+JRj!?sUUeNt2>EZnSif0n z={y~D{d5tqes+5G?cvFZ|DB8lKx5Q%yebsBJidVzMD^k(xP_LPbd{}!fz;fTX0dXEm*@uvAnblVW*fX945blk%Q9!X1OScI6 zIN=Hp^>`+^5A!8SVA+0IkAbH+o{HSUHm;2{dsTmLMQvakguh605lxUyPj`uN(GF@=jk}8a`1~;B#}NAPi3eHZ z#G{%&F;y7aQ|zKQIyUr&MR$Z^qa_v|*P{j$){=g%OPW2tQxw}cu-`IeJ<|f%o6i|= z6tPkD?!Nkd6uA5bwNrEvIqW}^G|f0=I7!2EvY!=vdM8yfEdQs$quzx&*SoRh z(~*l^$IA0Te51vFq8F`98j3-%#M76SQbBN#cda&Sz9804Dr2JpH2zNnGy)whBg_6CBSW`YU!J^Wbn0wOZX9%`YFU(Y#lm;3R&)R3xFr6mL#HNK ze34RNaVqdf^C!Y(lO`@K-@7G?u%d$QzvKE1y{>>csWfZNJ;zlwdym6Mxk*s!M%d7Z zAERgatyc&yN^WMGz*dDgrrx%@{)1Am+}yLr)uf7SG#(Sf5{ykaIl=@x8*=(R>N$$G z>OY9{#Y2H#)~thG0oDqy?Kok{wv)5kcAMA^@2VSQJaNeWvX&l(2gQ`G^BpQRp#CJ|`oW zu)-7pBkEFQTLhZII8g;SQ#)?~MO$h%M(2F&DOLGqQHY(DLd&3@w>6)gr$m>Ei<;_N zl!Qj&dqR&Q*`f%xFm45XQdXj0+A9W+AuKqts;sSgag>FwBffECd#dBD?*S?9jki(C%O+#I3RN4!AQ}@HTXV> zeUMAQUX(y3X@iw1`&1~=J?ZHv4+T%MScHLUTCx)KwF<{;Ui=h+(PTb{*UubM#4$I? zf^;b|ekszLDWaJvviPZ-p0rNfWGu6!-6sm&n