From 7f064daea31adff65cfda73085a8757b371d5b85 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 9 Mar 2023 12:05:52 +0900 Subject: [PATCH 001/121] fix(behavior_path_planner): fix lane change velocity (#3028) * fix(behavior_path_planner): fix lane change velocity Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../external_request_lane_change_module.cpp | 4 ++-- .../scene_module/lane_change/lane_change_module.cpp | 4 ++-- .../src/util/lane_change/util.cpp | 4 ++-- planning/behavior_path_planner/src/utilities.cpp | 12 +++++------- 4 files changed, 11 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp index d81942e55cbd2..3a55935b641e1 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp @@ -451,7 +451,7 @@ bool ExternalRequestLaneChangeModule::isNearEndOfLane() const bool ExternalRequestLaneChangeModule::isCurrentSpeedLow() const { constexpr double threshold_ms = 10.0 * 1000 / 3600; - return util::l2Norm(getEgoTwist().linear) < threshold_ms; + return getEgoTwist().linear.x < threshold_ms; } bool ExternalRequestLaneChangeModule::isAbortConditionSatisfied() @@ -574,7 +574,7 @@ std::shared_ptr ExternalRequestLaneChangeModule::get_de debug_msg.is_front = debug_data.is_front; debug_msg.relative_distance = debug_data.relative_to_ego; debug_msg.failed_reason = debug_data.failed_reason; - debug_msg.velocity = util::l2Norm(debug_data.object_twist.linear); + debug_msg.velocity = debug_data.object_twist.linear.x; debug_msg_array.lane_change_info.push_back(debug_msg); } lane_change_debug_msg_array_ = debug_msg_array; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index cac2dabf9c92c..1ca530c0d28ee 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -451,7 +451,7 @@ bool LaneChangeModule::isNearEndOfLane() const bool LaneChangeModule::isCurrentSpeedLow() const { constexpr double threshold_ms = 10.0 * 1000 / 3600; - return util::l2Norm(getEgoTwist().linear) < threshold_ms; + return getEgoTwist().linear.x < threshold_ms; } bool LaneChangeModule::isAbortConditionSatisfied() @@ -573,7 +573,7 @@ std::shared_ptr LaneChangeModule::get_debug_msg_array() debug_msg.is_front = debug_data.is_front; debug_msg.relative_distance = debug_data.relative_to_ego; debug_msg.failed_reason = debug_data.failed_reason; - debug_msg.velocity = util::l2Norm(debug_data.object_twist.linear); + debug_msg.velocity = debug_data.object_twist.linear.x; debug_msg_array.lane_change_info.push_back(debug_msg); } lane_change_debug_msg_array_ = debug_msg_array; diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index ea74ffdae881b..4c48c16179586 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -294,7 +294,7 @@ std::pair getLaneChangePaths( const auto lane_change_sampling_num = parameter.lane_change_sampling_num; // get velocity - const auto current_velocity = util::l2Norm(twist.linear); + const auto current_velocity = twist.linear.x; const auto acceleration_resolution = std::abs(maximum_deceleration) / lane_change_sampling_num; @@ -840,7 +840,7 @@ std::optional getAbortPaths( [[maybe_unused]] const LaneChangeParameters & lane_change_param) { const auto & route_handler = planner_data->route_handler; - const auto current_speed = util::l2Norm(planner_data->self_odometry->twist.twist.linear); + const auto current_speed = planner_data->self_odometry->twist.twist.linear.x; const auto current_pose = planner_data->self_odometry->pose.pose; const auto reference_lanelets = selected_path.reference_lanelets; diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 15666080147da..d5a34c8822ff4 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -2403,16 +2403,14 @@ bool hasEnoughDistance( const auto [front_vehicle_velocity, rear_vehicle_velocity] = std::invoke([&]() { debug.object_twist.linear = object_current_twist.linear; if (is_obj_in_front) { - return std::make_pair( - util::l2Norm(object_current_twist.linear), util::l2Norm(ego_current_twist.linear)); + return std::make_pair(object_current_twist.linear.x, ego_current_twist.linear.x); } - return std::make_pair( - util::l2Norm(ego_current_twist.linear), util::l2Norm(object_current_twist.linear)); + return std::make_pair(ego_current_twist.linear.x, object_current_twist.linear.x); }); const auto is_unsafe_dist_between_vehicle = std::invoke([&]() { // ignore this for parked vehicle. - if (l2Norm(object_current_twist.linear) < 0.1) { + if (object_current_twist.linear.x < 0.1) { return false; } @@ -2461,7 +2459,7 @@ bool isSafeInLaneletCollisionCheck( Pose expected_obj_pose = target_object.kinematics.initial_pose_with_covariance.pose; const auto & object_twist = target_object.kinematics.initial_twist_with_covariance.twist; - const auto object_speed = l2Norm(object_twist.linear); + const auto object_speed = object_twist.linear.x; const auto ignore_check_at_time = [&](const double current_time) { return ( (current_time < prepare_duration) && @@ -2522,7 +2520,7 @@ bool isSafeInFreeSpaceCollisionCheck( } const auto & object_twist = target_object.kinematics.initial_twist_with_covariance.twist; - const auto object_speed = l2Norm(object_twist.linear); + const auto object_speed = object_twist.linear.x; const auto ignore_check_at_time = [&](const double current_time) { return ( (current_time < prepare_duration) && From de19018ce76e5015e1f7ab0ff091ea42808b06c7 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 9 Mar 2023 14:38:27 +0900 Subject: [PATCH 002/121] feat(lane_change): support new framework (#3016) * feat(lane_change): support new framework Signed-off-by: Muhammad Zulfaqar Azmi * fix on entry new module idle state Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * clearWaitingApproval() once plan Signed-off-by: Muhammad Zulfaqar Azmi * set COMPILE_WITH_OLD_ARCHITECTURE to true Signed-off-by: Muhammad Zulfaqar Azmi * fix prev_approved_path Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/behavior_path_planner/CMakeLists.txt | 3 +- .../behavior_path_planner_node.hpp | 1 + .../behavior_path_planner/parameters.hpp | 1 + .../lane_change/lane_change_module.hpp | 63 +++++++++++------- .../scene_module/lane_change/manager.hpp | 57 +++++++++++++++++ .../src/behavior_path_planner_node.cpp | 21 ++++++ .../lane_change/lane_change_module.cpp | 64 ++++++++++++++----- .../src/scene_module/lane_change/manager.cpp | 51 +++++++++++++++ 8 files changed, 219 insertions(+), 42 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp create mode 100644 planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 00550686f3cdd..767c04efeebb8 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -17,6 +17,7 @@ set(common_src src/scene_module/scene_module_visitor.cpp src/scene_module/pull_out/pull_out_module.cpp src/scene_module/side_shift/side_shift_module.cpp + src/scene_module/lane_change/lane_change_module.cpp src/turn_signal_decider.cpp src/util/avoidance/util.cpp src/util/lane_change/util.cpp @@ -48,7 +49,6 @@ if(COMPILE_WITH_OLD_ARCHITECTURE) src/scene_module/avoidance/avoidance_module.cpp src/scene_module/lane_following/lane_following_module.cpp src/scene_module/lane_change/external_request_lane_change_module.cpp - src/scene_module/lane_change/lane_change_module.cpp src/scene_module/pull_over/pull_over_module.cpp ${common_src} ) @@ -62,6 +62,7 @@ else() src/planner_manager.cpp src/scene_module/pull_out/manager.cpp src/scene_module/side_shift/manager.cpp + src/scene_module/lane_change/manager.cpp ${common_src} ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 09c03782d9040..6d195e27999b4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -29,6 +29,7 @@ #include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" #else #include "behavior_path_planner/planner_manager.hpp" +#include "behavior_path_planner/scene_module/lane_change/manager.hpp" #include "behavior_path_planner/scene_module/pull_out/manager.hpp" #include "behavior_path_planner/scene_module/side_shift/manager.hpp" #endif diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index fd5d27efda740..b6f8daa40107a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -32,6 +32,7 @@ struct BehaviorPathPlannerParameters ModuleConfigParameters config_avoidance; ModuleConfigParameters config_pull_out; ModuleConfigParameters config_side_shift; + ModuleConfigParameters config_lane_change; double backward_path_length; double forward_path_length; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp index e6a00371c898e..489dbfd3b5764 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp @@ -51,13 +51,20 @@ using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; class LaneChangeModule : public SceneModuleInterface { public: +#ifdef USE_OLD_ARCHITECTURE LaneChangeModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters); - +#else + LaneChangeModule( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & rtc_interface_left, + const std::shared_ptr & rtc_interface_right); +#endif bool isExecutionRequested() const override; bool isExecutionReady() const override; - BT::NodeStatus updateState() override; + ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; @@ -68,33 +75,40 @@ class LaneChangeModule : public SceneModuleInterface void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override; +#ifndef USE_OLD_ARCHITECTURE + void updateModuleParams(const std::shared_ptr & parameters) + { + parameters_ = parameters; + } +#endif + void publishRTCStatus() override { - rtc_interface_left_.publishCooperateStatus(clock_->now()); - rtc_interface_right_.publishCooperateStatus(clock_->now()); + rtc_interface_left_->publishCooperateStatus(clock_->now()); + rtc_interface_right_->publishCooperateStatus(clock_->now()); } bool isActivated() override { - if (rtc_interface_left_.isRegistered(uuid_left_)) { - return rtc_interface_left_.isActivated(uuid_left_); + if (rtc_interface_left_->isRegistered(uuid_left_)) { + return rtc_interface_left_->isActivated(uuid_left_); } - if (rtc_interface_right_.isRegistered(uuid_right_)) { - return rtc_interface_right_.isActivated(uuid_right_); + if (rtc_interface_right_->isRegistered(uuid_right_)) { + return rtc_interface_right_->isActivated(uuid_right_); } return false; } void lockRTCCommand() override { - rtc_interface_left_.lockCommandUpdate(); - rtc_interface_right_.lockCommandUpdate(); + rtc_interface_left_->lockCommandUpdate(); + rtc_interface_right_->lockCommandUpdate(); } void unlockRTCCommand() override { - rtc_interface_left_.unlockCommandUpdate(); - rtc_interface_right_.unlockCommandUpdate(); + rtc_interface_left_->unlockCommandUpdate(); + rtc_interface_right_->unlockCommandUpdate(); } private: @@ -113,8 +127,8 @@ class LaneChangeModule : public SceneModuleInterface bool is_abort_condition_satisfied_{false}; bool is_activated_ = false; - RTCInterface rtc_interface_left_; - RTCInterface rtc_interface_right_; + std::shared_ptr rtc_interface_left_; + std::shared_ptr rtc_interface_right_; UUID uuid_left_; UUID uuid_right_; UUID candidate_uuid_; @@ -123,14 +137,14 @@ class LaneChangeModule : public SceneModuleInterface void waitApprovalLeft(const double start_distance, const double finish_distance) { - rtc_interface_left_.updateCooperateStatus( + rtc_interface_left_->updateCooperateStatus( uuid_left_, isExecutionReady(), start_distance, finish_distance, clock_->now()); is_waiting_approval_ = true; } void waitApprovalRight(const double start_distance, const double finish_distance) { - rtc_interface_right_.updateCooperateStatus( + rtc_interface_right_->updateCooperateStatus( uuid_right_, isExecutionReady(), start_distance, finish_distance, clock_->now()); is_waiting_approval_ = true; } @@ -138,14 +152,14 @@ class LaneChangeModule : public SceneModuleInterface void updateRTCStatus(const CandidateOutput & candidate) { if (candidate.lateral_shift > 0.0) { - rtc_interface_left_.updateCooperateStatus( + rtc_interface_left_->updateCooperateStatus( uuid_left_, isExecutionReady(), candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change, clock_->now()); candidate_uuid_ = uuid_left_; return; } if (candidate.lateral_shift < 0.0) { - rtc_interface_right_.updateCooperateStatus( + rtc_interface_right_->updateCooperateStatus( uuid_right_, isExecutionReady(), candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change, clock_->now()); candidate_uuid_ = uuid_right_; @@ -159,21 +173,21 @@ class LaneChangeModule : public SceneModuleInterface void removeRTCStatus() override { - rtc_interface_left_.clearCooperateStatus(); - rtc_interface_right_.clearCooperateStatus(); + rtc_interface_left_->clearCooperateStatus(); + rtc_interface_right_->clearCooperateStatus(); } void removePreviousRTCStatusLeft() { - if (rtc_interface_left_.isRegistered(uuid_left_)) { - rtc_interface_left_.removeCooperateStatus(uuid_left_); + if (rtc_interface_left_->isRegistered(uuid_left_)) { + rtc_interface_left_->removeCooperateStatus(uuid_left_); } } void removePreviousRTCStatusRight() { - if (rtc_interface_right_.isRegistered(uuid_right_)) { - rtc_interface_right_.removeCooperateStatus(uuid_right_); + if (rtc_interface_right_->isRegistered(uuid_right_)) { + rtc_interface_right_->removeCooperateStatus(uuid_right_); } } @@ -184,6 +198,7 @@ class LaneChangeModule : public SceneModuleInterface std::pair getSafePath( const lanelet::ConstLanelets & lane_change_lanes, const double check_distance, LaneChangePath & safe_path) const; + PathWithLaneId extendBackwardLength(const PathWithLaneId & original_path) const; void updateLaneChangeStatus(); void generateExtendedDrivableArea(PathWithLaneId & path); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp new file mode 100644 index 0000000000000..87e5d42688d06 --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -0,0 +1,57 @@ +// 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__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ +#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ + +#include "behavior_path_planner/scene_module/lane_change/lane_change_module.hpp" +#include "behavior_path_planner/scene_module/scene_module_manager_interface.hpp" + +#include + +#include +#include +#include +#include + +namespace behavior_path_planner +{ + +class LaneChangeModuleManager : public SceneModuleManagerInterface +{ +public: + LaneChangeModuleManager( + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, + std::shared_ptr parameters); + + std::shared_ptr createNewSceneModuleInstance() override + { + return std::make_shared( + name_, *node_, parameters_, rtc_interface_left_, rtc_interface_right_); + } + + void updateModuleParams(const std::vector & parameters) override; + +private: + std::shared_ptr rtc_interface_left_; + std::shared_ptr rtc_interface_right_; + + std::shared_ptr parameters_; + + std::vector> registered_modules_; +}; + +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_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 6b45c8f130807..ad011e35a4fac 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -222,6 +222,17 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod "side_shift", create_publisher(path_reference_name_space + "side_shift", 1)); } + if (p.config_lane_change.enable_module) { + const std::string module_topic = "lane_change"; + auto manager = std::make_shared( + this, module_topic, p.config_lane_change, lane_change_param_ptr_); + planner_manager_->registerSceneModuleManager(manager); + path_candidate_publishers_.emplace( + module_topic, create_publisher(path_candidate_name_space + module_topic, 1)); + path_reference_publishers_.emplace( + module_topic, create_publisher(path_reference_name_space + module_topic, 1)); + } + mutex_bt_.unlock(); } #endif @@ -273,6 +284,16 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.config_side_shift.max_module_size = declare_parameter(ns + "max_module_size"); } + { + const std::string ns = "lane_change."; + + p.config_lane_change.enable_module = declare_parameter(ns + "enable_module"); + p.config_lane_change.enable_simultaneous_execution = + declare_parameter(ns + "enable_simultaneous_execution"); + p.config_lane_change.priority = declare_parameter(ns + "priority"); + p.config_lane_change.max_module_size = declare_parameter(ns + "max_module_size"); + } + // vehicle info const auto vehicle_info = VehicleInfoUtil(*this).getVehicleInfo(); p.vehicle_info = vehicle_info; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 1ca530c0d28ee..93987eaf5a6cd 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -44,22 +44,43 @@ namespace behavior_path_planner { using autoware_auto_perception_msgs::msg::ObjectClassification; +#ifdef USE_OLD_ARCHITECTURE LaneChangeModule::LaneChangeModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters) : SceneModuleInterface{name, node}, parameters_{std::move(parameters)}, - rtc_interface_left_(&node, "lane_change_left"), - rtc_interface_right_(&node, "lane_change_right"), uuid_left_{generateUUID()}, uuid_right_{generateUUID()} { + rtc_interface_left_ = std::make_shared(&node, "lane_change_left"); + rtc_interface_right_ = std::make_shared(&node, "lane_change_right"); steering_factor_interface_ptr_ = std::make_unique(&node, "lane_change"); } +#else +LaneChangeModule::LaneChangeModule( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & rtc_interface_left, + const std::shared_ptr & rtc_interface_right) +: SceneModuleInterface{name, node}, + parameters_{parameters}, + rtc_interface_left_{rtc_interface_left}, + rtc_interface_right_{rtc_interface_right}, + uuid_left_{generateUUID()}, + uuid_right_{generateUUID()} +{ + steering_factor_interface_ptr_ = std::make_unique(&node, "lane_change"); +} +#endif void LaneChangeModule::onEntry() { RCLCPP_DEBUG(getLogger(), "LANE_CHANGE onEntry"); - current_state_ = BT::NodeStatus::SUCCESS; +#ifdef USE_OLD_ARCHITECTURE + current_state_ = ModuleStatus::SUCCESS; +#else + current_state_ = ModuleStatus::IDLE; +#endif current_lane_change_state_ = LaneChangeStates::Normal; updateLaneChangeStatus(); } @@ -67,13 +88,13 @@ void LaneChangeModule::onEntry() void LaneChangeModule::onExit() { resetParameters(); - current_state_ = BT::NodeStatus::SUCCESS; + current_state_ = ModuleStatus::SUCCESS; RCLCPP_DEBUG(getLogger(), "LANE_CHANGE onExit"); } bool LaneChangeModule::isExecutionRequested() const { - if (current_state_ == BT::NodeStatus::RUNNING) { + if (current_state_ == ModuleStatus::RUNNING) { return true; } @@ -89,7 +110,7 @@ bool LaneChangeModule::isExecutionRequested() const bool LaneChangeModule::isExecutionReady() const { - if (current_state_ == BT::NodeStatus::RUNNING) { + if (current_state_ == ModuleStatus::RUNNING) { return true; } @@ -103,36 +124,36 @@ bool LaneChangeModule::isExecutionReady() const return found_safe_path; } -BT::NodeStatus LaneChangeModule::updateState() +ModuleStatus LaneChangeModule::updateState() { RCLCPP_DEBUG(getLogger(), "LANE_CHANGE updateState"); if (!isValidPath()) { - current_state_ = BT::NodeStatus::SUCCESS; + current_state_ = ModuleStatus::SUCCESS; return current_state_; } const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane( status_.current_lanes, getEgoPose(), planner_data_->parameters); if (isAbortState() && !is_within_current_lane) { - current_state_ = BT::NodeStatus::RUNNING; + current_state_ = ModuleStatus::RUNNING; return current_state_; } if (isAbortConditionSatisfied()) { if ((isNearEndOfLane() && isCurrentSpeedLow()) || !is_within_current_lane) { - current_state_ = BT::NodeStatus::RUNNING; + current_state_ = ModuleStatus::RUNNING; return current_state_; } - current_state_ = BT::NodeStatus::FAILURE; + current_state_ = ModuleStatus::FAILURE; return current_state_; } if (hasFinishedLaneChange()) { - current_state_ = BT::NodeStatus::SUCCESS; + current_state_ = ModuleStatus::SUCCESS; return current_state_; } - current_state_ = BT::NodeStatus::RUNNING; + current_state_ = ModuleStatus::RUNNING; return current_state_; } @@ -162,13 +183,18 @@ BehaviorModuleOutput LaneChangeModule::plan() generateExtendedDrivableArea(path); - prev_approved_path_ = path; - BehaviorModuleOutput output; output.path = std::make_shared(path); + path_reference_ = getPreviousModuleOutput().reference_path; +#ifdef USE_OLD_ARCHITECTURE + prev_approved_path_ = path; +#else + prev_approved_path_ = *getPreviousModuleOutput().path; +#endif updateOutputTurnSignal(output); updateSteeringFactorPtr(output); + clearWaitingApproval(); return output; } @@ -235,18 +261,21 @@ CandidateOutput LaneChangeModule::planCandidate() const BehaviorModuleOutput LaneChangeModule::planWaitingApproval() { +#ifdef USE_OLD_ARCHITECTURE const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane( status_.current_lanes, getEgoPose(), planner_data_->parameters); - if (is_within_current_lane) { prev_approved_path_ = getReferencePath(); } - +#else + prev_approved_path_ = *getPreviousModuleOutput().path; +#endif BehaviorModuleOutput out; out.path = std::make_shared(prev_approved_path_); const auto candidate = planCandidate(); path_candidate_ = std::make_shared(candidate.path_candidate); + path_reference_ = getPreviousModuleOutput().reference_path; updateRTCStatus(candidate); waitApproval(); is_abort_path_approved_ = false; @@ -739,6 +768,7 @@ void LaneChangeModule::resetParameters() abort_path_ = nullptr; clearWaitingApproval(); + unlockNewModuleLaunch(); removeRTCStatus(); steering_factor_interface_ptr_->clearSteeringFactors(); object_debug_.clear(); 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 new file mode 100644 index 0000000000000..79bc075de2ffe --- /dev/null +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -0,0 +1,51 @@ +// 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/scene_module/lane_change/manager.hpp" + +#include + +#include +#include +#include +#include + +namespace behavior_path_planner +{ + +LaneChangeModuleManager::LaneChangeModuleManager( + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, + std::shared_ptr parameters) +: SceneModuleManagerInterface(node, name, config), parameters_{std::move(parameters)} +{ + rtc_interface_left_ = std::make_shared(node, name + "_left"); + rtc_interface_right_ = std::make_shared(node, name + "_right"); +} + +void LaneChangeModuleManager::updateModuleParams( + [[maybe_unused]] const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + + [[maybe_unused]] auto p = parameters_; + + [[maybe_unused]] std::string ns = "lane_change."; + // updateParam(parameters, ns + ..., ...); + + std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { + m->updateModuleParams(p); + }); +} + +} // namespace behavior_path_planner From 6a766aea0c6a654e02129d799de2520208a67911 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Thu, 9 Mar 2023 14:58:34 +0900 Subject: [PATCH 003/121] docs(traffic_ligtht_classifier): update document for CNN model customization (#3037) docs: update document for CNN model customization Signed-off-by: ktro2828 --- perception/traffic_light_classifier/README.md | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) diff --git a/perception/traffic_light_classifier/README.md b/perception/traffic_light_classifier/README.md index 24928c9ee4de0..b598d877d5293 100644 --- a/perception/traffic_light_classifier/README.md +++ b/perception/traffic_light_classifier/README.md @@ -87,6 +87,70 @@ These colors and shapes are assigned to the message as follows: | `red_max_s` | int | the maximum saturation of red color | | `red_max_v` | int | the maximum value (brightness) of red color | +## Customization of CNN model + +Currently, in Autoware, [MobileNetV2](https://arxiv.org/abs/1801.04381v3) is used as CNN classifier by default. The corresponding onnx file is [data/traffic_light_classifier_mobilenetv2.onnx](./data/traffic_light_classifier_mobilenetv2.onnx). +Also, you can apply the following models shown as below, for example. + +- [EfficientNet](https://arxiv.org/abs/1905.11946v5) +- [ResNet](https://openaccess.thecvf.com/content_cvpr_2016/html/He_Deep_Residual_Learning_CVPR_2016_paper.html) +- [MobileNetV3](https://arxiv.org/abs/1905.02244) + ... + +In order to train models and export onnx model, we recommend [open-mmlab/mmclassification](https://github.com/open-mmlab/mmclassification.git). +Please follow the [official document](https://mmclassification.readthedocs.io/en/latest/) to install and experiment with mmclassification. If you get into troubles, [FAQ page](https://mmclassification.readthedocs.io/en/latest/faq.html) would help you. + +The following steps are example of a quick-start. + +### step 0. Install [MMCV](https://github.com/open-mmlab/mmcv.git) and [MIM](https://github.com/open-mmlab/mim.git) + +_NOTE_ : First of all, install [PyTorch](https://pytorch.org/) suitable for your CUDA version (CUDA11.6 is supported in Autoware). + +In order to install mmcv suitable for your CUDA version, install it specifying a url. + +```shell +# Install mim +$ pip install -U openmim + +# Install mmcv on a machine with CUDA11.6 and PyTorch1.13.0 +$ pip install mmcv-full -f https://download.openmmlab.com/mmcv/dist/cu116/torch1.13/index.html +``` + +### step 1. Install MMClassification + +You can install MMClassification as a Python package or from source. + +```shell +# As a Python package +$ pip install mmcls + +# From source +$ git clone https://github.com/open-mmlab/mmclassification.git +$ cd mmclassification +$ pip install -v -e . +``` + +### step 2. Train your model + +Train model with your experiment configuration file. For the details of config file, see [here](https://mmclassification.readthedocs.io/en/latest/tutorials/config.html). + +```shell +# [] is optional, you can start training from pre-trained checkpoint +$ mim train mmcls YOUR_CONFIG.py [--resume-from YOUR_CHECKPOINT.pth] +``` + +### step 3. Export onnx model + +In exporting onnx, use `mmclassificatoin/tools/deployment/pytorch2onnx.py` or [open-mmlab/mmdeploy](https://github.com/open-mmlab/mmdeploy.git). + +```shell +cd ~/mmclassification/tools/deployment +python3 pytorch2onnx.py YOUR_CONFIG.py ... +``` + +After obtaining your onnx model, update parameters defined in the launch file (e.g. `model_file_path`, `label_file_path`, `input_h`, `input_w`...). +Note that, we only support labels defined in [autoware_auto_perception_msgs::msg::TrafficLight](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/TrafficLight.idl). + ## Assumptions / Known limits + + + + + + + + + + diff --git a/planning/planning_evaluator/package.xml b/evaluator/planning_evaluator/package.xml similarity index 91% rename from planning/planning_evaluator/package.xml rename to evaluator/planning_evaluator/package.xml index b288d911b4c3c..73186f6b20e88 100644 --- a/planning/planning_evaluator/package.xml +++ b/evaluator/planning_evaluator/package.xml @@ -5,6 +5,7 @@ 0.1.0 ROS2 node for evaluating planners Maxime CLEMENT + Kyoichi Sugahara Apache License 2.0 Maxime CLEMENT @@ -20,6 +21,7 @@ geometry_msgs motion_utils nav_msgs + pluginlib rclcpp rclcpp_components tf2 diff --git a/planning/planning_evaluator/param/planning_evaluator.defaults.yaml b/evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml similarity index 100% rename from planning/planning_evaluator/param/planning_evaluator.defaults.yaml rename to evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml diff --git a/planning/planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics/deviation_metrics.cpp rename to evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp diff --git a/planning/planning_evaluator/src/metrics/metrics_utils.cpp b/evaluator/planning_evaluator/src/metrics/metrics_utils.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics/metrics_utils.cpp rename to evaluator/planning_evaluator/src/metrics/metrics_utils.cpp diff --git a/planning/planning_evaluator/src/metrics/obstacle_metrics.cpp b/evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics/obstacle_metrics.cpp rename to evaluator/planning_evaluator/src/metrics/obstacle_metrics.cpp diff --git a/planning/planning_evaluator/src/metrics/stability_metrics.cpp b/evaluator/planning_evaluator/src/metrics/stability_metrics.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics/stability_metrics.cpp rename to evaluator/planning_evaluator/src/metrics/stability_metrics.cpp diff --git a/planning/planning_evaluator/src/metrics/trajectory_metrics.cpp b/evaluator/planning_evaluator/src/metrics/trajectory_metrics.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics/trajectory_metrics.cpp rename to evaluator/planning_evaluator/src/metrics/trajectory_metrics.cpp diff --git a/planning/planning_evaluator/src/metrics_calculator.cpp b/evaluator/planning_evaluator/src/metrics_calculator.cpp similarity index 100% rename from planning/planning_evaluator/src/metrics_calculator.cpp rename to evaluator/planning_evaluator/src/metrics_calculator.cpp diff --git a/planning/planning_evaluator/src/motion_evaluator_node.cpp b/evaluator/planning_evaluator/src/motion_evaluator_node.cpp similarity index 100% rename from planning/planning_evaluator/src/motion_evaluator_node.cpp rename to evaluator/planning_evaluator/src/motion_evaluator_node.cpp diff --git a/planning/planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/planning_evaluator/src/planning_evaluator_node.cpp similarity index 98% rename from planning/planning_evaluator/src/planning_evaluator_node.cpp rename to evaluator/planning_evaluator/src/planning_evaluator_node.cpp index cca9bbf7c62e3..663f0482cf77b 100644 --- a/planning/planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/planning_evaluator/src/planning_evaluator_node.cpp @@ -156,7 +156,7 @@ void PlanningEvaluatorNode::onTrajectory(const Trajectory::ConstSharedPtr traj_m } metrics_calculator_.setPreviousTrajectory(*traj_msg); auto runtime = (now() - start).seconds(); - RCLCPP_INFO(get_logger(), "Calculation time: %2.2f ms", runtime * 1e3); + RCLCPP_DEBUG(get_logger(), "Planning evaluation calculation time: %2.2f ms", runtime * 1e3); } void PlanningEvaluatorNode::onReferenceTrajectory(const Trajectory::ConstSharedPtr traj_msg) diff --git a/planning/planning_evaluator/test/test_planning_evaluator_node.cpp b/evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp similarity index 100% rename from planning/planning_evaluator/test/test_planning_evaluator_node.cpp rename to evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index f0e9545250e5e..a64427b70ec44 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -86,5 +86,10 @@ + + + + + diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index aa1877be4f536..9769a6a36332f 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -6,6 +6,7 @@ + @@ -104,6 +105,13 @@ + + + + + + + diff --git a/planning/planning_evaluator/launch/planning_evaluator.launch.xml b/planning/planning_evaluator/launch/planning_evaluator.launch.xml deleted file mode 100644 index b3956359c1fd9..0000000000000 --- a/planning/planning_evaluator/launch/planning_evaluator.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - From d8c826c82cdac1435fe626a06c309ea349e01a0a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 10 Mar 2023 12:46:54 +0900 Subject: [PATCH 012/121] fix(avoidance): fix unexpected behavior in yield scenario (#3033) * fix(avoidance): canceling avoidance path even if it doesn't have to avoid Signed-off-by: satoshi-ota * fix(avoidance): stop in front of the object that should be avoid Signed-off-by: satoshi-ota * chore(avoidance): add comment Signed-off-by: satoshi-ota * fix: typo --------- Signed-off-by: satoshi-ota --- .../util/avoidance/avoidance_module_data.hpp | 3 ++ .../avoidance/avoidance_module.cpp | 44 +++++++++++++------ 2 files changed, 33 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/avoidance/avoidance_module_data.hpp index 8f44fdc3fedbf..f2417287620dc 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/avoidance/avoidance_module_data.hpp @@ -408,6 +408,9 @@ struct AvoidancePlanningData // the others ObjectDataArray other_objects; + // nearest object that should be avoid + boost::optional stop_target_object{boost::none}; + // raw shift point AvoidLineArray unapproved_raw_sl{}; 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 28b032a2317b7..3928f7f9f2b15 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 @@ -743,12 +743,14 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de } /** - * Check whether the ego should avoid the front object. When the ego follows reference path, + * Find the nearest object that should be avoid. When the ego follows reference path, * if the lateral distance is smaller than minimum margin, the ego should avoid the object. */ - if (!data.target_objects.empty()) { - const auto o_front = data.target_objects.front(); - data.avoid_required = o_front.avoid_required; + for (const auto & o : data.target_objects) { + if (o.avoid_required) { + data.avoid_required = true; + data.stop_target_object = o; + } } /** @@ -762,6 +764,18 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de getLogger(), *clock_, 5000, "not found safe avoidance path. transit yield maneuver..."); } + /** + * Even if data.avoid_required is false, the module cancels registered shift point when the + * approved avoidance path is not safe. + */ + if (!data.safe && registered) { + data.yield_required = true; + data.candidate_path = toShiftedPath(data.reference_path); + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, + "found safe avoidance path, but it is not safe. canceling avoidance path..."); + } + /** * TODO(Satoshi OTA) Think yield maneuver in the middle of avoidance. * Even if it is determined that a yield is necessary, the yield maneuver is not executed @@ -784,7 +798,7 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat debug.current_raw_shift = data.unapproved_raw_sl; debug.new_shift_lines = data.unapproved_new_sl; - if (data.target_objects.empty()) { + if (!data.stop_target_object) { return; } @@ -796,7 +810,7 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat return; } - const auto o_front = data.target_objects.front(); + const auto o_front = data.stop_target_object.get(); const auto & base_link2front = planner_data_->parameters.base_link2front; const auto & vehicle_width = planner_data_->parameters.vehicle_width; @@ -821,6 +835,10 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & data) const { + if (data.yield_required && parameters_->enable_yield_maneuver) { + return AvoidanceState::YIELD; + } + if (!data.avoid_required) { return AvoidanceState::NOT_AVOID; } @@ -829,10 +847,6 @@ AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & dat return AvoidanceState::AVOID_PATH_NOT_READY; } - if (data.yield_required && parameters_->enable_yield_maneuver) { - return AvoidanceState::YIELD; - } - if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) { return AvoidanceState::AVOID_PATH_READY; } @@ -3842,7 +3856,7 @@ void AvoidanceModule::insertWaitPoint( const auto & base_link2front = planner_data_->parameters.base_link2front; const auto & vehicle_width = planner_data_->parameters.vehicle_width; - if (data.target_objects.empty()) { + if (!data.stop_target_object) { return; } @@ -3865,7 +3879,7 @@ void AvoidanceModule::insertWaitPoint( // D4: o_front.longitudinal // D5: base_link2front - const auto o_front = data.target_objects.front(); + const auto o_front = data.stop_target_object.get(); const auto avoid_margin = p->lateral_collision_safety_buffer + p->lateral_collision_margin + 0.5 * vehicle_width; @@ -3918,8 +3932,10 @@ void AvoidanceModule::insertPrepareVelocity(const bool avoidable, ShiftedPath & return; } - if (data.target_objects.front().reason != AvoidanceDebugFactor::TOO_LARGE_JERK) { - return; + if (!!data.stop_target_object) { + if (data.stop_target_object.get().reason != AvoidanceDebugFactor::TOO_LARGE_JERK) { + return; + } } if (data.avoiding_now) { From def79f3c7786f4f03af0601809809c09202d286d Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 10 Mar 2023 14:43:28 +0900 Subject: [PATCH 013/121] fix(mpc): optimization failure due to steer limit (#3044) * fix(mpc): optimization failure due to steer limit Signed-off-by: Takamasa Horibe * add const Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- control/mpc_lateral_controller/src/mpc.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index f5da49b1d5a82..0771a406516dc 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -253,8 +253,11 @@ void MPC::setReferenceTrajectory( void MPC::resetPrevResult(const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer) { - m_raw_steer_cmd_prev = current_steer.steering_tire_angle; - m_raw_steer_cmd_pprev = current_steer.steering_tire_angle; + // Consider limit. The prev value larger than limiation brakes the optimization constraint and + // resluts in optimization failure. + const float steer_lim_f = static_cast(m_steer_lim); + m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); + m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); } bool MPC::getData( From 1b35a6f6859c6bf28aa06031baeb3bcb3bc5e2aa Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 10 Mar 2023 15:23:14 +0900 Subject: [PATCH 014/121] refactor(mpc): clean up code (#3046) * refactor(mpc): remove unnecessary namespace Signed-off-by: Takamasa Horibe * refactor(mpc): remove unused code Signed-off-by: Takamasa Horibe * refactor(mpc): using namespace Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../include/mpc_lateral_controller/mpc.hpp | 67 ++++--- .../mpc_lateral_controller.hpp | 2 +- .../src/longitudinal_controller_utils.cpp | 179 ------------------ control/mpc_lateral_controller/src/mpc.cpp | 108 +++++------ .../src/mpc_lateral_controller.cpp | 20 +- .../mpc_lateral_controller/src/mpc_utils.cpp | 3 +- 6 files changed, 92 insertions(+), 287 deletions(-) delete mode 100644 control/mpc_lateral_controller/src/longitudinal_controller_utils.cpp diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp index c18711d7a4ffa..226dd803e3945 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp @@ -46,6 +46,12 @@ namespace autoware::motion::control::mpc_lateral_controller { +using autoware_auto_control_msgs::msg::AckermannLateralCommand; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_vehicle_msgs::msg::SteeringReport; +using geometry_msgs::msg::Pose; +using tier4_debug_msgs::msg::Float32MultiArrayStamped; + struct MPCParam { //!< @brief prediction horizon step @@ -112,7 +118,7 @@ struct MPCData { int nearest_idx; double nearest_time; - geometry_msgs::msg::Pose nearest_pose; + Pose nearest_pose; double steer; double predicted_steer; double lateral_err; @@ -147,15 +153,15 @@ class MPC //!< @brief vehicle model type for MPC std::string m_vehicle_model_type; //!< @brief vehicle model for MPC - std::shared_ptr m_vehicle_model_ptr; + std::shared_ptr m_vehicle_model_ptr; //!< @brief qp solver for MPC - std::shared_ptr m_qpsolver_ptr; + std::shared_ptr m_qpsolver_ptr; //!< @brief lowpass filter for steering command - mpc_lateral_controller::Butterworth2dFilter m_lpf_steering_cmd; + Butterworth2dFilter m_lpf_steering_cmd; //!< @brief lowpass filter for lateral error - mpc_lateral_controller::Butterworth2dFilter m_lpf_lateral_error; + Butterworth2dFilter m_lpf_lateral_error; //!< @brief lowpass filter for heading error - mpc_lateral_controller::Butterworth2dFilter m_lpf_yaw_error; + Butterworth2dFilter m_lpf_yaw_error; //!< @brief raw output computed two iterations ago double m_raw_steer_cmd_pprev = 0.0; @@ -170,7 +176,7 @@ class MPC //!< @brief shift is forward or not. bool m_is_forward_shift = true; //!< @brief buffer of sent command - std::vector m_ctrl_cmd_vec; + std::vector m_ctrl_cmd_vec; //!< @brief minimum prediction distance double m_min_prediction_length = 5.0; @@ -178,9 +184,8 @@ class MPC * @brief get variables for mpc calculation */ bool getData( - const mpc_lateral_controller::MPCTrajectory & traj, - const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer, - const geometry_msgs::msg::Pose & current_pose, MPCData * data); + const MPCTrajectory & traj, const SteeringReport & current_steer, const Pose & current_pose, + MPCData * data); /** * @brief calculate predicted steering */ @@ -197,7 +202,7 @@ class MPC /** * @brief reset previous result of MPC */ - void resetPrevResult(const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer); + void resetPrevResult(const SteeringReport & current_steer); /** * @brief set initial condition for mpc * @param [in] data mpc data @@ -210,14 +215,13 @@ class MPC * @param [out] x updated state at delayed_time */ bool updateStateForDelayCompensation( - const mpc_lateral_controller::MPCTrajectory & traj, const double & start_time, - Eigen::VectorXd * x); + const MPCTrajectory & traj, const double & start_time, Eigen::VectorXd * x); /** * @brief generate MPC matrix with trajectory and vehicle model * @param [in] reference_trajectory used for linearization around reference trajectory */ MPCMatrix generateMPCMatrix( - const mpc_lateral_controller::MPCTrajectory & reference_trajectory, const double prediction_dt); + const MPCTrajectory & reference_trajectory, const double prediction_dt); /** * @brief generate MPC matrix with trajectory and vehicle model * @param [in] mpc_matrix parameters matrix to use for optimization @@ -232,22 +236,19 @@ class MPC * @brief resample trajectory with mpc resampling time */ bool resampleMPCTrajectoryByTime( - const double start_time, const double prediction_dt, - const mpc_lateral_controller::MPCTrajectory & input, - mpc_lateral_controller::MPCTrajectory * output) const; + const double start_time, const double prediction_dt, const MPCTrajectory & input, + MPCTrajectory * output) const; /** * @brief apply velocity dynamics filter with v0 from closest index */ - mpc_lateral_controller::MPCTrajectory applyVelocityDynamicsFilter( - const mpc_lateral_controller::MPCTrajectory & trajectory, - const geometry_msgs::msg::Pose & current_pose, const double v0) const; + MPCTrajectory applyVelocityDynamicsFilter( + const MPCTrajectory & trajectory, const Pose & current_pose, const double v0) const; /** * @brief get prediction delta time of mpc. * If trajectory length is shorter than min_prediction length, adjust delta time. */ double getPredictionDeltaTime( - const double start_time, const mpc_lateral_controller::MPCTrajectory & input, - const geometry_msgs::msg::Pose & current_pose) const; + const double start_time, const MPCTrajectory & input, const Pose & current_pose) const; /** * @brief add weights related to lateral_jerk, steering_rate, steering_acc into R */ @@ -342,7 +343,7 @@ class MPC public: //!< @brief reference trajectory to be followed - mpc_lateral_controller::MPCTrajectory m_ref_traj; + MPCTrajectory m_ref_traj; //!< @brief MPC design parameter MPCParam m_param; //!< @brief mpc_output buffer for delay time compensation @@ -381,24 +382,22 @@ class MPC * @param [out] diagnostic diagnostic msg to be filled-out */ bool calculateMPC( - const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer, - const double current_velocity, const geometry_msgs::msg::Pose & current_pose, - autoware_auto_control_msgs::msg::AckermannLateralCommand & ctrl_cmd, - autoware_auto_planning_msgs::msg::Trajectory & predicted_traj, - tier4_debug_msgs::msg::Float32MultiArrayStamped & diagnostic); + const SteeringReport & current_steer, const double current_velocity, const Pose & current_pose, + AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_traj, + Float32MultiArrayStamped & diagnostic); /** * @brief set the reference trajectory to follow */ void setReferenceTrajectory( - const autoware_auto_planning_msgs::msg::Trajectory & trajectory_msg, - const double traj_resample_dist, const bool enable_path_smoothing, - const int path_filter_moving_ave_num, const int curvature_smoothing_num_traj, - const int curvature_smoothing_num_ref_steer, const bool extend_trajectory_for_end_yaw_control); + const Trajectory & trajectory_msg, const double traj_resample_dist, + const bool enable_path_smoothing, const int path_filter_moving_ave_num, + const int curvature_smoothing_num_traj, const int curvature_smoothing_num_ref_steer, + const bool extend_trajectory_for_end_yaw_control); /** * @brief set the vehicle model of this MPC */ inline void setVehicleModel( - std::shared_ptr vehicle_model_ptr, + std::shared_ptr vehicle_model_ptr, const std::string & vehicle_model_type) { m_vehicle_model_ptr = vehicle_model_ptr; @@ -407,7 +406,7 @@ class MPC /** * @brief set the QP solver of this MPC */ - inline void setQPSolver(std::shared_ptr qpsolver_ptr) + inline void setQPSolver(std::shared_ptr qpsolver_ptr) { m_qpsolver_ptr = qpsolver_ptr; } diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp index 9ab555635a8a2..17d29d1542cde 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -107,7 +107,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase std::deque m_trajectory_buffer; // MPC object - mpc_lateral_controller::MPC m_mpc; + MPC m_mpc; //!< @brief measured kinematic state nav_msgs::msg::Odometry m_current_kinematic_state; diff --git a/control/mpc_lateral_controller/src/longitudinal_controller_utils.cpp b/control/mpc_lateral_controller/src/longitudinal_controller_utils.cpp deleted file mode 100644 index 70c610433fa06..0000000000000 --- a/control/mpc_lateral_controller/src/longitudinal_controller_utils.cpp +++ /dev/null @@ -1,179 +0,0 @@ -// Copyright 2018-2021 Tier IV, Inc. All rights reserved. -// -// 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 "mpc_lateral_controller/longitudinal_controller_utils.hpp" - -#include "tf2/LinearMath/Matrix3x3.h" -#include "tf2/LinearMath/Quaternion.h" - -#include // NOLINT - -#ifdef ROS_DISTRO_GALACTIC -#include "tf2_geometry_msgs/tf2_geometry_msgs.h" -#else -#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#endif - -#include -#include - -namespace autoware::motion::control::mpc_lateral_controller -{ -namespace longitudinal_utils -{ - -bool isValidTrajectory(const Trajectory & traj) -{ - for (const auto & p : traj.points) { - if ( - !isfinite(p.pose.position.x) || !isfinite(p.pose.position.y) || - !isfinite(p.pose.position.z) || !isfinite(p.pose.orientation.w) || - !isfinite(p.pose.orientation.x) || !isfinite(p.pose.orientation.y) || - !isfinite(p.pose.orientation.z) || !isfinite(p.longitudinal_velocity_mps) || - !isfinite(p.lateral_velocity_mps) || !isfinite(p.acceleration_mps2) || - !isfinite(p.heading_rate_rps)) { - return false; - } - } - - // when trajectory is empty - if (traj.points.empty()) { - return false; - } - - return true; -} - -double calcStopDistance( - const Pose & current_pose, const Trajectory & traj, const double max_dist, const double max_yaw) -{ - const auto stop_idx_opt = motion_utils::searchZeroVelocityIndex(traj.points); - - const size_t end_idx = stop_idx_opt ? *stop_idx_opt : traj.points.size() - 1; - const size_t seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - traj.points, current_pose, max_dist, max_yaw); - const double signed_length_on_traj = motion_utils::calcSignedArcLength( - traj.points, current_pose.position, seg_idx, traj.points.at(end_idx).pose.position, - std::min(end_idx, traj.points.size() - 2)); - - if (std::isnan(signed_length_on_traj)) { - return 0.0; - } - return signed_length_on_traj; -} - -double getPitchByPose(const Quaternion & quaternion_msg) -{ - double roll, pitch, yaw; - tf2::Quaternion quaternion; - tf2::fromMsg(quaternion_msg, quaternion); - tf2::Matrix3x3{quaternion}.getRPY(roll, pitch, yaw); - - return pitch; -} - -double getPitchByTraj( - const Trajectory & trajectory, const size_t nearest_idx, const double wheel_base) -{ - using autoware::common::geometry::distance_2d; - // cannot calculate pitch - if (trajectory.points.size() <= 1) { - return 0.0; - } - - for (size_t i = nearest_idx + 1; i < trajectory.points.size(); ++i) { - const double dist = - distance_2d(trajectory.points.at(nearest_idx), trajectory.points.at(i)); - if (dist > wheel_base) { - // calculate pitch from trajectory between rear wheel (nearest) and front center (i) - return calcElevationAngle(trajectory.points.at(nearest_idx), trajectory.points.at(i)); - } - } - - // close to goal - for (size_t i = trajectory.points.size() - 1; i > 0; --i) { - const double dist = distance_2d(trajectory.points.back(), trajectory.points.at(i)); - - if (dist > wheel_base) { - // calculate pitch from trajectory - // between wheelbase behind the end of trajectory (i) and the end of trajectory (back) - return calcElevationAngle(trajectory.points.at(i), trajectory.points.back()); - } - } - - // calculate pitch from trajectory between the beginning and end of trajectory - return calcElevationAngle(trajectory.points.at(0), trajectory.points.back()); -} - -double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint & p_to) -{ - const double dx = p_from.pose.position.x - p_to.pose.position.x; - const double dy = p_from.pose.position.y - p_to.pose.position.y; - const double dz = p_from.pose.position.z - p_to.pose.position.z; - - const double dxy = std::max(std::hypot(dx, dy), std::numeric_limits::epsilon()); - const double pitch = std::atan2(dz, dxy); - - return pitch; -} - -Pose calcPoseAfterTimeDelay( - const Pose & current_pose, const double delay_time, const double current_vel) -{ - // simple linear prediction - const double yaw = tf2::getYaw(current_pose.orientation); - const double running_distance = delay_time * current_vel; - const double dx = running_distance * std::cos(yaw); - const double dy = running_distance * std::sin(yaw); - - auto pred_pose = current_pose; - pred_pose.position.x += dx; - pred_pose.position.y += dy; - return pred_pose; -} - -double lerp(const double v_from, const double v_to, const double ratio) -{ - return v_from + (v_to - v_from) * ratio; -} - -Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, const double ratio) -{ - tf2::Quaternion q_from, q_to; - tf2::fromMsg(o_from, q_from); - tf2::fromMsg(o_to, q_to); - - const auto q_interpolated = q_from.slerp(q_to, ratio); - return tf2::toMsg(q_interpolated); -} - -double applyDiffLimitFilter( - const double input_val, const double prev_val, const double dt, const double max_val, - const double min_val) -{ - const double diff_raw = (input_val - prev_val) / dt; - const double diff = std::min(std::max(diff_raw, min_val), max_val); - const double filtered_val = prev_val + diff * dt; - return filtered_val; -} - -double applyDiffLimitFilter( - const double input_val, const double prev_val, const double dt, const double lim_val) -{ - const double max_val = std::fabs(lim_val); - const double min_val = -max_val; - return applyDiffLimitFilter(input_val, prev_val, dt, max_val, min_val); -} -} // namespace longitudinal_utils -} // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index 0771a406516dc..ceb5ac5b9c6bc 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -32,14 +32,12 @@ namespace autoware::motion::control::mpc_lateral_controller using namespace std::literals::chrono_literals; bool MPC::calculateMPC( - const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer, - const double current_velocity, const geometry_msgs::msg::Pose & current_pose, - autoware_auto_control_msgs::msg::AckermannLateralCommand & ctrl_cmd, - autoware_auto_planning_msgs::msg::Trajectory & predicted_traj, - tier4_debug_msgs::msg::Float32MultiArrayStamped & diagnostic) + const SteeringReport & current_steer, const double current_velocity, const Pose & current_pose, + AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_traj, + Float32MultiArrayStamped & diagnostic) { /* recalculate velocity from ego-velocity with dynamics */ - mpc_lateral_controller::MPCTrajectory reference_trajectory = + MPCTrajectory reference_trajectory = applyVelocityDynamicsFilter(m_ref_traj, current_pose, current_velocity); MPCData mpc_data; @@ -60,7 +58,7 @@ bool MPC::calculateMPC( } /* resample ref_traj with mpc sampling time */ - mpc_lateral_controller::MPCTrajectory mpc_resampled_ref_traj; + MPCTrajectory mpc_resampled_ref_traj; const double mpc_start_time = mpc_data.nearest_time + m_param.input_delay; const double prediction_dt = getPredictionDeltaTime(mpc_start_time, reference_trajectory, current_pose); @@ -101,7 +99,7 @@ bool MPC::calculateMPC( /* calculate predicted trajectory */ Eigen::VectorXd Xex = mpc_matrix.Aex * x0 + mpc_matrix.Bex * Uex + mpc_matrix.Wex; - mpc_lateral_controller::MPCTrajectory mpc_predicted_traj; + MPCTrajectory mpc_predicted_traj; const auto & traj = mpc_resampled_ref_traj; for (size_t i = 0; i < static_cast(m_param.prediction_horizon); ++i) { const int DIM_X = m_vehicle_model_ptr->getDimX(); @@ -117,7 +115,7 @@ bool MPC::calculateMPC( const double relative_time = traj.relative_time[i]; mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time); } - mpc_lateral_controller::MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj, predicted_traj); + MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj, predicted_traj); /* prepare diagnostic message */ const double nearest_k = reference_trajectory.k[static_cast(mpc_data.nearest_idx)]; @@ -171,18 +169,18 @@ bool MPC::calculateMPC( } void MPC::setReferenceTrajectory( - const autoware_auto_planning_msgs::msg::Trajectory & trajectory_msg, - const double traj_resample_dist, const bool enable_path_smoothing, - const int path_filter_moving_ave_num, const int curvature_smoothing_num_traj, - const int curvature_smoothing_num_ref_steer, const bool extend_trajectory_for_end_yaw_control) + const Trajectory & trajectory_msg, const double traj_resample_dist, + const bool enable_path_smoothing, const int path_filter_moving_ave_num, + const int curvature_smoothing_num_traj, const int curvature_smoothing_num_ref_steer, + const bool extend_trajectory_for_end_yaw_control) { - mpc_lateral_controller::MPCTrajectory mpc_traj_raw; // received raw trajectory - mpc_lateral_controller::MPCTrajectory mpc_traj_resampled; // resampled trajectory - mpc_lateral_controller::MPCTrajectory mpc_traj_smoothed; // smooth filtered trajectory + MPCTrajectory mpc_traj_raw; // received raw trajectory + MPCTrajectory mpc_traj_resampled; // resampled trajectory + MPCTrajectory mpc_traj_smoothed; // smooth filtered trajectory /* resampling */ - mpc_lateral_controller::MPCUtils::convertToMPCTrajectory(trajectory_msg, mpc_traj_raw); - if (!mpc_lateral_controller::MPCUtils::resampleMPCTrajectoryByDistance( + MPCUtils::convertToMPCTrajectory(trajectory_msg, mpc_traj_raw); + if (!MPCUtils::resampleMPCTrajectoryByDistance( mpc_traj_raw, traj_resample_dist, &mpc_traj_resampled)) { RCLCPP_WARN(m_logger, "[setReferenceTrajectory] spline error when resampling by distance"); return; @@ -197,15 +195,12 @@ void MPC::setReferenceTrajectory( mpc_traj_smoothed = mpc_traj_resampled; const int mpc_traj_resampled_size = static_cast(mpc_traj_resampled.size()); if (enable_path_smoothing && mpc_traj_resampled_size > 2 * path_filter_moving_ave_num) { + using MoveAverageFilter::filt_vector; if ( - !mpc_lateral_controller::MoveAverageFilter::filt_vector( - path_filter_moving_ave_num, mpc_traj_smoothed.x) || - !mpc_lateral_controller::MoveAverageFilter::filt_vector( - path_filter_moving_ave_num, mpc_traj_smoothed.y) || - !mpc_lateral_controller::MoveAverageFilter::filt_vector( - path_filter_moving_ave_num, mpc_traj_smoothed.yaw) || - !mpc_lateral_controller::MoveAverageFilter::filt_vector( - path_filter_moving_ave_num, mpc_traj_smoothed.vx)) { + !filt_vector(path_filter_moving_ave_num, mpc_traj_smoothed.x) || + !filt_vector(path_filter_moving_ave_num, mpc_traj_smoothed.y) || + !filt_vector(path_filter_moving_ave_num, mpc_traj_smoothed.yaw) || + !filt_vector(path_filter_moving_ave_num, mpc_traj_smoothed.vx)) { RCLCPP_DEBUG(m_logger, "path callback: filtering error. stop filtering."); mpc_traj_smoothed = mpc_traj_resampled; } @@ -218,16 +213,16 @@ void MPC::setReferenceTrajectory( * well-defined considering the end point attitude angle, this feature is not necessary. */ if (extend_trajectory_for_end_yaw_control) { - mpc_lateral_controller::MPCUtils::extendTrajectoryInYawDirection( + MPCUtils::extendTrajectoryInYawDirection( mpc_traj_raw.yaw.back(), traj_resample_dist, m_is_forward_shift, mpc_traj_smoothed); } /* calculate yaw angle */ - mpc_lateral_controller::MPCUtils::calcTrajectoryYawFromXY(&mpc_traj_smoothed, m_is_forward_shift); - mpc_lateral_controller::MPCUtils::convertEulerAngleToMonotonic(&mpc_traj_smoothed.yaw); + MPCUtils::calcTrajectoryYawFromXY(&mpc_traj_smoothed, m_is_forward_shift); + MPCUtils::convertEulerAngleToMonotonic(&mpc_traj_smoothed.yaw); /* calculate curvature */ - mpc_lateral_controller::MPCUtils::calcTrajectoryCurvature( + MPCUtils::calcTrajectoryCurvature( static_cast(curvature_smoothing_num_traj), static_cast(curvature_smoothing_num_ref_steer), &mpc_traj_smoothed); @@ -251,7 +246,7 @@ void MPC::setReferenceTrajectory( m_ref_traj = mpc_traj_smoothed; } -void MPC::resetPrevResult(const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer) +void MPC::resetPrevResult(const SteeringReport & current_steer) { // Consider limit. The prev value larger than limiation brakes the optimization constraint and // resluts in optimization failure. @@ -261,13 +256,12 @@ void MPC::resetPrevResult(const autoware_auto_vehicle_msgs::msg::SteeringReport } bool MPC::getData( - const mpc_lateral_controller::MPCTrajectory & traj, - const autoware_auto_vehicle_msgs::msg::SteeringReport & current_steer, - const geometry_msgs::msg::Pose & current_pose, MPCData * data) + const MPCTrajectory & traj, const SteeringReport & current_steer, const Pose & current_pose, + MPCData * data) { static constexpr auto duration = 5000 /*ms*/; size_t nearest_idx; - if (!mpc_lateral_controller::MPCUtils::calcNearestPoseInterp( + if (!MPCUtils::calcNearestPoseInterp( traj, current_pose, &(data->nearest_pose), &(nearest_idx), &(data->nearest_time), ego_nearest_dist_threshold, ego_nearest_yaw_threshold, m_logger, *m_clock)) { // reset previous MPC result @@ -284,8 +278,7 @@ bool MPC::getData( /* get data */ data->nearest_idx = static_cast(nearest_idx); data->steer = static_cast(current_steer.steering_tire_angle); - data->lateral_err = - mpc_lateral_controller::MPCUtils::calcLateralError(current_pose, data->nearest_pose); + data->lateral_err = MPCUtils::calcLateralError(current_pose, data->nearest_pose); data->yaw_err = autoware::common::helper_functions::wrap_angle( tf2::getYaw(current_pose.orientation) - tf2::getYaw(data->nearest_pose.orientation)); @@ -384,7 +377,7 @@ double MPC::getSteerCmdSum( void MPC::storeSteerCmd(const double steer) { const auto time_delayed = m_clock->now() + rclcpp::Duration::from_seconds(m_param.input_delay); - autoware_auto_control_msgs::msg::AckermannLateralCommand cmd; + AckermannLateralCommand cmd; cmd.stamp = time_delayed; cmd.steering_tire_angle = static_cast(steer); @@ -403,15 +396,14 @@ void MPC::storeSteerCmd(const double steer) } bool MPC::resampleMPCTrajectoryByTime( - const double ts, const double prediction_dt, const mpc_lateral_controller::MPCTrajectory & input, - mpc_lateral_controller::MPCTrajectory * output) const + const double ts, const double prediction_dt, const MPCTrajectory & input, + MPCTrajectory * output) const { std::vector mpc_time_v; for (double i = 0; i < static_cast(m_param.prediction_horizon); ++i) { mpc_time_v.push_back(ts + i * prediction_dt); } - if (!mpc_lateral_controller::MPCUtils::linearInterpMPCTrajectory( - input.relative_time, input, mpc_time_v, output)) { + if (!MPCUtils::linearInterpMPCTrajectory(input.relative_time, input, mpc_time_v, output)) { RCLCPP_WARN_SKIPFIRST_THROTTLE( m_logger, *m_clock, 1000 /*ms*/, "calculateMPC: mpc resample error. stop mpc calculation. check code!"); @@ -450,8 +442,7 @@ Eigen::VectorXd MPC::getInitialState(const MPCData & data) } bool MPC::updateStateForDelayCompensation( - const mpc_lateral_controller::MPCTrajectory & traj, const double & start_time, - Eigen::VectorXd * x) + const MPCTrajectory & traj, const double & start_time, Eigen::VectorXd * x) { const int DIM_X = m_vehicle_model_ptr->getDimX(); const int DIM_U = m_vehicle_model_ptr->getDimU(); @@ -468,8 +459,8 @@ bool MPC::updateStateForDelayCompensation( double k = 0.0; double v = 0.0; if ( - !mpc_lateral_controller::linearInterpolate(traj.relative_time, traj.k, mpc_curr_time, k) || - !mpc_lateral_controller::linearInterpolate(traj.relative_time, traj.vx, mpc_curr_time, v)) { + !linearInterpolate(traj.relative_time, traj.k, mpc_curr_time, k) || + !linearInterpolate(traj.relative_time, traj.vx, mpc_curr_time, v)) { RCLCPP_ERROR( m_logger, "mpc resample error at delay compensation, stop mpc calculation. check code!"); return false; @@ -488,13 +479,11 @@ bool MPC::updateStateForDelayCompensation( return true; } -mpc_lateral_controller::MPCTrajectory MPC::applyVelocityDynamicsFilter( - const mpc_lateral_controller::MPCTrajectory & input, - const geometry_msgs::msg::Pose & current_pose, const double v0) const +MPCTrajectory MPC::applyVelocityDynamicsFilter( + const MPCTrajectory & input, const Pose & current_pose, const double v0) const { - autoware_auto_planning_msgs::msg::Trajectory autoware_traj; - autoware::motion::control::mpc_lateral_controller::MPCUtils::convertToAutowareTrajectory( - input, autoware_traj); + Trajectory autoware_traj; + MPCUtils::convertToAutowareTrajectory(input, autoware_traj); if (autoware_traj.points.empty()) { return input; } @@ -505,9 +494,8 @@ mpc_lateral_controller::MPCTrajectory MPC::applyVelocityDynamicsFilter( const double acc_lim = m_param.acceleration_limit; const double tau = m_param.velocity_time_constant; - mpc_lateral_controller::MPCTrajectory output = input; - mpc_lateral_controller::MPCUtils::dynamicSmoothingVelocity( - static_cast(nearest_idx), v0, acc_lim, tau, output); + MPCTrajectory output = input; + MPCUtils::dynamicSmoothingVelocity(static_cast(nearest_idx), v0, acc_lim, tau, output); const double t_ext = 100.0; // extra time to prevent mpc calculation failure due to short time const double t_end = output.relative_time.back() + t_ext; const double v_end = 0.0; @@ -524,7 +512,7 @@ mpc_lateral_controller::MPCTrajectory MPC::applyVelocityDynamicsFilter( * Qex = diag([Q,Q,...]), R1ex = diag([R,R,...]) */ MPCMatrix MPC::generateMPCMatrix( - const mpc_lateral_controller::MPCTrajectory & reference_trajectory, const double prediction_dt) + const MPCTrajectory & reference_trajectory, const double prediction_dt) { using Eigen::MatrixXd; @@ -786,13 +774,11 @@ void MPC::addSteerWeightF(const double prediction_dt, Eigen::MatrixXd * f_ptr) c } double MPC::getPredictionDeltaTime( - const double start_time, const mpc_lateral_controller::MPCTrajectory & input, - const geometry_msgs::msg::Pose & current_pose) const + const double start_time, const MPCTrajectory & input, const Pose & current_pose) const { // Calculate the time min_prediction_length ahead from current_pose - autoware_auto_planning_msgs::msg::Trajectory autoware_traj; - autoware::motion::control::mpc_lateral_controller::MPCUtils::convertToAutowareTrajectory( - input, autoware_traj); + Trajectory autoware_traj; + MPCUtils::convertToAutowareTrajectory(input, autoware_traj); const size_t nearest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( autoware_traj.points, current_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); double sum_dist = 0; diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index a884b7f8b32e3..192694d48af72 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -81,13 +81,13 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) : node_{&node} /* vehicle model setup */ const std::string vehicle_model_type = node_->declare_parameter("vehicle_model_type"); - std::shared_ptr vehicle_model_ptr; + std::shared_ptr vehicle_model_ptr; if (vehicle_model_type == "kinematics") { - vehicle_model_ptr = std::make_shared( + vehicle_model_ptr = std::make_shared( wheelbase, m_mpc.m_steer_lim, m_mpc.m_param.steer_tau); } else if (vehicle_model_type == "kinematics_no_delay") { - vehicle_model_ptr = std::make_shared( - wheelbase, m_mpc.m_steer_lim); + vehicle_model_ptr = + std::make_shared(wheelbase, m_mpc.m_steer_lim); } else if (vehicle_model_type == "dynamics") { const double mass_fl = node_->declare_parameter("vehicle.mass_fl"); const double mass_fr = node_->declare_parameter("vehicle.mass_fr"); @@ -98,19 +98,19 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) : node_{&node} // vehicle_model_ptr is only assigned in ctor, so parameter value have to be passed at init time // // NOLINT - vehicle_model_ptr = std::make_shared( - wheelbase, mass_fl, mass_fr, mass_rl, mass_rr, cf, cr); + vehicle_model_ptr = + std::make_shared(wheelbase, mass_fl, mass_fr, mass_rl, mass_rr, cf, cr); } else { RCLCPP_ERROR(node_->get_logger(), "vehicle_model_type is undefined"); } /* QP solver setup */ const std::string qp_solver_type = node_->declare_parameter("qp_solver_type"); - std::shared_ptr qpsolver_ptr; + std::shared_ptr qpsolver_ptr; if (qp_solver_type == "unconstraint_fast") { - qpsolver_ptr = std::make_shared(); + qpsolver_ptr = std::make_shared(); } else if (qp_solver_type == "osqp") { - qpsolver_ptr = std::make_shared(node_->get_logger()); + qpsolver_ptr = std::make_shared(node_->get_logger()); } else { RCLCPP_ERROR(node_->get_logger(), "qp_solver_type is undefined"); } @@ -452,7 +452,7 @@ rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback( result.reason = "success"; // strong exception safety wrt MPCParam - mpc_lateral_controller::MPCParam param = m_mpc.m_param; + MPCParam param = m_mpc.m_param; try { update_param(parameters, "mpc_prediction_horizon", param.prediction_horizon); update_param(parameters, "mpc_prediction_dt", param.prediction_dt); diff --git a/control/mpc_lateral_controller/src/mpc_utils.cpp b/control/mpc_lateral_controller/src/mpc_utils.cpp index f1af25167c240..41b15f17bf075 100644 --- a/control/mpc_lateral_controller/src/mpc_utils.cpp +++ b/control/mpc_lateral_controller/src/mpc_utils.cpp @@ -408,8 +408,7 @@ void extendTrajectoryInYawDirection( // get terminal pose autoware_auto_planning_msgs::msg::Trajectory autoware_traj; - autoware::motion::control::mpc_lateral_controller::MPCUtils::convertToAutowareTrajectory( - traj, autoware_traj); + MPCUtils::convertToAutowareTrajectory(traj, autoware_traj); auto extended_pose = autoware_traj.points.back().pose; constexpr double extend_dist = 10.0; From e4bcc868b09d6d465d0f4fa4fc62b30b2de36413 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 10 Mar 2023 18:05:15 +0900 Subject: [PATCH 015/121] feat: merge traffic signals from perception and V2X (#2903) * feat: add package Signed-off-by: Takagi, Isamu * feat: publish signals Signed-off-by: Takagi, Isamu * feat: add v2x input Signed-off-by: Takagi, Isamu * feat: merge traffic signals Signed-off-by: Takagi, Isamu * feat: ignore when no map Signed-off-by: Takagi, Isamu * feat: modify copyright Signed-off-by: Takagi, Isamu * feat: add converter Signed-off-by: Takagi, Isamu * feat: add selector Signed-off-by: Takagi, Isamu * feat: add readme Signed-off-by: Takagi, Isamu * docs: update readme Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu --- .../traffic_light_selector/CMakeLists.txt | 17 +++ perception/traffic_light_selector/README.md | 43 ++++++ .../launch/traffic_light_selector.launch.xml | 14 ++ perception/traffic_light_selector/package.xml | 28 ++++ .../src/traffic_light_converter.cpp | 117 ++++++++++++++++ .../src/traffic_light_converter.hpp | 36 +++++ .../src/traffic_light_selector.cpp | 129 ++++++++++++++++++ .../src/traffic_light_selector.hpp | 47 +++++++ 8 files changed, 431 insertions(+) create mode 100644 perception/traffic_light_selector/CMakeLists.txt create mode 100644 perception/traffic_light_selector/README.md create mode 100644 perception/traffic_light_selector/launch/traffic_light_selector.launch.xml create mode 100644 perception/traffic_light_selector/package.xml create mode 100644 perception/traffic_light_selector/src/traffic_light_converter.cpp create mode 100644 perception/traffic_light_selector/src/traffic_light_converter.hpp create mode 100644 perception/traffic_light_selector/src/traffic_light_selector.cpp create mode 100644 perception/traffic_light_selector/src/traffic_light_selector.hpp diff --git a/perception/traffic_light_selector/CMakeLists.txt b/perception/traffic_light_selector/CMakeLists.txt new file mode 100644 index 0000000000000..9a8555690beed --- /dev/null +++ b/perception/traffic_light_selector/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_selector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/traffic_light_converter.cpp + src/traffic_light_selector.cpp +) + +rclcpp_components_register_nodes(${PROJECT_NAME} + TrafficLightConverter + TrafficLightSelector +) + +ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/perception/traffic_light_selector/README.md b/perception/traffic_light_selector/README.md new file mode 100644 index 0000000000000..9e38333c0e345 --- /dev/null +++ b/perception/traffic_light_selector/README.md @@ -0,0 +1,43 @@ +# traffic_light_selector + +## Purpose + +This package receives multiple traffic light/signal states and outputs a single traffic signal state for use by the planning component. + +## TrafficLightSelector + +A node that merges traffic light/signal state from image recognition and V2X to provide a planning component. +It's currently a provisional implementation. + +### Inputs / Outputs + +#### Input + +| Name | Type | Description | +| -------------------- | ---------------------------------------------- | ------------------------------------------------- | +| ~/sub/vector_map | autoware_auto_mapping_msgs/msg/HADMapBin | The vector map to get traffic light id relations. | +| ~/sub/traffic_lights | autoware_perception_msgs/msg/TrafficLightArray | The traffic light state from image recognition. | + +#### Output + +| Name | Type | Description | +| --------------------- | ----------------------------------------------- | -------------------------------- | +| ~/pub/traffic_signals | autoware_perception_msgs/msg/TrafficSignalArray | The merged traffic signal state. | + +## TrafficLightConverter + +A temporary node that converts old message type to new message type. + +### Inputs / Outputs + +#### Input + +| Name | Type | Description | +| -------------------- | ---------------------------------------------------- | ------------------------------ | +| ~/sub/traffic_lights | autoware_auto_perception_msgs/msg/TrafficSignalArray | The state in old message type. | + +#### Output + +| Name | Type | Description | +| -------------------- | ---------------------------------------------- | ------------------------------ | +| ~/pub/traffic_lights | autoware_perception_msgs/msg/TrafficLightArray | The state in new message type. | diff --git a/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml b/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml new file mode 100644 index 0000000000000..44eec5284c03c --- /dev/null +++ b/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/perception/traffic_light_selector/package.xml b/perception/traffic_light_selector/package.xml new file mode 100644 index 0000000000000..62374ddb7c0bf --- /dev/null +++ b/perception/traffic_light_selector/package.xml @@ -0,0 +1,28 @@ + + + + traffic_light_selector + 0.1.0 + The traffic_light_selector package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + autoware_auto_mapping_msgs + autoware_auto_perception_msgs + autoware_perception_msgs + lanelet2_core + lanelet2_extension + rclcpp + rclcpp_components + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/traffic_light_selector/src/traffic_light_converter.cpp b/perception/traffic_light_selector/src/traffic_light_converter.cpp new file mode 100644 index 0000000000000..d67cfaa53de79 --- /dev/null +++ b/perception/traffic_light_selector/src/traffic_light_converter.cpp @@ -0,0 +1,117 @@ +// Copyright 2023 The Autoware 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 "traffic_light_converter.hpp" + +#include +#include + +namespace converter +{ + +using OldList = autoware_auto_perception_msgs::msg::TrafficSignalArray; +using OldData = autoware_auto_perception_msgs::msg::TrafficSignal; +using OldElem = autoware_auto_perception_msgs::msg::TrafficLight; +using NewList = autoware_perception_msgs::msg::TrafficLightArray; +using NewData = autoware_perception_msgs::msg::TrafficLight; +using NewElem = autoware_perception_msgs::msg::TrafficLightElement; + +NewList convert(const OldList & input); +NewData convert(const OldData & input); +NewElem convert(const OldElem & input); + +template +std::vector convert_vector(const L & input) +{ + std::vector output; + output.reserve(input.size()); + for (const auto & value : input) { + output.push_back(convert(value)); + } + return output; +} + +NewList convert(const OldList & input) +{ + NewList output; + output.stamp = input.header.stamp; + output.lights = convert_vector(input.signals); + return output; +} + +NewData convert(const OldData & input) +{ + NewData output; + output.traffic_light_id = input.map_primitive_id; + output.elements = convert_vector(input.lights); + return output; +} + +template +V at_or(const std::unordered_map & map, const K & key, const V & value) +{ + return map.count(key) ? map.at(key) : value; +} + +NewElem convert(const OldElem & input) +{ + // clang-format off + static const std::unordered_map color_map({ + {OldElem::RED, NewElem::RED}, + {OldElem::AMBER, NewElem::AMBER}, + {OldElem::GREEN, NewElem::GREEN}, + {OldElem::WHITE, NewElem::WHITE} + }); + static const std::unordered_map shape_map({ + {OldElem::CIRCLE, NewElem::CIRCLE}, + {OldElem::LEFT_ARROW, NewElem::LEFT_ARROW}, + {OldElem::RIGHT_ARROW, NewElem::RIGHT_ARROW}, + {OldElem::UP_ARROW, NewElem::UP_ARROW}, + {OldElem::DOWN_ARROW, NewElem::DOWN_ARROW}, + {OldElem::DOWN_LEFT_ARROW, NewElem::DOWN_LEFT_ARROW}, + {OldElem::DOWN_RIGHT_ARROW, NewElem::DOWN_RIGHT_ARROW}, + {OldElem::CROSS, NewElem::CROSS} + }); + static const std::unordered_map status_map({ + {OldElem::SOLID_OFF, NewElem::SOLID_OFF}, + {OldElem::SOLID_ON, NewElem::SOLID_ON}, + {OldElem::FLASHING, NewElem::FLASHING} + }); + // clang-format on + + NewElem output; + output.color = at_or(color_map, input.color, NewElem::UNKNOWN); + output.shape = at_or(shape_map, input.shape, NewElem::UNKNOWN); + output.status = at_or(status_map, input.status, NewElem::UNKNOWN); + output.confidence = input.confidence; + return output; +} + +} // namespace converter + +TrafficLightConverter::TrafficLightConverter(const rclcpp::NodeOptions & options) +: Node("traffic_light_converter", options) +{ + const auto callback = std::bind(&TrafficLightConverter::on_msg, this, std::placeholders::_1); + sub_ = create_subscription("~/sub/traffic_lights", rclcpp::QoS(1), callback); + pub_ = create_publisher("~/pub/traffic_lights", rclcpp::QoS(1)); +} + +void TrafficLightConverter::on_msg(const OldMessage::ConstSharedPtr msg) +{ + pub_->publish(converter::convert(*msg)); +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightConverter) diff --git a/perception/traffic_light_selector/src/traffic_light_converter.hpp b/perception/traffic_light_selector/src/traffic_light_converter.hpp new file mode 100644 index 0000000000000..db6d0a76c9c52 --- /dev/null +++ b/perception/traffic_light_selector/src/traffic_light_converter.hpp @@ -0,0 +1,36 @@ +// Copyright 2023 The Autoware 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. + +#ifndef TRAFFIC_LIGHT_CONVERTER_HPP_ +#define TRAFFIC_LIGHT_CONVERTER_HPP_ + +#include + +#include +#include + +class TrafficLightConverter : public rclcpp::Node +{ +public: + explicit TrafficLightConverter(const rclcpp::NodeOptions & options); + +private: + using OldMessage = autoware_auto_perception_msgs::msg::TrafficSignalArray; + using NewMessage = autoware_perception_msgs::msg::TrafficLightArray; + rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; + void on_msg(const OldMessage::ConstSharedPtr msg); +}; + +#endif // TRAFFIC_LIGHT_CONVERTER_HPP_ diff --git a/perception/traffic_light_selector/src/traffic_light_selector.cpp b/perception/traffic_light_selector/src/traffic_light_selector.cpp new file mode 100644 index 0000000000000..599bcc0f389f1 --- /dev/null +++ b/perception/traffic_light_selector/src/traffic_light_selector.cpp @@ -0,0 +1,129 @@ +// Copyright 2023 The Autoware 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 "traffic_light_selector.hpp" + +#include + +#include + +#include +#include +#include +#include + +namespace lanelet +{ + +using TrafficLightConstPtr = std::shared_ptr; + +std::vector filter_traffic_signals(const LaneletMapConstPtr map) +{ + std::vector signals; + for (const auto & element : map->regulatoryElementLayer) { + const auto signal = std::dynamic_pointer_cast(element); + if (signal) { + signals.push_back(signal); + } + } + return signals; +} + +} // namespace lanelet + +TrafficLightSelector::TrafficLightSelector(const rclcpp::NodeOptions & options) +: Node("traffic_light_selector", options) +{ + sub_map_ = create_subscription( + "~/sub/vector_map", rclcpp::QoS(1).transient_local(), + std::bind(&TrafficLightSelector::on_map, this, std::placeholders::_1)); + + sub_tlr_ = create_subscription( + "~/sub/traffic_lights", rclcpp::QoS(1), + std::bind(&TrafficLightSelector::on_msg, this, std::placeholders::_1)); + + pub_ = create_publisher("~/pub/traffic_signals", rclcpp::QoS(1)); +} + +void TrafficLightSelector::on_map(const LaneletMapBin::ConstSharedPtr msg) +{ + const auto map = std::make_shared(); + lanelet::utils::conversion::fromBinMsg(*msg, map); + + const auto signals = lanelet::filter_traffic_signals(map); + mapping_.clear(); + for (const auto & signal : signals) { + for (const auto & light : signal->trafficLights()) { + mapping_[light.id()] = signal->id(); + } + } +} + +void TrafficLightSelector::on_msg(const TrafficLightArray::ConstSharedPtr msg) +{ + using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal; + using Element = autoware_perception_msgs::msg::TrafficLightElement; + std::unordered_map> intersections; + + // Use the most confident traffic light element in the same state. + const auto get_highest_confidence_elements = [](const std::vector & elements) { + using Key = std::tuple; + std::map highest_; + + for (const auto & element : elements) { + const auto key = std::make_tuple(element.color, element.shape, element.status); + auto [iter, success] = highest_.try_emplace(key, element); + if (!success && iter->second.confidence < element.confidence) { + iter->second = element; + } + } + + std::vector result; + result.reserve(highest_.size()); + for (const auto & [k, v] : highest_) { + result.push_back(v); + } + return result; + }; + + // Wait for vector map to create id mapping. + if (mapping_.empty()) { + return; + } + + // Merge traffic lights in the same group. + for (const auto & light : msg->lights) { + const auto id = light.traffic_light_id; + if (!mapping_.count(id)) { + continue; + } + auto & elements = intersections[mapping_[id]]; + for (const auto & element : light.elements) { + elements.push_back(element); + } + } + + TrafficSignalArray array; + array.stamp = msg->stamp; + for (const auto & [id, elements] : intersections) { + TrafficSignal signal; + signal.traffic_signal_id = id; + signal.elements = get_highest_confidence_elements(elements); + array.signals.push_back(signal); + } + pub_->publish(array); +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightSelector) diff --git a/perception/traffic_light_selector/src/traffic_light_selector.hpp b/perception/traffic_light_selector/src/traffic_light_selector.hpp new file mode 100644 index 0000000000000..b21efaa2ec2e3 --- /dev/null +++ b/perception/traffic_light_selector/src/traffic_light_selector.hpp @@ -0,0 +1,47 @@ +// Copyright 2023 The Autoware 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. + +#ifndef TRAFFIC_LIGHT_SELECTOR_HPP_ +#define TRAFFIC_LIGHT_SELECTOR_HPP_ + +#include + +#include +#include +#include + +#include + +#include + +class TrafficLightSelector : public rclcpp::Node +{ +public: + explicit TrafficLightSelector(const rclcpp::NodeOptions & options); + +private: + using LaneletMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using TrafficLightArray = autoware_perception_msgs::msg::TrafficLightArray; + using TrafficSignalArray = autoware_perception_msgs::msg::TrafficSignalArray; + rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_tlr_; + rclcpp::Publisher::SharedPtr pub_; + + void on_map(const LaneletMapBin::ConstSharedPtr msg); + void on_msg(const TrafficLightArray::ConstSharedPtr msg); + + std::unordered_map mapping_; +}; + +#endif // TRAFFIC_LIGHT_SELECTOR_HPP_ From 85821ea1e97c12e9bdb6b5aa98fa7809e5f821a9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 10 Mar 2023 19:28:00 +0900 Subject: [PATCH 016/121] fix(tier4_planning_rviz_plugin): supress initial warning message (#2960) fix(tier4_planning_rviz_plugin): remove initial warning message Signed-off-by: Takayuki Murooka --- .../include/path/display.hpp | 35 ++++++++----------- 1 file changed, 15 insertions(+), 20 deletions(-) diff --git a/common/tier4_planning_rviz_plugin/include/path/display.hpp b/common/tier4_planning_rviz_plugin/include/path/display.hpp index 63788b8f7f9b3..d483cac062b04 100644 --- a/common/tier4_planning_rviz_plugin/include/path/display.hpp +++ b/common/tier4_planning_rviz_plugin/include/path/display.hpp @@ -84,19 +84,14 @@ class AutowarePathWithDrivableAreaDisplay : public AutowarePathBaseDisplay { public: AutowarePathWithDrivableAreaDisplay() + : property_drivable_area_view_{"View Drivable Area", true, "", this}, + property_drivable_area_alpha_{"Alpha", 0.999, "", &property_drivable_area_view_}, + property_drivable_area_color_{"Color", QColor(0, 148, 205), "", &property_drivable_area_view_}, + property_drivable_area_width_{"Width", 0.3f, "", &property_drivable_area_view_} { - property_drivable_area_view_ = new rviz_common::properties::BoolProperty( - "View Drivable Area", true, "", this, SLOT(updateVisualization())); - property_drivable_area_alpha_ = new rviz_common::properties::FloatProperty( - "Alpha", 0.999, "", property_drivable_area_view_, SLOT(updateVisualization()), this); - property_drivable_area_alpha_->setMin(0.0); - property_drivable_area_alpha_->setMax(1.0); - property_drivable_area_color_ = new rviz_common::properties::ColorProperty( - "Color", QColor(0, 148, 205), "", property_drivable_area_view_, SLOT(updateVisualization()), - this); - property_drivable_area_width_ = new rviz_common::properties::FloatProperty( - "Width", 0.3f, "", property_drivable_area_view_, SLOT(updateVisualization()), this); - property_drivable_area_width_->setMin(0.001); + property_drivable_area_alpha_.setMin(0.0); + property_drivable_area_alpha_.setMax(1.0); + property_drivable_area_width_.setMin(0.001); } ~AutowarePathWithDrivableAreaDisplay() @@ -137,11 +132,11 @@ class AutowarePathWithDrivableAreaDisplay : public AutowarePathBaseDisplay return; } - if (property_drivable_area_view_->getBool()) { + if (property_drivable_area_view_.getBool()) { Ogre::ColourValue color = - rviz_common::properties::qtToOgre(property_drivable_area_color_->getColor()); - color.a = property_drivable_area_alpha_->getFloat(); - const auto line_width = property_drivable_area_width_->getFloat(); + rviz_common::properties::qtToOgre(property_drivable_area_color_.getColor()); + color.a = property_drivable_area_alpha_.getFloat(); + const auto line_width = property_drivable_area_width_.getFloat(); visualizeBound(msg_ptr->left_bound, color, line_width, left_bound_object_); visualizeBound(msg_ptr->right_bound, color, line_width, right_bound_object_); } @@ -151,10 +146,10 @@ class AutowarePathWithDrivableAreaDisplay : public AutowarePathBaseDisplay Ogre::ManualObject * left_bound_object_{nullptr}; Ogre::ManualObject * right_bound_object_{nullptr}; - rviz_common::properties::BoolProperty * property_drivable_area_view_; - rviz_common::properties::ColorProperty * property_drivable_area_color_; - rviz_common::properties::FloatProperty * property_drivable_area_alpha_; - rviz_common::properties::FloatProperty * property_drivable_area_width_; + rviz_common::properties::BoolProperty property_drivable_area_view_; + rviz_common::properties::FloatProperty property_drivable_area_alpha_; + rviz_common::properties::ColorProperty property_drivable_area_color_; + rviz_common::properties::FloatProperty property_drivable_area_width_; }; class AutowarePathWithLaneIdDisplay From e92be64fee1ce30bd38cba141ab152660a9ae487 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 10 Mar 2023 19:33:24 +0900 Subject: [PATCH 017/121] refactor(pull_over): move parameter declare pull over (#3048) * fix(pull_over): declaration parameters outside of scene module Signed-off-by: satoshi-ota * refactor(pull_over): remove default params Signed-off-by: satoshi-ota * change double to int Signed-off-by: kosuke55 --------- Signed-off-by: satoshi-ota Signed-off-by: kosuke55 Co-authored-by: kosuke55 --- .../config/pull_over/pull_over.param.yaml | 1 + .../util/pull_over/freespace_pull_over.hpp | 7 - .../util/pull_over/pull_over_parameters.hpp | 21 +- .../src/behavior_path_planner_node.cpp | 235 +++++++++++------- .../util/pull_over/freespace_pull_over.cpp | 91 +------ 5 files changed, 177 insertions(+), 178 deletions(-) diff --git a/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml b/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml index d3a452a0db4f1..56ab9130ed19e 100644 --- a/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml +++ b/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml @@ -87,6 +87,7 @@ min_stop_distance: 5.0 stop_time: 2.0 hysteresis_buffer_distance: 2.0 + prediction_time_resolution: 0.5 enable_collision_check_at_prepare_phase: false use_predicted_path_outside_lanelet: false use_all_predicted_path: false diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/freespace_pull_over.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/freespace_pull_over.hpp index c08afe5f7b97f..6f5acfd30ef2b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/freespace_pull_over.hpp @@ -29,11 +29,8 @@ namespace behavior_path_planner { using freespace_planning_algorithms::AbstractPlanningAlgorithm; -using freespace_planning_algorithms::AstarParam; using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::PlannerCommonParam; using freespace_planning_algorithms::RRTStar; -using freespace_planning_algorithms::RRTStarParam; class FreespacePullOver : public PullOverPlannerBase { @@ -47,10 +44,6 @@ class FreespacePullOver : public PullOverPlannerBase boost::optional plan(const Pose & goal_pose) override; protected: - PlannerCommonParam getCommonParam(rclcpp::Node & node) const; - AstarParam getAstarParam(rclcpp::Node & node) const; - RRTStarParam getRRTStarParam(rclcpp::Node & node) const; - std::unique_ptr planner_; double velocity_; bool use_back_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/pull_over_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/pull_over_parameters.hpp index 6a78f2ed692d9..48baadc7d731b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/pull_over_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/pull_over/pull_over_parameters.hpp @@ -16,11 +16,20 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTIL__PULL_OVER__PULL_OVER_PARAMETERS_HPP_ #define BEHAVIOR_PATH_PLANNER__UTIL__PULL_OVER__PULL_OVER_PARAMETERS_HPP_ +#include +#include +#include + #include #include namespace behavior_path_planner { + +using freespace_planning_algorithms::AstarParam; +using freespace_planning_algorithms::PlannerCommonParam; +using freespace_planning_algorithms::RRTStarParam; + struct PullOverParameters { double request_length; @@ -44,8 +53,8 @@ struct PullOverParameters bool use_occupancy_grid; bool use_occupancy_grid_for_longitudinal_margin; double occupancy_grid_collision_check_margin; - double theta_size; - double obstacle_threshold; + int theta_size; + int obstacle_threshold; // object recognition bool use_object_recognition; double object_recognition_collision_check_margin; @@ -90,6 +99,14 @@ struct PullOverParameters std::vector drivable_area_types_to_skip; // debug bool print_debug_info; + + // freespace pull over + std::string algorithm; + double freespace_parking_velocity; + double vehicle_shape_margin; + PlannerCommonParam common_parameters; + AstarParam astar_parameters; + RRTStarParam rrt_star_parameters; }; } // namespace behavior_path_planner 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 3132a0c5fc45d..7fc12eb616da9 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -690,97 +690,156 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() PullOverParameters BehaviorPathPlannerNode::getPullOverParam() { - const auto dp = [this](const std::string & str, auto def_val) { - std::string name = "pull_over." + str; - return this->declare_parameter(name, def_val); - }; - PullOverParameters p; - p.request_length = dp("request_length", 200.0); - p.th_stopped_velocity = dp("th_stopped_velocity", 0.01); - p.th_arrived_distance = dp("th_arrived_distance", 0.3); - p.th_stopped_time = dp("th_stopped_time", 2.0); - p.margin_from_boundary = dp("margin_from_boundary", 0.3); - p.decide_path_distance = dp("decide_path_distance", 10.0); - p.maximum_deceleration = dp("maximum_deceleration", 1.0); - // goal research - p.enable_goal_research = dp("enable_goal_research", true); - p.search_priority = dp("search_priority", "efficient_path"); - p.forward_goal_search_length = dp("forward_goal_search_length", 20.0); - p.backward_goal_search_length = dp("backward_goal_search_length", 20.0); - p.goal_search_interval = dp("goal_search_interval", 5.0); - p.longitudinal_margin = dp("longitudinal_margin", 3.0); - p.max_lateral_offset = dp("max_lateral_offset", 1.0); - p.lateral_offset_interval = dp("lateral_offset_interval", 0.25); - p.ignore_distance_from_lane_start = dp("ignore_distance_from_lane_start", 15.0); - // occupancy grid map - p.use_occupancy_grid = dp("use_occupancy_grid", true); - p.use_occupancy_grid_for_longitudinal_margin = - dp("use_occupancy_grid_for_longitudinal_margin", false); - p.occupancy_grid_collision_check_margin = dp("occupancy_grid_collision_check_margin", 0.0); - p.theta_size = dp("theta_size", 360); - p.obstacle_threshold = dp("obstacle_threshold", 90); - // object recognition - p.use_object_recognition = dp("use_object_recognition", true); - p.object_recognition_collision_check_margin = - dp("object_recognition_collision_check_margin", 1.0); - // shift path - p.enable_shift_parking = dp("enable_shift_parking", true); - p.pull_over_sampling_num = dp("pull_over_sampling_num", 4); - p.maximum_lateral_jerk = dp("maximum_lateral_jerk", 3.0); - p.minimum_lateral_jerk = dp("minimum_lateral_jerk", 1.0); - p.deceleration_interval = dp("deceleration_interval", 10.0); - p.pull_over_velocity = dp("pull_over_velocity", 8.3); - p.pull_over_minimum_velocity = dp("pull_over_minimum_velocity", 0.3); - p.after_pull_over_straight_distance = dp("after_pull_over_straight_distance", 3.0); - // parallel parking - p.enable_arc_forward_parking = dp("enable_arc_forward_parking", true); - p.enable_arc_backward_parking = dp("enable_arc_backward_parking", true); - p.after_forward_parking_straight_distance = dp("after_forward_parking_straight_distance", 0.5); - p.after_backward_parking_straight_distance = dp("after_backward_parking_straight_distance", 0.5); - p.forward_parking_velocity = dp("forward_parking_velocity", 1.0); - p.backward_parking_velocity = dp("backward_parking_velocity", -0.5); - p.forward_parking_lane_departure_margin = dp("forward_parking_lane_departure_margin", 0.0); - p.backward_parking_lane_departure_margin = dp("backward_parking_lane_departure_margin", 0.0); - p.arc_path_interval = dp("arc_path_interval", 1.0); - p.pull_over_max_steer_angle = dp("pull_over_max_steer_angle", 0.35); // 20deg - // freespace parking - p.enable_freespace_parking = dp("enable_freespace_parking", true); - // hazard - p.hazard_on_threshold_distance = dp("hazard_on_threshold_distance", 1.0); - p.hazard_on_threshold_velocity = dp("hazard_on_threshold_velocity", 0.5); - // safety with dynamic objects. Not used now. - p.pull_over_duration = dp("pull_over_duration", 4.0); - p.pull_over_prepare_duration = dp("pull_over_prepare_duration", 2.0); - p.min_stop_distance = dp("min_stop_distance", 5.0); - p.stop_time = dp("stop_time", 2.0); - p.hysteresis_buffer_distance = dp("hysteresis_buffer_distance", 2.0); - p.prediction_time_resolution = dp("prediction_time_resolution", 0.5); - p.enable_collision_check_at_prepare_phase = dp("enable_collision_check_at_prepare_phase", true); - p.use_predicted_path_outside_lanelet = dp("use_predicted_path_outside_lanelet", true); - p.use_all_predicted_path = dp("use_all_predicted_path", false); - // drivable area - p.drivable_area_right_bound_offset = dp("drivable_area_right_bound_offset", 0.0); - p.drivable_area_left_bound_offset = dp("drivable_area_left_bound_offset", 0.0); - p.drivable_area_types_to_skip = - dp("drivable_area_types_to_skip", std::vector({"road_border"})); - // debug - p.print_debug_info = dp("print_debug_info", false); - // validation of parameters - if (p.pull_over_sampling_num < 1) { - RCLCPP_FATAL_STREAM( - get_logger(), "pull_over_sampling_num must be positive integer. Given parameter: " - << p.pull_over_sampling_num << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); + { + std::string ns = "pull_over."; + p.request_length = declare_parameter(ns + "request_length"); + p.th_stopped_velocity = declare_parameter(ns + "th_stopped_velocity"); + p.th_arrived_distance = declare_parameter(ns + "th_arrived_distance"); + p.th_stopped_time = declare_parameter(ns + "th_stopped_time"); + p.margin_from_boundary = declare_parameter(ns + "margin_from_boundary"); + p.decide_path_distance = declare_parameter(ns + "decide_path_distance"); + p.maximum_deceleration = declare_parameter(ns + "maximum_deceleration"); + // goal research + p.enable_goal_research = declare_parameter(ns + "enable_goal_research"); + p.search_priority = declare_parameter(ns + "search_priority"); + p.forward_goal_search_length = declare_parameter(ns + "forward_goal_search_length"); + p.backward_goal_search_length = declare_parameter(ns + "backward_goal_search_length"); + p.goal_search_interval = declare_parameter(ns + "goal_search_interval"); + p.longitudinal_margin = declare_parameter(ns + "longitudinal_margin"); + p.max_lateral_offset = declare_parameter(ns + "max_lateral_offset"); + p.lateral_offset_interval = declare_parameter(ns + "lateral_offset_interval"); + p.ignore_distance_from_lane_start = + declare_parameter(ns + "ignore_distance_from_lane_start"); + // occupancy grid map + p.use_occupancy_grid = declare_parameter(ns + "use_occupancy_grid"); + p.use_occupancy_grid_for_longitudinal_margin = + declare_parameter(ns + "use_occupancy_grid_for_longitudinal_margin"); + p.occupancy_grid_collision_check_margin = + declare_parameter(ns + "occupancy_grid_collision_check_margin"); + p.theta_size = declare_parameter(ns + "theta_size"); + p.obstacle_threshold = declare_parameter(ns + "obstacle_threshold"); + // object recognition + p.use_object_recognition = declare_parameter(ns + "use_object_recognition"); + p.object_recognition_collision_check_margin = + declare_parameter(ns + "object_recognition_collision_check_margin"); + // shift path + p.enable_shift_parking = declare_parameter(ns + "enable_shift_parking"); + p.pull_over_sampling_num = declare_parameter(ns + "pull_over_sampling_num"); + p.maximum_lateral_jerk = declare_parameter(ns + "maximum_lateral_jerk"); + p.minimum_lateral_jerk = declare_parameter(ns + "minimum_lateral_jerk"); + p.deceleration_interval = declare_parameter(ns + "deceleration_interval"); + p.pull_over_velocity = declare_parameter(ns + "pull_over_velocity"); + p.pull_over_minimum_velocity = declare_parameter(ns + "pull_over_minimum_velocity"); + p.after_pull_over_straight_distance = + declare_parameter(ns + "after_pull_over_straight_distance"); + // parallel parking + p.enable_arc_forward_parking = declare_parameter(ns + "enable_arc_forward_parking"); + p.enable_arc_backward_parking = declare_parameter(ns + "enable_arc_backward_parking"); + p.after_forward_parking_straight_distance = + declare_parameter(ns + "after_forward_parking_straight_distance"); + p.after_backward_parking_straight_distance = + declare_parameter(ns + "after_backward_parking_straight_distance"); + p.forward_parking_velocity = declare_parameter(ns + "forward_parking_velocity"); + p.backward_parking_velocity = declare_parameter(ns + "backward_parking_velocity"); + p.forward_parking_lane_departure_margin = + declare_parameter(ns + "forward_parking_lane_departure_margin"); + p.backward_parking_lane_departure_margin = + declare_parameter(ns + "backward_parking_lane_departure_margin"); + p.arc_path_interval = declare_parameter(ns + "arc_path_interval"); + p.pull_over_max_steer_angle = + declare_parameter(ns + "pull_over_max_steer_angle"); // 20deg + // freespace parking + p.enable_freespace_parking = declare_parameter(ns + "enable_freespace_parking"); + // hazard + p.hazard_on_threshold_distance = declare_parameter(ns + "hazard_on_threshold_distance"); + p.hazard_on_threshold_velocity = declare_parameter(ns + "hazard_on_threshold_velocity"); + // safety with dynamic objects. Not used now. + p.pull_over_duration = declare_parameter(ns + "pull_over_duration"); + p.pull_over_prepare_duration = declare_parameter(ns + "pull_over_prepare_duration"); + p.min_stop_distance = declare_parameter(ns + "min_stop_distance"); + p.stop_time = declare_parameter(ns + "stop_time"); + p.hysteresis_buffer_distance = declare_parameter(ns + "hysteresis_buffer_distance"); + p.prediction_time_resolution = declare_parameter(ns + "prediction_time_resolution"); + p.enable_collision_check_at_prepare_phase = + declare_parameter(ns + "enable_collision_check_at_prepare_phase"); + p.use_predicted_path_outside_lanelet = + declare_parameter(ns + "use_predicted_path_outside_lanelet"); + p.use_all_predicted_path = declare_parameter(ns + "use_all_predicted_path"); + // drivable area + p.drivable_area_right_bound_offset = + declare_parameter(ns + "drivable_area_right_bound_offset"); + p.drivable_area_left_bound_offset = + declare_parameter(ns + "drivable_area_left_bound_offset"); + p.drivable_area_types_to_skip = + declare_parameter>(ns + "drivable_area_types_to_skip"); + // debug + p.print_debug_info = declare_parameter(ns + "print_debug_info"); + + // validation of parameters + if (p.pull_over_sampling_num < 1) { + RCLCPP_FATAL_STREAM( + get_logger(), "pull_over_sampling_num must be positive integer. Given parameter: " + << p.pull_over_sampling_num << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + if (p.maximum_deceleration < 0.0) { + RCLCPP_FATAL_STREAM( + get_logger(), "maximum_deceleration cannot be negative value. Given parameter: " + << p.maximum_deceleration << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } } - if (p.maximum_deceleration < 0.0) { - RCLCPP_FATAL_STREAM( - get_logger(), "maximum_deceleration cannot be negative value. Given parameter: " - << p.maximum_deceleration << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); + + { + std::string ns = "pull_over.freespace_parking."; + // search configs + p.algorithm = declare_parameter(ns + "planning_algorithm"); + p.freespace_parking_velocity = declare_parameter(ns + "velocity"); + p.vehicle_shape_margin = declare_parameter(ns + "vehicle_shape_margin"); + p.common_parameters.time_limit = declare_parameter(ns + "time_limit"); + p.common_parameters.minimum_turning_radius = + declare_parameter(ns + "minimum_turning_radius"); + p.common_parameters.maximum_turning_radius = + declare_parameter(ns + "maximum_turning_radius"); + p.common_parameters.turning_radius_size = declare_parameter(ns + "turning_radius_size"); + p.common_parameters.maximum_turning_radius = std::max( + p.common_parameters.maximum_turning_radius, p.common_parameters.minimum_turning_radius); + p.common_parameters.turning_radius_size = std::max(p.common_parameters.turning_radius_size, 1); + + p.common_parameters.theta_size = declare_parameter(ns + "theta_size"); + p.common_parameters.angle_goal_range = declare_parameter(ns + "angle_goal_range"); + + p.common_parameters.curve_weight = declare_parameter(ns + "curve_weight"); + p.common_parameters.reverse_weight = declare_parameter(ns + "reverse_weight"); + p.common_parameters.lateral_goal_range = declare_parameter(ns + "lateral_goal_range"); + p.common_parameters.longitudinal_goal_range = + declare_parameter(ns + "longitudinal_goal_range"); + + // costmap configs + p.common_parameters.obstacle_threshold = declare_parameter(ns + "obstacle_threshold"); + } + + { + std::string ns = "pull_over.freespace_parking.astar."; + p.astar_parameters.only_behind_solutions = + declare_parameter(ns + "only_behind_solutions"); + p.astar_parameters.use_back = declare_parameter(ns + "use_back"); + p.astar_parameters.distance_heuristic_weight = + declare_parameter(ns + "distance_heuristic_weight"); + } + + { + std::string ns = "pull_over.freespace_parking.rrtstar."; + p.rrt_star_parameters.enable_update = declare_parameter(ns + "enable_update"); + p.rrt_star_parameters.use_informed_sampling = + declare_parameter(ns + "use_informed_sampling"); + p.rrt_star_parameters.max_planning_time = declare_parameter(ns + "max_planning_time"); + p.rrt_star_parameters.neighbor_radius = declare_parameter(ns + "neighbor_radius"); + p.rrt_star_parameters.margin = declare_parameter(ns + "margin"); } return p; diff --git a/planning/behavior_path_planner/src/util/pull_over/freespace_pull_over.cpp b/planning/behavior_path_planner/src/util/pull_over/freespace_pull_over.cpp index fc433f9f63213..69e71a54d0b34 100644 --- a/planning/behavior_path_planner/src/util/pull_over/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/src/util/pull_over/freespace_pull_over.cpp @@ -25,92 +25,21 @@ namespace behavior_path_planner FreespacePullOver::FreespacePullOver( rclcpp::Node & node, const PullOverParameters & parameters, const vehicle_info_util::VehicleInfo & vehicle_info) -: PullOverPlannerBase{node, parameters} +: PullOverPlannerBase{node, parameters}, velocity_{parameters.freespace_parking_velocity} { - velocity_ = node.declare_parameter("pull_over.freespace_parking.velocity", 1.0); - - const double vehicle_shape_margin = - node.declare_parameter("pull_over.freespace_parking.vehicle_shape_margin", 1.0); - freespace_planning_algorithms::VehicleShape vehicle_shape(vehicle_info, vehicle_shape_margin); - - const auto algorithm = - node.declare_parameter("pull_over.freespace_parking.planning_algorithm", "astar"); - if (algorithm == "astar") { - const auto astar_param = getAstarParam(node); - use_back_ = astar_param.use_back; - planner_ = std::make_unique(getCommonParam(node), vehicle_shape, astar_param); - } else if (algorithm == "rrtstar") { + freespace_planning_algorithms::VehicleShape vehicle_shape( + vehicle_info, parameters.vehicle_shape_margin); + if (parameters.algorithm == "astar") { + use_back_ = parameters.astar_parameters.use_back; + planner_ = std::make_unique( + parameters.common_parameters, vehicle_shape, parameters.astar_parameters); + } else if (parameters.algorithm == "rrtstar") { use_back_ = true; // no option for disabling back in rrtstar - planner_ = - std::make_unique(getCommonParam(node), vehicle_shape, getRRTStarParam(node)); + planner_ = std::make_unique( + parameters.common_parameters, vehicle_shape, parameters.rrt_star_parameters); } } -PlannerCommonParam FreespacePullOver::getCommonParam(rclcpp::Node & node) const -{ - const auto dp = [&node](const std::string & str, auto def_val) { - std::string name = "pull_over.freespace_parking." + str; - return node.declare_parameter(name, def_val); - }; - - PlannerCommonParam p{}; - - // search configs - p.time_limit = dp("time_limit", 5000.0); - p.minimum_turning_radius = dp("minimum_turning_radius", 0.5); - p.maximum_turning_radius = dp("maximum_turning_radius", 6.0); - p.turning_radius_size = dp("turning_radius_size", 11); - p.maximum_turning_radius = std::max(p.maximum_turning_radius, p.minimum_turning_radius); - p.turning_radius_size = std::max(p.turning_radius_size, 1); - - p.theta_size = dp("theta_size", 48); - p.angle_goal_range = dp("angle_goal_range", 6.0); - - p.curve_weight = dp("curve_weight", 1.2); - p.reverse_weight = dp("reverse_weight", 2.00); - p.lateral_goal_range = dp("lateral_goal_range", 0.5); - p.longitudinal_goal_range = dp("longitudinal_goal_range", 2.0); - - // costmap configs - p.obstacle_threshold = dp("obstacle_threshold", 100); - - return p; -} - -AstarParam FreespacePullOver::getAstarParam(rclcpp::Node & node) const -{ - const auto dp = [&node](const std::string & str, auto def_val) { - std::string name = "pull_over.freespace_parking.astar." + str; - return node.declare_parameter(name, def_val); - }; - - AstarParam p{}; - - p.only_behind_solutions = dp("only_behind_solutions", false); - p.use_back = dp("use_back", true); - p.distance_heuristic_weight = dp("distance_heuristic_weight", 1.0); - - return p; -} - -RRTStarParam FreespacePullOver::getRRTStarParam(rclcpp::Node & node) const -{ - const auto dp = [&node](const std::string & str, auto def_val) { - std::string name = "pull_over.freespace_parking.rrtstar." + str; - return node.declare_parameter(name, def_val); - }; - - RRTStarParam p; - - p.enable_update = dp("enable_update", true); - p.use_informed_sampling = dp("use_informed_sampling", true); - p.max_planning_time = dp("max_planning_time", 150.0); - p.neighbor_radius = dp("neighbor_radius", 8.0); - p.margin = dp("margin", 0.1); - - return p; -} - boost::optional FreespacePullOver::plan(const Pose & goal_pose) { const Pose & current_pose = planner_data_->self_odometry->pose.pose; From 0056a2aa88cdbc9e1a5971fb13fe26209360c50b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sat, 11 Mar 2023 13:45:09 +0900 Subject: [PATCH 018/121] fix(lane_change): use previous module output (#3042) * feat(utilities): add new util func Signed-off-by: satoshi-ota * fix(lane_change): use previous module output for get current lanelet Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner/utilities.hpp | 7 ++++ .../lane_change/lane_change_module.cpp | 38 ++++++++++++++++- .../behavior_path_planner/src/utilities.cpp | 42 +++++++++++++++++++ 3 files changed, 86 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp index f55dfe08c2de0..c0598ed7f04d8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp @@ -416,6 +416,10 @@ std::vector getTargetLaneletPolygons( void shiftPose(Pose * pose, double shift_length); +PathWithLaneId getCenterLinePathFromRootLanelet( + const lanelet::ConstLanelet & root_lanelet, + const std::shared_ptr & planner_data); + // route handler PathWithLaneId getCenterLinePath( const RouteHandler & route_handler, const lanelet::ConstLanelets & lanelet_sequence, @@ -439,6 +443,9 @@ std::uint8_t getHighestProbLabel(const std::vector & class lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr & planner_data); +lanelet::ConstLanelets getCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data); + lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 93987eaf5a6cd..0554c5d298aa6 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -98,7 +98,12 @@ bool LaneChangeModule::isExecutionRequested() const return true; } +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); LaneChangePath selected_path; @@ -114,7 +119,12 @@ bool LaneChangeModule::isExecutionReady() const return true; } +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); LaneChangePath selected_path; @@ -160,6 +170,7 @@ ModuleStatus LaneChangeModule::updateState() BehaviorModuleOutput LaneChangeModule::plan() { resetPathCandidate(); + resetPathReference(); is_activated_ = isActivated(); PathWithLaneId path = status_.lane_change_path.path; @@ -185,10 +196,14 @@ BehaviorModuleOutput LaneChangeModule::plan() BehaviorModuleOutput output; output.path = std::make_shared(path); - path_reference_ = getPreviousModuleOutput().reference_path; #ifdef USE_OLD_ARCHITECTURE + path_reference_ = getPreviousModuleOutput().reference_path; prev_approved_path_ = path; #else + const auto reference_path = + util::getCenterLinePathFromRootLanelet(status_.lane_change_lanes.front(), planner_data_); + output.reference_path = std::make_shared(reference_path); + path_reference_ = std::make_shared(reference_path); prev_approved_path_ = *getPreviousModuleOutput().path; #endif updateOutputTurnSignal(output); @@ -233,7 +248,12 @@ CandidateOutput LaneChangeModule::planCandidate() const LaneChangePath selected_path; // Get lane change lanes +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); [[maybe_unused]] const auto [found_valid_path, found_safe_path] = @@ -272,6 +292,7 @@ BehaviorModuleOutput LaneChangeModule::planWaitingApproval() #endif BehaviorModuleOutput out; out.path = std::make_shared(prev_approved_path_); + out.reference_path = getPreviousModuleOutput().reference_path; const auto candidate = planCandidate(); path_candidate_ = std::make_shared(candidate.path_candidate); @@ -284,7 +305,12 @@ BehaviorModuleOutput LaneChangeModule::planWaitingApproval() void LaneChangeModule::updateLaneChangeStatus() { +#ifdef USE_OLD_ARCHITECTURE status_.current_lanes = util::getCurrentLanes(planner_data_); +#else + status_.current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif status_.lane_change_lanes = getLaneChangeLanes(status_.current_lanes, lane_change_lane_length_); // Find lane change path @@ -315,7 +341,12 @@ PathWithLaneId LaneChangeModule::getReferencePath() const // Set header reference_path.header = getRouteHeader(); +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif if (current_lanes.empty()) { return reference_path; @@ -393,7 +424,12 @@ std::pair LaneChangeModule::getSafePath( const auto current_twist = getEgoTwist(); const auto & common_parameters = planner_data_->parameters; +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif if (lane_change_lanes.empty()) { return std::make_pair(false, false); diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index d5a34c8822ff4..9160e4aef11bc 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -1927,6 +1927,22 @@ void shiftPose(Pose * pose, double shift_length) pose->position.y += std::cos(yaw) * shift_length; } +PathWithLaneId getCenterLinePathFromRootLanelet( + const lanelet::ConstLanelet & root_lanelet, + const std::shared_ptr & planner_data) +{ + const auto & route_handler = planner_data->route_handler; + const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & p = planner_data->parameters; + + const auto reference_lanes = route_handler->getLaneletSequence( + root_lanelet, current_pose, p.backward_path_length, p.forward_path_length); + + return getCenterLinePath( + *route_handler, reference_lanes, current_pose, p.backward_path_length, p.forward_path_length, + p); +} + PathWithLaneId getCenterLinePath( const RouteHandler & route_handler, const lanelet::ConstLanelets & lanelet_sequence, const Pose & pose, const double backward_path_length, const double forward_path_length, @@ -2074,6 +2090,32 @@ lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr common_parameters.forward_path_length); } +lanelet::ConstLanelets getCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data) +{ + const auto & route_handler = planner_data->route_handler; + const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & p = planner_data->parameters; + + std::set lane_ids; + for (const auto & p : path.points) { + for (const auto & id : p.lane_ids) { + lane_ids.insert(id); + } + } + + lanelet::ConstLanelets reference_lanes{}; + for (const auto & id : lane_ids) { + reference_lanes.push_back(planner_data->route_handler->getLaneletsFromId(id)); + } + + lanelet::ConstLanelet current_lane; + lanelet::utils::query::getClosestLanelet(reference_lanes, current_pose, ¤t_lane); + + return route_handler->getLaneletSequence( + current_lane, current_pose, p.backward_path_length, p.forward_path_length); +} + lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) { From 0d4e4444fdb1ea039b26d7e87b3c4cd9b130c162 Mon Sep 17 00:00:00 2001 From: dmoszynski <121798334+dmoszynski@users.noreply.github.com> Date: Mon, 13 Mar 2023 00:56:27 +0100 Subject: [PATCH 019/121] feat(automatic_goal): add automatic goal rviz plugin (#3031) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * add first version automatic_goal plugin Signed-off-by: Dawid MoszyÅ„ski * feat(automatic_goal): extract automatic_goal_sender, add logging achieved goals Signed-off-by: Dawid MoszyÅ„ski * doc(automatic_goal): append README Signed-off-by: Dawid MoszyÅ„ski * ref(automatic_goal): apply pre-commity, fix depend Signed-off-by: Dawid MoszyÅ„ski * fix(automatic_goal): fix warnings - treated as errors Signed-off-by: Dawid MoszyÅ„ski * ref(automatic_goal): add author, apply clang-tidy hints Signed-off-by: Dawid MoszyÅ„ski * ref(automatic_goal): add maintainer, change year Signed-off-by: Dawid MoszyÅ„ski * ref(automatic_goal): fix package.xml order Signed-off-by: Dawid MoszyÅ„ski * ref(automatic_goal): names, initializations, main except Signed-off-by: Dawid MoszyÅ„ski * fix(automatic_goal): change path home->tmp Signed-off-by: Dawid MoszyÅ„ski * fix(automatic_goal): fix bad string init, expand readme Signed-off-by: Dawid MoszyÅ„ski * fix(automatic_goal): fix name Signed-off-by: Dawid MoszyÅ„ski --------- Signed-off-by: Dawid MoszyÅ„ski --- .../CMakeLists.txt | 35 ++ .../README.md | 80 +++ .../classes/AutowareAutomaticGoalPanel.png | Bin 0 -> 18815 bytes .../classes/AutowareAutomaticGoalTool.png | Bin 0 -> 18815 bytes .../images/markers.png | Bin 0 -> 70189 bytes .../images/panel.png | Bin 0 -> 64902 bytes .../images/select_panels.png | Bin 0 -> 160720 bytes .../images/select_tool.png | Bin 0 -> 86410 bytes .../launch/automatic_goal_sender.launch.xml | 10 + .../package.xml | 35 ++ .../plugins/plugin_description.xml | 12 + .../src/automatic_goal_append_tool.cpp | 121 +++++ .../src/automatic_goal_append_tool.hpp | 91 ++++ .../src/automatic_goal_panel.cpp | 484 ++++++++++++++++++ .../src/automatic_goal_panel.hpp | 147 ++++++ .../src/automatic_goal_sender.cpp | 227 ++++++++ .../src/automatic_goal_sender.hpp | 174 +++++++ 17 files changed, 1416 insertions(+) create mode 100644 common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt create mode 100644 common/tier4_automatic_goal_rviz_plugin/README.md create mode 100644 common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/images/markers.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/images/panel.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/images/select_panels.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/images/select_tool.png create mode 100644 common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml create mode 100644 common/tier4_automatic_goal_rviz_plugin/package.xml create mode 100644 common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp create mode 100644 common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp diff --git a/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt b/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..c6d4e30061626 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.14) +project(tier4_automatic_goal_rviz_plugin) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Qt5 REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) +add_definitions(-DQT_NO_KEYWORDS) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/automatic_goal_sender.cpp + src/automatic_goal_append_tool.cpp + src/automatic_goal_panel.cpp +) + +ament_auto_add_executable(automatic_goal_sender + src/automatic_goal_sender.cpp +) + +target_link_libraries(${PROJECT_NAME} + ${QT_LIBRARIES} +) + +# Export the plugin to be imported by rviz2 +pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) + +ament_auto_package( + INSTALL_TO_SHARE + launch + icons + plugins +) diff --git a/common/tier4_automatic_goal_rviz_plugin/README.md b/common/tier4_automatic_goal_rviz_plugin/README.md new file mode 100644 index 0000000000000..48fb577375714 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/README.md @@ -0,0 +1,80 @@ +# tier4_automatic_goal_rviz_plugin + +## Purpose + +1. Defining a `GoalsList` by adding goals using `RvizTool` (Pose on the map). + +2. Automatic execution of the created `GoalsList` from the selected goal - it can be stopped and restarted. + +3. Looping the current `GoalsList`. + +4. Saving achieved goals to a file. + +5. Plan the route to one (single) selected goal and starting that route - it can be stopped and restarted. + +6. Remove any goal from the list or clear the current route. + +7. Save the current `GoalsList` to a file and load the list from the file. + +8. The application enables/disables access to options depending on the current state. + +9. The saved `GoalsList` can be executed without using a plugin - using a node `automatic_goal_sender`. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ---------------------------- | ------------------------------------------------- | ------------------------------------------------ | +| `/api/operation_mode/state` | `autoware_adapi_v1_msgs::msg::OperationModeState` | The topic represents the state of operation mode | +| `/api/routing/state` | `autoware_adapi_v1_msgs::msg::RouteState` | The topic represents the state of route | +| `/rviz2/automatic_goal/goal` | `geometry_msgs::msgs::PoseStamped` | The topic for adding goals to GoalsList | + +### Output + +| Name | Type | Description | +| ------------------------------------------ | -------------------------------------------------- | -------------------------------------------------- | +| `/api/operation_mode/change_to_autonomous` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to autonomous | +| `/api/operation_mode/change_to_stop` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to stop | +| `/api/routing/set_route_points` | `autoware_adapi_v1_msgs::srv::SetRoutePoints` | The service to set route | +| `/api/routing/clear_route` | `autoware_adapi_v1_msgs::srv::ClearRoute` | The service to clear route state | +| `/rviz2/automatic_goal/markers` | `visualization_msgs::msg::MarkerArray` | The topic to visualize goals as rviz markers | + +## HowToUse + +1. Start rviz and select panels/Add new panel. + + ![select_panel](./images/select_panels.png) + +2. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalPanel` and press OK. + +3. Select Add a new tool. + + ![select_tool](./images/select_tool.png) + +4. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalTool` and press OK. + +5. Add goals visualization as markers to `Displays`. + + ![markers](./images/markers.png) + +6. Append goals to the `GoalsList` to be achieved using `2D Append Goal` - in such a way that routes can be planned. + +7. Start sequential planning and goal achievement by clicking `Send goals automatically` + + ![panel](./images/panel.png) + +8. You can save `GoalsList` by clicking `Save to file`. + +9. After saving, you can run the `GoalsList` without using a plugin also: + - example: `ros2 launch tier4_automatic_goal_rviz_plugin automatic_goal_sender.launch.xml goals_list_file_path:="/tmp/goals_list.yaml" goals_achieved_dir_path:="/tmp/"` + - `goals_list_file_path` - is the path to the saved `GoalsList` file to be loaded + - `goals_achieved_dir_path` - is the path to the directory where the file `goals_achieved.log` will be created and the achieved goals will be written to it + +### Hints + +If the application (Engagement) goes into `ERROR` mode (usually returns to `EDITING` later), it means that one of the services returned a calling error (`code!=0`). +In this situation, check the terminal output for more information. + +- Often it is enough to try again. +- Sometimes a clearing of the current route is required before retrying. diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_automatic_goal_rviz_plugin/images/markers.png b/common/tier4_automatic_goal_rviz_plugin/images/markers.png new file mode 100644 index 0000000000000000000000000000000000000000..8dd4d9d02bef43e70138d73378eb3f73d4058c4b GIT binary patch literal 70189 zcmbq)WmKF^wtJYaWMu7NYU6nRv6B~EiT1sckiC(< zqnVBMS0ytmBM3!($FGcxU#0c!zcMi}F@I%X;$&jyWMuj(C;e4OL`mhR#~1{}R|s)o z0VS8TlQn?5^gYqQ$Ts^RZ7im3`l>i0VmF*J_}&Nh1^`bb6=s{XI#H}PBgFHKYC6)lvuB~6+=*jcGr3t z-&~(C9mYo|m(h^;qX@PgDp4sXB#IwT>|~m}Wz0|19-9*%L)x(5&LF=0G7EUC?JOkI zr}szM>ipVXCHwkRtDo_7Tj#4&u401w5So+a!B&@vcypsOasWa6csuLG`wTSy@*oIH zd{v8u__V_}gK)7!BqBeJ=uxkcUem^wt0#L5__}s6Q8th{e-5tK>m{v0ocRJ&2|QAS zY1Sy0VZKpJ%pRjyj1b*+=*n2{;umdy{xw~TB?x<|8yBD9anxyoenk}zpF5Rw1w6`< z)ln^1F=WA2^jzS@J1Z7iH)Z*d_u~2bL7>kR!y&B}$`nL`TA2AX<{1sNP(7w178uoWnkG8+3QfYar^sa&y;hzOC=xq?n> zQT@!{zr9OKsjZgl1PW)e7mgh|ZowV-yHIMBCnP0ddx9QKDs(#|Lqfz;M)L9Q;NajM z9v&uZj7H+FA>JzvYAR7-;6?=MdcDSbfgZ`n{-_q#=jc=p%+1AP(rRQa9Fradpa=$Y zOUR?&xbe_x)cxt}BOQ}}*zeYnM|b2TDA%a()?;W(2!sb4`3(pjjB?G!{?XBsW|=1k z{mO-7O2vZD;K8db_xYzkUS?+I;W)}`t#eRul`1+E0s?~hd>N(C{rmXfiOQpcOCbRP zeTqLoN{e_AqFUP8|60JF6c#2q?05M!qU!$Q!sRsL3-}4)@ym;gpL{16B3)fwoAvAx z??d%tpsS1cRo`7izN)d&>pvC6*-v71>+0&z2+55J^ho8Xoj{}>U@}B@Qb+Bc1Tnysj)eIC>GoHpRs|w zx6X|?!F+T1M&lo$txGv1fvu`C4tm?rNLs_DJjB8(#Y$8kK7MR=x%{?2o(??Xv9Yn? z=HXdtb}(tM*N~6f2i}339dUU^v6xRn)$>TdK*ND)5T6QkJXS;GiuWbv#cZFC5nPWq zU0#X{nn|#~s_tz^S<0t?$D-HCQ^=P9FTn8(9)$1E9{CdS!NI|U(MZky?I}LBX8$ybJ3@V8b;9xpeBO{bts^a80JX*ZqOAkyh zHj%ykOiG-Qa$qme8Dm?BkUQ=iJWJEHK176spw%i*=bsZg!R+z&iLciM)u0^I2+@eH zqO7N5bgWxm^xEs}rfsqc;m5zn*#bsQ{h3~CeStS+}i`usvw-GacjM)BR<#f z1VCbYr6Y%%&CN}v5~UD>zR+E@N3a9?#wVZi!{dhLlGn58DY5XVCnrh&Z+CU9Fs}IZ zg^rb`PXg_*erf35&QbnJOTzD~jNz8=V?d{@7{AbGa@DJzD_d()ZrwnXt=)X2r`i33 z*q|GSt+w`?lYl{0^c-1&y;%}DtO^l1ID+1{o=wC1>5eNME7|yj2ul5ITly_k6_8z2 z9H?_R@QPMLaY#UVHj_HJRmoQ;IITdT_~Pc~J2&@Bu^b=Z3?FQHQ)_FkLNOBsu|=K< zy|5=5AW%r`T%ns3N_fUJU}=uwNzPzS}{aCt~Mmlk@6U4N+YT5C<0}R zk0h62qL^z>i8GxpKkwneCGay&3<(s%yWhH(N@jvmR8-_2UwSV;W`MVlAZ+x6_~Jjs zwEvIds>4J-z{zQB?C#w+eS^_zb*9~2dYB0C`1R{o1*_CQ9;;`4U5Bh273|SK)Zb6u z9j?1f_q*R8-2boQ5ce)S9Pqsb-B8FsMOX1v;A4*Xin;!(@n7TUi@yY2MwlP|`vS2s z9O0F05)=QlasOX!j21=fyZ_UKBHk}--S_7I=U=AZdLCSZeGp1TXRdR1wHWrCHNl7e z4%U%ByBoId=4SIp%T=d9vC6W@fs>~urgdepTE4q@<(S^V2%%DSz{Q8C__PYHKx$OY zCFdDDb6}z&i`+^)Tn7Qt@K7J+U@M{YAXb7s zEkh)TiuA&k&ObMmer_dF|25ygP_xPlJO9+Gy1u@zdFel1TL9+UNmU zot=Zl5{^e?ec7}Ol1!EU=3$eUY#2EgmtRQd0SSF0OQxfb-c#67MMq^y;EwgS>Ac6J1c|5Qk=Ifd21kYyBeSrhOetms=xZL$lTbKnKK}5I&bWq62mZJ31N!MQX8>e~!C$6*~xxD%JSvmgnK)n6D9`soIk7`d&cxlR64fgq2 zRFS!g%yjGl4c~8%T9^z^og;hMvkEBn+D6xTu&Ro$aWKaIIvz<+i80hKz&c|-CnZ}P zZ*^ON+E2YDRgjZe2tVCDhD!vbRn6<_46o<11 z&#sG<^ToDTsh(wQW^$Q_#v}hBi`{gKk0A2NuBS}YGQ8pJcm%QR1_dx@E9%ek_f6Y6 zN{Xpe@QIy+cug%wCbQJ-;dbph+cIurk?j=T*v7@PbC>|#h5keVbM$i75~Wg@J9*i^(za%i-+eAC~n6h zeR;`nKbZJT`CWK)FYHuf`Gq5M3K2f*!;zBHw;DIRjyT@o+EAU0q ztZQ%$PV3$C%p^qznXk-3;GJr(atDT;a_Dl!IxoF#pjA5=p78C_;LxT>2})EUU&ulW zcE&BCZa(Tq_mjr5D2|CSFo!d(XDIYRq!_6Tz7C0nUIGSr9iN%&#)m~j-hxJG82bGgI*^*<< zd>|9XaqR6idZiNG-Q?}R1rcGHOBqXcdgomPEP|It0xuy+V_XWU32zx%Y>%;*RVU=GQ8BOVAHfby+Ujs?oQccr-oOt>X zuv|_~3Ci^0(M@#0-R(rxVmne?@Dm#6t+9`lESWo3GLsB$1ufpsprs+n{8+u@_~(-= zV+^ykRlmpM1zXD`G%;0z9KCIk*#@anTLh{bT@jaU0-Co?V8?S6p|0mEv7|~wPKrhZ zG!NXN^JVT5+Z8Re73I($I0sXuZlu>k^_#O=+T8Y=(FPv9eG?+4X8}WFnRDUjo!kU} zSl$U!U87qyDc2!Q@;VI`Y(`@<7a=f=Kh`rV5X+o38Cy>(Rae#sz%ahd!EwivkBXws zOa5&(?e?rVeTC}v;*r_CX3ow2t74V2t2&IT1QC>U=Trs(mAHi@yPGhs6?ApcrPz3H zq;hsGMY*s^`_l0ioj+3kgYZmrMV^&eO;#E*Q_oEXw!rYXde(v=%#|xhj${%J#)-vb zLaPT`Vds&W2vL>8nLEb!_L-qd1W^joFPWXKWLCfOLoTXeN^cO&W?bcfcu5VS&G(yO!b12S| z#(L!6=7o2%DlWKp)uo7YAQ+mum{C* zBWc3?mH1it%WYjX{bw9B%<%1Wn{)k1jP6zi`j=LgPcu~REG8fB#XLvEtU5Ncr#^-G z23%0#NfEPp!xyq`Cx2N_go|yNW?F}zzO1pb z@7>cl@gZ z6)(}ZJrJeq_G+0~o0$C$dAH_9WY+fvq1>1p-z{(BTpCkv#{CDs{s$iaA87giDAKJU z&!K*!9#7{IQ&K_)oUf0a7VNl!xtzttMY+76(W};>DBm)FS7B9xshj;tQpr ztA21m{rBbZ+Qrp%*I5x97yPk6elAt5{DOuiBlxZQz}LA_RYvU3;OB?(emrVj?I5aF>cnS1Cw_mHhK*L#u~;1F?alkt zK4t2jt{kS7rBZ6=;IO^n^(G=8w`v`UBKTs`K3{s7o105|@Fo;4nj5|j#;b%E%Qo$? z^lxvNk8R+?<9^8F4m@(gyyWlno8XSampkvvWtk2lK0n$82av{x*Gx(5X^Ri3=R;8D z%|j@U_fUZcM`zV;?`Pog#khU=h*r?px`3U7Qnjz0hA^*&b z)Nj;jx!u=Zw)z0G;E+{TNXgCZ^?M8m+LV{UdWHYK5t>+^IbeB2#IMhVAjN`PXPmIu z@~BY11moU%PxgdGB`F{u&aK8CM`k0vFLx4Fks3f$W_x|vH!y>#XkVcPjzcJ2U*O!T zPq62_Ax9=0p7psy=RZ?(sfH%NCMfj+MdRdhZW1+zqMo*1z2fvx7tO?Z^YYc) z1pz3GuHZwl)C+1Z3k2s%lqw0NW+MF__MVX`2;N|T-*Whgx(25?(^@LF?S^sfEL|56 zuS2(gB+v6jEXF%hWC`R>Wz`>dw{Sr4s5VOHC`RNgYHH{mE63kuTKzR}zmgCgr}xPG z4c})=XX=wYj$8P}$1%Aro_eV8Q~3TvP6O0 zP_IgG4D`c^pC1BvccKqwn&K!G$r@K;+3;kCm5TWDOX}gQUI}9h?t1ArKfy$a8n&^7 zF#zZ}>Dq;cH$y=jXcn!C`n`}}GN`3CyDo`vrfWDoMOH7bD#tWukiOjhGK!3>^bsqE z!=L%sYrnT2Wu~3`U1W8QQl$mDyn{PN&H9Ac*wIXC%)SHNjy^m{_J{8V$bZ*MH1;ez z_R70FSFm_zKLDtY>`u+P+vDnW!7ty`nSxB^*m0wic()yZh7_6S zTgp5>KJMbE*8Mm-JZO+=2vYAWOg~m^_Qw)=DVa97_$DK~I}MqgL;kdk>Y33T<3&?~ zqOgQpmk)<%x7~F{>rYNz29muaYzwj|Uw$Z-Fn&Ip3Z2z^cS$CwuChq7HSQFH`^iotr4cH6~|&YHY?b;|*_r zlzOtm7sI@f-&Z2sXs^PL+kE2_^&c1JG$AaSA|@7Z6R!RK(vgR(S6dLpy5HtTkeoj? zzSj_@6t9pTt|-IHJJnGHCvTuv_2Dx; z_Tm*iVWqC%LXMexb7|Ry*#+UYpf*Kb*!Jqv8{<_h?_&IV4>{|xf&g>q+Ozewj=YHy zzhm!tnnGf(lhFvvN+InvaaciPuQ-%BHP)*1XPm_705&|E3Vr?+5I!wmu7qzK8#DlHuw^jgzL)P6kTIiHC=Kmn zCdGLG9^yM=<1sj|W3MBXi2IRaA=8om^9nFRp%mrg5B8#2V za2M=vi!@6yol@I-@<+xho|r&S1*(`2BI4(jVBVeaN&hrqo`e1;HfvkK3>?fC~LPv0V=4975@WjIWTB z$~KY+jbUY)4soBp9{r(*cl@6A?ZuQ^$47ws2c6u8ni;-KyrFkpMm5zvrQcR|D8weBf zx`Lj@LUDe{kb*IaOIw&u0{73o4wi5FTO-hlD`!iU%W5FdHO+%cwqRG82V!d6sqh9$ z!0y@yvnSB61cEkEQLOn=OY<)ZQ~sI*QFgTDT#w<=FT56Ct^BCb{%YcP4!^1aWQp0> z2t`f>{q~gQkwE=-t?&mEwilDyq0mrU$#bZG6DhV2*#_*Mc5uE_&==%Z!VnS?y11Zc z?=|&&=k6H4Wf>^fMT`$X=#zZhJ}2Vu(}*}^vxY;%J^b;oO`kUV(Rl7)vVvk?m4=)f z#Q4m9+9g-ZD8M%1*>LDFFR@&xsT6Xa??nf#WX@_HFQ}2&LLmwzM~sY&F1UjM9u>n) zVfl?OaTM|~Ov=ZX^8?H{^0E`ryB3d<$hesd8u1>3d&dl92Pt>hTuHz9|dK)a(sXyt(b@IaNmdo^5eCN*zFfG@{ z?@q<}xSXp^1`=85Z|vdjwi;_m&ngRbn1vnQvI(WeVyx|E6e=v(hjlgkUv5*?YDoi^ zY4QI4?mx9D*xNIWhgog6aldMrkAjCJOWUZAb$Hq_LeyGn_UoL>r__~rz6mHDjy0+{ z-5BAc;``vvDqcz2s2ZSnIL(2FRBLtb(R?cdX6AM-HP5H@-A8+hdg(owF|z0cOJ#iA z8O3Y5MIdn%oaxI=7sOCl#w(jF)liVN~)}XGIAnn z|1kXO1-H=|bsdOJxXL|}9lyb7m>8Kdqmi%WT}Zhc!ke9Wt@8$XkaNtCFQ3hV>^J%{ zvN>Sl{ye1B#_5XcaK?L9t~qs=3rJdb;XVZ(W6u<`9Cao#Ti@uUah7KpqO$&WQ8H<& z3oMRpGt*o`yM3H<=QSsXN}D@R28)9-P2@Ek}?mK+EQ} zkIq2Zx&<DN*N zb<8}9%`XloGcox(MoiM5Q0FR1chjVTpI$#O9y;cQt2Wfyn&9_IV)PHY1d)(i8?xLF z$Ry%Zx<%4Fr7azCJ}e8{{hHdRX*v|^tYBsM_yvAhzx2f5y0Q~(x|}J)vyV};Dl+++ zdL}oNdGCpN)xE@C(%i`^N-S3WrqdC*aXwd^tFZpz(}RACDW&56!%TTxibZ1?oTW~@ z;1T$MFB-#j=ei+w>#z_)BE)5dMFO?WxrS!Wv0l$}4ExP!xA>NJVjtsWb`>}vG!G88YSXIpjSyv=c_1XgVNHDq4j25d@YT+-2s z4fu}Z0t>&)I@kV$lSg}_YtwX~^SeVgF+JWtr}(-2B~8O)xVPuy!;2Ts61Gi%SUvKE zmCC>K)HG(EsN!BP*z?x!)svQ8+H|WX4Y?4*g0r49UrBmG3!CogTRKzQP?rp#3{`jC zo+*W7JEYB{;_pLFw0-C?*_ixG$QhFF5ow z2wVAkCs;V@kQ2`CcX`Aa$oAx2ei`|Rg`hhWhkzmtxls`upLgRC-A%z1&J^EEHJ8{T&##_bN*w>p%kFN9 z6^`=jEj`s0zyNc|q3w5CqlYV@Ww@Sw)nUc5;T`?-zm8Q#J142C=PgxB@{f{U(}-e^ z^5Zlo?W@A^tsM4tFqyz{m`5eg2_p1IXg?{~Z||WtUGtYax7XSzY;db!{lb+-4`{s| zh|gjB*GYx)3Zh=4A`OTW85w!9SWVKH3ZAq8UteDxNuJ7flZ`gl>jmw66q~%Gxzc@S zG_ZzYvP8L5M^n4me)FlpYQ;WR1039clZ8b>@+`mQ!MGEPBJ{Ar2nr1BXlMa<9-IcQ z#0G9Jqh*AqcBmX(L?28mRJNB>k}Dq17RRz&C%bMbyGKo*a#ic6c5@1Qf z)vbt<9eE<7{)<5*?|446@VSZGLW9&|`tN{%h}G3wM3VmU9e0_x*5IXqorGJQmQ8si zthBd-sEOS*=N@&u7=gIa&txXRhs3R39mS_Xt(|r0;_k^Ol9RmWL16UlL z^Ow>PupxVNsgsyINDFho4-h#VPC~O0M!0vuP=Wo))0O4oMzaIC34G}KcuoC%(PD$q zv}2QC8%KNqnuv$TrE`r-eJzL-fB#s97Q1ch+tmRj@w$}7e3|~~a((k!c;U{{z@Tgz zM|2b)2pa|_$TI%gc0^%bOnEmpLFDQzI%4p8mX7wpO*L%QIuPYslxD3lBKT>@FB6;W zX4BsjHRC8I_H=*!`i@2}Gpd8E+dNT_kLRkDOE9)Jm$ho*@h0K&L(RZEr)RtrTDya{ z_f=^--)?`Np+%aM8~$igoofq?CE?XBx%2+vMgf|=G`O*y6cecr_JlQ+kFeu~zwB~e zG!W`pVX*tNq!{0k*8>T8tZY3sV2QVbl~uAuesUFEk=mpr0#Ph8;1pOAY0)`dpG4Z% z0vc8((Q6v2DAtChIh26B{?HU}(M8^=O(r?P6}~jmTQEm)XdM-w3|F8+7iV#eQ`;edwVvh<$U;TvJz=X*TRQ#9Z>abRT%ml=%!s(szKSWEG1 zuSG290pxszcB+ZngKL8cvh0U9BjCgE8Y0aazF7H?zW7X=#x@pP5`8L0{}6YAmr8i{ z#vde(xVPBiIca(8%4}I%Je41go3TH(FX=CWOQQoQ%mo9_aVqHx#oEvORdL4NRG>C( zx7qt|ftd`sc;tI5Ie#QATfg81d0e1$5S@h_om5KUuK7)_>K?ff%9PoDHQ=l$Cy;zYO~+Pz zq&NO_#2BTn~ z5t22e242IWF0LkjX#nPV^9Hct8}&w?Gq=!zX#s|O`PzP_Z1|wi7O3#m2XM4PpQtw) zwIM$vGeIDP%FSXPzRSh1^=#d=l4|?5_#qJ4J@M=;evxl9s<*u?d$E=8Qc{O)v(QOI?pv6=>sgjDUv@ai(DEK zOCtnqf^A4(X3_ZeXl|mt!})ZXd#Yz*MjtuEhtFgjKM)b`&ewu!RlPH=JdnSD-9d(P zqNIzfh+th@QmHtr3LuV#MA#Ny?S?u&o;er;yiIO?1GY5hfnr!}$^7m?Y3#}IDHUb9 z9N~Hh-V*L!MqHlT3DrPR5}iGgc^7}iUoNs#=01~pRAz7a!kv|BZXFn}VGu==7|40* zKdltR6rWa9S&Xp7Lg4qWF;5@HEn$xn+r=meP;T*NIygo08NDt=0LZiab2ad&cqz4( zbLvlsx1`sSge*;Qm9lHg^ZcwdNc1EwLPpEZHUdVpa@u_vr1~dIPS8Sn5GkMeqH;p$ zO9&`6JBf*P%!@QLp&_ZLW|PO`>R;8C`^kFdzvDjzhTzpZJ~?41rY>?jRPZ1;nTTqJ zMv}nHEJ-5Hk~jULDIAeC?oW}0J&IdoQx@<#Vl7U6_(4XEBe4=QgaLD*H}j?CluruX z6J1IRp;l0Ya`!y*iil zzYS7PAT7g1(+30uOqHqEN}bnE(7J-~y4Ke-GI)R;523@f^K>gdCDyao(zS#0IL3{}tItac=B-jRlxEDX@%xR!CwBp?==`}CepWxo1t zBO5I7RB>Ro?TZeMI9r|B@*Z`*QUvBtwzyjo6nYON(tJ4JzQqcxd}*rF$0x9OR_vWh z@Qnn0UPcZ2f+eKYf`QkJirPggO)7Ylw~SeO^?xE3#(Bc|BaaEgls&n@&f+>AP^0{Za)5PPA8&qUmP!&Hf11Xoqlm<*25X%~LU5_1sjiC&U%sXuP9Aic~bwaCjyvLX`floz$9*~I> za=l(^Y074Zg?5xjNG+#taO^WAS+_JhivAh;^AK?XQ&+EWfB{PfKQJ>}Ay>Y%#xX8U zEh=;$up~L3?ixT5>MM~ib06x_lU#W)>GoyH<~8cPK&i0m4DvXT#aQa%vMf4nxwJj4`7_UhOe-C~ z%+ro#4FqhkaM?k>t2*dTlIPG14U8@tL-#H+?=M^$kud3(rm>a^%Ifcv>&H)w-Vm83 zpwLHl>U?qcy&=*Nsh1j_Aqj8`39lvu*QhY`dW$IXoPrY*l1Ne)T}NVSFhUETi6p(K zd<~!M!wHtcphaf+@v+vVQZhG_^*O?xJJ+#@JmOztkcE@;dHPk88f#s(3HVU5!L7Bgu%%t z%Gfumv2&_Ydk+so!d!p4tJE6IPSGwpiFusyh=VCysyBm)qTOz41JD_g6ZYpmb8@1q z#NKf@7_TIz;HH|BJQ}ULn%5l*L{Y)0uhlYsT)!qal`zpriOP}XA+r2p?XXuyDd3T^ z8N00?(|30yTm9?ht;#|LDe)ne=H)u$M`N;w90I(<8w)UumDdF#f3N@?(_{B*;OMn z&qAn0KNo*tzS=VSYqOJx!A$}9!KOcpsj;i8FVl@Mp$MXWMRRnc!gzF2TH(s?d z$78**d3(X9UpG3Nku-}Hn=?^`7s{FWT3&etSwM(#vbvp9b0|6WS(C{{Onf4)I9V@? z@fN~JoKNw%LEbI1G<81Wr+BvXDneb~Fibhj3D95`aMPH+wPXwzmUvA@dAM>tFD-KU7%hkg1$8Ti0u1^Vg60GwNK_1k&zZ4q9>pQ|v+cNdhf-V(n+dn(F z7Ti`~6szt68W639wqW3rIMH*>7nRteyrM#JR!Orcm!ckPE2nL`2kMgW#M}B~d?PF3 z%yvb$h_hHD2FAAhsQn&G6hD$BV-<7*9n7>l>39;Y1(@Ao6`}nvUF)DSlr^sU_9hOs zuZ(1BV2Nv}$;bj^^F0YSt}}M&UW1 zEDBujjV*x#8|t*%@jn}xs)eJDUY3j;8k}8X-(7OJqnE^E2sErVv~R^ZWU{F7ZtaHx zhZ|VG1nVi^vNEsSELg1=5?87Z+f%u$z6b`h%Xb|Aqet8_dkd+G;%W|u+s1OZvD+JY zSBpQ6d3`-0s`hw-=&xvvG}>!y>=XsFo@f3h*+){G30M;|VDaT3{kzMxFkhL?X{@z8 z<)Lb@5})F}i(_Pd{`QbS5m{P4Dn<65A|3+!qSNM+Snk!DxLbK;vxSN=Z8|y3S>d zECe-G{_)$jqBK>BhAWIMM3&Us;J0zy9k6HG&DVB6FcU3CMLl4&H|e3 zoHVd{6CZf5O$<8U_>smUUB0<0;MsZjQ?H6oV-}ri!v}TaZMdPGOO3Gu34qlmd0#1G z2ocOT;WLJ+*6TCv*mx zg_Iu>JL3muTPQkMpD&M#m-6#gq`Bm0x(>-LCrHuJc*CS7Oj^C^=Un9KDR=}>vu6ub zv7$(s^4J(iHf~+x01p^R7{VNi;lLBN6k7+pWMqKNW|a*QuX&mAeS+;)Jj}`R6<2|PG;H0cpMR$V z?HtQaWl_a6;W?j}O~vpfv_9J%jsmi3$|ZA;3Rc1C|IqMN@G^7>C_~6g8Dhp-i7q}F zHM42!NHJ<<@vpP+Z-?jK?9Tz1vN>Wk*vOjnMS7e(xPEdvjRp8XZ;(k}G}kBJq9QLg z>eB}tu@;KWEQ1%QPwqXS+7oNm3^P0e{>#LJz$%d@rv2Z6fRQY9 z#-JrU)F5p+Gx+_(9-8-kBc6fyoQUl9$0a0w1W9j7k1-o6Hp-F(o%S?n3DC)KyMpU3 zH-m`qnyD2gJ~uF*kfZ%PE%os0Ln6;}O??a;l@-bIEamWek%+Ah8_E5ru7d7CJ?VE|L*&nM&Llf=)_rQZE>3_e8%`R_A5qQX6SBU+xHa zP|-w~JlG9#%dD$xqEG&wDlKHJbI)*#%LJ2C?sOA@uOrMC6QR4p=$75VEh@5|MhgB_ zAr^3{NuXu(`*lm#S*|&1s*~l{(KY7@Ix~Ud#!lno6uRUN9qaB%k+1e84o&~mJa(!6@|}qD66nC|Uw{tZR69vp zwT51FG;oqCT(t%Z$6=%2+}_n7{w~X2-%hq==nT6b`tUu{9&219Ko45$R_tl@(O1}n z;6Ca1i>nrPM`Bl_7I{4&3>UNqu9P<}F}>1rQx`6u>(hXk6`QNho*Ev(rFK75^1$!> zmK0ZoY-aG4jf_3@sxB>QgwXroltvR66>6oaaDyR>XVX-d#5=aGzg}!YRPm4f8F5t` zEoT_yn+U^qT6f}v*6PDgMJ06>>N}lw{ct0BRkh^w6H!Te#i$jp`qC)F%IwSCk z#ZDvGlax0;$Aifh&2WKdw6Avz%$(4ufAymRiYYOXJa0C@I{6&oOg;TK(FZQgoLa}; z%Jt{b5SOoLyYJhM(e-J*b?1-Q(*6!LfW6Am0l%IsXtMx19P2S#h~YdiG4DJnK#I0t z8`LM};%X`frdI&An)59;2CF$kE(3&{L9(J#Rhu5pC(q%-d!pZDPxQ{qA;@Sz8CQFZ zTC1GtQ3G|^jn9-S&d%axN~ip(>Zv%|W1p0aIb2ftS9L94orsptuGN<2(Pj={)S!}l zEGuS-|4o4h%+ni{68}CNOOuC$3+m9{5~WS|)b5)lW8+SKnfSA@ zA@jHJIeV0w!OxnG>Z?Eh#(+`a_T)*sz6mMQl*Np{DRirpYrltP z0Mi!6KTFu&(Ez>J>tSK$o--cPFB==#i3}cHcadF8i^NlYqRm3_>lm&Gn7**XpG^*7&-Ct)9npBGs9MuX z-|}Qi?$ngY^HP2^MhV+aUE~`z^=05isCL&w?RQRi!noRHrz_T_%I7`ZxaCv|M@p zo4o7vNr?iAyrK4ZJ{CfTquq~Z!7;8_?wbV`dy=N!ILR5`&%y3)^R$t~!m3S%m3waY ztE*f;OFnErk7Ron^RJhKy}|NGpWkWtJZ>P=;s^|nUR&?55loe7Rnnwyap11SosnF* z$mb&*Q6Jf-sl|WOgm+egtzJ^C$)`B0ZeO2J$1Wpzx>w~DA4+$E+-Fvil$Sp~%F1&k zWLs`x?@191eM@D)KhGp>_=S~%Ap>-cHTS^5tohy1zOu+YLzMiF`km+UutV#{ba|`enW|^i7fomMW47@86cJ2nw&L+B_1vOYTgGw=a~n6hweC>{9zJB)T%Fqc$4h-!T}vI2w-~Yz5tZYS#qkXMOpfqO zy8YGINAQrn0E!|Bc}l*2|DLB6(dqGgheh?bKLT%Yc{yj!nD=Lu;Q&$!yUjQlh{GZx zdMvS-bpLN)oT(6e0Vr5i51epNDpf%gk*|3HUvgRmLvip$!!nKf(5$R1nz{Ui<7U7) zAy})VZk_p$!ZHL9xVx0`D#`rPM?Vs^Iax*^@Z|>V=7d2A!2bomhZ3)!-i4F&6cajG z_ce8ph8&n&WbgSCu*b)FtT6dUpjr4z-pzZq!$cOYJ32McycQ$;wC&*9xMn*qI^2E@ zZd9lJjen8vKPic|_;b^P6N%a%ScB8jmQN(%fZxMVHeL)P+93eVIVK8Xu)zN?vBG57JDi;Vq%c ztfTRr?@O%&)DJ!l;}W&dFH7F%brv)Nz!?agGO+d!Ws6lIiX>qh+r>YoKKpdxyDQzZ zIiP$5U~&O)j3>^BfNQ z9i&Q&doI(ZLuzL~VB0X1c7Si_!N)gX``wXqtJ1+eKbAEh%gh@mB`y8c$wu66T$2L4 zku~J9WFV;|C4(~rS}|_zotuBsXDtqzTb#ZTl)CC$RP^-MGM)0iMubr!D!QP65Vb8_ z3=5h2+Vu2aG{<%vuTVob$yy7XiL3Icp+*t@s#HK_zBvCtK!(HwZ;XPG+Mb8suYXj} zto07}ILzx2duStQS#`KZ6Z|eeNvrkSq=F9>1Cr0BFw^FP&^go8|C|A09Cllu$Rn-v ze*TEvPn<$0&U-`0v|8-TkajrOb@XN=;4@h3*~juIA=pl=_MFkc^jyZCN6gacu@mkk zqeE*4a3H40{1v|R996H4gc2IQI>(}gJ?snt!e{aIK16<8GG7RT;_@`v2y6~N(IPc# z-44dy@Fzoi%O3p;Ww{Pw&K-UonRT|goZE0UVG(;z{AEK;X6Nu2zr?^yaEOVDGX1xl zwAaXN04yw0enld#@6lfuXJ#i)4Otg=lB0r0^bfQRA`+YDHcvbG4~{DnHW2@QVH)EHG!nE}Dsb!wE&?_;FMvbdhReOG-rw5q%2Hi9C4S z*^sgR;Yyl@N3*=v6WjRjs9fXQucDHSx;C?52^cvZfzECh>YnFfk_4~yB34~b?jy}O zoi{aB>m)1nsR+ha;WAX#+GHJ zq@X!CnAUTLn1ilA@fQp^(jIV@X3s|*>CI4k+<))V z<3<~&bhj>|Qx_X>M~h^ni#LxX#+G-h#WPPZpcwSzm^)_{(j$xkWt7UR!}`Cp0+#2( zo2v}Durh8qu$yXlLYZ;d&6PdUDp=K8>-7GF-}VY474A$ejjp8xH)yeHA*}8%p2Niz zsYQp%>d?hG#lU|6+qGe4b)~n!^SgH7>~o?TMgvS3X4qxDs}mLz?tr-xeZtQ{RYSF3 zr%~Id4&RkMkvk0z*_fzg;)myZ#YPR5B@i^?s(r7qz_*+#El$9sp(U6!Os^xH^zVjf ziKR(?Aa(X+rATx4)$Nzv6fP!|x~&zH|7z=^ThN%sU)W(BeyoBqmdrpFz7(R^sO(6a z5BW-|GQJcfj;I={@!jFa6^Gs8U%kQr-*TMQ4U8zWH8UF!&a3;dVY+>6?Y`8-!M>O) z4p_q<>@FRvn&>k$bbT9mO%1zZBXT^>i|!u4sK4rsdd-_VwAOcHHJ66uw_kH9wc6RT zh_H2UM6r#lW1=H#b2L{W8LKnmdZ3VA(@?y>y!a|a=14zO{TKD+39#(qV-T`;CBb{X zp1{UaU{^OAR!O|rm3LAIK&2?sDEhsk%PMwVP zBNBM|a%bAR>)~Nnf1C?kc<4MvT7pIY7zCswgY8b^G{k^@=@17;=Sx!AYB=Hdlsb2y zkj0(@diOQO#lBH(XSP;h2t$l9K1?G*#gC=(yk(Xd^_FwA%PTAL$}Gcl z!t(QVmKZuZIzgeKTN@iOd4>m0oXE(?b}lYs4qiLMiF-iT3YZzb3HSBUXdd6_MV_er zAGn?^1hKc<9_WBFHSIrMr~&`IJZ6fda{#1a2jXN;5UHOP$KUSDlf_!|z#CY~u)_P@ zbE-1UkD{>w4qTCm29pN7Y_SepZ`kx++{=rbz~_z-3>)tw1y$}}oyZbiUQe;UmSBQn zCXf`w+cmV${rKr03@3Yfd$>nV#1syqM)!REbJTEdL&g(-XBy80>3h{|$@rw+zXiNj zhn*n?&l{`VvGmlG<5)TMPNMSd;n!+{j~tHlD6`t##}}@(PP75K1G?%hr4x82f-8b? zK748HXkzUmBfHMWEe}_#4}7}i+Ryi5KH6=WRMFMv&KJll3_j^s2$r&ByDr4Q&u6ro zK1BTrLbYBxNA|K9mBuW@9Nd)B{U!PgaR{#kSh~UTAnh#O4j(hV-ni@i zdpMHI>hh+~?Ck8OCHr|zEhKT*w}+SRj|ygRiTXEDF6wIwh1@(C!c$Bq{UfuP6R0+~ z4kx=Du%zN)Nvsb^3z-SOE>2+t$s$ekplQ%#Mt>>dTLQ?BO~%0B3l6Il82?rTgRZ^+ zW`fd~P_T@n#xOqEHEXIM+eM}RXYgJYJJU}uySwkHW!iw{N*!*IUM4?L`^aQyIC3)d zyRx79h9q}o9D9tZEe0#foAp_-clP6O>ux?!a>}OZCu>p6Fi(tIiL_O~C!&>pXi;A4p@j&maSE2^S^OrzSm{Dph7EYT4fMWq>du&INs>Bv+nIZI-<3`NTe zBegT;&v9j@2F1k$2+zVd9>%m}c-jRgbWQtJ&n8M8KEbA7 z_BvLxa`*i*sG?8wWAptd5ZApTbD*t7qsMm|&)D-M)V`3>PeD)(f*l?o&b+W=-04F5 z{G%=r9iQ&(qXn&EGw&wJv#$@RAe|Lz3XLYV}5Wd?lWEu()@&D zw?dz10j>1@LJ$9Rni+D&rRLim{CIJd&Xb$ae6rGVJA78Ss%Nc+8g6R3$Z6udn3muG zbeHw4t*aoy_7u7zGQH-^PE+Wjdg5?NydT*L;0^1^EnS03owE>N>VL%LaD&nwfh>e>SimI$8({57dk|Rqo>mZFUeO23G*9|Puh_Pi@BEU z>}Pb~@JeUM+;9|`+cwsxRN{%aLFcOk4^x&^F%&|T^x=4}N^;6dz1SVTX8=432BJmK4I&l1esC7>3w%I?m(utz)*=ufqw|26did4BR{ zh6mBq#-9VJ(VL9q()ucq-D{h)z6^?~SW(fUv00(U#ocN$(_9!F9&>txso>O#xy4Yr zXj27|Xp3?hDB=aO^F_Y8TueCeH z8yf4p{XVi;Uwgxqye=GmmMW4eo}fX3vVZ(YduL`>EFYNt;BB>xP8Yoe16c8pjz=x* z?N@Pilc)rr{L1b%@Uqrfi9P#Yq8%ZN|DVuKPRnu9C7S5Tp09|vBaG1;%`>(>VnTcx*?3GIU8PUQ>o);B}p0!TiXiJ z07SyT?>i*`)J`@c@1xgMJIq4B$P>(HE4D9B4V#K#S(HBG7$S<4&sEP$Q z+x;a-aq9h6e)yGp?9K3I+xS3keBW&h#h%;-Fw*-76sU^z|87T1KcmZXSgc z7Lvbv_in!48mGOzeF1b2d6kwt>1V;Dt?q8aTej+VZ#0PGDbKu4og;gqCwIWjRSgJ9 zzocuoxNMxBMim#U`%r{;m20>Bxw!bk&5etM6itmMSuhm?7+KZSI3{e>G&J=05MPJT zy&9uGnTqFG$e~rirsO-*UtS zn(+E08O#|nQ^lL`-fUE!DA!j0u0YxfSNl4Bi4;e{Kyfr=WAbz|n6w>tmwAbwaP(Oy zXyvl|v{$3B{brcrCe7^c@85*iZF%E2kQ|s?d5Vqxu(p8N9F@cN8gXn1NNaXVBYDRm z(D--ys>|c3r~L*+9W^LrcE+00OIKXNA7$HK{j38i4Rm)DePZ>&frm6_4$GlrbUDOm z!s};pP+DYddyEMxlg@G}xH*`OAIHnT$+Ig`^Z%m4p}kL*ydMVcgxe8(S5U55JC9ny z-wWGYImR^;4*aBTMvx$*vQGea>)ba}Q(1YhSjFm2BVm~!%DNl#q6`3`xktks`@GLRHt~wR zU{_Bzu(FUo*T73|JmE}6Kqj_57ACCe8)?<^6D@I@lL*WvKhVK0Z7JLMl*PvY_c|n8 z$;#B1%dcNtk1unlD?832_Htq2= zeuGlO*c`bs3bvUyO3pt8+4y|jl6gTLC7;82*(`Xy%${S!vnHc6d=5WwV$>c7%e)!k zj7_1LNwwVHn~7QQomr3l&Qhv-&Xak4omI-9_kTw(aKDn>n4Dh$l*2c6z9stMH5V!& zAI&T3gDso?)X!X6C1y1N*eg94JguhXg z>}9{J8FBsDsKLyGT%YHfzCN3*2X)gA5BVQY7@iIIUD?kKrQhaz7BfW^&-&gyIHh&A zZ(F4~0sG56s(!iKA&9-=r=XxAEjI0*3-|c9{{gy?|Bo?;p2ddz zW1*C!sjSK9yzBBXcD+6spqD_*Y%8F+BL%kfQ`(VGML9EPh3UoKS$*VG^8&_?P1;A++3ZmJnpzE*;cYr!}iuNS>rLK zd^G)h^P7+sYvxx=(KVm39UOD#(n?xtD3ZN=W>1WFzg&sO#K^${>oiwr@~gb%VH{m} z8wii&-LAbr=2ruS*@(_!R~P#H$FE~-&*8cub8gj#x|_*)k#7Cz61{NxhMGa7zeL5v zCALXYL|jk7LeJ(W2TD{dvZ3XU&3CmSMhT!f9JsdnMuwW@6qwBormMJMQplV2ZQ(9^@8YI3j%x_@3`W8dP4x>hVU zsuanzNkqx=NbA|?M|teAx@I`GWz(oe973YZqd5nOzA}&5#)LA&l?kw zU3_d!-@Lb;74!M#O6K+*+5}U+X^;MC&&AYksht@9i2qs;8~MdUY=IxCSgD?r*8qJ= zMdNpNBwAX>KpWYhYM?hE*Yu?(%+eKYo`$kpGrjC4Zvgc8o=6*m6CK|0AWBscg9iFf z!HJ7XK|DTG*eK8DlOL-@k{4Tn;eQLYv~Z~RgX zMkg^EY}tJgwk7eW3LkJ<+oZm4@glX!uiz|3>~F{s*4?FP+3M}L{sWY(EQAIe@Ku_P zk)bTg>n+*!SvLk2QwW{?rWv`OtFo%(~bT|w=Ov!%j4;T=>qILLQ z;qkb&wdC*5G-pTI4)%s#$~T;MudniTPMVny>e51KXDBR7z(g9a?$VGfbv9ZE*Bm!> z9rv6HW~*+b7;jyodWXv>l}qy5EpF6$SgeKmUN|B6oJk-wn-mLdh!%Z);~na>?54rU zQBN<>YSySm{IjB%ZC3(e;BM{jlL=i=iV<|XL&Oo9SkHWG%~$<5j->XVrdWLrRJhMx zE`Up}RUte%c_G$wVtdu(GzEu+a5N#Y96B20GoB>aDxy=5BX#Mv-|; z^O>_2rBqciQe~-%%-_m$EN}eH>FH@>l9UL7UT~~KEU>G?tSp_&(0$!Nx zTwJCce~G806bROaeA!$drl@s2P@y~cxrrzKB3$Sej{Zg7aPx@JzOgrX7b~bV|0HeT z-w??7fUE1@Rd>ypV}gG&GG6EPz;*Q1=MtUx5&G*G?nsdHTqX19i5l=J-(Gb9m|2mX zzytPghUBq%XyEN@-REPCbmw?%X@WAgG;YjKZD5R_+aBK6)5W`1SiSx8oEU`MDv9$! z9l+@9SkNEr)B>M#Xw4dIv#sCF|1R9}GegRH{izbIjV!pLp%g4?zDWQ1NGeZ~A7@@w z4SgQ}#-URZw)FB=UWkGVQ@gl(TB#HRYhAuuS(MbW3r`(7Hx%vDB0&YVu^qKpNL3g~ zFeUTP$2c0TS!4VJAV)mcot(Bc(i_M+J6JWQEuIJj!Y>7f^qqy*`=6-<6OFNa!Yuq3 zy2mRXA4+5{)oP4!j@r-sM{n$}GTq`Fyz^1&Y125;Y35m*sRX!wDBv(q2H$3xQ-{z0 z8j~ixa$XdYOVlrIfzw-`trE+&Roa>owp?f=j5B{V9nY}0{)68dFGV@<#*)2KSXbQc z0+y-2HSvTe_S#7Hfc^3T21dW<+b6oFf}yhOpH?$$hWVL}%|ostsO1Z|P)VDPO9*Va97_j}juxk=L$$9hTFTam}rp@6GkLXRB?x zKBCu9mfhKM++0($3^fYnBB&HP?{{{cZFp$Et#r{+!l7Ur44gqQ%ABXQeXAPF8jEq*_^2)X}1GzK8W)=+u z11C*eFR6r9(X)=7xMd88XG24%c6EPay*3t*)Xa!I%9I5x2SjZQ zmMrLVI9Yn%|4xnX7pXaD>Tj>-O5uweYE`9JD-)pxP9H)p+A?ZPc< z#5VyEB3TN%6et|gd$(xBH4`Xr|KFpm?@HAXUD@vNdiDERny_6#_E=F-`N|ao&cuXs z58!n-$->dQo@xQY1~Qqnfw!l0$%cmCQ~g-K7CtNFO`eoP4*M5n&5J#D%hPuM)E-_G z&m%*7O>X%(E*xZFBC$MMbd~JnAF5((c6aK<3hCO#0X>HWENf3m_R4W>8sqs4!#=_? z8!>>OD*Q6|RH%2pOXG-mqPsm19hH~L9H*QjAoN0g{lWZsMN>o>%ab^)D%#iO!boWz zT*TO|bQ;DDyC40%ZE74R&R-TahRjh&!wQsDsIYpaqtHx4R|V?rSLBF3{%+fCWH4_@ z%4=HwLmRdh^J@fh7|F!J+LMpz%Ahed&q0u{9?FO#*PFTC7o^{PYIwg`eo}H-mC)@6odB+IJ}=7 zcJ)Y0TSD^8ZTf#e49f>lnB`nO z@FMZ%7krV9dct#>q}xN=1n=$=)_^-#E$iqiNq%%TLsscs)cR=b$gkLlSL6DXp{6W{ z_{}Ux*6dWxVM~qi`Qh4=^EJ7cL(}$DdB~i`6Ks0P3U+0nJH-Dz>Ky+jE$L&6Vo?&% zoYj}4j*;WBMEK-&jDMht>E=cm_tU42!q7G>ScoI#`q`hzb*f&BbD)$KzcIeDzpLjx zT&M*6;*SrVIhU50OI3&@RwMK^4!N!U?_KzY1XB;CStG5)(_w?FSlRmKm!l?~xh@up z9f|W^c|+88S=fZ-QBkcqco)*&xuS2_+Q@WnddjkTUYW8RF3#nu2{2I~4^K4qJNdM{ z$dYxO&I6jQO%e0{fFvv&LmSnQ5FV2%Izocdn$JNW-}zCgmjAh)(}ge}-r+ToQ*a>3 z8sV0?ThJ!c1x0^$x+KDuy)Gz(5^L|w7!9pFZuuVX6ZO$GV1}tZE3qHu^eimP7m^5m zE@5)GfDHN&v@>jngloX|r?(&C4;$)^n;2CoLAuG&khYoU%RsRV2}6@_=sTPILbkcz z<0V8Jh-c^S17Ee^c-JMg2#2sQH(6&q(^j#17Ys71^<0=r6%05~Ipf9CQ|xUfe9)oM z#h(SSp*hEvM$}vl<)rM%4dGw0-Q{h|Hy|oxN@CmO~q$c%!9-f#q>RY9!%g?7- zpu1-Rtrk+HmTbHCHD;4MO}k<68G>AEjXBUJVN23p58q%c;bNQT?T;Tn1am|{VuTD0 zTkaxSTDXLSgprsGnxO@7N zaSK;)CO3Ea7_lgo%5J7n|EVn1Q~#Y?gH?!O0M#oTqP|jSl@b(xgmn>RV{^VH(ngU{ z#olpr?A>)eo#X9@L_~M02`y5QrYY%^3X+Mr>C&_`OR(MLMQ=?l6nDy|n+=n+ulBhA zwu)Q({V)x1w#D|u*_YNP*PDbdNn7T(s0wlU`zdxI!=m{hrZWuw{A8p;am_(kKb5>4_3 z#m|-4e3~3~9H^q;cXIRFHWn?qTrfADg{Y1*xg4bhHYL^2hwO%koX#UV-PlL;^2%&rfl71 zDriX;PPh~W*?<^4(xQ$s8}edyayu7?-%qgv@$2FPz;Qv99zN8;2&fj*M zdX=633_sDn8GVdAD{o>b)@2%@&z2bfc{l1E{pqExk&pWOVlb%5_2B*a&T2u6=PxN* z+{nUZN6Z(;7N$mPUE~nwEDu5i7+;=Tt1P~9bqmFvv3lDNDV~X>J2Z{;&ZLG3dB2@Z zWG&1Dw$wm}y~r^47Vr^%_onqI%C)#~KKe*)%06O%cnn7MNxI@gbiqBRZXl0=fe~!C@U=u=Wo}Lb((;AD` zw`YG;l@u_wnjBJdNLSHPM=~2M514yR(ZyLJG0&sAZl#N#93+@mLrYJ*8VclwWNpOW z7vIwLkS1>`6+!6U*Y?sxSX+z|IM|KxxAS`9Ol>-UNW%Y>_&lWlUhl8^^VV_a!j&}( zbeW=Zv(HpWeQ!pTkiEtDttJKv^A#NL(G|`4;+JW&XRM=qgx-}eO9e{6wT-j;D-ar& z%Z2*d{sgeRXCWbhOqUUTeR&RxjPxq%GcYs+>~@7qyw9D50P{C+aB!=odIVkFwd20m zcOGL>=KOWZ<)z$gnJNc+xU1?x9gYNX-*JLm2ZfN5uzArLjW3k}(iBY`v9e=yqDT-flZV?vpaHn`oIJ2J=k=1N?S3&6TSACptS+%dK4U zNB~%JKsw$--fn(9Tn25xvd28}_ z_%crVs45Rgd;djH#<6&?NVi-3i=wRF1_7U}N(cPm|8XI6KNzF^i+_w2tpFU;1zRUB zOkTD!HEuX0?*2=LVviB~yi%kzf(VCVI8quR-*)oRhu4Mf@(Tk+3)WgLw~R_YW~zo_ ztBNS8P0NcBhv!OFQ|nR>Xfg_tfr+(mxf~wBbHre6%fjVQdN$fj0536nUL!@%%0hUf z*c!9_@G17N_Kk}kC}m)x!>pbq^-Jme<^FtLbR3iy24e!5POdtfDBD$G(m4GFfE!eS zeC)qgHDmvFK8X#&m)>?Vu?eul#MUg)bxMa5gzI`o4=*e78r{#|=R%+WxVKdZjklnGY%Jxc9`0&;7A!=HzWPy)T{| zZ|v>u0mnyrgPw1R%ZfX*4|4T~sSH!&94jd|BB&)xA?P|Pei-e%#$v?}h>9jBxpSo^ zS=6ury_16pu&2)yh=6F8NQ!<(PA8mBn-4bT~L=|zzt@95mjyS$A!;aTV zOARw;#YaPv`iY(p-^3mEKUi16yHKRq-;G-`8N=yHFNywqwKiG67_EFS=FgH4>n6;E z2R!38k^93KzQWwie=i{No=gAxc5;AvUOP9-!NEbg z)h)ib*p!<2pt{|8y-gK*mu z_?5sTNISk5bqXx}9VUGtG76p~fVD+1?XZ za9~3P&av%Z$Nu>%5+-dGr4Yl<(X1uS33dkmL&*D+3Kv?cGc9&brdB3oT3kv zJI|qKJKxpZ%Vo}!#i>lGi9)~-VNOM3Cf^4;rn{{}JMO1w^?diI?MLn1q4p{jdszGF z?DFC*Q4AY`k^ai(x39!H0a|JRCl4@>wv23iJUya~Dkk1mt2sTdhZLcRbGkNOm9ov)m*T@c%A1O^)le z)O_&W<0U6#`*3D(of4HPc}iR0IC#38>J#I9hT-w@`z^!5UHad#K~iA9Ik~uU=8gdK zPIsFCo%(&*8m|L++$YlY7~6v4BaW6`E+0u+(csOSB;MA}n4ThIypHx&u(V-dZ?rG=P zeR-*7K;9(CE#0E`D}an|JCw`wA0!jw%kO5Y5|oygg7a2<$UnFppsg)OF2uKY_^t^7 z_3hSZYWT9i$N8x*H!LE|J!vThSlf@UZ4I9n`2Lx=8Q0?r`gYa}pjA~|P;`*A9nJ$M z_1hfXE7{|}1O2EagRsU_Eh zFRPw%u`Vqt)+>Uor-}y-*qNKL5q!?|wg{LgK5k2F&76esvW8i-@a4Dev1xe~hkz(( z1Yb;qDoCX`oM6ks>=$cJM=9*xsZQ6vIuaX$ar*9qARAxyxsq?Vg`a4_LbC(LVg_Gzv7)%t>Do_zPztw&PNX>%o8#vuno%jR zZsB^-=P=Nm(qVGfpp!NB9RA>Lj<=W!xDa&--|5%i1glQhRYKsA(vxd1WDYzxh$)jh z6!B$*?|}#SvUj1y)*cuLK_nX0v%2~+=($khSKwgjO|E%8`T{*GR7HsM-RWHjeW>-PSe!>fC6DrZanGWTor9A=3o~;#fSW>~Qm3%ffeIpo(xl@k` z$&76fv|x~cwz5P>8tWQ6Rcpa?{Id;Cs-R2^wC#aa1E=Ka;{{qTupjK~O?0|C7e=!~ zNaU{-Oi6Bk;5e@q1$VIIpPqCerK;}{-j0GQi7eTp6_b{M@;pAZ26f*YsU_aN2wKZT z!Jtuy7dMR1Ox2Sb*Vf*#Q-LYde#sie64^J6Tc5oi7%)ht{^~d?r_@S&rn?pEkFgd! z+qX$cwQbDvaSnNL(iylc0JMu4-x)TtW$y^6d{(K&KNQ-{IepEh5Yg)Z<6Wx{X@2&Q zBkW$dgetev==O(>7Rxx0y-to^n^Q0z;WglmFg^SE$lc1CvCA^0TEx)pJAu&EqPDZH z`HvP!q}aB9F;%agzn`0w&rq%2`H86_z1?Et^!!={@MO4<;z(N-`F&vHDfQ0G^j<6?H45y84O?tq$>~FH&YqeeJ z#WRjj2zE9@w{n5$AGlllo>x~`R1^gtKVyT6lk;H*ThX?L!ifk82MSqE3*yjv7O7as z9B3kr9Id2U`F?A1wpS0E^`o+q#$@;Gb7HrW?TJOO`a3S-MR>ffcePYEI^6h{*zf2B_OEMs=Dc+w>wD^{&Reb^4 zX5QwiUB7HiHqi2H{jZmsf!#CrMi-2&>09^KH<(a&X}cR4(q7xy!P_14E!Q7ao_&o$ zzJyM`q93`)2K1EgBO$G>0j@i zu|#HS;Lbf;%PWi66kW%%@;Jyv>f;8oevCiw$1vMo(m=g3j9_ag3O1{ir>JJH!+G2T zT7iST1%EVFZ5Y^OF$69=U)uXPB*9yIaiqFhJ3bFon#D2U17`p4=jE8`>O&ZYiyPkF z2#w=R(>klIZvJ1?M4}Wj7ias`4%;JF3Y_m| zq$Oh|1j1EadRbNu0|#?+bWHE#&e&C-9iv_@DA1~(Fmm^n1H`G@7lN>se6w_65VAHM zTsTvH`!4EWb0<2^@Dc6y3p8Sa^JXaR;VOqnn@rddKqXA;=`1A5#1mvXv7K6JbUn5p zIYdj$8?gYLN&|b;G&DtORR$Ka);7?Wx^8KIPEJm0lJ~*?qrh^4K5G}dpWJp{q!ZHR z!pa`!o{4r2^#hq;M~}48e_klG(MSpUEPwVjZja_Sn60a$4L)yAFTCj`mVB<;r?}L) zrt8KA?IW=b!S5e^aUil*IYyoUw~_)c`D5#2@=x^9a1X@Du{vKC<4}&duD(rrSl!7Tu%g7Wf6Y;0_RcC(Wcv70}#UE?Z1X=6?WrM~;aS*OZ86&Phz z#KSt97j*rKN%a>C4EbS^E%VpAI7+ifX7b$cKYobkNRU3STHI78gcZT;U+)u~m17!O zm1beXck;0MY>IZEd1%OLbBn;lpHh22T0Rp+a5Zxnd$^_&caTfec`9Wb4f7nylV%0*%#b zE5~c}LI?7H)U3E=s6^t*G+?IA5-w*N5U}P8$^Y&wS2dJ z#Kt^ZQN_5i%p1LC-H+hfu~;)J=?0{?_gueX63(V2kFE#4B^>fV|Grv^#+ug0j25|9 zRC$FyO32_36+I-C(0>qc|JqYw!)v$f>szNh2;&bWVM`f{?#9E$u%nLYV&xGc=@G}mYV&Ame}{FP8X6XhSz z)8gHEbXsZeacp)RaJ7kt2zU5a?l{}#dcA6Q28-)V+0fmLE5wz6i9*?A*7;0|TN-lp z3LYj_*^R&<_4J)rTgdZA#yEQdguTa%RWBdi-svHHvP6%#I_XrK{mD!YMT5JwxLT=S?_ogjWkskMqRC1~bDvhL(Gb1zl z2V70;$A^NOd!^-=Q^>TXR7UeF&Esi=`ekx7Bh-{aDcz9N`YH@3Lu4s^M*;}S|D5N> z)TR=MR>zRAMhO?*$jD29qmpq(VviQ{GToaM(^>o8Bp!wWv{QzGiOJ3ODlG@ceX{7Z z4lye$Fpmqci^0%k`zkE_>Ep*vph@-5^|klCnPYGUlOnd9bv_l<_-H}=PQ>j;^}M~F zpv7sOec|aMI{WccX8@^f2mJ5UmObwi8KIhLdeja!-CBqmWW_MUb3&UAGHyL#)v0o1JPfp1=ZlB1y68@qAz|YgZ%XLS~Sew@fLn{Ywyr}B~-NO7iqs^#<@GYh@Vk|xeY=&}rF z&b93y2r?z5~=aP_py6$NM|yd`hT~g4J7p_!+3h zT-=Xo`xsd=T#&Zj8Dk`I`$vi`Sysp%iH`EHW4p5omE2t7O@4>N5;*fXZhzALiFG$D zml%yuJbw)U@>GsTvoyeo35k)PJ z!pb!}nU9Rt)F(9qlX3y(>TtSf4tJr(XoNTQKgv=-+hVEWZ;*`ugqmTSNMu`zBUOSj&}*6)S#hDR!6%g9rZlJPrt$do%@4 zk83C%!|>_1KBkikNe?ob5>T|#N+zQLL?zXQ%yZ@8HPa&yu!#jD^;a&Pe z3PZW3GP7w{61@qT%!y||{{1zOrUr1eV76AW#q<>b2xE|%`pP@-vu$n9&iH?@H6a9VM9ucrbxV1?GqcQs^aRi#4*d{ZJI z7KfbI#e;v*diwVjXNC3mOkz158V`IGo*O zJ%s64zoCHxPs7&WZLN&}t~Bh>ozRvByt-o&;j8)AH!hEBbT89)OqTCC2pBkhd$u-y z;s(S&z|`4XquweEK#4#v*6@kis>Z*{J};`G%yt`d{>Jy-0WJ3tlpzSbyv(kqT;Y*cvKWAH#c{;DliXem?eMJL~&mPpB0`s zs}Tx02gc?|W@qyTm7e8I?QP+NJKnkw2vewt%>}0ji&`!dS~StabLu0zFnUM2V_(hK zJ3pPWS;xs}zvQeSIfrw{<%MZ|q}6U=e?P-BT54kQ51qK3t5cuEEt_UO zB5C0;eQ}2NH(ddUs>j*N`?K)(&rf)uW2fcG#O$C?%Rb1$u)eg%0-ZhV&D0SFZqkzf zPf^CqQqR}Y9kri?Pj}LiX^p@vA$J>^1DRXf@{7|3%lpAHFeKV^p)-SXN*SPK@*D1V zqt_p}xVV@c4%><_e4c23{xgr9sbI^t8{Ktdt$Mdy#f}-G`c<3r+DcTL<~P6o9Nu8`oZ}r6-+@Rr zkDP_ir?t!$L$)DEzKu3~AikmO#!E)4{Y+65shnYiWcxN$b zW70mA;SoQ)X{H-;q0hu_IPjTg>sR+NXwNs-x1(u)HDx#wAI-ti2Mc%JF{w0yZ=yYt zV|RBqDOFR!c%HRdfzF;{!)M2$XxWn7TWj{h0mR>o_#9P7rf7t%O&CND&a6)eg$<2O z(3;;UtMH_thGdExN1`yaNZ?&^vRfUT(j3%0+J3KGl?Xbqv3fGzV{ zK2`n39W&#;^!z$u@Sj?ME(#gxgPT&af)4N4n4?Vxlp4U{ruh&;z21|~^LCf^5y`=A z&B~*Bl}`<1s%mn|F}7=-UbXzhfCo`Lak8g4Q1&GFLB5sQH2X+TJD-N9xvpF%aZ{qfY1rXhhDH!_u>5D)`PY%Pah>nie(cW>CN9YxNvt5Beot!)4B^{G`N&Wl8 zOO7uK07eUsF9*u)nD9`MB1GW^3d`r*c#(VR*zE|z^_L&2=$wk7%gAPm7wxTQoJeV^ za;=4N*uA5+1Fq6j-6k&k*ElecdqUgza#v@?nNMEvf395{x)mgfyLUkQpOO-1@(t8U z&`mVNoOn}`QQD`Pp!n3ibEb+Hh;{mIy~p^QgVW&lBY`|{iFC(;d-Qg?J-Bwg*8P0; z9M^l4BUwP^bO$HsV2UJoXfSaK4^IXWmHQz4u_xybsVnUDbmZNtXg;IYGvacQIU7ww z(BOU1L)LAp@}nxkKIXCfvwTO}YPV)&OMG+3Y2tH17D!i+rO~{(cI<2-eUy1N3=0G) ze1trKKqw0*C+6Z}U;tfrJe4XeFuci$84(e2-wCOl&1$(Zrm~X$3lR|@ZKkjqk!6SI z=e3m@H3z5W;D~i`9s5fd9rh6mE3Bb`4ISN8TFpn+y=`AK3YU;K#6Q9YbKB+n> zF@h0bq7CY}J^p!l77-pkHiRy0sImO>TS3pZMlYVg%Ry^f z+c}&Y9H!24)wj^N1G|ip>)j2veRb+=h~Jp7yf2gA(}Ic=7eqg%e~i{qc|w!2!i(U7 zCzQa|c5`EQ+#Lb$oW0rT3yIi7(R5^>*m3=7ajjLxhIDxc%YJeaWnL}mKO~Qea52wy zp8Mm4obXhd$@x$T=vEV1X?8xpxS%|B`%0))$_Fw!J1JaT9;T->V$awzxDBkmh(Dt|6BPUb@8laY@0ROm=P7Q?P=l*Ek%llQ8+(+ir%RXMln7p76b<#ovj87P zmg2OE;E&ng%%d_C?hM-!Ivxrvdj&1S5;b1xt52RKfP zLm=_qSyfVlGYnpQKqu_s8QgM^1c#G0W{flyDB%x>4S!ddWZ7z4nq#Jnh{qvn<%N80 zsk%EE|K8<<0~{N{Zm&$jolF{%iwe)k$ga1?e^t4>`jwy5U0IOJR+W>($eyAXl?#pr zTPe~{G7mPg$W~Mxj>gE?{_YB`ea#2t=)rF(Zg%NV>&!Op%@?bT6GeX+Ri9kusZLr; zBQ&zskL61pYvrU=p_72|WPM&W`#mFWBn1y6$(IlZVqM`Uwe4(u|J>?(O^`%a-Y~o_ z%5dKDxO_=7Q3gXImiux@m2|p!6ITqM;w5iIf=1oYrJ%7TrP>jFcjsUmnY%4tZHH*- zn(m}rhdjw@sgZvUg;8!^jrS{LJ6~K#zJjm`8=L;GvwrosxJz~BSz52v70?|5^!;(E zQep7N=uF~Ah0b5O2w>t5fJZh@{Iv`GuvsT%>LIQiXdev$8wC~4rR+9Tzl>W?0q2m=UR}FY?Kvdna7@toFNy2KYRZ+`?bR248X8_H4k4dpw zy#02b$PQNAkG^$pEX=yy>6_{qV%ViF#mV4PTJ%A|OE6E{my#@lp*$ttO8 z`9iJ!(CCt1izlYZ@r7~|9n=-IiIvy)<;vA}Ew{<{Ty5#Ngstbw=%X+p>Rxn%)YEv8Ekhglz92l zrhaV;sb0lzo&BAfJKz1}bimm^?J(^!SH(_&gH~x*mz|x`*H`jmKlo#>&<}5l4ZTSy zNo!?JG8Fb$W!Ewg@@SnEE1wYFivTi>~ZraLmSt30T#rpoc`&mHl%#9%Qk8#EsXG%yCExKOp){Pg4ljxc-qA&j$U*6Cb+|0A8|r;c+R_L`6)zjA({)J<*PuLpq7Bz0wqPPxyng<*S+*NA4` zCWDN~NNb)A7#G}AQ&zcDqNP(@l^wz#^I@SwO)ad-o7vOdES<|ZCI|6~(&WK-Z3 zHC|n#O2bn$GRu4t1!gsTuBp!6ZFjO4*1FV;Vb$GiCD~;U#TUg+u3<0}PAk8!s9N0G z?nU_!%6L+hU1A~G{G}n#GC&VyfhU!$(;V&P4d0yjkhi*}rGH{k$OS?P^2BFbV@MEG zx%$EHKLn1P$P18jn;w<25yI{y)CHGAxdUOEw7sf(Lg< zaCg@vXmEFTclQMM;O?%2J52E44DK4--QhOx?ss?h?(Y4|@JvrnPxm>es!o+gxs=jG z98z&g6MNk%hRMBS0rl3Jf{{eCWKQ5tJXC~p!-K7H79uKWY14FRbvB#O| z#=PcgTq0)OqjPT%PlNg)Pg2xZm|y%J4k3X}l;5ul#7j#scaRB5s5ue`uMXnu_RuI@ zj#`cq5m@o*F;mrF#HeX3R&W*Nt5}o=#t)ct4Th!u-sBxil^Bm*#TBW$@|!Lr0$;DN ze?e}pGgH6h_sv=U>O=9ja&|K8xf-QQ_p8)M|9&B4gM{a?*=x6>xN;Om~hC9RUOCLikz-j+s9z3jcgVvPUmt9U6ry95l9wxIQGC* zhhc&k!0n>5G!-wPYfZ*n^iPVjnNgWmE)kgd?l>F>IBM>iqGTBVtY%b_G8)I0LgYtfj8}8=(@}43s8pF7N#_*1*L^p*ags(VRF@O}S{{~c zirA4mCLXg1d@9t`RSk_A`!uxrW2dz6T+9h8C5$_2L35V1=EjZ>lEZ-5FoWi~K|*P4 zmH9Cj2j~cPlU~TblO#dD#2Ax=gAOpd9LBl-uWHH z8qj(NDGNksO%ic*+JO@_Nh|-=&DwDw$lmtMoc%M6oIG3l?0fs(zZ3x+o&G<366CSdL*998`0%a4ry z@KgGkOjuvKG9l=nHW%woV-?7!X2S!f-wyx{Ei5ej5d$M0WPRnq4>Za^O6V4^fS8z= zl(b`J9?9};!SIg->!!cz2{V>H8)nme1jTn!9q3Qe6Y%tOlK2Qq^?G~zUHH#1DwR>B zqESU3bCbW`392Log|{RbMs2J#mL6;@2s#-ME4_M4ppjylAgI_L(PqtTzpQA(Fvi7_C|grs9YD z<%o)th#N`No}sx{li}!;O7m>gJb3%rwZ{U5=&udDF+dE z=omA_+1tJj9IVeDep_L%b--CaHB91qdy_Rtn1~0SlMP4=*z(Dt3q!D`1 z_v*PtLb8!5sidUT39pE*UaQA$F75GgyX41VE!{&l)bw%%Gka~{e9>p2S+bqV^xpXd z!`+oRY-~#ef;PMf&vPt;3!6phXoGM4qDr(UA@x9tQ{w0?G`Kh2-+i*InC$2_2s=$F zKcbl$>w4>h+c9qx&YMm14l|3WAzI5ngR1Jys2SRw$wXIY4ov+$Q(-Kb(`FM_k}i7) z-fjSh#TO{Cjse@8g`J zv&vxVf@G;MmesRn3Rg@fg8Vsu5sd~hQ}}iYp3F97FdK#UB5cSf@$%|RoO7b@%t_aI zz3v_V6mI2_=}JGTdqEn~^MgR%k8Rz)E23c!aCAy7b3jdx9baEc4c@Vj=!pLy3pBe6 zw{6}2;K{W&&c!5`MH0l(;#p2dw<_ZTrdV^MgB!SL4YSCm0?tMWUov}i zMDBQ9aImz*?tJHLINW-43heVY@|>F;2E3`8tuA+JNCW)r_Ea`n&el!3T%DZgjB;V8 za1w)Uh0Ukqq8Q+_3miZ>m-gyIL+tPNcrJNoGNlFvy61!Ey+3926nLLiG4(Gk5jY~C z+=Il009picIzr|S2bKfSaUFHhTMGIL&$@1A*QK1kT3Xf{0@I7SQ8ksRoDX#4j><7w+El@B_)6Am-ZoAP2oEB=0DIur58p~puF zp+~%EJw*k96T7AgI#Q2zR3{2@&;h`s^q?2@Pq=8`x0eCamxWAT`o z=_30pNdB?Lnvr#}pz3kxjzGRtj`vIdR(pSEKe6viT6k6xY2n=p2!~eT1$3*Zin_XipdSlQ5sLHxxI}iEL8^&Mp3%~(d+MNv516a zpSJ}7OViKiOZHjb%%Tbb5kJ^g#jyCK&ttB(ss{+ZTxu9<|7Z#Z3m_$t9w~amuvf!{d zz!39sW*FfM?t7-@nz50$@`?fkR%l*wTH30(h`PGE>+<>aCkO-rSiogZ@;5=Z+HZ<> zb#;YAM7)~+u0giLe;8(Q7H-$QNlZ`w&RZr{m)1Y}yR-Vo`%yTP&6oi;7V2XFVBgro z`WG0PWMHMU2fbj5+*3P}`EUqFaY>(#t-{vVXP!ZJ65tKb zPL0Zw0Cqrr5U4@{!~W|L#GKLX=DmcWuatpaYT*x2yjk{*1M8j{4WhMky%MWrj*x2F zNGA1w&~t&zRU7ETN2b#L#&J6I54r_vTU*Y=Iog{9r~Bl{q)fw@Ikfg&bM zrKGPO9q<_?8Wmg*mNOooo>G|fyR>CthSPW&KTTPdsa0{rnV|E^t3ct5F}JERfsTp? zU-}*g<0ZDqG9`Ok+py|%>WH{PMHy`7b{VT|Ha_)T`eg0*?|igC=o{iyzmet0@KO7w zON_*<2{t+{emQepR=qWP)Doy~?bD5eW$rlfoZ{igvN8Td?eO9Aa-y96DOp#M$|v_B zB^d9y6jiP3+I$df>Tq7UZVjgPi#pwr&fCd&vU1C0ekLs7S`=uO$X>fEZmp!AUZ8n* znoKE%YBu{_1tm%$I19b4d3g$gD|5b7N9&A7c4-`|42F$t4cK~K{`IBxiO#An1RT8& zSCQp8$1d}}4zaMg5hm5m&R_tqydfvAdi|Kpe{X* z3Zwil@VJ00pBew@<@hf&bjg+cCOlPFE%8qRkPrW#Qt$$y)Lnb^NrX@{+-RYI%?fw6ZbH7vkt)~OTatM*B zX=7Tz?k2b2aNS=176iww^M$>h37@>gme;k&=zn^Ar;WHx7QPsY*ES>Kj>9cNP9{3S zpzf1v<;u|iJCGf`$37ch(EqDL>i7~@J4+S!Oo5d~tH^e_0rRZZ~bRK5ZF|ZuHfS-U=p7zP8uxh@3Q3Zs2+H zb&Cp(!#+LZ?Y_4`L{>86rsN)k zO0Qd3-~ZH5OJ4WK5a>=WwQU_0iiKifRrOnk?We!uXr&T`g(cUH3IY+a8*B3*K|KQtx4l zBsE$_dSeyz0GVq=#Nt81tNql`q4)mD{rUE_d$wkpwqWvgp{T~y#MN1b1G|!b_fGc4 z166y@lgtoHlTj)cp>dBB_ge_fr^kRv5c^4z@2`jnWSVtrRKN2y2X4iPiMuDO1%BM1 z{yck#K+V8#{5kWFYj`|T0HZ8mHH_WHFp}rKi(x@0C9`f%B25oonorF`^p(XEoJE!M7wR=2wUC` z;Od&q5mX0V4WF}_@K)T~Y+z9FUnt7+9IO8%myrL~SA{~x1B%7ZdaUJ9fS5m2HyCE%R9au^*N zd7ON*hCBS-u!Iuo?S@LFQv9x8Awx?|emR0Ymr)7! z4IKS7QX;8sTp34jjjE!x9AHUk>rqoCTh4HFn5>a!Wj`6KgCw;-j5lW-@qpq zlId%ABmQrtFZDr7SGxBto!U9WbRBo?=H2cZm)?Q{pRe>u2vTLQm_IK<+eh;^s;n?cCi+!-ihJ{G~!Hs2|J5LX$fFfL(^&&3O6J_9)eH-(mXX897v zq^1lsa~hJ9#n}Lea0jG@;0SoRy=_$bk7BuLk~y)yrX1<#r&&2~`qqqkwF&(*y_F4h zw|}2@m&1#Vc=oan7KcX9s@PS)%$U0}vtwV8#+$dCrOw`C?_*6LE?^ys`Gw=gk)7<>Yke9%*w&dGa1t*rW;DGbK(l??~8L~yCQM)KIMYiDFlp-B=ytmK=#jSl; z9*Db45X^GDj8M2@(FjqurZ7Nth=F8jX^F>a6H!{q8SB2XdZTf^vfAQ&U>L1DSrhZa z5YT;LPj!=dFgZ|@q*K*?^x!+NV|7+nGx$mq`uz?k(UxoMn7^8<4!+Q`&DqtI|70m+9L;u%T}wP*qj;MOuRFdnF&- zXNiy(iObSb12!xOs}lUzo7o1E*1NlsbGgQ4+_73VFZ@L79aIC~+JsX3lJ6A`dyi~e zLfZ?@UF2tExXKTx8plM&X8a{8(@~aXg{HM95jY9(Nljh{7 zDuEGQ9jR1Zdap18HK5q*sww0COA7!L{xR3FlCflLq`btk(3$D*M1f&Nzj?ao~-?*8w=*@4@*kl3Tykg@yc0$my`Pl5Z^%V zY>n}dUn}gk^X~W$WI`TbNac~6;e{0*@i6^%NgoMoO zBhB95cXZ{qcFhAfP1%f=ml4rLM(pBy5pLEocoMUVSRnXZ&;2)6qoo0$B2vJLs2PJRG$szv3rn*%B!Uu_&n6zKpTR7nUQ~SU8;MPl@-D@K= zxBEz28gDO0ZCF&Z586Q9f%{eS<8%w|J@U!VXufFi*Y@d45-Xmdsc?r>z=huIEWMtw zgOI4}S*#5z@CKYzD9KX7^6>_(QMy)8mow$msc@P^yh9zs+VBM0{i%7que)O*8+A6z zEgQ(6b;HQ#VPRph`(LxlLW*K9gAg7kl^dvfFBi~wcvw|Ixx!`GJ;WMTnz!9Sxd zFzJ4l;QqIhq%N{tY@ip-Lp3!uRjJfcUpjl8V{=3HmX?;7a1e1K`!=G0sRh70zf|*m zwFRQ2fNk9NFN;9-k3y@L{`?f(!Lq$b*8n63e!cA2OSJ=(BxoZ7uD%g4v$uhZh5wgR$Lk zhFi2gI}aGb!GxlV@>;(AaOR*%z-GV@HiJx*q3l+Kf_*km75mPS8Ha8pTp^yubu9!IP!G%rCJ*Z_s;f% zz1Xk02Ul*L)PY$vLZY%kZLwLgeq`~{f$FNkfkl>aGtcJgl*TZ!qKuecH?uFXO!QM+ zq^+l+y88#sT1Qn5g3XJdnOnrA;m9Q9NYe4axY=3bB~*P1-;TpD=Q0p?)+~QT-L8#WH8#b1K8Dek7kRKCxJ4$(t?61dU-8$4U`3|k^DyITE zbcInpS0&$iAV-6u14H2`C=%H+od}?^3ki&l*P^EAOoQt)VBcD=n#>&Mr!7D2`Lb3^ zD!yyes;aO1y#NVs(LXsm`0*G2z^K9<+VvpO%bCM=2UtK&AC{!|vahf28?8r+46da3 zs{DQ7j*yWP6cJue&LN{Sb@&V=Ml9m$|M8ogRNh&5?961e#P)Zq)J8uc=?D3dYaQ)k z4Xw1c0Wp5BYDr#Te@g7s0|o!lHM*#Sy107Cy>{fH+zJ0TrK3PMuOW(~0FiVsa%lM~ zUyw)VNLA()%Hk-VnSy#a9yqeNTU`rsw3eR3olr+}#{0Y;AfgyF&B=Hh{D)`g`p>dj z$2ltkFHd(p)FX$>R3r|515(%aERq$MO}0EcJwS5>jgZBokmrYC*+>SJ0Q%41YEMn( ztwxafZhY@n-hh(RfN8r-b&kZYUZD$JaG3}UWujNt+Rgo%+QXYTyc7XFP0Gv%8`ww% zhgj|V74x>!eUd{D=YkeEz49-oyjhduy-4^^&@-|=(X#hGUw*HvJJpR)e;fJJQ$6kJ z#oNX=SW+NGa6xmlK{xkosk(H0Z=oE^fmonD_JIcRG2%{<<`=;gxsbsA;K69C`sL4l zev4WSFP)U3uEx@Akz=^+oX&r0xxqH#kCKOh^76TnBm0R_oCf z`mm(BZqedk$gsw0&_A>UZZu`bK79aHN#?B)=*%m|)|4=3brD>VBfS zaFU)_MzU9BZ1N5lKbss$+NHX5(L#mzDd3(RL+0@jcRkel)?_H@(oxkCHohN|3qm}R)h7Hx`_8!t4(E~`Va#Qn z@PyZ;NJk&?m%FDi>+4kiGIidYtH9L+H7|FG zV>79zk6qAS3!TW&X45?xO&WyBk6RQlUg#0-$2+vDApXx4R(>jV=10<^N5@k4JYh*4 zR`w6c&{s5)6eDX&Bl3sO?jI6tpE6lc9N1-gt1X!-@MgNuex(5^>>|?6$^-XQ2z3S7 z_{37D`;X9RG8rWM!K$a>nM3%IkLIWM-$s`xn^Tl8dlf?|DONrhRk`kbodS+$*Y4iJ zQGq7x80~a@$QRaG!hVF`b$zATB!ksT(r7SgNaelcTID0jV)Q(8KeG3}!7@@3HFAXI z=B&WWCL&A-za@CC>LofMo%84VoI_&PWxiwM{nGS|O8PF>DShb?v8X>!P8;tL3NkrH zHUMW2&46?Ytd|GfTDaD?dHo7zBaHG*w|(EYdL$V8!!VJyrb5{M>Z5z2cqveYd*P**^I94oKhoywlox4^{ z&T|P5?+f_h99RB6iP+!B$Wc)2G8r`4qk(<#6yIWSE;tp7_34&{NGuKQBY9{v_@+d4 zVp(a_C-i8SsbTA;AzKeEZ~D=gvEz-KDrV!?*n~r(X80Ek!Jf>hrZrq`MsWQ!E=8u< z1N>Us2F|usp1uu>q9PAZ&^z)3DXuPv$a3& z-}ic5Ejr{LxR4)a%Kn6`9d1W>Y=59UCTLZC!%^`txopUI;hQnGbQ(9cfAfz0d6Oh! zv;;=qA8fo_8F*P6VsKx6WMr9c=P2Lob%=8_O6wtWxFTlJTiJHwB8E3zEb(PIHNLTp zT%Q`A6K$R!2SjJ|$8)IK*Aiy)=aFqgJQDU?EhkoR!wE~9rlW;&ndlKPo4)KY%8l(^ z9dPHAebxK260H2&tf%-LkFSO5q`mtpT=8yj*6K*_?9kb<4hqm{`27vY*Mxz#uq)F} z16)$9B3iaeqDmI$Z)JI+*e&FrkB821VU}2M*pf!GG?bmwmoKqRPwq&k z^mg#O@D-o+W?ORNS6}D_g$rM1J74ih&kfN0!HxHbrLK04$i{f_{y&;|| z|NQizydFFT>(G@?t}AfT-R>yI)4Kighq=h(wlz7{gC-1p03I1Q5L;$I0L=M%F!9BL zsRj(&=|GrXKRrwHmCndJD?l(9~$wc!4ff z_XAsgx;Z>HnwHt(K;p>iOSpN3MST76#zvpNRyR?9(Uy)pK>ptJWNFvbA#)YbZ}+2s zcZR2xln}&dral<#{*1=OGJ^h&!XRXSG~8(EvmSTT&w77%(p>0Rq|zEg_h7|@M1P^; zP;?Ov&}lvhgq{t9%@_vLu{%N;DXmpRj4th}*gnXU_rx`JqVQ1tzI~GGaJ$k+cJ#Wz zGgpJyYY5{C1*->j>5mk!JYZ4mn+K=w_?z6d?CH^1k$(+hiCFu?rcTZ=Sz%$ag*tD1 z9dFrfKIMVE{TYZ&b878#wGt8m+naA+h32t4ws#bva9OK4J5?v;=??82%0w;4(u22? z*}TG|AFK@j?vQ>sX$rkrwwZUmmU&ilhVwpzhT+ilxp2N19gfryZyeiU_85nKyp{Ms z{BP{Uh9)sFEcE!A5`PGVOj*iYD?c2r#v$!g&e0!ZFP|zK zc#`SQT|ry+1(aasyLJXCiRyf>C#J&k)Zb;wHtkBedggqcpl;u7x$>WuR}EfGMrcBo zY0I18a&~4H(3V)O%o~#_h=7<_}gT3!G_;`=81uV|| zS^?{{++Y6)q^!&SyFf}t^WU)(K#3odoUE4pG`F~@SZgx!&YDy>=6kAGk^?C3(Jp1x za~{K$4H%w3k&yh%&VJ+%mHZb=vgofmy7iBuUxqYSP2)PY?sdxUFTy|`M+fHXo{G#{ z%j<7^ST61Au}iH@d9M$bn8g1wf;acCL=vN-o;A5r1A{u>G?8TuNVD;Hb1CDMZk__B z-5Qu304Gq3Yp<}*DGGRfU*XRKW?ruoI>uny2UsJ&%-8XI|9j1UndvD9UYBsGw#fcT zYxy4lfwyv@n%6w_kC|IT{`X!saihJ<2cdj!NLMpSR}U$V5yZ|b&vBOfPYtgohD2HY z>4%f*yv10UOWHtYUtdKzwvV$Wze36e39*4C^@Xo49 z*H3XD-y*(;!nT1qX==_HNx_czXb)J$#u~~kFDN*|OIq02i~BxSt_C}t4E$U9(PbzQ z4bq3Smhi*2NX6)?+q@lf`HFW$#_c5wx6md;?0Q_NqidC4r>@HUg419z5865>+!D(F zxSn0?{=V6X@QZPj44P;*)_!c`vva)Z0r|kLJnl0xtj;{?t?kCEG;wpU|NSeI29hyg z%G_MMCb~sh_@Z*GVX?1|6?OQ1k|xv5?H;n*d~@f#dX={Pg8RZ$p{kiWRW9X@!nrhb z2g$y8pyP^7yy!TC4~L!lT{J+|kS~yWA`D#qJ!O_m;QSR%mT%zF7K20Xe3=W4Vd+4k zr=yOxwMEBr0?+l-QL3}7#yt<0^2_rq73?ZSCMLnP6hn1prZ%U*qbtsZF1gO?o zd7Ce^kk>nX3DUx>r+o%B!$zHI~H-! z-=2xK9NM!H52mMwip#X6cdT#Nnr3~1R7T2wn6R-4ivJCd5hf!3y8OnqWn@XVF_^0j z_~mEnkUO#YPz0k8kUpGidEC3Lt*`$G7URbAuJJ#dqSgAY#9VUq?xaBl?qo6E1?1aj z`=UjH{)Uv<^TtkIF>O22M)nd#EZ9}!%hEC=Y7ay@Vivqn6HioHZr^H9M948vhQMs zCe$D_y!PF~U>lPuEqw$1RuZwVp3)qr*R&$BMYX6X^4KnNi&#pp2Kz5EuTY-sMr>gXj1NMbkO&pWb+#1LP`jCP^4q zPj1^3sVQ{W+X|!;4zxh(xxi~;&k@RYB`QeRn?xM8tvUf;@tRuS04_Ao&AvG|_+wg@*FsCNnB3_p^#8xZ5k)~cpkp9fz{blMu%g%k_Ww$1& z*!s?Vko1>0#(oj~$!E`&_*p-NA9&MNw;R#sQkDk!)y4$abId;nNP;a%ofH9Y2JQ*{xacWkgE^0XVJ78B%R8jZhgcDS;F5n+?rzefq|^L}%BpiR%7%bqarF`lD8o-~ z|6uN3Y@V125RS}}KAb9-l5g!dm@aKV+ICH2Pt=UqUhO`+6oyAeZ2w08w^~fTbNr35n|Fy{e3+MiSYT}Y1VI&yv_U~`zeXXX#2#APYbPw)_jVplx0er{WuO|QG zqp9qcM2j8y|6~vRf6D1U`1rwA<#A>?sQVa&d({oDOjN$vC&FKwf5k46U zI^U>6;i5C&3#aGvUeYAz5a>LZvys(3Kws9>iynWdY=Cu@^V88#V6n*ec47j#)}s^t zx)(3}Q$wyk*A@R*i~Gm>Np&J;B>>mHwVnrS4btsA{F_*5<)iF1Wpj@wsEGYEobdS)%Cgom0cq z`qRBe>~T!s^jzEy}bIoWm#-u_X1@;fyOLSrAiQv=tJh@ zEoZIU26K8=KYk8~>0q3+QYjvdTu;E0bk@-DPx-wdmdr^|nLxsvA-UHvQq21or2*MJpw;asZZ4y}i0#_aSa-_3 zhGgFqNBhPGpbnHk> zdW=OaHQ8YAQ0!C_Y)6F@VOj_o9uB*%HMDu|xoX8xABliJvAP!oLd&xzuVC#SFAga^ zQ9^OPl87EwT(4-9sX!D;C9Jn*6-rC%EfetA!&FM-!&D*_$`tBN<;l=+1Il;YM^B>3 z-iIm+Po6wndFX)1fKBloU@QD-#qqd#Csyj67pBfAMTBk!WTXW#1F2G-=#XcU&D!p$sJbwaiEAljNim)XhJl?mIb!&oG7 z18-H7;prlW&+U8pxyiGCBD4=M$=(#J&D_w6`N+aXz_1?Qm7Ol^c!rLYMwu)%gsp|& zo3P=HXcK$u`T9t|Rd6}eum5(-mBN&)^#L%!jP?m@D#J`_YiD$KE*VO}A0d@cpW`fN z+9o-vez^{83Y63oC=@DqY?@E8AJEKf$n#nA@|aW>sqry`8ian>+}7*Sb0ASYqd-)5 zzJ_Qt;wCk6=5q4H6&YX)WbppTM3Mwfpzkm?I856F-G$XUB_4e1qlO-~k&x|X%HmJk|5u(FDhB}>M*4r}1)k;Ge7eU?2QrS?x$~oR!x%{ubiCN-; zt^9*`A2w9#I;WKqtNSNzxB_(_U=0}f??=xh=lgiwr7;M7-VE{Y6iuC<5`uUNXB;am zO=nhYwkT^Ym5k5b=L}s=Nt#@2v4}d{O`C(KpW;_>2#gBnUVOllt!Z_Mqm?EW(qrR> zMhH9M9)(km@g1L_Tn5DB%iG@2KhT+J6|-GJEqKkRZ(VS{?GlmumllAv<9H~U#m9Dj zNR05lmfQ^kp>d`^t1P{3KMF~$qIM}(`-54bo?u{pu zD|*YEJcGuLCH#Va%n4$h>%4I8VaY{l`|m@t=RQ(ct$g*GRkeF(mE?MMfD2n1#o&MZ z*J;JgkvhoLELY16l$;{$EbS+5{%KP$#@TDW-1q^)tjM(uz$q`g-z75*vTp z3TCTk%dC6eaHUxluTX%~kJ~-HchKUgqnLU#cP?MFTBLM--8~D!fPcYYPVu#R9Ns_ssA^n9AVYB->+l=1B)U-%tfog?H zxzo{~Kh4DQgUekh1^&CuRw&rzazU{115@lqAH2dMDo8D-lq=1J?u-nW6g7N@r=F~F zG)F%y86B8r)s%f9?yvzTsG16YH242RX!cZk+P8a$crd`zLjOZg50iVk^vI0%n^|BmM(T+n8yY zM#{;H!qkFkU9JZksK~#=8`=m>v2rI|NyfFeu=|k7t zA$rTG+F&5yke}v)Sng}R*{ZuyBDiO%gW^oWEFmk8k|3f{KUY&4Clo%JT`8DV2?QMe zEmY!smza0BMCh-3w7;auW|eePd)J7OI`$kj3SFo5LO&=(N*a9ge$+Ho}}}UU?&$W7)dB_lCE@F)x;!s&VUxAjeV^E)0~ywI z7fN|i@_dVc5QxL@FoKxM)Hl_b^!{vNh~oU|nb~+u5V(=kbxVbyms=0->0vN8Li;=t zGr-T%=b`+E(efA{Zh_2U_&&dqc3@mq|vAfno2xgW!EM~ zt$JEEg!%)pLVGIZ)kD97&YI%=Y_c_N*1(exduLPdDDVxF6}s%Rrvi(t=Du%9yO4hZ zwNdgyQf_=rU>PGmH;rSj?3De`5mf%DbXm#akwtNduR809*y6N%X?6Se>GbEumd2(f z%DAmfRcASy!a<9!y~~2U>D=w>K_$ze7NgqY&CNmDJTb}o-NAOt#^Sh5TADaRLiWwk zud1ph)AAJks?)Ba`<=$;Kdfjr!aW8LC%$|89@w%s#+02~)hlV&QyaH4X->PI$sef* zm(KN$B+QqzYb5;I8!f$1ETfGx<-8J#Rk$HM@r?f7*t;M6qaeYtvd^L~<`Pq5Du&rO zo?4c%err49DldG>~Kd3TqGuLW6v z5gf8I5L2Ukk`+h1uEv*L&R2E3a**j2u3OaNhOhKPKy&)2UHn<(YQRvTpr1e(feJGPB0|+Nw}N0$gnua|J|^v;1t9q}Qi%(WDNj`V;Zu|# zsIXH13smF-Dp)g+YgXMPWg%=e7FZIfw!^Olb0Ae4fs}1{!Xay|m z7kJP3TNybrlS{B{Q7R;Ei`c1DT6qnVjwm<2@^dX{Osg}FQ2!t+C{jD%zzARbQ+mYtgY4RNQQDz7XzFZAk7_aFb0mgtJ)LMm z)Jd&gfA6p@wwdE(uC?-1)U;Jg;io;$j+f72vDTWXPAA5VeR11Q4|0dmU*qW^$pYx$ z9lPOn?N_#EYT8WqXJLzn&U{(f9c&q$oKsBcHG5Qrx_C^)fTIy=RRhcL^f z4UN0$<|9qr+baiCd26CZsTC7a3LdPjjj-^QtZSi`wHBXuwb4sPtC!!c#%AL_)AKR6 zHtETPZfkg1grUil>+RAee1JRcnjVR^ASNawXZ{gv>Q7>`wOE(wm7wB?HCY?NeRLA~ z=zdBy;5$}O-HKZ~A2Dww`{&m(*=k!)K{9LwS7z1@!?r}^u@hZKB+r7xwoG4X0RnYy}U4J`3{WCw#g&OQO#%ysvdZa)v)1qnJ@i!QA#N)m} z(#XJyd{=P%LVPe#QfJE^Mf%m2)$)kL#YRUetHz}fJR4Y7AT-Z4!|)J_PwiW^S7aG) zrX*M&KBJa=yh^x!+lNvT)0FyL53jgCasmft#4|s$gk)-18TX>ZkUiehuZkt^Oshbj z92h_$5jpqOK1}&+J0q-}#;Z~TOQPsqXm62tDzNCN)%j>EKIkrGm^#V7e6;hNj^=TY zGWLPwe1Bp%phe?{;h(dLwqK8nfrOyaVp-n9u;E0&uyNpXe8C?NV?@a`dia|-XG<(H zX&_?WzJ{n`rAEgwj!$HFa$rAX#3Q05MZm?gng6!6)O$~LkF0jZHyCn3V$M{IO^%rD z?9dm=Ww42nf4J41n30SwAF7YQQRTP;W8%#47;>}41~@^dBncU)-`fawwEyyjo*bn-Xj7KAOs+j=u@`KM%Hpt25AMJr^^yJCb}}WJV;?8k2RGkfw5SMn6F5IXei- zaGSR7JdiH4_r8GXGH9&!!B?_XNqa!qGmQGkjx%o9Z6VFyfKu^*N6163rcgs<4sw4~ zdMs*h>eT5yKbVs*Z^HVrSm|sJY--mvz30rn$-fGC;tOc=^%@51)fUE1$XX9K;*=UDFSle?O+pMS#{$(EHSiAv(EhJ4`QSB`}l zn;()U1-8JO2HK&$n`6AC`{Auko=Vp!|EqUk;)tFKNNd|{Ax}XVW}eghw^aC%f70bpH3jgOD4Ws7=ueH4fEnMr*^@|+J}9nO2pFS0ine4Yp*`C zn_k1SAm3(5@iasX{C@8mRn0@@kny?^*-~Q>N^~u#|npM>ZZQ-;} z$K;9(SmS;+;}k*Ql8oyQkT4r5pf9kvUS5nDgv=7j%}?K8kk=lbUuR(Co2wFBO1=}g zJ>T*lkwA+&xur8CCenMoM3w^Me%~nJY~IL!?<6J&6(12jR7##(-3i=DrLFwjm2dW3 zzy0Sc=B27TKmSD?{`N$uCggg2`L}1h8OK+Y3E@ZGGGm4N?`8>-o2fKNOy;U^k*eWE zc{lFfa6mhQ5q%-|SiYN~Rq{NT@EkILBgL_5T~M2XR*tx}4V>Bh z`CQ`z`hhBrmE3o-3d7do*^Mh(x}`AVt~b|XqUPBTs$a#+F6ysv?{(!+iGEye>9-88 zt@l(dC3g4F)=+No`LZr;YTQ9Q;;I|hmHtR(O+sDl&}Sk0H6pjTJUGV4$>zfE+fu-Z zbB%5_ANMIkQg0(wF!)R!71;t(XOo5eLuStJi!b6e?FQXpl-EUvk!>LIM6}acoU#@& zg8H#iwQAq~wvy<(^3fojo*<&q>Ulj~F{M`ycQy+m%ujru$W?p&_Yr6AuQ}atAUV2# zS1XNerVvDV{Pdpm88UKW(=C1p9X%R_3+2Ccu4vh2I_PQjdk3N@?ZiG8sSMPCuu3U;W{ z0_BFSpI=S$X`6m79gwy3+Y$fxxH{Arq4>bRMO2Cl~Q(-G*(f;vzltDQQz%c$8F z@O$rHT_Y6S1BXr8j&Wdw@upR8Q*;H%cdZOIkEf__%p`(RBlZ~=Dh+H@(y+^+PNc=GTpk0mT|4} zNBE;HR8v!_ENGN1`(8eW^1d;1OQ3M3!bzJdt=S4#iq* zfg;#^F;-ncleory6{qFTsQ)p^HU98NE3W<|gz?t5N`3T+MQs>+avyi9d5QBH%L%$5 zA=D(P&km5kl}FM2C;!cg_JI>bwrNiNu}n?oRwwXQ=CGagFZ9^R#hM%8IhcxAGD>C4{= znie(-dc?JL<*s}xDK4LJEHSI+Tz>ITHB(qwR$xxS%`!jC=Xh4IQfR46tX?pSU)#z3 z1>vLM?|CFYdSXC*xIX}j7un7{9BXI%O>HtkR?Le+2r{0eOdk@2igQtE>v;7Uwk?eY z72>Fk7hd}Z7Opcy&=>!i6)TS0d=$nAv z4;+TI&&q8B<>e&?&J>44DdOEF%LtYP{C92Tq01z(@mJ!tx)=`YDqck;oQ5gt_HS&5 z*Xyz$?~_2M7Gy7l%}>TNfuZXUxrqH$0dKk7rgDlP8+yw0@yufl4~5ssUDM&LS}sYp z;;*fmA|M+U$~GWBM)6(IQbr8$TdBT-PETO5MANTfpuW81Yo7cF%6bXo0dYP9u5mK3 zGrd&5+Ff+*vP0GJyT^xA z1&vj1UI$kSwPa-cVtf#{isr9DPQ*&Or@`;DLdy%uc6&Q*vc|(O~-tu zO+)(U3d4kih0-}Kt~bkzqq1e=UYc^rhz7Gs#0dj!&Z2bPKg|} zik9~(x7v}0Ga1P_7t|>W%^{fG_3W2A`BR%8XUOMrgA%J}aN}aVOy&zAij&zBB{la5qWxak3bV5B|@5p$(IpSHH8;q??H_)y79tQsa z=-8XxGZ{ay@z78Tx&EVbxGC8B+&ymo9e_*~D4dvg+`VMZb&DOJ%NtE2fA5|W5SBN2 z7YNoXPdDM8m(|}A99=l=^tN2)9XwRIFt-HHwyP=L_&!uBQ}_1vZX6vw4IbT{ zpLZIIhySG$XMGJ77fj!{8&Ry?OvPGuqJe@w$xMcPe8aw4)vI@FC3q6YGmP z+Nfa2T)llhhsum@B4@U8_B~c=F4{&=lRupaPBvglCf0{%skEyW^4tvy4W4Iz*lq9Zyi(u)J7J)GpZ?M*M#ErRHUj+ueI|nLt~vH zV2KDQ+1Zmzlq$e!VMJZ8Mb*#a`Q6Z_`i5;t)f?dx4YH`0V^fbv-G#DX=` ztBJ+^SIk>WZN0@hqc6(nN*xD(G%JR~p7_@UUk0fI?_H1O=Lx)8hm6XM45ua+A`R`{ zTzx14Fg9zBbXZt*cxTr~OD(#~f!}or-MD}QuKEah5~ubmPO7CVdLvaJzIOZ757cuUmgwmmzgB zY4ol98vX)(kPAGVQjle+(=<)X%tiOihO8Mvs;Pk!$184alj`L|eS%bDEi??FmHJA! zb8_0BOPlVVwIeNutx1>14U6;M0kO!$3QTA^!q(hm;#a-uj=_>Yo>=oyw!BT&RgBt| zc4S@;^Uqdu2b@->qAL@%NX)Qf+um(cL2X8#Uswtp4c0j7!@S3aQTI3hwi)r7UMKZ* z9hu-yP`IMlZcBFC828X0$x5!RP)utDL?j`Q z;(3HhH|*Iv3a})><+wYY(aY$_T{P{klh%O2p$T5YD3($8K0m;6#c(= z&T1cO6iAK&Su)itc`R>*u7!*)<&V1y?8qi-bVNR>k0xncN>`1TcQY8qGW%GdY32x_ z@T8rjUC_eyZu$d8!#8LVh0fSw3!LQO13d7wZj|Uoiz7}FAgx+tP8ujk)i{(u{Rq87&C{Q0g#S?cF@SAFk zYWXj4uZxw+3ecGZ*A#u)mRdXTt$tzlH#KC{)Np~o^C6chrtZ5uu%VQXK{W`8K3li1 z``#-T^&+Ubx^W*-mNv>21eLMSN%12MVx*t3UII~)Zfzu{-qScXq6XBWHRY5#P|V^& z-#@U41?D0*fT~zH>2HTSy8<4jI0w9SCbhSjSYGW-G$D$pKO&_UXy(6!)r}%M?Cko_ zDEks_-XwllY`oo5bQDV1i3MrN_M;0gCh}v=R?tCd;SUA55TA?w8a(#yan4afp|m;_ z1h^?hKVx=Su>XBY4OIq?!e=8_>Caj>H#laW6K)r3Lt-=~Xx6D#P1g|l1@z`F>$b7=H7{zYEaBQ=&h0O`QIFya^uWqC|yIbu{5Aa zl5ct9{C=5Vk8XG?pw5U(#N{NtI1Ng$zvJ$8N`GN!x}1?YAFFt{J^5m9TzNMZIev?I zrCBC1u`b4-y}~+s5pMXjN4&3b$JXHZHptoK`kxC$A4f_}a)1xoGHq!zZ0bz*u9La` z#5sc@`Bxl4haJ{U%4p}jJLF72;=l;%xIxR8w6hZ@Pd~llo04waoIS?Qb&RpORdGVL zxN$2e8~4?tdmCRgPOnXUz@0Kf3AAKzf%0pI6ZW(jr-YDuXPEa#V@aCLw%4;s=1SD3 zHDp04R2XhkzStt@=5VdS#xJ-!cF^>dCnb%?>q2iEZfjrkxcWxtZ?IkKu=R|df3rW$ zP~%QTE@-kupWQ_kX^T>+De+^s=(FUVpt5xsF!Tu3=NomRC_0S$_uKkSXj*o^(JJT- z#>LML#t#M)8l6w&Ux$-_2UNNj>`BdFj~pm>c8156JUAQoSKCTae0B}2E1C8L6IoIb zHv7wirCGU~r4$sUS=hD zq4uVDh0{XGA1reiC1}90P%Zn_L0=r(V0cE%qKV6+Mj`$G82PCW?;9_N_orlOnqzDT zEc4>3i}s-;;wUW2@2+p~36(UHpIwVGV&aC)+bz|4@f6neD^fh-xmm&YNLCia#$PVP zxJW)0BRz=FdP=!u2q;GGmW=}sXX`F#U|X7FnAWf+xg4+J5I1z8aHG-hl3gS2RQ$B} zDyi6k2qz2u)*yQ~;3zUyzL&Y8M%QxX`C*y4uCU3s+Uy?mVpnZM594uJ{;@c-OUgk7 z&CLku5Lazh?Ezu9W6v-?%0xA;xy~#Kj=r&|o=W#js)9y+%xWulG`_zC4LSAvHEZBn zQ_;cG)WP8LIN$S+Y;r=wy#jt*YEgBHH3wJQl&OrJn?W%%zeY7hUb$DnlG|cY%FOt> zC!tSs9dFyFnJj1kzk^H5r8)P+LxFo{^*{v3D(=4mh~zm8H5%OSwURfh5t&PN5CqQp4&V7ksu&s=EOhcY4G%M3oVyQFm#K&@m9C8% z$i|bUDJmZQ=hRx%_f%zCeQ zXd7;3`J7%VAe0*^y|A@?6wdM^APG0J-q6ll`_eSK(RB=(#Mb(ZNZuIYkn09mbqxs( z62|q2C#QpL5&`%T^|VvjpUD+bP;S3LM?h+oQv}2ej0M6}3s&1*;?B}w|DknK`UTNa z&9Ee-%ZDnOn)>xblg~n{ub&($LC<_0TTuGt5z_EMRg>sdt-1r3M-Hc!g9Zmml!Aef zue1{QTdS3Do$f?vEv!m*`)@@gbXhru7D1_aWV{xG$1r({B(Cs`3QtX|nD^{WEZ?wR z8yqlb=(A$U&8>)n6;ozcz==$T3By0TEL5dV)#7g}=iV^q)~Z=o-;eUDOZISi;Pjc- z5C>n;l{&6)VCeH50G(OIT#RcI6eAQWSt2qv@w8Y;5r4x%NV-ig0UQaW;iMmEV~zbP zo>N;9(SdoB`*00IZN;S98`75oU_pe=`4~QyfHN4+XQFP*Vu7nyVuUwP*0qrk=vL6D zB}n5BD0HOSx?E&xDEp$;Uu7+$e_!&lM~uB^4JO0107r z?tjMq2x+5ZeZ_f-zcXd{VJ35tGarn>{)1=^{g+s?&}AB6RXZ4J-O8;>JJUOy?aP1@DL|_IiBNht`nVLP$v^y?gW^g*`s! zg&ZUkI-D|!LEwLEKqS@gT0BZn$r1I#F4%6aoXcvYRAQu6|D0th2R=> zb{J?!($PPa97pvF{>m!Oe4uo7A)vw&ILvN_4fo?$-Kj!Dhe#;6wwZb`d{2-rK+!oSG12&fLIKX}h=Ju5T_P~y zRHcGA^iqR5RjpQvm5@5^*O&gWPbb(b4cG=ZzlRYoIgF=$xQtuXE_bQ;P3pAimn}=T zBUfmWl!ewLNd%fPNfxQLJX3}TlNX8<2LV)Sq>Njs=*3c}LPgYag*pEp#x+UxWtI#O ziVKC@B)-Lpj$?+Dz}cpED0CQx+GMX0cg@o^@mXa8B&Qm?1IZ&SDgFc5b=>iM>LKIf zbj6%@%$k|x$0LgQGPW@Plw?{RO3jq-Vfv46yD=Sdo~YyfsFTeYS;)(A^BMIJ99Jq= zHnpw_7n%!+gJv0>@p@j{z%9hX`&B!f`Mm;rSR?MoTfP4IN}1J7$~^~+1Nl9RfO(bP zWv=Bdo^l=s_iP}y1(sbl)rCz*N)pkH2;>M#g6B2%>6mCV)x*zF?q|QAhvuK{Dx_Uf zM^Y`k8cB=hBs3hPSDJgGJ1qTn^!=#;74n_i^x1j+WuN<=%c#@1Qt~{@U~OhlJa%#F zp90dkp!fP)pA_j$J(rRbPhN#9n*FUsf_HXIh?(7(Th6w6mFrkvN@#Vp&%QeQ-Q}3r zNHI+r-7_{Jcq}C}R*-#T>=*UGQgni~x-s^-%JXi;JN&qCYdr-W@qs*>K)StVd1ed- zA1WkJJLQH3%}_o|O2O-xMz|?0s%p6>nxm~brem0-IX#qAs^H=m^?XSq;x+9801;!a z(nyD@RqO9IX>ZM?52V}V@~ZCJHMclBb|^(A9u2AGMvW#E;Ua#~*s8Zb&k+{$v0VPG zYJYsHsyYOpi^1`TeeurkouM)JhfU<`4!p?fyR36Du4L9G+>ffAO+*=GX?}HY0&8ZR zsYk;|4eAd?$|dOS6IBYiRFkoJW~kUdpWy@A7{YNSyW)_4W>1+iT0kB6tm{6K>9jr! zwJ@pWS|ghd3)9uPJ68((s`(a~tAGY7r{E9PT@h@CQ97cUTa~sQ4p&$QTG7G>+<7xP zU>NH3Ao_uz{82Tn>0(WqHRXEjRX5-J>(yO%R4b`9I66j?8M15Yn9bv2o8M1&PVSQr z9<*vJ6zWG72@*IW7JJmwie3zAiVqAsJx$jxE+iMOPH^)te;H_~HZIs6bV|FQw4}Zp zc9J|YrTj^o3-V26g&LV1cnVIvbCk!biw-~SaefQkv`<10?;8)~!&oP+9eC*?@X%RP zxk0-n4q&|5E_b(KM#&NWX3#92WtNKC$R#R01vTx_N5>ZK8hNqZLVtEC!4#pnLm`v; z2zByd*>}Xr(XAMqH~v9*Q+k;^Kob)hwnaiJBD`mf~Jr>fH z=#;37I~7uKc_4i6zdbMCr_p zF!?=S;}ul5)De&(Cl6DJRZoa=9-b3+s*qor; zELb`qz!oKNO_X(wF7DIj)=3p`YtZBr?iMx}7?1F87F3sM?-_2UIQ zAdz*wC!`H-*7`%pkxgG%D=a40urvQ#&*AmJL_W8r6OAIjtu0FdxE?Kd2#NJ}4+{0h zN_#M0p5GUCnJynF3i-k>j=LQsi~p{~r?0x8qFxczZ2oITDW(eW@oA2yu~X2vfqQ%> zs|JdH5Kmze@%cBOng5y3xAfE9lZ+dMk;R}eXeZ3RHGW_c<-eITiyp8$9HM`COousT zI*pAj1ICm7`$6#F?wI$#O~RAXNVyfN{Q+apEl8%I|G8qnVE4W|euFL~)BjeH_CFnGz9PwffW)ZP zF-jaO`d6b|u7Jl=7NT=#hT*r=dynA%QW6F?|7Sb?wrLUy5P3OgZ}^56ZyYxFvDV@Gj_`Keh6FG)8!gvIl2aFjs@?DC|@RmzHT&VsG814e+6fB ze2zvtC{e7lVMe9ZoXlj^cd`Xb%IAyP11E63UZIITK?6P6e^;nim~q}z<49Yk-}f`f zNPwX2J(2PMmJM%kiCL>R>i-1A`}p|S@_!qf*As5OJg@iLS8KWNLuA-JUYmdmmsv|y zPE2ljkq#%&JejkC8BoC$g7(2vLcxZWk-;ffA3ELnw+@pQGwAmn;oJFzdhjmnc#{8} z~g={P#SN?_@I>+~rwvPVk|-zwU(J`T9OzgrQR_M|Jta{zZsAG*>SmW(PhlQq`yudV!fz!H*|kAiM!5 zH93jCBaK)j}*niPWIn#f;6K~)KJ%i9M^9r zeA^NeF=b?AR+=5)(Q@r{blqn;X!F)dMv3{JVhD*IS8s5x!!N&33--~Z@2^waBD+o*d96`E6?zLV(t z2$*XpQ}+W6`_|{qidGeJ0_CT?7d|&h?)Mq%EYb}TS2Iqy?05!la3=rcraT$USNF2N zI%XF6H0tq*=ax#+(h7NHb@k#BF;lt-r**{)LF`uJhn_NP(_WTzmd`y$`{KlnTDOqg z6j_qvl~lC-gwqhuO;)Cq1!=}3=8ez$zDzs?P5_r1Q7}Yot(|r&-n^ODskOH<6VOA{ z`!<9WjJaP~x6uDW@0k+cTlOFn12Q1GTQ@e5$#I#4!02u2;pr;9T~@5C|ku?gKLBw#FVn z>vZ%aMf7+!t|5t8W~HFk2`k^{zaZ*}Ndq3%YQ|M;jixlLYxhsNE#EmQM|$u+!TAqu zANeXz62+3~D4JT*VGU*r}RR%{;xibUGp`;jF%+OrDFad&M zYN1BKiU>)qLCm=G)y4uCy6vX}%QaHjwhP&kLGd1HPIinZ9TuBzz^gL$=x$7SZTZ{t(ZS+IC-5%oxvG}n)r3ns8jc~{v!zrOBTKbS$dXoMslfY%ipf7 zz5CXqqtOI481NGSh~m!8@o%hAr9E>Uwpnk7G~l}~WwQ$zQ5;OX;50)=k%5ccoh#C$ zMd!>EcyuzcnTzZAeq*XI@OidS4x?gGw3YLKDuR_z{10g=Bg{g+f%OudL8$G^o|UuN z1n<^U8{Z4GKNioKu;Z$!5SLqHlNGDi;qX*>w#WRz!sC?gw0Sp9efB~NXpx};LoonlWMvc>x2yFz}{nlviuVL_5nIe(mt% z+D!%C8P28{IUEal?o&QHW0-t7!GV87#J|yp2I4T$zV6u8qBt;foTLbaHbi3Lh*4Kv zz>NU;@tOd=<(mcgzrzNK0qU`1Ec>{?<*c0diPoTZXuV! zW0~Q4h1P}R6cx2c0WIjzYp`OW#`RjtSFu14g52TlO<8JUH+(#nO|udvwq0|gUqS2K zkmBm(%z>B2MB|bJSILr?8}w7HL0GQTvTSx48d-;ODfNI@%*I+?tDP-+GlT^6A;bQ7 zsJjGoz_X3ZV)+~(QURUiwXuYNg{WPlY86R1iH%@fnPvW0mOPvhk>?>8pVKkd!?F6P zVYL)r`D;&4EVy7R--_^=jIxfS(n^R=61>y_yBo#;05+qNaw)?R-*oG9GJ@aCmU$Gi-GwcV#%YZiBg($aea+0K$ouV%`49?MhtB`zg5iRWRv zH9!<1aH_nSICBtVXNbq8QkqaX>^l-GyYu&i6^#<@JLLHv;92L+XmOT%*M5mld)Chq z?Mv4=tKeielKA$xh2mJMIyjBbO3rRgPdIDc>h$v3&2uyKS^laqdp-o=&9apE{xTD+dsxf*(n{^iHUIpAbLfppB&4xAJX*|1 zKbRyPq_(~b*>o7hjv4+v_QgY9^5)>i^|M65O>XS!x8^zWzcoKXW{kpHXUmA7b^^fA zGKlPaLvt^1dTZw(cypksb;_MqHHWLb9qM!0JzR#xK5uIETC(NuKCP{d6j*9J7w<)M zeA24^4PCQB^}52MY#&}B!BcK|AwGLG*#aOYl|u*2<>#k%qk z;@&sYcJ9OnENv?^C(gQ0D#41o{e-`jgHA)&3Eop;t}oN(xHA))4X zh%MzS3zvr;92^WLMv7szS|d}9TpN+g^1&dJ`lS-tu30g#wnpH~YiRk7l>t!ULOo?_ z4FG4Cm+|zsK)^mv|kBG<3XIZ&dz@8os}x6-=dHKLsu5H16zzk|*#S|HXj#zi6> zno+p^&0BvZ^DCf&#*4vW5N}+$R6tPR@_V54(M6McGqn5at9E}cVH02#_PsO+!(hL* z74eoWn=_QmH%lVoJ;3;vNsQ=qkKVYPCfMN;B8Km%YD)~5Ups_?KR6vD3V~y&idLVf zB34AzsBL&=IA%$}p6gp7;#&aG^>Ui^gd@h38jS4pP~@(iR1AW4xc0K&LZM7AvJt1z zvsm4ZFCne2$ntLAoUe&0(Pu3qM(9|^j}nH~hmN{dmshjccqME;XZ_4uyO$!=ZAm)j ze?xZnB2{JTf_Taug~B4*<#F1O#S~2xs!Gq4BAx+AScrxzS4x|86L+X3=u={e96|h;;g1Vve?KaZCb>U5-87fY1Ve*T;$N=ziwPL?z zOiv-T6>EFj8iBd1>)L|S@`XOR-lC(|a|8No2Z3KS36lG)AE_LoJ#I&o4G~NCE`qN1 zvXTw3BmA{1@aYu@vf)l*Vy!*~nUfIPVrD191wCScIwJ1gm<=>PS`&+1lQ}F{6YeOAG23mu#KEF?;)CT5E|@LK8xuJa3k(dt;3pdj4X2YmXrjhX znZ#0{-Pwv$dpEJ7?Mw9FfxYRh0rKz5UOl^aR9m^=aXWj9gvnVi* zP$Nni`DanHMF`C0eTB=pUk%PUbQLANn0?1I@$ZWOj5yn3t-vyJFx~BLVi#kfUdF2z z&L}Ulv0?#E|20pa0YLF@XNrYL27MDBcHelO#QjM_XkiGVu_j7D`Lcj~B(1Ya411*> z@=)J;en8?b#SWNDCMb>ksrf?T*A)HGzPh@NtyynpgAb6=fRb}tir%Z+^q2!F&rXwz zww(5hUAQssZ#Ybruq^&M-JL7Pp1Bq*h;DYtB3$3W|F7AjVHfwuZflxrU6;l4eO$FA~_-Ae&`4p$MvS0|+G<7^8+JGZC zFlY93`y5*YWZPJ2-ST3S3%$qi64%nLy$d*QmxI=gXLn5M&h`nZ0StrS$MR2pP*YQ% zT)}t|uy@a+VEp{09pB)YJd%ypu*k^-*(T%*rp3TKCr!0f*IP|ow|=N1JW}$bJC&>< zTDCr7N{(0aGB{%GDFQ_UBvhYO?QM$d2_OXKtbYnT$|`Y-~CnC z9B+|xG3O%_fClUQ@lSEslNUIdo)yB$&>cPQTxNd?ldv`~I896T!>u!%E zj1N$e%>+@=Le2OHV^*NAAS%Ui4ctJCz>ndh9&1HyVw-0ck?y&8g@HA|{Bh69UEl4Cj#&F{>Nyd4s6mhRTmccR4=+7j; zKbWnfdwX5YVA1(FTV&i8LdK<~Hq@bdY;+rY1r+^G#J;|F?SD+etEQ>I3H@g zy3vUlX>HU3iO&uQs9EWqd%XTY%H9GdW;rc@_75Y0VAr;9Ht|OEA4RT(v>v-aJEMXK z`-7KH%j#-2W@wQ<+dI>izvNtvY<6|AHaGEy(@nwnh6r6rX~D-*Pg9d%XlN*&as!<4 z0M1@T2q-~DHD9g|C*lu~Z;#)CYkI!aReQuw>-M(lpWLysnb9NiE7SmErTw`QCI9+5 zpm}b7{?^`}(&lAbYwJ%O{Dr?mE*i`MLj4yIcoXzd?MF1E)D=DVV>u-6NKHN7&m&yN z;4MaH*!#ZgCnQ-jS+KdmLrfJF%$LHgN0~fB6 zcN5KPb-59#=0YWFviR|G!}p%l1gxQU6^ zh0*LgvRe3CP(Vf+8=RS$Sz@IwQT~+XVQqbWQx4{A^Sf7zg>L}gCrDMY`yDYBf=K>> zs{fy6xoWrOOl^r3$$M8y8y2H*yPKPM09dT!e$diJ zjE;&QKq^FmErkDVn{9&{sz*=`<}?s3!#Z76vBm-JHqU^Vaoeq-aMqKXoBR4~oiJUJ zOb2Y*%L@(-<(ENsy*+lxNtMlcemtt^9T-5v!&5&zIujuLK7d5X<1yi2sWNtZ`IzxA zaTn;aTV6?dLiexp;OJ;vW`)n~$#M<2h#rF$k0W+;FmrRa7G-oP6D)89V*OPH%7Q{S-&5 zFmldC*q*eydbxw0Rbz->jO)WD?HthpV4&2(PT579h8!+M@t(amFYO!m4f@Dk*;ce8 zGUL^_3Dyns6{GbniXAHWXk?&L=0wf!YxG~QJ1!e)O4QY>BGMMo{7PL5cA?r6I_JHF zzszaFMQ<<5iy0f6-uQU{R)>3V3HA~h-SAA5MUzwVvp-UKYK%?gD$gTmYBEBs57j2R zf!!Yh*q4NKs!O(p^SDZgkJ${4r@Nyi@FO%=bWMwLiybBq>x2?i`_Wn!MT0g9B|6DB z+iBgI9XL>q>92$p<{4@<4q9h@Ktkbvvka*2rhYP}7ReC6Se~y@x`dP*l87LyGszvGP7n2-tmg7*9S7)(0#d&$dTDRDREV&s=*Tp)0wk6qC~&u z0NKt`R9<$fMv(R;TwY1U| zXeEh2$b%OqwMafsFj1Cprxd^Knim!IC4pLnPhUUR?_ILa;R}@OuGVZg(3A z4rep=jsjiH`8C9i2CGlbx2H170F56eC;eL>gO}k{h~|sVV~fdc?A;3Gkra>}_WE*a z?d-2Z`S1D_Duc$-={j2YT&s0n?g5J4nO6I2f31YPMDIv7@G`tVnY{&3YHH4FuHh~E zX4$=lidDdls=dOFeC3*0y}7M)-Z@#}c_N#h{oZCi;Dt1>&R$jOY5IZg^la3JE`j0L zFwtzjrJ@w=v><8a_`?jEt-(0>^)xK2=xlIG&h4IY+ao#N_VO{Dl>1WQT?-pxl zw2!f=qX^zu#60sC6jpqc;{EW}=%e<5j_g&fHz#ANixH z#uw)V5BBhKhi^~&Mx%iCBswR2V&03K?asYqo;{hRS*6TBjTpC=={d4>=ah#7a-8I@ z41j`?;M%ln-DSw+RMeaEfi!Whv9+2fx{A5`i&><6Gdj&z&cqk1Ful`?a2LbvuZH#| zTIbl;xEwKVT1Nw!tOJZ^hXJb6ApxfB{f7kv-*mlTcCDWOq7VrctScoK|1=^@ zT8*2c!2EoE^6mX?5^uoel-1ijQ$Yt!{`vVzOv&aD~>l45T*u7k2B&B_KsWR&F4BP7U z%0tRLlk>yEP_`r59mE`y_}vIakuKGa0uk2s<4reo|2k`gM|wWJk%v?(YCVJ1p?-jA z_~MhL)*+`yt?0Bo;@D8?VcG#nS8wt$#8`AH+zqh5>^7X3ppI6FGUoFG*jiaUx?&JZ*ad?=R17aF* zkYpwz%$`t4oXd}Un4{5TLNvj$!uj(p@^;1E6fJf4xtsTh_#PW?Q@^zd{%zj_Mrb3# zk^R_`KG>>3V*@CywWUO}F*DoZd=%(}1yZUFXNmA^jjFibbbsx-S~)l+e>>sv%6(~_ zSiI=x**BtIXmH?uXYl2~N?CgzP}Zic_z=7nVPAzpwO2)J@g^4^ zes=c1^qob0Vz)D--8}NRP#>J$J}~S`*$xz>F_6U1^!(YyeZJjCa;)m%`Ls@GOk*_N z^ECVft$e@TDRVjg+O^S71+P@Xa%nF#o?mRtJ;xI!g*{Nm@O<=W^Zf+qL4B><-#K(*4t(#C?^>sk5|7m2se4ibDmZ(rz>Q{q%Pxju| zX?LK!rI~ZMl(*fbv&j1qVh_VTxi&a~nU(=rf7X1HyMc?0a8~>M#I~%d)ww($ns9mnJ1HG9HN>JSDqDv_sSjz2o5> zVwc(!p51K-RTgmqgV`1(soz`ZIWK0gI!|KD%e7=%!6msQ0Ui5$jXcVs=gAM~9-9kB zOURt;9PZ{-?2mGE6WjaeRee61Q%66M+bSwEIaaYa3h7nU)^vy3#q#F!@(6Z1MerNA z9#Dx-&83t>=j}~THG=7^lvL|s{rQ)H(ar|iji~b+=n-$@Ma@J^X7i=iuohtlwvH5V zg~h5|ZLV;8$LT5oOoU;!g1)G9KNy|IjG^5beBf0u#mdyCw2iNL{SB}=7|oTz#nWkZ zhfWa&jK#WQhT4BvU0S%xK_hphb3pCk7-#ypEuyvF&B>mQs0=L<%{*AesM4I3mG)u( z!!NdR^EIpikh%o)NpTAP3rhtSPer|sO681!$X!_OcF_#0`zTdW0}X+UUcap(!d-lx zIANxKCra=gYdWf&?%V{AnQU4ajRo4NoUsNO0$gRKax-NcdI$M+CffHo@W*<{X5M`1 zpY8S`r%8D_%McxM)5l4zt-ZRt$)?YIt46V2nN(s4a?>-sOL-!raL~tl(vPypNpX@e zVm#Ld^ZCoLu;%|>K2~6~X_VJ+J!#v0LH0+~Imx=|8<&4$+*Sv2nw(pgWI-nThRj;! z-sCnU*P3C45*+fc=tWDO{aLPHX%lLi{dP zu@Oxbt%5soh$Q+{NuN~dwRc~B%@)yev|`^s%d<$hCt_mW?E>zewjJa39GT~A4)8nS zR{_Md%mA*vTaA}#CPWU_!@(i>i z&G6K2>~JxA9p(-qf7O`Lp$_`h?aQxa(Cq{M4pl^e2y%+0)9{pJ`onPxii$&4Esd^r z$MD!~b5l}C{k||OffXJwUKVWI`p7D1qDY0g_Yyceha0l0UqIfMIbheT?M@63v?+S= zE#gRz09&7@3#2k+wazYwG0oi$KAIcgRSZ`bE3Vxepkxq4G`n}ZZXz=cko)>%ck%1+ zCoMU^(Kh2aYq@u3E=(QWgdYRg3%j43U0igSI0CRu-`;+KHK**7HI#Af&b>SlXKtpy zwG-{T(^77g0Eb_ib3Zx>BMH(k@LUP|H&Wq;OHL?fYm}I0O`AzIBE5sk>3-%uXmdwC z#AJ-WcKcHgNVjWgcs0Y=>si-$L#Fz|AC?EtQb|b{lJq3dsKIfk)z;P?8pnc_zcMWT zPZ!B7S<_F+W4k4mu_>xc*dS&#g|iz?z_*ES`Hq0@S=&QuhmH>!a0@oi<_Bai8pz`W zbUps?{!VtoBO`Y8;IIQ3GxbnuO3EKU^7t$YMJVm8o;!RRdC+8f`j<2$4$5}^5?rY%QPF1SLpU*T%*zrc-ITaLoTtHAfj z5}7OVknddoZdy3FlvtDfCKUG@v*XMzekt3m6{?9VJw6wI&&dwjA5)u?E z*Vfm;nR!&uZXVMJDvKDH=+}+Kv`J-@WaAmaGcB3w!;ozskLyiMB6Y8S?`?*2-RNT@ zIzpKtH8y5ruXI}S4~+=e6$R>!2{6v`R~aOz1?HCoW+ya+Q$_i@)@)OlHpgNd4a^o5 zM5n5_2{A)JKvW&svg3OpwNWkFl}m7?Gz9GCWU0$bqrNo{NL@`%wlbe*uGCXn8lvaG zgiJx$yZ-(-hLjSJ68|?LHe!wJ_>yDpqFE9-B_ts|WNQ<2&l3SnYni#kD}%SZWMRw_ znq%GuuPO;``l#}o_Y60Hi{k6C(l1R-o7Q}g{_iQ_WlFe|9~d;O@V;79OeIib02p#| z4z5Rz)5Q~(<6!!}I|y`E)&^AMp|a7dShJ;?1pmS!cXxMV;Pl0}F#bR!n~SYJ)MdX? zBt!YFHg}8anhH-;4j*j$smKU0=NMKKI!OOl%1~I0=Djv%ogkUL@GaXMOQf6T_H@EQ zUVA>Y(QO2sU;l9WcY4PK*3^pG$xcKz3kta&Tk$*3=JKrl0Y9E%Cqn))&pBlQ0Sc>sq0 z{Sm9k+%O&#y(6T(Loqh%i!I>@`g-12b}m72cXXobv>gVTie=|JpwnX-9YyBnPorj> zFV+-A??V028^~B2?g;$+^+l%J>p#8;%a04N9{+EV{fwB#e8;8lW??(Ny;zz54;~xv U8oHT2hyVZp07*qoM6N<$g5O&tl>h($ literal 0 HcmV?d00001 diff --git a/common/tier4_automatic_goal_rviz_plugin/images/panel.png b/common/tier4_automatic_goal_rviz_plugin/images/panel.png new file mode 100644 index 0000000000000000000000000000000000000000..1800202ea9f572d55d066a1e503bcf5b82f5878e GIT binary patch literal 64902 zcmeFXWl$zv(k+U+ySux)J2dXlxVyW%ySp~-?hZ}k?(Xi;I2`(YXXcxUd;WY8_xzhj zBC2v{uFPCJcSTj!4wsh|hlRp|0ssJjm6Q-s1ONbH1ONamfB^fFpgE@o0RWH;dMK+q zDeAit*g4pmm|GbWIJw&y6BxUhn*ac~trlgOd*E=!27TV4ID%Y`*|+jdt?R|`+cH!b zNv3r0Pc^P-me(gh`w4)AHLiT#Z4JMne>SOCgqO{)J2bzcf4Azs6K3!`udrRWmD4krw-aEsl<=gUpcOm{{Y%sMs zb1wYdu5dkted!$dK{Ix!I(9@F_3q{C{jmb}f#n_kaMtMi+EwdG%_w{A1CCCkE9@pi zaBRzve<$3kOO4(h_q-D9ple@~Sx3l!F*ocRjfpG6`r$T%Ug7n2KcRV5lyS8fVM`ri zo0-Mm{rS{xf3k+XW9aqizOT-|zCU(0_k2BmymonZ#aWTlVWK)?Xi{-!sc=QQncHf^ z5M-kat2EYp&2As*@X7L_-086kH73jb#H{Uz=ZK5G;jn?*a`kvZrWECat^3sXdNSZ$ z7qXj~TdyAWvKK?2AB;*Rma}xu_!QgL%5Bv!w?0EfOg~(-Y0o??{_zs~yau0DC~qh0 z8Gf>1sC(74A}yRUr$#qGblJ(qx&iC+`TUW4j#aBSOGhn&h0UGwJ!;>FP_Q)wPAl!{ zV=#~U%o(^jEFU@19uQiO6+K~W674F|(aLB@AiL}p;k_4#jB79?6yb1|!z3v*iYFv#MuHSw z(fq7bP5#dei|V4qRSVm0Pyyzqb*YM~rcKNS$D_#-ZuEP;HwfYwBQZSV`5Cd?)~P7w z37)aahKcSsDCjqJ_hc2d@7^8J)EBLDlO5;nYnR|^+Jt?!n2Ll$Jnxn61vUUkZ%rJ*CPU@Y%KsXvxC#;+qJv3z58epHGN0>)QGHJ;p z_4``0<%YYgP2UU^G%i1l*_C$DJDxu)4x*$VQ&V0yZ1^>-DPbop>&T&+%GeORJ+Jz6 zDzn8J#)nG~EXV>UJWLqqVvw3+$0-h1nbiEbspUL1smQHde&k$8oY%EAdfb#HH>|>y z&>nr0@xH*3w&YvUSl0uer05uI5^I@QXlurg#&wQyZ*NPqbVMizkkE;;`(4hPt+Z#i zuuYLa4?z%6{o}k>Uh_#Z4bIQ_av!z@F0$f0rO7y})q15>LciPvzQu$c8GqFN@W3%` z+;CV?7P9Uz>wf1X{l(7ud_hyHLmXavc__P$+9zos4L6G|E$8v(Mr%bHTWoYA7waX7 zyd91u@s0NPYSR-#itX_3w}GpJk}AhkGS&=xE43J--k1-MM45Rdvc zN4DFU^m>y;r#u=xcg-tq55xJ$I@m(`P-xM$vaif@5?RnE2y-t?zs=llE;)eUS7>H) z$61Px5Kd~EG>7hU3S|Ut^fop;BAZMS%cy3UDhHId{wBmdsI}X!t9_n~6}8B2M&`m^ttF#pmNZGb-L7aLeqoj^vs@Ti z|K=bfZe(u*NZ0&Ii$s`}6>UZvWU0o2aOeQwlA;z1Zwf>@E}q|YW622~6q72RWZRK_ zIct}Y$38~0I_MEdi1y5HpSOkf^Z~j$C=;9C*v49gu@mSPo{4#oBqhwO#gbc z7W_z(gSmb~s3{G|RE{rhz|Z>V;!AuiE90wv8n$I?n)AAW>YdYzo1@XWI8e<){nDNz zH^w-1X(sB*%fEGQ__XDEPZv6r7Q5i3JEk4(a`>w0!xsDO`TAysclY@Fd4=cj>f)}! zecaasUku<1>zbcTVJx_Y0O@H>%7D4jd9$iJ@q!%bK7R><8Gujy(d|let0GXH+Sm^` zZ8VU$@Q>%cdE|MrrO_xk(NV* zU5f{RqW<*+7Vb!DlLT0|C2b%peqU1qzM*A*_NOi8CgXWbOi-sd5R{ZKs8#=6)@nsa;0_o`g$YARr_#kehUxPzZIe;`c1QimAE4 z*%gHFJ1F$a2hu#XJ4fZUZh z9eKKoLBJe=-XzgI<(T&|FK%R|12oo}+B-wL?jXe;?YFirJ-QHlrH-4XT5#n+PP#vR zmTDSUKUp?<(yN|JPCiTEikKrkyaoDcOqwzz4En~+(tKfl73gE4i zjb7-Dz8zRjfvgS!_ScpnY2k@&SV9|sB9JWcD6Jtfxk(uzjv?cbeClJBAqK#YWH2;o z%}If3eiNxWdN526;@7UZ0Qyk}48H2dSO^H+;gY#xbqPFHDZ&QXJmR$P#@Oz57}Qha zUgYo{IFuBi7ei=zX%qPkThf}`RwEI49@ZbWFvzv#H89(j)<{??8 zJD)0|mZs-y!=3V5^%yB%W1fa60&M!vnwT#2mo-b8D$3}ssrJO5F!<~)5Mx34TXU^f zrEk~94mD~M?o$)YP4vjX?w<^-o9?rSN;eV-Wa+2~lzKqF7)f{XV(TQupCitoI~6*t zDtQsJ5=R8&_XiGBAXm3Ao%`XkcV?lMqJYuG;Wdma+B&8JZZ-@+;|*~o0IYyk;2R)% z!861vdUWHl27;C$GPyUHMqoH2p%K-?aJ+lHUwd<_*=ykQ29P#k`~wCPL>40o!=H8x zC_*xeBYxLENI>u#L4UrtGM|KD6PJ2r033wy2f#+I9m(S9gGU}o^){Zj^@cml6>sctVw{B*?TreR3;evo~p?oAaI(E|};B)`Xc zUZJAsgX$!U%VbJeqZ5M~RKPznWYt}|T_vq8IF)KR+w#^+ghieOStTxcY8~ZCbq~T9 z0Flu8#k4h#zK{JRY{x$$sjaATOD| zKg}9Ulx;i*ggL_uzdn6HPO8A@EbDKPnje zslJjdfu6X3VN_ca0kIteAXvW;9S%XngFq-R^^pchl)^38Kd%r_f`J;<>2AQ!`fSK= z51id>KMprfcNt|Nfvs$Ap1*q?T{oD@p;-?!@VdVF5eta7H!?>a1ihwr%ZJ=IJHRwUJ;hwdJBq;*7|pHb^5e z4(vN!yn_@SLZIzsC%h8r+3`|Qh2Z`PDPhh634EL`#jdvRT-&AsXL_Zt)jJonw|Jtr zxg^kIzcaOPm51z+*6jq}YI{kjd;+K!SOd-?FN{36(SLh8@6|5hm2YQhg@4Q?r?LOo z3jrt4(9n&jFgD2-IEPpXq&w=K>rjT2X`ZZg=tsnZ3JmX(vtF@Vn5xHdIo!w-0xk_9 zCQ(s^Q^xtBCAvb5Fq}B=HlEeIaAASXhO}pd_-nZd@_vxr6mkEWYN2SmZ+7Dc(=7k@ zQ1Za@JIpaJJgcAt1LyZAmTl=cpeIlQRN@je%2A#REA!B3abWJN3JXayA#h|&OMvY!FlIO}oVY|gP6ZN&{-5UyLJ$$rtf z02qMf0Te3%$^MzsRaFKWKup*m(<`b7f{82^5Nne}zyD5PX8KFqT6Fkq@Vnte4_qk8?f?$46t7b*`dD zQXNS;fDf=iRzzn zjLGK)_}EwKJ0gIPUWXHA46WTrnc`___B$C%NT`omGLan~;3p?U0i!W2 zMm<4}bbwB1V2uC7YA-NUPFk3x7dFAKwR$eH&SI1fnGx*XA3*ANs;2n%t7zWpyhl_j#vY=;)FP|rJ7qg z5OrI$js5hE1;)Y{FtE8mvLw~e`;qR-_V?Oo70#;bd9+y_JI@B~A4qR57{3XDllCB( zWWq4Oc0;M6XMfaVJUt7xAl9s$WieRVfi;(t#sM(QL@~u4oa#AyWKmnDSbs^NxUaDtiNrOKf9^?Gu0pOA&@ci1Savt_nJm}TIaH~ZJc1K3(?=(g zofaontNnh>Mcc|)#S+H76oBf+d1r~A7sXM+q^KWhp-`Sa2|sOI&W0NtR*HeUX(E8K zKbEOZQ5AO#>jk4Yu?(0)!X(*>q|(ahLO8@k&K;j2fTFnYqUOErmnhG#7qku_r0fW- ziZ`FU1!vz#NfrND$^oE)<=M$a zL1zC=PUn5Y5t{v=N$fZ$f}ts8z59`Vl;zlja;V*8SYV^yRoJz+Wxyl)BS8)MuY|Bc zgp(1O{kDE@zp4ojuZ_l<1;4ej&cwCt)-R{5)@>R)5R3|knn;hNt2jMH%4t544N{y& z@kE#O1#||?uaN(!F5fZPQQ#tbJ@yo(7I4t(fI$8Y!77%OsH$c}Hz#(Isu~vlLzv+$ zG6`mk2(J|_MM`l16MNMkcibf~XCI_+|M-^bH<|`@mP8+vJ9Mhe&Ju-GDY!ByB7eHi zq9`$P?j=R5Ux#9W;81^yoavlI2J{jU?Fq@Hs%0A5V2GzH4hCN!35*Bkxlwt=wvA=M zwktDt0AW+9dhOsXi9;IcxfrL4#yy!%Er1nGe*jD=yNn$qeP}t?V2XWV{e)c)t;Dqh zYDpn|3GpOAK{Y$1|) zo&dq-U`=F0lv@iCmCn?HK9L<$gD}iAVtJgq4lQqIL;3^$OcN@-b{-Q4pOcBB?|Y3x z931s`~P2Tcnw(vLz3vk)N|u`RWP*89ov(01#YM z<22Uai|L+W7pUsXVztsEq;yu?OF?`k71F!R^yAVbn)VEXmfk1aH@eGkCb{j@nUXAy z4rW@PC4s>CN8_i?0D#lO8~V~CozTb2Sp$ECaEWq+GuR3mI{!{1tEG3s>ICZ*#eJ!c zx@`-^D-1aBr`0DF`jF7syC6*5#Sd~1_1lh6eN*Bfr3}mwSPiWXJT8F1*@%&H4I59UN;+c4UI7qaDr;qzd;TtEGB0S%Bh ztsSdmxQZ7zNO~10F_;+E`0|#BB*#Yv(B-<$-OKO+Oa0V$R*vDOyJH}k_CwC;t)#`9 zqNIHu;~NQ^0U7~AV2?!6wjH!U1u0>pOS$5=z{ucv&wha51dIS~>5IB<4u7MXrdnp=oZz0D7U;#WWD6p%il5YuNYi`cs0{Y9V z^DuP(!rWVJKq2 z*7e8Vi{~bi6a2Q0DuKi*0)l4Gg3u$r|E>e~-H`K`-~?%kno8Z$k+3j9ZB~wi8>b9; z!AI%@-LIdL*2(DDWxG>5dffhm0t33E3TnDwGpFrR<2O=BzKRo1g93<^IsnP9%Ij&6 z_Ni=^q5fefHi9K^#o2icU~aWvyFcB-e#W^Gl>wU~5ONBIW5oSnjpu_240{ytI#my^ zBoay?vQJ`{M5ZdDix#eg8!zTih$n0?d=^8;2HuuMf-a*Hf^`znN4B5Bwe1Bck|-hK zwPEU^HQ=uskRFa~+44{tL{fRyL`h1D9WMPW zFW-xfR2hJybT-Nl0@9g4PzMx(*Gw-i3@%cJm}q_Hh-@5%uE!}@QOjlF@mHv5h^(BR zE=8XA7isi#P;a*;<6aOWRbO9DKlZ2Eh8gef-wK5b>|2rS2b-~19X}(9QZZL7xkZtQ z8nwJ0`OfU&qZXfc7r*U{lo}B%ZIDd2%b7FlI9o^X91YDiLUV#LsEIsZ?<@f;f=88i zEOPCwxcU+`a3jg8UAJ3~p1)yzo~R7^t+u4p4QoZZuUECm9&T4k5zsQ}bQ#*Y7FBVr zaON$Zpl@ww;0IR)5cCKh1Yx{~Gd|dixiZ>$z^{JoVjEcbuLd1fWn4vFCU8TE2m>_1 zEVkvZr_hDs#8*h$ihdX)3Ne#y9p+vrnq*ArpC+3A7>QT}7uE}H3s;Mti#f4yQ=1G3 zyG{N)A9%xT9mt4DPO?#6sN#lCYK6efA!N3wHVw|5$=Oo8kP5)=oo{L?u*)z=ZUl%p z#huliNJ-hCegqbE(5i#tWrU(mpAuc)S+Vhj?M%(hc2Ul&dWB{)(9I(xh7P3*T*3Xb zPB+9x@2SUC400?gX90nKO#g`37I8NzHJqvSo1F)&Ih#I*=!&L7va*vfHKp?OrSs5z zuEcwNoFTNahyHxJ)F9>SVvd(iTJ6#5iz2+(aBG9r{kY_=t_ax6RtmQeWx43n>-tG; zG5>n{iHidYAepU@^Bh@ePOXqro*UJ#kb@0&n; zvjWS9B(x2enWKOoh%!}Va#T3Em_SbxMLkc@QfsclRa-z@W-R~{zi|UQPXhoTstBuD z4dW^tB?BxbJi@Tja$~UY;nLI!f;*=%)r}XQeZ5CBamSbx`m|TRP4B^Rwk&Nr#ihXW ze3Dp7Wf2~j|HIvreq+*kBqX6hKLIubCFO-K&xkF1Y_QrtEU3t0PDrma<_HlM!|>is zZqbQtuB4jr(<^>51F_{MV29s_oxk%2m6m_ti2NFal7GA5l0#Y^mk%bK+D;ye4k+l` zCW$LEKHvk;f~k=n`*ysR(X<#Zg%$RRg;CPUhNuboXsBkrOVWZSU@{pm({CF zPuYtf!j_m#EF2D(AGe?y*5C-6O%WXk*Jj5Z_R`6a}_+z;Aruo8ZB0LAw%DbY(gig4( z9kOWus#C%Ac@(!2UqMUUHJVm=zQY+xtY^*>_}Ewa&wIjENg=NmpGqjfkgYi1YR>_E zEqO++@j_LwCQ_mM7o(dW3ndzP8&_!Mn!Y}$`L+DsKi>{Qy|iEx?r~ZLIc zKM;rC#Rbq}Nr{6Ui#0msa}6v2+TnW(xE1Wpzzx9U;k8Hv(BZE^`p_R2w#{S2#oM2c zRkgu|*hPaToB3T+CN?Z@Gv)3ZL`}br$13P@q3f_;r#mmqz!_kEj6k0jUjFY|U{q=w zn>ugGoOFa22i}LwbXYObmI=?CJLE@&svOu`eA5q##O;N3yQ#Oms@lO=^)<*|RQx4k z(9@Z5Dls8eo|P&r*R%>m{r8eH~FiaRQn((ZL+5UmXOUSv7$jg>=n&AG3NFOsag|ujqH$C};Uz4yimj%~D`Gae zg~sTOqDld^6j$)c)|^QiG>}HL;fc-gRx;cegvguXNavGBBR|h24j!!fS)dm)FZLr193B_D( zVKf$^uJUtB0i50RYVA&QT1sKVO2m45>9sN`Du2^&3=sn+RX2A=}1QbnETGmQ_y>QDi^a+{5Q4q~ojRjMNV6~3) z!T_4F_TwV6)T2FA9W4pG#z>Pts>KH1Qaq26Tshihf6{zNa++_(hH+xJwL##xVzGxE z(`frRxqME3#r&4Su!s3$cyVsZiZqqOVO{>Ghk%?M2ZS=W7=iGFI_<{~WF{bM=Ne%V z+)$8A?)xTqKOZBbAB4)zn?+1(bg0{x8GVsR@M=6x#^e*l{4mwciiAxbY_K7#XD1p_yRfS>m@VhC+l0()%E(Jl2f;V#^{7MR^49Y!#>VbOAz z;6-FKV-MbM>hIu0#${);{Te(Rw$udOCd~#v5mXIKPEHI8irpE|KfoRja1TJ8MT})2 zP7?@R?7n{-vus_o5w#=v7atJ?+S!)Jn(YZtGo>sA*iP3rTKe!Wuj3{5?(;aQU*K@% z8i&4Yh;gjNs8T(mk&uqsU1ao z{D9so-pDFNPZic?oEdB&?DQ!3K7|$9-Y$Ed2ZXSppr|7(vokcNkevZIpXYX|KdmV) z7hQVN3-qxUV;l}w_e=LIDOOiM@#SpfSIr!?Ca$hz zgw@+rVC+&f%Zq!gO}CBXyS=FtAY`GEl5dbheD8d5n@1vzavpB(eGLr}D(+xb+Y=XiTiZuq&!X^6DpDyZ^E>T(Y)>C)eI2F%97t=gLKW5yq(V6 zEVCgt>h&U5`|qVu@9Qc?5_2D>A%&yQCx+E6YQ8g^7OD<_TuoYZhRk;#R*FfvV;_eG zxp-t8zC5l!=6fWrcFM7cTCH~G1RAIuO!!^ueKIZbPLtO>d&@nmDu92h^uVxrs5He7 z8hsuLn02gO(rkAo#1s|7qiH`E&)l8cX`VMPYT2ftbH)A8@h+fTvgBud|1epGCy9b{YfZC8 za%`?uu*w6y&Qrna166woi@vAHhu0?8ZLZpqY1WVPlExpQIm{@XG6_G=`ii#r&7H|c z(dj|ea?;Cpe&&nD`L*Dc7`@itY45(fhVI)G1n)Y(#3{9;p0?~z0?{_rufwN5mb@KJ z#+??hp{ZASbjr)IW_*H{eRLgvM0e_cZEgxO7Z#S66c+yHex|QoOj+LXyb=Qf7$IB5 z5u#MM=LEZP`CJ+Zs3)Z=6hguB)QzWl4k!35<`RlpIG{@bf&7sw;OM5>xL>V^Yw*E^ zA;}q0sW&>x#;}{1J-p4=&D4%7fP4+(j0I*uvvz9}MM=g~UDQ_{L=gzY49IkipIIbD zJKWuuh}*B)S*FiR@0?)s0YiR%5eNpSiXt^u=EF+D4ak_33RYPHLqR9t>tvm#N_FZji4wXsLQ)Yp9 z=;9n1q8zV*YQhdb^SNX#LLzv9Ro}<-EP^2A{$S_QJckIg0!ClLm01C%bM?z77iKe7 zgPKK(5Z!){>ZXK;*#vsG)Y)1+;_wEjpRc%wwX=hWN~ZAKINHd+?0)|~cew>`*x-=A z`+WQJYu_1``Pcq3bs1?cLtAS)eIr`~V>&l$yRZFc002DvZg%>Hmc~v52F9l5HoQbv z9X&(@=0?0kYOFF0GIqkoX66ze4#r9zvdV@YmWG^0MErbEJZ@ZH0M^D%`UGy)RyK}Y zZoEW);c|T){}Iy@5&Wg%WXVgUE+bDMZ0lf5z(U7D$3QFUX70j7#0N#d<6vaMr6?ly z4~VZbULrFmCp#{BdRJFhI#*^oTL)8mMovyndIlzXCMMc14O&Nc8z+4?S{p~=KM;Ro zh!{H>I+)uzncLbB{K3>WuyuCgB_jG7C-`T4)^;*7|AM!1{09qPe9*h;+tD-9G0gN4_W^a+n%>6IrFD)4vE)iQp=Re^|itrNs@y}&sYiMr7_17Ugry&CqgRwC!I~y}6Eeku7 z39UYd3DegRCli}K8w<0sKKs8xN!mC%>Dw3@|AG1fr!)V;VK+8nVCUd8q2)9*V4!7T z;V_`pXJKNbWh}qECSl`It?`Vt+xx{Q8to6U9)7)C$)R^AR#`G^Ae+cIil$Ycs zVxnXCABnt`zLUw90WXoXxs9{i{|qRbTN^7m>HlGqk&T^$iGzcUiII_=gO%ZLM}Og| z8ap_CRpK8^Mg}_Ozj6Oe3)fdNU&QMFsnaije`d)g>|m_#Wb2@8Yiq?z^aq0AkL6$G zO~CW_q)3=MerdS>srY}?yppl~-)Da>0W0&rh6o7$DqAjn!@r$4>bn^KP3M>0-$RCG z`ZlJx$nLw#{cZhmug~1EYcnD=?t1 zQAD8$GY~v4(CZ7JpbA3~L_sv4^^_!zzTb3lJ$yF=CP66A%bPmN!jY)w=Jq_g9JkH! zG%eUaITYQF#i`H!2?6jgR7AI7CW3M=shG`D#4h!=2e2R&6)~9@>`}T>jcxJYNTM1TS4m@7M8d%hgJe zzb3mKpwJxayN(Csz|ZKX4Cy3La3uw05m5!i<}?g1EiHM~Dub~|`bCe)U_A~cKgrS2 z0ki4+JU=ixGURyJ0ypp9ns^uskh<`5oVZ?&zUfn=Nc21vDR&R2*k)eI?4!PRdljLn zw+~#`_TTho*nOF<^P5{g);5381@Xo92<0|R2$_$iz4Wjz=du1+%2QZJxC~cK_$Ias zH#?dX$p)=mK~s=7F5SU6Wv@ic+dS)~=vuA!5xS?5%MhLp-#jcFkDG!ZG>>Wk;GkAX zz`~JMUru!&2wrGA3sP91XFeCwe=>KYh~h${74~~x3Ec@7rUaUytPK?7!2<;pMU=27 zFG@9fpl&VO5aS5P=p2&f!vz~Ku$YO*6-%i{TgV|+U*t3!uw=hv1jc)yw@_E6AQM!8 z^r0fO_4Sn_=iLp5wqj|qdk;6{(Hk7Va4q!dJe|)?esB~2km0psYb8@9_`BIRk4>J8 zwf10r7ZL{7^>;6H)||Fj*M1-~(6Ka@H}A^Wse=(ZIzO?^-JA6fe`t7bu5cSpXm^uS zo@P@N#iB=o#ub&X4g3MJ4={PC4G&{W&rS{mg+oeTR!Xqt1pH8iwLMz?;qfbSg;4d)GdrR7oe5xO|b9p6|qUbyS(g{46V*z zuxw+)ocX4jV@}xl(h+yUh))o$-oV`ut~30%jPysmFzt)zbm zKSUJBT&=b49X5ktWL;#{oyzEZdN7Y*wxOt5r~_fm?5*NG;k*T_Wd2UnDH!h2m$UJ` zmTeEl0En*4)!jK+Ig=Qx0kGu7a>X6pFsvr(_o@sLx<%hR{tRyT&WiCsSF@3K)FFOl zq_b?q=ULm-(2z`ib63)k{y7Gx_zh(p=sSZ|KM7a}{?2gvRlUwh{~j}5VP7EHEvNnACtDwjVYcA%pO8%8-I)L`rgSvmPMb<9gtVRq=7QE5%j^ zdSNE^vK6`$#mNr@CFWkELv$5z3{X-3gjp&1zTtt0+!kz6(d6k~OrxKhi~f4LW0<;? zUS~upM}y1-zR0U+55(smMKqg?L7v|;rp${T9&C5hLp`^FkG0l&%TJ4ObV!I@oU5O9_D_?F*`h4fK@l339H4pQr`hCR* z@?cw-t|B;-VfSz?j2VM2k=GY76KC9&KX12RR(FoNm(?@4T8%C z=XJv(=Ur3scr1>ITWxPPLSrJ69r6%;0t4q9vuO@$`K;d*NR4+P8u&y}{bmIenM&&L zP&IQrRYVwdvwkzG-N@));7HyJaL{qcuyZmr?aToW7b}w5o z{o~R@3Q6^P=9Srfp@*+#14W0Itc{ve0*JOnb8&)hjuVTwwQ;@s=*8FoXI*<_tlQrJ$%D{!@EsQ-^y2#<@ zofdLA_)v0fjBsm5Aij%Ryh?UUkFbSX-z7j9oEw3*4Ex|c=12bZ209ve_1aI)UBU-ZjGrL{Qre5nC zmuAya7APgoMsN0vOlnSUS341Fi7*epD(J3$nf$ za9v)%0LmYnxOdto+8Z3v z*%dhkSDRLiKLtxJ3(A2*wF}EhGWV^=(i$ib4fi_CcJlL%W#{l=#MfA&Osq8(b>Ugy zi|p34y_$W{QPs5l?H`E_ukHMkWfbTpQQfLxn4aIk@zR;rIFpi+ zW6RBrjM0@ejLFGsKy=}$-Q9~YoVcV-fL~{sC0A2_y%TfiaMl@D8=R=hwaY~hg9_Xf zS@ytrF?mB)G;}a+)30CsjPK3`F0x?>kKI$(*Rd~g_o5kX2gadU2s2-eNlDRNuBXk# z7LHi1ugX$ohatL)q_rCB$>|NCwVHs>cg#d^5>Pp{IGohz#ebb0shBooRWWFJHkgxb z!2_41X^Ox7Faw+5@*z>XpyK0nFAXYaz&Con1tId_m-Y_4i{kH8WtOE;~lO zKIt11N1Xm1Y6bG!LU6i{at-Q(Ruie%XW#>b8zhS-^}GGuz?3K{X%B=QFiNL4&&{HJufy@zVC_&x$|2Oqfsn<#+r|rfA$S7cPoJ3MQ^#-2mbh06!j6-jT#U`N zcLT3!%^lcNoleM?;Baw86;o9cmNWxJj8$0a>K@ks8WueHQiL7dnG@@|&GAVpQ3K~d zLs)>xY>jh4=cLFr`jXC>lw|Yy%j6N|~mXG8%1(y0d_<;U;J#jn1( z8OHNf5R$H~2?iH)=0Y<{d22^z0nL^rWFzvs*28bUkQ!RBGWf1|S_iOq4?L!dSG+ZChtd@g0Q^c>1Hrk(uDy3dM|-l|KNtm@Nf}0O;HXOc z@^~u!QXXuztSB(I9{ppO*(*8{$8)5Ae^(&)B;*+zzCNGjB` zn7KYZf6)VD9f$!Sc`db`sVO0A#qgND<9EAeN;O%{H-0ZvTn|tjxM9xbK-EV<&9Xuo z2O)L_tO_OPhk*w$;JkveykhUE$f=3K&R2}fo?;3=lLkG*TDb!OaDXNp(C-8~k_?#({H-fFIm-}}|o22iJ+Czbp zkFq<5VkS{^mrtNiJ1+ML<#*@s9$k3K4^ODyU&z+k-hH?MIOAz_om}0dw99w$@``M?iUm_09dv@Rqc)RM#xg{lA zl(dUE!bhxxsA==1xqYtZ!G{qqH2W{D!RwlA!Vm?hO^%v@%>>`WnyK>C%{Qu0LzYzU z25y<)*w1CCYb1nL-EQAA@SiC8!+Yr-kqg0TKM}y0oLIV^*{Us0vhL5&51oHH8hhKZ z#HTp?CQn6}uE8X4ic;+lF}9?zVaiJV*<5m1S7|X!F8yN1SutC4_@XD**~Q`jU!qvf zTIyIjVaAxh6hTS1(Cg4hNK}e%tv3{NVO0JAIl~Em%DL7OUmm$zE@8^R`3N)xh=juk zgTENd_JGnWmQn*qdUZ@Zt}ZRFs_2nX`ePdzH8}Q#`@3t>Y+-hj%bKWb(f9o&ubYij zs|yeKn@g$evFn)V0p0gxYwoe*mFgFd>Ihz|jqkzYUNC@M;ID8v1w^gj>{@GmoQ;O` z^g%#+whN7`|Q8HXql;1AYXN-HN9E8Lb6jb71CCj zO^CF_vAPc$7B$qW&uZHmVqnlDB;S&%xU_Ebk)Vn7V#`ilw<+;`7~EXxIWvEh_cf?E zs%>q$6y%<}8~?6H^wI6&M(MHM;q>#h&fTj*jNv~2G`#5&QRJoU?S9X+^7cZiH8W;6 zib(lLV7aWV`KaALo`=tuYbq_2F;4|T)f2GnL`)OrSio)vzj9q&GLidbnx@#LNw8um z@u_W2qmC*5EJS>!*bw+|{5c6z_w;z}7rNmPU;X(oIBryYT@Z7sXf6%u^{7BOlhpN@ z2k3^)`EWpZF7tyka*H-*aKa09u5Tmq6?Ja0Y1bX~)`@T-gwkT2!KOpM=kTs^B~eqa zLPM00RU@@-W%_XH1Z#!{)UR3A{ZUnNr)IK1jM;nBOJ}aG4m)-nP;r76snsA6 z=BMs_s|=1*N_Z1SJ$bo|P)~zK^!f+8gBxQOykF5b)NYoC%3k8IWSbpn*;`ZklJ>-6 zI!i#v9sz~@jC48!?EEY{8D!mQxFh=ut$|s)m;Ry6=@0x@KQ?-cpK>SzvTS`zA2z|6 zT1TWzx>!MD-_FeN55g6*WD{s(1UCv8^9DBNaA_T(dp=eIJ*NlCMZp&mRofYHxz}gL+&cxn7qR7VE)qo8Q#m z=g7obP6yK@UGuwp{5X|-e@HX$9V*3!&>CFNsN~N4#u(u3(A}GBn_}F&l+tU!hP+x$ zYW=!t$~plyq0bso%3ZDnV=sCgn8TQ95IY!dV)br+z8#Ce@Nl{o0)(mCIKk@ld%o;y zqY`qxml&xfzbtrq2kqoF2P`TFjLbyutE;-e`((!8{gGdq$()fJnzocC5iLYS+7+PI!%l9hGYSy^?*eSK*0Ayq~OcG6Qcn;$Hk$s6I5c z`u7kd%}X2imrynlF||4^498Qh>TjC{t4-~RWVc5e!3e1o{QUgNDxwNWhKbHoFKLRr zeM?hQSM)WZ^-d?Vb3gM7Q?|&vbBbu)n{bHFx*+_Gaho%!{T+=MjeZ)e{VA zRi9)Z{5A2XW%tzuO!&KHIF^u*n@c|+`Io}E1nFPBKcv4pg@h!7e;R>85`UWqVf;CP z_-c{;k^V#F?_QyhP}J85VbFi5#348eCfRIfdy3tjYGztt{;}5LBNU@v8yf}vwvt|$ zGf_D5aVeWI^xNd8>?EFbk5&T17aSy;F&& z(ww|xi`C!Y>oM*9q%G}DgXQ|2&OEgFPTU65Eb^3wic!VN^PR8Q=Gt)Ilsb*y8b=uX!LT=Ot@Z5Y#Or<+0VtME zbj)xL9G<)Z=u7p&<9}q;0rFidp<(yyDqpsoc;PT1SbMFGTSA`i)LglMftS?)( zPHeu=4UEf$^KK!x#(|I0+il6_dVeMz*~$R){tg*sA(`vBX{sa`jhn05n-Yt+)BgJb z5)OiZp^~qv9bSKTS9-o--Bq=S#&EUt|4{YL(Um~URB^k`UxsTN|LSR& zEH1dmp6K;wrwJM&5y&Zv(ZLAbQ!fSlhFctzSWGI`nEzKt=2h!y5XfDi|Xt=g*Uj3S$F)nEH!SuC$=ib z>}GQ=pg6DM>FR~VH4ydsG00eH3;julPD-0Oh>AM6y=I6%)%X^1MEl6^b}$L^j`Bu& zMSCiNw1PMKNb(12veP&FIF9i8CKd8n!44)=fPPI68X#D@eBpd9E_aNE@7{?3AX-v?=&=q`{pnzGsW!sn&9qIg6ngJOd(fpkzm2`QWzX|ZD@^0j`8C> zgXE`c#?92$DA;HB-N}UC&|>|TWsbc=V)XgL71Pek(DJlB_#Q>)kVp*ZV#f<5Ya2q(!`qnAXrAtO>cz#<4{Y~n5C28C`q5g z33hf=*Cj&}-dT*F0!wTyMUAHC#4!3bm84B z)Ca>mf1-o0ST~Lrn>gtNB36$iQ#}jJmP=O&HI(%VmP>n zI00u~W(&3C+Qg2x!zZ69s`9^<#+J1gBB~zsT<@azZ`!>;2<6WGX?)?6Te>7KYaz02 zwy%B`Y$42aa(10$+_p2& z_ct7A2o}y(N~PGjM2~a5kYFOb4=cq!umCc0;{xJS_?~M|G~Qe0N2@fBc&Xe81Fr_- z9#?{Gtv?!e8}AnyeB3}R^-c#CCfViW%Qv-G7T}L1#m5j-5x&CE-zcVwPiB-PT!e7h z^5e?y$pCr6k;QrDxs(**k>P|_1sg`KJRMea&4;!oT5*{8?M-%&SU(0r=r+;|wCaK` zf^a4}9W46I*mwF+!7}&)Lo!Rup8Xf=TnyPi z3atJT^$!?Z0SI%t+&6AG8M)Yn0vt=$FT@7K^2er#)F3>1bF6;f=PFe{9cG$r zX^cEhv`?o;mWW?d>CQE!T(nbDj(28=2|nTJRdmAQlq3}G!ZEU*fWg2hQ;tmLfqoxP z@)dZe`c*9tVRgRRl>)riSx0-&h;nLFDq>Dh$W>UvWfC7iF0LTvmV+n@iTExQ;K-*S z;#TI_ZNy&Gzi@i2DT=JY`I5-}BT7lT%ky5TGVWmk3@)o9-$rfbW>f({pTby$yRL#D0f;e)qbEnu!=yXi}SzR;t`>x8~bOa7S7&9tA+Aer3J zvz8$x_mLNABf&j5{az>ZJEyVRS~$u|R!I&Ds`)aP_7>-oa4p4I26wi_n7OyY zDbulZ)vX&priG@}=v3{!=^CWhdD8Ha9^LmR9R?*GrBISJU0_S#F$pe;>8R-*p-0&p zTh1f%Irr~=wos9^`egW*l4Tbhoav6*>~Z{%Urf<0EjW5Rd`E8RNkL*0yT1TXR5px_ zDcG3)M;aI!<8*Y#RQb7oE_cc3gvcPZk8itEup1BAiV-g-{1}a}=J`-;y~xte6y;+O z2wHUpyq=nJucVBy&p5-@*4pAe=cLK$XXlQh6j<1gIcHn=iodyyyFP^V1tMt7H(jPt z%gl+EmtCXU`kfH^m-;<ys*Bu2$q~${98CJEq+8j|rtKRtzWI;N% zS+y&2L^;on2mR1oQ6(2$jc1%{XN421iJh7%c=m_Hkxrq|Zdn>h{k|*9KR^xj=@-Rr zFOrT)<$;^ivD7>R?XN@p^@~rm=H|O!E_2$dN2RG*j3K3Sm)!6y?M`r6{GR?4;yf}3 zeIKEUh_&bK8_TWv?mGT0HtX`6SdTa)m(#A#$XzRK^bdpIVxEL^Mw%K)tM@e_=$Flp+^&7VOk$?b~g(3 z!hWI{3fy$YoAc8ZJd7`;er)_)=Vnfk96-;>g-M><+M z`0s2$?P8g}461VU9D>$cKIZ~DjLT|KsU(cXdexp??O`Ft6nEOzqBW7&vWTv1iW}&|M-#F`|w@8BfPZ+Y`u8!s}hbrE^`i25eNvj$8sRgI*(S znS(A4U}?9rn9^7`Orq&Y{~&o?TgI#%5qY|wDt~tQxnP{Q0Y;@aJ)Uu+6Hl(;%zJYs zz*`CNw)3#}u({;=xQppgxee?O!eMcM}s z|7qKeJz`EhEQ96_WLJ7lr0EAV=sN4Iv*#4e)dj_Sa*8=Qh}i!CVE{lmw#yj#%DXlq z@m%PfoNP(i`Tynu@aJplO)%e)Gtxev9|B8P-ZUN#EZ^-JvO1U`p0)=aTR*@y-5c;R z%=K^R$^Q@LradWy`43kU{V$Z>wY67uFdQ8n9Ud7GtX?Wu8Z)*P3iaU+>GSK``8PF% zsHUd2!Ve2T=HvH~3LTl89NgHz$Hc@$6D_;DqWo4wchH^fpt-WLa%@(XjEG3!Ibl!> zbWTn;Sw9vWq_&O@BhG;)FHyfwNIqp^Qqst$LTJSO%S-vBg=}QvpCF_!71PzP|L*!+ z-T@X-J&HuA1E1-$B}V_7`1bOm^}kTRzewbN2mh~+@V|Ko|JO%I`O!C^ZYC>>prWFJ zhK?@r^CuA<3;_W_>V%1>m)BRV)Aij$0z46&2WKni*CtXzLPCISNr6NHd0o-Br<52N z2ySn0e|?w0@V%=Z2trw4MFlB2xtOLZG+-nwI=Z;7P7&u@H(@_@!>H)!#O7GcHHiAj z%34~~aRk3*C?Wq}m8KYn#{D7*Y(X2@;y~Hm5~Zufz?3rvF_$RYSNX`;OpJQ(d*h5% z2=8|!3Vb%zY1knx>xZu7Nolwz2K@-QVaxV}tWY_O^Q25W&$qWqCs>LdY=Cw-%HdIK zLNB(bqzdq#rN(PPT>(<*a&oUEod`)saCpMAN!mM5+9AgB(f#Kv^>5`d8Bt^;MD;gX z`{sPw!ZM1#`4$80T}t_%r2V=R!59 z(U%l+`^5nDrl7$=czr4SUjG5>Ju8X+xj4Olnr#2nXP<^2hCus=Y6hnbwGPoTLY{&| zLT8^_%6F}(mfMnA?bg7bc`enL>Td`iQ!4+?3r_)+I5Bp@=b6&0pe?}>DJeW-Km{MO;F}?;ZcRpg|B3=poN|a>j$n%C|&SPC~xrn zN#bucit-3Jv;m>FDM^m(V9i@amAURyH@u)>5h?y@>NL%SOKfr-AYm`JYcMAqv541K3M{(fyMDYb|gM{;L|(!Yw53xJSYiFRJ7%} zqg8p#FGw3K70@#%#&{SkPu z3QV4a?R<;&wWXXfsFKf?THWzFuVu|OPsD^&9*u}7Wq?A(z3|hm{PkqV zL=`6L8WM)r4}pRrPT#r2ywq~T!4{3C2j1|S86=z_L81o`yy$>NUT^9{aF}bi zOFYgI&isd~BL-a90p~fR&?D>%1H$ab_|CK4F}p zG7#&4R!D;M`UeBS^3UO@(;^fSy4jH#^I+$Oc7QE|`%g*Oyyah;K zlyZ((fV;;k?_l($X(oH;BSr1v-2+JD6>PL^8EI{fu7%D~9W_a31Bne`^#%TE+}|xN z$1zJ0EbwR~s`T{h6XHJFqRy+x)Y`&k80ev*AUr&FMgA95Cx4;bP|TcF|2Uek^K5J= z*bMr`XpKya}!8qbcaTi!R z&3W+Uni2roAyCLve|m3oR^3_r)86w?a$*SM>bqOr&UA1P5Q+@M0>lYNs+xwDQBxHu z)}riIad&Mvs`9Km{!L0&EOXaakQ$MdAt|qkl*|avSFF1>x|S`WjpkNlS@@L+?8UX0LZk0JEKvm-%7P>h_!Bgd8<+mWrdOp48xTY z{XS8c*Q|C(&v>o~si5P1oc9joFbhek2Mb$gcCxwn2zZdaa?pgVH01Dp5CUfo+DEGY z+F3#45uoE_sEEY0afpfskzWcWBa0W1?HX`;hGYdtLE>Sxp#7oxt7&N!8It}F4Ymd|X-W|rsY<<7h7P3Fj--DG|?#x&|YOvR`eMu)J# zLnPR;JOs#MC2N@1Mdsx)+I-%9i|DX6GH@`^eJ9#5!Of`Gg4 z$H#j@7jzO3h;fr?nEzedfQGjd7aSN6jp@9G#&+Z4ncym|=m%IGi}vi|hRUgehCET| zBi;^JDBC3}bJ$MhX1U9bk1Qm$0ofrtz&=KJVkh%RgY@+MV}TLj14ReDP|v8uX($wL|~r2;?01uD=B1+uKA@zxZ9GxzM%T&>?Mo zc>W5FlZk$w|JzEu%K7KkDEBk-$$154yozr*W9s@niKAK!C+N;1H{E84lk~yT$@oYF zz)@|86Lv>Hx0K!Ij;Tto#<|1N?GW|U2!Hfp7Vhh`fc}ec8*G2H&_^jWZl_Sn=}1v% z@Y}Y}ua~t4Pq!HS@>T%ECJ)B-L5(OorB>($4g~Gmg2>G6V57)f?C!u<|DKf3PvM zY!e{KD91v%Upz}Et@cS!=&I^El$J*$IfO42t6np1l%w8scx=Dm)*7dk@zj$V+M zW4Ge*CHjHki$y^BU3RsM1*S^Tk4JnHU7qEAgUXpHY*2e0fORxky{{!8&2JfBF{k$~ zW~5Muma-+PWJa`S6j!vPBn49sk~Zs1&w~VrVQ_7r@XFo-(Gb|thk3Sujq{USPU?3W zYtD^QR$5wEb2B?+UmEk&W~YbwW(Ow_D0%js@DB60uBkO z8~ag^Q=MZ44pj}VIrcUA4VW1 zBYtEeAtG~Rr4j2$%Gww#G6fC5L{SgS?>#eDXT4m(Gm?>!p?uQFyGV`F|4t&b>mR5i;NC8Z>tw z(IlE+v|-C?7Gt*?`B+-!7=1P6u-J!s*=?G|jHMYWaK!I8pYX(}h5D54we{@mQ&&jZ zI=y%##q(pJT2YaW)_7$RZ@#;Yw$T^fHYVRvo0ms>yoJr%{{ekuyo)ZfMzH>mqgknO zyT;=}jMbF$pS7>C?!bi2_4v()Rixst5TQszvh{ZODB7y`3(H(rl*5@!%Dp1_H0B*6 zYe^-w=GBYbK<3;TOX-Nnp^NG+9UTT4FHIy9`P27Ldy|&bZ~G8@j$M(?=y$}YIk}h! zdXB+QjN`ID2*ZrERld39GWd6`XRUeb-z=_op14C!_q+nlqV&$f)KatST==F$}np(ttPn5%h z-D!KVMYoW^)n6pzgK+aR?>@3E#pH#)roEzY@Ubd4mpEY@s94BHOC*+w4&|ZO9Y&O( zWahQ>J4&osCeXD{Qi?&(~%9>mqWR`RlH7pO2s_r^WHd;ep<0^i{?ekbeNYFFR)7_(K-FsPbtq6hQ z-&#v0>fY?H`%OQc$3?4L(UKyzWV;*9YMC}YFL*n9BJBzwD0e9~yt5u$Fe+jC_?&z` zkwswCH+^b|Zjl3Hm_1yHs&FslbN?L!ecdT$>GAi`RnFP>w3BrL5B6UiX>udGxMJVVf9~2MJk(z zc4qrg8lD-7``w99%rC~O{+5se`nTv9#A?#BV;g24>q_x7TI*Kw2E@vB|Lelo{&%u* zDIMW(VK5!qk9^zjA{)G(QFK@hO!kuOH%6mN6~C)_+}mQxE!BbpABvL}pc2wWg<69l zhRknO7%u#w92#xG{NW(+qJ`?lp01T{ODZbmLGX16)EvD2sHL~M<}WL)B-O`OGdss> zeegNb@wQSF6Fy8_rZyNdMSN|)C0;EnYAl`Mz&v*P2W@J4lSa#$scKQB)q7 zr<990cqI&(C4Ye`%__=+Bw|EbaAI6F+;pTT>2;#XwJrLDRQ=FoKV?9W^@0hP-hv$k*EO?dwhWp9(uk! zQT4*;CeKA(#U{^fSs3mPeo(5qppH7tTKw?FSe4k=v;thzPG^teMDr2hOKM$A#filX zg)s`SsKV21%4nW)y`%j&kS}KHOw#0yv|94><$ft6b($G#E-Yq7eA;1MdG&3nZzFqj zRE_ZHB@WfB%?m^4&2i|WUZsL-J6G68sPswJN;48}0O-deLSjF8?%xC<_gjhYBQDncI&$0BmC9kG1BKIy zB@b^K{YW&cr@fM0mauMH>DtTw7=UFl!0?e|^aqse8dj2(8-PK0la1;9MT2Ke-smlp z!tJ&R*|kDr^5fxQR<9pIUQksOBwUXtYh$UtwA2?BiXF`e*QT03et1@NoWCUn#fbSe zWUIGR5+otPS-$ES`2tx`sUn3wE1%FfP>Z~LmhZ2(D1_LO4ct#_kro95Ylzeh$UA*2m*KDIn7P?$ zTI&-+dqhOst^JpMokWoIi(lPE69#T7*y)VH1bM<(=-z=6P>b?*yQcHA2|LIafWKa& zmTnr$@So46Zj(s%yPT7pv`_Pr%Zcwe{D~YtaLJMo(1d^5SlVGuSeL)h-B{W?B0C~< zB}46MySZIGkpf{=mmvFb5bk7p#YxNQ0$+5d;CF;aMzw}_3kT57dQUL8QjvGC@m9Zn zx|ue1QERN!yRy@Op+`|`Ay98pSSL)*#Mou9X64NB@0UyBR*|D}s!+=diuKrcQ4W{< zVOE^-Kw=Mx$}2pl>Z0cCvr9`JoXiJ(b!8`4Tp9F+m-i2Is#jER$QhUFARtP@Qn>Ss zkwxV@d}-izb(VMFv*q?R=o4qU9jp?;`wgJT8bFeF!| z6E-8y@FM!17gS(`uR`+~ht14}%;AjfKwujKk*lRuQFgP=_yN|0m@N{a*}1xciJm~H z0FOH}Z08B3YU;!L`W0W)@%c!gDYM)g(U+wr*I@m~laaE~zZ8K0nCb)kiA46v$^tvN zV%}m&w>;yQ8;Y-dkGsPyzk7@?=bD-hc&{SQ-bzbr3FM^~KyfP;KlouzoTNcfDRI{$+Ag`JxtJ(UY&PvLV%YSj- zp4xu&)4SRHAHkzaD%RF9^{eYgzlR(80>q{?0>%Y}L_oj+0n1Y>w#SYI8%A_rC7UVYN}kHeX=lfb`#Z;)Z{Ba5o|fOBRDrDBm1JdMi!52FV(LRg zt5ZR;ZfY4S0oGX_YdZ0;%Kb5gOFojZKb>Y-FVntFGwa(B!rYpD6K`LCU3+o5a-JX@ z^zeGe%d)V(ZiaZ)dr-rhZbz7>Zg*}kNDmW@9$6I6?eaQ=Ag0P&x>9fpFn$xgbO8dd z-uwnags@ra;Rk`NRvRj^29sEZo>x4dGxchM3Cc|PI9;!+M2E+Psp$@e=OLeeE#ok= z+M4@4&yO~>XF4I;1~OJOb7$Ap%J2;>9>&tU%WB_I5Brx9ZH!D6Al|ag{I;I=rtFsS zz>7_`rwtG4=;l=wWLMrox3UcCRD<1vw}T4}T#+tMnRHid8$|sRm)Z`=k8e9Vpd=D$I~^HW z@$iI(i+bPf{7c;#=C~l7gkMkuA0XsDGmGO}qFW@*n!kjuUqPdoSY;w%KodM5O~l~? zUtaHHWF(=Rm7qCg+-f@YCzTa^wA(o6;<>#k<;u9bl76C6@c0(xY}xx|pW6`}d*h#m zPyVoKWO2(bP)%Tg?%yl5t0u|KO#HHvqV5nIfTC$rAM%BbblFPus`N*IQ1)b~y_KGe zMN@o~RoSV~&nt$m-!i@XsyTMngyj+CbT3mefmjMhP=miuVQt)YVQpG%;pQN9Cmf!- z#GagDV(6+@6qss6 z_4YomvqG1-$=w>0N?RXLw(N}5&BOYfl$hM@MlzE6G&NS>9j>D?2wzETkZr=d09bkyh!CPFp!tE_1X6#hX!UO?hxdK zeiz^MYoK`d!h_}sG7|{H^m4I1ckXN}wd7mgQYL8odN{s&uwRL`sQI3jT%J$hfmmX3 zp@hGjghRn$swd-M1G!QAZ+jZgcUOBAdr6Hu#ChQqfupOhm7XPaqfGBs7Qlwy#sS&C zF8xo#rCYdSY^*p#PK$VM7VuCSQ}vAd$VKSYTw-cHnv?~a_V_6nPmSPU=7FHw zd37+;qr(7#AO)A*mNZ0gxo8Bw1O>laK6MoLa6y!gNGQe(mdlnaY6Rxsf)`jyG|#_B z6$+t-`OSs`o$}2?!%A8`K+aTcOKyQ|sUQuW-d|4NRZ#z=yMH#m5quvg{NS1}v-)j( zw+SjF?o?*fTZ4odmOfgw3knH7-zQfar-sM2D4OKNLz=bE1eLXpyIn%6qGp8Fv5qS*CuMBi3O0Zw7O1f&Fevm% z3H*U}I~KvYg9o-T6Ttf;X&<9{XKk1NxpT8m8sS1>?B4oavw+Ed@W5gKZMA0&C6p$N z6*Ahg%Z7|?yyY~@;VHUF$wC7MoUPCgKxSF4r(|m`kU1k}VSY#z;x3EJJGqR&24tx@ z)|u&{(iJW!ka5Pt{delbZV)5-sIrp&2Hk8lK-=;TP^# z5Vh*kb9vy4JTTPpdx>vYKk30RDu%V<$wA(!zu%Ko*k4HwnZ!M(TkoH1jIZU8?yc_V z?&=6JuwDQ9Dsf4>>HOJAyzz@FC_bGXg}L#dNekz?hbG4UpDP6Y7FLk#+;rkE$SwB7 zC0p+xEpZ@^yCp@hHudm&O7N90@;x-yj-w)>U_|ky^w*`a?&WT7J!?qcYt#Dr9rY#d zQam61Mh{kX3HHij)cryA-MtX6S~qL>;cEg7BP*A2rKEIam&HTRkfG5>Fa7eo0ahiL zhr?Cs;JuF*Tp#V%UNixt>#_q!s($|2v3LJ)VCq=?pzFxT3JAMqFhW7C5k1tXJ>|@O zOKU@6N)BNX8Gl>_aDSiHDC3JVxPLR6%z;FL4GKevVR5waUEyfDSE4L5GIPM{zB}S< zPi!~7Hd`bE43qs!3BhzZ+-GO$7U4dkBcXR5{k%2}`oY|fP@JM4vyRb$wR88CnXPy5 zskO{3xd{$Btbp>#dQr{7Op@!nk}lT^Vy@Q$ITIeWY6N=FsT-Ll_5cDr`_p2Bql9q; zNjzP)7}KbI*}p7GH91EM*dmJym(rD~8tvPaq@4ckX+bzdMGYNAUtz)^+o(A9iR958 zYE&K2>Y@N6nt|6JaOjpR+4X@@pDy;o<59;8 z__5KGtBn-z0oXSc7taRpMf5EBD=LkF+jxX^EY9fgdvvR6N@3gUpxcMSWMlm&TVdNT z;R@Q35=ofBaxrXKB`HdUhkjQVQsCd;VbQ2v%_|BtU-~KrdNx1Xu`|5+_0SWwF&0d) zWl>lkozT@gD@kcxlWcWmNxDaU#r5&5gFE{DZwf-?9RqpULvCXD2hKep85@=R_78;x ztZ?&rVj$J<;cc)d(3uGgmsks4_&tvB2~?6kZ>BouJjh21p8}`3L-G4{Yx1istFH-ZlBT8oJ?-q~M-f5+6%mE8^;BZ=h=o`XQGG$%@Z5Wvkilzf)8aV{DZN)c zPQ5?e&ZU`38_XI{*^eS)N48&Xbr^LdczinlHswX?&vsyN$a#z9o|MGj*I?t8pqM$j z8eGx-I7(Q4KF;E~UkU5*@{9O(W5?PVpRTv1p6pNR3GxTQ?Mw7}mVd@jh~tH>a67%$ zWTZ5JlL%_p4l(m`Vnm=7(VQ1|Jji4N-fO*)d2qc1;umX z;7OI~#M@pe-HA^2CZo05>9*pqOA5=+JoHu@J>|xp+MgK7_XV7${WGbBls#rpQJ+z+ zAjjJwuMpBBJmC)UY<0DaVG=On4#hLU(Lbzpf;<&J5z3*mX*Y^=AYAtNT?L=CWMw#V z$`uo?L&spm;Fi7QE&6)lTpqQ~b8n*+EJXVer!h&+Qq^I6B6I4Vdf)q@-&JR+ ztHwr6A}2{q@2*>f|L|sQuoOXzX$qNB`vymrY{ROKWwveCOR!N4ZxcH$JrXo{AB0Bo z%X$42$8IP|u%j0#O3&U+Y+_=A76rhC`Tynu91cBm?{Zr08q7P*UpRHmtxoQIBCpV{ z-!pvu41Mv+iBvvC*Z~44rq$iqZQYvr6|)TGcG?@aW<2%oY;gIBQAoa5@~|c~X+h~T zTN0@tV*efY3r7b5sst~x(E;SlU+CYt7RR4jbwAhQ;%qUKA?}XD4G-^Q0laf`XmHRT z-`}kPEJHivO>K5&j+8SPz*YW(*43#pR4%(M3yTl%!)T5a#=4Z#CONkzd(Q06()a&a z@)0+8f13`%4O4(j*cFfbJP`|`gb zvDp7S@k3(#-zVUGz8l^yik_Yw*TC<^7g^ZZuV$_gf`l9$9YceW&RM^6LE#|5006*S zQz%I4{WHqUE~uZrx}x1)kB9QV;kxnVS|d?m=tr*6u`zQS8v@myaJ_e^Ut{eyuc8-6 zsRXFJQooSS(ZK@*2cvK)@Q9XaMn*;q`hwy6fYQ5a6%e3)+iJaM58;GE=;se!>Y-TQ zQZCCO|0n1F$Ql@n4DBr%yoZ<^uJzw+{jEev@bqSR?ZrO=^8iGofi3j`jOG|#G7S|U zup&|P2C>HtT{`0bws&nwM+Pa-rmC%o|J`h>1< z*S*VHEs!6)4^v|*vW)J0z{zulXcp@&I8@;}vC_c7D7F+fp0r>Fw|05&kF*TY=67qe zw(jD$H)o$Qng%sYMZ7BAk`n~CL*tl3i zIj`SjXKOIg-zOB^{<$DHfZR9)_Fe+_nw(egBR-pM&l!>HD}M;}zZ-)4HVOz&bx#No zFj%-OO#kaiP~>!xhTF?@rxh``xT|k#$UaJTEmdjXU@+HYW0wUm^_I%3t@YRIsoWW_ zArRAQ;$jk<_t%?{eA%2_Vr#Z1NSPKpXeOtrQ%Q?DG5hGLPo!j5vav*F$BsD7?WUTg zz&yXxYATI%5Oy>?Xd8sP049*l@pAIT31RDsOOxFqGAMsOY3DKn&U@0d*;WOM6^e>l zqnYzOwS15kPh|IQ zk)JhhQHk-qzq}A*fWLid@Dt~VQVba^+lYl;_jr`Iln4zRM;`bGD5WMC6Dbr-PtOl> zZ>d~c$fV}=ACPti&6$`00A1*qL~J%y2RlJgiGfhvx+!UW6sDvoTc!?JRb|`z&1Zn} zc8ii9S3XKZBS%H{5+=+~Y9c}L%V(m}Q~9Ng`n8%KufQy<_T=ewdz=hUQe*X|0Z?}g zg~qvw!+1?De`K_V)N{Joy16jcKLV*uKqjCTH%xG^hzfS)NHERsjC*ykSp@LFS%sd{ zBJ_<9dh!se0+eZ#o};S#(T#BW!dyl!yCRcV3{xByL)3@XveJs7J;b~}TyW9Kx8kIR z@jqClL)ydB2ie{QA)-bEh1@a97~Ko4YlFRo1WzpT+JMojwwMO@>PAY#j2R)YB| z{GG*#<;d1|ih*q)G5mkfuq!tM$@l`0%^$Px*Q?&K@+$LVe^2NH=I736*^!&Zr~MUO z6YmfGGfppo#PA~o6eAZ#9roCFJ;z+jbSHmq(9TIQ(D-bFr;Ei`uYhdE+#p;+xb&!Q z9)`sARGy?fIq^ojKDiHZblYz(_n}cz6|t^#xh^5q=tSS!uX-(ba1_1d(7~i8J7kNd zK!^!2Yp}v&2bAoiQK^U#S})bk=Irea7bVkHMD0n7>#Yol+P(azS+#{F#5!QVcG8MB ztvsP)+c;z4bo*9d?>30E!~S(Q9UTm28hzN6DVzOeNV4_95}A`YAVYD4>S|3=-2}|7 zcepTj%S1EVrziBdZjWzytWj9U)Esg;3kaaEiqBpVkKTPer`)Qr{Oc`<`GBu;?}g$^ zMwKRhSQx);v-_cP(6Nk>-*hk(2_04e^TNZqAmaFMs8=&h-kKM&8g90T-QisDWZk|_ za-qAah8WZWZ9M%~j+fpjb5?9@cK-s@zC&}jFF%^&lKIg^iDC;d_Kt0IjoctAZZ2lx zU>E`MOn5DYO$yCC{@i{FytBA`FDN zYRIDO%p#=jR(x*`#nA0iIJstE@-llI>o5vscpKP_6$ue<%HK{5s`CLI4Ve`Tl0^lW zV};{eXQb(p*bHm&^5APWRV5|OaGQ6mc$t6_HBu?+0{gvbka)2e$fU_OLs-jR4#oQ6 zW((-X1tp!fuw1Tey2@1jwz3uzc&dt2h9kzAMwThFUn#WwUC$B-{j`;itf{}HY!+peU`?}wjkz?-ea$@fNl;9fZv?OZ^^XjRB6`&+a+ zErrapP{iU2M!6hvEDm41j8sfvDJpi&RfUhU)0nOGGMDm*IFi=7TO zRlAk%VcPK~V)cxHoD_ZqLs z)Eqe#jDC^|#`<(LgzYK9Vm~ zH(DV81QxfclbzJq&ZTP9AF=tmvD@S6Zs7~|Syf@h{n*ECdc3EEGZl^EMq^?UA{%dS z*WVLfs*7@`wU>d~8qIRTlYu)eA-U=H^%wP^)qFmTqvHH=iTVrG1)9Ogp)&_tbbySE z=X{VpeN4Y&h^n%(sGveYAecAL!-6XsZxz;D6Po`jMOGdo>fU)$=U;FhSBuVPbWE;tR#j5S(u0hUzd z*8eawf{U(Rfq~FLg1DALHmoF1;QI(wT)LZttZJyONqZCrq{^~4TBF>&y!`DqgDf0U77!|6H#kMNhRtfP zIZ@_q!3D)i7>duZI@$cOA|1#pqYR&J^K(vdO(2CT2+&HE>H)5``~yBN`>a6tu3!^m z?aU*BEGhbM;<*DvxxBU{NI6dSRYk!!c_UVKcA3LCGi^GVDZ4uIoPm&P%}TnVyh3Z% z&&LvZbyZ^}dook`=W6fc=TCnt6QOu%r@U@<_(EsMQkb*Ubju;#1z9MjRw|6~O$4^* zb|`TjEhMV3k-TWgO>?EV3Dxg5f>!I(5@-y#EM|!e7hZuPQUy7XoYC*W2WRD}&2?FWMEf$N4z$g9ghR=; zY}f7yNl?zjTocZ?rqT7tRn?{|zYv2GSu}5NQPM7;ZzrDki23tANFDIhCTr@97u@;q zM*}FxNJ8Wju;3Lr0|V-l|Kh$pr|IEeHZEx{$c82M?32P* zH;XslMa|`lhWoA*_wB;(5pKWbH6(0Z6e-IZ8~XQ)C++Hwcg4yob|#@!l%8Ku-~_;{ zIg_6_yJ^9eO%VgZHOnfU_imt|#mO4#{PR!c-NAqG8lU~n8T3^snMFn@C~dn?l(eW$ zK6Usc*)CwtAFyC2dHB=`n6LqfLG%$BSa&&yJ0~q(Ue>M;bL!&It^(Jt#c))N`99;5 zTjz_O^ud}*hbE%(0CrkBy|NO7a$0DnviBoKBCwa5C?_ZPFVOTC-x2;AT0)=4|5VUN2x?)-ww>m;-7MOkVV=!p8a+IB6z99? zCK^OhGaYf({aIaycyP?Kn+a(`m=&{fo7eeyv!QW)HV2iEglUe7ApG1sjB^A6?>#0X z4sRKTU9+v!RH>h8_IpQMHy(F*Gm4h_yv_dbJ(AB$ZaQn+rHw`%F!Du$r1fMS2Cr=; zB9TC9_fWBF1xW}b{j_6#I4qNMViJgs-;hr>kta+ua?I+Bv;R@u#PBk2^$GCHqNgE= zoNTW7923&DK9L3VYp|4N5xttYgJuzV#^a}GfL{5gDpmxPB~zkj;JVfpCYUVz8xN>& z-E)NRQj>gXlj`e-qv5I!fuO;qG>b5lk=z|55o3&b&~E8SIIfx{udho}SDAdt5T;DW zKLN+Qs~R>gmKC~by8Xv(BboFW@%-FJej9T_ey^C=n>4_qviO^lg&+7qdP`Ac=USL{ zwsZ+R-@uwn;N&Ok=l-&}ba^byA-tfo;p>;ZNEhN;KR`s4>Q{F(n@5t#@@nufO;uGP zUIdDgx9OZt1qvn140K2-GEo1AdG~ID9xBdGvzLQsWyAUZ1mqJ9 zkUF5aY1AH*VMk5+>MkX)U7(Y#%?ATt%YIXR=hF+gJ40e*iIf)k$3r%k@5AVf~!3}?yU(N`+C z`u1i{D@uQ*p<>7F^-jwnD>yB=oR@wC4tyg~1IRGfQm=Q0?FeNE6$lBOcZQqA zx{J}6ykdJvV0%r8ajYqOu0qFrk}C4@Yu2g$!^#j-X`ks|FsUDe3};6v(x)rTaEo@q z9ol@YhG?eCKK?qDkOgo(HM6G3v0)L6yT=ws1^G5JXsjz71`Sah=9Vp60?F`_?CdvQ z?XW-*6K7E7J@;tSR?Ai|1KemTqvzdKFb$^*W!-FiDHH=ucMR_Oi9g|V!@Kam6N3Z< zr|xS3k&Fy~5DA6$wC-C98OkHlH589b9lU7hy;Y{jm1rscS_sVU)D4Sh@p#J5_7s!z z(=6KVoa|D*6zmOeiQ;N7&9<=3jp<=}xEH7fuzA%aiEl3dGrmf>k&Fn^nw&gR4w-&g&MYYI(60(;Y`NUDL0+BVi6umuoAoEhIT@ngmn%$!wH}g1ju53V zy$UcU=&AYWMbtaT;3Y4T$G zs~&egFAw~w1seJ7!>9?j4sUyelqAgSKaIhA(Zf5XkFc^|`ET+EKC0|?-!;nK&66Xp zHm(0vic!&0?up~TTvP~qkl!>kERz3sX{(kAu2{x;rn;m zFe$hG$ayq48tLzu-5>6yA*I3o1dCa_r32=ca#Im=Runw;D2Nf!%vUEl;5X2>dEBvi ztZn0xem5rJw9QP5>3Vt+lM>1T3FihwTXK;nO>;ZS{fnTr*mK06{}Fj|gJ*ELKarm& zYCxKhfLdp)N^gbF0$UIxwLinmB=MX6z(ud|@zqn!zke?x_dXF|nJUkAW+zEq`8h00 zA;^kST-XroQQ^#&jXu^>47quMW5_MRBnA)u3S-xk9X|MeuA{f5^M+70W5$YfoZHBY z(YX;SQ9V1WE*>!%ra*!WBO*WZBxdL?^Ay#8PMQ7#Yl6J6*u(-?nlzONZP75MF(K8g zxTPzTNrsv(Lb_!`CQ6)`d@RUKUs(Wt+x(X3`+sDdBrlGM%wooxJL-(0Lms|ykobp+ zbQ#`k9@;NAZ~{F*0Y_du1ldTNm@x`{KGBLOeZN0HAvCxx6lXWA-r`@pKzw7+X*dcC z6%0qD=KLQdX#fWtxwL!G;VVx10hZ&;uW-ibRGpPXd{S~v$|{-?5lQkM1CavA6Sz4K zms#Hxu#z!}k7P|r8d60gnLh^f6W-`>ym7zX)Vu>@M*`Q6dp69-dVs>J?a(x*O=jt0 z5y{T0np}3I%hO-$+y5BeSNwSC4T=BdXZsK?qWUQ~3ujWU_I!m0WHQkO-NmoEZt_0Y z6}fsiu!R!vJHhw8LknRiI`u88cIm+0Rir#-gfm&pmlTO z(Dg#1mZeL)3e_o2_$UeZkPVKC%4Z}jgOiRSB6;EvEYc$l#Leurll-9(njcmQC|D_0 zB2}kCAS|-X8s8?Zi6I=QxQHi4U~F80fYWX}Kuodu1Ak(kid(Ii-?KTJS@r(p9tUbE zCn3yW1oCogzOhfZ7uGQ%3;%-JW4A{0WT+vhKX4uEJX@^G7IziYaKw&D^zp_@)T~`p zh>4@+Gm+MwTB^lr7_=C-yFFl{kdZ`ZsGHrn#3}Ox;r8av^JCh^=d!s+u}|27V#Vs0 z0%}n{39-nyZq9e52;g!YtFSgK%!LYzD!Tz;f|$KCS6n(IP!cB;h*BpO(PJpy-sh8oW9vDQSt$0!cGjfm}Fv+SH5+ziV4r z(n>BOk~DoPv#eAv(c}-5Oij4M$}20XY7M>(rUX_Dm`VIYyAr@x7uUj3)uGjR`HuAo z7#Y(TK(M%@PR?T)s$es0k4}gKD~oDvenuh3I+6c>l$~`@9NoX>Lm*gicY?dSC%8)p z?(Ps6TtjdV?(XjH?ry=|T?ZIocHZ}Q@7}82s;%1prfOPFclGIW`aI9`{p@m>)DSXK zno(nxSQpe4pv%~hbN5G6m}_wNCL|2Q+cCLBxg_w2D^uZTZvNh=*z&((ABkA{zNV?< zAqOMl(EFF?V95kv;kz(s{s+4xuc|9@w+68ewsI;^kH)Q-Y=ZgwuJ^*i^2{!tOq|Ng zijPKUia+PlKqaz2}P^-C2!qQ%X1y`*AVhOSuS#i#E;=I z;EK!b1}&}i4f308bEbL}MKe<`3O`0-(>e`)tt<7EblbsiG$cKc`2s9efLyeE(L;zU z0VOn?qJml4?jB2{%8$bM12r;V0q%fu!t&<=x^O14ERpEh`Ht2o_CgveY#Z`^dt*qF z#3IVgu%v9e4Ez0Zuq!_RJImP@AdT~B7Iw*H%=DnpF^QosTur#|tBs5hDG6_yT=e)r zeFF&ROe88!>)8cbLKaBO*qkNsTkLe44?K^f?NiyI7dJ$q3TPQq9kkFF8YamSH`jp% zYPf)k4Sk>o_rAAYT9Rg#ca)6M>85^`>#{78{N!U#Vvucnu;oy3kQ)5Hd3q05a?Fs$ zN&WhDfi$O06^c_nGeOk1M=F&CQIcYQsL-jSD?)?YO-gS6FE8`xd`%(SFB+XYQ?xZD2o*#tWcngs7auZiJ{3w)N6I%ETRNBrICvq%vXN!Z%U?`vp$(kW zZJ#d|L5+2)I1AiF>{{(M#+j1va>i^)oN7|6v_8$?y{7Zj=Mew7&-l6PZXf2bGqlX0 zNhiSTRfeGCgFA^H))J^Wm2OmApBG7`xAA$RYPHlWt}(Xw>A6NlI;GQKK$;go?E-Ai z6p~i3q2cl)D%GK?=F6IReIm9+xu@J$qR!1$;3zerar5)7xr#*^Fps3Xq$EGgZWN3em3 z0=b*~oU7kfp@J!dy1b9f+1Ae;$M(=JEDso!{HSf$9nc{F%tw)uWsXiDMnDmoij3vu zaE*aSCpTw}^9T6mj^>p|No}q61Y4C(5T{NF%{Sux2;%np)p%f+0MjnuGr5XUHE-s) zw;*^(sCH_T-m*7O?~BLz1I!DHzr6YJHRWo$g-gfU9 zmENOV;Zq)?mgd05jy!V)UpPRXJ-3Q^2`9;Ma`*8PfK?Y(e-yc=3kVGlMiG8ChIYUP zt+?jL#&rAD;G3EACr>->%zcwej|tksy7{3pO*W}4pwwj$?gXLQWW{pl&J{j&krnWrdTY>{>q7|ouaGm&O$_V?EG z@)pkR)6iw;A4!IM$ilAMTi_IvRgD1SL~4?FG-PcIMfJdbFBMqk(Z3O2Hh(fQuDHv? z5y{&~e?gpCp|3F}G@kC270W*GIFC0P4Fx>>5KGL6IQJ_z_GBT~6$UnpS0+-nDTiZh z{hH9C8@#7wFjAY{e9^~Z)b*4H52~?H=J&|M`!D=zCz)lj2W&U|K7S`4-pNuFRHkdyuAhENet#dT^(md1`QwiiiUlC zs!z_>y>~3B9aeju4@qEyszySz;8g?7FYy0`bqo&vZXnXtyux zj(sx~>053L)6&yJobCQcfju0~%Of9(A&tok?XBy^v@g%i>x!yUhWUh_*()k9iYQa- zbvn!$!WuKeezsg~u~4GYZuffr7Ms#p2Xwivrm`dA5Qyi9K=jCW5z)h-BsPh6wq5

csiG_K8|h3H>lmXU_lqDf|0 z61~Q?Naaol=yx1AWz|VPK8xH7!ppKozU9F@+iN9S#u@#ZwJfNriiVVUGV*9I`&!d) zC9YCZT|I2ciHQD>Vho~SPL3EFl7v)-zXrYak^Sz3jTrnrYdLTLIqJU~FhF7@eFz_W zH_443M>fR%TlajXt7zT%vZLkym6b8p9!vNiEfoJH;pX!iZm}#xPK1b!q_IJt|4S$R z_fY>RhYVzwiWm@8)gbop&|EYZjhL9Y4nj2P9FX$z{YCQRnUs)bcVqM#{#jqw-GT4bmw_b4dkueTCd!B#`_jt_k%~NG zoN6s|(5!uVCBy3yw|>4IO}@_X_-tWr6)5ufMZa3(^(o)5`l?@a;QXPaWveTCoU~#u zINshc`e&#iFU2Q1(2I;cnBV{8Gc%3cfC2FQoJ>6OYt0%S&iu+nbAN$M&T@Z+R{M&3 z&hKdwF!8X$80Auhltna^NndP++fj&Z*kdph#6Wu%5Rl?SkH|7*e1+_$e8#cD*pga0Zi4K>&ut=pQW7eTRY;TO0po*jsLo=kr z>+06jW2BIqWTpVHw*B=+J=-`&9OrhSqvHu!^q1&`MvUV#+n!7#A)97Ao)E}Qu)FMy zMlf@D`jjS`{F}+{!g4eHv)-CU=b6XbAqO8V3rT%%AP0coV*Lg^F@SSsYL%ttnW;*| z9E&*u!D|R<%FhXbNuW%;A*^uPVDbj@dktX}?{}J?eGlLw-WisTZ}7P~Q_(}F?H~pe8lI&{KJJ**ZZOT6w?LQh{Q;@;?7ag`|3q==_g}}Jmzfn? zUBpxf{keCv$xbcKn+p3(ZP_7R*Wp?YDe(9=7}cE@RN@mTBjW*}tB?rh)yd#Dk?Z4| zdET2UmRNKB{`l(mkY)q#NW!CN>c58&BPNk>VSZ=~N$anGB5+djOZATcNuyO9!EuHM zj@H95I=l~}#rbo#g;=GjB3v)35M>y zMg~kR=etqe7g=J&oTk@g5fVTAD?*lCgU`t~2Y21yd_Wk{-KYIogG=MMJVeu<9AsV} z9SmxnM!nYAazjI=c_WI$;TSVznXdGGKQ=RKuwL$K1-wv@8sCg1R-F4V?YGv?%@h-l zBVacE3KX6R+L^KOINVTrIzCwAEqOq$%JL%Ia(+t*hF5t7Zv7mKPoI4}b8K&7!T;gi zD?inBg)RKPPn^~ECHeq0yPwLh+OV8+%?$L6<20V}*<;iT3AOV93jE}Q5#hj>`WdV> zYIw_Bck{{K-IUAfNO;2Ls&la8bG#-GSaiy>B}aob7?I@gzEw$?`+!>?yv=2wsyUHw zF>!G7utQd17}Ws;VYc2^z8+i2Doff{cI zx8fL~(*&9Qe5|rvbw_W3;23CI?jjTTlJJDl)w z0t9%AbDUra{*&E^c5u7<&1D0D@k4&H({LP&FZhQ1kd%1qYNdDCR_CS^1dP(XOG=G+ zf8?*f63zx+E>y)-Z@rOb!ikJ!>|bK@X+M6-#u4BH^mbqFV1(F$VBz| z^BEsgmP|R3Ij464C4i^WhAz$KCe?n!9BND&_0~ z!LX<+9!|w%?bmrDXE=Wu+EvMT9@x?X>_E#Cvm!QN+MDkj>dc&Zp1Q5W@OKdoR>~#K zS16Lp+};h&Pb>d_Pan`Wd*%`|_lbEkpGfkZjG6h8%)8!>y#(pM;u0p|Y|CZ$Lea73kTI})c6p;= zq(yZ>4I9E{WZ+?Y%ek>sxoK>~oaGIRi1ivz^;ijAsZi2g;L*8B)a zIryF1Y6!56Wpnl6se+qw@Q6b8+UT{pe7$?`VgA zbnkA<7Qh+!xf0-K+F-x7buo`>tm{rChuCL)NC-=Qxa=iyVqIEbd4bAk&=yD~mt5~O z3Cq3gil(BL@D%7le+KS55>co(&pgQh(a zh(moh;&*kRY|@-gqYFkQ(RSoto=h2|0ib@VIE2tXy{xfS%w1QK&N z2uF&SCf?pk_F0F1RsO^mFPEJoFG!_aR=oWXv3C>rZj2b_b84n2 z-&d8Syqr^`7X=qNe#dC?(N>fu|AsQJy!HFHUC*WHV6~>Sl}FgTq>y4UchHH&=0N;i)lNidWX^?VpvSJi$ zsex7#bBzd((VU45&k7-RR8ytCNcnebu{DOoZoOsDWas+p0o1zAPh*D#Yh~nCIgmE> z`$;#WKw;eER(CH2Fna?1^dpW4KW01UfQQMSGuLO8##D!QZ+3tID`0$>1@NtC-A$2j z;5X;O^G}dXVJ7OlRWnP$y{j^GR0a6l!@lcQQc-YgA}xl6rru%3azo@96sI|*&zigs z>41>M_>vp9ixH~dK8gb+F#P=R(ymTU^Nx0zHzvl-OjGnF)+xaXPV33q_x9Ke9Ld%mY<^J7+vlBN$b0QkjUxki~%q8&4kiuz{b_TQ*y~Z=a%vkE8Bk3A2TULlm!;C z1o=`Q7p7pxnmD(SVGyLSW{zul<3}gt`^q-TgnsbbEY(&NdG%;>P_uFu`Z>2QD{A~w z{vk0(P&-H+my{K#(5|-r5H|3kMBkb_adrluGH>K~0tJJkPR7MKL?vKShqm0Im;sGE z?^gxKj`YMAfkl5sq+%b9fsq@JeSYjsI?b4vSl$=chOYw1QI*b;ejR$FmP3?cIrX30 zfCqto?kN$M6$cqXB0sN?C|+;qA*IYPil*O$P&0l^%yXNgZQ9kuI zcJIaJTl}1VU;)fobkpcHu^o)@X!#9pl~mi2Sx4mFcUckLJtCn@E&m2{*tb7far$Ww z+wkn??x5-d4n+8TPDxvDOZh6=7N-fTtNT@N{34sz*HvfXb8E)HQPF14HV++q%MAgI zFDCk6gFpR;nY}q_imrdy>?2cnJ;|k!sQOf09Iaz7LPzj zmKvCOYK&a955qYNdrFAiM2}WDs}P?@!A56a%%?w^(i5oqJ|SX_8wYq3@LqDp*PxW` zjOaV%*~;U6aLy92{WDN9Ct-m$VIGgh3PQ%<&qt41Rg}v|wW!0sFpOfc3L7U;C{z0= zBWdyH!~bo}!5nRn$#I?CJe6=dh$FT5s!l#)jxQ=?;wewf#x5O))7jD4a$3PqR6`vo z#20|>D)gN))Orb8Oxg{$v%yt7Y;=O6H}4yQT#7S91`lb<32RsXSY#HlBYc>?r6c7$x!Xlj!@HrT#1_Jxh;J9kXTWo~-!MZqkRy?NZtmMvC9g;vE_+*F-1w<0q&)~E80)C?|I}b7b9hk9 zd%`7fUwlCsQ!iz#CeKSBQOLG4+dfW#?hm9NHTuaMLV|cEGvT zbLXca5eUQzpd^!{-^&)~1 zq(bV_7ugPGpji`qCzm^c3vSmN8VsR_L=)de1CagU)3XJVx4LYPnm$28>=>>{AwC{fc6KAUIe3gBsjgp!V(P5~RCei6oHIg{RY zfgi=c?|%^9q+)O-mYpJ{uPw;tDiE!S%QnQZq1MSiky{xAIsGTRFCY znuv|Nf?Gf_9g1#FGPC`&oHj`+vj9$cKwyRQu9*l^<=Rxs7b~_k;=i`8#u)6Q&iL@n z9@lg_`P3M3OTT7K`%KyMmXS7-r1>XM;9S#*Ekt3TDdJe2+e+`mn=->xK)&iBizfs2 zjfS;@aT$kwcn`Z5KRiz>$*m&)61mzw;_c4YNjHg~Tsvo5VOSUkLnRxauyl7^bdJJM zNQtVI+gaj1>w%FiQofp+6gm^ z#r-65!s2jlzMV-_ioGtTkkMdxHr~wlE*JPCh2rw%WXNgZoHEPv1l(db_m&|rE4h}o z+`6|&5H~HD=E(nxc|9ndwsLg>HM_ePz~cRFd!+bje~E4*!sn3DJf0t( z1Uu)r8})i!8%|1J1X+k0!$~r3MuUi(e^v(a`&On=rsN{q>EM3r_Qap1=JlYJQu>1t zA`VM2!x@oz0g~>Fz|-RjjV7T$W-XnoCBwm*pKuT1MSkl|ZP%%0mYByGpkx^7v4J{$GxPv(DClnkb@nASjpV0_fA?$7}Mcv8iQ?$ak7 zs_w)F6_0^4CL*7QM0s}*Th)^ZHELG6;z4=y?Q+`ay61!KguugROG(|HhhmXYk7m6Q zp&>%PA9@26%|6i=6Mg{wCL~#=>TJLl4Lja=x8&))&=DTNyM0Mr4#+zUGCjN&RuZm( zUtkv;)h~xG3E{F2u@9pXcQ_1|1gB zb1yFLPK;2{^hOqxZJc1ZY~v@v>$`C^P7*r@k(boLlGDRN40mdjiN1Y#)jjGbUZE~% zq|P2UQVp6H8(Y=(#WRapwI;*63gi zH|8IvfkIQjb%qJv)e{{^g-|NXmou1Q)8t#fgl+<5F1{ld_}$@8`en-WbNxFii|ZT> z@wgt?CxhXR^H-Efwq}pWBzQQVCv#w4;Tuv_ERoY@g!gODtR@t>grM8wj^N6liIP$d zKA?kK>*@LEfc-`8%gOrl&e{mi=C}_4HMdJOg2RHp`1OE-N91#J?Hq`ZhfoJebk4azaeQ*0G;Ut9#`vJ#%GSnZXKX+MqM zK`NY_724+DT?f!LwA{WmyX#T*7WTSX7Ns(=h4_^f1tG&!vTZ-{>`(*f=6!>d$8CP z2yS}A$EcfQG*-#r3{tiHI1*G#>QUg&;eoOu<)70y7?%( z#ozKc*2D*US`{u>jDLJUW=qYNu74nniIdzaeto+r-6%Hmv@7*lb+E8&*K2)w7P|mv z(O#%g{b)#)o*L=3n#*(LQr6$>y6Bj5b@~1+?&Wja8{X*N&G{UheKTS4e3*K>%_Jr% zsYp(&-w6T$mDA`*vCQw&1wEcxVRg^QqtNcNjhsN} zWcJsh+OS<0E=vGS?3&k$`k+o@^lmh-WQ;;TIaFE9De|E6K$MYuI0D_OsLZ!drV7U5 z>rKRe=Cp^>ZsAWbrQ&Mxa|{;5R@&Ixbo24!&GFF`;OCSZvIrEoF{K7vt{N7($CeW? z6w`Y~V1%qeIEbaV>Af>tOBKzyo7 z*pI{wO~ZL^$E>NG;;V!u4vCIhVfLtsjCreWG+USiE59CMtYl^`k=PMFFPgS z1&bziZ6gzk)ROsm#$vT$y~U~ zb!LA|kjD_^;!H?ZW;v^Asr$Kl|3)sbLAv;LMC>9-yRQrAtt72x`%GyX1c=HNIspIJ*>tfs1Tx2#I7; zbc<3-p7TOB$+@yu7dL)Xu|0`Q|J!*PCOsic@o$jugJG?vGS(-VxPex@Ui~1(aoX_T zgU0yk2QPyXka_5$il;)=Y|DoqmU`gb5b&=%Hw)lnpqnx2R?>V(v+S(SB zl_7R-u@I5}wW-l$#EX*DWlsJ#npo2v_vg=-49K-n4{XT%x0?5VrWn75rWkxE%!(oP z2#sli31WfiPnTvg5PtjsE)7LA_)h{7JiX~7C8g43M+BZqGIfJ|4qpY$l;_Y&W22*~ zz_c3=euQ^b`SukHt1t{3%j?tU(09fTTFnoMPnqh@h=sjAj1K)<^d&?S#dqE0+K+0>WGz0-ol9{rpT zp)mHsLH$)S2Wt}bDZowe-xit>CqV>-W7+I+n%jl=Wc2dp_?!L+c`tJ|2A<2}bv#iJ zlu3%P1ATv9v`SW*LF(N;;>V$C6H!oGu{Ymb*I_DLaov8q-G2Fd!=)RA>XD+wkMb9r z)5h=by0^5bBHfW&-x*k?oGqRLR|G|BaiJdgN}NCfg8U~|!mnIW1U7=W`W&f8*{K700z&bBgqhm1UwU zXi7gSq>_5r;lr2d~;v;ekwn-(k~2 z!Fsc zt#;+Wz<_ipUpOi2hrh@W_GsI!QdYY&YmD8!`OF27-9h%FdV5r4XS$X}`G6i&*%HT9 zmxeScYt|SaQ9dqS$LS3KShkTDfJJsENDk+epxc{krYr?4jU zv9wx@TvS{NW)_N|kggzq9=-G6g|^&v^=#hElCLqjeY$D?)nZlg+25^NbGSN{UTBZVR`Y?l zP$>Iw#W5gk0g5=wY`yMrLcbmRC`Ea!Tf49B_vh5RQwpS*8K_Km3OA-o68A(FbJQd5 z?n>`BJCsU?w~P?xv)@q1_k95suiJ`C_7&UyOX`SzuW4HuxOb0t%`;oj$E(rBOMYLo zS(fV{AXSp!{(emr)jgyp9<~i5&bJ1Ss5uwa7FSPfpbuO67Tmg|O8{Vt!12Gm0BD%J zw)7Ff#7`a{Iv28^_k$~KCspv#ilLho*ZIKDVgYA_-^RiL9#(hE83WtFvX4@zPFKS? z_P!TBu=4G(EU1Lt(GWq?5LhW0`LN|@>G1THuJe4cjHL^`ntyb)B+=V=rZyz>0$oY% zJ+PbE?6@3_X~3=r+S~~`z((?Y(93EQh6$28{tm*e9PaLES3ggetOM}U+krylup{c7- zsHpI`?-`y3uRhLj779O?tHgQTu9xj;jwxh97vpc=G;GT&9MD&v2n8O9PgW)|m1~9u zG57zDXl(6ofBacc_YNd_g;*5SU-J7U;`eNw+LUr;$*w+Auiqos;dYD{C?4)jz~N$B ziQL}mi0rv;Vk3p~d(JMLb2l;hMNO+xw0MgHUoOds(cLP(n9b7&^5tPC4Z&6tA+mlb zV@mc;hPy$?jjH%S^Bs4lIeVfl!NB9p-(S4tty7}jyMNktksqJ}&Ux{qg#mVlDxOmN zZvOqNr>ll|i#RhuaB$L^AVA<15!E3|5u8TE9${^HzJO~Jb9b`+lxfh+Yii@2hJ}Me z;{BnZV}B9DV6u|%J`$NNjVVm;nO{45nRp9R`1r>t=*5WSb)Zk7o|@Blz(&c!uSwL@ zcA=NTeb9jtfU_06rjtC^Ivo|+ZuKR(3wx|Sdm^W~w5qp!{!K2$<&v8^(+wqg!vmM% zMUm2DL4dJ~>LW3KAM>$92Y{=3LQl$`$?}o>`}bQ%OIK@at{DlyS{^RGeY(UJGcMpv zNMrsgcrgPw<|R1OWiKoLR$P0(W7*Z2%OF%uFnl2f%RcT%N;=h!M0#+nwYATio^e@Z zE-IWY!WwG;+cEN+A!g&D0K0qqK>t$H1n&B8Q-HV2hy1CyLC2zj*%BTat zR?lLGCXY=_BN$QMTzj2mvEuTMDabch9Xp*Vt#`Uv43e^m`K+TzqUghF^eqH7=QARi z^wAfV;+ohGc`BuzXzEWm8Vv~j!vepvOmMDsc5;t`t*{&M#C-l@UY=jK>br?T8Gal)+eOxL!0SA4V9TS?(27uNW6v! zVk2j!9zFrF)W*agUY;3&zjqJc)z2%=blF_}B7ukcqC2lpfgX6QY5lx@eHH~a{(&$j zr`qs!kAJkW`)hQnasp_MM+_&|#-H*Ve0%F~>-^kM4zrd4Cf#WF;r_Rk;~pT;kBq3s zuU!8QM=eY!Hs;qOs7LI3Cq~0U2%0xtkwM*+N5j|=9yM>-^2a>kJl}Og9z0#UuH=@$ zx5T8=_(4ri>@Om(m}Y(epSdxx>E?)Biauv>j7VoT%CO}(zSy>m^*XKP7bkc0XdnXg z1}QjpKhk?_%xUFyN7GwFWTb{L`A-qaF;iQ3p-ibMZnA2J1K0H9*lyxkFq?SNqq$|O4lV-+aplB_7R}y zOXc5Dmx;N(=z0>?3;TqXH(sSQJD(Z#j$B{WS*~`S7`=O^8p4Bt+<-SVL=@u1Rd2+h&D$jfxo$b@C)c_`= z$GIpy*a3eF$5QGOiOqS?`pulKJ>u%L#W;B1@F-SWL5)e1(R@D=kL=xs`H{shfsn?h z$G3H{7azx1_ZOxzROLIE#>;>ixT!0^pLUxFNCA2c-gx1?r;L`Ybro-{gKwr%#Mfg4 z)@hAJx!C8}&uCQgy+P`aR<#XQ2fo)e{5cjZtH(|25*p%t7MSYFi#^)irj_ z-{LrXdJnrJ5TVmlnV};<0o6{eDW7UD>!J`PX>>c=PgGhZDOB~Q=N5GC;esp@rE>*)@mXmyn(9!D6t~{^pY3Y)|8|fvMkkV>% zh=76exceyZ-Wn744=cx~Wa~Zhv*iQt8#zSmvWB4y`hUKC5_^(hMW$gs{<@*zQ2zXu z<(=B@M>ML6YtU15vxo2UjmS5cpw3TmP~vSfjWU4$7fGb_&YC z6H)A4B=Pae#)J*wdye#(bWYy(#u@n(hobpX%O{u(oag#^tN7&Lu_Om*i%|AP!EBd5{swVh;X$4*4>j}V-yVGX#bp{3i$4j3~ zgw~Lce#&X&Q-+zN8Nct_&8cx)*@lEx!HC*p?S;%&Uw@PDd2X5A34+yHYO&?5MR_W zpN_}1Nz!h~c^2mZMBd@rgXf|3EA0?bz{R|vRtYFX-N6*K*R>IZU`R`E zi&!qGj?*f>1-R+Ehh^dymXLgFIAu$)=*pVvJX&hB=3}^Bd4FJF^rTMxO~CV-$NzJO z*x_zyZ<(Y`YV1Zz^l~VwV3p%9;LM|A`R9&>P_p|Gdl0xa zelEab#%*-pa!S?Zxr6vIvCS^CXpyVg@|U`{_}CDS`}?4tX>x#urhw;0O<;0yRB8J; zv4C0Yn%46wd6q0)pV2K%)7hZ>^Q{%hxyzS|O{e*Ks0ScG5$3uMP=JlDHcrN@9ZWc8q<$i)K>2ifu ze_^uzOLhp}utUs@*){0?g)()S#cDrNWLT0!#Nx|c9O^wf;mP~LRfWeFbiF|o;f!}) z7Vj4hI&2(c&uG(KRSvxQ#qf{3%`AtHApO1O0?ykpBD}XoOR~md0yFkp;rumvn?}tT=`>QQ* zLZyg>q@28*$w@!OJnY>~C-82paf`k7L2Fg8`tTNX<&goni*in)Dt%s(P&mpA$ujer zF74o2(3uM1`+P!y8OD=Xdl?Y3;?b+nP|w|jbsW}xVJF*^5XajNJ*d!;I8$|4HIno9>)ULCIRcA+S6vjs=3~ z)h(!RpW=dax6cY@uoVirk|w7k_s5c>*6;6)v#j%Pmgh$0yBv|0vb*;-#iR0wZJrx* zpy!jjq;XY|Pi%159!}0u(Q3nDs!>Y~3Oq7lYyPlMF1!ZtI*jXz}XnmP|N+XS*~T5i{m$C zpn&_$sz6vWzRPN6^d%+Lt0YcWSHv2%!v1U1=VOrNNyQ0s=&PD9D^+ z?QuK0w`&JG3*0-hNZK*nkn6(4^5z+AC;)UiWY!*M`uvhV&pGpH&avmq%kXi|)mLU~ z)J|9y?%o}ZH;q#QP(jlI#D{fTbJU^r{%oF5^Xx@Dj9&IWPk zkG26u8T(cQ;cf!3x^qC~GmB?LoQ@3f=3$<@bA{OBUnIoY=JU-O^|lAXm#rc=3iHYp zVfS4n1{+7r@;#5LsOCO*pRt#t2JY}0`J70s6_$Fvk1JB3H)Mn}@!5BK(Av;bo8l7d zm+q2HkjU({=jW-*;{^v_vNf20GZatq-v1h|2jZc2p5vvv=|!p_rL)HqV(h0B@&%=U zAI-j;)>%9Y(}jV(PSh~~B8J}CDEB1Ykyu_ntTQMXmsI|UT# zBnscHYd5Kw>YY}4WWOWn&9O(wbk3uJ1IpL;>G^pF*BAQ=n|E|_qIdD{ku&5&x*dTRmtF`(h-#w+pK8^G(((YUX#Z~O(=!vVby=x;%uOaiDt9Zt346E}!$4ZhRVSG8sqcA2EUof5UdoQ=NxBwz0Ebv6_@Y#1Hw zor7R$&@4!Wa^GI&^$iB!eO6jnjo8FIWV8Z?^^f5%=Ym+5&3#`QUuUGseUFNxxSm|j z#rN5?2{T8#YssdgnuvF!kH0UXujfMdRw=wbjnBH3FFb$3%&Gq3p~PLh>-#hKDZ1gV z#1vG8L5_hbBlu)3VLKDHd0$$)nvs%!mh-DD&pHPiJec%@7aamqh%yjuvV-fed;j%Jjk+U4Zn$g1iug3>d+d-75tDcT8Mu2Tx$R> zpvyh$$gBPMz=%R@E5PO@>fqg%^mcn79X?&y-`8K_^>&qWlU_L43aA^}UbML3v6ebO zGtJcFW@#aMF7SN4(s~}*mW40ogQ}OOJN*~Hh{^mEIy|HowVdz9(b9-o_1pQ_85ws_ zZ{+%&Br;vZ-%1!bBQo~e=T4ZuQBqs9pm{VmWkbr0VRj2S*{ zh|SoQ%w7w|sCGC9NJWZ~Zn)dQij(5ZG*F*y_bqSX+JOm@z^rK{zLi#lr@H|>7I!iu z*px5Fbejf&;YYKTF2iX}V0T~{?c~)D;}b;;(NHjN&+9VTP}N;;_bDJrQAgg|7dve< zrX<=Y<^BvLNLwxH0Xl~ZO{!>K?LkA*@}wFQNMw$DeCEj|B}(vuE$FGe{; zJx$Ry$GzX?XSsBY9#611>Sr}iK^R`|Usj)JL)@^f6x?Y1!vNGQ7Om6H zSspg9&7D6Y$Fan{V`>{nIRbh0_Vl>n1cEt{74CQ??eea9ZM(SD;D`~Hg~t9aqTUVd z^R&9Z$&+{haHwLs2LkeOR1Tf`cQL=}F8jmK4qqzrd#_HNU;Bvmo^Ew1LFhi5rY&6QrVrEWENt?kj39EUr^;bjU+r-0o5VWv#`Z6 zFpi(I>zupYkSZPPA81p9_`kgad^3BV>Rez?RP(2kZxRSuxcO?IBIG#va)^FjsN*u zMOT*y^mt)%cQ}cKi!1j{JYwhUECR9*B#ZVBvNWS|cW4(VB0(b6X+)zq*(JM|ICVO*G4A&I@7p0EF0`mC-NBTimk zUICiOq3{|jMtRIfX#y#RL|#OOZM7_>jKnEg28)&(i@m;I3W z56#xN?Ai6Z6#4Jho4Y%TFT5E~invaLEx4MAx-PQA`(v+xpz8KyU_6RnPL?qOC3h}1 z+c)$5+4x;sis^s4il2Ppy85rq2V%xd02Nu4ldYAG=JToOkZzrSYq`j7(Xk&;Qw7(X z4xp|_UoV=GSU?4NG8E&CqYg3vUO)A#p^(}yef52T=$;ASk#>WE?T^bOyv@0U!GY{pUhmY?~Z% z5A3@lktu~>O>SnQK#R9~UA7k&qGZ7Vz}3SSO}hOxEw?)Ne&Mpl&o^1Q`a*r0Cz1d4eOemC`kvzTg zR%eE{8*CKE^F&kldqUxb%Bd`T}NKQv-> zS6euSO^E&HwDgY#q=ot5d^il4tjb{alTNMmVXgYoa_%r^|MqC~BmekprAsEVOqW`P1Z;sCF?XnCiww+XL8x`BOt%~i6 zor-PSw(X>1+g3&MR(-$e>91F>o|*g;th?^};AZc0&U5bG-_xzIkRM$Ubn;tnqYY>< zUtx{#Ss2`vxg%Hj?sl?WLX%&}|A5SZhP2pn;xvP^JHci8E$-5TXEcnb++O{YcgpRA z;3aNi%;8e7PjmNR90bIU+LqY_A{bfF z-VvGA+Wr#gD6@j%Qh$KftSx?J3BUg90{r`E^RS-P z=xUo*tO0V{06p*mfajnoz^QTf@-n)+yBqb7)#ETc1He=A@nTKNIS6r5Qc@C{EjMNCNy=2uVAty$!XEzfIHwZ(V`F4ABBy4x|*Y z)w=ZQLnp8O*^cnT^#?t$k@wFN8qy?0$1i_ZOV-CsP)ADQ={G}O_2+w{Sce=$27((4 zQ)DoqiO@U4?}ZRtz;**H74r&z9_L z^r6?7i~;Ytg?E8pXKCiiueJARx4;S6kYs@6jx5+=uKALrd@Kl@f(ukM9;{rCVaMQy z8)ktpkft}c*oK39Tz?s*zMdj_65GZN3l;e{6Nn-?fMI(S(ykk_Uun<#LgU0b{F}-r zJJ_-4-q8SH8<7pu&Nf%V`g3>DG35knu$0Lk%M2ar<5qMvrCuL*+{Cl5bGIF+1SfKT z*xyDx=WY`biiV=>L*0Yxg5WB`|G9yt0}3d1j${4y$%%q1eEK4UZ9u@}>n$Y(!r*Qp z5OyP}MuFK1MR`L$7VUGOFbW|1LE@(+x3a}<8pF24qhlHL8zfKBFOS&uCmJiiDDhzC z&8-~>a>vs)Uq~aWn*;cQR}Pi7?Cju38!J<&5_5d_T<(~bbt`@hOg)QFm>e&Ti83SKia#(b6lH|vr@!s zK++Ds+8%k_0->VhUT~pY6#CW2y+t}XL{OL5pV~EpBO>92b+>lqiigvN|=tSdZKo1)*pI1y=w* z7+RxG^)ZzUv4tGcWv)U)xXZ9gmXPI;jUsHOIo>h2CM{ZF;&Fi1?9h^*DLo-IYyA6x zsvuE56yr$^hFNS^4r(cRMw>`6@pXGek={ zeKO*Mj+o1j<@_k#HC%(O*} z2FWCSMNi%T+gHT=B4B9I2sC>7Z`)yt3gU`kO!T_7TPT~DDM^2=+!Lxj z1>y;9Ouki1ikdUG^}@+IC|j-N?%6gQJhc#jP(SVNKBOY#ZpMxYof3xl6-0_4MUqJB zNl8;i$T6Y3Ws$$=N^YTigy*}?tI}$mNb!Y)4EZ3R&pM)PaY^#ZbjXY0t3}B{t8sEW z(j0G+egue{VOUj>u^Cbj8j_oO_~>MLFY0R6^UQBmW_sr6U68p00PRNG3xo4$e{v;- zJyfIIh`&pThsGk#^9V);i#q>uVKc?kJlm-39cYFhE}NfOu%s$i&Y1GHUTwL$7Q%I; zby4Zh!E22N&re6naKVLetpbk(x8uq%Pm?q;K}#bAp%)5p6p~i$Sg)fjEfIaV8yKFB zxQ{fH!~=dl8>ghQH-x$!#7o>QvsCs(YyTMG+wGC+y_}iB)_uuWhl0N|lslCDD7z+S zUsLx_YnXGK$PRkoaKs$smit~P5}%Coq{9b>>wD^gq>Xt_X3T%f`a^gNB$jApIu zLbwXOvpP>qTwb)SYyOmdG`Lb@SW{8fAyp{@mXmXQ_u{roDP>Jb29P1iK!yq}BlP7D z`vHhld0bNC0%Ikk`<{87(ybj!bBdOi;aE&d&bLjuaNwulN+7tS^gQlo$Bivi)Pot% zhTz_uoqO|;zMr$h2v(w8L4z({>){kGZiu^Q@R~Ym$%arxD%xK!$96(=Mf+pPC#lp0 zHRorG6Z+nGZXd5m$k_u`D~YccfbO4#n+f~Qt|JoAI@b&g_IgzKWun#!S-n}~T?WEB zo$LGJubUX3@$F?}Hf03La|NvA`*U#>Tmh_J%svqMnKWhI2N1i_C!{M1&U{src&Ph{ zcpROVQj>yat-`u}8FG@KU0I<2$RH$(br7w;9`(?^f9f!X$3=s#q@&LC8+kikLehXR z$Y!vm0_nMRDFitJO0v9UG5wmi_qFm^X7h`PJIZ#pgrXwvi;01o25rg%RpKJuItXpl zmeqlL^)ytJmKmebf+PjC>&}&!%~C<;8bAA zdGB)y+;&BwW7&2>2IxtQ^9{>`Sfs&8M z8BHupG_)=x3eG_v07%Q3~dJs6^m- z1<&n#xLrw(EAt-CWk9xzFn3US(pVm@b*f87nt$(PBr8vn{B)b6EKM#{!<<>{_i+-^ z>7XKJ{aeUB+-)89izNQOH|mjz(Sn(FR>Gp9p$l1kFCs}*^p};_QCI&dbF#0i5asO< zgtNH|1xN8s>;!}QL-b?e&7+w)&%#a`8v92DirdNxu$OMnV!K!6xeybCPz_ARv6iVgMW!XPrka~ zSvyb&R!`F$*tots=7)$NpPL1&J+k2dRwl-(qtcOD3O@c~1qOccyr_)~K511^m)sXn z!(qnNCAmL^!v+R$${!qe=E}*wy&XD=P=7N!fKW@xdb@+gK;eB|@J=pTylPwUG_$XM zj8M662t2_VX(aTOkXSu?ICDH+6B^Cqc5N94 z!El&#z!T;nNnnlTtK*wIjA@LIHi|o=4v!aO*#T-oCs`{SOw~z3GbfgVsbeeopGP+tB+&6CL7F)%u}B`kTum^zg5w%RQtCdiIb7u2kg?j zaZ|%gE(93tJlS>IBgqwC1eFK|DHT6e%x z9Pd6x2slY?`%u*Is_uY(_LY0(2!G6s&leTn!N>)Ikww2codT4R$WX%jiIvgMm9yZ( zijDE6I+6^2#S@z`xcOGbeZjtPwYZ07#YnVrh1?E~u!3->bN=5*S9V-?qh(WZ*F=Gc zw3gMx1C&N2bHuo1@yiz+2}~J_?aO-%$OlN_vQXqhdBdtr5pMyuvlMh&B2~x|ks`j4 z2FZ2xEO?WsLJM0umW?_Uqbm`vBLUL3-Y7!vhBadv9RTVE!kxD<#mavZUwcvepBjl^hinaO_|VuMN>-X! zc*d%Sd6p{$Dy@(JLmWQ`ijHTuMl$trlFHxeOTy`4cj5e{lO$T-Y23_nD26q1Sj()M z>dA}<=UqQz1jm7XYee~hwu6&(il~AEY7GW}g2oM?3%z}C?$_z;HZF4FT-mq%<*uEl zp4!OhZfKn;Q|mT!j}SPr1`k$(1m!&7?xQLb`ErAGw2STWK4}&u1Ufid5sjU3>ymG% z@)NqCSor3qwv~9cXCm5{@HUDC3bXn!9^*nFFu|I#W|@iLxV%t^Kv;b)`RiX?&|PagMe1r+3?*FGRjXCbTixh zyk10=#i*1VtJV?YUJE%B#~~2j$!S{>?UMaf)w&@M+IOPYy2^7DMI2MiO#0cb{$ms* zzmVO$v8<`43DOD*R}k4Ilg@F==2_Ut^Z~@il!mwF=lTiJ$_aD8N^XWM{K51r)Sv0; z5!Kc7;6n4MjoSK6pfmc?;4|C zzgM-t=t2`3uK{Xf(Mp@h@rWt>g`LQJ5!rvy?pfolq(LnXG3DzZ;x4Q`plIPSbZ>l6 zl{gSIjC6_?o;Omd5QJEqTx6lVN-Z%eX&}6Yq=*QJGg)jtOzsp^5~EIVR$^} z?of~Ivq3gw(zM^ESxHruj9H`sQ?(q;)zua7=E(FpBJ;=HjaU5>4gm9y@m95LT*w1C zF5uVCZ2%K0Df3vh0X3*!nK^N4u-(!%4L7$}R8*{4vHtRfCA+vb`xfy|Y={6bZ-W_} z5z6Vgv>xnWscx90eP_hrgf& z7KNOx0MG|u-8?j}NOW~|=@4>JX*J#5UsCZ5f&Nm7)TF^0V4p%w@&6naiT^}$K)kk% zm#Pp!k@}ALt*^SMySSE9jwCC~yOpN{g0R>MZ+_5G;XD)eVUGRkWks<_DZ`_RsqX2V zD8HckHoa08a(gqTQ&VN|ywZgJym1Ow5}9w9pGV#+1Gp^*_R5LO zr_J7!ALiuEh=!@j*W2dKmBEaT(Gim{!0PS!w!)V#s3s^Dy6v11wtt6W{4}RO5L(-g zg+(~#PiTkmXvEce;PsjQ@Jlo)ByYU4=lZ_?tA)b8abm9F{)De{T;&f>&epo2bIUOe zV0MZ!urb9(Ry3#R>H14ilPWptS56YkQ4SL>^6m*m)-z>SOz=RDmz6kM9!HY#RQd#p zitQB7!%OquLBph}cCTAa@(q~7Sv~7TxA|s)VvkD+Sbqj9pO8h|Q<3WWeT;zVCyaVl`D=*Tyry)~k zXE1v$J}>{QnDs!Z*Brc_pGx)Gb0Ky_7F2J1=kzHF;_p6dr7XZRxa4&^Mm>+FaY3g! z>dzpN#F18#-bRar1RckV&5an!0*n3?=Odee2xq3w;5?;dacbFb71jth%|cCYC60Jaua zL-S`ly6fm3wPMA+npmaQBm^bZ_@c!ip#L^3a>--msn7{z_?*?oSq*S=MWHhzEPb(M z;4|Z^5(N=gKStGs0kf;+bHuK9bX2$@p))5T4roI@vMDGt#W-_Js?DQF9%|c<@?gKe z3`q5w(g#{dt4?j)v-00NVhnb5XLw;R!}$(Z7l+9bj`ZUq)WNa1h%C%mgWyKR0;#Ox zjh1+T16o3cvd1JU*V~ZcFrZVU>ltG4>J4|b7c?ed&s8-pJ66`l9*k8M@A4NAQ6BM4 zHG!XM;&@i4M#3VO0;7HtI5HAWSav%I2j#dVVZW+?N+l>7DE>~R1;M5Ja+|u<+H_Y2 za+wt_hssR5=QawefN}}DjpQEp@m|c5fW&WJrtq?oMs7O`E?84~5Mslydq*+ghBBVV zi|PE1B7mY6SSJpCSFW&F$hHNC6OgJ_oQOwKRGlPu+N{5vILmCVE+#^g^+9Y_l8}N3 zZP{jEu|{tpWmNM(N#cG{L9CvtNK`+V2Z}%?7xG>us2W;Rq*ERAc!~3g{nITm3sv~n zm^R1x46yc<20g+qPoj^u-vRySc-G?&IWkM?6%X@Ti7yyu%x6tvSqhov1g4_1xCsYE z@u_-(CY9lv=Q8rfusggqW`hC|fhj18LOwE3lKg5O?%(xIG@z#Po1}xzC$xrm#VA?B z2`&Vy4(pZ`jBR}5H%!_~pv(n7^9(3_S@wq4w|uWK5}dQ(P^D6itG zux{#g2S#ezTY7mDlVPN084&TAe!TX-FDJK0E{$1p+*e}ZGAH~pg&9*I6wU9j1TCNQ z$z49_vu^c^jb(SJ|CYGY%2{#@g@85fZNPgzsWoJEFlY|$n@|S2VN7KL(7sei5No81 zyz3KlQ1XJ~WulOUx1J@mE!M}5EMS(a!R>9HS=X_z2Ab}eAFZIXc$b(dn_v!t zsNI-}aY7iA?gWXVTl=Vjr?j)(FpgS&)e}89&Si4>zlk{p=;8WQkipqK;f@vr`pCZl z;Kw94)q{cN4gZpzZug`CPnlJrpLjfn8E(7i_|ER2d%PphDN-DgR zDHxexF8~RnY}RYQqhzOqDt~=Pz*vw0p9{^?9atl^UA(S2*E`ZRpF4LiMy;@|BNDrr zVb`b1+~|BcTD~6SQBsnM#mh(w$z0J+1tT^wb_jn^_=tnx-mjb`s^FVQ zONi(!)heEvJA5fty9A?Co^uY)0(uQSWg@f`q(Y^aU2#&~n>7{3ki?B9YoW*i#g7}3 z-|hKIna4C-IZ1E(B#&yEkWrEYYsUpV>;dl*izOFp$cDT(B?izoB8D|s@-ywJ^75q< ztAm%?cs~@Ngi~3m?&c-d+A+LCerp0!qHSZ_$1|@}7o22r-uKUo4J$isGw

D^9bk z@=l5JL{*IOx_vE>re4NIa?;#D4h|azl0e1aCLv@BP@!=r&EMcfV8JJ-kTN-iuqSqu zCVm#sa16OZJ%mm65qQXJ64onqm#Yz~?V1*iPvh>t1>-v7Otf6AcgH`O_pqidU8h%$ zIFC5H?|7y;L-1CJ-)tTDUWbq+d8=r7E z4AqqKw9B~_rU_`))Z>7gj@rBL3PWJ27!ru=@S*0`YEPB*%BmIt$C%D!IE1f@ukYRo zl14f<;&-kseRA&Dd?5~=N*y^f(mK0fnea;Y4aFsc_!+Td{Vev;aO2EU0Dn8@l<_K< zu3r9`WK^aBdxVv^fncf3LY*e}4W`MJ{F2|Vg;GkuWlXV{N z<>N+A2_zfWv^Df=`?jBEve$FP=Hdu~{4-N85iN&tXF1GL+bt&f`%W_=)my?e?5BSV z2$Of@+=LmIOYJw8j7}5hUM89hlngJoMiB4%Vb09yd`y#LK`nJwfdWKM9EbbKbL$IJ zvKz3hP`HUj3Dci>7xg^2UGY=*N|AKU7bO~GFh~Gl7SrzQqVFA9?Lrr@B7CC=aY_{W z4Arv-uM}%l@!apytoT0vsLE+rVA_ zwmTbkcjpmgIxie-o6ydTpu=zy>rXxK&?c)F3znEpuy9^J>=LWrzWsf@3>*U?Wgom( z%AzqJqDCDbNmlZE$<9h_e*MSHhK$&uNU-93LVy5OJYx~mOuY-5%$=BIOqP)YS%hI~ z7AEUb(=ztk^OW{`F@xEja51aD)zTbRis#0fe&MYm!R#{ZaqU zRRwDVUdWxbyz-(&-VMlQ^rRE(bS7N8PUe2mtAq@ig@xn#btm9ZP<2&$A^3T)r}(+i z`eR(|0wXgmK0f?6uFv?%fZFi2wXM<2F4;6%wz5WS_%U^7I2F&Jer6H;8`~nv z4_L}!)28KOH^Ohi&ZLPsMJW`j4A%JC{DZY=boo7{sXtnQ92LN$x|$t*pJnd3-dZRW z=PJxOsnPjeo#svUIWw_zX7{HpE&NfNw;7$(JwoUEDjZhrH1KyLvqQv%TZ;(XPR{ZY;j9x8LY3t9)8i4z;L2&`O6W88LD4dx&&z zj8VBl>}T&L-nwJER%R~J1sK;|oy!x3-&+&de19SY-l~&iK-)4@gX5ak(@rOYd}`tw<&i_eB*<(s0*X$95BAjUI-0bpefWra zhEtVzVUfYCjI_yM2477UlrV<+@moUjOTdj+!{cwe5-0~wl!Nros@ZEHy1ZGf2lwqXerUr@q=4-FW4_fM}Bq z*j?J;$xj_pSlFz7`@OQ{%)SYpDNH9edT*$3*I1miaL{MvoT&D>QIs*^8MPZVhg;~2FS-ddZYfb>MH|?q1bVl;l}ia9D8Hc?b)ObdloLHuX*I;2ocGQUOT)Gf&8EdnMRPOB-CY(~nRLCQ@!ZN9*yJRIjQ8Tt z=)J7(>qs6rz70O)?QwF~gR#WUcWLO2Ueuf5)iiKXAYx+OJqTtP2ywqGDfj*B&j<(n zCJi9!`FU-3T>*x*VH&73s5z`NUG}U$NQp^;WrR{Sh~7b^u?e}_)pnXJ6O{Vzftn9tEbfJ(ZAZ-Q?A&r!1E{BzLX1n(mxGmHrO+=+kOwdq_E3sbQ@&&{=M5VV$K} zHmGt{p@rAO$XISKD2@>Mrery4cG@@g7J&_ILY1KU^wf4xZsO5)_+hnuwaOo2cEgcp zx_o+wv(Wu@nK^gU@PG=HCc|%S2_JBhGi`+U1Zb_3Xczcm$n1>Xep603aS_g z3P7sKDAXdiCNS_JMzeh7@XB}l;n;AwF8;dgvc)jX{T?F0CFs5fvNP1+6pom>hyIoSrn;_Cy`IykE0FB$^0A*YNTR2?w9;_=peC-(+EwrBD+h&44kOgD5g2C`}dt8SEJLo%paWH`(oF-vJtq4nwUfV>)fZ~=TM(xT>?ymhsz8u9;308)u_bwUN5cMVX z>hAaiP;_7G_4IJr%NuaI;gFlgPeEYJv82DTrkebotMN!4G8IgZW_EQVM%mmQ(cVX} z4Ih!H=^Pik@bvP4y8ojO5YLwKO}4LI?)PSGv@}w^NXGq`ph!J1ls@6iI&QwzAI4kX z^2CVN%*b{4uApXR|Jdzj{dGFv`_uI`7riFwSlGal8_{oM4Zn!Q+!tuRn2sKy?+A9; zS0W#cGrdVO8$8F?`h_D-J744wcw3D_t*hwt!o5QDR`K_%SP9IMQ%y;3XnoQpn9yI% z@Y%N}L38a}>U2nuAaQY`0VgXtQ z`wGZ)cY29Hj;xmtJLZ=r`QHSri9`%(LN3>6~+8j)S){B1d(kxWburIgaCKX_xW-+%^XeTtbJ-1v}6>x3BsTWAE5ZRl4D`GxZ*5mhQY_~eL?`nB3TcVGC>_9xS~q*+iB zf1SFHE{}z`V;CQ2%v$NwP7hRxcJaDKW(V(((J#d(dnB!5}i58u?QRFx>6 zZ)j@LjeV@Gu8xsOXER7+A7=&ZzdQ`977^>s4a=23ox3k|tpEXLa>bW*+x@B{cz;!l;8em`?xFZ%-+|sb7L=nv zOskYAnf8`Jq#OY?)G;Jk8J|pBx^-U>Kr6NLNm(GKdsF|SY99S9g)c#DoH|s!o1bk4 z$5$}Is<5V$!_zQeGdJS&exUBXBe<~i-DRIaA!%Dj`c{W%Q8i+v7s^s+!U5LY*+ucH zjQr--Csr+p=Cvq`H1jkUl*tGrb`YH%|qQs>-GNR%hx%pCU}65BndKL3frBFDZrhGayFCXk3p@MPG9mc( z_|;q8LJOiG4KXUT1Rh~S_3!;kmkem(BdqHCxa0n(dw2=^ p?~8r^(V6^zZzKNq$qk@AeIhKCndr#FJ^%r}Bt&F|s|5A^{}-B^z0Cjs literal 0 HcmV?d00001 diff --git a/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png b/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png new file mode 100644 index 0000000000000000000000000000000000000000..61dd9e1d7a1b3646116e89bffd25bb158ad12453 GIT binary patch literal 160720 zcmYgX1z23W5{3#CFJ9c;rMSC8aks_YU5XcXcQ5Yl?oixa7I$ZXxA)1tFW=d3cXM*) z%p{Y^Wadw(f}A)4EH*3z1O$Slgoq*p#3u|0h>xaUpujajFRKFJuTPFblFDDe#p{dF zF9--i2uTq^Ww(sebysbbyZ7#^#g^o;&-8ZNwXwOBJ6X-&n^H-{ZCDy+WM=1T$Mu%! z$7sdJMiWVf)Fx(VXUAF9n$giQbA~sxw;YC^UVFZxeND){bLYe7YhUvme94&N0y<6t zaYq&x<)gyG2R!@5J_&yPlv|D_$5;mErm5dY&yk_Cj-0q2fbUsyMYT23`PJ&P=exgk z=sbGirR{xAa_sdZyR~$oLU;4q9~lkM6a`{mX}SuIqNv-q*;j*z7OBwoXMrj`6g)V8 z!Y}{3)@VeXq5t{&rMFMoiT3ZiU;OQ+M27y?_OI%P@zU0hzY!NqNc>6`VI(4Z`FXLk zBRJOT;_N1*1TBZVnZ%$E6(4OE^#57mhA?2a3dq?YR@lh z#VsV`7M5Z+$$b4w&VOH}3%+@P9u}5Zm+4}dC~oipZ1}wfa9Ud1BrgY=g{FoDzq6k!D^8fB46dgn>+w z5(2qB>_2ejA#)t-yw z4A9corTF*xBe}GOqTWS@e+EM3OmDhoD=TrlzfS8Law8nK5*tJ)o2JXN>z3MkBkrA9 zpk!|Ob#pnbiRMsNp=-YZe)uC!@~JWebA^?(2laF6rhk1hl0?z_Jx^O- zL!=Z}$}RG@?1Gd{{!u~bG^)z3wEH{m_p}vVuNbmkJQ662T1^M1If4a`Pb#ivuKQ?M zlKB-{SG*o*Mpzx`IN}sCghfB{j}c}6(Sy+#a|5l|y<{uUfD^0f^ydR+v%g@!% zrOa7p46Y0uM2g1xo}`9kGNa0L+6;e`*zx<~KimNA!y-tjIlgIV z+)V}k!&Kn4hZ%h&&A17d&pj3&5z*e#>dla4mAy^(&ycs{&T<7in{J3Vx3ljKr)O6% zFuA*?*}07A7kqX9OfKcRQGS|aC60zW>7;X5ppRUlR=IBE!$|x$T)bsoS9*H{Y-ROd z=;!#2oRxwfU8XX_d!~^u;wj8)Je&)I)kQuR#{Nz0a#INg4-RV5=bahVv|`r_k?;ft ziL-Y(J$3k@S>yth;>%hCT%FWFr$(K`-Bro(Pnr#08^_XUq!*Kk-f~6cW=qTs3OQxX zU!uwa*f4+3op)K){ppDAyU)DS1c6Sq zioDf)7A4rz=;on#s)iLnn%%j9vnUj=UTM33_x|#E^GNU73r;0*fc|eS1wE_@4+*_x z+_@VrFk)+9KFghjwFw2aUW~P`vtMwJc@Kz30*35x}mZs>4XtWouYXTBIe zs!1o~f!pEJ&oN$)geO^;xJ>AVj~{O;ci8jX0nl-Jpr{V$-Xq>Twwb%lN2_Tzq21Y$ zA4|I`@5sTC1X9)M=)>k2OP6Hn?=5mNhS*Tyu%1)TJj}OL!S&aK@6TOC$6w!H47kPn z@+1aQS1MjuOq|p#Rxp}+I7QC%#zqN{9I5Exf;w;@JF-phe{v0w{{(A#i#SqRl}5m3 zED8EdjY6f{KC7I~W86DlBq0}50It=ar|)@vyM0(oqo^m`z<;#;E&sd&09ln8!H*`f#B zVk7JDNR$XpF(ZL(?c~b7to&%XfCP`w&BaRK*nSpm$~?MhZL|9}&vfe>4}T?J%BDwC&8ImLJ*v*G;eLgfeF+77vq;xQcSuyAL$#`qNj_{U%H6o!NP=R}-}X zl%D((r);|FM*zus7rHx0%xT&58Lx>n|1*YIt3k7IqT)Y3$+9MULP*k-w(Y|jB03!M z^_2|qgWtOcGe#SP`RlB&+WO^uqN&a@2(lJK|5m#%iN_n<7!mK619gB$;&j(Tr`qX~-Z`#&yA(gJ7LMmiazuF&$a(=~8WL2_}{@o^9muC5H?cFZPq zSouuh^-E>AtDUg`D7;pl9msg_Q*Y zAV`vn=z#q#X!tiS#LrV_ft2_L3wuN61(Q0#(leYUuWrBKcGISJ8apf`<%uQ?#rvLR zzmygV=8-#}*M5FlP49XoW75$clipq2cnT=!VQ@X$k7CarCHZ9{i=F!co4q1h^&NK8 zdUdRuE#L~B_aBGg!^3P%jz#z7qS$ovR;L?Tl&g-OJOr%rxB|3U|!4n>rK2mlAd!3N)OEI2bzJCuw}%P-RzkvyMe z5G9FX*?p%ZsIKH_*z6a4bZ-LM2q^T$M%IW4p!i#2W-Nz}t4pQA=GN9FK_$Dh_ijPw zaG?X|?6^gFIOc=#1YbKxC!Ji-eJYs?!KRlt#{~nRWtT3gH*`?elDMKn$PMGsf|}6n z?`gc9>q;O@#M-mYF0{@y_C@ z^D$aX+v@`mf43tuW26u+R(-8?3qZn!{?7`loyf1KJF}&abc7l8)qxi;yf@Xwn|s^C z8z-D^v-b@Z$l-fV8sf9rm%7It@6f4f#EUuEJP03tC2PjX`Av4VIE7_4^-k-}@Gh^yXoQVp-fa9Q zl#cnSw$uIZBs$55+kPVQ;G9jLU7>8g2h8YF`T)Ie0X}DPs@@>DR1BKA`zW_L3&jId zZb~OSw>Rg{>5I0&CgTtZCW)n%$7v5Y8ZM|6;`PRf2@g@!+8fM;fr8ll>Vf5AqK`!p zc`7hdR9~LY*l`UFB_3``OO3}~RyV-vu}`|W_EhfJ+-Qm3C1#rE07K|DZYB0`iDvtM zUJ9&4XQz*Ywl*z|YWeSTb*Vk?ollv-siAVk8q;%a6wAfR^BC&Lu|ygtUm#wB7zx-L z*fF^|P$38;OTxQo@16Q?Qfnlnq^v^V_m8U)L-~LQmoFAcefQvevas&RNY=94&YA3S zM{Ku9&oz}jm9?lxF+WtiR->Zog)Zv33k80qxH+psiCUE+H~MI8#ihP&)j#wuJmnxj+=H9vi@#f6U*Q^#Ib^(LRt`dKbm%p7F(tyG* zFRA?4d+DStR22WeT)E+|LN5>EsywW(B(7km5gPFL4E;6ksHf*1H_ zWyAN9s!)AN(ycPx>h_z*8`Bw)B3oRo7c^ko_1XS_Z#uOD?y{1%H=|>xc|6^J`;lJfJfaFpXFJkfY0TZ?-3{NC6`Saq5cg>SDg zI6U9tHFegBVE<-Ms0H1Lwp^#Ju@%r_$~H1Gx84}3+2#sJ%tZJpShg>=+PG%5niL3y zP+A!OS1({=hdpffJ>v33aD7LIh>t{A^tdIo>V~Mz%q-)f|J%3<{-%5niwg3h?!bTV z@GNOCMT%Oi!t}DOZ6ND35Z=LIBc-DJm5}zGNlQ!Z@i~!`lOrf3zs(J~$q{JB?TT1d zUhcm+>*d|D0NxRTz3(|QYOmM7dG=SBe^bGO3*yvi6N?lMxrBug#KF?oW7jAl?VF8f z)zf2cZy$DYBpDm{9H1KB(*v0=7O=e1Dgg{&rhqnx;!kv)|@Kx*I9^&R6sxVP)l@%E>&1ue%3g1x@VRe0yj*6lzhAn}ZC< zNeHQUnBsJH`>@CXCVIq|z)z=&N;R_5!WD~v%+%1t>0dKuv?-hAiUx`$!!>n%Iny!w zhZ04q(!pgk=I7@HZf-F#05Sz5nTd(1zrSDE_1nLd4iugdEwQ&ZzoQqclQFxv!-<)t5Q+?=B3RI-kSg-_ z{6OPODf0S!7yjzSPT+M335P)op}*1YKAy$7+j~lCi zKU*w6w7#B6Bph7req#cW<+c;r=Hmmp8hW~4wbf|0Gr0Ri|Ap*V+)nc#0@o;ADL2|S zB>DA7z?5O^a`lB_3vl%kD0&bzZBU5D-p3d5U(w%#6}d5ByM$_as^aTwYkNmVO1A10 zYOcA_uP?qlJ)cyG0(*r`cKSnED=-nmWUwb~GG7Xvnx-&fNG>lgo4XRVYJat1gv@Lb zVE*6vO+8QQxQ}U;q${q_m#TjAS^)N?!)jg1FJqU_ZkK`Af!=*8qkPnP_*2YOPnA(#y1HWnu$Be*lMW9GKvZd3Prmn`beII4uRc|`8k``f zOV|Leg@K`Yzw!v>!3UcNmE2u^XzuThLr(g~Ir^kW3)@v8b-WYD9xCEXz1|*=v+LuD zkySU(gJWyH=HF4DR#Esi(KQT)KuLieUOfABK2fc!D8@3Jobx`FKc?}QKq^sOon|yM zHR-n)!WPMEu?CXMQ*o|B=KL3&nks^eGLxbE?f2pk@9g7djv$bY>8+cC6 z)77TvM(fpDyKNzS&r>D{m-DsIfPjy-U9W69txi2FT&^J*oQ}aQj=%%Dk^YgYY*YJV zGrrXM!eO?(z>4ieSBBY>*_K=TvbD&%0zIR}Rs_)V6qz9l8E(hP)$p)ngjLB)^gZmD zLY9vtXY53}>-CCd)&6S*#c8r}`I=9}B^nDG7r!RFyWfaT2aUOJ8b^~M6pfYX_4F^z zgs!qH!At#wpb!-ds79K1qx5;*h!h2E+ICwX7%iIgJk$dbN4H&Swlg@gLH!WDO9673 zL)o8nDI|@|50R1DZ0ZW?mVewA3q^r%@W=CC*Uu{Aj&RFNe1<30NosqsBPY{y*u1~- z-6C78Y+N{(?4&YOZ5OipP|pa^wBrLaKg%mNrKrxv-EtGOJEc|Xb%;RYK)^J}OSihz z{*M0-!frE~QFP=Qx_56#1LEKSDX@M)d`#+iFQH zyrkmujbzjl%PtgrWFr*IXCLz`(Mdu4_DL>m#GZn%J0j z-6WngcXO)U|;OoQY(8x&WpFe;6&0C$0gaV)t4rhyzEEmcR7Rog!(Zce^;_DVA$??pOFpL&QITfG@Ux;xwUVieQ;Tzvd@0Ofc5k0NA zqtrJ_)M`t`K0dhbgi;8M7HDU}2JID>J?)tAZGIK40|J>VqIiRwY5G?<1gTzbRPp1f zik3F5CsJgK+TF|8CK}({BU6@Y`EQFE<&oH*?+9XEh5{5Y@P(L}`88fg*!BsGq{zDi ztwy&SPDk8+ub=;J+pDL^nEGPapJD%qJ$2car$W0rALxqzAT&9huhwXCJQK>AI2+pG zm2h^#cMw?}+Rj_SOCRLgVI`1#B=WF)!BpEA6ww@hs`-RKK;N`G3k;|!3p9!|?k+-5 z;`2!ZxhN~H=vUF^j;oKS&^p+(jJ@a_EvNZ;Z*Pn);~}ePwa`>qj8P1ef*MkqlGY2h zFJZ>5wOVnmZSc45 zU**s*WX(i~0UqDUxoN_`TQ0;TB@KcNv|GEk(i@-a$NXuTsV&XGz(9pM6IuL=ufwU9 zSFGhnQsDyf;4$ladws!THT#1%R(Z&k3$(mo;pvvqy#4&P(VFCXpbI$Q-Zi&)-WmK4s3V${LZWoSiXurK#%UMQQqwN^dnBye^9GF*9d zU<$l`$(CGF-&uZjC9d#n-NS#y)aY`eS+|{XUB*;@I1d4xttB(nk$=^%q5y4SsQQBF zCF?c-RwQly&3ikBw1797q=AT$6g7-dM%xk{q-1)XJlzhDl!*i4Z0YMBXo9a;Sdsz) z0zIzI$8+0Hz-;jnUc+#BR-s7Cy-2I?+fs3X;r~+>qK%D)>7ph zuuG2E<|^|I-x-MDQx*_CVaAc$ma(>lb)rRPSR7a)GTcM;lIcvfh7oE{Eoa_BO|e!d zqQ^Hk0fTQCEg>%`% zmFf8Okau#{gAZO;UZt;_nsi{swpz#`Du;r^pZm* zWi{DwusI2&KsqmrleDCbX zUPQQ+USpV^{08A{EP7y`n<@RiX@y&e6{JH!cF5ZcO?Lqbs8y=>^y_xS4UE~6v) z;$Lj)y9@Tj7xGpk4aT#N8wMCR!HYtYh#`EL!&P^{n*~56DX1fYEIkSZxfnWnqn*na z9+LfBHLG-EaY*&j^nm}*B*utts1?(-)yh}w<|& z(_hqI&&UzArH6{d;GQFWgF6N9B{*YGpAMwi@FGctOY)cFZ7&sFkqY9DLs!Fd3&irB zdnHwFEgesZRDEiKyDAHQ3KItCdIvy8{k)iT);WA;iDIg>U6QB{I^)`gI9fEXY; zpo2HkgHNta=fdttlWlHzd;H)+z2StlhTQbn1%IUfhxL`hNI}L*H|Ch{u2(zODt3q4 zRRD!~0W*rH8QrEemxMa8+h-)>nZT^M_F@{q12713;__~;#&7^uQAr6>z0->`9D~mA zkmT-{{6xR1^#Bq-NT9>xE``zH1H!8g)_ez1O-+r}YGY)HQaHi6;s93xjMLl3x zhQSR$U*>xxmT$lp=%c2Xc_Os7!JyuJ$I6a+r+#Yjb*%#-O&Xd5E$K_8>^H`z&(F{+ zhAoW&@|~cd>LsIEJJK9)SL}3oM?%sJ6E!O>^%`5PoS}! zlV*R}I&OH9Xd=Qrw&y9UUp>zKH|Pf|a^guL?$r~kj8~=-z;)%9w8`uBaGDz5BNDMk z5p=z16{}i)+#?&FDS4bJ1;C!TjL%$tPK4(o6k~jp%;0ok`=cwhd0dnS?+}Z-2unuc zH9oLiqQXB>Qv&1(V{22tQ_@5}%Y284;q?TEnHSGQS^vo9nLv?^FF;c9DJ7J2&tSE56LB6z^NVo!PUF zoMQ{`RgbLyhXwFGr)YfCdSX6#&$lM_cSF+%-vo9kYTwZ!clK@K?3f`E-m8smoKLKW%Qmu zh}Yr3tjaOmoQb%;QRnJX-$^upSC9c8`bqE>794GY#0U@C^nLHx@@&wIlq>!yP^g$Y zZ*lQhK5Z7J_nR~5w*=0Lyl494WUBT`OT>4ax1zU*%0md{3HRrCm``Ppl73#hm`N3F zGMV-aER)=R>zj0dGXiJ#!sM`&vBf|4UWrH6tluUUmMF_%jvsg&#ms&Tz71SYvDcQF zlLSL!bF>}dxD>ey6{V5>b^FDG^angbajZeq?kxRrmMz zU#bB>Pft(Zp0DHle0_Ove7ZIsj3$Wg(bu2O6HSpJUt3$Vp_7;-)TtseQ|3oWdL7iW zw?5i6*t)g#%{^rELo|TnOg8wi+mx#$93y_&u1s4GVdMSe>HJ)diItz+L_C1;k<2L;DL1>aRER2hAbG>?7m zKlF$usa-o&C>vNkJCQA>@ei#k9p}hRb&rbn$f7;MKmSAuSrDP3`kj}jK2Ta0+8SV)7ic&XO}(}{OJ#<~pB2@=#!(%( z%4G~6in-jt4BB*$Vk8_&o=DS-4_ljUyps9s6BC9|y|)czl~G%6)rZ`? zu$X`j=-9ehMqwx@L4*&%%NUZ59VH-PEl8N*U@0L#w@ z!`T|Q>!Qc9KItQ!_Mloj#{$_Hi-;j>!|5N_;z3 z8VzK|Vp^1d#T}x!_)bXSgi7Gs8QpDa%4i#gu&sr0`Gn*<{T3;1FV!)L4v;SLVf)l| zn_r&M6c@9=a6L)^Ic&OcJ$)=2Sf43VCx${Jr`NZ}^QCZ`8MD$;sVmESgyP+SjU5SZ zJIop)lSfK^yBshu4?w>#kZ`?;WXX`OlHPPVCrf~XNpFq58C_CcBFEET_P1SHvm=^f zo1}WMmxG01URGcc#ZlV=?YQeFTa)=ua$q-3RgB=$`mV&mm&? zdc(e(9x&Hbrq-Qc*6q=l9!wmCYHc%4NQ&sz<(^~&-8zkI^)3w1>O4Wq0{Mb56cz}^ zb`}W+RB{D!DajfL@;r)1uhlw<@BH|~;#OX}dsz~_ych=)xmVnz_mXPQ_&GCUy5zRk z-efgh?Tn`mbWV{jrY?WhX4x9qU!9_7_=_tR4?o3!Z&+;@G+xvYVtKy$@^dDDZP$c( zmLgJnI=qW3_+p8Z)@)D0r8T0B7?qT6T~BM6B~nEK z7N&1Ih-^W+@BpuFS=(;E?Gm_S#)_Shk@4rq>Gym~hmESLs+*gezOk{&4zMk*+}_Sb zsO%5uti0xuS7VUuOVl`q~Bl1Co?$N3tJEj zFN>!`k*devIAq1HZ&*P+EvDcj!dd=0x*g9}Pq3B_l{LxX`MA5E(v^<(8A+zRboa&g z?I|RdMEv@+ZtAaa86qB6KOmZSFr1-NLP6oHprBy;<4!ow{Sp9|%juW(YU9=Ito&bF z?kHSN2TQ@)tO#1}Q(mpvHfv^IkUctJ6xoOWM?luP|DP2>F%R zz46V@gh6-dDSM<*1n_-LiwazioVzG>0S3SAUj?){VUr>0BuT zaUQtPh_m;m<5O*;ihrzJcyR$>>ykk-W~K1UrjIYpyqO`lIZ@#(-`nmB8=gOy_S(|) z70Q^lHfML$tuR@+S%S2k-R7=o+`0W7*aXB_QT zaMh$YQ(;w)tAJ1Wt4YdlkRwpy;xxBM&)j3VoKcwb}_@3jLZa&%+tOn2= zW@cm626R{US2=Hh{KIW0|5pl@*f}=!LQ&M%n1In~RC!YxN@3nu`AM$fozPt@ejlFQ zA$k3c3z%Vv-_{k=Lt-dpYWf!kLE#e>bc&P-l!;*|Tn!GZ%;HV0PUdRRbM%iMM|KtK zsV)t7YY|eyP;>O(FC7|(HY$*HG(BU#;i)mgS4p(cSYlNX&u7Z-ML6B6%5h-gm&*_kzE<^8a3e`h)N zn<5RxcZ+Zv!*b4o1ZFW`BH7yh%B4?^+41#~C=cfrAR*0=v7Y{?OB^q6GJ~QaZLocB zZ*R?h?Bx0GgwuWJ6T7WQwb#?N|4|aXj+BECEw{_*)^IFI1RnSOInD21T-%eO_D&8W zqr-&x@O?&!jZqxjTuS*W6lvVjOP6Q+5>w zUN`XQ2>!S8$t29k3Nj|9skV0-^VTxtqYjUNgn#Hs2$Eghwt!eeRcN}Fbt}(ubeh2n zC$^sUxk|qC{PyXw{E4o$eR#W&QO_?&m_o%+MI!XJX#53_;+Y#Y>$v3&B$uD;zlD4X~~>N z$s8EH;7TcC5J$SbwIu)!gjCm!b$BVR0l{O(Oos%a z;iuTx*wdAU@ak$tv1ojR?v)1160IisNF4Se;SfZKLnp3-@l;1k_afR`C>)Sg1aVf2Cn0a(q6@{(Qf)R^JLs3HNyMz6m(_s0;YBC1a zdOnuAklz8v129&{` zIgpo^*{NU<(-Rk~yyGM$%9GpG?BnXM(c{M~S zTkPmdn1H=BEVb zYOo2?`x)aF7X#N?qt!9y{Zi}Nb}E~_PxZFDSR^IC=UvUBc^`z)2J{BW#p?m=@U&Q? zG+7r~CM;c+tlgDowu|cQcsS8jLZ-(LyMpJl+lO7I%`c5q}yhi~p^|SC_C?OquN}3yZTeJv)zUeQLlX&9h0LzcT zR<*`h;v?8vTAv4TQESVA*Htv?4L4})igfB)SWMp;v=?l=lcdM89p-g`K3}gxjf#6F z69hDqA~Jl908zWy@2>*S%~5lcl$=%S@RFwtxxAFWawG&=j&k5V{MoZCqvIn#%4w#r z(Uc{XkrqFvq99h zR~V%4P=|EPa`TK`?5IgwD+)d zrp-J`3)AL`%!$ds9Dpxz_AAffQI^)=t|XoIARI%kL@V|5(yBh|H!16}aQ?}W32u$# zXh&77?k}#ZT6Z?FJdkF*c520O2^PehObC%>G{>OLQyqI1aE+l@Bf}gNnmLj{ZJjtE zs$ZXe&IirY>&|YGJ29#2T$NzBu;FDzE1c?%XXl=6LviqxBHnI~(14x}>nLAfF!i9q zqV53L)xwxZkB~Ufz|_RQ+K1s8DWWNbZL-`koT-(RV5Dg5iOV{Z={~!Gj_J%rWu8R* zRJ8|?fs+h1H`CUs?xcH1#~s-lP}l5GHV`Jd-rtPOQKtSuoyft#fd*2Y0W!ziWco`= zeTJ1uiHHG%8$Tl=BARLPj=b!qV|a%YlleJ{Vvxq;*9IXhf>Kybu>}!RaUZ?tDIiBC zA)!TKC8?M>*0{zK&|pdHYGCzjQ)zs^N%HaY^Mmv5zcuQ}Jv#7*>6{R-St-4Bg~>H) zv2iS6f+|th+f8d6(mzIbZoq4i&RL)bk6V#OB2pL=+rwbkDL|N@?8MjDJM=<*Zdhp$ ztlOfb5MqY8u^m$4f}s(o!+zKpe{_O(mTs>bO6q=oD>&!tEzET;an))|aWSK#VfcJG z)6U82Fn2Q~KFg`OW_aF=MhVF*5oLy_%zD(6vaEv_E=N4HUX#LHbs-qfja)0!#vu1hY|Dx{M@fUiL8%tG!MkE7mu`BfEuUbH^^ua6A!7Br z|HsJZ=Z%(VQnGt4q&1!J^RF}%6s%PCqzAws(!^Jiu=R3Ll%xoP-dVs7eBmz|ugKX9 z>!O)WD~a0jYc+CO^){8w8yiw9&$GrL94Bn2C|Nj+>b;>AuNjIaUgor)wYWFZ?sux^ z1WosXxA>|yQaSq>^6q7g2u%E)Bk4a{X4iDjrN**Vjs!<2!m#gtTQ-H05J@_nm$v1% zHSV?V2t4O9oR{#%%xSLiu7%l@?gh$O9te5CGFM9cBqH*2s=(3wtnS%hJXcnMWoHZ> z&ac~xH9Mjw_x?MIEs%MfmR5@5VDg6DXASJ;ncJ_W9XwR5dJTW|U^9^$8GYwPw8L$#;; zoLM9xy^Q_3`>&zy(J<9}`s1A=JvaI0OTTGx0Ky8pD+M5rU(&+IXk5Od+oQR@62F(} zE;wbHD!AyP+yY46nmUk6{+j5E_1L%Us7w$|V#?GC)G}!9A;MI5ia`iL!^ytMy}Zu2 z2?0jM!lvEG`}ja9YB|k}}dHoLv5gw>uZ1V;9b`vSJbBPYX4f zvfkj3ucQ8r+~kG~`FE-`9GGRw3>~`&-l>sc(l|gRYH?MTWrKl%L11t&3O>H>rH-2$ zM{aIzU{FvZM|MVLkf5r8HG%}!%H5GBU7e--BR0|>Er-8 zvbO~s4idHbY7M^X&)%w!XL!Qu4SWfjXIi=O-PFJ7dXhd`Ejjp~gq9SLY6CT84y=(S z+?=q+Nv>^@XxI94t8w}V#q9Uz^gwt?Q3G*{=_bsElo|NOWG#Pct*z;8^~N@;ITUB& zezkaH7NFRKCS16BKOE_X2*G1_CZJNtp@FQMYqK+NcGw+pZz^gH+S=BfU+ZXiVB-9^>2sZzaPwrhbQgDO{|-Qd_zl zX$VGG=yPA-yWK$S_u643oSd-<<#Dc>%cDyB&x$Qc#%%n==?-T0bU)>_-x(f^YItNY zmpZB94&)7 z!q|`x*c$+mPUXxeNhVm;Q7Ta|GQ}FLLW-LZ%T8(G_e&_Qcce$&lhgcqh~rU^2O|?` zWh~e&nwRy5M@KuDjq!R$d@JJ<>@tTRJ#m|ewXU?XkfoU^cX(oZl-la85ZcuM#Cu zx8oteoE1A55l{2rCfOeF&N73KKvbyr`+e1BkMa8gt7}7Vlec)gu&>d2&lePw%4^`t zS>WQC1Wi*d0gy^(%`S|uZ@LVIbUlJl%=f|lXGqaTNdo9|;UYBHV+cBNlS)00V%tzJ zdNmE@?cKJseV%v=jOKsic-RCrebZow-wl}pP|gfWsFx`p=95T{Q?;YPEQ$xuj9DN_ z^Q{kq=Z%QC&d%k*lsc$Qq{(1?n82M3SP-9*ASE@<=|cY=`l}Vs+<8^$NSbd@d26u< z@4UF_^0jlUzmOEwlP*j-!_IkRd!{B{gkk{IhZhF$m&NHs|IoZkA0(AuD*xaE>Gjfu zxnO$!*SbkH#Es~*wyhEnzXQ{80r=})0 z5fRZ}ZXI8-F^xZP9j_te|4NCruRMUO~Go z)!R+Zc2gIpC^-#pnj<$`?Y$}Sx4^SK&R$?i?A`PaNTGp+Q(rcnlWO=GEbEC@K+Nw?`& ztk$@MXCRv-AIG1EGSxS~#hZ#fwyI)cq)I7lEF1SuNxYtfa)EP{uWma5u4b1Huo&+c zl4%-|mS>1OoaKKa4!F{biEq1VX*XkNRPKf95a$xME7PVK&he50gO<7~8n)S@RhQ07#s zo0lN3uNN)BAHFqZ*67^!HW@U|{j*T;FxT|$M;9#;S_KcU$F2Uu`8qgup2U?I9gWoC zvCjKSLt8BMd0rbeKR;`GdDsrlyQbDqgZ9_bNf*j_F zSU$4>vl?FJX1@cAMy-{>^TBNGf=tY5qT_l)|MHWES53xehIgcZUPRLi6V{rLh_b&T zHTB5u_)AUxvN;5pY9jC|(vt7L-@1|E%qWeRG z%Ei;(IjG8@>$)iV_4FF+2_hlKESlOkzcUYoi!HIvmpZblJ8CCjrtDV|Jzs=kXPhNQ zU+ya?bo%dFe=HY7p4rBEA=EgYzv?#xkg?pye|RI67L?r%7$j4~C~ z9zYcFCy%(E0I#muIn_N~Os+lUXHB*Q5b2-%HGHL-8}X(hRDl}L)>n6NdnYFpLjwb~ z7W1XtGg2kvyw{Vy>jrN?uc2rH3P#4Sb<5*_r7PRrn7&)gQLYMO-H?)!GFq>&V$iB9 z9Js$lf*~b;fn!9&F znLYSMSrO8V`EL)}bb^=@T&kw>$}H~?WJ@WD*TYS@?!GgW&x3I%26JBBdc^mHs840b z-|AQ-IInnZs{)HL<%>kgE@r^U+w&s3p%2}E<#CqlOh>AsX~n=+m&Ig!>!ixI3;ShL zF)QkG^Lz`$FS-BVtk1(~$0W!)i`6Kj$P6$ECN&4hWO+S!c!Pe>IjOvb{dpmq={OY` z5_$>+sYLFv-cMu?x*D9<o98LK*NlEZorwK84oxsWl+(@9rJ?)SqHCs(mbm-oZRk54yK{GpMN`z^pM!2W1rb91xZc2M_YSKj+~oy*__`e91^1Ax$0s6!-OuUm$HDMD6Egkxym6 z{NZ3Low>YuWB!K)$X{rTe$}vS5^q~wP_?dTRME=j<7;eIrt?=(MpFLoeT|1d^^Fl%jHOyuJvjue4ar|s@zz5_GNKU;;z3|>-F%9N%+wAo29~?X;c=*I9 z8$UCnh=S5uozVR2*DndoPahx^6%`>apS_63pb^<;bBFEd%vN-VNg)G%7i{XVA`75R55n4PR2u>9|zJ=U3X zY&bk~&CFR=S=uqK+#v5%)(&6%Xz^L8|1{r=aL|5ncH_ZE#N`mE((SP0sL!=j(?}Av zx3`yAbqWKE1uhwgQ8em*0qBE*g213;q^?chJd5XokSlXN1)|0$*!yRaA#V7$G& z2;P6I9H3@)BLDk)#&`k`4y@)UlU)CKx5ys+94;-mr|P*+z-K!CDzPjIj@95@K+$=* zFt|~mU;vb}D-4(b3UNgZ;eQF~xU97afw>w^)^c~}yt}(gNKOu6rRU;G1BaLM^7G{t zjlnG)s43OKRAcFB7#Jw1sl&jU>1qy2`)*0ez@XL)rsV)-$)fIdzic`(HFYr~sHCXa ze7B(0rk(JYz*xs8CvCXY5E1yiX<(#8c6S(oF0`ioZQ%LdstbH88ydnd)6A{R_IhXcwoJqpO7Cf9o3!>)s2PY#aholJy_xFpb3!>#6rx})mlkSjk1;Q z)W_D6Rls{}FL_1IG}=vMnx3rA@HXgRp9TgByUuq@Ffii08Gj|DjCOYdY&M67yS21s zdqPmQrf0tUf>A^^@$lak%hZZn!@dq4cX-DZ2K9Bhn?p`p9gCmV`sorxJQFlC&x(dKB_!X z0r*~mHgM|Ou{}q5@-&0Wq&dq6j{`|RrVBlA7Zf^4sCI)Y@ ziLr4F8Hgu+v{!N6-hR!I&w=llN({OHj8N8_-N`|8dP>OsOe1fwx8PTKUM-NHZ%V3} zuG)Wbe_BE1im1Mt8G|PL-WN>>Dmy0do}cbq&UnWJ%3e$LX!#C{y zU=FPTKAtu!qF#{naoaV>$Bp9k{JmpexAWv?QiY?G&@~kt7OY}p=#w&@w4QXw2b~_j zl{tT-C!8fV4p=EUy6sU?L>xdnW%iTfI_f&NyHb7xO>sD+(70OCPp5HVd|>V?`eWf$ z@(GUv2GPF@8Y5l>L`z$+`3IfxBXlS@d`Q|T%--D$zF;ccry;O&Um#N-5?+S9GHGBp z5AII|MgF!?T^7Btdr0p0g>p3c>@g)UiC{wiCz(!YWmwb>l}l_S^^!dIe&Y=-FCPaB zG|WD| z3oT%$g!oQ0%)d5Ftat2NrXw1p(!_v~IQcTfh76HUD5Mk)?GyRH-i?H@da%{ZbmeU-s#RJf8jT&9}vE z8?Gt8FWV50K`-o8)W`@Myf82n3h!bvwdV>8nKAN4>a7KWV~JWr*aRGS8Msbzg{D91 z>T>#2O`bz0I~eP{+Dy9IZB40?RqtiZm*8_oE;5q^?cS}zyzNDwhhl=aG^;B6#asoXkzep#!x~^h2Ic*zuL?SF(^oU8Q7r;>TmdQzdBQLFs|%56Z7Lxx>Jh5 zSk7OrvvH|Pu^WD&H}IbxtX`_zk4i}#Ei^biZ-2c-$l8&k@vuMaV_0e>GpyRffhEoy zoxc+8rC%8mDn`STCzbQ$5Q%dvhsvq4@J0q#O={HbvDY0%(H69zQL%YlNUW?=@_At6 zy^q!Z+vjwD_+4R+&jdXuN4`S~z+R3a77x#sP1;v!LK!-ooWxIeM)r-VWS7V!p9fuL z*Q3JB+Z0qNas{Q_Xg?^TWAF;r5`X~hKWoL)-J2Ahnw;eGRklHZX?At$x6N*{CTr#@ zHCZ0z!(?js7O4!5@oDpkD=kK1eZ1=0MO3b=PPU{B3%jHITex_SaO(F}%CRJ}s3q3J zu3F+EFXs~rq#HD8Qcou1A)PFt^lHOOcRct3O*m(^5LzGx;{6L%4)WLsMj*0Yevs&q~>?lG-3hO3YjA;c{Zhq9cB1_-Ri# zia?KOs6t%fu$kens$zo&uN7XB5*7!-=|t!^JRNW_RGWL58TZfetay zU*r|Ul8s7!?c1BNd1qo`5)>NB zZar5KSHL+}Hv&X63X6-W`1lC@0qm6##l~+kn$ElIdcw@`Zxkea)+^=3#YW3bE?0-M zv4>^NF=1g;&l!u)P0#v`em$YesqNkcA^5rQU`pFb4Uu+lr-+bf~6V(rHLQWOQu zG(JEfWS5jg#R@%yMMOlz^*(qDE!ny`6_V?bO2Hw{&(9-b14Gj%fki?M4P08%7J9y# z+IdWEi#MOYz$YRa+MCEx5DPEReLmT4;jyD~S$D{dN$IKG+>|%R3j)B*e6Cb1sfZD6 z&L^$E8RV3XHwRZ=;NQSyf}9G)sL;Q=`!4i}yrEF}hQvr#dRajFo9Q&reCv}z4F+{7`)y6G}yifF70DwZ1_;BBDl{>`7 z#@658KmGui13klKQqa@JJ<5om@7j*RvPL)n$HJV|hD1acB_hJS8#6BS4W1J-hV@in zIyiH32>s+g>HE4)V8mve#dR_n9W#tob$Q{eW@bj@s2CLu_?&W9jf5{b8#wOv62EV- zVpVwcBHQ&nH0||_W+DcrRebBp{t6ZC?d7051g2@z+w&u=XsB60^L^3JVK6b}vb8rRz_xr@)(rlW}u9k8D`2#x%a??)?XmnvXjIx_Whq$H94j(M89C zzJ$cI2b8a{B(C)7TuXmx&#JX+8zdT<`L5y~=2;Lcw4amgd=DxkPWt3tfM%@H`jGYX zP%eMsVf(@7YmG)j%Q^Lp6FSzfG6Z0;_tO(e5P5ldjm^y5+@t|xNQg+Mk<4vJT5UEa zRA#@PI-vy2eP=F3na$?OY#SGxQG6yzk9cef{auA=$3N2++i-yOEs+4il*V^T@^ z)^z?d8FDto&Tp+A)@3C<)7zE`-%^iQB%`HdtGemDnxg}0ODvtPvUdb zNZbp?(Td(c-Nt9b*2L|$Kb_1>TmJkAvx*wob9x9^yED(}n9KQ#vZ$m1s3tFd&l#{liWIUe?b2Etj$eLS_SX+r@|;D=owC96TmK z4htx32^OfEM_`h^ln5fjimv&1bUk!~fu@^znCwRb)TQt~vILXHXFs6>=X-FI%y?ZA8p zxVD`%TNzOG0e^TtLeX{KNg`$;-A()Zpo;vucR}R%8HwEpk?Q4FQaD=TB7w@ao|`F$=ukCOJf7`J=1M$bjYAL zfN*eLE)u*gN$+8%u+YdlIRh5`+~70~^plmYEc1|?y>a}W=c!5}QhG;Ln=@9f`86KO z@!Z!Sh1)&$XxNsxel~MgG(#Q1!pXE>FUVXN}8I&u$(MAGzkl0S~| zb0(iYt6a{Cq2>@!P>jyLS?~SYB-;fM zf=0QqR_|fG!hgi~N~4Too-S$6%Plu%>0K>}+^OP;=jZN(;4x)Ov1~ADHb?zHEMzUo zXRUi4gZQLS<=|5Hnf1XqJ3a6KnzuLmsBV;upx@oI64eMlEu>4 zj$R46whcFb(tUA03)s$Jh6j*WUI`}h@&6ws^=DwHn9-|6@H>dA6nZh zACj8RKrD>}vCtPFe}+)B2?{^)Q%^{%J{|gV{+STOAIf(D z%M*p4KDo|nvj|Isyg7%$bRcw(wCdXwU`5uJWlT;N$>+ue!j#W?X(RD) z+0c1pw`8tNtY5_lxsC<)mVRKsXKmQrOlgCD5T7p@UX(xycmFD+p(p3zf#XtIS}vkB zdqtvyyQonYZR2my@ykTvVomsxz+q^%(N3I<@__4d5d11bOXHw_hbbLZchBNR%XuYO zA!wxruFFoJs=a*^^r`ff1+pT#2 ztbDz;@^x40`m@^i1z0h@+<$`)i7R`J;r?RIR#6_x<_AS)%Vc0>@P3@*`BxC|5$ciD zDSVl07M&>>Ut#0`rlqYlf4P7Vc1~>*rk08#`fopdoppcCuYCkpoHU`;Z_~6tA#F-q z%zsw;+K{@gawvBN9*vCT)QyRkH5!6a=%lF&3dR{)dNjbCxMI z0?djP-$wEbkUzo5VsEml1nkT_7{9upxY4XuNPasU4)j`JklB{mtwcD2Pa@=xU?;jqc)7h3hPVW} zhuZJ#5CIOoWmw3a_ zzqi6=;a)TzUQYUcknKSm9`dZEdD)ou;SjxXNN+o@c3rl?jZhjj;p4!w1LM~LD?5~( z3kudCm|MlKw>>>g7~5d0(#$OosmkdX{B(4_U^5HuDSr4`&6$O8UXm|diGWLVZ#>a!sZPkI*Ar%hrR40!C=$y)r?da&( z)JzP>Xe7b&Bkg=o&tv0h+ar+Iad6_9EBJ!ues)94`m(C+E5Q4Eb2rjE92*Z0i;Qe_ z*(9vrL8IA~5n#;^>MqAp*b5d%eJJSwuQpz#ROTOB9M->|w_O8Q`U?Q31>XYzO#nRn zb=i%SE`=AtyyoIJ(s;`MpIO)WM&J|dgU^2=l4KPpX<;o8|%)S@czaAHJ#wFf@NvZG=HZFCdQl^OTZ zl2x{KC=@WCAODZ|zAUP2Q)HBIW=A!|{iQ61U*d=mk=wVo?sYE&k9c0>!QY z|0d)(m;>kc@89pT#@v(;ouV)j9?*=X9D2*Pzb2-8~wQ>H0JlYuP^X*H$ zBr_E+!jm#XBih?&*fg1~pnY`NX>Sd1X?!e%51Oc6C6`oajF@Ma96zkda0jfMGv#?xp-o*^>?Uovk96K z3Ws!C#0jyc)415 z^A|VjxY>q@_M;wDxYPZ7vjeZ4;48#@*2ud0tzM@;7Dx3zh(Gl=Pf=OV_HqgE|%N|eEw~W5A2f@E1+=-->(|BdpzDY#ogU?9X`gE|LwO2a99_Dj^0^vrL4=G*Cv(3jj5f0n==t1nF4=|rw~E0wZ*zjw&* z%e`Z*bRq3o&Su)r`b(fc3*E7|r!=RwnsBb|%k6X@HaLw2Q*+|23^oAVh1acu20$bT zyiC{h%7=ug3b-Cp{aCu-_T>~r9ppMYcoi60%sS2oq07s*BP`uaH7EbQL?0r3rcgM| z?DuJJ4_ucTQT+3A#G9$nkX55awy~>D>v#Sl*ARzP{W9o-Ho6@iOy%ybHd#r6{Y`Ae zXOC9E$(~L4{`wgC*7d9xkjQk28kQX3$G(`Yyzs<&S4aTLuwFAn=>ArWv>W+I^qz=gR93!pX#oEf5kF zD{>FR{EbC+_<32aok(L(-=TVQo*X^j_J7TsK*NG^8(T?EzMEuPTWDsY9Nq11zZA@T zY%jQTDt9JLnSQljE{!feSQGqXa=avbHaWV!bPl$Q-$zpXs`2r3ua|0pOMhyx3B`AY z=|1jzWZ+AS+C}(w?l#p%RqU_Co`08D3w-#~o zQQ7eVWA&=}(agd3H9rA0`=NUK$wP*T^Qv!ZrXi+IzvA!%Lve2uL4V;o0W}W=XX}2a zM*h>@Yx3j*&mlRC*P%T!{wGTfhFGGB+`K+;z99CDn50U5pw7U9-%CiJ+V%R4-s%X< zd4V-2KoP~;PIDZ;6-NV=fhSB-fGgDCOs8??*(#gC$C=9t$M&-cSvv1hRfB0OcWo{NS`FoE@%0LftEwS7*)D= zcty@PTF%oLCJj%hPv+D|{^i@}cPH>s^pUzQ8S|eeq@RMyFUK3J`*o@VOir2C2gq8w zhVYhqd{&<*OL)}$p{#b;-Bv=a=|G(d)a#wFN8heFh{w3lLt-7&N7jx*UpsG4HT!`1!RK)uxzend|X49un|h zdK$Z?Xj$5_vbM*bm>JO0r5RL#fM^gC71hT`_K2{4O}bo$wXzUIIpX}leK1qcu`?Dt z*EqVh{=&FS*mbw7Km%hLg*FRoX6iJOyU!!*L>C4!lyxzyyghYpJfUV!B8mrx9@3(! z^@BH@TGkiXn%axss=W`j9&WSA}WpZspHc##mdicjZgyfS$-SQ zu!5ynI!cUIS1>_c_MxIKs@E74pX|p_U13%32VIilezN*+{XqV1M8ZfJKhtL*KE=L} zpIZ@k;5z7Vr;P7+t@E^_aO$I8UOPsy z&7kthigmGb!i#eCW!ldv-0HpG%kri51(`x~Fn|E||5z-1w6+ET%xvldU|Y;G;_}7P z!(fQmAB^L$)4Fe-7o{WQ3}pu!@ojv-D|EJ_jq7RJb?X$mFFk%LEJm=qCO4gjg$2$- zz5#MF2!u*^EwI~Z>KErH*rPI}Bg4g$jj!8%?w|wHe3Xc6LT*?lB$RIV#Vs{l=?J&-R09T%9~y>W8yk$elQ(B=>Z31;8J!wOfb&SI3=sa!eedH)g1p2vC;R{Y}h=jGik zFYazol8QB|p`#(&bCha}upQkqvpm&;rhxqs}_mddZDgyG*Q3P*mGq2)1vWL zQ{>TwV`5~kYm2|}%||4NtpwCJ_R8utDXpBax>Gt-G76V}YkwGAF&2 zZEZfT42`6$R-&Xz`w6qZ$gR<2+9}?{G3chTpf=an4D8ic?AT{JSiiebcTe+YNdP~{ z7#kY{9^9{5fZW|G*$In@dC6Nn-F>((6Wre@S9=5HtW0_(8Suql+e zE>C_KFhLECIDa;wyrOx9dRnS6vcraEu^VNu;jug3Mh8E+v&EalE6SPa{-M>|#!!F> znKB`CyxoAGthLr3ro4S*V>|6b>}P7HBkbNhcl&OdHHQ0ilT+^)uZtCfM3cfBtm&EKgVw;2%A8G`SE@N!j;-iHSx?sI7Sj zJ$|#o_4q50BJ|g0Hw(zVL*SKHNecMq#4tzNHdeW%E~qI29>ORSqnoz|(8!Wo{S6== z6q>w|Ra-njOdp+yNJd^hrs++VWN5dJX#lt?o~s1tcaokjuYbM}pz%qG{|RX{>30Po z{BwmcV2}Vhfs$ez_dD=IiqE98Yw#xn-G>i6JHDad&aHujW*09yAd0fJv$Jvg_>pk) z-2Ib+g0M7Bc>jF%_D0l!GT>L;chMo?UR+)d3=VeH9q$lvoCs!RWQ;U8Y{s~^8Q=qH zRfefwVa3G7Hi289A~-rZDJXMNI&vu{0U+knqP%7WIx=h}DDvXM5j50Q1fzW96 zba9%4P}I?p`}`Tvs5gpN^?eF_DB;8Wuxzdgd{G0eVm_j28_(Y|>(IX~PY^+#f&vYOh= zA0sW!X^@^?mlO;q_Uu=DCff5#(yEZFjqh!vn+p$=iZ!u%AjX{G{Y|ae8*Q74sQg~R#l?CkV zx=!0|0+dj@XzNAjE{z}6QFD9nzTTH}Gibym>!o>K?#(sl$sq`T;XZ(ha@D^I^eyY_ zFKU$jWS}%FQE(&9F04uYlk-6L1wG!V=1BSflZ6K)It_r;J#uUSUK9bE@MG|zX;khs zgYV-U!(9k@OM|&jT3;=yYE}L)?9@Ob7M#6I1Qt7bc3}gmR7>DTtxFGm7fv-}w3E#F zP-HlbpLqf|S%w$zn^pUC+9$=k3AH^f&Bdu3p73aH6J{a;tAr%M&HLilI8VpHh!9=M znD@`r%<|T#$Bf&;SxJ?Zx!}Jxh=)dF4aMwf_@Jut59BSet*~3ahPWswh2U z!dc>asKq20Px5q+#Z!W#&E}=+`DwouszeCAgMc8UugJ{HmQ{g?*`yr?U0?lM)-n#{ zfgGHYd|E^mePRi3e}oSTbUF7GPvJdx0cW`Z6&$Lc+HtZ?#!(LzFFHLxcWuq|l95zo~DAjh%}p!@v<1u{vMy5&iKR0={k zdaFS1zV!|{gIVm8ZB`)&-*J7@H!2)I;X?=sj8c+*^7hm#Biy231$|O7Ah=vz>>-=I z`@_0q{9bB}BfBvB`|~$KuH)(sXI4sHVmKPQ=bWaZmSk5vk9P-PomcO)^HqSb&hKp!XZDL?Q!nP}K zGA~8&LKAs;`NAJt7z~S~x_E3L7MU8ykK3Yamo%eco{DGyf%2_4s}4o9*ug=3v98iO zEnDKUE+O9n9lj=+c$o&ut|V5*&_~8QXJlNJDlb@P;+D~z!q=QrQy18AY;N^ z8EXvrd_W0oYn!oh<&o`pFtn1Z1_EOz=98ge&YeM`tsZ_p6hmCtmDV5Qf!TlilCOvh z2nNvaI1dhBZjr&cEqo#tCQy(=mTplNgg?}0>sKrF;pW>uKPwe5k`gyv1+e!hcHA&dR#3lM|>`x)5ehb zJtP_giPPzMqqY#WXP~dil~0xaB6Rl@Cuh>pQ}|189}iYT6m>?Vq>qO_96kO-pAdFd z;q&J0B@x~?)p|fk05J*2QLY%DR)i$v$0Z~r>~K~2^7W&M&Bst9St!($V};;~!J*{( z4RV-hb|e-HZ8Au55L3kPrw)4-YekOA`%oSYyKhth=YLMXmm&e)FAk(*$L!(fJocO% z6|1mR!xGv--}cYqFq8&;{TS`qehx|57GC#WZ2n=DB|h2CL1Um>tj=0(b%e0P|2wTU zhv0KJqV9=4o#*yhT)yU;j~9!F#=Awt!M~*dhz54$fM9HpGv^lw7P;!m=T-lZ?BK=i zJ^LsF5g+m}gE|t%IaF>cWdZz0t9d<=Tu3N|FZfWHIVoHMAwggr1cO#jHoCGXm>w>S za6$Yj=V?1F9syfV-a{Tm(hgUiu*2=mmiY51M=1A(ivafnwWO+bMgI#vxK_jLnUJ;t zpZm<}pkN|~Ic4S8_LUA23`xK8z!)Pe4Bnq@e7rf$GQiFRAWsGt3-z$F3Y)a&pIjl3 z%{L?mR}D=Ip5HfGZG=wFJX3@whOX)|_2)J6AzfUsA8c53qDHKj?ja$-5;H&tyWTpT zkH+QrwrQkOgH*7U;SNiQ__GfpV6fb*iK9wnGh1K5W%nJf+m+m!TRnA+k0S+uE_D@+fh&i|PH+7N*IljoCc z%y!86#MO~`!duD!?|W=&K#0=s0h}=|i2Q&ivr`XlYDNYAr4$A%nWHP;P~aPHyl?xK zW+6Umi};rKu@!XqIeB~qKNt&G)PiyqTu_O2<9DE~n$d|H53y{fKuSXcm#Z2&27;2U zEt7A%a4supZ0Ob1Rl=9}{-nNecnEBkx5sJ%kB!U9QczRFt+U}?g?RE62Fza+5%)>h zE>Vam0MPRPkPwSga{#y4iX-RdzNJ>By4bcCza;kcO)Kdm$k8uMeiByzvXm%4pud4`wy$O)tWf*aB^wyD#{(tYv3q>T;9Tn+Amw zmt(OWukSIF@;RXf!@s>yXq=Fe`j;V5|p>?Si)**Ik=g z<*=qW=olIEfC>?nzOq%FexD(RKkVAtJel?i69u&f&!cjtg*Dnt<5 zk{PM8et9`DeR6>$ZE_)&4}B>hpH%&&y;P4&Lp*jVFE00{Bu`?9xc|lGHe)ksBucQD zpU>n&)S{F=ciHiHTNy9Xp!fbxH|ds?I@?U^tMfQ=^z-*enL{bj)*B60@xrts7P8YM zh;)UkgnUBz0fj)J&P-{R@V_CX{ok97b9Tj#+53^9qv;Ck-vE)>r^?m;RaI3rv<^%r zHM%)6j%^w%W|Ugy-@(wJ|G*@EsXDq_?s1N)vW6eGkvT-oxJTqfTqM8G&djizg+w%= z)u3M`G%+miAF0rTN^y}p)p|ZZb`Qq#~418z$+@*88oC*cRx1RixV3e z4yz5}#ZM*J1WsUcedV$%TZtaBV6*x1dcr8XC6nDM@{2vzfvcUFuba<)n7k8)6Cc4b@N@63M}4Qi&6b%)t+lp-k_ z!2Kzy?zBOdjDzCjTE{RDhk^R><;&$nk(jIC%ENbCr*tMK zFNA{y?^$aLe#691=}5Q;j`>w&TnPy=4Ok*$e062GqXaiKip8@lsOJkgV-waq%`fmF zW$5UMiUtDk{dP|o&ECZ1eIy<;s>Od}lnw*O?h)&4+zLWrZ4Sn>Ir_!lzst@8#mj5( zC8b2<4Cu&yYHiu@caLU^9<1TB5krX5TM~uxKHjWz&lX%>?n`^`PEwoFrsAvlA4|B@ zSa)$4ZQONo?h6Ps3*%jLR2*7qv{Xi<#_6_(Im6Wtb&fvcfV8XA22){O7{Z7PMs*wN zk>S2Bp0Dp|dBtibx^yqd%GJ-D@UNr+D(Nhjl=$)XzuCV;6AXB0|K1F8V$($f(eWw^ z_&JTxkHM~9P)Fo1d_*i^z<&2#x3>tzr9`7WE8~%{Vp%sow{gA=r4V(a-0lg&iKRVx zSBTL_s@A6)IcmXQ!ip?Swmx)Vf8D#HDI|50FoKbJAT^cI@vBoa@o;)vmvEBx=Cvw6 z!CZYPupi4;-85k@9DXssPtR$_8nGXFC;xJ)!cI@R`z^RJ5ARUAGd~C3>58F z^z{0xP$WQ$in+Eh@k|H95^h>Lh;qVOhq~tXyFdz7DGBorPC~#;=DL(Vj|!|*Pyl*W z{OcWud~gK_3Cu!Qj;i=|UL-rP?&B24hw`#h{a@md2e1%O^;2&E;=6ZTDgV2~9Htg!M)BfBv9hmi*b(M`r;O@Pk4sF}NDx(9TX)W>D?0peqhEv-D)p;UitAWMn{L z=@_!$wFha7Ctu%9$_fBM13;l)dVF5-SF3P+`p&o-{KQNnU(s9I{DSM%>5yVz$bSKz zxk{joIYeFB?@2;>Das_U_S%e$COUZVwndU`y;trG=qE7JUnP|# zP3))(U<0HvUHsUEx~8SPwH7CJhR>YYpXWilG(!&;H-+~L*OyuKu z*Ri8BPcKWh5PG+{nIJ4bdagq_Okn=UR6$S2MF~MIfdTSi0|>6#Yh2glB&+;xFu>x` zm%cB6PnU;t5M0jf-8SFniCFE&sp4~DsGe_OpAD89HcF+6BXt}xZ%v;dSJy`A8 zc2pw!&mDM(fs;JYv9LY@^!E69)(9&GA-N7L%4n$ji$cN&Da|0n7vwU zY}>~SQgwAL1?86dk-q3N(xvNZ(qpo2d&iZYK%Vj*os~O$+h&e@@Fh_jsrTlj#zw7T zPCo$^P!x21I2$S;DIPPOqPV`-UOyWTp%;Y2_%UcEU(A`qXJd~L`$PYJ$$sE-*2`5v zT%U9AvfJwN{_cv?n4rjJaCBI@H*iE2GCqrccenV%&9RJ_*gK$-E7{Z>FGcQE!JdzZ zc@x~#6&4jm&BRnT!dhpeqOCo=(&{ze?Dnsg3TTOynmT^NTXTHlW+eb@+>Qq#YDeJ^ z*;^tW1$`b=IFELbgY*9W{)?)r zlBT9KIXaI?27+9(dU!fK&9&Pd@FE@Vj!nYG$BN(uNq|1Bt&_ zz)?Ct!l-S1+QETko!#o_&GBMd)@+To$j6URKxGwlVCPOPLYglrNgX#y`@U%^4Qgo4 zeZkazH?Z+LHUj6jSaG(5#l{wtm6bIv{;I3H2^$SctWR7x)a3yvqG|QfwF4CwwtwJi zA@$wFyhvvi2zW-{<7vBsk`e|GuQ%Kq|20C^e-&K>?79Q9$1cz{+%Ug$6o2iTvEUo;Pv&iHZ?k${ znFIZ6{kk{hR@dIVf&mkJSfQ-gy*+bSG}0&od>|+E5||bh6%{AhaX;sVZ2h+c+9v8B zI^;2^IF^={Z#{h9&OY-#?}0$Xc>AC9(CVg~6)%9sVgT?|VLm}wXS?h<+{DZXhWSU0 zVScZ}Rj>w3UbAowGEVAFG?PY!e{wQDEGqHb3E!KaJ}LO_8$^f!i%~D~TcYsD$a@ed z3g{=w8Hy~o{zi70bV_Y-K@&} z+_0*;+QQttqwZJ*545$rn*dOa!=b3{s|v2JTtMe|{*C((1AreSy1*r-r2Gdnvn@{T z0E)_t4`~4r&w4SxurREpMS!VkkMbY)U=}7qE&?1=6p72Yk?u6Q-b-X>3`FBVnpHtS zpX{^0Fi3KXCO~-}x1SZHp0#SF=k)=VPzj*l3E#hWC9@jItA^|7tK3W&J+0Y2HXNz9 z8>vO8mErR0xC>+g_k1)&ei{JEf6iW-TV#TvWE_BQv$Vq!Y}8sOP+_N$V6OG zR^_dU`%?v>xS%ipL8@QGH#5^A13K3*7~>&?ve1%-f)|f_Ipk!ga%*aS0I*J;cs}3s z7OsWoR@l2H&%f$xLVt2wZghHQx*gzdO2^1+uef7A@`iB*G8Q3V5 zgR~_2`k458{jBtlITpN;(kPo@4%OZHh>@0H*|FZps^7ht(1q;U0q<-A>1Oth2x%Ic zCI&3Io|{H_>*NM&v=^?z2PA}9#@;^N}1JaNAu ziw0;nQS(0l*sqTP?LW~#D5CBT6AyKN!mny)wF(%4G;0GrUx0B13 z>wT^pwWcsKwiKe1mSE{{1OJ{j6NSsI0GF*(=De!W-evai_$k{>qH3w}Dd=}S-WMBF z0e2!r1^`N zl9JM%72rN=n=j}hc5qPG`CVhg)+e&_{DZ&Co2jjs()Oy==g-?mq>dN^@lqrM3qy-& zuK|tQn+@Aq?fTixVQ5*edM{V}c&%j3KarEjm{_<9O}r&*T@h1N z{rQ$e6%V+1+DojrF8{wc`Tqea-y}&mV+yYy3OJvD9A``P=O1OR=H_6 zmKqZ#MTA~o)~{P0Bsihp$;1BmD#F0eo7}pWhAvrAL)>oio#oy#zvb5K#c}NReydBS zVQZ2uN;YgSyKE)~#z2C1>p>8CWH9$x7x~RYlCnCaC4P3dLgKDVN1PZR_Xn?!$Djjp zWL7cbs)xk;7TMSNYV^y3J_wQnn$T~-)hJAVK2$xv&L&_6k4#r~iX6S-S4K>*X<24& zYCR~uT&inzd$G0d{?4|wriiN4^s)rZcFJV zER<})fOok=#C)E{t!HxN_nbTT>b|1Im*nuQ*4!y0& z)QE;6g-k|nege{|$6beTeNGTO5HeD6)Zgd;ZVf-TXr zJzeMwH*wX^eSQ5!wR0P#hKYSmgbou9CBL94xm7~7JL7Kxv=J+eiNi3@$b4@TVFmT1 z*-_6GffE<4uq)Eo@MFlbnYQdKms(D~OF?m7NNJkuFO>c1wjUT2LFm5|BoJwcTVB?p zU?{rJ<)Vjj-9n(!QYEr%xe|Z6TRbH8d>-^?P3L_uesGo}kKm)fwKknE$f~ebciIj@ zFU|Xa2yA0H+1dWbi}l=|C)iSi91w?_~p-tTQIy$R-e;l(H?Ih+A?O2(!uAsryk;&1G;oUauTiA0olV_&hnN! zmeGUD{-G#|Kg%+rENOH`RbL(6AzN~J4{RJ@S50MnSb10X1BR71gE$pplI^`IkIJa* zcH8Z1ukew&y{jz;r?77)UsB8!AC4Hj11Ow>LHt=^KoNbTJ12>87mQ|u?1)=!=yTZ# zDRaZC?KA%Y6DLryBh=J2ZjvGPvaCk=@|Jsk?dKRO1!|H3J~lRX98dyZR0QnlQ0v)Z zy1Jx5`5T|%>XZ#4sD`@`BD=`4VFD5QBOjMcP$dfL?+@tXVjo7L`m$5fd7fo7&sG&a z{JAmE$jCKC*$5EU?j06Y65$@rxF)Zg)iYa3FVI{=)OXE~ciJh(7v_sh##O;b)|Rlk zdm2$~`Jx$W5LvM3FTLb>tVvy*UAqs0m?O9v@@fEIusQ7tgQ4t149iJ1Mm|^f(FLK4 zJ!x~yzW@El7X5oAc{i(=oauOOHNku{zlC(A_#aWrTc%AvW)RJJl`va%7R>D}^ZA|E zy?J47rUO>J!cj!!Ce_Q0<9n(xf+0n#_q_^48t6_Gx7tF`i=s&lzkZK->@=3AwD*%U zy%HtbmG^!k1ar2h$TCae&hOI`)k$+BQp5y3$OZ!thWx3cU8qoz%$x_44}`VKg8X?2 zHsT%sty*nU`YK+wR8jT7txd{i!vor8LsJSLwiK$_sy&(6D*C<-R%^L;Ca*e|wwb}4 zO?8UO>%|ej$Hh^w##|wgz885N<9qwrzl%mp(r3dS6$h_x^hC=%FbT4pOf1fQL z?=p&_&E6|o=*a1`Q`R-TMkQKl#`f|ZXuC`BrTirVXZ!m)b$4Yx_#M(zfxLmI)bWwo zh=Rlm+m26d!lWe{g$(h2>*d|HpgN0?=J8Q40!0u{CvYgLIi0`#+2JR4F<@vCu)h== zv;x*wx)(@P`cI~Um)fMg)t6&INI|aUCO(a*7|bR(=}`HO6MG!P-*mih9v-co$?gOc zGkkbeuR}b0fL_@3D_a@;yb|yz{ zL(#?HCxqggBsqSjkc$FyMJ36YHoJwjw;UUl5W-ePLqtU3TDB|_EZ^M`kZO;JCo7x+ zotKD0)-v$>HxyI@!{|%8-*ev9dxkG|?y>4Cx}p|Co6SfR3)u#WzYNHKwP|(76Pk&V z#v=h{aw9D4$1ieCBr#$IWJ~Tc;~coZwnjWu+=%alD;;fAw+P7pQcG&H1TUEf7O9?I zte~kLoo;1!vpPS>UVK+wN?X~?<9=UA-W{L+0Wl>dr9`9hw-ST_;B*1M1)MB5=X{U? zj;JyQ!M~a05!BJI=JbW+Mj&{H^z+yL3(lX&1Q|i|#)_BVTkFE;tJnGfqc!T$!O9%; zu0-|}y;W8M2yksg{pwWzAyITdOzk6qwof0y;~+tUpL?XAUnNlro>&;z2p<*+k16Vo zq{Zja)%9p@f_F-eG$v0bsS0RQ^Km9kmZmp`LnE-K!chYwUy0kky&n)G@0`^y95yva}^t6_JTHV#!~tYtWw3q+#e8gTQ!rKiO07p5tt|&nzHe?>_)G?epUB z;_dRt;)u237tl_R7jC_F-5SBmmFm>B0ISuD0mm2kbEipz`i@_U@H(>&joN!nZGQ5H z4?-ls$*YKz_vkqUgt-VK|BNr5ZocSySoQ>cXtc!!Gi~PcXxLW?(PuW z-C+*T`#$s6Kl6VzHC1q{ZgIJ1pS}C^-rZ|;uVucXzKP_mimlgks>M?F?|_1mS`j7r z-jcCRxQ+Sh4-M*&;5DcIE?xAjS=(*2-T^(upYl`xN^#`-UdXHqh+kDm+z4xoX6 zed+!_&f~k?vfU!_SMt6oQURzB8+tIr7eW z2?nL!?hHP9G>WO|{BG|`+r)V8Z!Yq5a}_#K4er+{{=8m#f@! zKN!KffnjT76jk?RyB}bif1koyr#);b=qk#xCv&$Jlnv74;Z72JZq}Vo;K$=tniBas8qnnqxEND4 z9bTx_wY$G|hLVvaWUTeDi3>EQLh>nHctztUR>Z^{8J%pRh!!Tvfy&x*)GoA8l*|>u z2V59_BjE^Ql0ED(7q{s1!2^1427%r(9UioF4^qKYB`K3;thPH~llFZU27~)&UP{N( z!&b1hpiQX*$RgyG7j?F+Z@lxc)nj3_w{yR>&9G+le9d@jNnym5LPM3L|Nhp%m_dc` zVsu?{iB~Wy0l>uQvzeDv)zla>p>fV^X0xit5LvJA2or{Y2 zb6BoA9A)7vY00-g(UF_Po00Ub=UA*$-fr=>eo~B4_MF3GjeGiB4D%&5x#*|pkPf;n zO+Y~LA>8k7*M9q~0qo7&K)&c$w2>vDUV(t1C79|d=@(gI;HUzap;^6igvOq8>m$Im zOJ*<>EgcCMR9i$>lS9#n^(q6Dy+8?=}GK zzIi>VFV^OVqt<5)^!=DyGKUM3pJKrs%lr9t#0kA${{V}HH~r|epS!*xa=KlIGJ^c8 z<`kTw1x#mV0@wkH^>XiqsyTUsSwVV+R051q-eqE#0Bk@JyhWLAN0`f<*^APNm@FS+ z8@-eG-Z+#YbrwE%cT{%;&2HJPA68=5SZvF0%d6|#1;|mFyUW`kje!UrL_`JT*k%WX zuj2LbFNQi4D{b{l~I6XP&0w%v3BMG&BTsN#?6k*Orm6 z`)59@nI*+Nu@S&@u=qc<+(_w}NwFVgrzn^4XD#=yNRFtYe4NFD|cmis!~*zmzkt4n9ULao$;cBRLoMct8=+MsSlIwZ>m8TF{Vbw zpZoD%P@PaPtAingq!^qTbM;d-3kOUQIf8|M8HSA+Y`@5>w>|Z%@M?AVuVY@uloRwJ zO)Fh&Zc>m10;_HRV(FmQedyR=86Nmlfe3>*+rtM>gd;o|anT=agAs58j{dErB+DG0 zQw(3^c7Zq8NbCT#i_2V{jkYz<}-E&r|^{gO;iCD$K)_gZCLSV1ja1hl$PL19$-yv z0;^6~I-R201a&_4Zs5T#{-w)*BtXIuu^XF-C0cY~J8#o(on-cql=3A0Qp&em&8kpo#fHMNB%zzN_8FeosMA@QVc)q45+ ziJ5Q2B>Cau9y>w-qEI=Wht24^!LGO=Uz|##Z`iHvpio z5WS-I#<(`RRsD=5V9FN9t%6E6OZ~PDtZLc948{_qhEN05uGwK%=_0GDP3W}+!JlLt z2N)??C7tpR`>biH)%IWm|D`k(Z*~ZCDmM1368W@xyW=NR%`&xDUaSTkdo^(; zA$fu>)6CNzXJ-T%jw0)I9^HD)K`P*Od3TdFc)lzp`6VLtpXM(>r75>`6T< z5aD;ALd>Te<&VjKs9vsWv3(I4oGSd}0?+wCO>T52X|j1|FyB(*YEltqCNhW&G0G~# zHzXbo_9<$VpzpHGMU>m{Q$ekhY`qcH$EF7uVL&}a)#Q2>*w2!ZtwOYaVz#j2e#THR zP?~`0QCGMKj4U=!`kWxeC)~B^rdK%F^Gb*6V#Z%44U@H&II+Q`3|$SjGm8)vnP%Iu zEb(Qumx{QP)l1fWMU+Hh#+w@I<1YQ)FcN-xFtVSPSjI%_z(U7{Zl=T`yzMSyHAzUH zChy!W{GJO_Zrs2hjyCAkiXc;Qzc3(O`%&S>#xP30< zEmIM<7gaShBrGf_L4a;@xeW~s(z}KR20-Hp8#f`sNQY=YAj^(ZbI`JWaQ{Rbbz93n zN0(A?`u-Y-u0wzb?bss^1Ph4U-zll7`>a^c@pG%RYX$4XOe)u@*R4Ng<&4f9{TMfc zjTPI&D>wN}7%B9X0C9WY5|EfrUxWBqB%Ff2zJY5vXEiRFZ|dp5OajS z2YdYcMzAgw0`0$l0D=RXuWJAK5b#OiR;NV_Sjj|MW1x*oa2Z>&6rhBY0LZRHT7)8Q zvnOU|Mh)(mD`E!s3dqQe%UeYM=RXH4zra#|=%{211+%76@CN9WJpSWs}tSs0Hjc^C@hI|4ecfTy;c3ntKqV-5qH!YO#K_y)7-m-Ia z{@4U;?27nFX^EgY=nUXg}z@)oN8sRz)SDB_%)s9DwDl zg{Higxt^J1Jk;QHehD240*a~2Vnu)4-I#}uhl`r4hDGtVTOrYL-+=PGzhsK~LRwws zIh}@5tUuLSxBfeSpw@8Iz_~COfHfMZnzD{Lvwx4jL|}DfA?b&0c94wHD|HPQ^3i^y z7#}Yi31(Af(n$={i=udWdtxBQ^j_UvQGc6ieR-{LQsTZtA3xW(aPZ)YO<|A0#=~1$ z8vFMugc`F2U4AR4HZFFAC@|UPTUkBIib05%@@@8JU4$5ZY`oel2Cov1SYAII#N|Pu zn5@22D=+X3?!z`ZtjD)cIs1%YS9T26jCm9(d_7>Y0Cb0Ve08Q^Fl^@Aueoihmjwli zVLOkA_x<>;|Ma&r%%N5t_`L6~*|N$V$cKpI{t@wM3mf85f|KRVe7$$tt6Y_cUJypXZ&GvX|#q~njzC7$e$!FDY{i<2B#-?8P63VW8`4Frsx!mI~RD zo=Tdj7!?y1WDkdgf}OzG}9|G`_!rAz+4ZdyUZJ1O?-kCe||9 zU^VLaz+AdQ_nBrL<$GQ>dbsj-aw*b2(k$d@7Smi$k%&OH|B}UPO?+<=wd=1u&u=VG zvekV@cz5j+OeCw!iz<%nkv^u7NEts}$PD07l74GEXWYN!lYdzuYciBFXv(&rE_{9R zraiL+>ld^_XEOVg*{0C(vckjNNfUNm`2y~bY_arkdEDk|OZYZ;zSCAg8b0hfZ#DPl z`Su($(Wao{f@|;P-WZQ1|8kY4x2o}&8s^{Ue9UrTGXj86C-~meFqus1TBKaV1HF79 zMY?B0kv_BVaC->9f<%omK_3#ugVoSb#Tdg5>W`vHwa0g|O(OP*;9V?@}LP?=rES!Y!7&8Qfscdu}aZvaD-s zB9ZX<56SZrPg#d0Ls+A>L?-XnDYf}4hVzx)XxC;o8Ir08)x^YWIIL`Iz!^x=FY!|W z6BB=*P=7GkBvA@CbWb|(-qPGLF z@3&04J(cjD4q_8$lE}KOk(t1a7m3}Ax0=8e+F%dM)>$tMXpeh74^GuX#W5_?zYbr~CkaJ6Ws;O6Q9L`3+$%-aZTt*kudMOgvP#eg{Av9C-<8`Ip59xL zE}U7aU_d)+6(r}EgMDWXw?hM^rG1C{2*d9+i*|iv zu{gG5+(w4DL0>E;ibtQ;)bm)&BtpIsb{w|Adu=2kAh9yQflIwM-)v!HVy;!m1Re-W zBC}8ymG~J+EOF%+Xqa~w17VMh*ZIm_v9b@`}2|7Me3H;vnZ0z7=Qg@h~${T=7B@= zRYPj>I-Q_iC(&Vl8?zU*i#PJGmyVS2`t!=I5Qh0b=O3xL!I1x~8Hk)ROWIo{KYgBI zZIT9c?!PJb$r3NJsNK6y%Ilt|JiJf)jY^LwI21gXPLJdREXZnIv+)k+?jS42l}zVj zWXZa@$ni-->TK!5li@aLT*uuP9u65MzEnS#l10apI}KhAs11%vtDc53-|6;H-K+9$ zO#15Yf825$Zgr!LHIFtuehYnL$=t_#z)lm-d>{0nANAbQO!Xc7DHkAn#L9`|^n=H{PW)|}9V zg1_)saJe597k)oU7#aA%WglW+PP=~(`8}-Oe&^9YN@FDw#)}Srv?Z{4&E)cmM#%U? zm@u*iXtMmF#l6^Ija^?~Z%v605Q?0g@21RB5C`MF8-id4+5gEocFzTL3b^Mdz?3`9 zQX1ax(REyXl}lCXvsv)=v@*uVl<#XT*5Msj7H%iVef)LdI?_)U==2WXNA^n9XC7Zy zG|4Nb?2X_|rfCqa4=QB{Wk9WWMqZxo>8iI2wd0hY2@0tECz?Zo@j4>)p9j@ps*Y|Uw|?K! z!u}~R$E8YtkkG!`Yy{f4AAnzS(5kb!x)l}kRtewccqf|CvNzFIO`5s3TaO`6al`Ax z$+qFZhK}%S>HQ-2Y|zE+Vcj(8{#8XHj#-A|+!@dNLIR4zc=Qu6;ka}R3`n(0Z9Y(g zUs^ZDPUcekTTelh;+i$I$1$z-ul}s&&QTNg*?$Lv5X9L)@qqin^x)+UM-s#vYr8e& z&=O;CU;WxE)_g3x5Y7C+^~Sgw+HwC0tpbkmFhsS9d_>CnZIIjTJ+o;#t^cZ!4AEa; zEQgP2r^L;%^HD&@yNRoQB*S!GDAB=V_^VDU@u{7L#LJ;+bm96~j_pVj4H-OSk#=+V z?J$KF^E9Y0Sb|SI+92Kg(D6R8(5?xu_uFS19$Ti2iS?~z9Ax()kJTSw!*O?S}cz^ADcO5?B|0BJ0hoAI* zBQ$z%Vt3dlphiFCFba9I+PGWQ4Ykqk@R>>lB?n;wrcx;ugZ@rRW{)TiYq1SESt!r8gZ_Fc2CoZICtJ3{WR#IU;5cx&o2nx{xV z9UY1K=PHv!2|w@(L&q2}JdpTsMN&p@D>(WDrip`)_gN~pBi)gvmrMB*&sTF^R_$R; zy0@Te=bzc!>NoI28Lo->QL=gpv--?(AE#j@OME1TV6#95@44fu1(p{(er>QT70dKKTA;`keAl26sk= zG#p!gU*>oK653vwx==K4T*Pq$BKh*4e)U=et2|2xCG7q=DCQ*|Az-)%82<@v`X*A0 zFUs5Q?qR<-iXbOW$5#|bzSh#kcX)AiHrc}NoVf)o3>YIRHinZ`w56Vo&6+kObx$%l z^0UyxA#2k;lG(1YR$T^0(}YMNOGA)rNRn6&i-fnHyNo{Og=6NTU(Gexq&Yd;Frn)Y zckq^qKJej=zSYQTl(FY(9zm|g*( zR{wuuyX^z|=($dWc~#!OONpXCdjB|{ETe@UFUtj{jNfQ_cQYmO4k>psHtp2NJ2pO( zKUV+lqflj}l@^iy{!L!@PoXW{&dIS%zK5fxKkSzQ9S6+h*o^%IKgt$uPris97%VDX zuV3i1On)L=YLDLWw&UBun|4yBg!RAOUukme=VLdYPiq#pzkhg=*V~bN7Z3-HG%fLLt1y>4_`9zQ zGfnT8@0W$88Ce5%zvu7a&M>?ncc!~yTyT9_j5zLj-0&U9e1>h^*%;UbnW+6Mb_*EZ zx9>!nUk<%8=+$N5#D&)Rn();qYT_QFjGz3O5?g+kdO!OJv^NoeMjOO>1 zeqC^4-a66#mkR)*c+L?OMpE^$`I+(`uD1uvYiRUnyR7vCa*t8VktP!vV-$sHej~d8 z3&K$wfsJ1tXl}``JSXa4>d~$P5X%0HjBtH>u3XgWdZjv|k5OzgRrp$rnC|01dYIB2u8N+9zU+9R9Y{;6x;vdzH|h48^+t4EB2Y0y~S=xkap z7yoQ&LfMmVnegb+Gk5QAJ+O3DfSQL4dr2lZAJsW-Zy>hq_DZ9VTb8ES*oxNjK5Lxm zRkD}9RAIx17cnabSgE5X*BuPLob-l-p7KZ?O+}s1#R&iB$oxlt(7=5dtgEdHq6@TK zmjy#?nw}|trSQOg&Cbc}*)J%O!1_1{$8etdlPN=St7rc&gndYP$58KYR>*jr1G%b^ zT~;x?BZ9wjySv&Qc(`6oED}1q@O5hK0nJol462WFE_=fV^!$P%^j|3FVYu5%GD*Ma zXS}SBmasxvx_TmlZHb8mkH9JxIVox@rk_AWPP zJBIn?O(O8Xr`zl{FosgKOR+b90D_2O^1q$lJ5rM0Df`y1m1tiFk5^f!OKP!60CUE% zFNdMFTCNL8NlE#2-VcCLoj&hq$3?QiH<0iZDU8HdS;I)vbpC{{J2Um==A@s!TI_Xo zm_yMvgU?;AeOCP9{;F1cSNWenuN-G!{hz>{RDt^@xASKSR@G0%m%&A_6n%Zmn5^{i z*ELpZ|057X2_x6u>gSevL@yx?H}w5mbH%PZC>Sjp?7UKqL1k14fm%7~SHn{{{FL#4 z$deJmK8A66J>3Mf7MqL9P%vtf_z*Ie^VJ|ATjii4<6(x{kHAtZej?IVeV_Bi@}E$G zxsI}GvRso5fYkhflt$h9p(CTi-l)oHQO5?!&yt?IueQ1OME#gjl#U^`9!9z>nwV*r z(zDL!I@-OvQQYA57OX{1fn6q~B2&d>x3%^TNbx3AwL!wZ6N3dgoOf7ywaFp!%oZg) zp7nW%u}optv8ewe^74y0Rf+0oZf)+xv|ESusmq{ong@xp6bvPPKIWX2ovNM(S?9C8 zLGdM&tJjw7-@N`GcawIA+4>EFR(17(SimxVxLF$WIm2_H^Q_5uTFA`dYG(y+(FclI zf;)$>3Xw$#LmDp{hNVAsbCD%?3ocj}nysjMyt|Ug{Q%cxL`YZ?a@C+#(OQJylbkYC zj?CEXRfWqW*RmjK+^ZIFw3%bh!Oh4NTZ;_B)Ah8*dlQsOOzN;7j)TWT7jK1pu&yzm zAo9hmPOGx}Zfw`;&KE25kM;ijHbU$)CW#^E=P6Rwun=4l7SFm85EpH^8o(<5F@G2h zo&iBGJAI(1GKe+IN4z93!%V=993XDZsfIWW@0a4+L02@nTqU@>r@h+H+zlg=ZMgvf zrIF3rbLVS;Zc9gFC?Wz~E&#_5e+2QZA4n*>lN8D2?^MiSL!uoe8=M%4_Odq0L`-BU zyFq?hurxcVn4R>!!K=Qh9TSA|i4u@OK+2+|{=qT0vZQa3l88rxX?DyK8F7Ku^WUd$nHNE(@ZS)0s>?84Rfa z1Q|s@Lj_=;+cXB_v(}M>$$uDvbV(-b^8U5Fii)U-iAn3R#dR5?H9YxjY37E8yponq zgoF#CwCx*1+kZl4Q)=S7({3-fDPi}F?0MZ^vyjEJgv#&=d#wEOLx-__NqCeg{bMVd z1hWN1Tren1n3pDT3K22dw5<0H)0$Iumg#HsgpoY|Ko?eTPd2WIi}v75#F_%X41XtNm966YexSkOoMq4)3(3Zz4%V)x<`zX zEj{sj6a;FhqYB-cKtCFlN@rAp<{Xle`#$Nkr5MFZNvW&1jj}1*_g{t@=i#mcU!+Wr zGc5j@BBC{b*#LOqN}i3zJtkSci|1%7DF-EG_`*jjM7YC6Y8o~zd4jA!xfIN(?D|pd zn8)4Ui03x9RSOp1WEf(ZDE*J(cRf{43bTlzN#ik0QM6~Qgk63VS(Ms z7t3mzF1GNQh1$q;xlXHKYLvCS2x!r6=)kyJ$F4*mr`_$~v6_`69uf^pO_+j=jNA)o zjIU^kei#Ul5N9M=UO#XOhD2lZxHY*vyBMb$)&fG$@CJG}qq8ZC`H2J_^`Yxb6$N9K z9cKT*(yf{91gwca#Gk35r_%n*diuxf43+~B@p1}0F1lJ0uM^A+mxbvd=otMJ$yDeD zZr(ENJULbK+BS!&9oV6TX`{@4E>GC^dBl?-4pF16ZU+oD$GVI{e3hP~xHk2l!F{|i zi*G0fa6hB{a}D4{IMtlbihl|oxcsq5+*>bKq?m`fznquH#e~k2GL(MrOww99in@` z&sKk1_TD%Ym1;lV*ZzI}n(&|;L`LRhr6*8o*sU7qxmQE)ZRJ8*D1rFBF0*&b?CzCk z7w>BtD^7#qo#DqZ2vIOiF9nuzmhSexPfQc&A^+Oxa)jz6Ee#J4Tuv#m|GzPdk`{2t zz}4Fb>`sHN@XzX_C)1ly3zHA}mtS<2kp#tMOy={9raxEJPl{QCcvF}4t}F!Aw!bF~ zAe9{xWKT1`y;-9MI&lhsD=Cu<=;w>2#7=>K#W*-w#dcd$9Sl-{&#b7fX8x0>lnMv- zEfPkX?cv@u_2PjAul)yvN$gAhXF?5DmoqI^pqcF-_ptsR<3w%IMw>OxY~>F_*{6pI zEACW2o$cyL<8Vmga4>20gKeomhB+MFDB6O>LTZ3M)9is0f-LiV+W8iwM1bBo4+tn8rZ;c7R+KnGwG-OkQ!r zxb@fOs}kTCmH}-6_Wd-6JHFAPiSV+Dians1%6PfX{JD_@4qRFJaK1d%vG)XGxh1jb zG21%r`9&x#(Gkb-xJ-Lkv5`CQK4oc?b8UJFFgfUO4TJ;Elaa`S+5a~{!=HB!w=?-u zh#tb$v!x+91zszI;FjbyKi*Rt3w>OJUa)LKO(eU+cI2n16Jph&)soWiek;6!9lcQ! zZY+|);Jm{6%85zhAb)+z_wcBF^qtrtR?MbQs-$Znmef*a=D7f-fpPWRRz}ut_BvXE z1LxY!V3-cNtDR|O1%>o*+_atp6lBUx3R=@U4K|T_ta@KWZ>c=uLAyN)ZFU-QYfpEj zPfUeQ`^>Grtz~|Roz(kcoxy>RyrKvpjxvr7m2`i{@Q=w$XQq^p#X|rwqL|?aW+qBb zE;iKbZfCxH9e7#(Pho*)+Q><))X`~0cDOV)h7W2rEq)~4sIn5&Jgrlq?!E6O@qwtL zD{{Sip&)qL{Wff|DVu-O6csTLQ4f>)Li*_MeD<=Bq3|ooy9`v4U4PtJ@v84@4m;=@b_<)i9^%%n zY?p_r_((1p-hU~1^xrxH*m=Dkwt_**A0jy*1Vik09 zTEjjnO^Yh94EFMQA_5Um&X91Ksg3CIwJn1FX4u+>(q=l~ERAxF)C!rmXD8tGrs|!Lvi?3QnU(YGaOTecBZ}QWNV$6o{x7yGd4jU;c zX4U8%>()>lXfI77>!dYxGY8?}48^mj6tMk?E20xhWK#PJSp*OVyS`?-dPHcwuPmKV z!C<5JUo^8MYmkAqFZ=un&F>@O2`UCu{qJ8#$HfV|yK@542RElHiQcbIKsgcupzWkl z!QK>UN|!mF?f?tTqE*R$xLio*=j_`10p2@P)~btlF?;`n+)fQj2Cz$rl)~ z&tR~jf|fPOEbXZN>KL3X&wh{;OCfo-RJ*M`5(!OdH{+ECV&AhDvV^x65^ESyat1yL ze{U!%g;%iriG@9girhN6faR?KaBZH!;w*oD?N8our{@rWT;q>&g@bBsh^w84wa@}% zlRXlw7@AnnMW=6E99+P*z+}7Q2cPXTI!lWaRILUs`u>!K_{vNTfWj#75KK%nsEG5nc9lA5KQcZ3gw(w|#U4e?`jS%N40+ z(kyHx!+yH`@}TZn&Yms}Agl@WS5T&ZNQ!S76+wQ71ZD(@i@{jY`?t%8wlB z$#p>21_$wNceW}e9~-z)I1+m%7v=E)HkZ-B)F4!nb@&15*|)9AqFi!80mbn2QL`T3 zuNwl`0o-ku<7hTsM47?pD%FzUb9lWECq;jJ5Q7HhZ#|mc%kdvyxmF&0@X@MQ!LxQ| zzTx{w)uhwHWChzj6WL6cSZh!tU)7F4l9N6e_v1`4Q1n$#m@wGC6;XS>A>z|+5H7(8 zrgfpw>5KvurTF&hZLapEN0ZDEKv`n>#^#hJ*~Oyu*6x(oh+$*;m|>&LVkft^rt9N~ zw5hz3&WggR)yoKl8VaOHHRE=5dBDx-iyM0s0!QjE%bYj$5W3e#)k4W2un8lXP13O z_FnNgp2(ZG{p;0%i(csWhWp2BNTEYCY!OF=FNWTaE*%ub6TY)cZvzqGd>p}b>|836 zDE2%-_FF=_HI4EqMgcpvd#>Tjw{3T+Luqk)1jEr1ouApRGnFgQt`&$vn=(l}e|SO7 zr*Ww-6I{>SFWu&?1lhf}Ao|Kyl8{)y$(~MjlW*xF=k_cl!=pJ=a;Z%l?H%wsNxC{N zlRr605-(d2QdVFKjko&0S2(b_ac94fVW7s3!)M~V8enKWas9}FvOm`-_olj|eZlU; znMwU?My2Axjp-$3cLuJj2yS<=p}J;($6<>C?oNzkSgRKylYRb>>gMEM$YZJuZI9x4 z(f#S;H@Ga5%~q$-n0EH~CLHqrfw{s#A40Vt;W3K?!6fJNGgnE8UjfU36>hUh8z?_$ zt8~8Qg7A~g^2i<-`W(N-yD-!;%AHydR~f8ug-C?--yjES>Q%M=m~@?n7q#JeFa&hj zvjL34bO%zSn3`rkk;nRzRqdhFKo%?Pnb=as)W}Si-8;btH)#hmimgA+i$C@+FG<3K}S6kC-PTA+f(-b7?Gz zd}2WB>dFJK+KLNoiCp}MBxx9RZ5&|lV~lp_eNS?bR#a;fRtb{@5vbDMB#FAHM2h%XmQkX(+z<^a_(>(Z##32 zFZnQ*b>7^jEY=pK(?yjSxgUi3+PvGb@SrJ!G6#uQp?ht5Ff>Goy!cJOdl zbByYKy_aKO>H0S26Nb$~vD!OJnB=F+ixYHAi^|;1u)?P24%kPh`-nCd1c+cyT%x1S9w6+m6JIxJNopr3}@fGp#Q9k7TQr)ZF zdBnmDBQWN9ujXGRqvldawthKKPUJ&c50!IiM_+Wm&y~Byj8u4qHI2|3$w?a0Ksi^P z)GD)A_{6&u76|r3@w#5oX?YAlStNS(NP8`_UAmrbtEcfis)OynC7Z5ei?k?=i{0yt z*GhWljI-}d2CQ_+bUYiNP62X@t3Xrp=E$Y{_mE>+$C%bTdC~9OI=^Jt0QF-)!(;hG zDKl!FGRFMqX&U1fkWaiZv4Fnoz=#Xd-^1QO8)o5ilb$`fOuKdE% z=~q7N|CP9yRQX64^u?v6jehhsAa9bxR{~N#Hp;lShLk50am@8NQ(r7NgVs|x`cbVY zmf+YA^T5$fKWWcHB=8REcAgI4ZoH>zLZ$jDa_k<`P-DEZ+E%*%L?Y_F6~4tBoUN5H zeJ4woA8zezO(!wsow#RWluLCbpZ?20?Gq`+%i{3ZdVbyLu!E%~7P$EI()&{B{_S1s z4o=BN&{T$TRXB1Ovica zNp%sPFXEuug;KkJg(|Y7iH+{aKf_1@ZZ?HVlJNn7Cg62*7YyIe_S z4gzgA;qW~6G%LJJaID|v86}dg7x|W!&uLZ0J5qhoK=|S-liV6=9-SS>Qb+rk(z}ww zBQ<&pnRvHi$9(krkr6_1T_tlwB$P2VGXm_egn$ z5=z&-Sc%msv~3!>op}b7@1ga=2ccQNm*|pxSHjefOSY4nX>(9GOkV=0pY!=3Ixpv3(SAIPuE^>-fRlXP<#G5{qn`)?LjlyFIoq_7BGBT%8<_c}L z6|?uh=d4uU-p~Kv=&SZ%mKa(f%P2}eFN7j4>Vtht$kkFlQ=1Wj`^b^yVHeS8d(?%> z45hH3K(bz4{KCMquHwb0qAzMX)JIs;^ZodS7(3Ef+4`%266KSr!Ku=6R0y^j&-$n`D$?n5dXvKN z;WNpCD~^0rF*{Zm097ykug@qd!IHU^BfyxhR@ab0Rz!g|BSfh`v{e>@MZz->$nKC} z;q@&YAY)$q-ff`(0zlb^(QQDh~;bXbTzM@mgG=5g*9;<|YLOKNlmp@loyl3^8WQZ=|Kt-*CD(+mBPdGdwE%r)bZ7M;)17;Bd z?d-6;Mj5n{ ziPgu5Yl26CbUrHw>K{Al_@ibEVyEMZTy0vYJ02xamYFV3jerNbg@#O{W%Z zfk#|BW0$UTKQ(m!uosorbd1pal=&3y4YS%U_EH z^&fr_#G?V}HzCO{KBl(U3JVF*KV7c3rX>nsXQ*SzlA{C2m(U^%iYhyWMbp8$mT%$} zOL=m8SM_%1R%FXxSd=SB3%sD@#IczV-fLYpw&azL!3R5;R%(}|mu?URzY{>@-RDe~ zG7HEfRcW`QQU6i4y4R2sZl+uWX@9Dv`lcoj_f5HY+VUsJVY_w1#LL?vaa{mJ{Lv%# z1n=ispzrV~ZF2H`+dfWCoZAUI+IZY}!wmkO<*M4m+{}Ef$M9!=;nqaP=3}F@i87PB zrZ~>&6RP`T%|A8DB&*DS`+fyQtDI_f-Rzc)di@lYj|Vq7SMNTOA}U{DE8UMU@rry8 zc&f7$1K;3IsH8PM`8_O3`D{!5KIU6)tGUgh1Vt4$3^IZ5)75y>nvQMod^r@1AN#rs zy1dStvFr{(uC9BrDYWsG@zS*57XHmaoib9oZ0Y1%ovI{O+GJ3klJj%CwS0i(@M0$$ zuCd(COe}M~wAs4S_D;Q}xa#uMcO!e49^>4K3a1!i?cddCv`bxro;##v9DDf0Sp=1N z>nrMDj&NtwCtAvqO&~B|Os-bZ$V79Yh+s&*K+++`V@S)SC zBHgFX{w0JgrQv=*RMR;;u++b`=0#Q@E<-HWH(b5En72(TZdo|ciZN?rEZqN{yWu%A zR)~s9@;ryOT0&r~GsaNZ5^!!>VX~L9w6GCNgbue6yb3vmso+sF{%q~281oJMh}*_1 z>e=;SILhrIa!c*~8bnAz@M5n(Ak`kO>6Brh%?mtMOt$B_4;qWB@uIU($Heyf+08+i z{A)dHapvu%>XcJ^6onVxc85k+;P;UjJ|3C&mt_*=4bfcf|t?z%rcWd z?W#z&Z~jq_K^3dsk`C(`&V0{K?XF%{3h=mkp!L7{WqF4Mb$xU&F{PHr)8BS~Alg&d zL(DaMARKSFg(m;t(+G&G@jg==9k=M;ak=kY&Wb zowqjb?KiRwQ7x%cQ}x2o+}MwM!EkMEgH4^!myf#)IwPi!y7vCfdt;HY^ia6M-_3i^WF*w~oYvCiSu;4`hmlH-%n8R@sgKX2K^oggA^y@ zIR+{uhOOK6aT}Ky43q8CU`um9^tW{hUK7_@zTfL(yT{eHsY2Tb@=VEVbkSr6`_Y%( zaz3O11kmX1Kn-y8@83U%lt$vb3yWIt&X;O~zuZH`#NXsL->%cnTKvt3)}GMrhscIHv%YqHcEKHsHTXQ2 zP-Qwr#of6)Q1!@zC?xmU??M&X7ZNZ=0mK0Jq?b)EsgB9`htkKpYlV9%S4Xe08E5QZ zZ~pnlonk|^SsB?rfIP%#NRH zgIDC&$src=5mOH6mnSTQKHWEkz(~njjlf}#=gWzBcwXyvu_A&>D?6SLq8_NBd-Ca6 zSWsKnyj50`#!LW)&$xU9Fe+Mw6w%eEDbc4DOS}uoFQNN5r2CnlI5qfgXi^8~xhD(q z>Zh6-mWU=6-g>t&PMRL+)+?oM{-~GXaU9dpsv<&Un9Go5}Du&~_X%!vYK zVo*TVCT@AeXV8~VMnD=ke~W*AQnS)Y0NwLwHw1-N0+mlrK_MU?cjV?(3Kg{obeI`H%<5vGS?VX@589SodHbSMQSbjyYPs(F$bicx28aM=B; zrht){CC@#=rkU&005!OzV}_E}k88vw$af`inOyX@#+sv8woc9=eXJU%c8$yI8&bh5 zk+f>WcWqRyDvk03M^3=xYp97v7y|t{bZ`yv?1mwUd(kj;P0a;OPd?l+2Z6tvT; z?VH(I%Q3~rD@A3@$?KiB_(eY{Zf}Re6xcfswYn3GFxXdP3C7L4m}q5DSA#wgzQqVY z8N(4BAA7{n(M;hz*tW4(s9I7anna58bN?|>=cJ5xc6vFc4IT!f=nEwG1E0H=pIof; zr|UnIWm&o_P~VDxSrggm%j#Lb!BJQyd2jcF-92_a?N}&kItAE6M`>R??aqohUf7)& zuLbc<&f2Xfw|6EJ67cu+KCo>o>pxq$E^`x@zBe}b;x4J-5K2aW8BG-_FrDdWMMx(N@{A?eiBgm3#W(-ZZKvYqG*c45bY1Dw#7A=1INDpAo?~Ta&b|9`^#h7=CUCN`2(dY52YJY@F8*ia0|@uMQ}yq zijiS0Bam`!d1n)bm)=~#lI^ZWn5F8nj*jGPj&)z1tHnYCIs-}sjp-;*M0SHC#3s#+ zq3R-9t5A_41d1FDn*~Fy+vvf6H)CNLP(8uqXltO3y5+!2iwPgtA-vVYvwchJ)lsF{7nnyx z#{Vw#Sq@bK$AZRGMsVj+?jZIv%&cL&*WcZQtFd962KHCWzq@g@os-fbpQJ?LV+MP( zg_=hn>yr#nyGFJgxy&SaA#kq8^KyC3;_2 zzgh;wd?kBkOpgnJeKxMF>lxDwbH2PjA1p~!Hm16waja{m2OvvzY$}{PqdDFKRx|R2i`Sz72$#jf62e^5u9OsmA1?k zd}_#*+SoJN@%<4rh{MOr!5lsWZoN1RoBXIv`-y6JDWP!so2Vc*a{nyDrqeU|z3Wo- z7P)SL2gmPS!4Otlx?Uip@n!u+3>ig9HF;o1cNj~#7EKJ&0a`JRbU#r-T!(mcb)a=Vt zKQ*gj^U0P%@~-ugV5UYA%!TyO4qw7_IOPg!KL(AK4=O#Vmm~jVj6BCu0>#8%1z>df z{a>WLWl-GFw=9ZlaCd?QcXxMpcXtTx?gV$2;OLLyziD(f5jG1;K7xACJx$<7dlNp?GI;G9iy*2I^k}pAyl8n z=)S3c`Qa!q*TSU)qR`&i5c+AFDTsCh8c?BlstTI&UerFWTbCzwr|fAhgnKtj(@4-I zJ&^&P7*kWCpyK4zCJ8Ae5-ke+NMJ4f^G&HN&(wHj4Sdd=6K_CUf*m8*qU|xiBjC8;io3}DIk~;L2pb^L0p1Lv|3(Uho);>+ z;39BWe;v4Z2?i=wW*kN`4Xz4Tuwc2JPn8v!hGvi3!Z=79k3#c)*q_3Jx~6nNPOluUIKHB=TlvjA{Q5H6&n!`Q(PxbH!C$e!BM zkla=)$LL-SDaGd~`D?X9;(X_LOk%pj4=%mV_gL*)x?Fe^K5$3*wrmY=sz%qDt+5Bh z<+cNlz5qW|I!r(m;h!%icup2rV?a!ZnX1EYMzFlg>02f{G@R+ThXrA!661pbcRBDr z-U9nIpBI++Mt%7#sM(CartVb#$PCX~#av_xMvO`-`urH?ZHyqj8kS}DEYV!!)P-)*@tEgqn+AgBq4^m)#iMF6}@XLDe=Tn|@l3ol$* z6jjiKKzMY0=2gJ)i-{@SOraN4Jfl~X<|LcJ);@(yE;c9DEmz&QYMpHL4NOh|(mSW* zUVDUF*y1V(I|@q1!~aH7#ZQ2`IN0tE!d{Uj!A3){>HTa)Ldv8BWkp}K`fzxO+9mkt`ST52_Z$H0kvcJwdlCqU}zdmWmaRBRCT zvjL=3J9u)uTZxkd_^~l$=R}~zK@J(q6T6jaPqAGS_iU}niEe+CWRbf~w4`O(av{dO1Z4IOeX|!q zw)FwtS673a&my050QIro>l44y!dbQjR_;A-T`}G29c^dEc$sQAta@U7{8VV2eb4NV z$7CuE%;I6mqPrTz8~pv@*%6 zZBy?tIg~vg)OXP)Xr*SYoB!O2GtRXR^kJHdYdZpSA{Z+W4TXV~oq%@qU3gx} z(NSvHSFzV?jbv7aff5w41@wJ8wgdH=8)!=*lAtrc$t`!W*Xx}`w^)^!raG&5@m|iN znQJo939{+*q%r9Cx3DEP-<9U~Eu;|-*wm}TmoZvz;$Vc1rX%!Bh$FfH40eQlQ)ztO{rxoB zd+7iEx{fVOp05J;+XmP9=tw}B@shot=4_*G%@Io1uKaHOAN(eX#ankRK@}AQ*aKY< zR4)i-E-jt3Glh-XX93O$Nk?V$QslWn#((&VRqSHC)(K`pN{X^K&g?rPzDdiZH|C=^ z>Wkk{lDSIl)`+veE}#44T^SGEsxBV0VWWq_<)!L_uLPjP%;?fNH8DIf<;7RxEHfoHH`F zL2Va*4?^RM7RBi@Jx~*CCA;a-?~PTX-48iUMv-2r zBi_i+t@&T&#Bzl-m0>eSH>bVM<3L`K+*FH%ia#ifslawEMLs}is-@}vG+%hH?V1Iv zDpf^uUmOiRhTN1f=}M|(Zd|LX{eh7E^T|e*!++q}gKjN2*w7m^6i(EV7hjJz2TyB@P6X8cr|xD#epIdizQ` zUtm$HndG|$;ZOmjW<+5*-kBCP8sA9q3GDenlI%2KAW|D=I6p zi9lFXr5*Ls%>?&n}S(Z9;^}m@zy9rrFk+ z-GmD5E%PUT36;ROI6aip0t2N)^ZD6?#tI~hZhK!< zRW*_IXQY=;gKCA29|uqO6vZ&5R)x)O23x<#6QOVTG;a&7Co9 zY~<(;AACj$z_v9rRiGiY@tQL%)B!-boN3;*v?P0&|ITh39K7C{!1n7$l@X;xg9=;h z_?jClBg<+(c{N{mnH7$lUS_n9MyUMF8u{!N>)EYW-C0=z-{9=)PqUO)M_VJs`ovLg z2Os&XJCW-|6(WrJ@10nIJ#2(4r%+oTPsT2>?SDM!A1)vSdjP!@{7ajqF04%Gj4z_L zoDhz6xzbI(SEf1$Np&SH_Mt8-tevxlfuLzO#}}evjJraTYfl$6|3Xs#>^Cxi&a?zU zXZF+T<8Q~<(|L{4OMC}7^GEZ?b*x!zG4otA=$E+9E6VawYoE3?oDX`lFQ`^=|Fg92BLm_R@G?c4ygiQlL_6#CJRJ+2H%8-#imj zC|FOWOvRe$j=--kkjLMPF|e2ghS_{RDXcEu$uCVe5KMSxa^!iXg*d@-B4VJqZ&+$C zG&P`4q)S}wrwC0sedLJe;w+(hZej60?OT%o==KlAnURIlW$x zE9+SttrvNjIxqN9wU0zA*@GH2rph`&wEeX?x*do`XtMtW=V&tyAu%}ZrAqs7$!0|` z7*nf1#BqW_NW>DZydWy+0;cEHN-iz3@dk4|H82%x`t~#KcDxY9$KM-5`I%VXpfPol zp?f6zW$HE#=Y_Laun<+}=RvxDGL4tEz$;y}Y~1zonY+_OuO0-s-e~L%?T3IIcdstiHPUt-vl;jOc0r=6Iw0o{(b-6@wUK~G9$WU@2fPQ$9+Rv zR6(*LBLAS!FOS$a1KdB;Na0C7WBzRpqaWkBtl{53zGR*P8#Ox^!vMK&0a8nHzeN$q zD1H;gJ$2>uFg@^{0KrWxXe#=eg3PR}fn+Kb%cUB^_UnH?Em&XI1)6=+yRZS_B@H&Q zyYex4U#ckQ*(0 zSnYp(fsoWGR?@vSrneia#9qnauLL5F&K$Li1Iw%i(EQ5Hn=cGhAP}fHqM|y%Uy%Iw zV*ie_0r1zrYZZ1H54^2?zwR(Pt#Ys<H}05EaxfQOPJ~1WFqtcCKJ$-%rEu88@<4*%hnEs(%Ao*cD zl{?3R>&i`F0{HbC7&?HJul{c-96v{IN1vwB)C`S2-(O+~`Cb(uv3j(d<90T(8qSY~ zbX^zJs$yYx49!tQI@xzB7M;!o)CKjWAd6~jhyQ_?GlfGL@b~`>tk1bi{SUGZf%V2x z_5VcHd&50|t+iQMW}U1O2&`$jSLj}EUij<0m>QS9){cYGTpw=(9L@1kOCSt2Opu}j zkNc%55F@3GQs&#B5Oi{4g2$vae7@dUIIF0Lq8($koZfEAVi0WE*zOsEP>*W7%@QO_#gd&@%+16H=*mVr-53$pT4xBOKh4 zo%8>Q1*(8nr$SNH^Uf<9U8I67c9@>;sN=H5gQo0O3HNO1k57Uj*~k8RhU)ufk0j)R(h_A4* z!B?&aOM~Zqk*y#}y9^0hmUZ8r@gDnE`;?PVK3l*eT|Z8?;U7xSig3HNTTP&kW6^xH zUIL>ISbK{*a(F7fNwWw^y9&t@xlMx7a`PpzL+LByFyMM!O=;j>5QC#q1G$+x&o-Na^LdRAg~4Tr!WIDe(i^uHm8*B zK}C4#4LVzqpmw$ZJc2GAkD4`*O`99UtWCVYi^Oj8d1oK2h+0FA-YP0$qmdNWnjSRu z(GO>Qf-A1U4H*rl-w$Gb(N*XT2U!eSs}GMqm)M>8d;O30J?QJFRFUbKKtVxWPUjwR9F=c9ZGdwN)8(mn?zh%*fLY2>gmE||P4pSpL&1Rle zQ#aemrmTcW<-{0y_&D2)l_;iL15vC3PtO5zc@*8MO zUXN~lAATbJTC6xgFi>b~-iSg#AP4lo9vvMmE-s#~GZFzha-Y&KH|B8I6OQiJ{>omD zRct_BW6dau6=r%jTl&VM^SPD=6B~(=m;9j?nyY08a2F~|_WPm~vG<5YC|z&FwvCmv zUrff1ZW9DQI(~Eaiv(_$Ndlk(Y_pq(fZGLxzA+}08d#0qfv&qTxNN6Yttn)%VmAV| zl@))1by|9>$M@y5vX+vDW-pe*9GG?#NITX9G)9=bHMLt%(`lB&mnrkHr&Eo&k==cmAa6dfZ|7I|QF;lgT&f0uDaC;N%){w=bkS?Rm)no^0w z&xRX8t^t!@t!-mK+=kF{KwW=i{K}b2Q)#k=HwBXkbv2!`=%N>3-iWU zAT5@3(}@R8i(|>RCY0|~9;!GvQ=`zuZJMp!A-s@5XvXR58&L~N{aW{En^L=9cZ$5;V2eD6k|hCy*08XfhW@-c32 zUxk&NpcW6n4iJ>IamioUwk@w&grVcl_{~ zI(~oe@_F_38P~wJhbq% zIQ~P5`nQ%d*=(L)&uVRas)Tzu_K4qUZgER+hZFVK; z%MHLVLZQxiVaNH@r$tpv;M=6LH_=S&*+SsD9D^5Gd2ck1`|f=gcabG#{Ud1Tf+ybF z6b9DJ|4_ZJ`zJOq(O?y7l&Auyf36W+2kkI^2KKvv(h-o-zYa@CTj-{d+ zr|av!`ozmuf)*vN&uZIT1gaaFOHJEOJ=~VpcL-l`S zY7RdZhFYIQE>E|94WnRw<0kEc-Fvnjv(YtUW!dju-+Ky@#$~BxMrA&fk(Ph`d|CeR z@xD*|%2w;W&+%|_(DS5(3m51N=eNT{GkVC2yDrgS@_U^sUh-L8nyH8r znK(z%W4^;7viKXok^#y={!aq|dni{R9-Bl!OGE$ru8t0IaN5G?w5{P$&KPAMWM;ANL~q zFfklip-rNyCgzmPHsR+m-u`3}S_p)-GrX`yRO*ktoX6_X51WP^W&Yrwh za@1v;1|pF%4sQaD4$pSt$Ye!Uah((adshR4N21ci-XnH|1$!6y%hEu=^y98-neN zGbl!KcWj2P=7?XQhG2kXYTd>1)bNHQOa|1@Q^$Fy0A2zmZskOml#bl6B&0A*@oWW4*R3l6W;7Osq0hp zM}PN*wOmHo6+pvy$TMhxz56 zrWD%e-`SwGe!~~lw48U%O_n%+cW4L?4)QdV+}13s0<_zr%zDp`oxByQvX|AwMRxV> zo_*WEF%+XUZu6Ls8X8_S!zkv}@Iv1&#pP1*7Cb;A+E!VJQ%2zPnKU6Gfz@I2{T7b)9YZLTx=1`0h%yuoKY86B zD}4p2GC=?0oDPMY{!=AHV+F%*6%U$MxP5IEiLgL&esSPQaPsxd%0h0w9 zyg$5iTM!Flq*#SXw_W47$9P;Xsi>%dfp3578(>?kGN#C#p{jg$_e|CJ8LlM99*+#R zcI$J_ttqaQj8Rz>^PmM+L56~7{)}coof4#s1c!`|CcIS)!ipHW#jXa0X+Pe@kGbz2v*h+%Pq%2KgV@oc3 z4+(37D#{+xbG7@Cb0wo`YB>D}_u&@|oo(&(ENbWDU07V0NyT}Nuf5ae zbUu$Uv0seV^=K%4q{&a1^$j4^wLIxm5n%-DszeXsSXr*ye2b;|T4?Y7o2gK{)4KJm zz{SRAm~P6$=V0q*3kNSEqb*S(?>Gu2-yMq4}h!+shf9$eyNLoFlYUz0*9>vW!a9E9( zj+W5h-;;P_V$vU;_W@brsO64OPo{lI)>*PEj7b)FB&L^`HM%zRB3J!g?1kej$CB&$ z2Ccp#@iP|qI9++FQt!M|?qwvCCk!4yPL+&i6dX1FY&&_+?+l#c&z6KAu=1`*Ku;E~ z?fW>+hkQjWjDDeB<-a4zF7mDTk`k zlz8E!^b*@D6Jq(*DD@$;IMZlF1`!(euD#{;nsN z3~mHED1S(Qj6iiXe>0w7Am1-FyLAy~*RBmx0bMaRGc^7HXmI9;#!Lh}rYH4(;KBOK~q-GTm=^XV2V)UL!SPSqf9h(ExPfb#n zfqXJy@)9DIQ8$nk@Q4`povAo^qWeTe(aQJ>32J?}I8$fd==3P~Nz9O2x4ySHLtXhu zJJ^6Rb$dK3&)ew=W8_~aZcF-!UE@&P_kev0z*8xs47ZUL9}W z!Y<0HbAS5>YuoGd@~k{}W`*c@C29I*QK2nWB2DXL&Cbn??lfxph(k8&)x4ZJ~v!NYN7aX5+2W&C*ijLZ;cMX<^=9ZbrQsRs*8GyCBr z#M!D#k9F1kw0VG``OK052aHuBW@SwVy5P(L+t~v}YkD4Ss(1P*pR#-tJ>dt+f8uB+p2Cz&Toey(83*UskGQiwv$Eib@B*hn2G3CV>>gs2rvH?L?xtu)X?hg)k%U-6I0!W$$$Dl5yyg6~h6 zcbbXX^4b|lomJo0$@Wx)5SyKBuow)^Dfc2aqV*~VD9R}t67;)qjn^{)x1@;9ddS%5 zf@_C6-{e^584#3aXPAcicdJmP$@p@zAg)X06RyK!yE{%oYk-g_R^WdPjREbGjJ*uL6~sDYlU%AOd>M{7;1A6|5G zb*eudP~b{7n7oLUT}KQETDl0;A(eW*fPU=Wj9xX_q+TKV3O0(nEWCoRy;0i|rNyYs z;C>ZS{@{^V9Fg?6_OPZZY}u=9hTqMY3g66!&ODqUv>mYBabM2RDJ;`m%vh$TPD$Ewpmu<7n~D z)#!N-y`4N5f0HWMIunVEFS{AIx%AKS=WU1*kNfQZsR8*>9*{vcHj=0?>h@iQd=9Rw2X|BS_*Ir!ok4-9VIK->hkL~vDY_*C$0!BzO^tnl%^!G zbz3pcRGWZzxK?@U=t%Q6D$DB{8$Vy0e-ki@BqvFR1sAc|_&PCDO`KSF@nx~+wki;{ zw8d^6TJ#kuu|pn+aViZj0D@G*f^UdUO;?IPJ*`8-!5D}~v0c^DSYUN*vC$?~iL_*# zqb(D4=AS8;q-J=N(S2Wayht~=hi0l(><$)P{NB+aO|`!FPRD{XiiS;p%;to=C!%6w zj{qsuNiRGhMla2eklq<&hw0$(SkGJ3HbO z6>2p9qaj+(`CzkYmGmZK`2-U%hK2K zkQuYT$BmF0fWjqsXR|&`l3R`|GkW9r%*!-+W8Nkc36%!_5u85jv#p^|0)BH6kGP*y zsE+J%kE|*3egz2;KoOZ`-J(XgL>}@_QU<;=V%VqrZY#e-Viy*2PW$8Y;N_hCW4w7K<>SjOIgS4&Gaa zf*x?5@lF;3lNy2O(*GL~Fpk;k%JpiK;JOuEGEwzIg)YeF9P(*bL$jZh|g3L7xLUFfB63; zkRudVB4O-+9sMypspnny7j^ZxgiI{=anS7)C4QM1a^U>s{i*s=_8dhfz?~!G*PcYp z|BZ1rR_DWxBM7~9ewD~vei#*@Rezi5Pm1j(Nme(4W5I)JG#58`^j}E#s77OB$RP}+ zhXdavQxrf@O^E}gAjsS0!GDG_Jik3P`w0BR`DsKj2>Mh9ySbtI;YSkyZnFbo8Q=!8 z#*yb-LQF`!B+!rq%D5ds0__ipK%H4ws6Dm_1`7iH1ojL_Tds$7d)`8Vt}$crIjMEW z%a_~iKYf}Kg{}fSUfF*ZmI~T7G?rubj)oh}B)bvO_3n_xhE%7~ELc-w_`0VP^b-i~ z-?C`5{ha`vYZu{nFm>LdtppYfYd4>a{d0qZv!`f_(L|fXgnNjT=ra>5PczVU|Hpbf zG5Gh86|!6PsiQNXw8J$tHgzB@@%i>lwx<&EU~knh>F080wcr8y=JHwI`o^nC?iT<- zwELOZxA5Zp`JD&xZToMBLL@PaKNE^3C%jr81d3`K2s+VkM95Bseq7X%1p*RFSClxl z{0?7ERmV29dvmm$Rk5FPZO3gtfUFx;k{OQJjk}GbCpy?S*DZ0WMA6W-Xxh9JT*LoQ zD!dmJ2@SlAWmtzhr&Hf?AER$*cle@b6Re0)J3D*^!~#2^>$;or)_tTpn<4}+m_m~G zAeX8t-%s>FIzTrl!&>DhDc~W)K#T2b^)Vp~YqOmO%1YM{`UnXXOxt?NH`V+iQlRB@ znYwtGK*brkHNPH&TL$%}a!8e@Ezi$2Z}X_i0s z@OZy=a1k*pk8vN2ce68McwZs(uDHkbXs~YMOj))Mm#1oP?q%}ojV&m&Iuub~Kf-H! zy0Vg49>Y~fbUtvA1entD{1uAE6J<-=j2AC1`ht8N7?(k|zniSs@ILfQRIQ~1^B2Qz zNC^DddwL+3cNG%*9*#M&+k5pfo?tTMVTLBuS3u_4kpTd-4(RGj59MAx9|!;5ABx?b zL6JH>cXMpdF9gF!bmT6m`o>E*U$nNIrY+>6i!Nj)_W6X5NJ$+;5&>$gxHBUDRjG`X zKUUvOwVTy1%)0HW)hiaQF&soeF@)mZDB?o|FTESH z&dqCAGPa14;vs}l1qH7?@4WPRGIEYGuEr5Nr|vv^wyw~KWHh_ulH(mSvAz_s7>3F%y6 zR(mY>pt2*Dm)>7|^PPl;4{H{8Z34fHifq%#ae|MXVIcs(1P4Bm%Gz2JpkdlShS+0` z6d490T+G+^LrB9J1qR|n;_Umj)?5=fFbQd+CAe?9XQ@U^DcN_8q5B^7Y^nBYrwY2X zr6n~z9Xn>Y2l@txy_vk;pM=kU7C2rsFC``lL^@EDNJ&Osx%0KI$;fAiVqNifUIoXo zWkNMKD{8?mEGR0?ytvy{_tf_2GlVznGauVO*ViMX&1n@DJ)q*iDk*tI#>_v7i5`>l z>iWk<1?fX(poJ2z5fY3ozo@)aTu;fKUcu!^;Hg2Ds$dc6(tk8JW8fq5oe!MM%g99c zOzl`=k*r2<)GYC!lSyF_prR6!LnbB?)5-bEDJ(s?zWZXMdG^#gSWJ(ztv7g*KM~fg z7YjNXHvqjVf&SQany**^^EckQnwlfa_0W+FTS#I`miG3*>4owwH=q%-F)QwqTnBs{ zWS}50r3)g+kI{CXb8`~~)KWEd>8VrS)|9eUm-FNpXA!S2pC0vmr6{f2`$1W~BpN0q zW%~;7n$)n)1)q})5gGYv>!O?8(`&M3J~srBB^USfg;L0+emk7y9YH@rLZw{fG}rmQ zlOfztp%&9|+CU!h2MLtE1(zNRC zLC27gV=xgfZd3FA08k*&Ju9P)E7?rzd0>L8a)%RdNUqqOxkQ+$uvfOlOd}Bi2i8|F z4g(MNUvKGSJD0~{FL%#wu&=BtM6WZy3??f2;UW=LPxM%X(=jWb6C~yMcgaUHre*dm zW%O1@!bk`NXFqwH0$h;T`^|j8yO-;f4Ms?=K;B;g8rsjNJzA=Y!WlZ04EAIezfa7s z*9)qgF>Aj#%g3ek6lXqoU%qa<{$hbE!=Vi>i8_1_hLDhL9f7$0m9LWaAK{pLf|nm| zEI+r1My-hS2V3!o%woFru`nwtdAd!kt?!q9U373$(k+Y$P0E;~a>+v<&@(u^s7jM2 z!f>5oZu%e6Lq$ud5py2G7!~9In=554EzduG!F_*#LpX>$!A*k1oR7)L$-w72Qu(h1 zYjO^bCrT|c;L>iPx$)Sp7Ee9eua)#-VxC@}LX(n1HZ<~Bc(brPBqo5KL^i3NgSLv} z#dZ(S$d8ACydaAINE!;u6fL-qIKHJg#TrFg4ailXw&^I_=* zT$%_gtH6cIhuP4~G7mShqXs_mG&-x`<=n*ZvGt`2O0d2gkvZ0HI|=U(5K_UEA)#*E ziMl`oIUpjh=DN~KiZcYX&+Q~{vbM1yrJ;#-+8ZXo@{Yr*nClypIa?t>9cs4t!CcIc z$3HZ1WT1W%IyX2^b&?G<3&HNI@3X$}l{@<@&cTFYUiC3@N)KFfK#*l?aD68SbB_lB zse26tKqE7a4Kvq(P#K!Ebu&L?3(ZT|Y`dLOL53{a&1U#?@OP8e>H)r{e zPS>rIAbeoPeIPUMcj_b&;J;@9^3ode360^IpEueVe<>`di9h_3)?Z%@8>lS+qbLfD zxJG79B1umsnuw3+f&S>BzzVfb5zLCtp@aPfd%0HkZCi`PNZRM4x^V*$ z^qF6Q%iv!R-m0(@X+vR%ex?iy5wsUjZ1t^XeKeVXhST+k`j#fT0~XdVIH7Rfr^OV} zOhOxUZSIaLPDbLQPe<9>Do8}PNr;#e$Eszxj@_Ns<|j|%&RB)CxCmD;jT>WIVZ4#q z8n$YCbl0izZAEmu=?hO;;`n5fPY;0)+}1a)9D)-_OXEn-KBq%bFE9maqn&@Yte5NU z;pFtkGN$FU>owa5_xEG?mJHmP6yV=!skOuC{`P-p#0uDU#$kXufP^cEq>$56z^cI- zJ3JaXJl54O_feIW{PZj-UkdCcC(X6d{hl1E$wgChC85_M&g5GdDQJXPC@C_jc_I5crcaCY&-X=gjN4e34~}Eg#RTC2-lJ z0t#v|Fj+$yh@Zb3M>IQ~QL@;mtKR9w!BWKWSJ2jTFePO9Jf>AvKW4Q;{23>~uMq6HQ6WF4Z>; z>`JFm@`tbn(UM`}ni$ zFOriX-S9M;n-olry6mk-S@AQJ+KpKj?$qhCNuK*Iq+9luyE=I>Jp75ER?L@~;+yO1 z(#wmeW3qac(Xwa)M+Ol1sNzde=%Kjuae>-Q*VCSpx3~FL{t0mIr5D@3j zK)GuND2R0&U{?0@Xc#uocUP*$Cr5jWMjx(XX~fa!h(?eje1x2`q?VH>N~wnPd*uk@ z(5xEA&KTj!*f9;kVJw4lm7`xoUu5nb6uE*=c|@}7C6V}X{rp1p4Iw3g6@ffo@yfBW zr#ScP!g0nUW-$EY;x==z)=j1)>K>KgY7us=pNRV zj8l}Rn6#tqGpLo5uk$P{e10^1G#10*ZZyNCI{_a+xU-H}>K?$Ot@N-!T1*<-%PiqM zN3LX9AsnqSq@+Et#qM2JYd266+Th@Xzw(#-=WK@M_4SU0na|9*g-vMMic>-Ig{`3q zUdV59r!AbBLDcQ6-`*abEhz_Ppu_0+??tJk{Ui1Lo9eM8sUX&A0O6J)7KgA{2r2UX z(UFM_>%=T0^1?wWnVhUbLDr&m`<7O)Fh=oW>;%rXsVsav03VC(vaVb1XIt)u9X&gT zi-_g z$y#Updx7qG#Gmh(qd1*G(QSahTHvVIl5wuIUo_ZVypJ_ca@Tda9)sFn!nvq$^gbVy>& z(@xtK+y!x7blOz!`smSz?GU!vUe6sfc3c)Y54C42R|L8-$%;AoP+6gmLEekslRPta z1UsZwV@10ADXZ*virGZlae}n5=X7Pi_H|F&E;=vI7B<7VfE`<0#_ZC`-kj*3w}7)A zpB$y%Ssr`kXCC*7Z_lRZ?SOvi!0nKoVsuO(Nt@1YxB7iSNex46hTKvrk#PhX3qGhq zTyRElO)Qi&hv$hWyQ{GwuvxCp-Ueh06vJO(>qMMog^8K9vdK$TRj#0lDFCiXZSnRG zUh@WGYb(^W*GC!Ke2*Uw8BP+!8$*Jve2l4RdeVWNeaj-Glv7)oQeQS|pCfR3>4q&t zXXIP(Mm05^K0*-x-<$x`d}5mH2*ODkZ^y9nP)B=7WNsoTMd!VW6g@JwGck(m@7bMf1{Wau8WG4VFgOtW zMQ4#z(P||tZ}uto8if`Z#ayF3FA5KJ3tj5`F>QG}V5a*^y=Pr@2=BMPPhw~#{kVnv z9bwJq-$1N*VLM(gPu!Z?mfJ!74-LK+;iZam43AMX$yWB#VzN%)5 z@?45DCd_}y^4Nc1?olD%RYq%fvc=ysj+N9$I&)jN{Y&xV;UXt(e;pVyMJQxm90>#N zv0>-aJR#pm7sfK%FUe%XI?uu4?@2zE{TiMWpEY_lERkT%6aeIpW^whk?Mh`&-m_UG z4(>)NKd$s_;M#2(har!!93zX8E7Mw!Gx}mMCvmg-*RvgGh5sB_A5;%{KQE*7w9Jf@m+#(*H*cVV1LHBAWojUGU_91% zt2UMUWY*RkFTCkHU+0g5U(7qB`@MX(Ql+7PJA?WYqK>t(A@-a;cyeCnzVhj_pO@{1 z%2m6J2TFZ68pqG;ulhz)ZXVmA&Ers0wdx*+)KqD)USQPaH;h4>&Kb@l;F;S_gLQqa z6SrF@USGJKtbYavAwVI|ZSGDpc^iebHy=^7j_)y&_Jw(PcU* zW6Q33jT=%!_r^wqcrw&NZ-q?{5OH`D7Fi!1Y(v1Nd11D`s+75;8^q465X1H#^Hqfk zE8Nu{=~MuitiMcZYgDTOgtV>;eYIu+RFk%^~06kel*wO7WHfa{S`n6@Zw5~YGQf`JsVOP=* z=`Py}SVya{6xvat0;t0fM<`rVZ8SRUrw*lf>~zb(Fx-|G!GWP8U@~N_T;Q~$xt#3I z<*2?Jopm8B>B`B>x9j*o>{7N(m!)IRgVC+tCZ&o(ta-a`OJlSy=4pD-H%d zf)=CW4piAjVi<7LSNw0n4nI&JQAI3YD0O6j@Ul zP&wnZoMF=CXU_r*xcxke!qiTPh=8@Qw8X2Wx60?VB<2xF$&;5Z>L?Ct?I|C!g4tV- zq*~`%5!oq?od=&BHvjDGiiFAwV_O`4NMe2#(7{j+o^V&>n+ z8}f7V@7|*a15qu*-T@|tO`B|vj>xY_Bdb>6$Ac$fVY&4;H|BJDAjLt0Twsm9Mwr$(2Bo*6EDz7SKk_rl%F2AloOASN^sX@ZXRSUc?fm__`V|dbJ`p-W z$ol-!Z(*yUD3TU~%jNog9tYtTbBw;L4K5 z1-5d{1B+GdN|82hswXW}3YU}7GeaA*mn;}OARm@8rQW{15agr)sj`wpnq`^;+{+qB z{PI&L+|%N$RZxDF^MUe zik2=7MHO;K7;-NL+)wTE-6VEbE0uUU5|Kjo|9NDTc_3C&8O0v@dA;s5NAk3^e4lq)B8?7_GC# zmKNI_y&DS-Ae@hTO4%&yGO3GFNtFSmDE7^bosBI{F$~IVnD7WC7M}=T4HI!N7dDGn z>8Vqv8N}Z8nwW$?9S^XUmIr;%h1r&d{^Sst9gQ%1D|6%W@&P@$MXfZ0Mpe!l*co5< z;=xLk#x*Cbs|?iWFDU^luKoE%AKVwGa5x$BL%`8xQ;hi!VoketF*keipB3Gj z+NM|ytV&Rr2iQEJHjI|W|Ed9Syc1$oHh!KxgMZMJOwHH4@}mm&G3R!> zI%^b#`P=QJJQki%pk+ER&d+uUM?833a^2)6PQtkZfQ?rNt-}wG zos_Z6P8@3h;j|xisJ{)&p@Pv+#uvw+;W!EBBY@+J3e&Sqj{BBqBEiPEnc?^nDP66=i>Obm6c9-NzT^pO3LcVuqlUzHoFPZr z%@Uzh&%++E+?(<~Bhs$qv&c|$6v;0h9-|-+Ric*IcEQ0; zFftf8f=HAQXW^@k#gPRY5cR39oHgH^Qkv6YW=K#*nH)^-uaUxv_Vw)gDOwx?Ow59f z3VHuq01^RO6QWD?d0T}X_86{FQB6fc$;(1gT!~a$vY3g#CsN)kFl@&*jUKLfZ1Kvf zq;ujbv{H?x7z|=aW_G}5`2!dSG#=SXOhnMnNgGI>1;r2qEh6|qtd6HjO{F^# z44$P_l!=jJTPE<#%qeF5fL+FdKR8nc4nJ?E4mHc;BuPu>(zbi81%7C#lqUt-K@G*S z1cX#Hti(}V4-E7VJQh0o6rGaYNl6$Tb_TN(8Y|CLL}7hbcc`Q~$Iq!fK1AP2EtP0P zia)?(7@<>0<0Y8UyNL`dW=s~zPsy_%NbPr7ZNU6%MM6X;hs7uu20Pz~wf@bCuDmSBN66h*+=CRCt_BwXx*iG1gV zvFqfh2QVZWD(8cS^^QmVif_GMJ*Zhpe{_jmQ!joMO;aNOQd-l#`VHK3)Q1FxFr1G!3uubqi7+5m*a6zq(O*?L_qkx0I-BVYn;a`+VigU|XK zNb2x#DA5keaP%TUr+FuU)p63hbu6m#jCE9^!YwWY)Xaq)zGCFl${gPhc1IQb)zp(q zNtI$)L;KZPot1jcAzGHXo}DhRSq-u(ONA(!wiMo=v@M{|Pj&i=Bc{C@jsRypXhocrQN=UP|cSw&ol&7|VqyRxv*k|m#5lH%sPA|g0doI@51!FB6h*Go>12Qj9l-oci;ukP-ES*zpX zg6$`Q>opsEGtf@$>eR*~O@P0MvbFy*0%>t?ZWzH8H4@wzycGUQZM*wHlB1gI1ZnNu zk(zK4!kY2#GZ&}hGDar1rFTGI@t)O}fe!;rG7t3xnYSW1gcOi(c&5cp2K}_m@vK{b zpSPkQAu{+IFx* zCSo$o;(L4Hx=`obMxrEhPcAiqevF*iMH7N9nvO6Swc2*FJX%lN4M6_Y>*Q&pumRM}*=goPExiek1c)gqFvsRY4z3zhOJ3ttb8Jv8@wf$zw#MkP zl`ht}_`r*w)u&dN{`)q@3PNTE(Q;cq)Dh1Wv9WlmB5&4du5|wnZvD-PKSU$IC!9zw z2NXGodM_f5bvdl7Cv@n}yty(kB{I@wB={OqG?7O|6LoH0@@%n9m6q$)lHjDumWENrzp273qyR#a(8t2sI}Q`&u8=egS?&!_%6Ju z8LrGPAm`mW6;tjo80QiChvJWHb2)%gV`6sP zP$)7}zqz=3;now*gnImA5&)lmT3D{@P8H#H2Z!Q7i4UDBDft&?pOC^fA$?H&%go!R zfC2*n2Fi=h8LM67yVAbFl(<}*)Fl+0nCWv5`QI946w;94uuCZj0;`Rh&nhRj5o5K@ z&w}*S96w+m?*OScky%}CGPJHd9UQc&meNZX)h>;tQ^Ore^W__d`QwZUIJRO|c{kz< zRCYH2_--Ucl;3+3%)wBYBbm#?P8Qb>CuNAgmj+|`bPU&SG?;ydt-j0WrX)LjlQsYpSua^@Hvmq?K^ z0YT_&)N`4Q7K@J9z|JgZVc>nj8jF`T1kyb0 z=G2u}8xIC}t$$RiVi~hDJel zy_PS>DZmVwoivL+(ln!t1!vnYU)aw%*UvN^sNtR6&kpdzEwa_;Q>5nQCdx*Y#Ino7 zXq9IGJK_?icq#&wNeV|so5*D5bUNyD?n%$HNhI6;{dkN@Z*X8%%Og;1X13;v(|6|- zAM2o;cUK_dq6jC};>Da6h=Yx5Lk@Ih`;b5dB>`RR2x5aIuTH>#X*}Ta3;*k%J@Q`~ z@kc!MkLkam+WIDrdo;D0PZS3-9QLY@tfue-{cdHg6Xx;j!)@_cMc zz_XG(5W|1PQTEEsRqq3kAHH~acRY-^eGJIz)VN=c_hAkrB6I|oB(P{0;_`CXe_dQQ zWIZLq=t+$pW-@E?QGi!e)f9QV(GF$FxKpK%yNJ$vm_$cc4GlG#icc~Ea1v3)jX*eO!bfPV-F;w|;1TfFe@i61JznXk zPuh7`=p^O+=^22-3WQO8giprc37?5IZ9d$;{`&>$2yG!iIYEnlH5F50AWFW`nsR4i z!K02iwp-AEVkK1Ydv5$LHD93VvijhayBqi)Ff9cf3Hz#O6Q^vQ8t3SpV^<_y8 z)t%pFy&;Q|lgskd=vY{?pZ`J`zvaWUBSAk}ZZAMsB3cWnZDr=_r{J3|T%(yTHle0+ zhLagW8W?D@4WqGmNuO6&W>_2s<{oa^ICv3jIy%js?fuQro!K%sJKrPw=666CtmF`@ zsTfZaJquV6Tbrkb`qglSrGJ{ZY?R_i8ME6@4ngM1#TDL{_dhfkJnKEsk>f8;COqnK zqlaS=p19K-h`3vCZ)P&O{B@Wi4xi;{(^RzkJwd*?5BDA?r@2>c3imgA`?@c~B`jWI z5XV|3AOeKsT{N0Hm2;62s!HsHB_&Q*gIvohDnIw1nM<8f%P?yXCv7LBov&oo$Jevx zCIt^1)eaTT92o+HX3_tTI0`>BH1x;@9H1pCdH$PH!#Zx^N=rrcvURJW^CuJ5g&Lap zTHEKmEMo&8I8L#Yq}c!*n+`*^@67pw022d)#r0zKD@XGGjegqg}f7;B#*6B#12FO8Y)2fH+7|aFk^r(?5AiLjp8#Lg(6nQW+NB`8&-7 z!30zAvU*Z_LisZ(EQT*TXfPjQKnvkNyvl(;g|v+Vqk)$vFr!>w#DB}(uFnt>X}>7S zT9W}PEVf#!k3POacu3-*jcdsvKHx|MP58*0!)soDwUspr5HF07&IlxACY{(ShoR0`A z7~`F}6C@y?&;lnE3K!|*ewGkKM8l%2yE_};2%i7<5{|4t?@%hp0*hF!|<|Sq9KT#$&@>l#f2M&_iom-_09_ z3lyuJ=&iO3`mnGOzZ_VGFHPizVnMT{qysK&MgiE4S*aci3lTrQh-lnY2>{O;IuD72 zp#pGIEIt3oqWPcYwF2&2qf%5<{)PhvCyJjghgyB09{{wPCLRaH{mx-9*gZ3@*I6FF#FM--YnszZ;}S_%Ow z(MCnWpbR7dDN?qLM$NL`PMwW2DyreI6^4EgNWd-_2?xeBk1V5Z#s7yMTJ2IN3|3Vi zh(zaa%SeYB8;egZO^dxOCeuxpk_!$7W5SAk`wRWUF;KX?F07O1Go!j@DQ_zi=d;DQ ztG4#pRYb&~A82$cL^z0u5fK7mv29^Kb`0=N00+Esu+Oc3o8;vtEZHf2G zdH5|<)H}-Wt1MC&XqKdm#QTJ9NF`O-^}dWCf93r_U6Jdz;Ofnl1pJkQyMW1!qWbz9 z|4)jf2->>t#O4F;{8J?G(ko6vT)4BKme{rJ|BzoZQ0i)DLG7J9Td4a6qb!3X=j7DV zn7I4<4~g-!9kxxU`(ab1h+klood1P(<+91k&#soIy}eBX$R=GO3yayP^|Ro69(+tua(3g!cOqYB0^^&1FJnMIU*YwxJi zF(Ig^$W+6qM*DBo1H@$(1~-2-aI&E2At=D@$;Fm-$%UbHb>U@+i#E0BNSr7^kS~Lq z*w#XN4i01IHwf^#E2pBdo$-1(8!^p4-mS@Yg9DId-(h!GFpxC2XJ2pd8{}v*qv={h zej(m8qq({H0GGp($vIRY+hI81+FI+l+QFrTfy4PjSG(%Es_r`5w6y`6z& zaL_sR#G*$`LPRB5kA(Em2N~HD8gWIxsL)yXfJ|iV4yH|@HA@qaB=g#Oa3NAzx$7)q zP1~;XW^GN&g*Q82*mvxFwt*0)mzl-;-_T#h0w@K!IA#S;xAFYKqYu8H?4KbuBCZ53 zz&&qyd3gW>lV^GT34*Pb-;V6zL3epzeLH~Y!+h?@H;2^B0H+TZGqm_+t-UjF#TBxg z*3#@8idGc&{Pn#PqjD2QK=oh0z!3aaC*AxvNkCac24Y*Q;^tw|SXJPhl$J0}-=>|T z*nQjW9ws_ntF=ZF>dRlvhF~?e+gk)gt)74cYL0!rn(n^!9|fdBQHlJGPdG=Zzd^d^A|_VqsZhIO(HHpi|j8f{%eo*z)HWdF7SEW!4i+*rug% zGJ?IK01yWiMqEh|EhIEF)Q3139|WX-gwSu3-lnmnBm|jMg2{ThT0rYpk@pmfYjCvr zo0PUWrr274QJLKF5;0@b)eWME?R~rv zf{~5Qg@D(k<7r9v$IWGv#seM_GjqAt8%d9NTH+@x8(*5le$?59MLFWyPr z@Kf!zz?{fH?}yCxcp(LzIay2vnqEVEQ67Xe-|NJK@;)llQwqHX_nR$ zgruMo1frx*L70$3Nr-ZGu`P{MURP=wtuPG@Iv$)h6yxMu`hj-qxvF@TFZJ7SpfFH3 zb8ULR+MvE7d0jy zd6+%d89uwDP0S+KehLFXuZmz{fdR*z6}uB8Ou#--6>_<;`)pd5q)u` zG{0v$uhi*TAog(o3LuOr`6+YifjZmk-EWN;dSCW^SLU4PnqgrR#r(R9&{g&MMR?HE z>E(wGp6+xTaO)tjLGaYX_mx{|?XsG^y9s2#HUnOLp4QL%+R9G9DtFk7+B-Urf{LvOBLc-(dbTf`W zPJ4BD@APCo`vih#oaMf+4wDbPn?K`}j)~h18ZjeWhlcmqycvf1#bq?Xd((7In8tiu zK@vS;~OiXIr$LWn`>k;TB!)WwWl^VO|R;Il3^y-{Ij5G@#9-HCOrXBa} z*75Mn6MM;p;Cx%yQwIS3P9xTp+JZj$p?FTTzU`T?`i=Vcem01S8(g(tee#ouh&=oj za7OszJ#&-G3<*2m1~F^8sxf3aedjrIZC-QGk&`=aP*Td#Bly=<;&=E70}F7Zk;~$^ zj6W-{j4Y(`??nj~7HHQ%Qeg*)3|(iSc~DoY$4qsST*+2Q6g$hu3JtMfOI^Bugj{m>m2y8f+-tO#7t0Y*cC0#Hu zV3as!Ndd4Frp$h03<6qBVcp3Vdo=+3R7$hK2s|bxhQAjR6LaKnEa}}wR0-|FSCAoZ zIH^rx1Jh{f60gi_o-E6)+8L)r3``R8=?*m6&f3_{@0#4-^&qA>!oG>6w*YxzTe~>4iOhM`il*qzI!H#G+3QY>KK`HO(5aKoFY-XZlq_`wEbq?i1tWj(e zW5@1*&aFppJs+sbb{nGQLL)awjo!|Lf@89W%Z7SH=pbRMKC{nt&l5~&FiNr{2=cq7 zBbrp(8pE|^od2w{v6-3U+Y!RDiV83P{3)}8-uJ6>bzFRI450y{fl~gqd*z~HFqMme`dN-xxZ;&;q_)#y}1kl;kbNv1X<@+ z97SRZ9O(}XH~_4|@z5YnP+3YFo^Qvh)Z^&_@De1V!5qgcJ|5=$9Netfety#A_L&o` zY_i1Xf`NRW*66GruN;a46hbeXHkZvEh8+a2xK$Dp-}HKrS+hyF z2o$nax7D9A)8a6Mo^+xd`*dx%gn8cZWg`Ge)Xyyo)?%>B{iJJEElK%!}Nm=spK-(eSZYhm8#7pGpMH?n{Ik^TK=LnpbJT0 z=@FVF!=Q;7B^N ztS_H@O|?zmrWYJB~R})xenWuYJHEC z<)t`&&+@^Iy9#_(M=#!+v08oS)}sk){YIJxnhD*xU+}vy8w}FFU&*-rytu}e!WE3d zRwnhYkjqPraa$eYd%bY{<^2@x+cFDZ6YG}eouCVTukn231IG&dQvW?M>hz>{Hg*e_ z$CK04Xu{N#ZnRbV@Yq7 z?BC*Pa$Mz@fk!&Sc6A=n^VEKOkNR6V&&fzuD|Kae_6$VzIqbOICh}Q7 z0xGTtyoRN&@@-7KdIS>40s6XRK+?GJp1n9YkY?&56A(0rFnUvkoxDzBe;rtY=h(ztGQ?5ti077^0+mJ|R|0K=(B_!ukD$ zSQ5kV3(sIr0!Rg|4`hWh@o}r{!t-fTZ|mdlLq~VxEt>DsHZ9-x!$9`;1#0&9d|J29 zmT>TTKMufO*Gez8C#6i!D|Jp9f=2%v+$nd*{N^_Ul6<7mQ`5xDKyodHbh;4>*M$SS zl3drmccI^%;5K7Visg0B$aJ=>hv}xU)*>EV$9Eaual60Y_a{VSoP~>6#b?v?*txO@ z$EXw-6c~bJ24R!&zXe7wEH;5K^AWeT7QZdfGby;-mSX<{fMrL<324f^e5mI1H5`?m34 zq*A`#O#J)698m3Vl&cJ9#O<)O`}rkspJN0drZT3zNXT^iHTi5-Hz-blPePcwFZNU> z*vy51ripURCOadaib=~pk96x&2_T#baOkZ!1pXz~qgVrr_9z$L%(0hOwB8wZSd!AM zQPYYA_xl|?#rHlVi7j_{QqK!;Yp%4-nW^swr`PY?zlq7D7q{-q4Msh2tE^!O6blR_ z6_W-UIIt}qe3iA_ZmtCyq)aq zT<^M!B$I<3sP}QHnj>-fVR3?02J*8)#hN0wG|euPd^JW7 zwL7fu&NrRT!B?%W4?heYq@K2H9^>|&WF_%TB=kx6xZ{M!bX{LzB9h4gSx;l~7uGMe zbL|)U-MVRG>6;oR#~f-Y9?a`DV$u{gMPaCSaelWqtfU<-!E&ayXvaEi=>-+SN8g`H zUrBeUFh+2zZkz>IvbYw7`DLDIIV0a&EXl0j&hVI;1iMF;9%A4)R5Z|glUe3TZe+Qj zN79?_TLyaG9|)0h=64q<9sI}EH`PbC-(Dea(0zY1tF>C~s+O(`*+T*}8$NF`q3YlM zLb_|^4#%fssC^#*>s4Y;e{$vtQz3=N43sh)C2^)XZP%0~ao>WNk$*+??f6n=JnN3; zj}i@ST;|{;@cB>Jb;S$ny%IUuG2h*w4?tCXWWHAU#Jhn#i~idI%!BJ^r$d@%4*mdU z4H2Q}ff8C3jV^uhY=xPyr4=F##z);LwBp)a{!4Sh^D@!=rSL$v2U{MT@qYDh&N@q9 zIMplZkd*8C`Frbv_5Vc*_( z*#%Xq*d4|8@J$|mLA`&#@0Fd&48IR>ZHC^Ajxl~&ewjT=@9qhOsyia(Fu`^^ztK|# z<&P!&EmW1K@L*N?{hdC~6kB+dhynAv-7vquD@Bir=nKUg?hlzMlV08gc2j!4yFW5M zUVF-*wjb56`W~*EEijA{o6_BvsS@Ely&?o(dGlH~CwdgV189#p4W~1ua)lw*h$uV( zCvrrH|10gqu*Xn-0fDNr(skoXLzfy0&XqQ@@M6RFv?NWV&-asfO<7x8R!&Z?&uDT5 zAiO-BE+AHXitepj*O8O^q3o!LCB~!dxP`cG{$k{Iz|iY{zvxB8$ZqG_G59erFZEpw z=tsou7shI_Gs;iwaaLR_vVVJv#BFE%dqV#b*|fxzl#rqMKDI{uz7aq!Wi&o-tG)}G zctJ-;2EgXkcLN<4H)_seGfh;=oem&}|I;`gf((m>Z=VqO&4o-oeEQCZBtji0LXzGD z6p2oNzmMG99f~4;cT^1G?9 zRER-en`J9;5(a@X%BL{fK90b=G&mN3JfCsFkdAMSQPL)(-Y`=+a6ljVT^I^hQbwNK zYVFrygmP>fIY4*FNlZl9{Pj${)Sy*!cyvTS9tC)!UC2m7pq0MfRHse;vV!CymhZft zcZ9gYHyp07oV8SwrmSsfGB7A;@&~;V8FX|hJ^AURIKrKjZQlepI#doDhV!tgp3%#H=`}he4fefvj=NprT(JZa&y!1c zhIK!)_5UQ`@nRH3AQY@m2$siH#%GxBY4oDjG3jS!GB`2lx;TD_A&1>%r=Nq*Zz~+$ zeMbT0w3;L^X=&*+Dja}=M^#2{ekk;!_h2~f2rXZ1@C|Ltv-L3_G~hQvlQbx54~duW z(2Hn&({l76Z$(|}o`%yXu6BK*!75Y+vpwdEmZx?fSa!ckB3tDs5}eo!>w}am{<+p} zl$L8rJdS4y19S9KAPrm2J}l$I=kJtcp?cv{MzMnKtNF2q*cBSP@;d+ExO1dvYqOgC z8zM`ts~;#q;{}lwXNKQrtilG?mjZMcC;E&5Uzia#xrcJ8v@Bm;1kZ}MenR zg=Nl~N-Mpc|M_yMt?>n)xDX(}L?ZY}(kS^@CD%pol~BQOVtSaDON>(a>2 zoPn66D-{qhc|s_)Do)F)C@oJ-F;JVIOLLTLG_2p)U}g)mV@i{saQm37^nf$T0n59P zlT7o&wRjyH>B7OG3ST9p8MULDPiOSY1~TLallvJIBGY`M1JG8Tm`lh_UI`V=^>-^` z)YRAo^W~h?V3z_?FsYxsk0)V?{IOaT3mA$}23LW^b;Fo#iX#Lz<(yCX@J=Ok>v)IN z!b1aMw{D>z!{J0UF7E|nUrcj{rxM3#HK!%=VzLn8uYFFkzuuJo2BRhL(BffZ(m5;+ zOv=gnadT_P8w;b0DogJgo6I#E207bv#F_=jG}v$?i)!9Pd26mFP5ig^0EWbv3iMLd zcduob6!Tp!Y!Ep|EE41&v=!KNe!pO%J_+}Fpy|JK1t9?c7^5%MJaRzt0VaRP%`xvi z)nwPcNLssX}#{bLZusW}Q@<8Dsri)HLC^I>)1YkylEm7ejq& ztI|-6Jzy{%on#;?HQ$dtB0&&GAtKf{kA`za;x1V-=SL9Bz02*ep89b8w!b&#nK4GH zqKfqq+ckj}*Nk0~Bx<^Nyvbv2?~z=;lx~?$XFrVl4+9UK1q5wI0_3(Nes3-gW=Sz( zr!7r4IP(&?eATKc;&XhhXAE7B$c)wpw5>%g%Lig1+4hTqpy8e`mo>5s2gqM-D8T6b{L%<`!vp|{o#2uc|5ejad*Ex}ZI{fLMb+5R-d zMciI}Vv#8M8J|4bc@Xe$fgbj3x_STCp?5_6PsEh9|rKs_9UDP!$$9W<__<+ z=BZFRU`-t#=(|np6P!BEAo7y}(`udEb;qerO<19x{fpQu3k zUC|aQf|s=Wr%>uhk*OA zBFOv99Zp4g=HZsE=x*uoFE#>qW{Dj7(fiZE&$X3+X1Fkrfh+#@(%aHt-e`8z9h*Nq zj#;_S8^vsBICE)4v%M}Itt#?I(a&`K$#M7*kL!GRaG^x|WFD#ncChs3lbj#1_%nM& z@E#^nc9MI9FtQijpZ9udHi90WnjS48ab|nzJq%0TCV&^jo|a*5c={G}@p-~v2AH&c zxC<9T<$Mn3{oL8H zzAeB8&1yW0%>>SwzqKpv?Xx)KL6~QZX}2v9O)VRz&hu!xg!U5?j&f5rif&?53sLSj zb92YnucHs=;CZbUazIIQd0ipL=+Dv7XfPTAZz(`S-}f|Q=?!yDxK18bH?aFO1B>n{ zbA_*f2{9cD%*XQ6@)EI>VZen!izS#OT_aZ#oX(TL0m2MX6KZI1PzTn8d65Xae;AeM z=Aw&M)7zz?+dVFFMMFzOIC9#AUiSwg=;$DBk{Gs^)quZ0YNQmctD8v@J!fs|ViY#F zEp_}5!r+zZrzJ_w;9Nfb{uO<6q=>zwHu!dcfHpKv2uYV*j>cr3woIE0McT=AkU z-;$)|3QEDXC?yo)mOW+kSIP`p(h+|ZSlf!B&y1>EO9A4^Zd8^O_fCox(U}TwJ!wLi zlIZkwtqs{JRGhWLjlcBahExv1%N1IZHcv|nQ20;S$js614wetlQh3B#{uRg)&8RPf zyQ$09!=Sd)G$g5WiL0*w#GS>|m8)yc8w}>X{V((j&ydy}|U!T(74&_=eG`OVUi33$4ZM6QxNCp#-CC32E`N>B zKbx^EUMuLe7qAv#Wbfik?Eq3(K6p`K0TQ%;&s+BMlZ+$EWIN*PDl$uRE|YP`M8VPj zumBvFW_-vG3Oq8^uUe5wMK~|C6Q5BDU$;g-Mt@Rb#_!lvPxr< zG(&}f6#ZghK-kiW6@b_T5s)RTzZwmZR*a_d`%0xg4&j!vaW@a+eDi2Rs`X1(tpPWL z2D6s!1;%V@Sy9)Vlu=dybFNw$Ge&-BWY1jhJ81&H4~Ja*ogBc&CTL^D_%|iteSba2 zgN;($n=g!Vsa%D}Kx|I;`>@p+{|)-}met|P%8vQWsWhd^9R}R+z&%ATASTJl!TyIA zAIX(@%ICG&#W_J?u7pS;86SlAVJ(u1)60EL*XbG+5+kDBAJovBRdvYCE&3c@4;taP z@5>1)JFTgY`12lb?3U)2hp&aB=idw7q)~S&I$lT2YyxLPO-MtTIymCFCCM9 zHgKG9SpD#A3WsZL=Cdp6Jjb^=tOP*W7e2M@JklbG56yW_v${R@weI6%!h!4xRw14`pH@;YE`K=F2?3ynE zKr<+7j_`^df|5V75@TPC87#%{kD$@+;2ilQTh~oJH-af@C}4Xm?|^C{N3j4N)3B@6 zgqNEKl4|q=Lc$>TlcP5V2X(m`Tq~&H4Pv@b(Fl_4hHX@g?SWDa^mPPw)jBBu?Td}o z;${)JQl_G(^J)6XSvQgqCgsjb);J!~CkuSG?@y6ed#gyE2zuF1ak#|T_(p0&riQAvrL~o7stq(C-15)ojv0>fLj)vkDThN(`5)HQ9f)x&Php_O8T4 z+}Q{@C+yB@|0KM->P$T2{D9QWI{j$1=InC2HrwFk+^1Yy`0tW_k4`*Z?pvM8uyJ#`{+pRvl+5^bwa!nFZpP3;B7t?=Ol#Y?q>b= zdNTIaNE#g%SGII~fgj%Ni&p_xykEPWK)is#8Gsc0m>xI1zI}j?nKdvzzYoG!yu9oYe?n_r_~0}5Z3%D5Xws!I60HZsz204yXL{QL_LO+St4 zCZSHKplZU{9m7)Df|f;tx_G8W;P;HHMp0{adcQTMYmazveC0;TutD+=EXN_Kv=gUkm+Iit~ih3WS)0Rw*Y_q*R)FGYufh2FS~zstWWWgiU3d@F^}}w z-4DPi(YO8Jr%KsZb>r8Y>0JnOW2-x6QGh~FApL`dX^C;C9?H|E0!V+T)KG32@y{6z zA^I^D;)TJ8z?!CxRqy+?^Hd@0m`ZS>msr-w#UP>T?POG|* zEGT3$o5UK9!5zuwb^_qrdwy=Qq%<@znyDREo#$4|<(a?d-BJrTZ>Tv#q%A~;9TeKq z(r>4q`Ihc6K&+Yf^AFKwY?4YB>AywjzXH_tw&h+1Tj)HyNeO^fT>70^V&|H+O^?IP zEw;)id+%2opTeVJW6)dc*22%M_ZQz>$hvrDrPjtPABWg_-g*9*#D8crzm(qbx0Y<* zn$mfhk@Duaq11xM-&iaL5%+XCyrFiVXzS&4rL`*H@3!2!Bm^MPtF(SOg6h-D?iWLC9!`uP#OLH!F18rUAni#j<5 z16f7>qz}Q=^b}fq{^2mQ7<@;?Ta49Wec%){QBlg4-$54G?6Ougdw<^3_Lb>d<44F+ zt-npaGAkj<3R=7mT}s){`8gi+YM4<9)=%SyQK8Rvq5asBrnYkb=U)0h7sPv1JsNG7 z$~fpW@)&AG*Z)I41U;^;VOctbEyKIG{OMS!?yR@!d(Md|h0yO+SY2;wq!^ zLkl+3Jrjqhf5cuYm_7kNLw){@2)Vm<5N#Lq35t55C`!&tB{XY6sCGpM&w!Bsu&hoQ zg=5O+wE*U=f7uo})}(XNLXcoaFh z+nh-u_SL^mA$GU7^H?w~fc2EI75!zdMBUo$C$JDqzT|c4=#HJCSFg-OE$FG~N8*lp z*}cX9o?0zK;fyh=wC|UjnmM1$=j4uN%67Qn3a1!oGJ($I0;}FZ*OYWIy7kQ?-H;*t zh-d5sj`_T+E4s#-U7_V)W}+;Vx3DB&rd$93YSLt-;#cH#as;&5I^r!peo+l0q2P6 zl|GsVdtzm|aZo!FrxCU0Br}xM*|Wl-VjkTqMiA*j?=#D_mAHnU51MMSf)y$M$feqR zkYSzzzD4DcMqTiW376f)v+&3pL!m05%;d+>c=_JVHT9!3{0^I``UL&T{5eZ#X6$g- z_M0>{j&}!jLHfR{NmJ|46rC>Em>;t4{s=j!v;G~ws1ToL?+0>05Ds~$nq{!~oP%H7 zk!|U$rHu2f+Y0Uk#o(kW^Pto4}+XJfEtgMq=sI@EOS$Ahrec znxheo?4yCIp~9h3a9$lFEEK)5GRnFUf#yBn|Cp^_w1=QPqj2cs_LR=g%wvoIaB8z@kPO} z*ITd{1NW!u0%y*}f}sr|PyV(%E#vzq<(WI$%|Q{U$5}R|NYoG5$bAqMH1Osrf}<|+ zg9`Oq5-AoG9LFj7SZb(0?ECsD8tp{PG0$&3>I29);56B8FFuY_>_vv?b>7cJ|KVGEl9v$EA^(%>EtsuH>D%Cl-X~09{#o(6^tE|0FtZ`3M$)uX;ET=J zGXp3kynWZo4$cCXY<96Lo&No<+)KgDYMyivX(22Zo=lB`JfZ5L`r&19^KAciZ~_(P z9%edysNl_gd^z=_e5aDVCfdBl-|1S-l}G#TVzTR$kQ|gFR`MkNr?tJkX#=}0GAylY zyp5Gu->A%V;Y1Fu5}G)i0y!XfnG^*Ua3wkiSoZ4tXZ@Nst!Z?*()+wWf%jXm0T6wS z=5^REK3ctw_&Vi-3?^Ton#^2oHI)Ni2-f>5#ut-IW##_kqpb);WxF>fqbUZ2 z>#3R>V@*k&s-u&g_w=&kRs)g1$qHw}w{1s$Ws0`a^QI!~%V&^h=bNL&8Aj$yT=*b? z?zB`>W0IGru9N@*()7wk|I$eBOl=9U(Wy->q>nA0tUZcE=9lUkyd7M%G&HcHFz5@VlPLZL zlrB}NFO(?|Ha0ayL`MGE*ua%el#-DVQ9}D?Fb-I~N@yVfkUo2>Jab|OwvV)JjOt#ebeDlH)<9BTiB@50T+7cB_OHbttS|}F9%8m z0T))EONzoSc~W07buER@+&q3l9lW(KNlu6 zuLN@_cf7JU^d^Q*u|)cMzrblZ{Vwp?x`{3@uNKRn!OVPXOaEODN4*>AQ+Kfn<7AU-8U!p`n0 z0bU5P(!JEf#lF6@)RYHRgkx`uF6s1cD;%K+FwNS!J(@BFrn@$TQ}FQM@$q$GZwzeJ z8vo;OR;K)_I%`?gF_i{jeb zxdnx$7)#Ijo?c(`7A#^$2Q!e+{x`&c4+e32STUXQumMa&{kTdSL_fa2su|6b#j=>JY#VX91`)pnnf2mRU!L zlE7iJGz%mBgM0%&y6cULH}K_C=md3siaW<>tXxWrrp>t_)Lfl0RiznJRrB3 zf|-i`{Pnb|YZ8;8G(SHGSdi65YtI(Jax9UYVS^(1MHKyZHNH>f*oVTpr+i8Ib~f)* z?R*o69lmk1a-)DN7+GV@D`qSP?0$LX|6DU*3U1*nqOGR(3-G(G!fO!=a*6(?%^Tq4 z?$BfPBX91Q0rT5%Z3N92&{&Gi%F?~XV?RIRiXUq=M3242i~r6<9_Rnpj=3ZCSz&9h zy_YxcMDP4kOg+64d4VcbEEQYW*q=}<5LM*hed|HLh9iZikVhl(iBBCd=!90gHU9ne zF{?qVXwH7kx=Eo(HiH^5;om#p-XKXsqh1@d(-)eh>d?ajkeu8F8Dw`0i__se-98+dNH}b#i;xAYMei$Of_~@2k{KEL10to7gt}23`i=SzEVW6J~GCh(Bc|c^dll37QDK~8k8rRN&fy!i(asvOxDdt z(0KyCLpLNuJwSCUK)ZhaoWhH$Z3h2F!g z?#@>Tf#$?!6j=Cl*`wpr)SG=letr;qe0(=|_naBCf8{SMOiWCbPRp#>icfn=keg*k zacALS5DZ_0k=E3tnkCl1wwOqe6Jrm|ejg?1V|`%?f6O7&%E-;j<8V2{w95=+Lq|gc z@OBuR*5g8K+dX{49GV(JiTV7O<&tL8X!fP`35%FWCx|}{EZ=U6cm0%PafeMzp@(^W zr2i5K8b(GglttIEOpKoJ4BY+waE%pyKroX01OW?obl(e=j*3UEW0oqASl*%)?O)<> zjDRROt0J8%)C3<~j8V{n5&xlbK}9G9y7kwt(CLRE9qo3U?(DLPTKAOLyE!TaQx!1q z9@7asmKlcQPpsHbvwQ?(MX?Ivm!0;OGJ5UyhQ+7>m202!S5A=u7&SS1XV=p^y^q4F zu&+!tXU{}QtedbDJB}NUZ!Q}NQ9{jxsUZ=cG%?qzoKd&ro1p=AthE{&Tdp%RGo%z0 zSzF72|ADpVEpS8>WRoPtV}nF1UqH9*O4+q9@&%n+B%s+%I}%PvIo6`Ug63~?VnC;{ z&2+a=;Pl2Q$r@tMSvNE1Z^4v;1uf5ETLJ6I@@4VKp8~Vfq=P|O->~z-9`u=FOC6}j zLh4=$zX-4+KxTyCaEcl>v^@DZ-W*#5<4^SdbC7-;A|)rUwOXl_BnS%&W3}izb~0#M zqiif0&jeKE2(1KlWB88vXJhGM-m-i;UeoVx7ayDXCK#%7t>MOdR**kn2iCSF_ycX$ zpAX3$#_0Lxy?i{HX=nUJ?>G_O^0=5ECMNb(o4IQUUSo~`5K{cBKQVY zuy#yW`}BRcg$5kAy@##>;m*b`Nr&^Ot0<`bdS^r)XUdGh1--d9?ECNb{aY??*YTES zNXLVE`l6HZQJ!zAI|PBo-TNIX2`4M@@)}B4G5q?&jYn;KDOib{#{a^+M+IVKY(Ja& z@Y?TssMkHcVTrxDudYg@Lb*1LLkqk}f>E*}$%tkN00)VxY&8!Vwc*VhgOyof6SxcU zxK>a%9H+k>0l&^!{UJPM+59Z0xI+d*_x5sxF7ZU`{C}#uj4Kc^U>sZO>_k<HRVH}V8#s>|#gCt1N>ZY)IywRXB;3H`d{OR0j_kQ;JySTX!&v-L~94vI4{Wmv%0 zaoPD|Ziln_kLOEcu1_^|;3W9g-x;r(bLUofOspq`!>y#gQO3=`hyGi`Rh05kHx?KO z0hcdmTyzgSTi6}@J{fX+cjw98*{K(M$VEV*U8R6?U`XQ^E*gS20&zi+&-{@t zP!{tGo-y-O@$m9Ns>6)gm@W>-BlczOl$)`Hk7A#eri%|U(ummRFX|?yVkn{OuC)GX{y#WmdEYx%Tn_u z3TY&P^VDb;)&7}|jDZU5q1Qc81sufLlO0tw?;9eVD9^xnvWwD6Jdn7$vKXjPuP#>amMhc^a}PUET-0BZ*nh{#8(X8U2&a!z=*;3%#&i6h$UAxAfhv!xvuG7byE^BnE|CH`p z>fD|@BrjjlNM*UDXgOBW(Wr^az3yWKx47U`v00iqn8Z(}ES(MrNe1wHZ!=1&?8B;q zPf_0S)u%N~TGEgvMAz8;7ja_{|Fj-Gp(GO!73p6PNn z=Ofy_{Y*P6a_$8+VYBDA?%Oq6D~Xj1jWc|ERGtJTKaPT@wh9tVDTjQ0Gmhmp#yes> zpIxNY8raByjn6GMF3vJbjeRR0%&wInmvjU*o_&PYVOwc3LnYogECBhHgAbP!!B!(^ z_)JPcd?jhLCXKM_Yga4yLGp*Au`>n-Zssr$7S(2e+IL z0qnwe?B2B9OG-Y*R(F)-6C7Pno#L*J?+N9$wh(yuFX^5N`fk&2V{(YQej`Ea!#yY~^l%l@dbef}6>wW8{XZq+gOy5Ai#LU{SZ zmx&kF^`-uI9zzYCt8Yts`ph15X%A~OQ7MnNr;Csr+v>8)?E&q`U9&e!prO&5ShSU~ITh)pgBdW(@@XMSzpv0m8hhjZE zcJ(pHFlG;opn{Lx7j z$dC6T*;7{z%8*TimnV%Lzb)#u*U}!>7&mQeH&}Q3P-N?7^$LWv8?742*WHoTo~6+9 zQ|E%+qd&Hxm2&DW`IqtdgxeDDH^8;28xZYVCjA??KmWs0%UQZ1nn);D zSx6m}U*Nr_=WyE!rw+l z#%+nT#xLYWKl86#g1i?^@aNccuA|_s4PyjM#R=gzCyPU&-BhsJ=z<$1NluNT0A zqe9;Ze5?dSUA!A;t^#20icMaBT!xIB3QjaY`Iuo?Pr8`sWp|^}1sX@azG?&eVDe@8 zV9mC%%~i%qMiPRqQT+jP1qP1an^DnPS}jvX#XFtOR&k%xHqK}j&G+JDcGr)&-$$q( z(uW6jj0H!Pi#08T21Xwy+T_#tgto4Tauxr}1>j6_h0z{qf=439cx85wzZMcCCuPB0 zi4oI@fob)&TGN*FS;Xw+8Oq$0wO`Fyp`1ngT6!V+%!f%#41Gw?REzd229$(|$Yef_ zW1kYS(*FNM+|kgA@EL37<5d2n>~$V1d)P6`O}Ry0{-B6aDeqaTLk(rcErVfysC7?E z_&f9dYfgDFRd6s0FMsv%M$psNL{;sg`qV7*aF;ujqbwk?kZnskPTlr);{_S=-nH6c zg-VM@$3Q$;NyJs3LX7W?;L-QAum8Z7iRR2}i%kRj?o=u-#r9^&=E$8C9hIrkW~aH3 zhuIS<-M7HMkS-G2ZCiYTR2S5iF|M9a%cbE(i3><;el%kjbnwXRS}>5>_gloVUtEe{ zC3qi)A{Niaw88JJmea-x;}vIV=x~QIJMM%bJyA*^R{r+ky&L&#CQj%cyM!yj^$=}3 zSz-x4W~chTeE9)mY-JD0hf7N|cLF8{&Z*3CgoyBe_X_-K&#Hxmy)a3_nV;YD(MGaG z*5%NGexEj8L{>We17bjo#=#zZR>D1QM_zg(orzV`J50rowvR z^sl${`t)2soH927qH1)DJzA0*larZYh>8~Jsrd|fEV}haOGAvN7|Y?Jq-Nq(^j9M< z;ROta*vYucjMJHhlPd^;Vj^2xTbGM<^;7FF0#CNZ)`B_do)HijvH4_W)1nrYXlb|W ze1`SdVdY?!k%MaNfw7a9T{dFYcZjs@8Mv#h;8Noi+z-=;uE$MzzdS@sXlk}4tN`NH z^XYOjSB!^$!zVDh{YJR#Fjh6&LE+WVV$W5oKUSM1tTh$}qpG88^?kAQ(omL(G(Ac-G7`qyqZ;CBNIzTblT{z2EM>(n&eM;0 zX|vnIAgbRh-b}yD&*`^iy=2U>?M|OAxVa38vVPF-utn>8@sd{Gyte}7jYMZr zX=lL}m#GRjQ=OWKnrDhLfpR4y$0yDqkCVl+|X&k0@RB$IxH} z?}$$=fQVt)51?!FWm|vx<1V5r)5`;Z8*?+um@Tv?g_cP8^;3|Mkx`WsK$B%%-WFoSrJliVvl)9 zzmw3!#atuxMQ74GKQXfsaJ+becJh5C!pHx>Y{U`@v&TCe8t}B6trHzGF24QqF2pRlaI=Kva`UPj;O5i%yO6sVX7oeMHmDa~Kyklgw{|Kj;vTP`-# zOqkJlPxY=4pzu|q^*~aGGFkFMCGG!Tz`ijXFriPBham#P)-!hJ(bD~8(d4gOg?XJJ$?s1V<9)nG ziDp<=BntA-T9afNG`$E1MEg!6={0A=;As=&C;h#tT5gL$`^D_2b zBKCU?SImLqn_r?d%f)J7h}5R>o!=2V>vXE;nvO^35vVJ1MS`L zcafVrB8GBG?-T485RO9~bZ^^(n4vAh7n$4dOarrYikEaht9ok84K9x=IJlZkCrLxR zN_V%+7^YnDTz0}BNZ($j4jyg$Qa;YW$hY2bAxhbH?7fp`_GCS>hV*9`xZ|B9XSX?T~H4vqkq%PPlIOF{)x7hb^UXuc#pCctpGOuBySa()!ql#(>a^89ujhY(`n6Xxq?^J_7xHuScZ<4#uuqQ(R=jiGh z)}|-@X;3P6q{+9xq)zfR0Yng!chA1FDLea*; z%_f@)W$xqSFkze5Ji}8gyz#|IGGV z@k=T6wH2*1_eMBt^gDz5kECNatX9G|K!iPhiPE=+^jkum0W+E!Z;EVZzv@`#_+=xK z^ui;@g;{+*)_OwNplWOUor~>eS$$3hrq_3DG=VxSDr#`9&IB)Mv@81Ya!W4lhw1%R zRs7sBDLs8OFbLa(ls&Dhi%+BC;SN(Uslq_upJw)#9gW3uW6jRhqYFph6Je9crdu{o zyU*&VBsvEEiLGJNEQ&oG44GneGS4Aoo#eKxzxK8>ilk_CoUfAu?RDB>UV&fV8X(R- zpOrIp3A+D~X^vg)5_07-D)flrmZUxHf1>}{a3Bvf5LN`%94(2b#_pF; z`}kOd3Cp>8w9dHie;yZBz0p1dh670`1qiZR5Nh#T+w-%L{@?9D0m4joN^!q-vQ}E> zxXB?m&hk*=`&=x@xqP5GZItU(S2v4=B7&=G1Zptp~PRV7j$D&wRznb!0GGDhy? z$|N5XASx#VXWTAYs^$LE$63@<-3JTgkFfdafg#ipv zsI&|Er`03hqM@w-44pIhkv3&12HFZDYs~>+&hNTST70TRwdmyC*()0Meo15t_=Pj; z8q7#yJR(%I#wEPF!OSh9>Bl+UouN!z{eg)rm2IRTztyjWrDXVn^$rf*mP$ofn#;LT zOP3-S)y980k(}dfrdsFE4-_~dxy9|DYrHf+DC&ml#i$SK0Ny8z180WU{eo(_X46Hv zI)~!VpAs@M#tWs&PM4b*zyP9ovk>4E1}HDmEu2|9j7E?FRSa;&n;y1*{NlPFyFLD} zm~Nhb8c%@6${7(S9U!t`hxO(nFMhUMrdwmErC)sLg$G7*!48*PWt8t9)x9;tqRG?3 z!%R}YjLA_Bn;w+ZHscMHa~tK&(zyl@&aWntsOKLfPIoF)i&FssD8i8;yXm$Ew^*tD zTQo1nbSe{=dJ^e=d&p?J$z3R$Avu-FGh@aAplBg2jz>V3q{?Zz*EjQbo-W^L1q$C@ zaWg;K7k>>E8h{B?16+Ox0)fuyXmHT<7kDEA{#nW50jgNioKmW5f$O5BYetJ@&uw;f z4v2col|S)!T8%bR0ggIPWvFVn@khv3DJ|ubclN5Z#dI#06C?#^;BpOIBd#Ej-z7%& zH)wDI*@=ZS1JL0r`agW|f z;IEh%TXosbBj^Cm{q9iU04}ZKG$2i|MI45ciFg{xj@M9Y;Yq?v`N2dZYZV*fHw|)e zyrZiklVhjn%Ugu{HJZUdrtXged(!*0J_}_QlcaO?|G(=LF&rW7BU@`nGbP{;euvMw z>io-~S(j0_e9S!y^}_Y4=qWRl^%e!A9(|Tgv;%QsH>|>E}JfH zw4ahC1(bmRonsn^{=!aE zifnW{X~HOT)C4F>fEik{#-}We9Nm1Q!_J~f6I1E&cc)r-QnT$Feg6i&DX|S`;}ln0 zdRlSh6fF00jjpr`t|&rfPd0@C17&#-dU{&Ug`TX}@b5|jlyrIr&=|2r=yl(U>B6lp z`Lcr2{G z`US3hG?I<4Uw^B@(RfRG`$4s>R};RHFG59WJQnq{y{-%uieCcS7r()-d^k*KahsAF zRT6vrU{50vz4oCQMPyIp$VI^E4z!_uxZ~`u^ZblQY1m&23Z1n5POm`%lSfGwZ^~4& zHA4#u^A4E~=Px&@QH7+vKkPS+fC#2ZWE{`OqMIFj>L-u6ejIu0Gdag>5J`LJ(BB{< zfhI^m8&%8m|CFZmJ2e4Y00$){CGeaB{`IaZiUP5dpIVM={FYEPR zc5`I7agrQ^I2+$EHMn~cM++^KVpF!3FtpEJ z`N_9iWu?FilrIVPIwgC#xx^~vYCSS+8%ky8Hs&s{*2JrJyP;FZCI~{mzm%!wK|+x@ zU&;!Whk*};$FMMw6{wIxD-m{naERI{p}~yBLI^N^1mTVBPsMBfKutDFju)$y%Jp&d z^>Q_>9XQCHhDjE{!5?)b=`nXzIJ2wuyoK)MJ=nKPg(Ew=?D@9uM_71|K&Yl@SIorZ zI|Z7NmOl7~QV?(P?d}9$U<(ARfh9}#VXa!q!{a_|cTg{7w*K2;`8dhF9k0X$cNot` zbBqF;=xk5+uARRunEVKP>=Y;zCh>Uv!$UXv-bj_E6o(x{R>aFECW&CI`CJ94;py;q zItZ5PhO?6FL1*{eNQ&Cr?O4)3rnEi)88VPJcO3DS6OO>X| zR7&JbOtEy@t<@$I*vKd-Sd0e3XqK(R9GSu@@6a?EZ0Urij4Ko_S96+ zW?l=1stdnx`{Al833=r}QDuD?{jak`ul8M;k4wQx!I7Xnyu7mZnojAgR2Liy9H}OP z--mIe-}P{*$>*!=n1#tqS5Ua?YC)3ZAXn(};;JO)Ezu|8 z^e;#p4iX%Cp})JR(DC&L1w$p*5=YZOD76Jzc@{+GQ4`n-*4zvsQOg>o&a>^%`up-Q zGh*8vpk0Z%EZm#aidNo1Bp6{;e0g{SL#O2%-=~jFex6X!*;EMs39*o)r%INaEB$3; zdzj9oYGI@Y)iqeeh{rZSxFx_2j_EJU`ZObU*~GwOTHJqbX@d9bx}kUja7zc*>TS31 z{Q$y-YFp*LX4Vfp&gl|O+mLnM;HE9#KPC_7QV*of+(Ew#G>)<{?25$+)oUr>ZQ7z?&vIb zkidD9{cq#44FypQV?(S8u-BgKvuxf3iSjkQn3(7kBMw7Ef<}6kl{_o`Qc>|HX z(YTD!Va8+nPoDVLi>Tx?;4HTk^ij8Y)IgD@II@N22_-iwf}nRCc1oW-{?=l{t&JVD zbGrM>)Q-nPdP~y4M#S1aT}u8d^y6L;Tj9<5y+lKzuAAvD%vaiIO;IrDq&vZe4G%rK z4IJg1@+us77Z-Mq;OVQ8l{4v)4){6tj%Ezyz;?S@<{c&CbQ5~7-W=*Byw@9jUL1U( z27b1)^D}!&BfT=x_1eXniBUl0Y?Tad{l^=y5ucY}$y=vrG_Hy1HsTcT{1 z`Fja`{ZhTn2K2T^2Y%yjwxapjRDh>2RfAQ^isIYibuXKa=9M-{X3aGlK%&~!t3uOU ziZp{N$`#muhm{O+Q&`#b%frh)HA=2)!}hA-364`$672OpzW>8l0sc)Sja^aU%I-&Q zuH%b5E)M-Z{67DK?`kPt0!h2M_H!%QY~(D2@JQWcQSB>nw&mIT^_O=(j!{3fYuq}p z)ZmRSZSpFbE--TwpLL`uIf)-yZym?zXx%7ic#gHCwah}_bS~x{psZAvA74d$BA57` z^F7Qxk0FWh)$aS=ziamf({^Q=_OOYOY6^U{-x3EJwclr1Vq4Y@WyRFLwy1$;jt|WyX4|TPCizR|e06Ca>28 zuvX9aUe`6*KlYmMC#-aDFFZA23z!XOmcS^>bm;p%H3l<6DcTCG*B#aJS1TIU50B`g zSMP3fIDQK2Ie86dpRD=9J@v+8F7yZbfv6fhcav)l7JfM?(vdUCd8xQ#1MOZ*SlNB2 z$7zW-2N*{m+u`DoXry9Nq%54s@7d?8EgM$r`h_F=#^u213aO&{o`(fQe4I}Iv+4-R zFzgNY;|}^2)K?yAa#nKpow~aeXVTZ@RZ8BA&7e%!pJ6`kNT*$E-Lpw2e;UuZ9uC(# zERT|Im45S<*Piy@DW^Sq*dRz->Sn+Hfm;cTJS{ofsty4s^QhIEaJAB4&4R}39j0IE z-`@@3Q8zNOfT*WG@)R%by^>qHnOM@jazQ{a7;-&q88~vpuQskRRn%OSEZGm%j&Fs}XL=qo=LfLOF% zW*T29u`304rt(x6QaCbFB;MLAZQGSW?X^hA9S@uHvZo7d;2T7_s^&}J#{J5YZ$EBA z(zh?@luuGgWrhw*`GaKBW!=C93MbT8jzR`%!6-jy&pFHsojME)8$+(hzBmMy_3Vb0 zlmH!h&RJebu&>>{xITP=F5^I~WpPQdp-3kgW$U7~w+37SvqDdGHZry8Zy0g^yR0&5 zE3ZRJ<%kRf#RBNC{F>f(3uCc!tJJVJV&_$JQ z2j`gtl?uKrdNU%vE>2CK>&v0$LO(l_mFa%?XJEa5KX=MBw)GNLTtj#=H&AUy&6X9R z8%!*`oULlP5+-PmMQQP)h#|6ee;E+BnDB_Ze4Q+4>C-=y(+#woa=xqV%$m9v-bH3D z)@ycNJKfj9FC#0SEk~0XE1k|~?4;-_xHdg~T3HV%B)5w&6G>WU96nVcI!`0J+w4qp zqS|e@gpXt6KO&<}SsCHtDqHa6(mAP2$FstHzk*Z2&NSM{RbX)hE1vK){qgg$WP9+^TAvi28*oO2E8)Buc|F2;A!N_q z8ypY$MKyP(7^19BdCF!mU3kon4xf~RxGdXN(=7&zUrQAda}v&OX=SI{`z!0PTXPjl zR2Zg$v8zlJ%#vc=U(3G8rqb7)MkJgV|5j5S$ehijN}mG;VIa`qvg(hHw%hdovdZkq zRC+&vX=7#`50_kUsB~NJyG{&xqKHSh%CJTD6!6S8q773Wq1Nbv`V|P1S-L8sRun za4uBpplfe1;naSQ2U|@Ni~Lpq4eQ(uxELtG;mTg@@oSKag#_)e(72M|r4599rrer| z>k0h&Yz5Y_PQMSb(RM2;_qzxz&H6tnt-(T>4v#0i^t+KxODqpmdgUH6lET%b`*g*R z+E6w5>M^)(Pq*2!lp|*x%H(e_*>UEJ(=wIZ*ypgGKiT8cN3L)6Sg^0I>nY~P)bi<& zO7n0sEQ=g>hny7U2I|O3gN7^Rw(%G!W-1AdvAuTvaXCM_zOo^SlI64%^hfcx&PE7;^T6?_>yff5DsBe z#{P<;LmA7DmJQQ@AKtqojwna>mL3=w5Qc*-)CCt4k z&N=3Tl{$7iM|h9VDT9-yY*j6lWFbx^B(r%5mS0Mh?aD(t*7=!3Enl~b7y1U5%)#v5 zTnbwSXaVl58rK`r;E|POgN6X3LDJ>%+zbnY3Vy$;)QkLKh<{54<+1AYLXy9OoOf^0 zJF%UU(?F3D7TCH23IDNGbHxKzPvUL1%+d^+tAUBFzQf*W6$jcGx0EA-p^V@!sGvgg z{=vcA?=TZ-Y@bI%18`@XcuEP)Xw=lF+}aA|CGN1a+AM6H#(18s%Ji0Gm@a6$<=4PQ@4JKG$^4YBu_IrADQJQFFBc%Z zl3%Zw0uBEzCT_qt_V;htuD2Vhm`5bRU%rY;N~l}DpF9BMPX;KAx>JZ`vv_5!tY}J0 zkfewn8AL>$jzqUbq(j}A?Byfvqh6He~kwO(V-TOe$1 zhSX$I$@j>QiGCmmbVGkjnVQ)Xr zk(C-^(&lv9h!Jo7>n6+@S_?9CoLJN0AmxR92{ z4=gprB~4-o_|nnfQ1GZzL0tYDtvd>3=oEv|LrvD2Z*5Kj3dU~TyZHq=dV_3~q^H=& z=y(Gw8Obp4OlEm*gbCEDmCa>@L5L7A-@fH5zb!!Ch^~VBa`$;Os7y#_#R~_JB6`I;dT`6eO86u$HJ$G zs!#8z$1QAO77ReAV;F}=r*Q68l-#K*;&>c^W<3SsndeIj#yo#3{Q1b;!_VWp=E>wu z1cgD$z+17&?YSNERH*Oyy3%5*S`J{a+3{z+%_VKua$z~P1L;mG16UZQ;!+*IY`#1G zv&f9?Ola{7UQG8S#2!oCOT2M=&`XC>c4jxY@1=Amv&nXIbC$14BU= z5Y4TlekyOIqJ0J8(yA7>bhxNZD=pH?)x!Qjr+02xF492LY*Nnb_L{sYH zd)gN0sk^7?)Wquk8wQIt`^-A)gaJm?s3(2*lLf&~3WGi;?ai*!L-~|{qO-2pU5IhT zKlnGLxmh#X^g{p^G33qlt0@+{I}09Pv){^gM5rx@G68Hqez#KK47F-DTuOH?D5Esv zt9(l<+e3Ib(b0ZMfk(Anoj-J55o6hw;-s$1_1Dr~!#IM2FfM4C_23785@!mpi6xyp zclQseyX2IJg_-D^`spt*N$-TO}qfyfR1SB?dK!cGu!IuwE2zh-x9{~(%2$?aiPe6+S(A|&cOXm0( zE(Cb*9LFscqLRRp99{IeaKnqx5z5O6AQ3;V=rTWzxk!3%(pVI~64}(7&ykNN(*DlN zGt6n6diV6&A4akOx(vnM8x@Q#jV`d}fTsFN^x;if4LtI|G7)_J`ZZfBiEcnU z5*Hi8C;H&`QrG^KZdm?WI*_73GY+ec78)~|43z||>~YnYvs_(12A|`lBQkrGY&lXB zeug3v*#os#*Pk!w|GXbj|5ovnYx=-qR9$!*F#>s8>NoX{B%%Rr1frm)(BbUQe}>Z0as#=_EY-!iRmN|AUa1qv|Eo>5zRsH3OA5*fiUpE6rLlxmHhl%>?F*l@m3Pna zjFD&IZ9jmo4X&(gzSYSCZ1|+SygFd8|6W$GeuD<^xB;YjoeT!Og|Akhr_LeHb9_d*Ac9`Ci1NNRBJq~xymx(JBz%-@2NwdJ&rZj z*UVjO=EtnCmE!1d)@mH4Sg<+P2XccEKPf*xKITh)hHh``nM`HU`a}G)Cck=z;c3)> zkORJvkX;WTH-v(MN>5J*bWg>lqtCZTVbRfD=X)!%zLH(ZSW4=S;jN&BZOh2^ZKxD{ zqrstuca9$XMe8iPNT{O0)r!qy^+|% zY3qO2vd^SWzhO1GZeaYN{FHvP)|Szk$$z}e(pehROInf~s$BZND~n zxLLiO;7D?!{0z7^`XP5BtRzf`A4M)rM^?gjZCVbZfqSdDn)e+hoH0IUjTXe{y)!k5 zYpJk46db;?Gv1ad=3E_ug^(nX^85q^X+QFJ2Oc?wZ>g(K!t>>~LZS0oH;$FPUEN4o z+kOWkHk;g{S{r%m(HC~ZTF34(DF(+xP@6S`ADqA5B-P7_!~I zHso5EBc!Ll{{jqWjfa?Ed3~Q}pDY)?t}ejk<)?wWJlK3`$mqKeiQYBQO z#&>qiUuiR)o<*PAoQZ+YDh$M*dQ*X4*_v?v&1m#>ji!m6#V>RCWd`9V*EoTz7}ptY z$9K&l<~^0nb~=`OwnV&$ua1Nc>zkI=V;Vwo2vDh$9FF%|DW6(nPnFJJADp@;_ajv0 z$*^5K(s)!rsQIER{e=24T{P=XYiyJ(EkdDokF9zqH_<*vt+85eT*o0;1imV8+n^~; zJLAc;rEL`5B*n)It1LF~amUvDlURQFcEF%fF&K}c(gESt=K=7`M5FPwiNCMvH(G>IMUyO?zh*qC^If1NVDORob0q5WVf*FHwA@A)>{J&gnaK=nYUqc_ zbP$_6(Y(K-B{|dIf=|ZINd*%zF27yLfrmafu0m9wsFZXy#!P>q*1ey549wWc)05{W zd+^NXo7#h)qbo5!UT8l>;dU4eIihIH0;#hhS@w^^2pCzW!O3js9li(f%6(f-nS=&r6i` zp~W}bW8Xa#jsaj{9%l)8UWs`PKczjm8@@f_XOt*TyXF)*I-Ne^(zB*VZ-osmAP;30 z*fO+8u~1-K?#@+$HZ3d&%4rF86=taIT=NamCks2%Q+Lr~O*%@sI;=vne)=3#6*^r5gh=^96A5pAY@Q4LCvQG2-Ckeo1IRhs7Yv6$ z7+zl9V5&Zg27?+kc~pqNQauJ#uT#?+i@&K+4r9Y$egQ&iEQ}L4F$8T1JAB~%3+9x63|Qn*NHx|}`1RtU75C0Ib0vRI1D)l#vTM_i8Bn!l}Z`uu3h zDS<|MUu3Otezb#l5!XyrPJe$jl9cC_ zv{RCtuVO=7!-x-`($WtHS?-%#VpuoI^iMYC;xS~!w62L4)ssDq;k~t_-@7r16AYje z1W|)*WU;12Gd-7S8me=C#gtQZ`vVQ*d3l|VKVQyQaG z>tescz=cA?IcF9bu{md&#WU663z!(=MVOcxJLcf_R#hVcD6-2+3=!j6HvfqbS~kh- zWqs44Y)kBHl%^*v15y0k=lv$NnReVt)y5l*B7yXFkrYubu4z^lxazarg($hJ&L!CK zH@6?GlGyBZe>qmCMpl+B211ay3_mJnobk?bldFyK@iwYn`4#M8>$~zEwxr3jg9 zxPnS?8mA{{LZVj|QCyl%T~Z-*u=rR3R=_E8(I`n(@;7(%z;*t zR4EaZ035MDlmir;J8a>L*AIqH!ga+m!?8wCe)H-plq6_b{YbItaW@4qJ4#|SyRzVh zvNDo%jOK!U_*-(e>;Xc%Z%)-h^(WmiV%>jv9y$JQfy46-)7%5E-Ig<%WCw}p@2!uK z=MBi{6L&I-0Spno^#7EY-@nMr)fO$x!liR(O$JLnJ3}=OW>fVSZ0M+dU1*|OkTkB= z8&pGYYZ_v^Crv@>Fk3VIa(?t+WY^Z2AMsbX0hx-@S0_hn=|Rc9JtOfz({oh0^4EJi zee$)95Tr1~t`X08OGNKfT&0^RB9@uqjwgyb@^nggCSM3)<_@&e z8}}cqe<)T=!LsB1xkMWFM zE&UUdqylPXaz*ip^__c@Wq0xO9y{+g-b-Uj;7k?MXWBxdOEmA~P@3{!boyvS5e8C{ zd9?0;?6}!X6qUcL;}cCnw~nLw-5Q8a=4#~Mr*EiYu3m2><_fDVc0I^Hg>*iw$SH+P znX)I+@>itUJztPD>d-o={HSG$DhzAh5ep~XQ-AC^fmsOe>M2%cFdIVXXth8W)zC9q zO4=S$7#ZBa=N!h_&b3J?b6*<#cH|J|8Jb%-yms)AduebO^CTIY@@lxCS?up}tJyg@ zb@7RxidC7Wy%Zp^(Q|6=z2E?Mdv&9F5NJ5QI)p5I96NT|nUBpu;d0R16(=vh>|QPM zg7&p%l!}F9xX9?N_Z^7%e|&v&bX;xwZrU_SV_S`FyA2yRwr!hjY}>Zg*tTuk*4cgE ze&70?b&!>RGHWt>X3w+tb6>cxdvZ1)Gmz9CZuE_J#&*0)-+@#>D|!5&-!SG3ODgRP za&Ylbhbe!cn;0Y%Wf>W950mK(x#>)y%*rjmUoA&RMtWCNSlK8E1VU(PdNg0BkUc-$ zv!SF4%FAlf5F=svSA3z_$?_{qdqbK zY~Q2XW&Z)Q_dhF~Ui)GyDu%CX;Qbpmqg=Dzt;7DonNbuL{~+z)q(xJ`m#zhOzKjb| zYL)mFe*=_vp*c|e3-ft~(#FX7FL3;yFUMp4{cM5^DeZ>%UVVAH&yR->AuSDt=X}aU zHheX&ZAs&8OTCMwTjfCr{QCcWy4d%|k>Ij^_M1&636K22+1sDIjZ}^>vF(9&R}yGT5@#pE%II}u$Ncv63A;f$E6dJC3E-aIT;Lzx&;D5s@T_cP z$O@p6EiYHYEjLr*5+~D%U-6ZeW@);+BKWes`c;{W6#WsT!vJy#wMo6V6~_TXyz@zjMER6G1(sZ*o#lL}a?ql>$cr;$sO5DJN(0!9m{)l;hr1z76;5 z9wedGV|W_X+D0!K=M-%|w1>asb`02Sp+3kB^H{&ZhI$+KU5VEA>FWIcp4MJ~NyW8~ zGzNhw(q#~b^v$jO9Bi?q3citqBb;-b#rFy)$Ef6(P#qrngtM^XA9M4t5L{e1t^CFh zz?A2F_2Icn+*HZuK#&#O6Z*ynxyPue(x++L(+O9o=6yctkk5RnlB75*FQ3a6gR@G; zqEeJH3(gEZ+ZE+$PJhPK;3Jj=RGugsjs*;wr_Tfx27cwnkxWzyv8y2}_;x^~@gJOJfgG6f%Y)U=St<5O}wIa!4)UQ7~A*{Z;6pg-+K8;{3q z4GjO>F*+I6afIt)@T#@LV-yI~=Y0RUTjg9z^Y#ox5jEQGLP4X`3W`66jQ7>==fI=? zN!!#tiq{!pnuNh-4W*FFU%9i9ho|F~PYb2OL|Mt&B3!3d?lNibcQG)gQNLQ25GN#n z6sva&OGr*LSj*k**+nUTy<~{tZ4`XIq??|h3hD6;S?pI(FIw=#u%dg9FXJoMo71B- z3$QoZlHNOc{TJ>^lG5qDHef4r=E2ri0I|Rqu(|v7B$))#(l3E5d_C1BgWoCBoKw=r zy}CGHJ4QM&8JMvv;hII(wIA8ARh|c-W4UfY`EbNW%Y9Bi*>N@KF5H2nyEyTzS0o9S zgy2sfPePuIe7uprvr_K>vjMp}oanUb8;1q1$T&Em#l_4POSJ>LW_y1w+TmoA=|u?= z|GE<83$V;nlz<40J`9x9m5Tb?{1~=R;(#w&Cku3rVdoghONEQS#*`# zRrK*vQ;X;szQT|&7@tk1;v!QCkLG5AG^XNlx!(BAe$cw*ss5rIRh_IYg_6YDcDqu; z@~RKd7_~4q{n%Rqeu_6-CTKB~s@hwu)NmbgOYxB!JBh)9j3oUveq1Z053}QANg7#9 zY)yd6Gfut*O>bn{`E+|RqVd;J6_H0$Q;y;L7O_=V5GXjE$sT4aUyA!5dn=C1m8vw# zv}9NNZ&uDm4}@c`b=evoZa+YcFN_0HVUJ~oUqObCy~gfx6m^d|NszeAn2~wcMmnbll~dJa zqFKa@^mk)Kb%>d{Ke2H9%uR*3!|ab|(ixFxTXKlLPJnS{H`E@4`635#Jg9LZ>QFG* zeLLv(8#L_U^_jznw`Zq`R-)CiwbxuE?i$PhOqqkZ5iUHY<~^@)EVg*wuVGH2pd{m0 zdVKjEhE4194~n> z7@N{}aY+FYGRsS*o=|SV>p`okY!?po3iI7MDIa#1kRy!Kldtm=%pKJsN?g31&zf}f z*V~ITTkFA@iQ1 z|IEpu;>{aE*ob#ioL;17_V>gl#ALFAJSA$W!b_DL*IZwz?!jIvI6esGVyJ1LZ@j$y z_63YLt&zKzBQmg9fuc+?Z^~$zV?`T8 z8qR#AJc4V(X_)!b*ULeC%PT*hga&F8^N%HnKj=@Vrfs zdl|-1BB3u4Bt^i5dqxcct=tHvOe}Yp#1UUA>!v2mW~c@VDl_YlbA_`&5ZHkc{{un6 zRa8^}A;~YEM(yLq$%#aTW-C3``P*(%)eF;zml;u=8@#q)zrXuRmf(km94Ow1wy_Z@ zt^=lA#IQSqT07BazBO`ECjLL3BwWLgGnS`I+=^0D zJlxdPLk}*C)MsF0OVkmcU9{-8SN&lEp?U^g6YVg;;K^L-4AT(>!IzXD)&%1}+2>~$ z{M=cm&D>1Bc7b_yi_5wVJ-e|@kyw8^BR+kJ91U8U-3a{uz*HJ_MG;MyZ~v$C>t}`c zo2P4IpU8xbDvahv$@Fj3+}ZoA=SKPeXlFU54du6grknpUN+2{=hAg zzpF;K(s+{a<@FUn6p(=aqq{$r=KlVAUu!%GgwqlK^0^Hq4E>K6z{keM=9>(PR62K1 zz6lPWXX?PfcV@|LKXgsM$j55*wm%xU%Ey>|kMocktAq0^9sh(SK0-xTbw zutHItZFWgh``UU+DO!^dN8 z`{-I|ce$b6uFt=(LTX*t%^Pc`za#M&lIl6!n*dln`?of(&ffMfR>WX$m@piV_Yy!xcQA2c6fNHIOvC$cd z%@#f~BH`}gVdLo7H$R^M0Ml*2AsK{BR;XM>2+T+_P8J5DHi3?&T_EGc{c4b`chwi7 zznAVnF`w+vDqYv&{8u%LFT&Pa6@V{~<|{Jx*SB8Kgk%=#EwJlMXDMeG{?$%nfoQ&o z+pDXqE@S3w^2PTYvA%zBm>>fNw=+EmGMQA%VU1K8=LhxHuOl9)emdI^M=meMa3s_N z*w0j67u_pWrHUyG1wwe+6n`Xny}wuMZ|PldWa7dfD43~>uOwD<+#MO0Mam~0kY&^H zY;#h3gR-Wb&CmqCaSVTUeh`x ze0*uZp|C%mvA@!2r*CNZ@lO|pVuj}D(QJuIjUgAkJ_$dv2$m9K)xX0%&(~0002`qkXK+0V-2S^EOH0Y$HBxg6b?elYKV`K8o%}x1I z<*2DVab$daE$hyB(3b1=a2PcksO8&ZRHcvIU69asU2o;1tS(8dOv&43*16pUhfd1z zh!L6el)iCYtJX@CPUr{f>RizxO|8A<0PG!Z582ugX}qxJe@S)zLdMrh)-KH-sLuFz zF%sxQAe)aY>h9Uj-9~WNoXgrX{xpj?``^`7iAgwPa_NlTs+-2`zup zVhL)^;z%BKS`nz~#Z$=Q@J#CNExOv(lQ)`D0-NTDrlwmP$9^;|syt_aW=T+5b|yLL zQJW`B${m-LFvrI82wS3E{gj*&Q@a*bar|A!;9^7|K<7GAlO<-6)wsx#WfOk9v}V?^ zr4W4$;@iJDoEKf@4DTmX*SQ!fVs<3&8mxI4RLWVFU0er?X@w>kn$>$?JM@mr5K-zN z(1mF(1Ho#iI~1uo%8Ipj>e1i#R%#@@$++dM;8~0ndn;eya+ala1re9tsU4{HLDYd0 z3}1G$IQd!1a&u#yd6>%NQm}GdREjO1Qq4QI*iXJ3sd;`vc>AO*y_dj!27DN(ViD=N z9ep}=j_Oz)hPuy}j(vkO>U^s68sdz;nim`l-q z8Rr|%h|wT+e%oJ&^ye-&%lX1{)xLHO?~@qar^{wz4;48HJ2JfZkS z`VW3OAU6*RFb9pP!B$p!KjP9}Dt^#_PXuXQ5%L(NL#nuaYk>b_nm6nfKUDuA^QSK_Z+aDec%I-M?;191a>29E#Ky8`EUi6HdCqUy zs#p58a0kx+2Q#pMOI{jf47mjy%=AF@2j%rvbrIhv;nyVZoG zwqi(Ln`0M?4d~kWkB<)Duvf|g65ou~`qC_V1{#zQPBR9ptkw*s8vM!<{d}hNj32K! zuwdPM3?{!7iWW>1Kjhe6SuH0&I;gs-wjzntRMn`cjK{UlNpI(oC0`Ys8pS)p3$_}# zcxgB-jn^1{bpwCJ8hz%I$SYF%z-R8N$w#*N5bK->?vMU>_RQ`d0FnI>lh31{)sDr# z;imo4BzH?-|Iy7PG97noV1X|NPnxE?Rm7-x0o6MB#y;HgHGMnJ|N4?^^0(^NLd^{< zsZ-G2&X$Jz63a$?lj=c`*};4*G8Ok*{{vV|;hDj114*}w<)M_+a^~JTe!xS$*Ql(`d&ze^0=&=v?uR|?=@Aj|z(Q#w_#KHYe{p$9 z@n^+Q0$IS{6zDOa+Fq-aS?nc6DCny*wY9Qw;s}WCx&<+R z1^4z-8xCirh2*-yzTSsIAy=G|D4<0lUymMEjU``E6t#GM?2-ChV@7EJGK7ob+9+^PWo$(@PvnXi z0t%vNuH6|gE1cH@I2EjPwdEvvGRKFRy;i1_qK73$&(u|aMXvqJv2o2CmG)Gn6r=Nn z+Ni#JJ6%xL&o~!E8PcWwu%ZO@?G|nnZp+>u)ReDeUr#Jj=DKeyg1H%X zc{~rVC}(RdWi-#m{o{M`qbwfRlWirQ&jj%3 zYvj=A^QVUe(W*nu%u`>S88b*(b@$-Urz>iq4t(*wkR41u+gw{JX>rDR@)R>@>Cqo$h6ikGBKE)Fxu&5H@e=-J$9wWzO$ zFNz=2*0e_K5QPrcqao^0aGQj)tTcKX(Cr77I+c!N3g_yObsl+I=C@UDb*=U^4!hj& zc?Awmd8_4LO)jk+V)giH&g=V7M)lXrK@SvEr>kd9*VoALb}7ywL@!0}-S?mg-Ykgq zzWotF-Z2|H{Z{UUqIjJ39Q*k57yY4(Ih8FqSv5qa?U^myW-1n<7bva@?T+VJCDtI@W(W9TuD&9-EZ!7x$p+%?f3Gj6o&CLOBQbL7?#wb_EGgfEcqvetaV+%IauVt1JUEAE9f=%QoJW=}s>cAh^BKmJp^(N=;?jDRI@4do+W=;-8tU0o!ZcAE#RACJa zw)q_^fizY9y~&vLG}!M3=6IHbfu_bgMN%XcXH!>fi6%X|IJQ*QFM0{l^R?vDCMx9* z0w+j#q7IUF&_rWy1F`^kJni?l*Tvy-Hj`6hLf0!r*6=d7;mj_DyALy`yy4QGOXCn0 zv{iejBsh)O_nM}VVoyh@Jg%X&A1x19Btc96)yg>mtsDlnSTWnS%rw@fZO+q;OeEA5 zi-Ha1;JbdE^@9bU*KdCfE~h`o=l%@u6RdT6^l8cQ>NbCe-$-A5978p3XpExAaxG#1 zi*IoBDmX5^|6Fde8q{*zdjG5n!>zvON(*|KxowmVX*5@0+|quJAR0k zZScwRYIw0Ls~6MqLGN;fLAMcZF!c8;-)F4`%Hz+L#lI%`LVxfTd{oVhsof=t?@h=u zEJQb5`sT?Q7c{wy?F7aMwb1<46rpT+-f$#Q$=S8~XWK0(y~bLv$#7kPR&WSBZ#Y_g zg?dkUAsM++BjMe3n|5C_EG7bKAP~j6&sgq(d>3bi(CNGvs`hn}Y$*EDjq+O>mrTz8 z+Zpa(^adi_@DRKIT;F?oLXTIr1&i)@l>kobXA-hZ1apQj8pGB!IrzXh&I;Sfam{Tb zC1Y=P5){$Ezcojv>`+M=A;ddUNx zS=|_f?tfAJ#1&KbOq@{ec`96d>+-Yj98Uj70iu4Gi8RMDs?K8>26R(3k&y z@x_$M@vCJ7!`YkqRy~d0y_5Po!HdDgYe&(;aUz;21rsfM@SclF|?je+a zL<-4BT=DLY=&YtS-lsL=q&|eI87ULlTAcJpW>{@6IzrXBJ=^Hp+ZD&s2t1nN zS1%$6Ryqy6skYxIapw~#nz-KyGHv21ZG6!laK^ z>~G5<2`>GzSN-j`c)I#vVGePmP$Knu$7jn#oXQ5htZYro8jIcH&yrJY>$WMvT%q9e zWWl$Wf{V^T;bOw5{be%<`cd1QSyUNu$_k7x!aZhqnoF+25c#RBI{Wb+J85-^>h|L+ z<}Qy+P5BSEw#Q=3zQ*%uyUW>qESpPjf)lS6wXW~kPS{O??78i7SC*ct9*Em@sO}er z^qrkWYKQ5ijR|iA(o>5odgD81%;nRGydg+|59YAYO}SFd->=j9^%S{{fjKq;lzo?a z5q*L)h231+@Y^a?jJ;R6wej^6?}^R2Fo;KDPi*BAegc=uQw!^YGM$J3ToM^%)YPqLiO6 zr$lxCsSCP30ui}6R#FgAs}f`w&xQ!Ej-&<8RatKmv=zoa+f;DJ4za(BY4DtoeL3DvkgdUT3%#uouG;JoDqmNy z9>5oj8@qmZ+lETweUtlqxn=uSk@3f_;5&e+ioXQVmZQyw<3sa1wBD~&aEA^C3MLrK zclTY1nsOB2S7ypROXU0;g)cyeYP~47+ za1v-Wwg4{Y&$u2STy45kg()OG@(;h(B6g*$^bg^Nqsxr-cr{G7*yKQ^S{4uVb^uLa zy}&G%L}n8tfV|293@ktlOuhMH7clDu$N=NOtp}4xRkTxcq4Dx?1uDsn$gn2+dhZdbqwgBLS5>?Wp;$f-<-;VIN_mji_-HbVxD%h<3MFshYpSySPF1yK4J#i|_+Rt})~Wto zVL-PEA_%blj4l~~&I*W)gUKAsGd=E>B#WwWW<0JCX|6V*)ukxr_jNLN7NCEf`RfY~ z*22QXMgKAd#7cyr{Oga8t*L_sW&M;15F{yZ22V<@#>#W(WNK!%F0q+|3&yhX`1E#W zh8{4iVM$*1-^xhCBPb#W)}PJA#Q12ZvqYIc-w-zt~3Fcc@`Bk-$RK7K3AGnP0hwfFn%L?-ORt(k;hS)ij3~$<+Bi81ABmKzwm}RAy zZ`geYliV8n&A_sHFNNf#s5muaIv#6%>gaoJZjI4YA@}nb+Ks+eJw62 z;4HuBac%PPCX8C(n-Q0}29(@xtJT8$y%{&3z~{>d;{V(ytgrVZy{UPGuR7b{@kEmF z${O(fU@y(ncoGES?Z3pl?KHr;Ravp7p&qkUo2qi*G{9`WBDTx@o;IRZu1g&p1!DIr zQGFUnm2r+^nA5GU&MMDU8cCAF?4D&#b`ok`ywDQx?xyQd&RQZtA>eHoy$$a+m) zwsy`>u?{J3wU+M0RYz3qJIqA;QtKRBELtaa_m#Zf4Gp0!A7_-4IXe}uFtgIb613im z=Vy^vWnMx2oqMX7O#7veS6p64<1RIRlh1k>?xj2kN~s343^nX*%t}&>2RFeRkUy+NR9v z*y<`~Rb(>5P<>7HPja4Vf^P6&g;J>PZn0F)VB4NYyst> zxY9bTwmPCls*cOjaaL?sE;RFGb9MB3j93h$BuGw&7+ibs1~;sq1A{Xw(QbYsGDAzO z*16kk&5!22hV!hDf{1|B?og=(1e)G`W$A)}P+oS1H4BF;a1ZRN!qijAx9C4wl<{58 zuYImu zTd>LfvCHFz^Gz=o*7G%Qy)DAUWEE5Sy`xMO%>l;Ap>IN@VuR=P!G}e48B)`&b2S7D~4@qxZ8Mj2QSTJ1fFA zg<@HHpU^PZH*C(@G@tTgocwl;jl&+PE=E<3qe->>uGt1^$^JCL-{I9(a%HAaKQMn1*&Fy7ajJJLu+PDZwVVm# z4Ov23%4YJQ3aIJ%wLGIZr>M=S<2rFKe{*mPWvBp#!mJ7lHAt)$TL=>E#84|^)@E}w zw9hAz9orn=ZulMn9)lm7@hxH9ysvbJ)OJcySh3#q1Qg5z&+4YfTUXd)&KRx?T?h(` z{%m=?Q?Ssql74Sy5am!P{wgS0)=IbvG*}!%QXE(3ZvLE!{sp~n-da>G-9bUP6kmkK zjmjK%_43ZPm(`&aVmc_O)|fGw>paxx=r`03TTjhVcN2`K;(#j;r@TadEV%-zeJ9VO zi6sOSce*nW_BLMfwU5cv7lBY*zvo|J6z(%Lv_Q^erN^@)AOJ)jz5&`E87C)Jn6QAd zvND?K)E1^@+SXEYDz6KJ8s5I~c6`E0ehd!BW9i7RkHx{J;Mb#|Cpx(NiekaPk+ zs*qygt=&%eXTa64AD$K6lMxY{x(Gh)Hg)5RSZeANn_>Mdh$*1_#( zf)cVJ&KA;0r5!VvVe22b7>o|?>el}N9-Kf64#8H%awjuI_;_Gguf>QUyM&)c>y6ZF zpSoI|RD;P}tcyP4X2*8rq0b$Y!nRw(m#&<{KPaH-QhD_sFF>bk9)$uShF6A&C>Y50 zX6uV3wP^&=-A^IRWZORGXlEdfq8+&ie-9TuTHVS3Z^}Qsl|p%X|8eL~{MqmhB-wB65XpxDmZzk3u|p2wZZ>`)qJ*a87a() zVK?@y*j72%#MbN@57w4MYAnrF^agG!bjvE0x0zsD-GFE ztw!^tr<3JFjQb`u8jBD#k?tXsnwCD+re0&Gkk)l<55V78Ek`!pCQrHysKb#aGpsS? zz@PS2vVuM6$)jA;7LvQH>n{1@A8ynJeH%5EZSEG7O2FtTX6gQ12litC`4S8}-b3(W z(dzI`@e>P{qwda%M-MLtNJsuB52Nt>p0<+2Ov>KrPde`i24|{ z{@w)S-7z%vQS{sO!$mW{(h(Hg^1TTYlij}PmI{c{ib^K$&$Y@+|}M}Pj>YW({z{~T&u za_-+Y_{xrG5^;9dn*+J?<6GB1j*qvON4qbSe_m|=zf?g09B#Jb=~7|w(}hh62w=jY z24+_RQxLgV=7AxZlg0xXe0*48FbJbIdnKi~YYBc*9*JvpJ=Yo_WVnWJl~#>1Zp0c? z3;IsJ6%5EmXhN5l^$7l6i^0FHj;VdW2fUd4Lkm=TPa5|aGuz%CDU_=>b^(y45$NNF zgoFes1*V?@-T9TkoIk~K^+BKqygOwR77SCb{yJZb z>|Yue$5m0ybg~7mF&=z0y4_X3XIR^Y`_kXo(VrtNAkpG&y!fvBqzztG^n}TTUy4pk zSDa(H=#WZ;(uv;o^KDJ~b>oFIHZAL4@sfiyW`aMKqhh?e37=8`sZmjXiz&44qSVB| z^j8@L)R@5=>z!XUHB8_>AJo*;YE@~l!u$d1!S42Gb_81L&8I?@Woy5|=|`*YbxsIV zZ@RnCEBVp3Z(X#8kxhaJGS-jd91O~lU;`KNXNd^!tRPqvV9Asm@ibfGn8P>&%`GBd*rDRin1?5?Q2 z?Z%$AW;G=v#MvUuxra&895O84>U6hvtHXisv(=7wo#R>o1s?UUw$KE&k$;gqwKiiC zJ(i@zT5`{7Prub_zJ2HjF-U|Ze#$6TN5@PWU-bBF`YsV+jbc{)XWTu(=}kW(uP;H{ z(<##%*T@I9<|D;Ha%v5Bi_H{vZY(>nuRiz4%55$XqBI z!esbiS|8Vj=gzc_*tjLGk^Dli5-~r$LQ*bagAOksWg1~yWX^`v`T1yFTh&FGz?IeQ z7{fTRBJpzft%Yd^uQfg_znUNfwop^YRniPa=-VV}{&=|l_l54#KVM>Sjp$pEaEG*&A_h&lXEa^X}z=UKbAmFs6tE1fRqrWRp zBPvM_J+nsD1Tx|28;gRrwPuTYA`GVqyet&p5v1Q?nA>h6E<_FnNUCrX5H&wP>wU)Q zNQWT09Bo)&di5~336&6@IesP1o%|`fC!7HF!lu4gdp}sqS;-Jjj7yZr zL=7IwSZ=KIhY|QZQxdN>Cu_(Ui@40hD4tpC2a)x;k@l8=pS`8l7R^^x6kmkz;HdrU zoY+{&^27LC)ZpFiDI9p0U}oOVu#!eK>E9Uq(BghkY(ztwwX!s>fEHc055BnaOqX*oHXl*2SD5kYID^8>E%*`tKKE2@ z?%@Pm$i)K(Vy<)tetvBvQ8}fh$A-^Jrq=uM$hN6L<$Fg0!wq#?j3Qdvr5-aabJ`np zhVRk0s=mBTJfw&!9TS))I40$}QV>O_twDtqtXf|AbB^#IY)-(83}wE0bRRWO!Hb|I zLC#z>r3;Ncy3=nAH00n)P=_0zv=t19)ktUi@g~@vH#;6{Z3_1v+JxBCoFJwwF3d?$ zSP`7gXxrB4IPt#(2_O?f;yb6a@!<@2S>u;(H!z;9BARpH1Tk<;vZs^%Z^Xj)MdRwF$XM3i`n$gGLPQ6>Ud7)=;FnqJ0u+9~w4?aWnGLwVpBdu7V z09#=1MTcLYxzzo%9$m;~@}VsFpwYvYM+^Q~D6Exjq3IP_%!matF7M8rGyF-5E>nSk zr$L(9NM7Cw>ln)BW|>o;*F@xVRLsA`ZJ-wqIyySQS!R$nUVJIq*xJ&S!4%Gk+S$~wQ^h7!YA2_|T$xpF^pG?bfzt&ad+S!&AIGfkk<-a{eqFWpX1KV<;nVJ1_%HKau zY-wbDK#apbzjKk@Eb}j_SkII=<5R|H3dHRX6^s|>Q8QD5LWL$g*c{9cJ(yV7C;CGE zxgWxcj{$+eWnN#nYCV#r`f-_{rgelV$-$~_2=`_Q0TdxJc%?;`CAYBNVV6c-(IcZv(M2* zSN?dn6)dH^+R|b0RJzYQm-S~TG<$Fu92~a-Z3~B@_p{R`IwoC0+rmM~bwy_-KTTPR z6x6fqcj+)1sv)jZcoo$4s4d6IwypD=oj=XGv;3%Iv@GzygT}%+GSyk2rM9;nA81K% z4fP+@F<`)9z(E_k`s}z58PVyCxKTIm_Ofo4e}rcd9r4yXb`I->ulGCQ&*Yg$xwCU| zZmwE$8c9N~NIOpwoKh;?o$RI7Q*XvqGZcYfNT2FjsasOc!bu)}QX6Q}mT8GQ?pYhi zCo|;kyVzT1zT)mL&VbVv+?^Wds~XOt9W`Uucb4e-X;b@b4B?saGB8jaKE5iwXK$8RW-;9y>P>4Z4h>99QgUh~HL}*A+ zQf6;c@SMTWL33e+(LzI}!M@mxNJdmb22qc@K);cFQ4np`lyCTbk!5lwvCo&=EbKcq zV;hBn^`ptdNyknH2YLb`Ao8K2!p0fs>+6bk?y?H$4ou1fuO@hh&7(`aQT8gxJ>KK{ zQ(q=9x3ffRO`6BHkkWfgi@kMCVpPVAdwk(qX+yw{Zx4PjBz>VO(?>jJb1o=?pN^+7 zT-SEGqkf9xhE0&6Q38KnU+*pq@8&?`3}1ipzffnw!27{$%px{)zA}xUJ!{;N_+q>o zLdIj|#`~>c-bY1f^sOZffiUH7A^1+AB1z62S>5*wQfSiV^jwg3RpQI!!wFu5REaeW zFF{OrC2T$G#eLZWnGqkiu#em2*6$K%4(HCe!mBZ9C%tK&h2WtaM_b~d8)L-wT-Y1f zQ}M3IQwa;)i;-M@G3WXP>xADA`UB=x(=K1#kE8r(%HMXn3#m*r^;~Aa6_XF8N)Q{eI1q` z)n$@|-^Bk7JKxqetN1zOIW3q!Ia&l>$EDA}JAP|)N%j%VJA8Be4xYy5r;aCdaqWCk z)|10-jAD-`M3KsN{dkSlfFQQhKHh-LYbbRF{<}Agkf4$#>T#M&hb|awZ*MPIG*r!0 zyzJMV^&U<`jfsv|Nu}jY5qkjdIcvw}G~NvCfDgl+H2Gw*s!)1Wx;H62?HJU2J)PlW z76KMTo}?JL3*q5hJxCpCZDv{b_ciFz(c3hp1$#-7oT@L<)5t%H*%hbTjRty<>|rM_ z=Hpgo%r&E0#yK99kJpo>;)JK0`@hd@NGHmWzFI9hpHR6zf}#9mgNM`a0QDng0P9~?5^chmxzKc|*1ty|Rm}|7G0B`&k@JiMbJ957VbDN& zb#wX<&)Gky%v7ei7o=^`^=?w{8E@k8y0bdWeRU?BCTB^m-4%B2h%p}Zxx#wifHz87 z>u2GiPvOmdM2k`Zsido<&gmsKCb0reAP!#!ft99#Yrs(~om{vWF1p=##V0>TH|}2~ z_MY}y)jui1%2fDrVI4~5^LqodYBon&jqnS0@&>(s`jXM^_*6}Dw|eIB%=VQTN+s~) zq`c5N6tfYS4!TszGCrP7$^Q}=hIF5u^I7#tk*%@h@*iCp)S_by)r!ezXlCx={U#ko zdrF>cc_z5K)r5M|mNL*uhxLPyJrPLq`sE`&VLgR7Joo*_$;3-ttn~6sfo8MK%h`0; zqgfyF8AxVt#cF{)l|xifYk|$cXT@DUolB=vn{}3GRtGbL$xNzYBr&<1RHq}2;S*zN zf*!u0t=(OV@UT`fAkH#RENbH0E$~ zyq_&+^5NnZNEcgdcCw1!`qN?Ra<%iVVAwr!H=V~VFfedH_EBZB-a?K0RbbJv^8=f- zQbae}-JqgYb#-+=!@^45zi)-I3dsZp1!YMjF`~`tFk>}39HX6`ouT#b?(FzV6}bKO zkCgZ~;H~nj^|2j|Uxkm0+z)8uF>-Z) zsqnwrdGdELDKA(rs#f)CNCIDHkHPnU+y5(m)-_8_TaFyr^F5z+bIy3=Tu_Ar0Uo}U zp{41644#oK&h`*#nI1b?pm^;n&Cab)}~%Kfu4Y>h_C{ z>`62k9|^U=H3-YZ-mqDCHd#u!ma`+*d+}fMstqn1fFJ968azJ*F^@u^dmRAjp-M%} zwvZ`atDSq}SR19ol5g3bD7UsF?rRoPbS?Xqk`tL8hii-Ve;|E3dHUUuUGFP1lUK!& z$m*U}<#A9yeR8)S@7eNGJ0WvPaf%Cp0YE z$Xo-NUeC!4JT>iuTLXV=(JP*wV#Xc|KHwsJ2#99+EBQ|pHnvYSo49yB+?lEVFV5aF zD9&~3+Jz7xcoN(p!QEYg2X}XOcX#*T?(Po3wXw$CU4pyA>8zEtzp8WAe&4Uo4=5;# zuI|U~dya9EgUyDZmqURhE1dgg1YKtjX??mv7PB;w>{~Y%h3C^P zFrSH%OMpTa)Pe;PC?#6_5KZc>-Yb^=xYXK}3B$N$C^1wFbLZ4IHv|QcfpO2T2k+p* zS11Iu-Oe3U*l#QTB>&2yC7B_mv-jHWjv*aMIzwT2?ayNa=Kdpcr8P;gCpD_sOm3|y zG+ikDf-+>2*o*z*jCi4+t$Hp`oQSb%OyVLKFeK>!Q09L{?_IFeBOF3V?JhCY<0Y|T|r;D ztwrxJbRIeiC6^!NM=UJi1hq(4>ps0bhpXM5HfvR6;{gXVE)X}(QRS_mb{WNk!h*6t z4Jb4(t}zdVz3ZKw!{TfLGxMSg7r-2Yqpxl4tRseIB<>Qg{95efyeXfh|I(yqIyz~g6kRf z?He^Re!xBLkAK`y6Pwns-|e6veVE>UPh!pc&2!Il#ple}V*~_XuzPKxB!sz7mWgwM zf?;pAP)YFgd#5lQaE+?VRl&(LpG2ZLmj@e zE6D#ZrN3k8zn1>0poz|;ZeYwu9zt^M(JA#*C`h{;WjvPs%Jify)|Fyr#VV*F8@DySPmPlR+MAA4N5=uHxAY~JY?G@E%LLg-wPU-*?Br8>Ubtz(QJ7G+ zVDG_ta7Y;`YQt+%+|XvD-nAA<+i`;#|HD3mwG%G%7if9a`SK4+O;YyVg<#QY;^FQp z%22F#U+>y`pYKgkGE$ee-=0i{jUDi?)a@2c=>V&wljYrc3UE+T=Fv%Yna%5rKH|uhHjHSi}L!XAVyS0sO`sw3|zQj=6)b)5|P6FIPp4%IDE@ zJWbQ=z3q)A$3aV1c^JZ1$Ul5ntUqW9u7OyKeN`z1D0v|VbhAZZG6sQ2uX8KF?fw0I z_M}O%5_Rj|dy|XG37?SR+vxUv(ZD9G!VWKghL$%S-GeVqIE$2U2Dwb-3N&whmjZ3^qNRB$UZB(}h*TT~+A7!17d`{6(Zggv177Th4EcS16 zkcifq-9AIm^a}UsrDL$s2;nXy70wVmIOjBm4&MaX3>}Lu&gf$wjIpQdHtM1ktF%ex z;?v9&%|0s)e+v8&FRjk;uM)zbKlqT5gz(pae8DXmTz$ZEPQ)4%xa=pCIX@mcKO^6g z)ovj4@424wD&Ul|r6NmJz!gV`&da2eW>_5d7b0q?rW^Hdj>&o~!G{@6 zswCgTYj-t@Iu>W?<_dqfu>KDb!{T(TqEw;Q4^rZOTN?PD*OR^DiBzh7-8#SH9B7%L z?4Nmz;IaB|F~Z!zuFo`Xr^SDjg|~{2z!|8eT`Q`-ElCdzWO7mXkQeeG z?!}u551GY{t*Tv!{PK$`$32e#k@>XCJ%ba}e1{$cf7?W(f?~aku4i4$m429B9ibHE zrdE&{oFEUz{4};d;#)8oH~PS=f52#NjE)+Rm)KjXH@cco zyo|+w<%x(=KbmGzUf{_$U%(Yn81AX7_AqP`f5?3DA74NVLRMB5bg$(XSH*Cag#dW zKfo#fYPjML!Us|()q=xtc@jA3YVFK9JhU=4UgK1F*nYe%s=53S!-GwvkR)#{;$^^F z8#x>J0snN*ZT4W|BRIA@ou^S-ZSj|DfArh6C;OyzSnmgeLTu<3O|?(f*O~PX$@tBD z(5>ko764=bgN(rfP>eI!0w_wl(QWp`-Rx%eH7}Od1G5jNu`=nXF-x_M zCY;Bwd`$;F?xvu_PNL5r<-pvT6E&YIb!w?Y>m+X@-cLM0ZdaA-%pIJ;SZKqt9=(_9 zGcx=T^gmncsa(x$lp4z&$-BY)COA71b4kBIwY~iJzuDw3(4a{G*hol7dt({mHG2IE zE%u~otk#8~1y!Td3l|?B-)?s}FqbTy!x2_dk==IdJs%$*Xkz_*rDh#H7W5auxbYzL zOY&R}N7fp>zU7&OR_7(ka2!I0Y6kvll110;Hn<0UK7zJ3t6maqGU7B=5eb^a^MgLR z*~|R`eHb@&qSp2k6C51bjwMIrthaZch;~$d|0uS~QwQIt3MeME@T|Pb8~3aseZ&b@ z3ED5lX|@z~uGod*5Jy1$j()3*AzSxj!MbgbPM_6fv ztHY?_c#6rpPf!ToRQTq-`@2e4zXO+dm(H^S(sS|f^tjv*@OoZg;%BxEct&z(@@-yc zF-8eTeQOIOeJH;|I_^eV*T@G9zA`!DFewV-Q!Kp)Lj zi-)p*p0X`gv`6?Hh-whiN`=Q5td-I}?_T)uYuwBS7#>U$;3E0Id*wz~(@n*{8L+g{ zQd6xoiNauB{B=-%eDAz`k(A-tTDxl4K8Qx$8Hxksw%&sR?g>HTcg1)2^T&DL(zV*% z=uIXFK=JrC_V&GFV~DJ*thdLD{uvp#q|%v01Oz@u^Hq7J6hh%>yIcL?>Ac>VpickY zYw|X{(WGRxypIr9)H_?FkC-$zWT37#!T$xCzjIKw6-|nZL*~dh-TX<<@Xv*H4SLl2 zfWpSOZ&c$*B*E~s2zc(v2@dZ9B^Iklt8IAF9WHQQ9vFo!oJs6#llz^QLE3=5^k_xXb{wsQ=?Xp2|t2bn-#9KD7>1SRMa{pz)|Ml&UsPNnV?t_ad`O60Xh^7L{9s!MK@ciZ3t|dK^NIjIr z>y0Q#3@R>mxcq1+^;yX7RkhCA_L{mqJTm+DG!4)JV+zlcZTOpTud znm=U!i+9gostFYcbO5pG8trbsCwAC8TpEIAS_<;>zXJpPY5+=-C|9ZR1O17?{no|{Y$e5OVH%&uB@-F#5_IT?j8TL-6 z&&YeHdqJr{R8q~oF50pMS8~hl!fE-ElT*>1Chs4sibiG1536OYi+9ssSa8C>K9#y% zwxaPrFaHNoAP)^Rh!Flt5(kqv`Q6Tr0fY^JOo{EyO}@>Zz>BM^uLJ~Opg8bKt@c#c z?ji4U#WLY*O*_Qt?K8^T9m-!KviPLsbtmj$&Wo%$99C-BSg$Uet*{Nr4RuIfuR<5~ z-YrN$On+JI8OgS6mPJZ6KygA|Uf8_`&vtyt2f2p{-OtaIy-C%#Cqt?lS=@GSj8q%F@2ZyK)_=zgOZ|-;{{MBnIa3nG zHa80z1K9K0$e!t%#)J3)Y?^TxR_IPK@9sR z$q#U&!FiFWN-ZlexQ(0*PgW#ePXue2cF|fR!t#qT{ZMW8A^1--U;C!<{3Wfp-eEI5 zRKtwgmY=GkX`^$NUqhvPtmmI7w}y=9NO(>yMKxnlT=p-DAb*-!Xb=p1+B7qd%uoko z=1uO;X+`4Q?YWFD*6tuXMf}b1yUaeN#*rjk*)M(G+6|~!gH>1N?E!fr=j{Lr`6{~h zLgujC>;u?oV-beF@f=^trAe%R#m2W7|FWaQwvYCF_^JQ{B?Q)uX?$Y-^raSBXF1BOerDiQjqm0jA+A%VUOio|$QmHsLdcyBA)YH7**ezyF(BzDn z8nrN(Fz+T6_OVCq&$I2#4K&^%0yKvNRN>^it}ia8yuLiCD-8HEqjg0nK|qfU6nSLl zKg0$}m2ITWBN9(fZm7XJX9BjYz)fVU9q)ujv`wAqGYrJ0Kji9t#eBFKk8j}ae~xya zx}`SvxQ)zhFX}m(<#7&T1l4>+*19UtOjm+8DubLt7W63?E}laEm%q z514j!CRl|UH{#cYu-!l1I;w!|&-8)vd|+VUb+!D=)?z@%?bg&)F!PB-p}Mx%#h(Am z*d{)MGH&VyShBU1{nRJ<6}Pm=}ao zeW+1e^@r<|ObY}HQBQ44BW=9-w*^55ix0i~5_$2K@6a2^b^2o56yD64J0;7b@`To> z;`%eUgV7WZugmZ?gMmhVo!obK(gn*R*bB}=1(uVf+j1?oHjI-s{g@BiOk#^G`zt}T z2fWSXZ&w_nwJdm5cQYu2f`$KsQ;syJ0LsU&5aufbwo%6at4+??@_%WQAJ3)ft1cBm z)6aGo8S6_kNjp?BatCY1VKyj>~vs^cs{oTVDdGP#s1l)^3L@wg6*{dx0@$zaI5e9DrO znUQiIS+-#16<5QoA@jZUHLyXPFsudammyjcUay&_{T}d_6umjzFR1txaD@u_uLUoq z^Lq%bV(~Z(sjm2ndErHdhFmnijs8mCLi?l(S7c+9uAMdrQedUT)_IX##d$ni>AkI` z{YL?1A^Rptc{@XHc)~t&!9Vm8?WNrbZa*vxNm)pE8YuxnBGB9Q==9q zWH^DlmA!~s+@*jt4%Wvl@_=@&KseOTg^hhnu9{ois+4F&+GC6q-sHUaqwuGzPoP@) zIpXC9d#4c_H6`Tcb|SP$6Tzc}RA0JFmS8xg)JE5-f3kmX$&b6q6jey2yxM)w+cTcj zZi=b#yQX_l^asv^Fw4;fo3V%1; zkbeD>uYW<%a=ziHluxym%%Dd|I1~US1Jq$kp-%x8mtxLZkSr!&BFh!>6OojRk?G*&yK7_2R{n89=JI ztIE0xEQKXI3^3grPL~qA<&?OI)vnHWBRoE{GP3U_ zrG)%&=GNxznpZSSstUR;?C~A0UWGT~8acDyIGW|A)B`8gvrxf6{$n#}hMpA{eV`P+ zWpB|sT2MjK&d@udJifeS`XcuquxgP|5km&?OQ3yO_Q6D_jx>MKyzdZ*%YKyqp!@0X z4dNCraT!b?wA`EuT@D#X$(RnK~2A5r5nSgT3Ys%o(m> zBM&c@ymvXyTE0ulH6ApB=M%5+&-`_< z!Z?Y;OPE#&UXns@QwyzPy@V0YT=tUpQ!E4pl-Xq2rDng*LZFnLSx0&CcMaa5)OudJ zAe_FwvJqG5FIPFc76q-s34IN?caHhHV<7-iL6Ml89A;EaO0xqP$(e$5H*bbg*=Njv z%D*pO@)25?3a@{Vf+FEWkG;s#e{OdA)ChGhVNJL0aJhkSOxaD2cL8#D&lHg)q3~&$ z@L-x+gD^?t(=!*IJLLr#A{JzZh%D^BXX*Ss%6~EIe{5`kl^4+%^~_sOaZ}-ghJSZ# zn{&K@hJTOY4gn?oBrv~x2#xs=irNsE%m+*@5LRavGn>W|npBEhQp^iek`veg*-9sBxKI`-)m_xKe~-XY5TXZ+c)fwfQ2 zS7|?h3q7>5!)n72hC*^)V(JcY3q+O1DlZETE z1*de;qEdTO7+#WRdtTY4$%?xx9HmpEjz`_UDy*z8NwrImV$s<53y5t8jo z*?s;tsjoeX&3bg4C(+s#Rf61ZqP&O<3~Z3Vs_}nE-I?oYi=Y#n=idX=T(7+~0IPV$ zIY%-Nnvcf}xT6v0-@jxt`NHnj3x8Jxq?>V#YkHS>p*w!tEP?fnd%iVYr6v>3RAzfo zG3MhI$_`L?;Je^Ruo@$995~cIlXEhow*3*;op0CPVxTz6*;iaO^9X12WQ`x$o&5mt) zz+v-BouqvA<&dWd6`^&^=hw;VZIiIqcTKFOiqrIWixfd)xuX#omcffd>u? zRtS7b6@UGfp9;=PefhTtp^{T_#VQ{og)MdTTs&d93);)6r?Y7HwF}+?bn7)RB*W%X z`Nyo@*V_R;f76c4xe~UmJdV`N~X zrbg)X#@qPSjki2ohG`|NitpPRLsfm&X&4C9;?>f# zdO0?ZR)9|ww9b$ihe2;PR`*lppfb4XYs`0^B9l1U{Hii-kM%+lJY^wjUtSuqw;Tv_ zjm_&zL#aovijrS#{PBhoUDBFM=6QMKVykjqEO*bH-#mG9z$ zqL`Qa<#*(*udnX|ZZxPm76l;-V`F0vAhe&Bi#d*OzO?k!kUk9<-7Y0A?tag>t;djp z*OAF+j0hsyhZVU%lxP=7ipZdO5`OOXhlW8w04hGTOg5M+uZTg{U5&qEYh~ZP_jEoZ z+1xehKjtG`JfrGkG~DW<<25UHPgn(za=j`<8dE)ZdtR7c!&&1m_il7@S;>8fRR;A5 zyoZK1e)P6g3eP12O?;IB30XL}y#@@Qu(89#!^NYvYnz%xKu!JWNFr|k^o@B3ij{L2 z!WC<@;3RC{Euzz%JB@7YqbGlSW4cmoq|q3szMDd^ZzQ={^6K#Lrf;H%$S+AELj7$| z{nKd`faDT<{*1V#D$WVmQGUj#<-H<@MF67NzdX^PJO=l=$rjUVPt8dq@X`XtDlt&8;Prv| zzVWebejndN|L7O@Ra0nr%To|c&1nxz@u_~93$ML|?cd}5fGH0npSBn?^yRvjR<~P- zQNgIpqV)G;o#_po9#9|x#W8IvJc9B=$M3ry381{Z??c%cLF$g-Kd(Dp+f||f#-2sb z&n0Xwa$z@axio4)4jHzEF2l4Q1!~7Z8f>fhOG$bAf?g#oUoc5WqZK)JCIiw+LU3aL zJ|=ygef?#V^+)sx(d%bYt$6apEudjxTY&_BZf|ej2+=@BE#v7yf~)u15xCc~bwQBpnB zE!Vg|r-5fAS%J;_1nhIZ?6ix_>B9!KjAL4CY0_8~rI{90#)qa&~)xXR}2 z0snY?cgT$e*GR*VG|X9DydIVa&uB3}#p3lvm6b_xYy3>_rE!{wYx~Drhr7nBAu=ys zq}Ntm((GeWu-h35Z{2Vov!oZ*TRg%w=y4UBcYeASFKnHj_&d|P zQzaPVnL&{szg9z94p!BUo-x3`J@?0P%8xi zIrC=I=oyI%&F=3L$-}H|lekFGM>SsDV8yr7ZGS!z%PSkM*?7H9g>*P%rV&3@yWQbA zS-xZv$GOYC?!i6=Hg3du;Pz(!usOlHFlANcG~?pTY=gAs=)NYrdRUDgs2EHeua`}I zT;^X=ssyyI56I;J1kpU7aJ419qtS>@Kf8~AtF(t$l5@~*Oaq?H_w8X0JVeWEx7fXM zIGvzhUS+OYyltBEV9UhK;EQ~ovmtVS-OXc{+sX}*DjO&UwuaujGM4Q}=C`c!kkq>b z&ZB9MdH(nwg8om3#UT@=$gvUSD^Fv1UDacY1us0xua{b*;<)R$0fMI zu;*R&-RGoCneR>oPVd=YhIZc%d3%f>uq2SF4f=G?rN}uB)R3}2S>8!i5pb1%A;u}E z=Sa+Vs(Qd_dAY6+lq-IZTBcN>2K?B=5qS0R>~&v+qdVWtdB{nGYak5Zh^PGJGuiVl zFOL?Yk%<2n-oPA{kgmG;bt2@&2eaPb<=UTl-buZ2X1ZrG;iAE3@3IGQ4c63i-lI?l zO#Y-Z#6mRKU4*7qWQ?7+@`+>Bx(I*J>3)D8f=EbP_Z&1X3fnj-v0=R2>(wvJNawp^ zutH%vsHwK??;QF#r`5*0^R0boKsT~@=R}N;lG}~aJxtlEx0rd~b%BTFt$Sq+LZ!-d zr1pg~nYE47vNv_IRvv#XtKAPN4Mnhfbk|T5=DZqE+|+fjBhbzxet)BdhHCNZFI|dl zbJ~(3a(6G8p1vGK5d97VKJdK!84I~d)7>G;J8w+h=@uYg1`78K8ql^8hnz9F1^yDk zwHAqh!d`jTgVA;gk0hX^zwoMSUYcZE6q5jn#zONxn$yNR>H}n2?rw=1b28RV>O{vG zDHXOV-0t0nTP}s<*3W0Gj7vovQrH(f34^QPZ%v%PpBvTtot_e z^z#a($PHz)$!sB3Vd|GCSycT6CU0hR;G)Jz->QTKn#5u*;)2Sr8aj?m`6{Gv={3*e zkFF1`$Xi*tBWGZLVJxrVctogHs~zE5MMAPDC@7~SB=(dfzF^u&@QEBwZ+3VHu$fYb zVAlt{aW82kM(SQYjpM2g1$f(QL+7zo0%yC;UU;U6S zC~cC;CZ${svpRqto~YI{XJft;c_}{|5u;dH7&^T1Q`1)2YqIGf>)<4qV{Km8j(Fdq z)*}=TmHJscJufjEz0iFtpU}%qk3xm`xmb3o_|zj}z~w(UId#unld6++jzHr=Z+lzO z>q0W1r4OHlYZvtgPdYpsK?}UAAUt6;YJxE|QNTdvS^rMF?Wz=k^KD+4n%v3diy{?p zB`i$%;#dEU(b2*AkjV3lCr>0SSP3ARSr?b3s>)zu_O=b(^+>l@ZTl9Mdw^Om#+@*} zxP25BUo5GqoxN@oVWqh@MU#_Fd560rT@`zI1{+6>J_W|o+}>-E)?;=I;bz{DY9)jJ zJpQ7dA{UsO%ftrhq|>)z<-&Fl%GsE_3E@7yn)lf~=<&yFYi6;`?NPprkPc2MS}OPBithGJ&|6@)C-VH2wYjziyuO;$?Qn{r zev&h}eGubtJ#4YJqDBrz%ug5#pN7NIPgBIe`pPngHPbBkLlL1;x;2p;eX;50EUdccF(=m)pPnu6;ZQH7ep*R#rRO12*^kp8UQf;=kci=3cqjL{QAP=U%wk@(jh z?hkp1l`zq+93N(Sdgn<~CKZ)mZ0;ve=;K-&N3IZcv>K5HH^;Nd>Qn^@Wqy@5tZwt^ zJ?D$-S9}?_Y!s%?x4VLg02ZCw%oYcG;KBt@q`mZ_)35NM^2v@dB=KOm@eeYgEy|7C zoLwI3}`g0)Bc`D6jHe;Wnp8ak~z77K;NvxZLfi-f-m?_!ZtP=XVa@nEeW~ zbnR~x%Q=`5DP}>-6DERFV9D*A&C=+v!JYoz4=3vB%{THX?l~NJ^Roc`bc7*q;m=im zb??GF34m(cAyuCON7w#-- zKLC%V#tH6Ap^fc(=g!UZ z+7J}bJK_%%{xD+D6%!>nUBbLA#~8`a*x+P}|DiTv>`vX#tZXJ>qN$!uGm9YdP%}%y zl7T0k02au&_`J#tlthKOz!{YJtBWPXW8>^(Y#4GA9_tEHDE;LAW|Y}#O^kq$Fy%+) z7>Z*Z>4g@ouy{D&2P`pHdM)+xGr$hb!hWX#kMPi0f%&xlXcd075YpqS2=n{aHq-O| zKPvr+$O|jjhb_#g0OIq$4V_}2xi~p1(bS7I9>Dk5Td>X6$7K!r(OOdY5ugJwX*@SnPL+@ zPy)Y(>u|s)_L3{olrj7bn>O6pBgj>06|gXf1_6rfhZ6#kty(y>@Vm4!Hiv66P!JW- z7N8)a!aL1W@)w=O{FTdVKniv+qOGcWXp9;pKG0NGJ~Bp!(h85KuR!AHyNGDkXA`~L z<^)^!DJ%}usl2B8?h+T`B?*iW-rvdjx-=qJ| zTkwz@UG+_X>%m71Uud~wWx@))UvM`;fy~I=T>v0bN`o6#HYVyKm-qN-e3Wztd~K;B$Yc z`F%?=`-|(=*LRIf!-%&>Wpus{^w*)^n~nM4kf8eHuX?l`vktdCaR*1?Y!3GBf@wQZ zjfN6y+Y$7`zQOX?=yCFja4$ByJ+gFO@|-`((k!^igGPjlghxXMp0ehnK#qdYhAe*F z4)JG8WEHGhFD|_$Lqz(ti> zx8sVmVa_Dy;XDcmL^cgf6le)O4<{CdRb5SYDwNqCFFWGc!*~xbQ5?KmnwlFQtsEz* zX6Cq3V|Z~3(JzE;^rSNbA}v;MOyg?Y%-5qcO5-zWg!SCk#Oy zS8p+N_jm=Lbj^{Xk;Qe~d~dvfL8O09VHWqI{pL!_ccl}yKG0cHX(340J4Ixtq10Xe z+|i;G#IuTxd~oM7Qha>`#AvxR?|6QI;5p+--m7apx2n_XL$s1~B}J$~KiizGWcQL@ zMUz@Mu7tOIg@W;4mYq}_&ln*MC0~rB>4ubHa$@5kTUoiGHkXE)7#{x&#(c`vDR?|U zPaS(dcy;_{#WMY7oIOxKcW*H3GwmkRD8Z-40@N9H7RE}f4&$O<(vy8elH&si$}{bZ9Sm>aY2vhz%EC}ef^7AHPE z!>u>U*)j?zx_XxYq=8U3Qkl9FmU*14>Hgwup+}*@wSIC^O;Lq{w$BUb)=IWwXUa#i<_eQ zOKx!z>RgGYZ|T%=Z0HG_HF(l<_LvN@1G5lm3vzvslE&-htZfnTP80%$9H(~-vo{$Zd9)AQ zk?va%sl`sl7-^b$3N^K1-BW9wZQmqC0=IeMrT9&yf)nr(7Vbjh4<5FqO`va=lPrC~ zMT{z=ztC)eOK-Sd5O}7oeiWpvhP=m+rKtTnD5BjykhIL~L1*w8|4wB%l1Lo(sc~=n z5lFWG8gD7YQR~v0NZ(sX_fmnX(OH%gBf_pG>5?!8x{Bg^>hXB|n7NB4t?kHwi8Fw; zJht0q-Xh5g(_%Ha2q&v}_~J32szk=(iaYsC8yTPK5=x9|>ksy=!RKCnVFeWsfu5xs zhDk#&T4k33w3&Txevgy-g8GPK#p0dJ%XCpV-PfV3$><3IfdVjoT5l0nmJrqQXEvPR z5iA42&e6=LKo@VRI{3gsQndJbm#x#{jc3@r&e!+_zO1RH3(~$KRUONHiJ@$nbjFq0 zdDYeJjq(l;CmKZYXtDZx17!JiiidLzOMgJMqqi$h2Ah9E+`5s{j;2B$a{sfRsS?d6 z$&^O zrh>+sc*1M8WjRsuv~nohoZQnh-gR^zAT3Q0^e1jH2g?;&BKQS)j0=}_!>3KA73Rf} ztJFeOQ7;YLN8w4IP3E9?%Z{0k$@ zm+3EKsFqIi4A4xAFRPf?bS4_&QPJ2v$&u6x=Rx)~Zh{{!?#S`*gl3D2zXu`Wis|U+ zcmY5&iCjT3oq=_A_FlmtBug4-Fj`Yu>a7Y|A@r-Jr>5{;N1KyDONDzQXsAtAmg8n71|bB5QHW z_63n*AV$s)6lpKQqV(^vOVhE^h>fe@CDG z4u=Wh`Xg2TRqJ0$1pTF=^6zwkM(nVAK3;3jf%0HDoQ}W8ei6DP{3{RU?Vs){Xwbwf z(LCWux-=jXeiO_`baa68x~B+eRuKMaSt$i5#pH`nSoUNa0j?nOE!|0m>B`Y7YOndP zE6&u;A&H&wx|EKQNW5Nkxo60h_q6cLKkxy;b;DjCuO8!*pg`E!Kkp@A$e;(Lmt$fM zfsS#r*9!*-@carg<$P|A=C5Av)_;H1dA+zL(r6A3L}J^^oa+uKI_0`FH3*imhwjiU zL&Xo|9J?P&ylV#RYO`EyPnzJlyVHy)o@HzSP_fyZrqkmHUUx?|UTvZ9X?ee0ud`>w zAK|>1LOfNa*f+j*_TcnxI<8mWNZ_zP4#E;@x&6@j>o5=cUia}+fLOD-MF};vrQS?9 zL_|bTQ#%MiQ>#FW6z&DR!O)0^(GHz{G-qr4w(v#$k{zPYxPe@4b=@ z2Kues0rAc**Sj?HyJ4gSny+C^Jv@agkKzipb%RdrANik^|8vZzrl#mprjl>$VV&a` z*NP;q8_I~lMUg-j2NWHh@tblp=VI+`Z}lkLTw?B1?W)7LEm7iogvZPfzB_M8pk9+k z5+&$V??l4?#r5@xTY~~t%QahBrVT+quv37HiP#@M`1xyx^E+-HinSjZ4qq>2JE1&g znqGSi?K-awpO*Azx4o5tcCWlr_1bCU%uf6D8IYVx6js^aQxhhCPa zt+i5-f7Z0DuCDJMDx)~F?6^8V`4?d`WR{#P~lzU16!@lEH>m68Yce^Ei55o|$7lm=OrUV$gBK=MNlZ zRWn}lnHs&SyrSJu#P=0sqoTP%K!z*j1A~{FWAkKD*~{+g;}}h}1|t2SxY1ZD?^!W> zmcsA0m8>s&CxR3%Z2@CT@7fEfD_=bWu)uMJ|Bmza%YVHeTm+H2Aj;_3)N zvs%%di6kA)ADln9p(WI9p6*`dKVVEp+x$;rpZ&*z)c6R2_Pb=x73AG#X9=tqs2tV` zw)!>%8g_2Q$gh@rFMS6(++>Mti4(oEqw{5~o%=vHOVzWb@QV==`7eib;cNIpdBV2G zAsFI@l#G+4PSu>HILIBT;@OH{k{YG-7oaU&K#4(f4z|E+`}kHj=*VTtYmBB4zSBUN z+*<}p4>HZQ+r7~sR-0`^W9PSMd!e9e7b8p9WUFfDwGRVMzap+SGvF^LdE$Pe^FKHJ z*^bb1i-?E>Az2ecE9Fa%zvd{rc zxuuSh6cH(X^ZrMdiK|9DnU8Q*p58_eAv*A2j%9jJMYI{DW4kKLcl2u^L_?(*RRMFk zx#3V03O}{&u#7vBN3l+ho~s?mZX&=ElHCnCJGPZ;?S=JIRSog88cpoiu-CqFcTBh` zOua}QzD}#!=Ac4w*|{Zh9ETmOjqEWD(QpbUD0zdM}(5s?g&z6~JV0igD$@f!5IM zpNn!7g6|G?o{_EN%f27ofhxy`fTtQF+yA2Mm|19jncGmS;3$}p$KlMF?L+Yv`7DBz z{_Unp|ua)FylJJh4&1*d@@X*vI1+e7}Olh}Xtyd1d3gA*k;H36%G zEo4eyQtY=-qA#N;DZI{#;X(Pr-k%+PNBX#P@5Tm@Q@G#Gp&NV z6?oFF8DY)sbLCB23lNwznINMmg)KIStp@d>4CFDxMJwdZ{|X#^w15X1N#ri3pOkyF z(}B>cXXt7xS7$E9HCXv_Tk`a#M+KnKXz33xZWL-Ygk(8J%TwM6rn;|&4X@pp#*HVY zK-&y0Xj4<~6N4WD(X;OVu35OL!Eju2(4|d--L%ZKf85&r(@FJQw8N5f{_PP5&Xg=H zDy=E51uagn_V7@WFGFe5$V2XQPi2sqGD69QljW5hK^}P@5qGyz85-&iN&JjI%MDuE ze3v#9vW~q9sLnWlcf7}10I%ukc#!T#rcIC-f-CYJvBHno2kY;u`Q}UZ#EV#sL!MZ$ ztb*x!98|@~<$&=B`>HFO*RH3|$Zuf*`PT&%$71Te=Lp)^;k$#ADu_sAnlTFH@pNLX ziUaL|54OboVIZA`mU zz=8i(;6puDAohi~H(8(jVHh%oj1N+0#$dpbk(sK9t*Cm!7-6)KUs5M+qJ78i_PBPA zwWD)Hp}dB;hXYhtg4!~}#$c)chTD)ue!#~NjI_--v|#mJQ?zWZ zwS^VvoSt&nOjDRBS$TB*MER8)hQc(O`WCObQ~zulcpx2~0;{sEf^-bzGB zncJBri>T0m_2+x^LD`Jbi=qeDE5uV((yRT`z=$-LnA}y?iJTB96eKK`s=o8hvuS<5 zM6GTsm6eykk&@^ESo3rUGHs$*Nc?C6)$TnuKn7`vgmO(9-IW$ zBa$cT;v<}D8rNOlbwp&&WG=;qk|{yjI^5)W$sSz`|EvM`A86RQZzhabT<}A%W;0%P zQT|t=X1%oE&N)PZ4;lO{7zBti3}?R5cYSzaS5US+g- zMz^^SPvi#{xEEyd!7RjQ^PwGB0{f9$8tW<7W?XQZy51a;)?#(FsukV|E$W?H{^u7F zW>4(&9IO;fnEgTIoA0r&TwLwd&(Nyq9*?9$aj(fevAy{{QX%J@#^T{&``Lr>1tgsu zt56DW&OenOvPXKw379tKv$H3QgQiJ*mgnLME0vXvg~#QH@9OG${+;c4Nkl;bYizv# zj3^L-o>}^OgV*+dTfB9A@&=7O}yFdoBn zfsaJZ9qB{tC?7Q0SaD;+N|9O!-6tXbwZ?f*a`XbiC&38piZG?bcx5a zm-Et1GR4quF`oAQpZ=z2I0Ffa^p?+|*4g9X85%NQA8a*@e~xp6k$38U8kg$9D{Nm& zgyEFG;`|I6DDlsWUaEp1iHD=6iKF^>%H1f>Pf6YcE!m%MBuTk4O6d=iVPryiJHv05 zrQ*&Pyqp(VvY8MK*Y%C%5W|=OHZH5I7Tm}pM)u!27EWy+k|dv9m>xszN6cPE1lpa$ z@Rcn#7Jw4Q$)H9>k$8Lit2Laj1hK= zCshuV-lBR|t47$Eo>L_C38P~)Jv{f$D1N-P_*)u&KFiZF`c-b0>&w15{&3+uK4Vk= zJYz6IOg{WAA0oeGh%$y`>H>}utY2<{R_SG(~V@%HH{8ET(99zUD1 ztG-Djw=_00TM6T0MM6c6`Bc=QqhjA|<>7mgUZmhlgJc4!OxWMG|A*NBL(Ryd$e;xN z!Dfcy*90x+^(iRP1LQ|nH!($WWU5bHyh@)o?#iKPR6a8uxPO7#y5uA-D=~8EAbiFpx0MwvQq-T>6J=s5wAM^k|+Ie zfshW*ob0qIiyj!C@p3Wqdz56(1^SAdBo2lWmO#oT4ik8COItZ5INmMB4H`y%hJQ{tmceRu;eG3pj;^VHoU-EDvd2E(jK=dO#FEn0z~TUGtDfQ^n_LJ#AX3>AI-~ouXXVmq+ic!pMh0B(Z`J=-)=d;srFbNU-vY5dl7&1E8}9Psooe;{@Uj8 z>6>lk;77Faa!K%MgxfLf?ggm~Tb{N!KAx0l^9f~~fgoCrjZ&Y1#t%-g8ZH({2vWYd z81zlpc!+LWQPf8FU26_^#eJDM9Xk&70eXhvk%&J&$H@TERj<{!*SIt?`QkbV`-p=w z7)7RvUNKKkRwa1xsbfc;CJi5%IXpTtg?25P-51H z)UoCfOPlGY#W6aMSZk>L|FHL-VNGt)x+v1E5D-wRgr-#K(uB}ULJ1{GmC&Sj zP*IRBy@PZ}2t9Oyiu7JWFVZ_m3BBA8UF+<9o^$uT`}{jU&V2IYOENR(95b_wG2T&# zx+LIWHXd=;ZnW8K@4NDTcY6;h6YDY}8IvE)Fh80&g;L};q{r3@1c2r~X z!^LOtP->|j!HQ@J!9Wn@ODr}>Xw`M;c}$v&4pzeN?N1ox{1CDG6QfAG6rR`BkG)REm?cG6Q1qOe2e|ZX5|1lZ{?=hHLME^xj9?8D4qO2hXc_;j@Er5_G`BwJJ@^UxMeD&{* zD|QU}|3iw~k*M?q#R-Mxny5$y36E>Ej)qH#MruUe1^Xx#9Yv>X&6?%6^pCyESV($e zTtq95)$NJ?n@Nb2Znm_7{1K*~cA8)W!o)lhloUW_&#t1BPrB9DcEmRISSMm=t7|cL z_tr||EloB1Ls>?9tD2wYW?x@Ed0Fg`dE)OGUkIORZoG?|JzE5k(uud1nA`|Fv}ZS2 zn>L3WDQ5J?GF18|cFg3;*OnzsAW+Iq4TZ`o_ zll=eZNv|ZFSpj`BZvBfj> zZ(FeQpzCZwR*$^N|048rY?Bu!I=z;!-I1Wgl2|;C@(w|3+(o~*mNU3VdNVTh{8>psV}O26Z|~4mlSfoR9?xFYNp3Q$4a)+tH4@7C2`GS!mFL%V zE9*p4sqLgdLsj>*f4WN?L2hn;|JQU|!h^T^&Ec}ygdy>({Na+_;pyKSwu}1L?I@zr zGG17EbIYBJ=>6iAVVMVf(3cafM*N&PS0bzD3+1c#Uo*%7;@{~=CNl*sSvw)2*?r^f zx7XvoJ`c)58=n-8J6SvU@?T7PTTjP*l2ITOV^E%Wx$+{0G&8Rs%SHl=TL|rmb*wQF z0v)dCI_*7h!(^6AEG?n_XN0(Bo481A?3_JmVC`q3dz{wIFp(R$nb_iDa~f-(C~ z!4^DXx$?>qq4d*V9dtYOf5fjWtla%F(;oVs|24zuh>-|`uOi2EnQ1>`yA$z`QQkmD z4eG^Ly(2TrU*0$lR~CpyaQ-r}JKaeeZ_@ZbfByb-J^5+K(bI3r57cj5 z16BGM{b*NEd#^Z_87SE{r37An@ZfQtbME99Ze<&Zz@ei2+gsY#)JzzM)!^SsH*)YHtzd>JMzd&~c?ekDd^s@VSu0Ub@DB1`Mtb~W`> zDb3EdK6vxp+|}&$u8_k0iLjtTk4*y!uyUKN(=G0|#&e%Cp&-v8&V{&D!~FHcGiM6v zx>M7zKNc&#?|=}rQYP4!yM0xlq>wBA1de;kyT1|q3*>2gQWpGL&CT}>4%Pvg6jiIULscVZ`9lVX;tz1l>S8XvZ zcZ2d5rKsZ%f?JJ=Sr1orxIHckletuydot}3B;%*@ABBqCwm9#hQs_i@S1jSJfvIzF zxE17Ny1j3<2l7Z>vBPBfoIR=WEq-4gwEX<|Bf8WZ@YI z2!vTCfRyFQlP3*xKyEj&z@VV-fR81BpUr;EHRq)?fZ`fBfh3S6!^lJ6rC*|cmz+F+QU3gvd|hokb<_*olk^Wy za9PPWy|q;Vh_JCcQWFyBS73B8@SmDEC8pri{S0Iv6!)6FW_n(p!&WITD|?!0-~Qmw z?)=^I!&-Tj#I8lJK&5~7>}98|eE*1Of5!FClDvE~3%8xDaW2rWBt2Zq3ROuG%(fiJ zIig7XgK7L8?fFKckew<36ke2Kf$$#uRzsW&j2^Q8(fkkMhn$=t#l^(|4HvYLL=R>D zPogG(Ir7{R~`pNZtS1NyGs43;$~?*RVUmabNRE>d@lWpdDokx{~XdrM3+GcxBk8y z&;|29SpGa)_yui$<;x(JJZ^mCUD0_g0YSR|KS|8M_jwpz0qvkAog=btT$ z%6Wigi{J>TEZs1@jcCT@%qgR{WL{2({>am-*8y5TwD_kho#JZI8D!&$2PY_x{uz40Z%|fvw9KqzgL=D{$s+RJG#{%C~7!+#mYOO%9s{) zLa{K?V#l|+^daDcB~`z1IShXjv>&Wj@`72JJ32x^N80I4 zxd95^zZPqAk6iYw20?3qNuKuYkhRY5e3n^f6_M}IYk$wr1tta4vRs`uRw-9(uQ)%f z5-{s#;d{B*@4D4j>hiZl)5IHl{MTFut*O*=$wKiVG-D_q!*Ekm-yL~*9U5gxwZtRx zG$H%OrOAz~iD{*J&mbt%nAYU*H6b#F_xdE}D<$LM{_4ydCa?hiI&$@(3|sCh%I$Q; zj&B9eym`E9k3^>T9|sI`WR5r=92wjNrh!N3AGLj4lIB~*vl|1(dTc}77Yq!8wn0xF zxXxhs1%+PE5Iq=OKr7ly% zamhiQFB1ut_q<|4ZKCEIP-opW_26cBYBHOdWqGx9n(w?-p>&7IeY zd)&b!n~c`Jyeb1bdode6-HXa1)jXg7+0#<&aps7%UcOnf~JI>M~@%}gJRfo zFkxLjy=Kym$QNyK5KWSX=Z=NfaOL&M&!>?OHgzq?|z=)Ly_^Y(@)Fx>JpOYYIR7*GTHrAp-$qyxU#yG`PlNvPY zfvs>pZVE&sx_mH+6n38F%pZ>Jo9Z9|;u}p&1pO_xPmu3gS=A z*tYRl6!W#0tgFj+3SWcN`3|?UzE5Xnx}}Ij^QX+Wt|Y7SS+cH5AT+&z1=jEKfFb_J){dvav*nqS2+0~v_L~7@GQVGUrBKJB z^ADyu8_K3nWl>iF|0JUaQs{asU0z@AOjxI}M}T`l5={_7@ETD&U+Q0)eSqIdq6Fuo z+>a>t2X$YDGaHp*l!3o<4hdzo{7&X(WQ!0xkxc0v({+V8<%N=5S3HUN5X@F>Jtvp1 znN82dGRdA-e<9JN(1)O-u6|9cKgH9tK(RaOruD7bS}(av9x$@q=eymnJpb|#SwqSc|{wZY>L6Ww;tA#vb@q6Vj#1LwW9>)IFJ0?-G4@{TS_t*ppRu)0>YTx4(5Q>C>kP$Sl(|lC3#48!v`n)tF-P8~ zW@ap5r{Mp=>at#caGEHWk6@>J5j@0+Ihe{c&sWhGKx9S3pd7|ONZW*$&d=^JA)3

t|{H@&X)DqRg2iYCzaa`wbXuFSK`AXYItLGXV z*~c06K_{}Sakt=>9;Qa#Q{3~Lr$jxV`DDrp_S{Wh?SVne8H9h^as4j>0!Cc|0s=b{ zHWrms>252we3ekJgM&+)1u~>v?@KJ!un*?Eb3AeJb8a54pBbBow`qu=nYJnEo_2@~ z@O6Qn7nH6pDuLEMN@6_LUwgZsM%pGtw({sdb*3KIj}c>LFN3KWa#o(hEhj3stai*$ z6Iz7Gna`je3eI=~LnrrL1@C9;43mnHs)PvdT*5S+xFT?5WS(-*D}?txaj2b+PUGZh z3~Ip@2@~6Ba1lsEK)`c@iSl=~w~aUd z8xK_+!2jgNu|9_3NLL~t_=$-SvYXPW;CfF;K=5nmF_4T*I*x$g`FnjJ?C%ynK-<7|bW*UA zD?3T&=t6riF>O}#s6fN@2j${h?KKq{wICcrAzhKo(lhf0tet_(BxTB=jHj_8@-3%c z3`>0_dBW^)w18Jqvr~TIX@XZYb3~be_-PFKHJx*k^Yb3>njcXcKhLyN`R{UIFK9brDG-%`NZ#adihh0I-n*9r4W z7`4oR!amFg?&XG;KJr`^wgZVg!R%l$%5Y&`u=8$=X57cP7!-~`C80rmpy5PWWmnJX zC^0JeB9k{XPbsKswJ^v}XnDzo7UQw0;0g8kspT>EJo zNKM!-KlYU|np#52cY>ka?y&=mqPhmxKaq5hTDI~_h;W|f7gkVK@-?f6l0`OOk|}S( zJj}k7n=`mD5!DLZUXvf$uXPb|IU2h%elH&%S zLh`0nfut@jMo9tuT7l1fSsaye-cAVYEg-c#4ud`>jXg0gKj%D5pd>5EOWO6f+|Pd| z^TfDfEsC?SefwyOY^b)(KtoGvJKl^G{*SJ51zH|;1c^L&%D72yC62cAbZP4UZBYVkIWr`6Q6)WF|LPC zsvkqUzk?u;Wm(#XHIs^{5aunnMFcD|wBhc}N5A4tRwD$9R=w(tX6&c5=i0eL?cl0X zmf{Pk&$6#}xZ>&>FL2Lp6I?J{ZuPg7Q=#}wfdwZ^XG^LKB8GB}3Q0E0iCFy}qiuNd zt`8D((s+-OGH1GFFglJM_R0^LZ%|3HgAmkI((Z-=yjtQ=R&-*I1XC@GdbZN_@!X0ubd1x z4{^6uWz?hMtQyp`R1C1HYjI&ZX{&msLv$PGHKic3XBl5?2g+R=85xL#VQ4%3OwWpbVd=I zUB=3-pKi&p)L-&S;NF;7C?g5DbWL;Qg-z{eCGo|xJiOHsN-h13%6h+^qe=T(S)1hR zh2)-lUWjBECN0Z%J#wBo?Wg~$fNjZ;-FTiHoN9Q%(gx@7Bh8-M`w55R_|X_GWlnLi zc;aru?E}BJC+lni*{>`y@!ne54aw;g9E+Bwm8_unA_CN$fr5~&zzD<6ZrEgE-({+0+rXxG5{=PS{Sr_Sy9 z<2>gGagP{5ZiXy};T)u1m&Eagb5%0oSN$3G3(u|H5nU7!BIMv*-x%5;ZR zI|g=85wEtQ%8l#CHoQ*5`|eaKM1l+T6!Q?TpH@%kuOE|>(Ahsf@?hvMj&vhT$e46tM=4RFdOJw$;3ygF`;>qlv(345aYbHtjhOuRnh=2mJ`PZT3Wo>w>r}w z1Ts9BYrEFG{JO9Q`g9*r`UJG`=B z0Zqg39Byq{CQ|xX0QbF*sLJD~~Oxir!-HIl}{42T&3pU2p+KiqJ+#MIR*48t* zEhm@S|1LBN=Lm^6ASTmln`cevR1;>{OeJ6qcZJq@Spsx`BA`@)i|W%9<4$Fkbk(Q4 zihdP2+QZYVc_yFbG+!-H+bdW}FIt^%VnOPM?4l$D+dn>CatqpJ3~A`VHLW};lsZcc zb1nhSN?$G(cNg<>Fu3c-Yw;Sb1~^_*VMVMY{XKI+Bue%*kP>w?TU_UMH5EFmKk%Zr zCUmBB{Cw~@bQroArRuTuQ^ZEhuGQmZir@zejV7Y4R!;WSUtah;sKRLfVe3E#yy^P7 zM(4)kNuTyN9&3H#W4`!`3a2hcR~?<|nwoYTDlzAUuJh(z^@xv4C%sBSsoJQ1xw;V* zn3qF;w*o|2{rs-Z3+zbp-KV~ z82Gq*u(|p(E7}L^5EKZRcb3r%IoCUjp`qwV-@_X1>~*Dw3rrc0X1CL7#t-&Qicz_i2P2(HJ?M=ur&lu zVm=|Xp`B7Rb1;K|?9{SbN2G(f$DM&dkWt}9;s$p?%&}#`sL1TjjPG4+YluJ}81I_5 znV{$!iTDAKlDSTkK}at}t>MzaCT?{3+A91Zc-?(w70LX_&-vMLa(A-lRGa9PpWF9K z0RC;tSbHNyL~q=VzORC@kcRw#C8~_I>sgjy{nZ6imq_r_Aop42Q?>g;FPCr8H9zZM zI38Oe-Au4y3{N%4EE)`1}6aBBc>@ z&U$~=DI%Vkf(-R&wx#jE9Tk8KnDX#vXq)jU5G-HjAyyeqtlpdP48}K)Iwyyjo`?LzX+T%e=PXQ&W>3>!?|!Qbogy zJRmD;P2bDnW>QeWV4)6Xc205CyW#ARMCj?d3pl5Rdoy{PE?bCe_`LY$Xz*V@j)uB= zQ>>`&*{{45lz99$#XkTeLE=3`$$qmPj;RCL~Bh@5%k(U}9DbG}d( zTu1Sl8&kJA+5Y|8?zdU%2dwd_=CJ=jn$=ue} z+u98bCdl7AoZ(fmOk`Ef?L&IYAo9BQ^2d(0D~a}1*vZDV>BPvH7CcYI2__~cO%3WZ zQ1-`hv7PSG9C}$kQ&sY=?G);aU|w#k4*zMhp1~JVsjO}D`8)Xb_H3M2Xo7=b08zPm zLbPy9c3sg6Zko*e8Q;ey=#qAuh>%@R%t=*L(Ee&>PIiBOl>3^ zBKPylZGzV#P&6S5=)^kpxZpip^9*#JI@ga5bL0qJmyjz9KUZV0*pEmnO6Ln8T|-8| z+ZYD!sLgM(2HWdJ=#a2)PZ9zNOzb|F<=9MR-L0teXyF9Aq>Pqp1f)!94J3Da%pZSn zE2bYodk;;l9_Z1=sBJN?gsEPC*5R~2MQ-ch8dWG~y7=cdXy*sZeHz^zjEXxx2S76!Ow?(grJ%dpBluahl;+~ z8t&%3ZeT^s;@~#KtbHp`zd@4{y%;u()@H3Eqg$+1o?@Z1z?(djbPGgNF-oq@3a8#q zeobJ4CeP@upRr`LJ0VE^t;#?%e!%)dqk1Sds1A%9bcvD#Jp2csa27jI3Lbw zc^q*ns39(Gk!MotL3Dovn$FH+)zPXZFyruuWLZ-a zxDK_ttrhuQ()~lYGgKd4aj2vp9L>8?@65J!Pto=Q%wcW=%_eQS_bcQ~NZ3O{tbB`Z zP{7o`#yPKWe#Q{OVnLL^&7h_0MDL8GVzv-wuMV#anOozxQ<2FoikGABdAfCzK%w*Z zVXED1hE6>9xS}X90EEGmJKWAlX6m%ahA{vMiC(_8We{{Z*mwweA_*` zUXxpVkS%pU==H!|hBXoDO**XL?r$Uzp|VGgGqH%oGh1(NxxJ?3S4afSHRqUrZ2>s7 zbAvuc^Z0&3go&a$-AmgK^3%p9AYXdIkL{mZP8y9Vg@XK%UT54i)w5r?N7qF#ZxV-^ z?rC?m=hGkkve@Cw6)}rk?k%u9#)s+YNyg`o8kVh%9N0k6)_PD&5%AJgCFGmMAG}~* z3vYNPHlI5V$ACnPA`p^J>H8nYqsxB?!OF6dNHe4@K)DC{gD>#W*f?jup{4B7eq*S{YMz7h9>kFQ71x3Km4hA0h<0wO=ZMOTI0gD zH4>Uai5`fD1@393t|i zXuy?<&(yq9h}6?d^34zXX2D;vR`sm%72(@MzHD&R(5Fw&is;2X9zT2bEPd??K>!f4 zt#x=_H1O$h^Z7XA#j#8Kjc@61rDt=uz4g;hXp#1zS=DzdyAARQA zC8`Gx3IH7YUuA30l2P89*&nwqSplH@?F)`%)-W~AIzK;pIO$B7X-{9erJDQJ1F`}do-UcZk%jz zR8IXXIQ<&oiz@${{8F$@%~c?i2Gpv$8)+g(i|kj(Zi3W0^6La8>ki~5cxXWN|} zzQFc$Gl|t6D83qAIohCz6!+6SIs`!%y^upTg`|_jOtyBz#m8olhn_D8v-TqFo@-NB zouhM9m-Am_zmI+dRU|a!LYhz8=uE88hoC(9F;-k3=M{1x=X#JYE<9Wk4x;Bx*9d;S z|2?;~P4ls`fn5D5C_Dv)@+`p%{6xSgzSH>8WJRnEca>kOxEO(KalC;lm89I|# zHh-gwZc3eg9IH|J4Uk3#iUi!JI7tc@a=PG{zOQLp*KbsqBu>=DN=(n>n#)kWKAOOS zylpC`>~=z3?9T`Zeo~Y$I{^X|ftp1e4goFSsNsGvoe5>a4k7i=5xSe=!W{*Ba#oAw1~bCt_GQtP7sg%l7;wpE%-M)V}{ZQ%Z^h$9LFgW>6NZ9a?Y@ z)KzFjOSybDy}#^V+R9X+n|&LUZTvAxp`GnOTnS=hNDs9$&~xXE+)3J7`|f{?Uot8E zXc}kJA{%;$gVPOp=MD)2Uvdl!`C58^%!btzg~_nZztcqf{bjRq~RizU+Fdp7Uxbv#^X){mN(uHi}c&^r7*NqPS zskTDSoU=qxuUNtLv7+MQGZBxOCfkG+&0>tmy}C>wl~2~@-B`=U9!aaYpadGsVK|%e z!&?MjJAR*=Q|hXUxR-g&^=Wzm0T{@FCJO}&Pi*7dmGgCQbNh6Ein*u%8pg?-YC%j? zzCIDBi5IciTiD|gu|G(S0Z?O<&KbYRlY&ahl)x=-#);_4@t2skotHO12wRDUo)@Oq zRp6m>L@ZFGvI>d#a&EHT*}^Y5;#k)~mqjuf1Fn(^l8rCdaaMV4@=WC->vgsg!vYV0 z|E@clRRzYxI9unjx19d-XNxlYHi6yS|BS*uq2CCl@!xK3w5^ofD+6>z7j_c?I7I!$ z?nsFV21um&*9ZrovgCFD1FxC}g>F+{3UNUBZ}Gzaa2%=gzztmEww=*wUe;;uC>?i= z;H&<^R7#R&mck=fSJ!~?N0(S_5t^8a`>|zzmV={XRGVpyul{A{#+#FZ#{ip9^JeCK zf40)nn}05Mvl89;%}s8=tLy_eA;8W@wwd;$^(&3?NPaUVMO@sz01wb`kl|~0>-XIn z+Q9&DI9qig4P}>S2vEMh`rmqp{lE?U=%*QwEitbU-cSf+TKaRRJEW$j?)>_t-W);= zUvc@}oBj-tbJW4bMf=U0H_~xe0caRVhxQ?iPBaHdh+SW5L;f2r`VPdSprD~i>@_1G z`23}=z8(Wu>gm*|{HDN;@REXuL#Xp4h5teTISnW{VavCvPlfrkDJ*Nw7Oxz>562Y` zDAQH4IdKt8IsK+j&2)LS4-Lbft4#ux$m2KqrO+3zP+|IaYskSh*}g6XL*br0E9r$b zcvpPKR_1N4*j4A%#_=$_-ed-s<<683h0NTw-RGt1!IgBwUBk<|SKRpiz+L12=YhtL zexI+DWowlLVp?Ik>;>fFj(=(K_D znmuI+Y?*y3&zf(G)m$z8RqBAD`NF?NghDlnVqJ*_OjkWR6JW zR8fpNm9Rw5-6=;wy7Qd32G^#B{g-ca$=aaMWd5bDWI#|Gr{9%HXZi!DTd{z~9pQ{BoEm_~#jXGbxQc3bU!HV55VE;6-k zyZ5=)A8X*ONCq!?qec57WGIbLa$xoyg|p+-lP(Dgi<>VxUA!Zkpu!RtXWu+rV^R6J zD8*0_^oi1xQNeYvakyWUg%(!>6IeS%Pw06lk=f_CB$QbHf=;~z%4z3(yKL=neIJw} zT6QWnF+aNw+EQl0+5h;<8&?-ynyZMEEi`I}WJE2}2Vxt#CHa!rABR>>q!`X`MnSVh zm51Ny+aI(cufZ20%G#Kt+T;ka!kkHGRsQ}}?Ui_%$?4NjN&dCWcA_0Mkd6>pHc>&L z#trMpv#MsyM#e(USR&Tjui1A@(HRNVnq1sk8%THLul5#9*s9kO`p%!JB)9NOiF5b| zwp}~Nk98A!{4k5R@U>Z-SNms1`}K3P#~J3+TfH&4gnzM8Ww-0;ekA&sCwl}#?Bb=n z*5jpe7nKKBIeMNk&^s!N_b)#6I~A*XacVM zyx{x2R)+x9X?adEH=27x8ZzT2*uKBS96Ii>Hp+1x>^P-{aq*4+{{8#jNqpiCuN;T9 zxcQyanL>4wEd!#GtP#=FdAsyf|p{6c+Q zOJnS)gPz^al4AEsTU)~?7#;|JoK#_Xw!Yc!GcPLO?OW45#zL)A?uvKVIIu(pb_`pd z^>43gi3fMqWKP0$v=^?(-y5_^9J1B@(&NZ5@Y#cefA*JO@LwUHSZKtjbH*41wa#l& za3dC|W>umAN42=mk0H~WpTtRDHIS;`qFQOLNCm;O8@`u14gE0V;NO@t5D_f!m#!_) z$a(~JF(ew#v!QaxZ>eLz_-uIL+3ytw8j4uiD!Y3N9^F7E?7-XR(W!>jGWCrs*N%`@4on% zSCy+W)6_sqnfB|haALe6lbX$%q5OtS(g`9#blKyoW>`)=t=nU!n}`J;uRGga8L9U_&dz9BW&rYLvWC)=`NV+T|lW#?+= zlwjUA0i|0|5-!#_&tOA%MmiJeWB8T~%@8j-nVF)~?DfIwYGUPHo``D?sLWbK#Jk*Q z$1)3V7S%Sd39->PAO3J_u6!k`kI30K%mksB!~ae=nrYk5M9lr`eY!4u^}gz6Mu9ol zOp!e<40OVFO`yz^+F8-n4#!D!i>t7XlAYP}gEseif$V}l%7>6A0U}L(VU%G8x9+#o z*oYARoEnEQ5P%(u($PMJyc_0!iH zb4^MDS)~E9*aeLMvgJ?W&(XWN-m5}3PaC|8u2?1GUiV$a7m<&@SosX8i7$JPrNe@4 znm@Ed&CNLV)Tp;&l3IEzMq@DEC+wrd79Pgq{#_ueko3G(Esu;1=eG-k;&{+?lwg+9)$h#@R%?xuYz5Iwaqt(Gy+ebm$K!uF-!4@E6^JpB zTB@{qbxlv|5E4n6DK*QJk2!<8o%GtLa2we~KHGwa#H-iil-*ZhsR!DFrjw|B(!7fI6mqT#KEz zqBo<%WiqU0cYe-_Z1@9F;KKSW(v-a{@6B#o4J;!qw$lTi&_$X|wpiXCISPGB#pKjv zJA72{=`48s_LvGVkus{P0fAdz(uGOn@-3yh?x+&DiM;sD+kJ+5=Bf_uC&`ziKcW18 zc(=_LfcZ%CRf?VqC#0Bah8U+lyL)lhU*NunbimW@9k5b9qD>Z2zr!Z?!Ki=Cmnh$` zj7CJnGfTTrw8+>(XHDT)5t-b`*tD)bO{2p9t=7+9g)aZ4WSMHu>s&-;YDtp+qsIAk zB$E)z*FNqUPyGCPjCOaVtxaMcb%5Q9Q@C~Mo?F$>k0{DzYqTKIlLRxD$bzS8HP2?j zjiMnf3^%mat<*N5wT~l$O#yRE9%Fm^Sg_0JM&w4(9fYpu7hC@O1toq&9GEpI`mid} zW7n}i&GmAknEuW{H% z0)ytqkd4zreZrHR=l~lODScqXj`%q}f$gR(Z=q2i?%A1=(xO;<45y}~-9)D70@33L zX6iVMS>slz1tRmI8elyGIr1=D=tp3im8%P72w{23?aA$$Q#wpkp?!nDB%@1)bQdZV znvd$oyeGhNo_LLcelQC)QS0JKXL@#Qr&N2yyuS-w2xP3H3Ev7Od6A{9VwBe*cZ`_( z1=aWa~o`R<`()g3xvVT6B_UyOwMw z;%RqFsJa$B%vdCm?aX#me~@}=tyJ#Q0Tn2i-|j`leyKsmITmA&ZQlwG(&ejfwS1&d z-61B`MvQyejCcSJy)41r$BQmDBlOwx>D4ja*0``qPiHRsuQ?L z{Z`|k9Zk-hxSrAGk#cc>p0zY;9oLW71xX|c$!iH6Xn%W;g9shZi`P||A7p{nsR_~j964Z4AG)~nIB?aR+ErpF#L1bCiTI@>?)h*)yxv8Iz%&XM

rZ+pwz)U+Qc{KX06ua;78cO68 zFN>{0coe!FG#wc1s9T0DrxN`Y;ZK9bQcb4r5PS+2z7*cafz1FN@a6=?T(EI@O-Z17{VIq$O_I(j(4tl0>D*=ZrA?3DVo zJnQVmRiO=`l#1HNc_+N+Rk-X@b0u`46od2r7`&>cS46Ec8}eB}Ta|0=sAChRNP;|U zXKoX&dbesWXvz(QqbQq3_hf&<#`7sdLz`A1C7*W|$TYg_Ens_#N}l-|P3kd4({fBY4+dG1409<}2WsNKBlU!FObo}$sSA)?WpcVi0hNZSryOfH z_ylULT-TPQu2fpY1qYy@x*V&5c1#vZ<~ zignV8EtW!PVhd>Y#|z(*67LPP28Gid{mroWwL4KHy}C}w7fJKTJ*McTFrG{)`^(q2 zBYlq)k&5t8o!qZ;G<{WdApZ6ITS;nyqT6v%%x0b8l`f~lg{>1Tw!iw&xCcIflZKln4gUZkQT-- z2TqJD#wg)fdi5fst|o@|g%s*Jzj^5$(;BBksOVh~S|}XNXR}`72$&|ECFTsAUlHeL zli2lq<|XlC^1v1UEfP;-$W|gq@;V)qZU!kktAtgs83^45%+joOd2mk;Lz-RasFnl^ z2!5R^16m^iM#gRwke-`}lvH)ugW&5UAkxnc9@`&KA*JASQ=q|t5uRpmIt@u+#( z#mDStB~9mA=|Yt#Yz5C4M=&wu?7$Z0Qc|I6}U*#5t*e4m?Zap^7a)oKQMp~8Hr z`LZJwJj{o&xuJG?m(ticfiF-hXi{QgR0(SD6Xd&sH`L>0b zne-59J_+aQtzo*}^k1kk_w`c_ukCvj@!GY$9=BQB~-KAI#^!qW4UK|wFmIdU! zXLDk=i=OtqFa(kyXaPDr`jg{U=NnGrtSX)jryParUHeC;aDK#@l=EY{h+sbRc`j)ck@ z2v22b=HPN()S>cbdxc<}WG z)i3f$LRLG#X$P3A&Z?8H<2m|V4>BL~yuXJrHVrF~>2x)lU5wWVw^h%M9L#sQ{Vd{o zkH?RtsxkQY%!8aOWYQlko`M_B0TWF@GB5UVA6$6coge>Lu*!-n5xU?y!0SbU#QVvs+`0MP%+hC=DlSWS2 zW!~$TnpRE79F4k;^k!!;3=GlESX%DAu%Ls4UO1&54Nlb?1S@cWR_!WNbvD?aO^Q+^a`D*qlOSVFj~y<6OH#%SvaKYVO(t& zknl=#+DGs?-w;DDp{Hgxscq3MNiXF4z%2a$%DicdMtoyYfb-ORZXHgdzw%ll$KwQW z&_IOG697LN!OzkysIXOnHf2Lo3+ZbdPF7_)O!pLXKa%9EY_u3LIDTC29RY|EX!XNP!+2 zg*r(UJ9b%-73f^w(Y*S$LU*YeaLYxu>_Sr@{TW zrf*!p=2)sa_C&T`(L=IiYdISE8RqrWhrjSX+1Jz?RYH?Eke^P zJ-5U)P-M$45!6ikZKo>^V0Qhf(UhuxO*lDr|66 z4md2)&^+I=bzsE|B&6}20BSg1~ublN)?pta6a=Bn8*jS*NQ&SlC7G+;eYuIqDA3Wcp z?sjy>q6DkKb;;x6rSJytf(&+d`TJ6n(b&uBuc}3DcFg5z*eQ76ou`p)E;;2<{iS*R zQH7q91c-?${l)Ktj7ozV>!r22;nHI_$F?5u%UcMS@lF7;N%gvS1=WqzC%?4dugAG< zS(>TnD&Aa{l7F6Sw#8gN)AwwQ^mT7yy5%4$ILjM!zqOVp)bqL2VL{#y&RAqZ=tJ$E zw6v1A$edV;m1}}8iO?V-Jo+K1XLZ~-$VxNA-;5y-D=(k)?-_qtuBGk$+A-cvNUOWp z9|S!E-p<_RXePSfN`>%=X%FFiAADUrHFK)@pXDsS8K(YWmD!B1r=m+h)F~a!`+D`x ztj>{qhMIau(S{O~q?f+=o|}sY_)8CH0q@XNv%;`Pr5%>H`tP(D@axySq)*0{+cKR$ zzC^j*#umCa&Q8g8X}?UV^Nz%CKV|jB->ts-_PoTKJ)wzy-W4Y1;lj3b-As-y%Ls(O zW=A*#-gOG&5v>!q-rH8DM$3zhALSb=67sXj>LYeuoP@w`$l*AGJ| zSjA)FCHIn0q@|BD2ozG*mt6l7p`#OwsJ99`2nKu7l)Bgf>AWw2DwP70T4V#7UHP7# zN>+BTen8S+Z0Q>x999h1{k{wgp=doZVz3W=!n_}_5rjXj_;(;wIq0at8x_n7{M0*9 zB}|baf$tu7raH7CNwStvJN(rwDgYaY=SH$E7j?r$L&n6?h)0pZ2G7r>Ck}i&f@!@6 zmE_l+T}ZrY^%37B9HgnY>ddPK16?YKC@rlrhYBb~FJPd#9Wor)4&_DKy3CzRLkTFv zfhmaKX%=QU_XvH(!)9)6Y478fa*E?~ncJ>heAd4~rrm^;B?miumxYU#5#DqY#wIS& zlxiZhZJkMR*An_9;jC&H_4Kgvy!L6>riP(b8Xy5LZ4Ke$l(TbvuXPy=9zZ5l= zj3M5(Ue<6|!^blM1x4$~U%6wL7x#yLv{FYjbb?(d!$0Da)$_otIoy(^8*Ud#=zB^5|t7Wg*WF`%!?sY zCr|WNJQnHN61TlmazMx(=IBUuR`yR-B=i&G)tLkBdF#q41DSX;PH0NFdjx^1P8cFa z!P`y>G; zr|e$)Hv1DrrfVlm_Z#1WZ3t~V_i}cWwDOVTw;XfyH#)-Pu7JB*h+6c7%HLw0zFKtLgMTms60a(M%8JPw43Dgk#%XUwwFugVcw<91C5+NzK@nY%e27MRe*#??532wJP@fOJstVL>{*g*rDUjv@OCZf!CvJG}vXTIS|19DqRd=R2h?ZxU}QOoXwY z*^l3wE!n=*f~&?z6-K8BX=!QI&y;UoxqP__xF+Mv_wNlG4l*)Z)2D8H;WkZ@qu#( z2PcRf9h3L7N{(HW6oaF7)~~+KG=uWk$53vR-)!p!o}aHXSY>5{;>Pt5eGk?BNvO)prJ`hpfS{d8 zc_5gCwzr>quTDltqLt@|U)!n1pib&}Y@U&lGEWUktee?NU2JwNZC%DAZi0zU@N?wAz zPB|D30=T8_zBnwdl|9gT(|oG6K?5TtBa`QQbKH#L z@(kSh|3kY*j~nSYsj0aEBi5|<{hA+6bdVzVizxy6aQi(yY zbkam^EMz=D;<&IQ+NTb{EIAdskAKtki3btTKQ9{7@%vcb?s9n+S>`jT1X=oQVPR44 zGuewqqkMeicXoDQdf(y@&!Fe*932Z7p@7X&W|8M1wSNN*gev(LIry8zLU=@t&Rz;} zK#$#O%gF)J>Gb*>%Bt_D2dp9|%cxiyjV2mk14MK#!~W8nee7UgEtrsA(}cJ@z;Lr! zb}20`52)bS$P1;RHRjzZz#>~Wp%P2t|Dz}oeJGLaAYG7h%RBNjb5Kc~M2Sop(azc^ zsmv2EMQ#I|kQPWI)yyT3iVXZMeN=e*Oes=KSJ zx~lKJpU>y^3zL%(g@wX|0s;bp6&Djy00IJr1bm-=f&*%9DvX2x8&F39aiyPtkJnG5 zP#_?DAaNmnCAW<84OcJZfwzA*QiT6e?fodKH-anOcURebcQbfqWXD?CR9NF zj08;qMMmhaL{8W#W;^Q{0+btcKelms6@wgaSNa?D+Pz!HlBT`BzP`D~-NnR3rPcGP zDjGrHCxH-$1wR_!Pl7;%7*a^YKtPp#A}AzaM_`SFKPaGDK#iE+|NF>_zxe#$$Ek?N z;(s4k{#)$3I#7AArl!W9Cg8h(D;Pdv^cMpy2vE2I$}chp(*`FH(g_da=XL-+82*)@ zSS&}Q^~Z8auD4JAawDLGOiWBn%F+;Ia`L#U>NqQF`z!*`X`Lo2k3tEvL<+xrL%*zO zguHDsdwcuYzxe&}<3<7-Z79wg9P<d{fD{?VDjjSfVF9oV@J-9E0RgusDuwu>sj5%lL10A?zN{b7o?7J~=-;N2al zq0N~d9xr;aNVYBA`6 z`=)q7a#X9NdY^C1CeqRDdS(@tss>E%%@X=Te$?Eb2=-T~1 z3+U0aaxn06Lf_KW}ptWp_u!#u0zM796kc00tN2N1Nb?0NYd5)xVn&ML-I` zMHYIu?aoc6)|@6r65s+IXrKGyM)1wc6iZt5kX@){+ zkj9C|eLV7WH8GyF_F@C;;aJ{DRaGhiEq|d@ae4qzVE^v|+yrRE;Ipm^&uQJyo9yDt zWj}2*GQjC-tBpiHb48>id_ahr2rSmUvsE~N>gAx|qDXZF0WNn2?1zS(ZDW=%#~1k| zVXokYHP+A%3#vHUMxxURn|>c=)Qj0vf0{)_adu~@waH8Z3Mk2|&6LB5v35}mJYrH( zsk=k{lMSrAyqb%3jDz`7f0{%DLbM7O*58!c^FhklPQ8QADUSi+UdHU68OvW-Q9fTf zX%FF1)Q=!rgKEv{KN8Q$k&yzt1Hem2W%M9niG42Dhg{$JUDT`4KL*5 zwuO1JULqtHA5f}!Xi?Sbe!^e)?7IH-m_d~4pUet(c@x3KQzm+RlqN*1unynf{Up+2 zHfAkXv(arAw$eeR#aoHS2=Lei)p)t>pUOzJ{m~mc#WHKQjED)V`Tg^7j9vj92Cyqk zrHkt{3~4zUBffhGNnoEH%tCEb{$ z&s0QB_jo0kPf$+pCDSoL(Mz9&Ag%9U$sEm4!pt5_Zsl7l92_hN87DGfEy;5GVDCj@ z=rI|*?u2+<7_hm&;O^;IjJ71FIo#fMR=B#U$;gBq88I1T(1ScY-@Nk{ArMZL0MRy7 z2IqIeDoc9K6ljbjM17s9;z|04jl`2`ZgJ{UUa36h)YLNuX?0$g&jucCrT1-ex-W6$ zXutVA7DCi=aWu21urqyPtiOZT-0NHx1=g&;r_<_M2s87_u5*PevK!IOv4q^%Hde>W zBL!*{aNxW-A7ET*NqHEuj}{CrxVc)o*k<2NZuq(&6sm{LQY|+g2lh;Wmm}Wq? z?jES7l6Vi+olB`)z>5Hf zQH32*1iBfN(8##JSSThYQmQ%}jG}CwYhVe>n`u@4rVfz286nN4bG_7Z()P8R$qQ?_ zn#dtOYIQoqKkM>L3@;{`VKD-=w6$D(5?B9w8Yne)e4GS|NaeA3!l04YeA`F6WY<)2 zIJ8x5Fmn9-yHc{-cYo`>TAQ>;w|oeq+uCsJalmW-o@UG0daNDmDwp^mF(ol^k5eUY zh%>-#kT~EXl{yV0p1k~u-ZzO;b@ErKdgwgWI=9dD)&nVAK}9!`3;kSo#E*zchm&)H zrg0qp)QziY^L~j-^HjWKsZSDxF2i*lp@^KVN%wSDkQ|b(79r@8}uE zyH&B;aMkUN5=KzLHfi2L(&bUTpojJDOs&US%4L!b-MJ z$t_uCZ{I%ENnn_AGMK0BzHRH%67lvXt3BCti0U46&bP^d*CDo?{g}I0Z*&<-QEz)b zxPNjPTv^GCcC^Vwnra=mLeO9Yvb|E6$6|{YRMEtAB3zu*Z}rwKf~)SY%06-=5v}~h zMDu+~x!QYUJWGB$xtCH01`as6-kciu_~C=en(iq6Vy++Iet_Z2wc%a5?(%z#=656g zR<^8b_M(?3aji4)>ok>)xqRwh9Uf3-tU>?!5!X~mEsYm~OpAp6xs8xIYMz5X7}GY_ zhGxGqGNI+2t|fL2V;C&$yhq(ycP=&kvg#*Im-j#Eq-=DAG?)mfF-=uJ2L0f5^tL=d zT3g(mM?K=pMF%m+DByxN?3|wnazsQ$U`wYyHrm;dd_!Z-KyO}y3+`B~P1IgiBe`Se zX>&4nLypQ7*87mU(>9)s`l2AFWI3nq5%4^y!+$W@RA5P(B^tD}yYJ|lGNs3Zhp5qv z7n!=_t#f}sUa}`s_XxY{2fXe-Pi#QtzlJWhR#aXNIVo#a)jvZ)K zsM1wQ-*htC!Uk<=q}697J1+)G({JCONA3*i8M@}X zz{^#uO|CXOvAI1G43T+k7}Mknnji*Ts!?~ zZ^H$qan=cmQ?A~TY@mCqzlpPY4(Z>qYzVpIi2_A*Wj4(I0ReGI!z;>chYP6*mf>6E zf!9>_@@qW&8}DV$ne9aWXWpk<_GkDHK~+VcTf|4ETl~`|nLj%`l*+W=RP4hIBrarS z663R7UTzHp-Pk&U(tXZV=@HyU@$Jr&%4c?r3;EIVq;Nd3gY^;@5R2SmM2Dv`UD@4O zf~iMjaSLu-1Ab86rgY81@-`pz;XgpO3g)YHk8RTVJ?`X9eCQxTSXu0=idp4VuXZ!; zqX`x$1L>hRi?c4syYOa1mb%SGAK}aO$MGp8=iOPxb;jk7>LRZ@rcRq*uU9V6QX2PE zy(TAj7kWA|6g?mmF$-uSCpYRLT2&kgIhR<3cp0-ED@*2SAuw zW{;1;bIsmD-{=-(@%RM(A`$^Yz``1%tnLt4KDhIGIY_3`?c&|U!5s>zy7JOSI8)JVtjpL zJBS5hVec@<(mS_7W}!cp+Fgh~)kqmqX^X`%-`3x|_4xM!*XM%A_43%w&7J3(*L7hI zOZL*?Ei38X6E=;t;!n0OtcUkK1v4DA@xwvG)4!sP?s}#wZd+K(&}>dy2J;_2b+r^o5){5`*nPISDy7fxp# zKEr>MKZZflX&7op{;rs0zd49TJgAfc$DZBGVaE_D(mAwG9{20@`A z2ABGl#&BG>(qJ@BMl2bJru|{x+wu@T2D|wC6b8uG-f?)2Elh6SyDQ=HnAW_JLnIS8|98eo^y%V`8{!M-mmOg8k z#tUKLdI$-rNU2tKJ1Wjq!m8HZZC%hg#bR3R0nD+4yhc;`$nlrvaP-$gZf?}))s5n4 z);xTCMv%f!R@OvK)?WIv&jK6Yn)MEumdoJwh`$ZK4tQ|eD*gs=&8_xh{+CH9*;Qx# zy6}54%b0D*=@EaOxF)7U+vQDqtAh75^3dT*W2(Q}Z5=Rh(qi_GST{|TrYNLn7Xsjm zqw-B(I(#2H?7|d~OIQ9xv{&$wsOFh?uLF;&f2~bBJ2j$nn^5g!Y6RKc-1klp-1Hus zaGz+9WGdc1EPQ=jDmImNCEPEldET**v&M>V*^jy*HZlpCc#TxX;mwx3i!ymxGi1Zs zMrx*6=53!Ih9hDLMi%84Gj$#xxB1-)9^Kq+GqAP0?_C�GlOO*%RfWPlT6>ADI=X zLE_~#X^~1uwoQ7JS!OBt5YgC7_6rZ?oQ#4j(Q+T0Dg!a`c1M0?atG!hRz<$BTri){ zQ`FY!G`U=XnBV2Yj4<)?;@@P{dtzH2Oi@|;B|5|?D~7~?OYe+y!hOn{$Wls){~4jF}R($P9-{B z8HrRWUalf{$=fIl3!GOB%9XS6HRaZ?4i|Le+nw51i;ZAAry-B>wK7+{w3o^7UrPo* zo|C1P8uQt9t?(wo+DY&uR1ofnCv{bBZfX9SCx;8BMn}GJC+xg+8R<3izgN%dcZq#@ zlSxSM{mshsgam$@?x1C{AR|9hyXi?>*9U;56L-Em zw>+=7!;#7VI>WW49&@s`+FuZgHc#&Pa%UZtKObQ{IVeY3*lV~}^mNhkY#(VKwc`3j z)xX8qPXLoWvMmoeejbbG4YOtLs`&51g}j`_G#Zw)7`#u8JDmn^Y2*$@%rcak`PzD!gXT{ zGMR}q8mo^RN|x--!3WEwFflP_U=Jo%THU?FMx=^VroXApnlqj1`pBA|=dI(l`L1)5 z#<^Pu{aL;(4z##f*|!M}QA7+B@Fb#kHWD#SPcP=@Xjbg5iHv6?cQ;oe94^(OP33G4 zJ!i>XMk6Su4mH6rV0weIkors@HVqc?@FZL@g_=%zjbk}h7ve}?X(iW=q1|cBbYm>#|7yf?I_!I} z>9}5V;4xQ12b1F-lb+Jr`3?Y%x3f{wQ0z49bF{da}FjO8T4G#SVfqhl+E0Y%8EJL(<6@^Uq z&DzC7IXAK#SVWgXIZV%Gs0>uuX0*n6z|C}1NniuT&Pr(ObCSx(n#;GibskOaqx%vx znL;8gt-7{(P;Jv(@mXIM3t3e|Hf=1FP!dC_nc_irO(?b25o3-HLYq?}&S}Y(^5iH? z!Y7Zv)oy2JECXZ#1j;y*EQUDS(1&Y)AaEFOwAJwlw*}tW$*EudP|eruX2!L(*5r5P zmi+ViHH^lAY=lFXCW|M9rBC_~zA+ox+0R^m(6}_gZXfhyDgv8VC&br>v8O%Q%%)UD zRYD*#&GmygmZP=t)PN7mYW>UQxMg-n+!gyEgjUo0>*0NM*Er8tY9BngApQ1_pC4u{ z(%I8MKXRO>l2;mh)OU}Lbji18xwOY&u?)28K=-nJdH&+(;=esd`F=wF&Z5SpCFeM5CE>Ks!EwKv9e~wwIU&k$ku6htpLe!*@y+E8JQDq zb&nS~7z@Zla6U#ztG4AwBiAiis@l;iggWMk8;Z&IbVqTD3v|mX^qErdVR$@Uhr_t?-tgNKo@_D1i=kM_i1BG}I ze7Ysf_4c$vrS5e(RodnGXvm33ptUNN2?_*7b{EE6h7N+v^sR_v0SPq#nc6)Rd_*N9T&Fe~$F?qPbSR4S7wy zp6=l!pim;wpGF~z0h=T6qC!2aI@;&$Le#;r)^G^UW~(dHB(uGp)A?+1;>i$N9^sbK zjLzv~)_6REwrjY{`>jMS7noQw$!Iv1phB${n3tFLbg@#Bj}OTCbe@2UDw4zb6agJQ z<;)+NV0M;^OYU-Wpv99l7>ASY;XKSHextMx&sIVTMn=0mZ?i-EJ%ZNYbn_z)d#R_# z4=^f+<7on!Y@UgWwPy3RCTh4BCcGeo7xHR~_x1gJAt9lH(g8=!Qb{^|p-b}GS~ga5 z|DAnt#4OL~lJaz9{~vLrfiPE0@NBg>+K<>rm}h6&$}bA$W*8q zI=(n-y1v4$&cwIX-8Bj1cf%2J>j(Hh{M|H+iv6eL5n_ck4lcFJX>DYP>Lqxa*8&mX z87^0acWgG~^782$%?0NpF^*-IGl&6$pA-x+XtzLVi${7wqx$zg&IqPWMUZ8ds(jeG zk(B9#0S<|we0{QH%BpQM_wz>Au-+7&rqd%A(5F@}_e%h;M+~v|2kP(6y*U&-Zsg6g zJ%D&6^mz#i^z!N}M39XLF((k~=4n5vOH_Tu@6i~@RM(5myvL|S5>Nw-4}9tKgFb^N z>T;X!emJfl5U1{~edyJ0KYu*2NoRy2VnqnCVHrx)gjRttqjC+ zbnoL6l%x7b0taNAlLij+5L1K;4t3b|RP z2Qp}PC3Sdrb22>wrb$JR4XL2`jPwu8I8UCTPvmsH~cvLP|DV(2Pfdyq)O^Qba2q2H8kdO&FooRIuXoj9& zJV5k1I$BnXkz)^MNZJj@MC2igYUspG)_t}g9@w^edWmU!TU?&=}Tu`xt~oM2b#qhRd@{N6^6tZi5kVqWU`A**>0$f|aV1SyU^;yy{K* zSpO5vvZCz4DhwTEyK*7#M;8HwzOjWMd?L zIg2ao;^l5xtJVMJP&yKz28jse4EE=wOaL8=5T)f4rA0s=5(?9Ky2r_Nuoe9QlH%v@ zhXBi6Swp+VfV{aM8OZ=+hlH!3PCd}K)=YEW+1c?BN%S;{C^E+YhZ?CnZ4#6HkF@p$ zwvu{H)=mvP5>Zyh4u@U`g&cW8>4D$JhoA493WhpzruZfG#m)?g4A9%SCLA#Fe}9da z^vdc0riM;UE`AW6xLDG6ecyYI(L`mW8183?l{_u40&|X3c2;A3Yfd0uO?TL>+Ocpv^!Ay|a@ca8T+EE!vfzvHU zXgFkH{<(&PsZx-@eQ#xD;kgE;v-svhc;r7!l~9BGD2x97^F4k==0N1xeZ9TQ&9-== z(bzke8|?tc7xMi4%tUHd*_(|2EiVqIG~yF}aBy;R0s?A*I6~nPrBXy@%fMeEz`uh6IM)Wu8O#y-Dpg;Zm{G3kb$qTauzk3#gCM-{f z4nw8Wkup~-%j=YrW1_s1K4IeJ?R~ObOJq{74*V^y?$Q^YahTMnM&ocQG?>j$X@1m~ z%`tj&MpT_GudU6sI+{|sGof{SORKlZ0|vPOCU1FVg?oO&yNKU^#j40+p$t$ycm?_v zV%_cmAx4QtZ5rDPiL?@K}EpK$<6Lo+kNExd0}+O@Ge%fMi6p8QJAf(&(1-mf)a#6r_yt55E^Mx^uZNv;zr|nq zYc4LXx&=x-YH2`E+S}jy5~aS!4Mx$<@6W6PSX<*685s_`6o5Jb=H*qIk}+ z9ASbi1D8TG_7=1$)UMGqyrY_r;PD_rA%4lP*TZw0F)5ix@sBjK8pPjXdiedm0jIm7 zIn_um7C^=kYqfhKFc@EF%>(rYAZd%$GAjl)%SdCHltU{wM;0zxqgK2GLN4Ut0(*l| zt!_7jN0XV7^_5Dc3ePVuwdQk0A!WsL5I@vMUYX?uLW}>RcBLPTU6d%0MRJEQRv%kS zG@I~Mw;{_rQ5CU`i;!|jg3VP`Q$H0?9*IQ;0_0ID?WONldwP0G%0^QeP5<-*5wNkP zc)vYz-(tCci_L#aah1#${5kxHukC3gJJa~)A8_6|46%egIwg~DS%fZM{YE4w^+X2B zN5(p4>d;?bP`n=Za84U+gkaY=kBeh!23sld?yG{e+tOji8u_OZ>i%agK%>-`1yMQ6 zSxd%B@1^6@^ad84of?(|JD6Ns$!J{ttTI4m7qj922?qy`SWF}ahwwKbSd?5k7GE1y zfJ;(z<%MqUvCz- zC+@M28#?=mLu?X2$_9VMY5HPIOhjXb0Y`}_%FkdM6?Vio4hL0Ow1ib91c9V5=d0D) zTMpwiD}Y6$GF74fs8`NeMw)&V24}JBbui`ard<^kDr4ibzs^^WK>&u~czU$eo2p!w zo+S))<0^zBWbp2ZN7xn5FYc&Sj^P^QJwlp>-AsUX7^;@PG$rs#Z&hT!t>u z{K|taovg;{N-j$D6@@S_U~JB41~ehD`pesd*)bW1NCOiwa9FW)2>*PgK4g1aZ#02i z5#KoOdn76z$V2d1J;-XfTN2DAj@?WyYAx4OzicekI)&vnEM`j$o!1k{qN&oS4lNfR&sWVIRJ=rl~ zEpEV>$W7sk=FUHksvbx&lw7k;=93(vIb5HpO-B6M3mRC-Xy%WXgY@7NhYcm4^}9fS z3hXlr%U|E!8BS$!oBR8Hn@H0sT!{p-xcnisI{^tve;5tqU2~Y(N$*{lL2;@>+F-+yxFGC&MpwN60U$~jhPY6^?ZAm(fUTUy8i7-v0qcV zcza(5)D!IApZs#tXmL%Z07jM|rVJE5`C8iZXzx)UOcBxacOFQBPeul4V5nUa9eX>w z=}Me+BZiyDHCx_WU`T-7AheZEWdPIETw^+8uoRCi#`-oqapeDdmWmjW`%nM>&x94k zZ!d??OYuKiQZBl(xqf({jurUNRj;(#U8qH`Y{WLR%wz4|9xu3PioOjnF0-ralNK1{ z?8g6|{_=mc_Wzqb^Zz*g6cQSdN=xmPAYe=VA6RA17~!{>-pH!K=iht1G_F{7_e1AC zoBy`^!<}5vh(2alQR(UF4+EXRw${uC3%L~$x`RO3Fws|s!Rb>#Ndrf=zW^P7RN40OXZQlA8xEit9g?c;sAR4oeI-CF_m@C(%yUpRGGG z)I&nO9G?x4T{VeKTa22Pf5eqjx}<$ZV?y(~sEe`u?_1s*(lf z!;5HXycFJOcUBh(V>%DjZ@}xidNu>C=xRGDGVZ&(3GPOQi1(W17@Iyo^;JuU7gvXO zW2PV18=P4*+N5=~H1yK_DvcexmHAeU6LaK+~Tpz;!}z4Eu@0cl3Gq zbh2&>_X}3^cCXIZ>&~CnbLiAeoIVt z8qjQ+xXxFhJX5eq4WZsXJdwe@29U5!6 zbebE2^2$oWqOzwp)6O6R9$tO6)v7XY2P>_6rZs8*$x9RR5Tb^3Q7Tixjkeyo()?O{ zge-2V+iSx~ECVxWAeU{F5TW_(jEWc$1fTx7)|5CWAzY>`*0rR{H#hBo!NkUVE*kS! zG?mvD+EVqZpZ<4(M>Iy^VoR+hsc9lUMIy65eJBMAj25pK>N^M|j8tO+mB006`0wxM zHwjl>(%Mq_BJa5dGzal^Ft+^&EG8hN!*_5hw5uIKN_my+? z9}f?DMV?JR)tFW%%2HqsVXpOQS}TK_V44Igo#0+}91uOt%q|d%+YQrdMw-d2q$lnEBgpi0iEoS2PgK5uT!tzDx7x6b$51? z9gjfKA7sFT>?Dtkjg9EJ_Rx@+F=Dg}V7|ZrdHLzCQGK=U@R=vS0Dv#s-e&T0`b;_+NL$jy$p$hiwD?h`rNVB%xAB>`cxyS{rBM z!5oLLLfZcTmbfn&9CMyAf7aET5rRYmX3m?L4#>ck(E{-Auvp|Xed9mv`ij}KV;Qk^ zeY=SNN|8J`NeN6zK?gwBpdP({da)-EfRz{8VN|PDqekWC=C*yDvLp4!okTVu@cP;g z3WXvtAOIvh&uC@qJ6;YwpK->~UJ8qdAmZY}=H>17;x)+vhZM>GB`PXvWmVBlBmV8c z;6>$;0X!V;NbRkYl)n@GciqdC{6e!kkDYuQ`gcR`cVuVk?rs0~yv_fI=PCQAgVO1G zwdv2%@NGJmO96BSKibX@Fx1~b4OT04`0%vfOBr>sLS1oMxJIJwKYm$X*{|vMez9-_ zs{Q-(4aDNw^73@KDs4C#tqxEjBH-R+Var;_+U*bj(rC7cDl#`q3$8i?T5ora8Hhle z18{r^4Q*BVWfXvtsB)qGfxQ9GJxFyV@0g=*OmSwr)C)BLRLv@C5~WR;jGHjB+N^KC zKAZ&x1=(M$GVkv00zL1=@Tzrrv5zIw9>wr}ZXad)0{8>vl`*bIbl&dSgu1NgC0{R6w|XBN#}s5)%-DF+*nZkn};g=enuyK@+gw`W9-J7A4XV@iMx z$}DaoCZHD+`)9?HZ;pu?L0l-@16WM}TnK=d^yn}pWfE#?=zu;Ai%g=z`7VYKbhk5j zy+UO{*ARj0N}wD=(?zu;kx91J4cNz_*_(*l-xoQ_A&A(D7FYvr4a4I+I3#KWSp7<` zYPz)0&{=8IZxv_``+wcd8*Np$LyO&a`Y}bz2WuGn zfjG>fR7Y38z_g=D12h_lbZsuxrU$-__om^>Mve6vOA?K?h4V_2wPw>TfPzkuBFWoz zCh1zt5U(bsL5fcjuWr_xwVY5)8Ud8?y0Lp3HRUl(D~1qp%I!@j9hWJg!VUhN1u>@p zai7xh!dnUw zrrK3h+6hu=vMENcd0)rV!pUSRqIR1`hWg+%(6#er&p*b+3p5s%?N%!cE8&jPJ2{BE z^oM60UKS@qoxM_U>)NYt^x2)w(9|%bUKT73{v#Zxnc-E$>2lIMq*KuJu-NMts*H>W z_?rQ3eNRHhIgMwxXX+tJhkae+KvxZ`u|<Dkt0YPV%tQL5aX0RsC~o zD?2iUaF37T`ZJru12jNDwPCmdNW|1)Cy`3|2cVGWDqLM%k2;?=$5e1f3=#Q;a(a92 zeuZHrF!9dPVIl)}WDdV7Z$JriOzCZ;cr54WQSF9Ax%jDbr_($6GK)xQiG@z#GbjY_Sw~}m$>0hJJ79+M`C_qkz6u-LoPeR7OEE!V z=GkfrS?-zI5d;3RTHy~Q_t$>gLtkC|fe2UY?TXFsjj5;=Wx6Grx{qe`&q1Ftf>n6N zVYM2jOd+&IQ-s2Vep;@*DY=nTx*_uus}saJl&dqTdZ<(U&bxV~<3Z43)zlfMg5G|= zUM?-FOQ^G%v_2=5*X37wDuWwWdi18?)poi*`>OW`R;T0|g1ZGdk_cRJeJ#_FX;ZG8 zP55^N;5Wn|24Ehx0rylAiR?GTPh4EwmC-&cmiXA%KY3*6N?-v5XPZZ$^}$sqWa^@j z={R2n<2&qfKx0)SWs&qA?66op*ED|$<@ysNxkgB9=bY@ z`0$M6E#0mpXuEYiqe1i9L?ZD4Q@OqdYNjUj#ZydZ%rfx>kwjf{+@VGJXpi73Vx_H` zH01+KbSLiECHOO|oSm!dl>Hx|FhfMZhi^$91q@4YFakIQkx9w~M_Ji{K1F)(waZ(J z0TgL=_+aZJGn=@e3S{T)$$kddquC9YKzV}F=>1hLm{L|aO_l3U{Od`TT93J>R3Ryb@FYyP#6 zlNZY;AOQZBKA}cuVCdCygc`}hl4EIh8(Dy`%X?l6hlqdF!(Z1=4~dFAAol#>R<#jE zw3+epbrS_1bRF7a6)7$zJ5VeF8?K33qkrb@(J0;49{-OOUk zP^L*_^&`R?zskbp=&Xsj#g~^tI(tOc5!zAD)ZW8;_PM7D{GVD8MPf$&vgbJsv96U7 zGwkET$?9hMN`%Qx)RPPFnlwR9phS8&k^1W%OvaZ>?nZCHdwskvE`9du;NzK#QiTFI zh@Lz$pCr^iGImFYeXZ5O@(JkACU-qw!BQyDl?{`l#r)q))sq3_fY8Bc$q?`Neo~P+ zz!6QuWwft*f-U|Sh-b9pCR^cm1BbA*=<`dyIQGre)V`c6G9UG>Uwcy$O1D+v1tsiF`JCTT zhw06QW#6@DH4%Rhbq0?IY2lclJ@mnXk59wvx%(^1XCQ&Ic1z=#C`+Ja%*b9DAiCOj zvl{x%MWw7f)6icP@C*to%1I=nP6gK_Vjy+6E#_oQ+#UJT*>&SE77@RGqcJMoR2t1QuY*+3HS{r zr^|ctb_`_z@?q5AbEz3;>LI(A_p_S8_o0|c(jv09^o?Tg_0`_2SInogf`4bxtIZ7a zBB~r?p%Z07(^>x>72=esGCJl*4uW)Xh0&#CA^XjO-fEze{(hdMUioms8i39b3=aqh zfa98muwqEXbpxfRT&mU`nwWsir#}M^@AP~+JS)$8dpHZRZEdq^)k3G$owB+@!@&_X zhll9G`1RM;7%5E37cNgNL@|=5D^;J}osh8j@=FH3yGux>b2$7*7QO1**&O=7^6vcLo|n6>0R#G2NsN77MCVxF_bC+R`|Ynu}R< ze9rHfRQ*Zt>G@mCjcR!pLoM+8IAkcbXD?YwYyJ03#8YqT3JQ_a5TzJbIZ$WDZlRtGT;Ltzs2JZTSo zqdPh`)=m2_`27`QPLBGv?_Al&yS%OLIP-fw{}pfh(}W=i6cFk<1|6@qc#U3-HD^z56ANR6a!#emhRn9L;R$13*x8Yb9K`;J)O86z?%?v% zVyw0Hf@t$;Na8ft@zd{b6jC2eq>dizlbXs1KUgN6uWKy+oUd2eq)Yu*UE+ z#^G}L37SY5VVm2L^`mDzw|1dM9vQhj0(M~#cXT10A_%}Q69Bpi=v62EIdlB$1KY;h zb8b<4pzvhqz0sM)Tk=3Y@Ya@`Y{Qo1jK#(Xpm0>Y)nRps*m8VrX|Mp0$6(Z1%1Skp zySEZR3Ca+QjTH>Su`bmZPlD%tkDbXEWwg;F3U^1&+hFt=PvwqKokgWe~B(Jq*G0AJ_GlOtsdNm1b#E~s0K71(zWvvoOp9* zH#j*6XPOPgg!hWVX;avB#A2_1fZoQfiArkNgU7|3HBdV#1 z%{|I!WliL@?h&ke1vZ*VdQk-440=Oc>A^{$B8cH2~}BfZJ?j;Ps*(Q}hB#5+j- zT)MTA#nE{K)MEkm-$V~CTKB3GUVC`N$W{DepE`RTN)P{lonzg=U=@NeCGSwX=N;u;OhKn=%$p}q1dZoRmn*cESjOtgT-T56Y*`xP!J{hem$afsxP~-$ zq61^ynX%XH%jpaZ{SnJNwfQ-ew_sfaojTMgOx7a%y+Ni59c+k&EQ1BinHGCPOja8q zYG2Y&j`69!Rk@KNNKaDQQC8oe)HlM}4k@WA5lp}|V2cB$!SI!Jd&6~$n1m#l-SIF- zSnF`^=!aMRAl_j;y#>plr=bX63##u6@f$+l}b#~Rn_@@KbI-8*lH4usL{ z)5e)5VsEuZDh`J?S)66AP=Cd#PGTQC>U^X7C;*cqpDE;>z>&RPtA2ZNog74G`DhC~ zBW|DT4vSBuWxR7NHZx39o?mXZh7Ti9{qGRu1i$@}6t+Z+t^aYu9+cTyDhY|n0xe~s z9wPuX&79SqfD%o*FnvQp$9yyFgmhv>mI%NNkh_C2gdhv|7>HYeEHOm^7zGBse?TPC zY5f3DhQVb9^!fP-!0CXDoceLuZs))8%}S$SOF1=-HqJ+wpsIA&Z(&G*=GJ6zIUe$r z!j=NSN@lD6D$2+fEUy{lz8yX9G&Aok?x@XKZ+mH zwTUUCj}~Q(1^;)tiRSbq%Bt&BaxNB1{c}%j`GFW|ae3NuMu5jW8GW0%TsJ{8QIqlI zP8#Ng1XPe^cK8k8N@6I@#fO6cZ?NrcZv*|i*&A{{%5+uOOldWnA?$iRrR4dzpR+nj zj=zao{9j>v82b+T8~l)it+=ii&UtNf^U!8bvLB@ZU5NJ1YXH%YFKW^MJGy{_O0f&% zhL8efGM6|>fb&d5lunbMbcp2+spuZ#w}<^bjb*dZk~rTfpMo0Tx$A2Dqkc*F2S@Yg za~R5uGsbdp-a{>rdRBYfskMf}{i(-dc1@1jVd0Z8ug@9yR$5{VqPdrP!JL$6}Lo;cND&qmoB0cy1e(E@4_;uYn8?vzR2vX(4J^1>ed_}hwg*(eu zGK#TW-SLvcQuSh>(U|je)$~ZI{udXw6(|`%r59_%axmW?j(dK4)7)4DgjwgNMw&67 z-lOz)UnC6fo|1#SnrzC>*dtX_Jo+P@K*9I6{vdjFe}i7;S(Ri&?9S=s*Q{m zdlco`I1lRH`uz?N-{1rH77wLGoGk;X^=je!m9^vl_V>*E;NI0al+{>PDo|0zI<(sC zcbB9Fh6Tb@WwqWf&l8 zM!~S$6F|7 z<{X|DeSIey&$hdjJ(7D#RwncG%loC_L#XY39)mgOhfj2EAWpZxXh=`svxyy=4H^Fc z6wSIicP4oRj=6FfLPoookp!Qf;0va5&4&%DVRy+OrLuCBmTRtXOq={&mwR6`mue`VTplr|Lr3OtDeZ;GC&_*58qS8rsZ-|oKd{&B7vL`l z+>jSu|J_`TCs~P475$opL_qXFsG0tSMYdS3MNY_4^XDB|PQDsyv0SxQ2P;o!KB7|} zqLl(ME)9sBPfWn0TGPbG7nD#87>kd*EBk1L^z8CH)s-dA{V0R+2)0@ez+}C+4(Oq7 zGGIghL0fC_#|bpky}iNOa=g4J=wBt4M-afq`z?Mw`w`y6biy~eopiEz8b|8s7o*ziGk4@YgxpV#Gx08u zY9z-i&G8D!%VLeELd9FNL)i4u5}6C(ov9YlWQQy1=DT<0{FZi^p&{D9Ya0-87zLo9 zVaS-;v z{eJ(bfjuZXn{#u&WSML|u<*ck(g(hZ-rzEWLh|Gp0C^m1DJU!tc#fboz1HSc^f*A4 zc`_;a!6&_aTBvJ~^5o0KaOZ_vR{x9hS^)QJm!RrQ|JDO*ZX08r^#VmF82ogwuU#pmF_ZUspyD*hN68j6dL&o;r(Xm!lb z%JOb&W7l*$tIrkpGPb2PGnSVj7BOn!N-q#4*FV3tSC;22 z5r$sjG97tt1P>+FXdA3J01*doUHKS6w%I}jK>Io?Ve@jKa=#&G3n^Lg;Hqp2*ymDx zCKlWw+_#+fxTGol`b~EC@LRTA`YQ*nN4f|ov&{&s9nWtf(R1`^n(Mg<$TRvJxns1c z(UUmb8de7uB4UPJ6FfTO$Ec*XyG?r4v?6UEY=)|K=HK5g0?QzN6q%|);A)|SW-fV` zl%RXK+w|S)+{Ar$_ELM52?xdALoY<84veI(WQa|1rZ0z!B{^tn<@iw~jXGl4c(B+l zi9TQs3G&#|g2ceDMm^7<0 zId0D5stz1t(k9Znsbj$6IhsfOfot7ce^H&8M%h|>p(Gdk)O@hH(ByXXH_h#i`OOjJ z{)5AsM#k;km%YEt*&Mmo)xKx_NJ@VFa`pAF;??z28o3qG{N%KpHp~8Z480k2R&(^; z0C+v&^>Jl|uQDD1wC0P{0q~fjs%h8)RQrX6l{(H!pBY1`(p@9B8yXuXtE5_8L4paZ zwg|;Yjudy)F+x)N{aPh#^1p${q|fJ04B4{fkjR`7b0mQ>w^&5+#AJjcc47ly=M-jV z`v6tCT!r&3E~ktMa;naMZ7$d7Owsn%Yi0<7v6J`ytsknv#@$ zr3me-R48MxWdzM;cLKR}8@ju0rw9EduIAZ&l!C~PsKSO}ZJ>aQ6+Az_RaZwp&VDT( z5)$HkJEs(>BRt3i@UWa!CEbC|#%7DZKs>pJ?;8idiwldAR5~xfDJ?0X)$I#HXsl#0 zBL#INMB=!_SqbahE$WB4(pXWsC!BCPRiEvu9TG6GnYJBIMNnNV*VG#Yc zkyM?-f_D3fS@q4^lxsIr%F?ilL(Tc61YKTR8aG{wv(>wCZDMb4Wm~m_O$`zxD;s?2 zc#~(z63OvImu{)vo$3TtWUDkPnn^&RI*RxARMBx?)r3WGH9bG6S zJAZACe+fR|^i_F3?m0d8{FnYZwz1roqLtqF4VOpv z_*c8=%|*2ReVN`^0Dg0QWpH?>;l`*}w4EQNGQ|&yADBap??JU4-oB#P)JRU7C}qpd zvA9}o0cWj=)?=g^!mWFhwi+AbZ}ISR5@l&~-%|~wFnRW`O@mWGkF6}LZeLcH%#_uz z`wsD+XH?r&V09LYI*L>dUsQLq4-&Qh(ZOlYP9{KtgRRT`WLOkET-I77b;|jI*QZ1G zN!?{PzOTRk61bbo+XXG${TK&@!i^|*Z1>;2WDgUfDD9KajdW($hnE!-c@$%AGa zYIl~&U0O&J=%9u4K5<*QxoeoXRPIVZ`IY#t2)L2@)!gGhPfgKN-?jbyw$>K1=uvs~ zoegR8*}aF@_ifv%;Qis}>eDy@w3ZEJZD7PsxjwcAtoEuLxiYo=x@_K;f-H1#i<3EW zw{PWR_)D$fqwGLAm@8yzVIi?tu5jzp+4*5Ju)WPfYBZTHu&JqualQ4VW`uP$LpL%< z=zOiOs9of7B3D1n6+hMrXLzDgle>xZZ`~TvkIILL(+v6;I4}&Tb&nCndNdTb6tM8g zAnF?_x*=0vel<+C>g6g~DTVs4i*B@yG0TOR?#&UWo*F+~?7Y?<+f)Q;>Jsm>5~i=kj>jq7&mq+0 zJLiT#dVQK&x@KH=*Xs4RdsX99en(k06Vu>VrjM<;a)i7fVE_+b4XtjsKR~g^vHQRs1 zj97LCcx8CtCTi+!u93UtSbBs$pS@%N-K^W^He^}TcB{(BxGo_}3kA|n2DrSly7S*n zq86tsFy>P^(=lBxtJz#QHr#tkYD|u3g0Cx5#+rN( zovmQGGC70gej6kJ0Jn25v&l38m?mKDdRW7k7DF+FKpV={UaD10Oia(wT0$atOds7;^PUiQcBV3uZ{EpeDL-#g?7CGM%Tx28o`_rQAep6Qcm8v&)#L{oskG4$5KC_i z-CpriD24~mwnvZR$%gFuyxE^F-LvmoGGCwHzNRLJgc2=@s^cMNf$ga@1xN(I?g2Ct{9MERvL6iSF~}h) z=lUQwp(MAM&XLj5(M3975&vxu_96KA07>Yh>j^HeGQAIaRG*EoM(Z6jg$cz6H%aeo zF#+u(p6|0cK3L!JN>gqyS4p*_6emJKArj952+f1PKH3Mi`fR3&U{e__woYm%fYgp& z!c0S?rlcgqY270cxOk_7n#O{RLi~6-TW$%l_I`*F<~gNvv^Hsbo(Y@0asM7%LIGZB4RQL84x-8qg;d?U^lLWubdV%H6;O=kmLE9 z1kmDP27408`4selqJMmS{0y`rUK|!?zVS>Q#I;>J>GDbKcHeq&KkD8?ztwJta4t_D zyc%K9DbspDYVcVkjXC}n;*!f5{s{!#e^*X{+h@m-GK=H|RtO*rrH%!3 zYjZ0od<@mb<`VZuq?9lgs0H(I$BAA2)^+h=F<$+8o!gM(mS(^Id6JtL87}Zme~?+_ zwhKx<#*JwufOy+2tuQZyGOf=NL>;iAFCd8Lzd<00%#QQTvN5nwiMiNnt+7OUgzKGE zf?Mvm6rdyh$WVKQmdW;Pd+%z>MGxog3VMFj?UOOT5!|=M7 z(;+3bqbWc*lXJDT+Yd-P{Z+>|f=@B%I|sjel7-})TuZ|?UGcRYax8=>UHpsp3;tHK zwT&jQekoOb=9G&LpDdQl@h99Lk&RIZEkNVi%Cmeamf|pcmdR9}g7aHwP8JDtPXXm% zvC`!bB}9}K`$hOc_rY<--eAogG%FA5@*`3*?P)ECrJ^4s}W#Y&fyp+Z7L za~eJP6Y(Q~37o$=m_RbiiIvC!3u<*T+U)uJc{TzD7FOqMwOO;i+DY=$0lK_$V|&Xk zyg?`KGYtmnR_`g6J<#$P;*jal7ci;P_Oi3&FDIbqOy*Z3w9)ur*0FZ9IV%sbVc5Gs zUKGZWS?h|PWu3`5n(O?qA3l10;GLSLRH@sO16|RiOTFjl_`Kp{u{ZT~V!Of@Z}qLx z04~&A_xQ@lc_Vb4aq55K`)b1tcN`Bd=7=1r=J&nBv`T^M%YHkU#cOy-ts5*YkR1jQ zYFKx55-R!7{=}ZvHYC>KNF2^m0I4{Jgm_0 z%k(tFNasY1%&NiQv7R-FBV!?a27DHXN@g+j7c&+@<+61vs7d_~P?E?ZLx&5*F>q{V zupdip`T8ZHq8FXXRQOm#XJCKr!Yt$`Z z$h}4%0p9`)!kP0OGv?eYG+rvbcadZJYd{vWERar!i6aMS3HD^{Lp&dsxn8q-KAE5` z10>i#{Xcjb?G?3=UUR`3?>4b%MCeCZiXo-9JYbdyp^}ou!G2 zF-vO@AB8t)d)~%vtd>azFw8@1Uoc8LWc5F22dpJI+O&1=(qM&Ry@&HM3cFQA<)l1% z4=XC3W$zn$j;0$+S9rLF{nnfL5G$wH0LRpNzwh%u>?d?F%k$9ND7Pt+<)&y|KCW?e zV=JRnBF48AAG&vearg%95Av-!!TKBi_|vB^WZ$M2D&uR8f=hpbh<*NTaAU#BDJy1A z%`T4O3BtTt&%YVbP?SYz%{1C7-v>4^USBU0Z3#uuY1})L?h6gAK3QL2MwfpG~H1CwokC-7;Nc^N%6+c_yKgJCJt7d|Dhud z?pi*=Que}+NuE-FrH7(^3aN(Fyh1qNl{C7kF)$Zt3rmEqvlE;yeK1{{qbOl4{}cH4I(n(;JT=($6XEdd4Ki!8f$ zm5Z+3Xl-w+axZ4fzi>QH7&#w~zyqNFy#f#(%DPQD0rz06U%ToafwMF!em=t(sv`Z= z3FiaoT+ol##9^j;p8(5${h;`T(v;q+?T%I8Tz|^xh~KsG5&l@-iy`t@%ii{pP0GfE z*ow_wzUTRlaJV*ZqO(G~=V60UvR6^|+1`(8p&C?4u9vf7+&Wg-J=UN#FO%sE)d*sb zpvT`RA)K!`5kc<4_#x@N??zjrKB;--_bFvQrBB&H@#cuEB(jRUr`_T^7wTiwbm>>< zu3QrD2I6ix1ng9rU>uF_n(yoH{}!H*oMxXUi-H2NTKHF8TSzm8pCbK=kTQ=>nzkD^c)2T!x z(Hi>$@2(c%8&_&bceW%l%Hl=l(5NA(niss>CLwR1+|$?nc8Znh)0Z*yz<#fV{aV{U_&2wZ%x9>G}SmIn!)pWEUZlJut!HT;*v%Q?95B7f3>L2-gOVW|u zcY`yO^oOz*V|E-x`6b-PZJ)Czc7e*ksa;gtp6ZXPHJ(yKDnSvyglhsJ3lr^ocPC9* z6H-5hH$H9r6wO`2#6#v-?g-8x-Ern<>xql0JvmSGB^<_7A`IWirBkXq6J5f3pIvRn z{wf{rcHRF5)4%;KB7IWycy4>&_lVl!cgU#=Er#0}80}`sLk*wN?SbN@J>J9eVzf%O zXU`>X{$(?feS(;w(PpLdhjss!t^3yJXnkoO2CVrVtairC8-s5bJ!#nTtl^LYce`nS zt*j@i_||fP_Ag?{e$)DfRjBvYYR$qKmoCbnKv{Wterf3_rR|Qx!^5zjbOn5;PJMYI zu?Mpr)Z|W&DD$MV#}ji4Owk8bS10AUZ&izZ-7H+0qO(vdP55?DjeYMvc4oJ{8JOw+ zuw|^|s+=hTU5xSpq^o*&Br!H2VQ;R%vN3gdSQHSfXtU%ZAb_lOdHl}aN9~nr@(xI1|O!f;8nC&;W zmNHg=1Zcr*66?RzII4YDjgXVezT*5)CvT|*x#(F1MkMz1SW&$!0VoDL@2y#Q-Sl8`WxDb>ntxa?Q zh2Qxl(t|WSKE8Kc*(tc-AQ*uqB0IggCPfUSELd6uBFwy&jjav=#e?{}@4%nZ*dtb! z;Ro3yW{S$o^IKY4ZtIVZOij(qrt17EPk>S@ZyHP<@g}u1JC3NR=wh7-3IhX!{qa1! zcez@ltdf$DsOXpM>}+&6%^&(7DN+RAbnGNgN`Z{5EU%^IAAqv}D($0D87TzTvI~efpA!XnvFpu`}0ZBIm z&ZKN?sg!CBQPI&n4h{^0xzVGe;(+R8wQBjIIU^7tsWq5)8`H~bXh;YOLIc0xv9Ucz zosz%7!ZDxPOLBRfZ_`5)KxTpc@1W^>a^<%{CiZCArV6)`f_e_W~6S%AT!x*aQiqSa43O-NTy1Xr`JqWkQEhu@7 ze7!EPIc%y9dw;e+^K>NrmWJu=E4X$Xdw`7{Hl{!DV>vu}MoZ7GHv@E-?@qf<0c{`p z`=8-}@g1?@q&|+zB~1le>$fTJ9~9s;a49eB$46dlIPGNVXcf48=Ske=ch;_H455t; zXBzB0dJE5uG>+Ozzh5Ym0GyNa{AUe&V2}X7TMooJ{yK*;u%P7yaz*27v;5il ztb^bM1O$}J6@gwC5fPD{y}cT@d&`i}(8KBc5xl#s`nblm)CPcK;1`l}x)DDjWD8p6 zTz%SL3kxaI-pyf4=5+lE&-G`&z*6vL`dhQ-4q@AQQXhzlle@%=18O&$0H-W%NAoPx zMZ1ThZ8+rNs%bBz1mnl4=l6fk_ zwKB72GFLFJQIUbHg&K!BC-czcLCgvG-b&KY#00Wm8{uKsjImxR_d$jU1mg3#zilcmL=$fp>~eRd?8R~}Mc8hl zBxG|o>a-!ze$ToPPp2-WHphlFbtDD1k*vmvvGs%Ke@?6SxuEZITpv@#0j*lq7`4Qx zyI{oqr4D?jh<$$zF6_5ACQ_vnZ#ReFg;Zbys2&De`RXQMN_?M$9p zfk_huxI$GgH;pdOiC)wfvk7|gpX7detiep*y^`Pk{sDj;YtaPVV)#N4ecPAPz*7QL zS7~Ty=ouLSxhWwT8Kjm9J!*7gP?>b_|HTC`H}5;Nud&;gWOX_d2NaPwTyL25p9?%| zUGAGlf)?E(l>CG*W=NiP(XQYi&>84A8ZW*61F?rg&AfC9ji`?mt+>x0!FqeX=>>RC zz!;9Qq}w>bi?@@6TcczhACO?RNhgK2P2lLB_2j=;iGeFT=s7XvelyN% zPIn(7CQG57msT&}$@#Jf`|Vz6T|qLxU{j?rf_LBW2i(nW_q>!zQyP)$>D}a8<|&?T zG%Nu8OyR{4IGdb{hSb;B&(6(lI<_88<^Ja)1`G28v;nUK+)UT5EfOj!zo=-)0t(vq zbz|3CDSX3DF~{&HzB};);}ir@wS8_VfKI>BGk0cz>?qm%O5UJ(0aeL$kNTd%7!-)x z8vd=r)q4gxCPUW(ug_jTaMy2sdv-2L1FlEE)9-Kn(7&w97NW^R=ST5TL|x!S9d*cAKyTq#AW z9~^6YI{##;Nu78}6~9ft2n%=2e;%51!Lq8y=(t~S-!b60kImj}{e>!yUI#%W>wU+I zW_NlGvVMj^`vG6~V{xg0An~XRy!I+xl6ZG_7u&R~s3<5a>sQzS-#*U&iV|@n8_bt_ z=F8Q564dYkKD=ibKG39TlcNH3P@0&SXj&XQwicI_nYX{LVdCN8C5`R9YRVySl4A?V z=u7rQ(_)09qM^yj%kL=Iel#|xk?fQ?`nT90ZuRqud_cOvLazTECNf1N^1r?#%_>wJIH!}{Q&+uVr6Sfhst;(K~}a*w2Z z97xhPBpiSlF}bPe!JgyMa#T!FnsYg^eha=Dt`MidSSKg((NG^O9^>CzWfgp|o)~(@ z{H-5TscLJ%J*AEP&~4amv5F;g86R|uG*h%z9X!THW{v$BHWY|ma>Zi&@$*W^Vu_^; z$J1E2N8JCqT<>9DsDF?`rhs80Br#dx{Qdj4udlDJ;|Cz648+*d3h_#sE`I^80r<(i zJ0Q;9_HS}*cI^!yJGWwyM*<+hUwSP>qGrCv$DRUqkO zd6+-wQ^4#uKcBTu(TAURJXhR0g!c0S8wQwRZLBeaY3cxl&sO#q zG)P23=MNh#9nH!!vc*d6d;6>Ff4E42J)Z%J_Jhh54ih zbG{plV7brmv}xQweb<1;EN6Cf_wQZ2())iNQpeD5iO8;MmNKIKJhW*M@SRKSR2s9v zu&N3ApY*2Fnc*GpB$wo0bq|xV)@1pIHt@aV0ZWL9@|tMZuUA!*dIBJCP3yXO zbK~RY6%Xh9kndt(-Q7Gz+)kw?%`tOqVnx%u)^&AZgk3z=8y!vt4~U2@jT&ArVYhKFvb+v{5xwgIhvT0xUboOE z@u62dZ@KTpL#UIgmrj%sG|2&Yrw>*TFf+hl0D-79$7Pdp5k9qv(vp%0cOyYeMihBw zjY-QXz3``H*SbAc#@4K^k`-K{}XU8wY$HulU(qUvc8Uiz5M`ljo)k(N{c@@e^{^x8*6jcw-wl^=n5ECDR`&GVX{9*+z>Nt1Q+ zQlS%f|H1!?Am!(QT(|o@N6-&Zg`4?GM>HPW|H7Z+&em2v-z& zzb}@JWwC(p2{E1sGV8&8`{zO5qvOzYY*cfqJ`A1ynS%l3A0bxya1p-ZwoK;TD3}qQ zD%~LY$Q2A8er~o-)Bew`W8S5|Gd1$bx)t&18Q&eJmE2(>gY_2%u+2v&gTpTdg>ENL z7*Vi}B0&>q`PNJ;*B-%F3dW8YFbH4!DEI&|Dx02IAUX;U52vT6-*9YIBPPZn51|an z>tk&=8#UxZN;1bIfMmU>4TxP;(h-uxc~oQCx*9m74&ct#KJ);NeYB{CAiTVb>q%uT9-9^Bl&82qvJw_;9hu|tpUm;oZ8 z3;jgLC+WTK9H?gW;eI4FtXNHLRWpZqZEbCQ;orZ12O^c7IT3mej&vHm0sEp?z0+`} zwT&>k@h+g8_L{uBta=7Cu_F98kz199k5{{S`S~vOPDWoI8Pxg)eOl!u~r2DX6A~0Qem5AL=HxUW z6{-o{!se@~e(Mp(kl1A#T2c`=(4cD>N{lMvkI8|c5itZPe#BS+L;xXK__Zuu*gh^A zQ26*B4T7clUDsvnXcjeime=HcU`ypW(wYbhK<8!^(4zpS}PM;c8I)C}`7`}4;CG{=V1)>Wq+ zud;G33CU|v{h$Y1i=aw5Q<2{2PB}B4)NF*o|b`BLP**F z3YUI5C<@>Z@kI!kLu>8kvuMZ6l%y2t^GtJ?W#r*jXGe0gjK8RU@2J)4HvURfB1Vm* z(_E&JD#c?!;lpDn9ugQ3V0eRAdVdY`pGyZhz-z_^n&!V9fQA-(? zc!hX*d8USwdu>$Q9=+dHv-{O1*9alQ)<^upTgYp{+o1(%NNBB5jXFXVNYxR zWLi8Q&peT%OPBUlH!`B{E8>iLc(=%n$St0c5Yker2BF<>K;yzEnRYWWQ1*28A#lDczDpm13OH9|Igllr8xOtM63UQ z-vX{Su0fu}A1Lcm+qzkZ?S+kwfQ8ya-rmeW& zhb&89^#W_dMejGR3xF?$h=DQuT}j=BLXUOxBfeKxcQ5Px@7*Qy1Uw548O~d<05brf zX8;=-_DGW?dVhbv``wb!$5#x=$C4GFFp1HSlZPg1dHz&T2o4TrQKU(yz9WJ`A(qtN z>I?oqUxj5&-iv9~#sk2BoSZdJW8J{VT?2DR3os~wLVZb<1)n|N4b9~-rR#&yO%etHuS)2I4hhY-Ej#Euz(p|gI}-hs7gd)!N1weE!nL?c_zJKQE4IK~ZETS9A2*^2D# z360l7BwRTjoBz@uu@V7WN$$NsVnk5raN4c;>ReF&RPZ8!7lk0U5+9`kyyaWo#|DqZ zcdD7-XfLwY`3c~wOd0DROlDK4HG}~R_~LDGbbS1{;r9)l)t;oJWXrL2#n?oPwZf1% z$y^yEa6%GBME%rw6k0Kjy|eJFT}!`h%L;zH=2S%bkI+bolwk}*Pz@2OI=Juel62~o zN+T;8-vZA~$m$GTHdAz`CBw?t5S%1z??FXAHB+K*4F<+4S%SCqRxC11ZN2?BXR^jx z10{$K8;?Wm{YI($A?n|1e3gcSE#hBHQ*92(4BZfAf;EC+X>+q?l+*g>+rAv7rq}=v z+9h$D9rNBYvM8CUu|4_2gHY5YM>O^Enk8&_!BzUs2}MCo#ZSL`n}l#Ym>wGiD| z3&+R*Woj&S$fjiy94h>&Exc^~jDX}%aK@Wp%E@S;> ziHhw_C}(_e6Vj3C(n#)olE_!iK@mCB?Ut(#JvmKX)WzX8_5T(!&uw7BAgWKx(d#bF zjsw>*j0Ye=FjF>H6NQQMm0A-Pji7)r!)+is1!6tl&ECN6^Yir<30YZWpkDFvayas??+x;3TdT?>?r_TF0|f~4!4=( z7W8Pwm#ZsN;E*@5$VKmjr9z%J^c1Do>e{HMDrR0@^Ai$^++`HeAn?`rU3nyK-6+^{ z*Uv6d}^m~LO*TNQM4`{~{fR=&c4qvC$zy_dAU9h^{>8lobU zXF6cM^Q45v^x^S&AVoBGlF>~0i?JGffryV7lwTZob*eCHETarJ7PoUcuzMic=}#>V z_QuFQ$5oS`_sNN0f5ePL`4bl8=QGUJZr$h(pnrrJ>jR#=J6VE+gaorb%ulQ_TlnMo zaw!D#77aY^XMXGYjO)$~sO$syyveBspuB1by!f-plHW*qE_xVx7+xR$lJLYtAuDaj zvW7v?CP#1;$?VT?>GPg)zvAiy)yQD)U!5M7QZz{DJAtx_V&!UhzbR1FG{N)daCm(k z$i&E}AW&=`4w^)dtxa!FUJM9b$}<Id{e&d8r514QME-I!#3kqL>Ac3EqH)+yH2Dn+*jsNW7PsW%X?g(Io@ILV7Kmq_% z2YP<)p3e^sjB|2xgTuq~i;H2sfsXMRpf3=D(`|AS8n_HRG%iGz_BpDb-h!f|A&W`T zb*`Q5FX%2~dheC7Y(wUg{KX!ad(cot3>o_yjwqRfZ!A`l4-puH_d^E=<`tyn-7N&w z?>m;0voI%HD1bb>rvZmET+38b-y>WexK_>6;j><3dox3of*Jb3G z6KUus)+J=8jlymgKz%foFUr2Lu2T<8_3)rMCY)tT4Z5{DUS1Wpc7_?a(!Kh^hBCS2 zxZ#W8isIn#N4$HgF90g%Q;R7_4Hrp&M5Ts~lLmxxZs`}M6EvdaJ2@$y`k_dmm>0_=mh5!9QWWF`A zi-5q6;aOKXDY}RG1GFGw$xqnB7+!ZpguiO@wV>Qw4DlrMH|3RdW^3bt4T7hNT8 zpc4r;YrU?)AL8cP1U#pIK0OV7tc{n$a1 zkG}qhsw==y-vVMY_JQnlW&)Ov*U*|`qb;_(F#(t@bkzT}xnVgQt!PRXUQdJpz=S{I z;LqmPO&FkNR0BZ!K+%~RBOLPc=b3u5h57iO|HIS;7OfZn95Owhg7@|e!2sSB6ciMY z>Q5C);Q~G&(#HQIGK@BHYT~JzICZRby*-+T)X@TVN#JaNsl~;I!ht-d_}IkS&@T%- z4aF;C^JC3%*!rmr&BaUUVv;iLP7K%|up=t)l)|YsTIN?&AOP)t0NVI*j^)k4)Z(cl zutATFjp^&_zZBCP!sqYoCd!_hywg`ODafiT@?B@-2#v?Ud8*eZq&oyM-yZ)daXQy^ zQn&p5x7-Uk`v2aNY^iwSc$or>-S1=`NbE(vN&yN#R6kD2Gld!?Ny zmw(A|o0clD16Ij~2Y@00ZkuYX_gE^EoUAOM>;6osXVJI0JQGsJHq9hjSA9V59Yr09-!Ny^$v+eEvEq>;vhaVLRGIO+_iaT9n8NT~o78Rnk-?&k;i~JxC5Iu>m{? z6X1F1`!KQS=;&v7;u8&jQ!Q*2xmJl1aDWUZ)cahFk7J)Hy%oDnW9EQ*y4byUi{qM4 zh-6>1UZ?s00ANt|5=7^~ND{Plb+MG?(HQ1UT$ZCjwPlKXWgh8 zcF4@(3eZ>3#lLd+fZ@UVbHltK^YU)M;@QgrtZV`op!*AtxlVg)GQ1m)>CTh&www(yFSgo2+uVIVEHv$X(}Wx$PYR5m`Qc=$Ob5v0}V6h?&u% zzA~S3s?|`TndWB}lYKZmeTO~g0w*eSY6bNo>vF)&^%SGW5Vmwr{&B}ibk{fdj$7iA z?nTegl@yiuZr#&vm}Ub9K(NpvwT=hcIiXmZK@)$^(@pR`ASr8FlGYG1OG!uFW)3t6 zBVc8%({l6Yoml43yDRNCuGU8KK!)T&j37ZG!14v64_P_6;_`C%XHQjC44~?*vyK_L zRiXOPU4tOor}F*?d=Qou|c_2Ow#abcyF zK~eecM%^C7Jvof;FRbssg_-#Y2?+sb9^i4F7b}@!>l#BDzSYJIR|8$X=FL;7qaRHw zl0_yL_Cx-=bh3J*5Im9zT{7;Bgqj^bd@GZjR;J)(8AVRdTDF+K;ZN*jV(e;{{yZV$ zC>&=icA zilsldlfb}l4sJKFu?VRD(#OC3QRjqLOmz`=-Tr=-S1t2@aRI83Rqg19Sm>Bd6fp*X z)TG5vju{3veF%u``*m@Ueu4e_@w*HeM~Nw86IAM~0fN)*H{_@zW+qVa;|F_}mka|& zLrn_YJX~SABL*Ud0U&J(SPqcOK1Hub>;GaMfYzu#sW8i}T@i3nS`X@R3_2?8Y{g70 zO&w3b7EQf0dxgOpm$GFDL75tl z!{$%~{rQNb(m1boH>b8a2AhH70A)HTQ(TS@y=E@tFHVYS>Y=T}%-Xc%I_ee%VAeYB zInA5Y{6a!>M&nrX6&hc=e4)Mq{n|o0QpkI8CgRuU*#*_Uw4J_rQ#$lQNM;x%4wEZE z5eNCLEolwjzGZYsNU>w1W%}lP*;%N`yo$V3a}INL{i8aw){s2kJWkzAD((=a3F`zg zr=j-UJ@ zCxcEsJP4!2gYmsE_?;|H^qpHlC=rq~(`wf4J$7n&IRs=WRGQ9w_dx;!nrc&Jp9XWe ze|5=8aX@uRFoFCfor?O?ffcwgs0SKpfQ_4|-tre>R%@%9Xyh^*7Q&6|YtaJ1;Rcgj z3_);;e{cSrDa-RoEjYh7@TOmB()>}@kURVPxW^R0uP{AG#H@e506+L5Ccu0=WrhjWCm$l0)&6`fYcB%?&4<8T8X!z{~h*Go{Y zTK`2PX404*9S#}}x;O8wa^?__=Y5nJORZcGX&ni-B|w&Qzj1PyKK^cp4-CqE3Aiaz zSyU*M40rSIFp$d4wuHdZDY#DQ8{FjebMVY=(3enzbz%=opk@AN;)#6yMO1+rwraVfD0ojEB0paj-k)z<|&=SscYuJww~IaK~B{Y4$#wTq3H`(C!G|slYp1NZij=` z4~xFk-!nuq!lAkRqX7=S%H#`?9ndCkIp=N1JK z{FL^fw|e$B1RLT%I(gjT4+#{x*e+*ubj)=v(v_9PDA3ud&WzbPUu{-9R z=Vz5ix}Yc!vl;o4!XG_~q2Is7(-03T4AorN24>9*_R(QmFp5ejjT+wwLXhEvO9B(p z^W|?+M26A?BSeTcV0Gz5Hy{YGZCq;q1;v5=Oh14p1#Byy0GJ?F)iL-Oyy%x6aL2Qy z-T?=A{z1a1q&VR)g+NFWj_}!gbm4S0?hu7fzpG6?AFgioEhUQZ?<}IWGasv645CsK zlmDS_)%8!-o=|mUYlR^o$T>C3sgV1f-IRnico4~5)SBZzZ#6_4Ib^h&nP0-1N0gus zkCk8^oGu@UTkov0$+R!GZXdi`b&(s8t_WA7f{_CryFp0ikii152-tpo>4j2}qmiR@@$0J9G z|1mAIdjTt!trj6}G1QB>)uNKCewy}<4FyM>dybnRbn0n#2 zV!A7zA}PaRz_=cm6z8fj#Go4Rq9lu(>XR$D4Ntnr*(f_~IMHP-3kQFlLp`u(wRYM* z2^l<~MgjPYd@3BfY`-{YkaNp6FmG}~MfxnGqVQuy!cFr{oqjHdp@OI%@3K*|Hk%lx29HBg&iFkfVek!Y-*zpEviVMrp>hajQ=1S z90RO!t}yxVZ%_sJXddbWZ$)u-wI|vbCzOa$PePQKE|zgLHKBggs)C4|0$s!b*6&=q zWCi^!S1WRbT{qaQZtVyn4l<-x@F?KjW4v;5e7$QL^p6Vqe(`-T$~h9zdHY7x%1i&w zPQ!&=$zhujbSa+jJwyRp@!w9!~ zoK!(v$A=qB3sNjs6#(}9ym@%YPxekufF3aQ;SDyzXV=$*R1OhVXZUIY5#2NB59f#2 zgTnKl^Mla|{`KD<{Hyq*J}v{ptNdH|;}wv26hI_m@cQ}+Bu_ZU<{$s-i31`jl1pcH z0RO7d>4lb+m5p$4jG)EUaC53@Eq?dr$@v)e|3TST1;rI@Q9>X{u;4BsxCVC(?i$?P z-K7Z-G`PFFySux)ySw|`ypfuZHy`uSRa95gb#LEu_FiZ2wb%O4*8h?Bee~c)US3{6 zOA84n7S!R1X#q9kk?N_|zc?uYL~MV^Pv8Lk3ZU8u z0lI_2dVq;@42~)l`=o@G6U2DBfTsX#S(pD%8DX&r3tQKZuo9f3^00<`M#u(ezXO0r6f6M= z8#n~WK?AH~fZz1KZS(M$;Q zp`ncxM_#+W#C7)6r)b{j-cmsY1og|iNhRf;aUSD+O!9zxAkGq{+5!(Zs8yRD(1*!u zXaMNeehVj`b=O$Hzc2;|;Yo<)3|Q9x@HD7E{P6=zs9Hpy%hX1MaJ-ppbsk=ZO016td`e!` zt|qHFe4d$$QUunKRbT(X%An`)DAT|O>CK!NN}O|Ze~L+WW2KDXiE?_S$pBo1!bPQl^n%n=dVe2NRZOe^_+@22qMz^@=xzeQ4uu+7&A*!ZFZ!r_RJl~`ELQ= zpY9Z+S|otqXR}bHPH2E@(z#xKAzDhPn&Wj)t@;m4iBL%iZiG2*v9#P(b2E0Ygs<`^ z5T6%8(C8pZ7lC=p57q8nVT3vDpm}H@LZJHnLmPlZOKpAq_RZ7a(2yQrpdd=3Ro4-< zhQM2T4?_cm0LgP(J3Cc|BObz-6)Z)@QXN;!V|3VB#9qpI*@7)+mD{Tp6-@w;>-1%-cb<}xbUSQBEQ7TOS>0ekw^#LxL zl8r5)xtVi+B12YPeHmF&CCc#-oqUW%+SOAa(g~|fJ{R36%6b9JSRusZ+rsRmYDcJX zhHoyDp5!1Y1DzxI-4(~~-D$q_1!6rV&R=;m)$Qy_Ns;X@2l_$91?_o%%uQ&)g#~li zbVEY=cxPb+{u|*N7nvgCdD*Qd}ZmJip zKj>d<--0CiU--L0>cx{6FdZz2Rkg67c5d-f$bq+Bt_?OCiI=AI`WMvLkpZL{0!SE$ zm*K)d0y~53+c&-GqyGzUH#h)z8#eu4f)Id_{XY=e_djoZ?MC@8X~j17?%`o(anZH3 z1~?87!6*W-H0K|sTU~t^5akgQ7w4E?;s{V$9XEIWRlk*P`)cy|iX0xtwEb z{g?Q*K{W?T31%5~+vtBVTk_}g)~@uwz19unF&J3LPf98(ifU@X*%TBZ-GFN%IZLII zZD!o^F;ps#Uluk70-5DKTJ;S|m5k~_&SXtPDtTG z(Hxr3OYf~LVpA29nkJg8#pf;UN0QYb^c5SMGoa8E`j^vpjpXE`VY{yt%2&<{idr*L zCLKt(zp_!824x&{W5Lm&)JqCW9j12>iI4sY<)Se%@etQeh^I3BTTPol21*3RN3gN6 zXBQTL^P328|9~b|jBKZAKMAyLT|L9sq#&bHbon*rIGdd13nFR|6mm7Li4|$fu+d*q zH6i#ow`$t7?QT~EW8_wH!N-n}v6 z?+Tv`9m!y0ArL=#NFXA+^Qh1LRPjQu<0`2dr6)0-&iDZvCIY4Wt&qR6Ai!!Rg@`W3 zcQh-B(qe@24qY)CGt9U$DkOw8H`dd*KPd{ry0zL);y~)(Hf0B%BXPyT2vB}MIy>vz zx!SyQ2M1WW>#@^O@WH#7h?Nc#1gzy2M4WWLdvk^KOS6vRYZ4X^Hx%z@rvx z{T!|BwogY$i0vu9g%Q*&`PvC(_*XI;XJ?-+k`N95t?+>G;L?Ib-R?iSrO0AQu2L0= zEj93i9O5@D)jLdpv0MgEO-Z|jFYXn>J3UlZQWm)Kz_zWEn_>3BOA69D=xJ(!ZD8?> z`J%ue$?u5vYt^!_JcngWrg|d~iPqVJS)P?vcP*n0b|UHU7D&cFuz^hg322a)YBV5r zY(z{P?9|T4{Ob`UC%eNGiDMZ!B<+Y5RLqELXuzST951FM%F1ig*n{|h*_r0Ck|M%& z5n*M+*7hFHd^tv4)}caPKJd7oAV%UzQAsOW>9jZ3R{@eTDY-a##6mkPfxD?zE2lzi z2>yA4(4ky*Htd+=>@3;7MAHFg&2&kuQ|HmynS}~sVe%-9H5sENC@6hYaR~`xx?!Kc zA)sytvVRfJe`pc|9bH~qdmIqulhW2+w>@Yf2WTOx2WO2+8XA&nYS>^Q*|z6R2l`d2 zhmKDzYO8xDKK43+f5=|hoN9HsF1F%6Ae>YJE} zGB&yv#6G3NoXPW&Qn~&MW)3OV7$xoqU_@uX zABsv6w@@;*|CC$Qbj2_I-}2XEtObBzY(fGPKrqLkRrlYxApZ(;c{?LZc+!gR@?TH@ z96qcc4^GK$FVCT{Nkg_u8oaAhuBiXT4ZVdS3?$;ApY5U{0;9mEE78uB2$|vhAIeGwpOD1`O{(>3{&0Z)D>`t}In3_DiWB>#^eGr2&$7@gmxn1p=%n{Q z>pL;AzO@z42jF7)h2gRx@^v3Lw?x>@htuP-T4vVOp=V5p%E%xBD)yYjN5yYpr`DHx zb)vcqrbLHX1$p7tb7Bgyu+oN%MNwr+XOuq=r2F*des7HVn13f75ApxoXDn=PomD?2 zQLWs4GV>K5ljCZfoam@b72yl*U0to2{^aLXig-wU`0px=x(pVVE-cfNbf{L-zAIc* zx>HAvo9F#Y=n+#4N#Gf`y?NyF9cAIyUy?@sv%*9F741TT*dz+mWs+NzXnuXi@w~l% zk~5;_#NGuK`hS-B^7FG?$r)hRB-*xh^As-Z9j?*T)C6QW2GG0b^z?MNYI8{L&kA<4 zaI(JfSF#peCUX*~ijjEGZ0MocBDlFC*PE%i@wPR7}a`AoDt%mKdJxS2Us zzmEm@LUILwSj|goQs}0)?LY>kb}1>wBq=JN;_z~X`zKFFXJ;A8s`>d}r_L|ABG{|{ zr_u*t0AE{TbwCXfC@aUPvwek`Tw9YC>|VUG?LV+(pF9!eJEjwdu26|15tq6o`G*<) z9p8Y!_didi|K9j-g*>NjUW9r;(aQO3*{Sn{GcCNNqCFYlxfn!J1OEviY`bnKSYQey z)#JRW$M5HvNAJv@{nZ5MJtmZ{+0<1_Svkrm3HW@@58v#|yn_0x3+VIBxkJM10}bQ1 zhmWZ=(}C|W-HkGfC=6d=zQRD7T3F=N)y2ifVmM-GcYCh?`$UB5^w16HFoee7*I}EhoEh|C8TwCOQ^;{ zo@uv>imrwlx~#xuk7tZ)?4$s2g@8QE&uL)X;0*}$`U4H(P+-P08k^DqH z8y5pW9laeAKCl7pm_51<{2Z)R2l$BX+`@gL`^(@fuhod{?97sf3k{s;CBp`=v z1%$H2uAu&> zG~I@$9l{3pY3jvJ&h~`PUiQGlX$HPL7BRBhJjClksXQ6=OM#DUOsu=dMFb#IZ;M<^VM=Q)^b0;)wtcx=k<&jY#`Aht+x8_ zhrb6am<&KTOo^jJ=bF6dphL#tc-Ksdts;~xvYq@nUhd84X!)CDCZ9-qCB=0B{o1Ba z@k74l@v>_~m7O+;B8H%i<@e_Y8xp0d;^~{CkIT9js3%YbUpIC?Wh(bvA6G+$kn!Ko zZR28&`$d`$fe4L)el|02tDgZw-Rt4bb_8D~Zcajj>oHGuZY|No9SAutwTIm>n&Hqc z%i3t>8^QC}7i*{ot9|XB9!wft^c94^u*Y>=H`Oxxv(MbTAR2@t2u~7H|fb_LWy%j0IghW$gruiUtk}+ zQ+XTFcW|u*y$ypVnT~HT4G;VrrX;f*SX&Pdt_IJ8j|0)nKb)CDO-zt6kvR#g+zK4d zaxSLWt*LzyT*_T^xp!cXAG8qb{7m9;8MNN1dKCK*PIqninj_VQkg*)0N~^F(HE*rb zS5Sv%4lRo1ZmwO_xVZxT#ZcYTq6TYG=s=ec>PR-ujsjovHycaEDJUp5w*m=ybw*|@9)IH(8J*K>Ugr)a^?9%rp!qgcW9-4q_SjwJKzHC)Lo!w3v{PO1_$&{ zl|WLv9bX&0_PTvTdb1-XPbzWUOJ8X^M}ffBATVwp7d~pSso}YY=Dz7|>fPza&j^H) zTUp;pwS$?e$%1XZPAdwc8+rcf5%#lG%Cs7J9!CG^Um6 z^-d^H*BrR9!4t8_Pd%0|NKDokZ~n64`A|BdihSqf{oaAZ$i>NjH^R4_uQIPl=-;G% zsB@z@-n2=XOMQL-0?GU5Zz~ft9_Yu{w)F*&C+H;@>K|zKt$~`;l>!kL>JJ`|klK6L z6lJ$>GSFo7=SQY|J@~dV2p?)ruR5;EuvxkB)$=h$6*X=Ryr0(1pWEHAk$slyl9B3< zRUgZkf^`iYVgpVuT8HODR||cPpZz^5TGM3nwZ=Xtq3(%f8N39R+Kuo2#{B5Ts|gH{ z&DiRC88;E%;VSjehm}|4PM528;`W#$wpLAIKyARs6u1rI1XFBJ0Y>G*s_ zMP>T8a0DVrV8dv#rleluwvi|bLpZl`F^Tko#*E$Nr`}Q7_s{zuo?>3FXVAPW-|0PV z@-f)|G|8SC&vmP~Io;4Fg6t{q4c3!18+RQ8MtJ6i_&~0>8EJQ-^E%1?+86{GZvlu z=o5KrKYBS#9OjQ$b;0+gK_*u%H;vmVm`t*8sl-=DBbZl5jvt0|HJQIdcs{D;782Wct%7*-r#C+PF5VIFVeJGw1?fvHowkgrAEc9Y~ zZqkv28VUy;BORZcar({nf_1&SPNP&C`J<;z9na$QVFO8nNUSxJzOON3w^;mUTXhx$ zd-!WAPb)VKjBB=?>D|%9aB8)ll%(pqLrtlc9BE4rJlz}T+@Tj_(r>n}xaqrDE?d_L zItN!Hcw+pMR~%E<0kGHdo!AF7hJJn6#_t0Mu z0}Y13KlwkC0Che&WkYen0&GweScXm)rd*WK5zJ~9MQvRC^yy01&zmx=FcDzZa{f<8 zcK3py;>e?NyBFb`FJT8?gbueW0YhLka$Xus#~Z7piBS|5zOdB%UFo61Wn)|594e1o zT@)>kGX`Dyi0w(>?&c_IO%yd-)f_sV6M}e=xY(JM<0)KrtsP0fpi2TZnhJjK>+^_O z$CBiJQs`i^!s3bENx)el)A-hDtlc}>>z?K6@pp$QHAAG0)8Sk?bt!?$*szs1pNwZ0 z!p-BE(7~V@RCJYIB);ox_chlD)dvu*aDvXb;{w(CtK-+hJwG;H64(7W%|!NfXj1+$ zosO}w3Q_x$8_?!<@6R`fh3J}7%j?%XOB$|NawN26R-0@YrVNL8cEq;}$russaAZ&* zYJ#c#SAY6mJGGd~iFSUyjgJE2Svv-$n9ZxtQQ*RV_~l3oizz}vvWp)fvNFD!TVFoM z`Yn)1tzv+~OShG240>g7kM%`;Z%7ChBe-xLA2~kI$bAz3vkd&hT|)sC?v9-acS{ zB}cyBhP>zQLvSf4+ZiBq_&ACRM1Pg2{!3F-xRVMWM)R|C!j-Uup9m}(V@=O{$J9w3 z25R8fDy*+RuNv`=d(eukTaqJ4us4wUK!W7EPtS3zk+=_ zUD6!pzgJ#$Tltekr4AxI!Z0hG{H&Z5jnK-_~L! zgz#DJJ4R~AG~5^*rGSO%CUHr8Vo8)Xoug~^P^$dvpjZ26G`W25DS|JXl|5lq+~w1c zC_Y-ayQ4YJbtmehtzv7(8Oo%hohDh{d{$M)*m}X40Ydq26PwHW_`j#eEa67?-#x5% zQ{k~M6%tB+ny+X4B|*lSwWwBu6OHLn-r)9o0X=imk7Die^@qA0bthi_0aZp9w7)R1 z%CrPdoF|7K+1`f=jvQDN#^&2;=^auV++Gd#lJ#bluL|cuSC1JqBmfzoXt^U~&I0;z zSz%-m9Vm>*;6Dg-X90clj0x!CfZ}*w&KL6X_W41SG9FZBHdCe~CMI8K9goDoaV7Si z?OYiL#swPewq)-u+E?8zxK+Cm72DeN@y~q>Vp?;tPy6;KaZIoqf8@H86D7U3gA!U> zf+9(4gWYy}2`|sM?qLS$=z1@2Enc4^3hYn14M%^cF}FMrHofmw*m}QyToq{8kl%=6 z{*XS;v-85Oc|BWH0l{07V+!GzdTe3v9`pHWHe=haP=+KtS;ePCc-O_!Qil#QJzsKI z3>97&s64M2PJFOAvRso_U>-p;ZPxS3p+&cP)ixSg+Sv%&(1YijKc?T*;axgx^d*x>SWUeyw#~D^vrV9%y;}V9WY^*Js9|dE@-y4g~yv+qB@LS-rrrBu!*Z zg#5Ibn<^2CWc?1OCbGV;e#gw1vGZz$@5d>gf5@oJ@kO^i7#J^FOc0Y zkY^lu?z%b+D^TdApyEp8Ns5lvUaE;{M^2DL%NgQe!vTS>S%dVcg|M34vZqyWCe+1t z;(ox7{H;P%il0~rcUE2H3mQ`h3QncL5PxSmfC@55CyCjLxcJm5N z#}$03nrzIJ?10C$Bfsj%yVJ08by;ewTeSM&_-h!&H=n1`}k}*G7=oGjU-fpe6JGL4; zKdOv0FJFZNJx%DBCU*8qVx9&F4VtzB-281CaSZQLKC+lLx0);@T&*`o>_4%+w}kW2 z^0<1T`4}=!KD`^PUdqw>)ziqd9aogPKYl?W@%b^p^kLF^zu?{e(fL#JMS>07i{$Fa zL5-81_Lej!qerWvg8!+@tJU`85BF(kmTNtPA4v{}wTB2mPb_t-!*NbVlKi1dq zpO3D5RuF!J-QNA)Amk*pb~$WIPoJFl4Q|^c$oKLrc+#ku_2A(yxFQ=j_ho44D<*VN zQDh?4b5b;l`t&r>x2>-QWk1eY+m zM4nB6tn7bp<~&ca!JzUCk&90UYsAQLzmUAQ&p;J2&vTKtX*v2wrO<2J-ZEm0ZxWp@ zK`1NBX(6z%WaX99q2alQu&4ilqrwaS z-V8T)$3fq&B&noFCeF#$cA~Sj6qqi`abTC;L=3B?g6ZfS;9C`rXljE*OG}%T@%APs zkF4Hr@WbEt&#mL&@E6*prN|fvH@B?)2-LLc-WQNpO8D+4#%-F%l!cqqwuvc*7lQE# z3~+#+SRu1Wv=zS6F@Qh7iE40nFX-lGx>N<>eD(#M4gulsj1@NtFR!CZGG5>Q9pSZk zi6Go0Ozo#JexL_!HxE(U>U5UHlK>+Aa=uli82WhieCc%_hRH3uQ}LulhRTn@fr~Itr2@A{G%qlVijmiFmsI3z)GBU;fNjl4^0Dday z_fq}xIQ607uc^d*mz*Ge`F_HQLhs4@Di*uUeg0~xQ7C>S23KGGcE)!TcsEz;=rOs> zl<0M@)%re<`uzl?cG`91-y6yp55WY z!o;@HMdNZO>oRz7_eXz6qX4Y~$C&YNavmp3@+-nbtCUfHdk-)oA4v-r0TxP_sWptj zeZ_)I>oh1BQU#Y(StC(Had@pD!@*KNuWq;)Gz9%aGQo(x!2Fj8zL*=a1%eX_wrbI1m>8tge)hj0q zv-1I;LP77SVCcciiD(jvaEqzhz5Rdn)rrYBHjM4_uia1qMsHD}DJ?QL=Z@+DNh@l7 z)0XMX=eJlT>+M=C3l5_R_vsZ}k+zFD?8PL7&hgk!&Ut8+TpST?c4m-92=D36w+ur) zC*}bdTO&ntQBoH7c)WyH$s(}PTczJS?AT^-oSDkJ$^Rg<3<6hHlJi@#z8#uhOB2Te z4&(CZ_K)Q-ZC6Fo=_?+v`sh8=Xn&0RT@56|pyc!aLf==m-fpEWVb8H-VZC^t@^im4 zo+rhqq^t75?}IBGN)qQseZQ56=3c-2;|sW2Gs*5H#Rn0r+NrPQ|Eq_n6uPN-3l&HoDBX_;zmbONK0pcVELU zY~TA`Ov7b%=l-Z%E*B;IF#Vba54rW|{2C7pv~Xb5Uz#smT?b};Bj*WOvciYH{mxPBQK!!FU0O7b`@9zmI!_G6=twv= z5A$lkq2s5z2gHH(6Wf7}rntQcYD32zSNX@L+PnRIgR9XNIt4U73D8B`;wKiv61B8} z?r=XZ7%ilR)|H&6N#{7h;T=g2%`Zvws8AaWSfl0cFy{iBLMHn%WAIo?Gt2f(;Yy#` z{O}IXRfp4>$9I0%g??nuGcS!0pzeA~G}NNZ7@OE7l*QSwd0?eZPZ7B7*BYK{6keZT zKARCRh(t}CUsvtI1KXdrg<3*gt_l{YUcrE5DwfOuatXcpVTZM-k>9Euz42TnS+PRlOr z2G|I)-hx~l(SUt|Pv0Q96-4w6-lHSbB)v5_cHCG!XWQ*DnoE`EObP5+L%m5){u|+| z2`OMq1eHO$Qe=I+->qoR;bn}2j*#Zq2=%m_ZDv_ftVcby<$|&w&O$~V-p9$ugTs|z zTwj^P_@fRfqWD}Vye`TOJ1XsWKAHD2^O6wrXmY~H$LNpA_J%YSKKx$n$jX(!y8}a} z5P{Cn1Y|YeuZt%YNH}m{lzHpPnTnyIDoZA}4=EaPoZHNW0C>(p6{tXUe7< zcjR(+rDujpKks_^$&^O3iR4coB1Dx4f;x+sS6hsWdR=NP@VQvTvWc<%YN+%@UVc-N z&j>ddyS5JDuz>{Je%A9gfLa#5-|Yn#uN4VjlQ%0LxRMTehig{&nD|kvYkic;yL{J) zSJqCDOvsLgg8@6GNFXnk?nS!$yNMQk*RGH?^}J$-5t54yHl8vUqq78*mk^pxN|3xtnPDi<8)FFoYanHMP z8Dk`Ped?60cz-Gc1MkEm9C4W737t6E1LneX0r`N}!{HdWkG7A>?YafmV_A@~y9mw4 z%dAass>6BigPBCQK~Y}Bfy;f()S}FriatAARTv+uY#A7=bFKZwz?vg?$c88%N)nU3 zt8IDwbQ!|xg;J1s=s~k^Q}0NNTkdc~HiKNGp|PzB?ZX*DW|fF-pD&5E_~B02SXk>? z$=9^_L1}U$d#4w~baQ#|KLKr4+*$_%=#k>%QrleQCet(RF&*rI*LbHp6*g?ulwidu znLMMni}{Zv1ezG3nhV2e+q-P>~#YoieEdeK9N0NXwqY*u+okZb_-!i(NH@ ztW)_cHICLONHhzVJ8T+-Fut6N6UAXprC9JjQ^QZ>8@j zY;Pv+>MWfsDALn=X-C4a)=Rg?2%Mr%JQ>_+qF!&0UtDjtMmUTfn&~Y&e2HEkX3Dj2 zaV86^s-gff&NSU0LD>|ycX#+ZrT7`eTx+!~{+tZOA;W;U!gzFFs9Kf&XD=_W*Z1HJ zWI{|)wGlAb8T)>5Bg+_{ctyDHk>)3lmU5)*i(SLm1hie6qS`S zGWyE}0!&IKMeK**QML9wTpdrqczyDDSND%r8F~bMDZ?rMoI71R*ffSa9D|bCW)a!;{h8!Y zWKV6RI|(tGE4k^ZhZRROE`@BG*w8o4OX&&eSEfYn?tnvnc_3eD@d2N;k9NI_%5 zJDsG>PS!C|u}P#;-Ag@or&-u;EC&W-9wH}toL!3fEX2l4f1j;zb+_n+@|C4m;jhfv zKGEJi4oz*ttu+=eiWt=cQx-OVHht)UpANA^FyHYyKrzd}oGVzR!2qK3=_12xz=R8o z;!8RaF9ok(C~JGqPx`l4pM5AW(IK}+T<0vvS7uh`OTg^|v7_PsW+IA3U4iatD))h0 zRLDWbK2mo52*26jzQ$bzX@MqWi`jzh0DDB%<#nb)Re&R10A8dZ73|+`kMxl zGPEbJGAHzFAsIe0O4dZhcEJb)s~;4$+@yk1>Zo!PD`P26E%@g-qODn}tzexcA%VYA z7Q!2a=Vnbx-3<*V~H9;(9G4TI6wo!Y1qP0E_3baOCZY#;S-1v@Px z>TLuP+h+y_YPVwgOu)&!``%LlbXI;xP52#`gSGC}{)RsWsbRibB_THwjjk;U zyfg73H%t95#KmSC^8?gWZ{lF2Qhh`S8c8V>Lbb7@dd>kMwi`EDxq5O}Q@Zo}tvt`1 z9~DEB*{TK_T?Hyo54~SRbW8hwc$=1Cx4;Jy_ALnmfKi8rcTJ%<0I|pHUdbta{eLu< z$$Q?!7X%XieqCeY!|{f+w|e(P6YuBUp{bp}{Ov>QFc0Y=C;#9@#f*V*a9l)PvVA47 z5!7NFJc_-v8jmS`eot1+!~1MVT@;mBU-Df+K2Y%n3T;v{@u5H_({wWmGv!4pH?MPlzd(&`1X2MoFh;v`ZX@KZhids0IRXxxg zwbmJKW=z1Ga}^T7+1~QYo<@pm2Zv(-m!@|tvKd98|32pu=)C(3F0;k}tiZB>U4Gl| zIg2{KP63a6YKEPknrfJ2ekq}u**GIm@)x>H(PHNvVSDFlvI1Cr0p?ZD2|?}%&XC<( z7zvDy#K6TyE(}Wl6ajM2T?01{cj9zvvcmps?DV17wvNNZ-WrFAVuA(=j{cJzyce02 zIHC-byQ_x_eVoDmh1KF(k5keVjkKw;ivD5${e>Bf?$3}p)SqJ@Xs39_sWLfKa>rzj= z`D$u)Ko~Z)>S>Ol)y!Jo$bu#-yQTRCHW7cfrTAOCH0KWT@VoER(l6H2(*X|RL{2m_ zd<2?}XMzJ8?*sr%f@$uHy;twzzMjpF2>MatcWej)$D%-hZTB^V=H}W=<#NCEhU24* zywP~!AlH%AVFvU*EdB9B&GlXXk-~(Iu-BxTx&}+w`8-A8=^+GT&6?2@4&=#eE zf(keS`JRZb1Bcp*m+k^cM+5U@bt*L-vx`ZZ?){++YBy%5$-4@I>C2lnVT%UTp@QJX ztCljtD+67c#ewm4CR%P;UD)$6FO_6TBU|DqTYkZHXcOaG+Z&+2Mvz{ztm42RA8WhG ziSKdzs4PUaFe-I06=MVgb%gC$<3uzom33QtwF~uqBO__Ft!Z*$rpLjG?mk?+p`t3i zW&P%QjDx|`Mf{V9Z!I%(O@XtIcB|+06y350N@FWgvW*G3Zj|z>H6Lx+TI{_)G2YzF z80tl#CJ$efMMAHx;;Yg^gY88#tMg~2%!~v+(@uALybT_5jL_2UD=1TImn{Y5&WYqQ z+EjaYJhrh@y|)3n`-o_~^HtZ!2WStu{XE+xUmCgvD)uzG_uA^FL$y1*WF4UMXmGt)ZM0fK*SQ{;QdiV`2H$4gZ>FSUQr+FzJ47c6&9 z_a!WOCoW&w+`n7o#4JXtcLof)It%p^3-=-0J|Lf75Z~WcAXJ>Va7>Bx;)V8neGfJB z1HVq8PO5A88)IJ2*kDY}`tYt@_9jA2D6KQd&7?eWQ~c|@B&0jn<6Za1#JX3Y zsPY~H-pBe8%a9@2P;MXzFes9RiJpf8{uwvBkyS}k*hRTgS5FzO@^rhTq#R+PyfMT| zS(C=`h!z|LMNCl8{bJ_)Wq@SXU+U8|cg8`J?BFWbLAnRi=u?_KP)xGjv{+@T+m5^%^h$;mH zz=v~h7QZfB6y|03nMeVL7+?sA&Yo(n^oYTqg(m<^w}Q%8citH4bWK9y98q7w{;0tQ z_wC+_>yaQ(;%7ZiJiGXs4jXcwhYR8=qL^M^sctGb@!<_=g?H=4`|BVOzBp{A!>HQYH*mp@};7d~8&*VAMyR=?KAz{36>6blOSDWrfw3Y?S!NK;(? ze|~p>RxZ%Jb>`-5H^I=*1-yCDFa!m_clX>t8y$op5lmLmByJ!1JnsAoD7VL-hla$4 zhWuZikP-iK7-0g8uOs{X@&pof6d6)JKK2Xl3+G0_{AJX?lxA=|pv|LA!@9hol9KM; z8kem;qh1DDKwy3I8^vJDlI2%C_+QkJPz1{~7%(tkIad#D>ow9|JOEYJh*U`lZ+Unm zD;IKjIJ0)P1s%g3#LD87TK?+<0Wv%18|!>aU!Q;{HwlSP*Q6Z|utf{HIB-ck-=7Xn zm+MXv7v{`a0A$VsI7SzIQ#t#Am1(1M;moXdKd+!+kzZCf(=B*05shLqR#!g$^78)H zo}rR=UC;mc;^7As13PMLb2*74bm+ML#)*G;w{9?N4){36J+P#Wr=;&yk_NrKZC%=7 zNaV4J9sfmK>n_@q1eem!Cp>-ItshEdbu^1Nh->I^~ph%eDx# zPXKo(CF=50?phXR*9WI-`2~mgu1y3-^@jO)%#ypo`J_xDn=V2;&u4Y;U43s?cZ^U7 zlk5J!?FZ)|LxHa{B@Xv3eS7v>_DvMDv^Rs?pkRLP}+(+US&;Ba%b&#CMPG=r)6;s#pU<&uNrmj1x&B6t+Zd$jgQS!A`#vb z{g5omU|=qx`=LZK?XFrl!Y4M=^8c2IB@1Y=!YaX1&U=hFa#ASfX zeopCl{%h1@%@aJqG#KmY4B>aaJd!r@>(X|Z*?`+bZuSBRsLx2}Uv>fw`eYWQ5 zBBpV-YcBOc8&*f#hF1;N!;Cr5e9#2UWgbp5^3~KyhwgncokV8v#}NCo@a z(&3``2YjkI%6krAASYkIMF`BCQH~F8o6Hp}dp_+Yy#BRW{NG#vE9;V9W!IDl2_t`c zwld4rjJtRY-0tbutprByPj%?_mpu9jR?}ZXT|A!48Sp4dPAHtFGYEXtqa#TWex{Fg zo-K{=(M=+IzD)ltLH}j78^)z59{iYs+H~ZZ4MR!k5oBpxx2NZ*+u&;bNz)&T(TxDvW8!i??`msQQXG~kXXXWU z`Nm#b+{Gm|Uvt={W`Kd>8yct$r;az$+K>F^F`6damA6x|7Z=kaiUd|1ePWbFrtsZI z+#P6tsCryh?w``ToesYXJs$l~-NE+0;Zv3OEcEE9dt=GhUJSJE@;;n3zx`d63c497 zEx9eTTW@>eId5#_tLieYHOB{Ev)bQRsI2O+G}uTMVdEo-SyAIbya6 zon*%h8qwfX{N!`H$|A2kak;*NKs~}e5BycuhlciZcyPs)Z6<|$0I2~b7k51Lh1(~v zjc{$~(EDof?ap+T^EC&G@hK^Tg45x^8yRwog!8)w3JNM}5+CTD!9o-;6fvGiKU2gh zGeF@NDe@_MQ5Wfx6n$m)m7tuW?LF+_cO<=X@f-!6%LoShcda9kijLWBuJ>5PD7rNo z65nXQg$o4G@VcF9TQ@66j_yCf%d1q~z1S=gIP!&RvD2`kLZWa~e8Vm`|%e#4=@iT+DDcfS8;6q&C%avs+aiG2n3@qPd^I!?^$b&YpZjx8_`eez^0k;wM(1vh5nF^Z#S zmdLECuXt-P7&=O_V}By2Vk>3xi2JR}p_kQaKdpmjywOhiwfdP7>ZHp-_xs1oSeH?S z_i)Dc?5wf(&}-nu0hKad%Q}v%C_dYH>YnG71%446-~K$Waq_Uz?J@pf`);7?JBYe4 z&6&m9N3+T|qrR|da~}Co-b3|^#P+%BXuNpXdR|s>{7nPpLv`!Ho#wps(zu$28^y{y zQ;CFv>$Bg&k&UVT$FMN>&2HY`p%40wHs%1IaZfTtvXqgIg7Dq@I-W#^2e0>Z(|o&; zj>eZRBTKq#TgC3Fr)#Gw|eV=6*D>;V&~PENpHP|?|4b$(YQY+R?7*2s1(A) zC|0>-IhxM%62zay!e6=Msev^F1WrdzV8i4I3KpF{o{Sz{6M5_+Vzz<7TFK$HMaLkm zb>^7=3TLUfd>w{4*LfgwDJb;0!MdEbj@PbC>`O`4AC$A(h9qpkqdL(j>DF+()^-<6UC~*qP zN1!$RgGpQ#G#rvJ;GianBYz-Ge3$*Rujr;hCGo>AgwN}W6x1>MQTeHRY&?NeO!0(A z0oMf_m5v|`3X91avMX+AmEnVypvfJP2V71s_(<6PTF(zAq7mAf5p!&3r&vi_MEI+hNC9JU$|n(RA=~)~&D$%`(k9jfg-$;Ol^_HxjNqpupMCoxiDR=qUxJN*9 z3)fd350jE7Jx$<4e8EvW1B`N?|6&iw?fkj*um>mPV-Ml#@s!-L9lxviap95pI)#Fv zeTMINQeXZ}uBzS7lf-_CG^gzeYszn0C)(|JMR|6E9ec)ZgA%5D>HP1hwa?GrzH{bh zjy_=P46rfI)XkWX&A?(7ODD z9WMCg%ZiP4`P&{PfjVnqL3)zU8Hw@?$p}S%MnRV84B0i0^yy+Xs_46h6wGYh?il~{ zPYb(QOu0#Ght|OCFx)|9ME%=8@1kotbooUvMyHM5V%WHg3M=>D2F&$O0`LdhM45

;7sMD65NziY6bW}jiWp?4k;sUMKjEogZks- zNqSFg%0*jOyBpw;N$3i1;fSZ`a() z*R`@Xd3uT0LE1GSZfB?lb@!RO=~YM5?(y$X^rw!?`{L-aQrC;`_wjRf7Jt(Hox8LFlrNs9}v#QsF#b2i1hD(D_?j#9p{({5o#NYi=2K#sbwPhdGD$|&1oz< zU{)VP|3~3BiN{5P(8?OW)o$+I+S!>|ibNUIl0$DyQd*u=Yrx4fUk@MeOI-6eCz|)E zp2Y357{dBVURQV$3wxil#s#jy`ZcqBr{H+KM z{L^G(lyXWkEZ$NI%%AlBcAia;#*&E)5zF*KvegJnQ^Ms;haUcSY^{sSKr#l&kqdO zQX+0ZAyv24vz6yz15YY?gal0vkeso%$*iHl6>GgcG1htKU6kn8?-03?aaisZBA@XY}-yIwl#4wv7Jn8+Y{UN_WXCBt^M%q)?4*{J5}d& zDyL8P-SLF8z|0r8{9G?`NOnW#%v zX8X4>O(%t(`1&ma%V~_>{Khm^d45`@7~#*`;u5@PvkTd0e>2-|%-29K90IMW82K)P zT)fcS4m?umUaq|;f<*g#bXW+&*yht;E5|**R1MC4%vq_ha_SJsPFS1v&e_?^PjzN@DY+cRc=a zkxjcZ)7uh=oNO>hXAplt$Q?oqEv`SZhSVd>$^Zk*V(UCMdlSRV=;rXHflO`}egv(``Mu(&sf_?j}wws-O=cQuj3{ z)}r_D-8Giey-)SEi1;&;M}lzG-n|JCGu@RLVfTUI;CHX^v#!|N^G7EfS6EZ26k4>F z(-->;-S?LFhn|KFkNH0l)xL%6$$jk{@P%%do12wW&^bE0+B{)}b4p!jT(;fbyh{_B zp%y1=v_7}EXQ;#>_V*;Q%xxY_ejc_Mh=MG}h@T#>m}jSl4!gm%g>o4^3B@2$1o-=v z2<9&=UL%L&ges%2kFv(&{azXkW8rE_zj)2MVg3!wC+JnD29Oj}LIUWmA>P2{ctDm; ziwQ@qI)s1@)GSHa*cz3O-39@sm8ixJquSXc3Fr7D4#eqc=Fj?L51RwcHbJ|4DA~HL zn7hSGMv>j{tFwI~tOsMES@pf{^wmb&L;-j#JW~pmw{jZIMxUI=vcN5=+v>+@qjk@V z)uvFWSPyU|f_=FT;1Rhq|Scy<*~Jd;XsyS3waKH~M4 z@J#s2`s#&GUBcbXIV@rH`F2Oa^d9d}{a9JsQoziSl&wKI3~+gSwYyYWykw$}Mg#h+ zpojiN?3$086BTpW;fWL3BTk1Dx6^G+ndL62oif|6`5P@HjsxATtY?^AR<>5vp#}_R z#tY*uTa^q|ySJA=wl5tF-B8xLJ%aqI#)@m|V3Nr~eX*uYM*?4usepDT7gSB|Vq z{G^K&F(IEd5-9YKnY$BHA@41>Ke{7bcRIh^bM^BL@S#9b05M zPz0e3WlokwYu-pII_FcPL-Ngf#0^B|WP(<{jqoal+ z31l`GnXDG5FfcGBoD#sN1MMBd6>W6^nacD1lK$F8xA*gnt2WNZ^!mctR|A zKhB_#*rc2**1QX6UMj#_Nf!l&(X9bm45?{o);9E2RR;j3ft*2%9KXbf++x+LtnJvi zeAOWJC^a4@^PPios~JK0qS)K0E!p6W7K#Q~@ zd!{1z0RNodM7TW5SsAg>IpXiW7nah@m6AJjO9IHCV7223BNsW`95+y;Sa{r@-!Q(Io|AY5BA1MGZaZVu5CK857#>JHmj3EL<9~^dTY+&-9l$_i( zEc|^qFz$bELSgKf%%di?0`(AH>1%=3VUB zi-!&(6rmC42uzQ;F;W$9$j$9?Yiq>8hfnw$U$rhQF?kWu_GXqsPWGfPSC*aw`#h?D z#+>~r09TmA{w8@u8Z9oOpnwdAMPK;qm%qdA;PrX)7Ag_Z)X73Q4zD|7dU|@=gy|-r z7C0DB-&Jl)kd9rMLaGG+(PMd|Q2#acM2iDkwI!mdo?Ap{7GeaP2E-WmhQ0plmTYbw zj0XDO-&8;3)d)=*C*09-?^4VYyh5DD9U*fp9p~yOtE>t~j(dY(JN+1EHg;?9I^|8> zsa@+$CBSAxUQo)cJhT@G7eCsdzJ##F-@YtctheXT6$#xD;YVsFSWs_H#GEnX;@c`5 zUn9j7du0*qIuJfx>9q^AEm|SXPj|R-Kt))E|GXD*TvBe}$m~d<#@&E*_U#cJ7(lgr z@bxy4AoK95qbe;O+E&bGTmE@E7xbeN+})gdij1c@ZM4nQxDm$69e;xaOhLvn3Iv3% z)qb`VQi}br9So=Ss(JdsC~w^(;jfNK5L~o?Jf?mz%^50gCxDIEyCMM≶Y5C#mOk z&IW80tQIQ_=1UcIJob};nb(BN?#~=R8-{{`G2nICIRxmo+U+56+?)tZAc|P2-=Xhs zuN|aYL)Wu4Rd5X@PprfugTza4qx)+SKyt_}sjU=)?@3pRA=L>6ULR_CzK0tq;QOAV zTf;iBb|wmUz~NFg+IYK@vKAxfdj;pK%CwwBEN3S7*j5s~7a(-GWl||c^OS%F=EP>Evms+?^|$yJ6t>A^gen`GeW9IWJB}~6)!Zc8Vz@X<0E33Pk?K^P0Re?cHaho@EAJ{WU~V7%k8|) zxgc)$TCS-of9t}U>W$rKpvYPwSThW2sLw^taGLC@QM3-IeImM@HFa#Sl@Nc+wdl0p^;4enYOSAEOP z>eODLe=M;}s@(-g$LuWtTdsA3JGBagfrF!99gZ3t!WPNn_*H;fq8v((l$>NiJ!N92 z2eWWL(V~!-#P|1b+Z{>3{de7yjfdKp9V)fY7lZJP@J34ey`@>&bU>ziR`C07Xs5cc zrYVJdC6JCeFtEXzy{fvO5K~;E6r(^IR35C+g-~Zww?eb)RDs?E2|LqaxFL$qoWbaR zesT0jnC=J(ucE9`gE3CRCL11?CVcOQ-@!WqOgd$p)ZqR=T~=JUkTdF7Rah z8Qymig6CHwX2cvt_<81T?V*NdNG6FYd&M*#TphW&8@VDjfdvplS_PL*E4q$MHvW1) zPpFYB21G=Jl7^O8Kp-2z8k1?IrbSk@+d*wv0p;bp!gC5ZYpKeRE^jZ2kfvm zFwrYfYV>(^t71PJ_jgaKihr+0Q%^fz@g=N^DySd@_F5ZTFZX=(;(ptSPK!bfaY6Wn zG`N(LDS~CwKSipjqAHbWZEHalXHoUL5CqLNac_+&O!q0gVGfx8&$9d`c@;mlZ}@nz z0ZhAt{Q~fxpKrJFfcB`aJU-*Za=yiZ2e*uhj<{P|NYEP@5{6U&Pwo3x2(O1<(TKgj zk}N9R2!9WZA|zqX|6;_Mq2^;%UDy>3X|qDZ#up2iu@>f581C{$+a?b;4NLg**6!*~Osg(=PqN19Zea7(4&VJ>dC(7;(D#*iWq(hHv zD)1`!%E=woVbfY@LV09rhm+LOj2q3Dj-0)>%S1hIX|I;7q-OVRxD+$s-$e+4Li%KW zf3g608Lrmsx={!T9a+g;DU0Z(6mTV~CU$DRGC*^`if3dm{zLrrj47|9rOfkdn= zhfSkgSR0UmqI(rm`lVnooeBE$XeDy^Z%PTMiW&flj<0{H=Xn2Oi(bmg{RSqx=>T;> zZYkr$8MhHElcI1u4nBBam?_rd00sUeiH0gKd~f@(Usyj;Ac}KYx=Nf zny7ZvOG2ek)|eL9xLL-RjG5mCQOm-SndOM*BkTiRL&|5s_xkO8;+x$R;?25rgRfA3 zNk58hlA!CfhHmfXPA6--2|6{Ouh526#GNZcDQNo~ho+3H9Ezp|SBpYE8#pQfa>PJb zE$FB}=gWgye50K}dlOgO0wgGj=M2lLr~S0i(2zNFOiVE?NiLs9z;c51Kb*vN1@ZB{ zCk`j4VRtf63IM!y%HaTP%Ai(5p^O{gE84D00)~&0S%K^ndR=MY-q!cNh5#~20s;c8 zxCp+!z5r7ixbUc`slU7K1 zpBf3gedgLeb*x>f#+pHrX~&a+qLDy4lkm5E(f?qSrkdAu3$U_&vHP{~^3!-|j_Dtr zwKx6yIFuV|BP8Uve^6QENr?Z2!^r#ozh4;20$W|qwVV@)0?cOBf0Urt@Y#w;Uya;} ziK&m~2_HKF#vB-tU3rI?|NK{bs2d2nf9+d6b~aScFZ^ygRatprIXJe7WH)g2I-YS4 zD(!PFva+-snFPi=11zeo?=3tn0Ok!#G_ZX9jkarwQ&!oy_~_Wd)%!HPr5c|Z`KElc zlKT^pI~HP1$6wZEQM&8d0?S1LUwumck=*e7{tHcpw`8LMg@E@B-I}y~Z-ty0+W#tH zwU_t5AOg2_vS{426j}1UcNcTeomg}I--mc8eWd2}bl#om*=hai6{m4<)uDx?zFDkd zC#fw;T2D4yBjoEK2BX1KywVFxnBAxNV^_M7Si6T-^74OGC#C?#dT>sS`|*8Q-xEI- ze8sME=%2F0OkY7i=_jN&{xr`OFj*y0qQk0ap*0<$53b*V=N2!#T|oTaO~nzVBqJ?5 z|IYKG3j6Wn8rby+Yxk!G%Vm7dXkFy;2K#m2Q!AIq?bn0zWHLv#JpLBa;b@~cb;XQR zSLzd4LNo%(Pw+(i9lN5Z9M|hbWxREpxlGL;AtA98$dY8Q?A1Sfiuy_xVC4~EJ{9F} zcS{$y*5K$G;DJ%hax>R^UP4Q08S@Jdj>u0BI)fZY>Ib{+)70Gkms>w_zlo{wv-?*c z)`jxzx`Xm{9+2 zyrar-y=1m|&=)o(0oO98XR0*C_~v5CTCCtH@BWj)N$cflAJ*6Rz>@w5N6ud_XwcYf zc^zR0^E$db&2NR#Q%sY|V!<3<=nk7N$ZhTfY5yQh8)g>aaKI<*_iPM?A6Z+`K_y=I zPv(_@(3S8bPySwUEdQ_$B-?Lf%*a7nL0?Ou3d}krJo~Pzb#7vft~~lUFMDTnJl|>c zJ`X$wTbFJYp|tHm95)a*yWMz4TuHc%7^RHNt`>_=g6I%(cJ$NSCIr8|H=4t%<-cwX zQb1*X!QXp(gsI|U2>6jmC^N25LF!#&VXA5{1nah=TP%E?V|y-i8q?`l`#- zKpGoY2c0%^>b|edVCM8HmT)|YqMPLL3WILn(bvm_n*_}o+nKyqiTvhoN&E5Nx_{9J zZa!IFVor+(Cvcq<<>dvqZTY0OU$jNW5@q)DL~a@at?S0drVa+Vk{9i_rT|uO%ONm^ zjnU$q^G4lgjfi+wMaHfHGOY5+ znm9kAkL>e#>)pnfv6>9mdRa@;!spJTzmC0VkaMEO*Grb#8R|Ttv*}5VV=`!%<9h}> zi0(J>qOMdciRj8J5I*0H!Sqs_s>wV*{&AUeID;o1zq|Q|Lb*>2oE~Uk0XT%&q*AE1 z&5t7xu|s`;#BZ3cdA+xOieJXVgR6PN6AmEg1Gl(%H12|sC2{Jxp<8%hu+Td+r(AO& z`f~1AmF2q)@=UA#&AzhL@2yE z`@P%0^EjRvuQMTXNEKX(%{{n}X%Qsa;pA&cvxWOw%aqghUZ%rGx z)h8*x+_lzqX5dTuv#fYW7O96s|2HUX&@tA9%FoY$&)|{vus|X#4-A_P{q}>@Htmyp zt;!?9*U;4#xLzIe>*gS)_#W{AHlV+5yX!SzPb1V}y1kteI0OvO+aXwbS5$PGDe?O; zOJ3&V8smNH2qaX@KflOeV@+-a)|bT>qv7wDM4k#YsEA8FheypjB|N^*>G&BiGxcDC z1}3II%dj{)6*O;k6U1OVqLio>uxW*#@B~OKg*vR|+qwHj1>}Fv99Bj&92fft(^8i` zWHL?5nVrZSzF$sr{^TRI^YRa%LTfoB(vMeLxmhlAqR4b(RchQ5@4e%8<|g3w!Jg}~ z`J)QZ;UrQ|WR3bTp*F;0zFqwNBMT8vB9VB6#)hKyU%ddEqoL<=I+}RPIyT#ZGhiJc zp#H`t{b|0G57x#q$?iG8--#WA@sG#H3axv-&o-v(Jyx)?h0?3PwoY15TfciR##7Tg??GqLE)Mj! zXw4Qr`Tynwyu`?F_+f5UYz-gS@T_QSNO>$W>$QEwArTCd50%sy;vHJ$!_#D?OKA9P zkMRx1x_zwt?jJ=<6W(zRY*02v7gKD!R^?o2)3(%lfPX+RhyXGv! zXgTQK(%*PHg<^GdUDk&fb&oTb4^D>Ghk$2p6sS2lhfcKf-{D=}9Fp>@1gZpnFi8Bx z=o#sNPCvhI>yghMCJ0ONSGQd{pLhbFi$7gt1@g6FJ(KA|XiVQD$Luou34AE7{p>ym z^*dpIT1Yv}aC5k06-MBY^jpFXwW!*|u7~HYqe!4< zm7G}yF>IKf$(7qJOjL?+>Db^#m{gXH33gVH4yf6@hVd`Ka!eG4H zjg%XA7c>J{nK;^cpO#_ytWe+wSB{BozK75HC{ zNC4T<0AQAU+E3L7q{p--CMJOO9e@SLk%m`P&;lD?Aaw==V7u4uX-r1q?G`dZyY3zf zmZ7}O{!5>?=*`^<;swUNgsHt(R3v4}*;84uSV~+@Umv4Bp%!cr#AO(-!IWS=bTiRN zg{wb#K6SikoO05}2M}2{=)Kc&mhf>%DZM_D{kk>(=pRlTL^O{%P)37;hs8Upwls&@ zw4|jwRsVQh4|Bh1AA5dK6B#N|>vvqE_!M~_2IKYHBF(8}LFU_&#{77q^}8s8lxKQX z^8r{%lcs)+aFuK^U)4Vo-7YSpVPVF|7;3Ghu@p4n1sJ3ZYjPBbiwEcXx*djgr5x7V_S)Z5mV5 zTW^U6@Y8Zde%y3AEpdRNK6Z%6FRQqiJTNGT=|A?WdWYSAfEurdv#(TC;dOP)z|R0A zvC+}d<5E+HfNYyv8v_t`2yu$g>9!>WfI+=DSB&lF*VUo6Z(KONsFh4(#H^G&MD8HR}o|d;o3Nx36Ef(GUMa@ROsT z*_ei~ZO+v9dvDx$2ZS4T&B@!3`@g=KQMALIOs3&{?6nCq&ps+G*8OI?uza|brf80| z!W;g+zh`n;0<^%?9@ZIMlmjR6Qt-b|y=x8ATaHPWnRB`(54vvcRQz*d4Q^5Wj?1K` zqA$;DbrCmp1H&LQndfT9CS^@ZNY$6_Z0~$*FI%sVQ9Z3M`}WvLHgi5)vqeC$bT!)Y%|GdXXoj z>n(B{M6Kz8Hr?@>D{>=r7BKQS(t%?A2f%qJ_!m9Vs8<;e$9=8Ps13{$2}8xi90aa_ ze*#p%NCy~Ely!9{Y7F{@hlh!om}>i2b^m8(eIrP5%rc6s*Su9KQ8JCC! zD=y$&)M&B)3b@yz@Hk@Zy5Ca(XRlhd-o)RYppo(Merxtyz_-E($Zm3HlT|#&KR%8~ z{RIQh48Sip2Ai_7&+hSLg?}~Up4w6x=(`dY0g{yIzgXyEk1dR=mDXd3zi;YS+n2UIjQlvo3UgZN^$XGt-W%NpM=Y-mEmj9hzNrnJ}fIZE8vLI zy^C!b1?!?xgQhoDC-%eC@F@yy14BRNXuhOpbe^s#;fj9t)TWVbT?CZWMy;RW!_u5O zj7m2gKqn{}c8sYtJNQ*pN#8seD=R3*_7#X))u1euK=l-Vx%9*sW}Pnu+7So+{ZokZ zLfUikJ6HCSRc4OVe%->6Q`4s?+~x`71AjH^%m-bS^{s`1U-? zLWUeJmm_H;7Q^7SeU0e^F7U`~y&0v^1RNc?eji-d*Vj=vETQuJ&%q;!6uE!WRh}e< zkSlD9TS`GWh%67uzkkCYU&kYdWnLxtliVaVS+b~m0iCp;!GvYBQ(=9vTW zhmw-SEqe`$_Fmz2{~mZk-n1St!&=Hes_7F=4Z=Dg8%GPx3{u-#mOwJSz2&(^D4y8` z3Q@rdp5ohdZjHTP)&N8{t}Mk8mZAzB8uALl=?uiLUP<>Tg35xV-kUx&7ZR(Wqm=o~ z&G2|^yj!WQl%~7;MF&SXqRjzOye6*A;woNJ}dc;eMc|0GjJ=5qN~F4NoYr_prmlJT19ytSX;#Rl@KYT;^8+m6Zm$-e9Lg6HJqM5Dp{pW~V`SsFm8%bgiZ zvzQi$DvE$j)J5r}Nu;Ao=N6jNN`GN#JCI)7Pf^&fHRNfFa!jok=qBt=``RA{*bfAp zcpLY5D5Iw?;QDloTLJ7pA_-kFd z=;$0M=y|smv?1%uf+Sj?6E?A(3Tf|*QV^{39N*?XF@$hc7mJ`|2nu$b!lS^kh|nsF0)$dqcwhJrl*z&wI&Y3HY=hYp{X#mOt$> z>C>1^VAq;#`nK(X7UW?7y^eIT*5Sco*_Z*;jI#IYJxi-AhvsyK9#liZ^ioWC69P>s z>{UQ0I2IKTZ>HlKV=z|2y2Zrj&c3W_)~(D5+GIneI$>F*TymfJ5Hhmw#tG2{6x@9& zs*5Jo9t&4h>lJ3TrlHOM$_u$mWr>pt5AtN;2xzTE5xMFbE}jU@%gW23j5ug5y$c61 zafF1l*zuOs4UynTXy+qp`{EOrV^*~?$XEhE!rqsZUyQERl{B=QebL3?KvsE2 ztxn>D-hC!Yf$IVWMMxNH*_xfcbq}@ck7v81>d6&>Aqhr)45NtvOb0ef0n0ZwvI z((@7C2B&>mI=r~j!H3x&R$ExW5G>|QGeKpj{Mbudy5WKJMKnEzS1#`%N82{Pum&`> zuP-K9OrlGdI=_ZH;>kb8tDdwIgurBekvs0a0VuL5tIKp&{P{6YLNLBEvyu$bdVYF* zMF=eR&JQT4|6QrzrVw71w=bs|fCV4{Ml4-cgI;iJcJ0hpNF+jU)XBg3+-^igasaQJ zSQ2{-sJQ$Q?gt^k%&-y0)iN|?Wg?$A>X1o}x(;~#nfV0l(*YZ+FaYF&>Wy{-- zh709P=!g>`g|z4>1fFGm4H3~t|J{B(RNQ);N*!U7#zl<*1kiEu zVIF1yM;{E;iHM*j_otRPISEeSc?5I}1jYgiP{1fk&c%iErBZDSup9f$E?UItM$fCL z&iuqvS0+d%3qeXM`u{9q1&@H4gghrY#NXTYomDK39IU-X?lf@p%`>_Rb=gM~>j@9;;SUCUe zY%5+ui(548r9j!;o|UzrDa3GQbRH99?pN&$-|~2TvKdL9kSFX79F>z6j9QuESaK4U zx)B1BV2MhB+OSG0h9cUJA$cR>4hj5Z?Z>#L+VC1^9?T%v6-Akq0Pl#?`QV2LfjeU` z|FgoXx&-RZ;P%>tw=C}r*%{Im6?|nlbr)x(!k|Z&sfP{Df!_A4L!a5C-S+vQk;{qkG3@lHk%MBYzU)vsAN}GQ3d9D`(c~?} z*%b}6d**oD@^m4uH|C7uanp_@g+>>rFg|bpT0ckw!HFvMIy3zJzxckMbM*H0jZ99O z0yb$Nv{2U8j+`(RDVYON0Cb*1yLl}wX;)YF#+s&pI`zD`a<)`4=`gX2ZHp&8K|Gd= zI4$@CCHRQ|cbdXNMDm0pJ~3OucMuWZ7HD&jRIo<=S{gTvj8E`gQ=H%H2DFxJ4yZBu^~xKSM0BV>LqF?ZBa!x`~ZrRXV^sJAr!c4ZJJtI*xiTB6TN>)CgPKV%k+ znnp)xMB#oijKt4GKKf!-z}-NRTex&;^7rr0cQv4v3%I4_$kbF+f(HzRicSD`UyB0? zVE@gQ{&dy?+%dq*e`0ygY`M3$H^6oG^!yy3m>8s1UIe&-oB0t&(hqy;#>E4!0LgU zc@7v5$mGcYBdPzhfWk?zuCi}!W=3^H%S1Y$(JyQ8@0&`3!}M|qODRmjwH!H{i2$Jw z{x@oE;GIC?2B`+ptS@2p=NM?L{JgLf{{kU1Zp93j8Kl$t*5{Q^AUS&uHOOLM{zf$! z|L=$_o&5GZIDC2z`HuGA8}IU6%@L+0ujmJ*bobWpf9-gIthB4zPjv1|TLgwpZ-iSl zXT$U{rvROCBqzHct2EjJX21aC4`4SBVdq^Rl9hkr`gn-3boIiKDQ^(7`nSw*f@kVx zRlYULzGa8f_%wE_?!uqp6n!ko`+*`qXws;sX->5eKN~9jq$1h-c8>lehO;Us_u_m1 z>M4jC>vNoCpPcX0o_166N6(_wgG$YF`IJUeyL1KhS7<**pkJmiVbqgfKV9f0e@)Z= zbvURxY;9bY(81i|sCwy)%QWzJ6Wi7Ko%uK}8Egn>@?tO@cL);)Ur&hzn^}Kq9nYo6 zMV32H$zp-T;Lp;MXNURpq_78JI65#>--(lSUB0Q~_qDRujWII; z`C?7TEUPrX{jK5j8}jORDoBW5HKfR-zkwho>&rF9tduV#0@XGy&_C2y5X(QhZh?hj z%i^>WXTJIV$g}PdkXV{UY&{HwS^tcc;cb%w1=nRL*`gm|a#V z3h{$6bow^o^_jJxF}pK9`*LgIh)@WdRqO4H51Y-70Lp8NPpreCc2QeKb%4bw8ZCqU z=H{N{7|mqh*UXO^GKb4gT!%M%8lkrBj+QCyXqS@C@xmN~r_*_JU<; zQo@b7O`q4*j}NyI@v}5Q*7txSVznHCqss8Zr0)pBWS~&BfC+rY=nj7Kd%1x7@QlY7 z`-&%;89Fw*jVH0B5qkDrB$t}*{H&<1BYKnT4-{63;70JSG%;+9z=g+mLy&q`)L0O;tJ#2?$$kww) z;W(rB3>Ag*U`m2+p}MSrC?w*HJH4C1lo)Ak2nYEnn@jYvFd{*bfhM=Dz8V~~o&*4% zEB$8AZI2uA^GDL{8qFL|`VRnej*`M04<)ei9V+!-gWI1K6)`>%UWZ%zV!3Q-5fQM< zu2*`16^%tCz#i^~**O46SBHnkcY68b*WC^$#&ZR_#}4D~Ol7IfEv_l=xeCXhItTm$@%$^w2tW+KcFQ(I~jA!*uwL<&X7tVcGIl|Z^t}7 zdmAFFSReLL5bZyVn4&h*{rGus#Nl2BHF>ZmrVNuTXb|(~TTd5>leEHT8Sl#rov7A= zij7yQ#6@?IMSPIPt$o52%Kf$<&q`t+&rq zMqXp@O**Pflg0^%F;M-Cr`9!eNckj6+(;ibz%ydg`+j>O>S%IgyLk@U&orc(OudFv zzz97dp$Q37NhJi2BnhBTTeHuVt24YjoR7_yDND)86@Nzhz`()^1H-Rq${Fl#EaC+y zo!6M*W{Z}&_8w1U%5{k94- zpLNj_wfZ+Jy5kO*$e)Ee29<7h9KlVFv{NedPkFYgvmCTVmoYxZ$T5inI(biC>R_(j zLwg98o^MwKiK{$cK_>8C;#7(d=1kvv{N;bgr^UteHnZ0+Z zt|au>;yu|95_&_~865M>n13-m*|sOk%1IR1zhc=f`)Z1V75qti9e4Gm_$J{TT4~E8ok~>M5n435Ih2d$uF9I|9YDcMzw& zKFn{zMICC%NV-8hF&f~O5yuExL~2X=nH}#5Nnf2S89Nvc?$P%53}>Wf!eiKj>-qg- zfbwJWSaP{LcWiXE!F=aVJ@TiIkCv!atH%$4)bR^veD1X2K06fEN`fE(t-jj%z(+-R z3Ql|0um;u6s|Cz;uS$mZMN^{=-^QnlwB9+c!ObAgz{~+;B~C_VA;J0s6=nj%OBArd zdM~cH3*o+l#v3s3FC)>#be6w3>tll~V*92wg^))h%%$AF04WrBJocz?GzzVCe&bBo_*1woFcrv7ZnMm?TJ+jVK7d;Gn`?ACjU%9x)c z=y~pRw_3{VT>IR;x=;km>vFs>=_xcaSUb|ptZ=dk!R_NQ3zyK+bs1uL_he0w2x@v*eQO)(mPOnF$ zLy8qBg+{eXo{V0*IaEzPcwe4=h_Hx$NDcEhm`W+OFxDp9WihqW!R3ua!2q{~-|m^} z_ID9b1t)EqRiLCiff;v3N{KmlnJaPAmja?wdu+czwdtMi|+#o@R+i< z)@NdmT9;agIOXNG<1YtsASzB>oplx;9+9pPLQi%;b7nFSsw~%;zyUTx&_9!tF`J!U z1xoL8sR~k}-P_J-OPPuU`lL>xZu#Ex#yb4s(&qY}Vm#lt8VsIlC~>=Ad9&v)nOj`2 z)9=k{n|SUbNsZ^bq!o?rERcVy`R%IMeKE z4h2EUbrIGZP+{9GRUW4dw!@5`R?A3oEX+nK*E116$Wrwj%VZ04!^Lvtew5j9^y(%R zX2}djiHz_Fuv+$7sSTL+q;?3ja|ivVYRUL3T5eVlS*R4EnwM}#5?SIcwco{d-7v9# z7u`KbC;4#EVuf&~(HP8!;H5k?6hR`8m=0>X%c6`jA};Kw;l)A zartqgB+Ic{giIc|sbCkqji2JybxR!l#Ic3Y4dYSn-C|o? zxRmU9+Gpk68Kk*;w;2X{NeYX>ID3a@)lLX8grp5Ne*}Awo^tw=xJOzhg|=sCD6B{(6%_@g z=VGIM1;_x>X*ZDqMXg`Ih|kW?<4MEo&87_5Gr4?TSmWd4fgXKG1l+qnLuyZtKW50u zE@N{h&(u>L_+$c{1XbH)Ju`Ac4IcKoXoovZYX7Sjpd~&sTHC|&{yD8{N~Mqfn$pVDr(fI5Hle`&4@VtW zL3fUvnVJ7flon&kT+ru`f0L7 z8f{K&1(#57$xzsv-C<;uS2bSc9U?dfq1e7z1SHJpsNL0q*>wk#1#7l|ym)m(-^yI7 zrS98JZjDPNHhUh61bNinyGyplYkt+92+io6--;dOmT%;-2sbmEvc!*#lJw_O6}_?w zNT+XDO$IKs!-|zxYDPo0cZ=uhT|n!+!08};hMJ95cgR7O6>RomE9PQ;+-0SDSn3eUS@5X_{!5CWQSJ5q~AEu0oJSHVs_eNOBtEubpd z($b=F@7!s(#cyb2B$Mo?nZf1sZ+6AtY`J#t;9%$YI6OO>ASWm1Y^@oIhlgh}i%Z1a zol{Cm3i!3D)hZ;ty?Ij^^i2U5w22Q;i-YbpvINAjz#xof@}fCwLPkbJb93{;b9-y6 zfst}UyGFu=z=Pz!hRPq6UqwQ{FdFm*do{V7uVM@%HIPbCzp4Lgp!}HVr-?(FIsYRF z{x6#EO$17b|B3ZAfK=4K+9@(EsuAi3WM|LKNg%tWgC>xb2=)_D%;fu}|BzKMHJ?jo z`}$Vd)KHG~@>AwNB~hf*BU|?`o(18Lm^KWqudk8KiDosN0#^bwhw{aI8xirR_0n=Q z>jVAImzz7!J^D@`m$aW()wlY5c0$M%Uju`oYW|i4>Bvd~2k-Z5d%w&DNND7PzQDb; z`r?%+<(zdt6g%Bo?4HYng(oczih24O+j>8O1`yt-J1#pmD=3;)oj>Iy zuT3T1=Vo|4b$f0G5^IQn!xTA_utgFzW$!#;F)-~HnTBk=w(?9@TDWgd30!bGO@XUo zrZcd#htsW2%8YbaDQ_Ze%&dsB>{{bANb@qA()+GsYujL@Xs&$ucH99C16Rgiz#E@cNxd%5LuBqSc1 zCE(AI&sh5=m9QT>n=6!gsh6Y;DvqR98I}lbguYu2XM5{ zAG97MulRh+8RM{Jx>+%AvfGj?5RV>h8) zsw?9+;*ia2oD>|KxINQjN|egRt#R5WRC}O*oDy4sMdJ3k!%J44@K2}NLd@Sn6&S3< z5g}nCUfEHvY@p!>E{UWVb16zPiEM<0H*0JTTl~w8TST-Mww|etfCm>a&AWxvjzz8r z(*-c9OGDGAt8Jv~Vbe(lpX38J;cM4f!-B=XD)bSyMAoEvX`2wYjmdW~jU)|I(mNA^ zldj~=vE=z#cn?jM*3N{%Y()L}MsEDQc;TNu%zXJl4l|bauoWVYk4p|xNO42OLLkdY zM7^#eLXLA%4U2<>gm} zq76wkeb#mDU>+)7=xY7kBS^puQpRAET48Lh0(&a(8W3qJC}+B~4#HY~6eDL8YuAVv zrQw@!)(h{*S-Z!U5$5r$zII@SCn`;<9j;o{b)7lX?Pq>RCIR=OLI&bfR8X_=AIL4s zXp7Ybs_&WXd2${S=+g4v@Hi$utE5;lvdC^GD^17e*sk5?e>uSwDdxs5XK37E^=7aF zcWKH`;=H8I)488OKUYF__C&r|Bx8yG_8Jqx^G#&PKM9|6Dc0{WsbwDy}>RyUg@9OfMx^2j6imuImxseI6s7U{0^@SDmi`VVG zlz6JSiLk4=8fv8VEayHnbuAvq#FI?6 zDVxh@dbs9UaroK|Cn~qu)3obZb-B?ehUPDOlarmb$eu5zi*R7|`ec)uW15&!f3b8= zo4JlTmyze}Va11|q11LuYrGa{;T7X}ccd6|ktM4PN25jKjW_MroBDP)Bsyq#%(%onCAz+mJZ>5O?Fl{Yo}^mdI}aya|B zUxdvwWztur`}Qya1#gY}6O~b4zbBIJwN`5*8K<1%daQ$Rxq?7+DDRZYw|`83FH_(~ z`qnJXuan=XOK@CM?TO?1H zGFe80ty~hUIqu-ZM0}Kfdv=B1Mh$}`iP@Qn<>AG6vrlAhDiW!%lNqA)n`JW@`yj~A zyu1VCZfDJ@mzMDP%8c>KWdzEME6E;k63s+Fm(gZuX?V97*F{{d`>9 zVmtT#yMR}gOK{Mb)o}hW-u0Z6Cnef!R1KO4L&kg(QZJ(xYO6Tx;x|+sRW64o#MbcMKx68Zy%2othovY7A7=&4)p{`m-{SI+%!L zI6U$7(RWwIN&Pyo9=EZQkFcllnEjnrHI%_06X?Wmf*FuNQwT0BU+fW&)G?oRW%A8U<3 zS%VSroG(JBi0gajN82=evXS{tW?xUI19qh}33Q+WFsR1s59~96ab2~u2Vkp!jE`@v zYnp(7s|~}&b6TZ7ZCuA($7mE;`TZKBQ@Ro~F}(Xk4kMYHSHk8PYtzH!tAoeDMTUH( zcnFTNkb1ztZvc)L3NN|YV5=XtJ|R#~cTRlDfouLSFXL>Uw;$`WCbiZaqn~Is+ZF9s z+pR<0h-=JpprrEjm}3^-n>=0BlMm0}-$A zdWfi!9sXg7R5qoZ%r;r;5`jtGe?nQOo78L83Ehe5H0gPF4+I!foO&D;)lK7x01_Gq9;VUpjz4HAvZ76F`t$h9`NOIsiD1iWMtZzj5x zKgF5v9v2V0%~}1I-Df>}E78yl5E`X~bjp7>EMX({uJd%;myVw@kk&98hJJHP5D2NT zu|+n$^*|`2V_;Va@texGDDlkL1EjJg4Hfk64$=~n2*@YFEVkGRQ}+n>w$%R(01=(iP=`9h+^jJv|EaZD8) zzOaSM#sZ;x#;0>+EPQHIJcZTMqCCq==(M(QI*v`^VV+No(3T17_ToIPO6k%HY2|Sb zVC;rC5WF1F#nzgPVFI#R2!CLo3Pj-IMKA5C3g7Q&M9kk7kRb;j4tnvj%XYGa)?@3_ zZ#r{c<{)R5n;JZ*?IQ^L9`$v82|Z$Y)Lzgp-Z8}16>g9cwZ-E9k+31Z8vlZD`B)LS zGw(^bxh#?oq_VHNTJ8MLJ_ zRGRfvdjzY)_4jxO@j;<79$Wq`Rz;by<0Lq^H&q$J8o{5*rX*s+NsWz1T}{=Si6Lu< zr!1SdW8FC98@s9!Vd|O-ziEYf@;-BxQ}fMk&DM$k6Tw>CKH2_F&alWy2pRVOPXMT5 zy*XO5q|rJPY zjk_kn3!k#LdY^z04trdyGScxVsbF-QC?aKyZiP9wfNCySwW&@BQwbsgatQn)xw5hAOI>e!A)NoIbMG z-fOQtS{~ziJR)O{hVUTDW_mL}eRu)~vrj;`RIu|pIi2=;#9V1gZHrJWnIa)KUH69w zl&q@g@#fyf)#gE@pYIx)nnu^69(Q=@us3W@J!9|e`Yjg1;0eGkFya~&DiCLB_}{DM zF%kOfRD^`U=;`TIc(u=$8)Ft078G`MlTF4l|HcvvfAD;Piqx*|?gpl&Aw@-$&v&Q2 zfD?tqbPNf|E>uuJF{w)nN2mSBpWhu$QEzj#Q_uMTPZz06)%u_0<>gfhS#hEYe*M}y zJ+*Rrv$nQgSU~fNl8Qfjrvi+AGl}Xs;4vVn05s!WZUHLw>_BS7lcB!>{B0trcayEt z;E)4nJtD9VAhsz1%));GGQock8Wctt(LX1^BeEC#B0jb`J3G63&nlI&!^wQex3@Rr z?=&A5Jlwk)1OyrmL{I*b!5uMSF{x|5KpzK0Csiu7BnG1KVW)>`BZcz1*4GJxw*J~^ zF%djw3KC{+m&ozuwr5}g1OsLl#^VNcqxuEXuOF$C;>f;wUt}*(HGFPE#`fY4cYppI@7l9lz>v_%97utyj z>Z~<=XTZ~4bNW%nv(*IglDy*hf-%O;n$N1u>#+Lb=PaspN|2bkEax+LC!OZ-W(MM= z`1{XwVL>DUA34`py)Lt_2Fz)UI8j(|5cUoZfY-ej@TCBxZ9skj3K6jgs5%X(EhJ~w zY(l+zOE0gCmE0p$V2}8bn_XxwFmg^F!3!D4F>H1|do2X|awvfq_BtYf`4C z@zTay>k4BAucVzJfV)POw`LXo(a$feS@Xtd7hSyu5+qHFO06DK08ncTer)aR9`E&= zC3K`(1x-RfxW9FNdOeL_|Fu8kZ+gga{k4>mC{gjjanDDSE5(UP^2UbRw1(j6JP&x; z#xcgXbzaZT0MFCv^5dZF3iwV3x9-f>M!(>!|IW-`^DDyeDeBtv&2)c(<)79Wf0xEv z@c$u^M!q|C8P@P!3MJl1c(tU6F>U->UKl=`!Ad|kR#J9(z+cs{L}d&+D+@D86Vdpw z#J@{KR(~2&+gxoC(X;}d?QTs(ZXtrnhxBl{|7zuV5l)>oh$3AvIYx&D6_o2rv*3j$t{ zfjaU$g+fW`Y@WyL2GW(46)ax&dS$m2f&>s|$TG*5?)+9#6MlbZl#A@lUghvE zv4$|~mN&lPaO$ATgV}FcK-_Bx0(EMyOlDWx^k%U!Cv^4ptDb9ct3#9Ud59meewfJa z^qC9{t~6)+p?@j=TmtvAFJn6F?xw%nHE8`8{AN1=X|cUKGCp3nrxju6>D2UF!fqSV zPm1ju3yK&VNlaxZJJ{tdB2!z7XTr=o!oNS?S^FkayT(4BGrk37yAmu6Rabk&s2gM- zaNg-drgu7|LDazoi_bub2ka`-uh6pt=5t~MdthQ zS+(xJu8!vqyimZv06l|=q7!G<+DX!2uDJGS~3ikO7?stVS1KEJ|yK?JFKqOy|dA=R* zAqY4aXeLuON@D&RTkMZ;NMFm)+LU@N;zob@9z#_`S|0iqjZYcnSgdFp{6D~H)Zzx3 z9eh@rY`qX>7)irpxvGzDhG4=lG}|6A9yvVlotK+8tFCP?wCggK;rPCw-t`$G@w4;Y zJ-4g_QytlV1{*r#ZtMwp3bmXoU!!gYRn0NW14*L9CAGk4x4{O@GhDCJ3JV$@Qk~94 zG3gn#QI=za>wnDR;pTqJ_~rUb^y+FSsBP5=FHR+Az=~qbn>EbFn$2X7Fz3>O^D_~u z^AjoB@L6LHO6QVQSd<-zfmt!<9|rBYIzDR>r!wATA7Ec|mF7uag}+eE-PqexIRXK_ z8XyDK@mOQD_&^Qy7csCK2p0GJNFie0K+qp1D2Vu5>2DkfM@#vWW&p2hfjzUE`qgQx zDkFTA#qioy^i3z^lCZw_l^C8ULCe5Qb3Hil^|{$1FH1+3ziYp$G2i(!|4ODd^}IPK zrgZbp4#vD-9?92op72CmGIR%;c!$q4u7U~%@kut&Xrt4v&WO*`nPw{#T>JvAYG`kc zM{7uK%NE`;$;398Kjz5g+dWk2SZhIuC~Kc?J4VL6gXKD1!zLgrRMGkBEfqf<&gdZU zO>oR;A)ImgYc;S|yb!+lX#YFFB;3E32EIQY&s+?0OapChGlqBk!13t+-b=d(VwzYR#?*bi=vUgU_0K(~E~=ujm|4ix_pP1e%x( zyPgUZ3=rmS$RI4D?Z{8=$Zf}_vZLmrhnk^<{toe9BBcg5QuOg%oxI3w#Y5*X4?5g%qEf%-sqmfB5#v;ra2R*-sdQ->f1P*4KKMNJMp4H+H)9C zb+hB3AyeW*hrXRsx7!1OaQ0zKjzRwtX4~9%_SrDar=7;8a|sPz&(>*R^ab}v=b~t< z;A~j&iOA3sr?hTKzLOgyhfi1}b9Shh{bARS_D|-oo7XqanSXrEDC3=dx_@Pug#QSs z$wsYs=8rHPcEK)n{&`$Gre;YLtEkRzLRKbS@lagHf*FH9{I0VpBH#)lOFlQre28m$ zz1F7rwK8}6>AVi>I?Iou?nz$wb9_7ZnZ_q>l`r~oy=ya<)}s5#cWoS2AU3US62nB? zS9e+Dbr(9t#cMW5GJI|U?5)v6=cmzusbkg7eN2&GpO;m?0rs)AoMmk8cPhq=>sEv- zI1|U;v_ zda2uzV&XPl%^Y1bdF7M@53h5z#)~hc$<;knFmO04_LN!R_E$WH#<5KkUnS# zkWUc1vyApw*yN$htkyO(! zD}#_YY6)pG-e+tmR#olEkiK_Kz3YJ9VbB&TU)C2sUg+`xff0zU>q<>oG%&9$i#eTd9N6?DjlKNa-!MY4L*41g zXYzs|cD2>sC8mdWl*W$z#V#EqPsgwZFJ6LkY~<1X$6`Ct$Lc$DDIN1Wc_79_-s!>`jg zBFy%UyN7RIPciMh{w7QvWcJQ_(LTCPBGXg+(yzWHs~=O8*5nT3dxN=}yX!CNHBk5x zmGxcO=ugf-n#O+4(=A)|b;Z!vbUO?w1}LhPr>p5%ruV_PQFhs@<*mOj-dx!QbkJh& z;^`ePUv#5O%--p-Ak7?^rhPaH(<` zo%QiT4Jn{$=lO>m5ak2<=~x1L_f8zBlk)bk9b?dFvshcWpaKEPXll3JqrNr$p4RYb zXT)_2A%}vgD$+F2Ju`Kx8O0@2%6uyw%3qK7!`=A$e4mh>u5oe)pwPRs)#q_^fw7IP zx6_kIsh%qjgczzANaHcGOM4#bK6;|t`@tu;_-W?J_k`QcPg?wovEM8da5#C(IARrjY;Tb^E&sAVCklGpMj4V#W3=fnrC zmH$!MmldC7}6U8k|2x^xI*gKJEz&S8g()TjS=(Ab}Z)fP>YEd*HeR|41+ua+@1kcpraixd; z5`ri3tUo{3 z|Af(|h+mcjX28Uz~RmNh==~GZg8=nxWpe}JBzN!7#rUWc8#`A#Hx!Bk~ky&!0w+9 zLPnPCb9kOmr28U~2(hM4RodS5Fv%{>P)sdj{Ehu{C_KL z#w7pKxLOUO&2|3pFDOScDN z0M8yCpwFi|XZ)xN_!MlNCDoJFfm~c5I$*Hc;$&oEa@B{ayRo_Hr%*!1!?O~OXB-Lf zso2W)3ic1_8+ZyTnBDEXfpp7AgBGQKY17Z<;y;;115hqsFvtvNj+todIhwh)^+^3* zPnF>T>rb@WscW_mxdQwSA*dDISaS1fS99TEKG!~1(RM5!dpyMXzlNt&lr z(q&f72wxL8SB9r^geH5oI8ftoS+KL>{i+b<;mhxww!hH04`o_O7H4cnU>NJbJjhsL zXK&YJNR*9ZiV0be3CA3nEL8T6cc0Tg^e2;O3vcD7dg08fNGmsnl*gSZ=gYPu|z< zUR})syrY<{yliY3h={b5a>-FxQMpRgpwQgw_D#5`O^$nDsx0^yh_<58#Y&QlI5ju- zI<>dC3a2eI#T$OirzB$cC!1yrxC(k?1=~6@Q>gwv&Z!V{! zM3SNxBEdYRy?Hka7cfr-+l?ui86D&YGjajZJUS>8I(SKt?+aT8=z;k~43z`-wpWrQ zi#mb}5=14ZmsFU+AywQ(cLcjbx0(+j0EH-}9$|qNzM#m&z}bloZ!k4E-LL$%Pvl7TQ>-zH?Rc;Sc zHH_fh0H@;~mfdgGu%_4kE?%RX!^552UQJ5B9t1Iuu)umHd*cxQIq*o9Qf20-USCx-XLS#dlBAsLAaZ=dVf1{Az(r$%BNn+q>FSs$=+m|a7T z6z-?T%~&X<{uPg;)I1Fx6ZNB}%(6@f)Uew8O{-0fxzXhpK^dwTvTEsi91)`pPC`!MiYjI_F-F1fg=8k&Td4LO%LjTd>pEL~#~dqn%45or2l zRm$oOk)1X&dfln5!(zdq=D&roB~+`l+l5IWxICY{nmr#-24tzB?&z_aT>0>E&&Aum zPJLo!r8+sS*(SNftjxQeGZov!qs>E=+!P1M~(WVHIOZ0;WLk3fA8K zRDchQ*r&JKRU&b(1H;XN%%itP(5xtgMWDhV zzpaiN!KE`^K9KdkFZ`<{=Fn#k+pQ^1dWu%X+q21RAY_CgzCWIm5+zCs5s-Ib_!S38 zEF=O-8qz46{0HL0^8na~A7L=aFZZO4`n?bUSMfs%0U`iYOiawu($dz^aR)FrfUym% zDZW)z41nwnz)x&zZ4^--_8++A4X9A~k#_iBgvLZ-|2g6R?O*zk-6a3gYtf5?`hYV4+yXKl|GDeG zpgjIJ5w`z@e^V@-624ZgFRV_W^U>bGXR10PVj7y#a)d7*P4Y(g5eY86;529jphD@(h0Gc0bS zqDYGS!v0nbT5pAN0glUYjVp$ zikr_RJLRb5uKVgZ!H^rcNTQA@$aI{Z$5qzhE7~LO9jx%B%DI_U?0j$fGp9WM#&(O3 z%cJv;9X`rJIFZJhbNmi+AL9*l$Q4~Yf=tY!lgVFJx3lZ0(C0#Dx@dyDa_^QtfK%=G z%bM;KQsbZX$BR?sHlpWhD;3z2F|V-Hz&4 zLe7}W?%xHve<>z(!_4myyx&+NOi=l^gP=U@6Oxqdn_CZiq=zo8PGrM3P9F&slrzL$ zDs3LjmacicPBq!2t^H9!B>g=YHiqBO{1H^tI2 zUy9MNsfMD%`WSW2CS)((>x6|CNJVO%m#PR0`t%_EcOerimFe3u1}xMJ-Q@n;HgW5j zEY9oqg8N8{1+d(%B2g&=oW)O3#YLR`{d~BKu1{7L-<~E;uSp%BaZ~sgG4(D*3$Hw3Ha+8+qeEb&jIhC`;rtflz)J_H56E1a%2!jYp6}gib_1 zXg-ijKhf&j8s{^%ENUL{_68y+e@HS$eFJY|Aq6C1pe5q3Gu|pjwY<9!!2a>a_kn*@ zz6IWs>x%};j-&HudwxheTdZ^VAj z=D78>im_eeoSL&=fuU?KaqKT<$O zuXL4{g-3|?{Id3en0t=4vuX3~4NWmup9F0D;qSZHlGn-kk4Nr%V=zAzM?uh1<}WWH zm+j2hbBczk1z-v+0zVPHazv=ZkIc-I+kI1yFil4r71nO$w_#K79@Kxm#J;DI;Zaz; zTol155@ote3jVx}EJ-uy)Io?eJlGWNd3y|wvzW9+_A%-6(C8qbLlE%Y!9!FwHuj>Q z=Et!o9vy%}6k~k5B?^tO({mjnjZ`r`J=C79%q|V_=BRtsdJmE)b?6+Aq8Br%MXtYo zf9lV$E6;g{KF^k;P^}%{Zey|;^NDem1<7l>nU${0T*cE%SHUp*>?IvSv3tg~E1>gm z0*QvYzUy<|)^$RM|JJZ{*?oULMJa9Nqz;&89|JL;D2v}mhwX!M5!@3qX=Vi2rIt(e zB}!@JWMms#TmF*Dd+=z8ad82tI8)ZIisj2(6z``HAA2noDIh~QGou993l(bvqoeS+ zxEUnt66BFZ31o*%cnSaPk3ELn2C)|aWV8c#u))U9 zf1dK6*)#vKw;QvuPIP!Z4;@YXGaMJf!oz8fNmlZu_YotbqP`6G{v$zcs1MjO#@gT! z|C{@H;LjZq@3e^oZwEwu&%h8?fMt`?+Bqus_llIK6ljtyznobtQG&NKF27YIXW#X*cr! zMCxhE6n3-&)7%tb{FLw(xZEoNKPFq=9ofiVP$?~T2A^l;0g_2yO#0C|p^QKz%A+|+8pC~xfTCTzoA}c$H%V0KDJ9xFza#g#pu{r6F>D zeVBk$9x~>}U4ZTI zeMq$P79K3=QLa7xw{9%iCwu1BJ%n8KZ!V5F9-d`RdVj7GjMmqvO}P`6#S}Ta;5{^1 z+3xse4%o6kzvBuOEp;~?S=QW_$j+NDQ=jmqOg}u1E`hf$>jT*gI4izu@5{nVS*N$n zv~FX3opk?ICV_P$SZY&;IZiuH@W!ucy?qRkRsCa$Bx1vDwI?6P^w65l+UpQ%xHlh< zdwh((hHB84EN!)P7%50t zT*>fD#v**^TbqfU53cC%^MLcS`YuZTH~(tmUis65qJtT8i0DEif_!`HuzQn=?z>mW z8cHMPqdw25Zo=~3)BUuX*eZRQ_d8b?DTtPlMSuJ}*ogrnNYQqJP;yM>8~)(X(4nj= z_En-Y5=V6^pdQe{AzAm}CVr$DFX6lTZ+Moay8tWbJv=f8v6+(nAe=>cDs%3Rrz@=9QUWx_=!V$*RDHO58pH4+mI{f7r^a6AihQcz6c%P`!c&qL<+lYSToDGg|rtNeePLY@x7SPJ%e-hANm--BISRe65 zP{uR~!iDd+NGa9N$d*iGgzYPE0_2Z7U4fbfU=Ta56Q3+Iqn}#Vu4{O8k`BiPfsh4l z&(6vZ&!S=PliIOWbd5Xy6>suD4CCZ&qpDW{1vwnJP>&%hZ#xd5{^7E<(Vg{RZM(Wp zsDR>52J7`PsqKqAg92v))SeCDcqlD}|CA_lB-P;$EcqdD)LDOtE&?^VL#UqV+whdm zqXsqEGeJT`y=0VoH`-Z);!{SkHCw0N(Tbwly4+t&h+XyEw7TU9Si^3@LJp&}Zoiyt zsx;fwM!dy+?&>3Hq(gOJ!3qlzcU2QHHQxcvaTjfB@gc0lcrp2+p118gR^8D|;Gm){ zu-S;h_$@&6)|bV@ZbQdf`%wNF$$J@XE$T=JpD-+xmZsj_hXSI}2CmAT&umXW=NwZo z9z;F)7VEQoca6TV(sWkW+J#tiYYtxb8Yy-4w>Vi_y6gvXrz zu$5dS&JzWW`)&?i6?XwF-(o%J55y6H>pdV#P#-=y1{*Pjn)iEAI0DoDRvb6BK3q&N ze6D&81PkV~UScB*yWy8h(N5XauQkXTqcB3Tcd(IWI?(JsSurs_3i;PZaTi{dF2eAQ zPXvsQ*0dc@zsdU_RD<05-Bx7(o}Ne_u?JF`Y-Gr(=9zq#DbSJ-xm|0YAhKa9Ej_qD zCsvzqf@ndM?Dc_o&P%6&W=A=hEHPzSfEerB>JYoQdzdprWx^nB`RW%ze!=mCbvEd0 ztfF~@kmcVo{G_i?6*icCr1(Ci=1q z8C#bkTv}h<5NFHpN!v5#o?nzA6PLn)^BmPbfbY-bZltS}#RBjPf%h9vt%iLbvbeo$ zB71ybC*9KU#d2r;a`?%%jkVONBleq!i1DA15$V*lG-yS|Y0nJF!jCd^nRw=1s(QTZ4hKuD&H5?5Z+Ea4G0Ss?SZNLhyh=%j0FdXHtJ%cl%Gwy~R9C7r46RW73upv-Bsz3BgYmgAK z-%+-GcxdBmk0szRv}I(zH4+jUpH76~N-e{n4inXUVf~@nZ_YG5AfiOrE>{3eEV87G zd}n7m*;NwHs8SNt-=o3N%8p`F)k@(g1Vzk`Hh^)9-XV+8v#_AWF>_3-qCJ8n=YoL# zo8rx26J1*cNY8A*XZf~n!WuL;qlTqwk3_)Rfxcg-t0-E|0WkI^E5gdEnbClv$zEOz8YI~~P+Hr$}r&DF;kr5H7H8nLPfMZMK zwNA3o{a4QT**om=$mnPg5Feue5kSM*laZ3@4S+)0pMgf7D{Mns5r7P7&0<4wShPh@XHn?n7d2LY1R{yUweG-crx8jE3ha-R#F?EgEX zWpIO75K8}mBrG(PO3M7M4gwyUD{Cya4;WT){!>Rb@a_YBk&$o(1qA|7pc3&!67j?l zlq4ii11LfQP=1MtXhudxiIQ2sZO+clz=|boZ_hkq(LfwQ@o~}gq2t7%V|85}ZPF7Q z4hk?&P*_|qHU!n#3x%qIc~V$NuBELV z!D9_@o{;dLkp>vnzZ51bTgt59eIHkkxL}FxMp90 z^w99u%{(%ROlu+%nlT_;j*XNp3}E3)fIcnc&6x$SwbG~K+ z5l|e(R@Pt*SnU!>owf5x8!fj5hkIA*Eq=yCws&W_(}o=w6>|XrnJwkWvl^YlTF6B_ zTAE`v^D3cu_`186^;Y+vwtbWutEZ**leLrsvBF5;*vZN8hL0w;On@hL0TC==E&q-i2m1 zgMQ6IH7Z8Q46H8gM8G3b1@kW-CTf1hO#f|aG$BFAyF>;=aM=4QD<7w%Ctp!ArhaN*6(O-51BT>zeSEp?p9 zd|qx?JvM^0Ue2Dm3YI4(P|e!dUlqWfXB=gcmg5I*$lbG-3sL^pcGr>I}=wYu`*KuK}r{T$}TZS1``)d% zLxvl-F35Vp+0NduI8JG$k2O#i8>igdognwTm~p#3#x^^&uxD{PVv_jf1RYR`INf1Q zylSEN2|IjS<4JK`o{_Fi5dB=xp$Dg__o8Xqu&^1{4o^D?qT3?SDx|-}r9LsPGgWF} zTAsdtsw97jLT!{aK1E;f;l;}djj4TmMJwvS3*)3L(^p!cm%c8Gzs7D`^dRDTUC%hU zoPADReq%IYWe>o z!N~RoZ1A{Kos~oN-^%S{cv&wYzf_;`NOOA!mRME5o0Nx>OrXvso^;p^>istZ_VORdbey1VOUnW;`49Q*&O$-A=aZ zmLrzByqsXOWrf&T_};eeM)n)`zUyR^`|^6rd*TEyW{vPYxW^{!#vqVR$F=pE<31bI ztF2{wFm!!mTZ!LPce)h*ayd4~mi>?b!W!SNsHJ|SC8+CE%*B3Kk~cE;7E^D|j-;Qh z0&b^5Oi5_FCgH*)scfO`3`C*!?vrn(BSaabOZU$7Xbq7i`ctbp+*M2Xk|eCyzm0iu zp*){TSe-XYiShELagP`fWXveodu3ajohTZl&xoVOyHT>MweOQivsE?&cZ*`ST(4Ff zIL6+s^KEl*HuXQ?;eF>iN;r;~5V-IA3>?2eY9VCD$UvW7-mZ~D*^eyu!->3CgDlSk zTuhfDBI{+VzinkaPuiYg1o}Ketc^IR>IOuSL1As+x|}_78@_c7Qk-wh=SE@OU4w&k zm0CyGQoqqW*$@OL-XwaON)A@&@-&5}x}vXmwd;fWnLZgf*gVY08$S0%H067IQvM8b ziPTErEG!<*z_;EA$NK}P^W_l4Yfl9(5HLc-5rcxj4Jjdc+8tTfJ8*KOeXmnp>`cEg ziX2U6mV_Kn@9o0E;Fu0%G8=QUV2M+;e3A`&gsv-M=wm=mLCz=$PEv=NQp9KJT*S~~ z0Rd57*)Tyo>BNN0D)#S;&I&4K$A5GFeEuBkUl%ti-s*(mH#@g`mdq0SYidKqA5P!q z;Sd7tsv|j2kz7nmrVRna_2nycI~ziGbZ(T|{I#ZdtS#{wN=pUd%?Mf`nS^cWNh0oy z$lZYA;PEgY{dqcEYS(Nhe7W;$cn~UP?%0ronf`M;H659f^(>vP_{TDZ zid0*KMW%?#0gu?z>lJcUAyqun;wGCG?<6x*ACG)Dug-(fpjR>zdIL3bc26*87GgN& za=p2o+g|~{Jz?{?mP?aoISiIHa>loO*cS<6OFPPtU5oP@yq?Wbx|Gt@{W(F0_Zz=uTeAQtimRhu}? z&N+N*Hs&4@x$PR;Z%O_klv({H5nM`#2MF8}MwJq=((*sLU`DWTBbfr;0t9)_^cVLy zU03B_g{n%Z6sUv2KbAXp(4`J-;u44VM2a)s&;xJMs|vxUw?i$Fd)zn%B5@1!`gZPp z45O`(HQrKU^Z9u-oJ)}!`Z!yhxOpYB%QYo9C^IOz7zi_kfl6?nK^gh+Rt(!Ske+kQ z6Eo?}#as;AUARhBdoh4dUbr#yCgX4`4#RNhFG*d_7~$!$%5z*jVu(Cp+W58L|6(Zw`6u z-+$V`W1QaYa|H&+%LsMd^1C-^^ZcijqN-Y1ydC=naVJt@n_tA1`?1Kxl1w_Z^aY4h&y;9`V zx${qCQOD4_Vx(lNkwX5*L^n1X*zrctKPm#7-h=d?IT;+U>qX_)Q*PV8Tt`HcHJNKq z&evhGWiDsh?7okRHNx^sfV{T5_bMN!7kR_uL~2Ibg*@x&uOl?wj4?WzAAw!(bRu64 zTa>Tbp*DyH>3OnDmphwcCOzWJD7PA%1sjpwVui%@mXdxoBD44bW7X|II~oW6fx39n zoK`z~6PaAy4{@^b`0`ZMF}|dC>0cd~4%Z#}y0!WU=YNB(rm&>%r}Oqz`U{4@dfdxU zjZRROp?`H>7smkV>+!6;v&jrt(Iw#GqJquqvHX7`S zRYK_h?CjoO&Me@t;?#G0(9Y{UXg1hmunsLM^0@g&4;3QrF+>QBujS~Eyof#=@<&B@ z#$<;WRomh59s!l;ho5+dbj>w1G~!|&$Vi@w04_ZLM2(@?;AeuB#1wJ4f%fKgB7HBj zjttsea_ka)Rw5*X1TkS|@7vD&5+$0GwRT*5F30aLZgpwzeH|sMaq@%D$_j_}Tpc{M zNI*zuv;~BSeZe@|LOd3H0(i+3tT`Zt%AY;0KY@@oz*zAk_D&x1-tZ0d_e0>wyy-`6 ziMo?XY>5Nr9$$ESKyDoJNl|ow@_MEC$`x!j9#`~@W?Bq2Tjdcr?EA0kqg8C2#(Dc8 zkJ&@kcp}(Ah;&2MUZ{kOcU)kGZ52iEZ%J{ zaGfP#5s@1US_$3pxDWrvP#n7m4=M^rI^gBFv7j+0{I}Bz1z7)nZnDUR!4>Yqj0hE% zk3)2=t*N1|a89H#G&EFGQv(6X1_toW%?-0PGP3-miJ@Tt08)Vp0x3?4#b~=8&H?f9 zJe_TA{KqS6YXrAP#(ZeoK+&rvmvbHL#?a8>mom*pdJrNmu9iqmp+(7BI)Qb=q-feZ z`N?>)!_`O3^4zvS2oDdBnJQgE5Zk>G?BGu%KT!aLE35^SBvMPxcB$BisAQsJBQsLH z;=%V;XYj3WYz%2^WXHq9vwgZT2hs*wwCW>5i+^5RT=)hAd_o}L8SKnLk0chwy@7#t zgQa4~|Mbny*48&B1`!V*9~m1vY~AO*y*vYO1rY<2N0vp2F&NIFuTtW>f=+;cJ|K7F z=?MY?ur5P^IPEqDGP1Ikj*ia7)m0DR6&P-zE-2cEhWeIu{f_le{Izg%ISK^$k@zMn KQYob8|DOOS1 + + + + + + + + + diff --git a/common/tier4_automatic_goal_rviz_plugin/package.xml b/common/tier4_automatic_goal_rviz_plugin/package.xml new file mode 100644 index 0000000000000..11d263e09c789 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/package.xml @@ -0,0 +1,35 @@ + + + + tier4_automatic_goal_rviz_plugin + 0.0.0 + The autoware automatic goal rviz plugin package + Shumpei Wakabayashi + Dawid MoszyÅ„ski + Apache License 2.0 + Dawid MoszyÅ„ski + + ament_cmake_auto + autoware_cmake + autoware_adapi_v1_msgs + geometry_msgs + libqt5-core + libqt5-gui + libqt5-widgets + qtbase5-dev + rclcpp + rviz_common + rviz_default_plugins + tf2 + tf2_geometry_msgs + visualization_msgs + yaml-cpp + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + + diff --git a/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml b/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml new file mode 100644 index 0000000000000..e7d5224550868 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml @@ -0,0 +1,12 @@ + + + AutowareAutomaticGoalPanel + + + AutowareAutomaticGoalTool + + diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp new file mode 100644 index 0000000000000..43fc0edcccf84 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp @@ -0,0 +1,121 @@ +// 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. +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "automatic_goal_append_tool.hpp" + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif +#include + +#include + +namespace rviz_plugins +{ +AutowareAutomaticGoalTool::AutowareAutomaticGoalTool() +{ + shortcut_key_ = 'c'; + + pose_topic_property_ = new rviz_common::properties::StringProperty( + "Pose Topic", "~/automatic_goal/goal", "The topic on which to publish automatic_goal.", + getPropertyContainer(), SLOT(updateTopic()), this); + std_dev_x_ = new rviz_common::properties::FloatProperty( + "X std deviation", 0.5, "X standard deviation for checkpoint pose [m]", getPropertyContainer()); + std_dev_y_ = new rviz_common::properties::FloatProperty( + "Y std deviation", 0.5, "Y standard deviation for checkpoint pose [m]", getPropertyContainer()); + std_dev_theta_ = new rviz_common::properties::FloatProperty( + "Theta std deviation", M_PI / 12.0, "Theta standard deviation for checkpoint pose [rad]", + getPropertyContainer()); + position_z_ = new rviz_common::properties::FloatProperty( + "Z position", 0.0, "Z position for checkpoint pose [m]", getPropertyContainer()); + std_dev_x_->setMin(0); + std_dev_y_->setMin(0); + std_dev_theta_->setMin(0); + position_z_->setMin(0); +} + +void AutowareAutomaticGoalTool::onInitialize() +{ + PoseTool::onInitialize(); + setName("2D AppendGoal"); + updateTopic(); +} + +void AutowareAutomaticGoalTool::updateTopic() +{ + rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); + pose_pub_ = raw_node->create_publisher( + pose_topic_property_->getStdString(), 1); + clock_ = raw_node->get_clock(); +} + +void AutowareAutomaticGoalTool::onPoseSet(double x, double y, double theta) +{ + // pose + std::string fixed_frame = context_->getFixedFrame().toStdString(); + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = fixed_frame; + pose.header.stamp = clock_->now(); + pose.pose.position.x = x; + pose.pose.position.y = y; + pose.pose.position.z = position_z_->getFloat(); + + tf2::Quaternion quat; + quat.setRPY(0.0, 0.0, theta); + pose.pose.orientation = tf2::toMsg(quat); + RCLCPP_INFO( + rclcpp::get_logger("AutowareAutomaticGoalTool"), "Setting pose: %.3f %.3f %.3f %.3f [frame=%s]", + x, y, position_z_->getFloat(), theta, fixed_frame.c_str()); + pose_pub_->publish(pose); +} + +} // end namespace rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalTool, rviz_common::Tool) diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp new file mode 100644 index 0000000000000..6fc98cee9afa1 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp @@ -0,0 +1,91 @@ +// 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. +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef AUTOMATIC_GOAL_APPEND_TOOL_HPP_ +#define AUTOMATIC_GOAL_APPEND_TOOL_HPP_ + +#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 +#include +#include +#include +#include +#include +#include +#endif + +#include + +namespace rviz_plugins +{ +class AutowareAutomaticGoalTool : public rviz_default_plugins::tools::PoseTool +{ + Q_OBJECT + +public: + AutowareAutomaticGoalTool(); + void onInitialize() override; + +protected: + void onPoseSet(double x, double y, double theta) override; + +private Q_SLOTS: + void updateTopic(); + +private: // NOLINT for Qt + rclcpp::Clock::SharedPtr clock_{nullptr}; + rclcpp::Publisher::SharedPtr pose_pub_{nullptr}; + + rviz_common::properties::StringProperty * pose_topic_property_{nullptr}; + rviz_common::properties::FloatProperty * std_dev_x_{nullptr}; + rviz_common::properties::FloatProperty * std_dev_y_{nullptr}; + rviz_common::properties::FloatProperty * std_dev_theta_{nullptr}; + rviz_common::properties::FloatProperty * position_z_{nullptr}; +}; + +} // namespace rviz_plugins + +#endif // AUTOMATIC_GOAL_APPEND_TOOL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp new file mode 100644 index 0000000000000..e04228a8f7b88 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp @@ -0,0 +1,484 @@ +// +// Copyright 2023 TIER IV, Inc. All rights reserved. +// +// 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 "automatic_goal_panel.hpp" + +namespace rviz_plugins +{ +AutowareAutomaticGoalPanel::AutowareAutomaticGoalPanel(QWidget * parent) +: rviz_common::Panel(parent) +{ + qt_timer_ = new QTimer(this); + connect( + qt_timer_, &QTimer::timeout, this, &AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick); + + auto * h_layout = new QHBoxLayout(this); + auto * v_layout = new QVBoxLayout(this); + h_layout->addWidget(makeGoalsListGroup()); + v_layout->addWidget(makeEngagementGroup()); + v_layout->addWidget(makeRoutingGroup()); + h_layout->addLayout(v_layout); + setLayout(h_layout); +} + +// Layouts +QGroupBox * AutowareAutomaticGoalPanel::makeGoalsListGroup() +{ + auto * group = new QGroupBox("GoalsList", this); + auto * grid = new QGridLayout(group); + + load_file_btn_ptr_ = new QPushButton("Load from file", group); + connect(load_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickLoadListFromFile())); + grid->addWidget(load_file_btn_ptr_, 0, 0); + + save_file_btn_ptr_ = new QPushButton("Save to file", group); + connect(save_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickSaveListToFile())); + grid->addWidget(save_file_btn_ptr_, 1, 0); + + goals_list_widget_ptr_ = new QListWidget(group); + goals_list_widget_ptr_->setStyleSheet("border:1px solid black;"); + grid->addWidget(goals_list_widget_ptr_, 2, 0); + + remove_selected_goal_btn_ptr_ = new QPushButton("Remove selected", group); + connect(remove_selected_goal_btn_ptr_, SIGNAL(clicked()), SLOT(onClickRemove())); + grid->addWidget(remove_selected_goal_btn_ptr_, 3, 0); + + loop_list_btn_ptr_ = new QPushButton("Loop list", group); + loop_list_btn_ptr_->setCheckable(true); + connect(loop_list_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleLoopList(bool))); + grid->addWidget(loop_list_btn_ptr_, 4, 0); + + goals_achieved_btn_ptr_ = new QPushButton("Saving achieved goals to file", group); + goals_achieved_btn_ptr_->setCheckable(true); + connect(goals_achieved_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleSaveGoalsAchievement(bool))); + grid->addWidget(goals_achieved_btn_ptr_, 5, 0); + + group->setLayout(grid); + return group; +} + +QGroupBox * AutowareAutomaticGoalPanel::makeRoutingGroup() +{ + auto * group = new QGroupBox("Routing", this); + auto * grid = new QGridLayout(group); + + routing_label_ptr_ = new QLabel("INIT", group); + routing_label_ptr_->setMinimumSize(100, 25); + routing_label_ptr_->setAlignment(Qt::AlignCenter); + routing_label_ptr_->setStyleSheet("border:1px solid black;"); + grid->addWidget(routing_label_ptr_, 0, 0); + + clear_route_btn_ptr_ = new QPushButton("Clear planned route", group); + connect(clear_route_btn_ptr_, &QPushButton::clicked, [this]() { onClickClearRoute(); }); + grid->addWidget(clear_route_btn_ptr_, 1, 0); + group->setLayout(grid); + + group->setLayout(grid); + return group; +} + +QGroupBox * AutowareAutomaticGoalPanel::makeEngagementGroup() +{ + auto * group = new QGroupBox("Engagement", this); + auto * grid = new QGridLayout(group); + + engagement_label_ptr_ = new QLabel("INITIALIZING", group); + engagement_label_ptr_->setMinimumSize(100, 25); + engagement_label_ptr_->setAlignment(Qt::AlignCenter); + engagement_label_ptr_->setStyleSheet("border:1px solid black;"); + grid->addWidget(engagement_label_ptr_, 0, 0); + + automatic_mode_btn_ptr_ = new QPushButton("Send goals automatically", group); + automatic_mode_btn_ptr_->setCheckable(true); + + connect(automatic_mode_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleAutoMode(bool))); + grid->addWidget(automatic_mode_btn_ptr_, 1, 0); + + plan_btn_ptr_ = new QPushButton("Plan to selected goal", group); + connect(plan_btn_ptr_, &QPushButton::clicked, [this] { onClickPlan(); }); + grid->addWidget(plan_btn_ptr_, 2, 0); + + start_btn_ptr_ = new QPushButton("Start current plan", group); + connect(start_btn_ptr_, &QPushButton::clicked, [this] { onClickStart(); }); + grid->addWidget(start_btn_ptr_, 3, 0); + + stop_btn_ptr_ = new QPushButton("Stop current plan", group); + connect(stop_btn_ptr_, SIGNAL(clicked()), SLOT(onClickStop())); + grid->addWidget(stop_btn_ptr_, 4, 0); + group->setLayout(grid); + + group->setLayout(grid); + return group; +} + +void AutowareAutomaticGoalPanel::showMessageBox(const QString & string) +{ + QMessageBox msg_box(this); + msg_box.setText(string); + msg_box.exec(); +} + +// Slots +void AutowareAutomaticGoalPanel::onInitialize() +{ + raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + pub_marker_ = raw_node_->create_publisher("~/automatic_goal/markers", 0); + sub_append_goal_ = raw_node_->create_subscription( + "~/automatic_goal/goal", 5, + std::bind(&AutowareAutomaticGoalPanel::onAppendGoal, this, std::placeholders::_1)); + initCommunication(raw_node_.get()); +} + +void AutowareAutomaticGoalPanel::onToggleLoopList(bool checked) +{ + is_loop_list_on_ = checked; + updateGUI(); +} + +void AutowareAutomaticGoalPanel::onToggleSaveGoalsAchievement(bool checked) +{ + if (checked) { + QString file_name = QFileDialog::getSaveFileName( + this, tr("Save File with GoalsList"), "/tmp/goals_achieved.log", + tr("Achieved goals (*.log)")); + goals_achieved_file_path_ = file_name.toStdString(); + } else { + goals_achieved_file_path_ = ""; + } + updateGUI(); +} + +void AutowareAutomaticGoalPanel::onToggleAutoMode(bool checked) +{ + if (checked && goals_list_widget_ptr_->selectedItems().count() != 1) { + showMessageBox("Select the first goal in GoalsList"); + automatic_mode_btn_ptr_->setChecked(false); + } else { + if (checked) current_goal_ = goals_list_widget_ptr_->currentRow(); + is_automatic_mode_on_ = checked; + is_automatic_mode_on_ ? qt_timer_->start(1000) : qt_timer_->stop(); + onClickClearRoute(); // here will be set State::AUTO_NEXT or State::EDITING; + } +} + +void AutowareAutomaticGoalPanel::onClickPlan() +{ + if (goals_list_widget_ptr_->selectedItems().count() != 1) { + showMessageBox("Select a goal in GoalsList"); + return; + } + + if (callPlanToGoalIndex(cli_set_route_, goals_list_widget_ptr_->currentRow())) { + state_ = State::PLANNING; + updateGUI(); + } +} + +void AutowareAutomaticGoalPanel::onClickStart() +{ + if (callService(cli_change_to_autonomous_)) { + state_ = State::STARTING; + updateGUI(); + } +} + +void AutowareAutomaticGoalPanel::onClickStop() +{ + // if ERROR is set then the ego is already stopped + if (state_ == State::ERROR) { + state_ = State::STOPPED; + updateGUI(); + } else if (callService(cli_change_to_stop_)) { + state_ = State::STOPPING; + updateGUI(); + } +} + +void AutowareAutomaticGoalPanel::onClickClearRoute() +{ + if (callService(cli_clear_route_)) { + state_ = State::CLEARING; + updateGUI(); + } +} + +void AutowareAutomaticGoalPanel::onClickRemove() +{ + if (static_cast(goals_list_widget_ptr_->currentRow()) < goals_list_.size()) + goals_list_.erase(goals_list_.begin() + goals_list_widget_ptr_->currentRow()); + resetAchievedGoals(); + updateGUI(); + updateGoalsList(); +} + +void AutowareAutomaticGoalPanel::onClickLoadListFromFile() +{ + QString file_name = QFileDialog::getOpenFileName( + this, tr("Open File with GoalsList"), "/tmp", tr("Goal lists (*.yaml)")); + if (file_name.count() > 0) loadGoalsList(file_name.toStdString()); +} + +void AutowareAutomaticGoalPanel::onClickSaveListToFile() +{ + if (!goals_list_.empty()) { + QString file_name = QFileDialog::getSaveFileName( + this, tr("Save File with GoalsList"), "/tmp/goals_list.yaml", tr("Goal lists (*.yaml)")); + if (file_name.count() > 0) saveGoalsList(file_name.toStdString()); + } +} + +// Inputs +void AutowareAutomaticGoalPanel::onAppendGoal(const PoseStamped::ConstSharedPtr pose) +{ + if (state_ == State::EDITING) { + goals_list_.push_back(pose); + updateGoalsList(); + updateGUI(); + } +} + +// Override +void AutowareAutomaticGoalPanel::onCallResult() { updateGUI(); } +void AutowareAutomaticGoalPanel::onGoalListUpdated() +{ + goals_list_widget_ptr_->clear(); + for (auto const & goal : goals_achieved_) { + auto * item = + new QListWidgetItem(QString::fromStdString(goal.second.first), goals_list_widget_ptr_); + goals_list_widget_ptr_->addItem(item); + updateGoalIcon(goals_list_widget_ptr_->count() - 1, QColor("lightGray")); + } + publishMarkers(); +} +void AutowareAutomaticGoalPanel::onOperationModeUpdated(const OperationModeState::ConstSharedPtr) +{ + updateGUI(); +} +void AutowareAutomaticGoalPanel::onRouteUpdated(const RouteState::ConstSharedPtr msg) +{ + std::pair style; + if (msg->state == RouteState::UNSET) + style = std::make_pair("UNSET", "background-color: #FFFF00;"); // yellow + else if (msg->state == RouteState::SET) + style = std::make_pair("SET", "background-color: #00FF00;"); // green + else if (msg->state == RouteState::ARRIVED) + style = std::make_pair("ARRIVED", "background-color: #FFA500;"); // orange + else if (msg->state == RouteState::CHANGING) + style = std::make_pair("CHANGING", "background-color: #FFFF00;"); // yellow + else + style = std::make_pair("UNKNOWN", "background-color: #FF0000;"); // red + + updateLabel(routing_label_ptr_, style.first, style.second); + updateGUI(); +} + +void AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick() +{ + if (is_automatic_mode_on_) { + if (state_ == State::AUTO_NEXT) { + // end if loop is off + if (current_goal_ >= goals_list_.size() && !is_loop_list_on_) { + disableAutomaticMode(); + return; + } + // plan to next goal + current_goal_ = current_goal_ % goals_list_.size(); + if (callPlanToGoalIndex(cli_set_route_, current_goal_)) { + state_ = State::PLANNING; + updateGUI(); + } + } else if (state_ == State::PLANNED) { + updateGoalIcon(current_goal_, QColor("yellow")); + onClickStart(); + } else if (state_ == State::ARRIVED) { + goals_achieved_[current_goal_].second++; + updateAchievedGoalsFile(current_goal_); + updateGoalIcon(current_goal_++, QColor("green")); + onClickClearRoute(); // will be set AUTO_NEXT as next state_ + } else if (state_ == State::STOPPED || state_ == State::ERROR) { + disableAutomaticMode(); + } + } +} + +// Visual updates +void AutowareAutomaticGoalPanel::updateGUI() +{ + deactivateButton(automatic_mode_btn_ptr_); + deactivateButton(remove_selected_goal_btn_ptr_); + deactivateButton(clear_route_btn_ptr_); + deactivateButton(plan_btn_ptr_); + deactivateButton(start_btn_ptr_); + deactivateButton(stop_btn_ptr_); + deactivateButton(load_file_btn_ptr_); + deactivateButton(save_file_btn_ptr_); + deactivateButton(loop_list_btn_ptr_); + deactivateButton(goals_achieved_btn_ptr_); + + std::pair style; + switch (state_) { + case State::EDITING: + activateButton(load_file_btn_ptr_); + if (!goals_list_.empty()) { + activateButton(goals_achieved_btn_ptr_); + activateButton(plan_btn_ptr_); + activateButton(remove_selected_goal_btn_ptr_); + activateButton(automatic_mode_btn_ptr_); + activateButton(save_file_btn_ptr_); + activateButton(loop_list_btn_ptr_); + } + style = std::make_pair("EDITING", "background-color: #FFFF00;"); + break; + case State::PLANNED: + activateButton(start_btn_ptr_); + activateButton(clear_route_btn_ptr_); + activateButton(save_file_btn_ptr_); + style = std::make_pair("PLANNED", "background-color: #00FF00;"); + break; + case State::STARTED: + activateButton(stop_btn_ptr_); + activateButton(save_file_btn_ptr_); + style = std::make_pair("STARTED", "background-color: #00FF00;"); + break; + case State::STOPPED: + activateButton(start_btn_ptr_); + activateButton(automatic_mode_btn_ptr_); + activateButton(clear_route_btn_ptr_); + activateButton(save_file_btn_ptr_); + style = std::make_pair("STOPPED", "background-color: #00FF00;"); + break; + case State::ARRIVED: + if (!is_automatic_mode_on_) onClickClearRoute(); // will be set EDITING as next state_ + break; + case State::CLEARED: + is_automatic_mode_on_ ? state_ = State::AUTO_NEXT : state_ = State::EDITING; + updateGUI(); + break; + case State::ERROR: + activateButton(stop_btn_ptr_); + if (!goals_list_.empty()) activateButton(save_file_btn_ptr_); + style = std::make_pair("ERROR", "background-color: #FF0000;"); + break; + case State::PLANNING: + activateButton(clear_route_btn_ptr_); + style = std::make_pair("PLANNING", "background-color: #FFA500;"); + break; + case State::STARTING: + style = std::make_pair("STARTING", "background-color: #FFA500;"); + break; + case State::STOPPING: + style = std::make_pair("STOPPING", "background-color: #FFA500;"); + break; + case State::CLEARING: + style = std::make_pair("CLEARING", "background-color: #FFA500;"); + break; + default: + break; + } + + automatic_mode_btn_ptr_->setStyleSheet(""); + loop_list_btn_ptr_->setStyleSheet(""); + goals_achieved_btn_ptr_->setStyleSheet(""); + if (is_automatic_mode_on_) automatic_mode_btn_ptr_->setStyleSheet("background-color: green"); + if (is_loop_list_on_) loop_list_btn_ptr_->setStyleSheet("background-color: green"); + if (!goals_achieved_file_path_.empty()) + goals_achieved_btn_ptr_->setStyleSheet("background-color: green"); + + updateLabel(engagement_label_ptr_, style.first, style.second); +} + +void AutowareAutomaticGoalPanel::updateGoalIcon(const unsigned goal_index, const QColor & color) +{ + QPixmap pixmap(24, 24); + pixmap.fill(color); + QPainter painter(&pixmap); + painter.setPen(QColor("black")); + painter.setFont(QFont("fixed-width", 10)); + QString text = QString::number(goals_achieved_[goal_index].second); + painter.drawText(QRect(0, 0, 24, 24), Qt::AlignCenter, text); + QIcon icon(pixmap); + goals_list_widget_ptr_->item(static_cast(goal_index))->setIcon(icon); +} + +void AutowareAutomaticGoalPanel::publishMarkers() +{ + MarkerArray text_array; + MarkerArray arrow_array; + // Clear existing + visualization_msgs::msg::Marker marker; + marker.header.stamp = rclcpp::Time(); + marker.ns = "names"; + marker.id = 0; + marker.action = visualization_msgs::msg::Marker::DELETEALL; + text_array.markers.push_back(marker); + marker.ns = "poses"; + arrow_array.markers.push_back(marker); + pub_marker_->publish(text_array); + pub_marker_->publish(arrow_array); + text_array.markers.clear(); + arrow_array.markers.clear(); + // Publish current + for (unsigned i = 0; i < goals_list_.size(); i++) { + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(); + marker.ns = "names"; + marker.id = static_cast(i); + marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.pose = goals_list_[i]->pose; + marker.lifetime = rclcpp::Duration(0, 0); + marker.scale.x = 1.6; + marker.scale.y = 1.6; + marker.scale.z = 1.6; + marker.color.r = 1.0; + marker.color.g = 1.0; + marker.color.b = 1.0; + marker.color.a = 1.0; + marker.frame_locked = false; + marker.text = "G" + std::to_string(i); + text_array.markers.push_back(marker); + marker.ns = "poses"; + marker.scale.y = 0.2; + marker.scale.z = 0.2; + marker.type = visualization_msgs::msg::Marker::ARROW; + arrow_array.markers.push_back(marker); + } + pub_marker_->publish(text_array); + pub_marker_->publish(arrow_array); +} + +// File +void AutowareAutomaticGoalPanel::saveGoalsList(const std::string & file_path) +{ + YAML::Node node; + for (unsigned i = 0; i < goals_list_.size(); ++i) { + node[i]["position_x"] = goals_list_[i]->pose.position.x; + node[i]["position_y"] = goals_list_[i]->pose.position.y; + node[i]["position_z"] = goals_list_[i]->pose.position.z; + node[i]["orientation_x"] = goals_list_[i]->pose.orientation.x; + node[i]["orientation_y"] = goals_list_[i]->pose.orientation.y; + node[i]["orientation_z"] = goals_list_[i]->pose.orientation.z; + node[i]["orientation_w"] = goals_list_[i]->pose.orientation.w; + } + std::ofstream file_out(file_path); + file_out << node; + file_out.close(); +} + +} // namespace rviz_plugins +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalPanel, rviz_common::Panel) diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp new file mode 100644 index 0000000000000..0ec9ca530f074 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp @@ -0,0 +1,147 @@ +// +// Copyright 2023 TIER IV, Inc. All rights reserved. +// +// 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 AUTOMATIC_GOAL_PANEL_HPP_ +#define AUTOMATIC_GOAL_PANEL_HPP_ + +#include "automatic_goal_sender.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace rviz_plugins +{ +class AutowareAutomaticGoalPanel : public rviz_common::Panel, + public automatic_goal::AutowareAutomaticGoalSender +{ + using State = automatic_goal::AutomaticGoalState; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using MarkerArray = visualization_msgs::msg::MarkerArray; + using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; + using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + using RouteState = autoware_adapi_v1_msgs::msg::RouteState; + using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints; + using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; + Q_OBJECT + +public: + explicit AutowareAutomaticGoalPanel(QWidget * parent = nullptr); + void onInitialize() override; + +public Q_SLOTS: // NOLINT for Qt + void onToggleLoopList(bool checked); + void onToggleAutoMode(bool checked); + void onToggleSaveGoalsAchievement(bool checked); + void onClickPlan(); + void onClickStart(); + void onClickStop(); + void onClickClearRoute(); + void onClickRemove(); + void onClickLoadListFromFile(); + void onClickSaveListToFile(); + +private: + // Override + void updateAutoExecutionTimerTick() override; + void onRouteUpdated(const RouteState::ConstSharedPtr msg) override; + void onOperationModeUpdated(const OperationModeState::ConstSharedPtr msg) override; + void onCallResult() override; + void onGoalListUpdated() override; + + // Inputs + void onAppendGoal(const PoseStamped::ConstSharedPtr pose); + + // Visual updates + void updateGUI(); + void updateGoalIcon(const unsigned goal_index, const QColor & color); + void publishMarkers(); + void showMessageBox(const QString & string); + void disableAutomaticMode() { automatic_mode_btn_ptr_->setChecked(false); } + static void activateButton(QAbstractButton * btn) { btn->setEnabled(true); } + static void deactivateButton(QAbstractButton * btn) { btn->setEnabled(false); } + static void updateLabel(QLabel * label, const QString & text, const QString & style_sheet) + { + label->setText(text); + label->setStyleSheet(style_sheet); + } + // File + void saveGoalsList(const std::string & file); + + // Pub/Sub + rclcpp::Publisher::SharedPtr pub_marker_{nullptr}; + rclcpp::Subscription::SharedPtr sub_append_goal_{nullptr}; + + // Containers + rclcpp::Node::SharedPtr raw_node_{nullptr}; + bool is_automatic_mode_on_{false}; + bool is_loop_list_on_{false}; + + // QT Containers + QGroupBox * makeGoalsListGroup(); + QGroupBox * makeRoutingGroup(); + QGroupBox * makeEngagementGroup(); + QTimer * qt_timer_{nullptr}; + QListWidget * goals_list_widget_ptr_{nullptr}; + QLabel * routing_label_ptr_{nullptr}; + QLabel * operation_mode_label_ptr_{nullptr}; + QLabel * engagement_label_ptr_{nullptr}; + QPushButton * loop_list_btn_ptr_{nullptr}; + QPushButton * goals_achieved_btn_ptr_{nullptr}; + QPushButton * load_file_btn_ptr_{nullptr}; + QPushButton * save_file_btn_ptr_{nullptr}; + QPushButton * automatic_mode_btn_ptr_{nullptr}; + QPushButton * remove_selected_goal_btn_ptr_{nullptr}; + QPushButton * clear_route_btn_ptr_{nullptr}; + QPushButton * plan_btn_ptr_{nullptr}; + QPushButton * start_btn_ptr_{nullptr}; + QPushButton * stop_btn_ptr_{nullptr}; +}; +} // namespace rviz_plugins + +#endif // AUTOMATIC_GOAL_PANEL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp new file mode 100644 index 0000000000000..51f7716863465 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp @@ -0,0 +1,227 @@ +// Copyright 2016 Open Source Robotics Foundation, 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 "automatic_goal_sender.hpp" + +namespace automatic_goal +{ +AutowareAutomaticGoalSender::AutowareAutomaticGoalSender() : Node("automatic_goal_sender") {} + +void AutowareAutomaticGoalSender::init() +{ + loadParams(this); + initCommunication(this); + loadGoalsList(goals_list_file_path_); + timer_ = this->create_wall_timer( + std::chrono::milliseconds(500), + std::bind(&AutowareAutomaticGoalSender::updateAutoExecutionTimerTick, this)); + + // Print info + RCLCPP_INFO_STREAM(get_logger(), "GoalsList has been loaded from: " << goals_list_file_path_); + for (auto const & goal : goals_achieved_) + RCLCPP_INFO_STREAM(get_logger(), "Loaded: " << goal.second.first); + RCLCPP_INFO_STREAM( + get_logger(), "Achieved goals will be saved in: " << goals_achieved_file_path_); +} + +void AutowareAutomaticGoalSender::loadParams(rclcpp::Node * node) +{ + namespace fs = std::filesystem; + node->declare_parameter("goals_list_file_path", ""); + node->declare_parameter("goals_achieved_dir_path", ""); + // goals_list + goals_list_file_path_ = node->get_parameter("goals_list_file_path").as_string(); + if (!fs::exists(goals_list_file_path_) || !fs::is_regular_file(goals_list_file_path_)) + throw std::invalid_argument( + "goals_list_file_path parameter - file path is invalid: " + goals_list_file_path_); + // goals_achieved + goals_achieved_file_path_ = node->get_parameter("goals_achieved_dir_path").as_string(); + if (!fs::exists(goals_achieved_file_path_) || fs::is_regular_file(goals_achieved_file_path_)) + throw std::invalid_argument( + "goals_achieved_dir_path - directory path is invalid: " + goals_achieved_file_path_); + goals_achieved_file_path_ += "goals_achieved.log"; +} + +void AutowareAutomaticGoalSender::initCommunication(rclcpp::Node * node) +{ + // Executing + sub_operation_mode_ = node->create_subscription( + "/api/operation_mode/state", rclcpp::QoS{1}.transient_local(), + std::bind(&AutowareAutomaticGoalSender::onOperationMode, this, std::placeholders::_1)); + + cli_change_to_autonomous_ = node->create_client( + "/api/operation_mode/change_to_autonomous", rmw_qos_profile_services_default); + + cli_change_to_stop_ = node->create_client( + "/api/operation_mode/change_to_stop", rmw_qos_profile_services_default); + + // Planning + sub_route_ = node->create_subscription( + "/api/routing/state", rclcpp::QoS{1}.transient_local(), + std::bind(&AutowareAutomaticGoalSender::onRoute, this, std::placeholders::_1)); + + cli_clear_route_ = + node->create_client("/api/routing/clear_route", rmw_qos_profile_services_default); + + cli_set_route_ = node->create_client( + "/api/routing/set_route_points", rmw_qos_profile_services_default); +} + +// Sub +void AutowareAutomaticGoalSender::onRoute(const RouteState::ConstSharedPtr msg) +{ + if (msg->state == RouteState::UNSET && state_ == State::CLEARING) + state_ = State::CLEARED; + else if (msg->state == RouteState::SET && state_ == State::PLANNING) + state_ = State::PLANNED; + else if (msg->state == RouteState::ARRIVED && state_ == State::STARTED) + state_ = State::ARRIVED; + onRouteUpdated(msg); +} + +void AutowareAutomaticGoalSender::onOperationMode(const OperationModeState::ConstSharedPtr msg) +{ + if (msg->mode == OperationModeState::STOP && state_ == State::INITIALIZING) + state_ = State::EDITING; + else if (msg->mode == OperationModeState::STOP && state_ == State::STOPPING) + state_ = State::STOPPED; + else if (msg->mode == OperationModeState::AUTONOMOUS && state_ == State::STARTING) + state_ = State::STARTED; + onOperationModeUpdated(msg); +} + +// Update +void AutowareAutomaticGoalSender::updateGoalsList() +{ + unsigned i = 0; + for (const auto & goal : goals_list_) { + std::stringstream ss; + ss << std::fixed << std::setprecision(2); + tf2::Quaternion tf2_quat; + tf2::convert(goal->pose.orientation, tf2_quat); + ss << "G" << i << " (" << goal->pose.position.x << ", "; + ss << goal->pose.position.y << ", " << tf2::getYaw(tf2_quat) << ")"; + goals_achieved_.insert({i++, std::make_pair(ss.str(), 0)}); + } + onGoalListUpdated(); +} + +void AutowareAutomaticGoalSender::updateAutoExecutionTimerTick() +{ + auto goal = goals_achieved_[current_goal_].first; + + if (state_ == State::INITIALIZING) { + RCLCPP_INFO_THROTTLE( + get_logger(), *get_clock(), 3000, "Initializing... waiting for OperationModeState::STOP"); + + } else if (state_ == State::EDITING) { // skip the editing step by default + state_ = State::AUTO_NEXT; + + } else if (state_ == State::AUTO_NEXT) { // plan to next goal + RCLCPP_INFO_STREAM(get_logger(), goal << ": Goal set as the next. Planning in progress..."); + if (callPlanToGoalIndex(cli_set_route_, current_goal_)) state_ = State::PLANNING; + + } else if (state_ == State::PLANNED) { // start plan to next goal + RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been planned. Route starting..."); + if (callService(cli_change_to_autonomous_)) state_ = State::STARTING; + + } else if (state_ == State::STARTED) { + RCLCPP_INFO_STREAM_THROTTLE(get_logger(), *get_clock(), 5000, goal << ": Driving to the goal."); + + } else if (state_ == State::ARRIVED) { // clear plan after achieving next goal, goal++ + RCLCPP_INFO_STREAM( + get_logger(), goal << ": Goal has been ACHIEVED " << ++goals_achieved_[current_goal_].second + << " times. Route clearing..."); + updateAchievedGoalsFile(current_goal_); + if (callService(cli_clear_route_)) state_ = State::CLEARING; + + } else if (state_ == State::CLEARED) { + RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been cleared."); + current_goal_++; + current_goal_ = current_goal_ % goals_list_.size(); + state_ = State::AUTO_NEXT; + + } else if (state_ == State::STOPPED) { + RCLCPP_WARN_STREAM( + get_logger(), goal << ": The execution has been stopped unexpectedly! Restarting..."); + if (callService(cli_change_to_autonomous_)) state_ = State::STARTING; + + } else if (state_ == State::ERROR) { + timer_->cancel(); + throw std::runtime_error(goal + ": Error encountered during execution!"); + } +} + +// File +void AutowareAutomaticGoalSender::loadGoalsList(const std::string & file_path) +{ + YAML::Node node = YAML::LoadFile(file_path); + goals_list_.clear(); + for (auto && goal : node) { + std::shared_ptr pose = std::make_shared(); + pose->header.frame_id = "map"; + pose->header.stamp = rclcpp::Time(); + pose->pose.position.x = goal["position_x"].as(); + pose->pose.position.y = goal["position_y"].as(); + pose->pose.position.z = goal["position_z"].as(); + pose->pose.orientation.x = goal["orientation_x"].as(); + pose->pose.orientation.y = goal["orientation_y"].as(); + pose->pose.orientation.z = goal["orientation_z"].as(); + pose->pose.orientation.w = goal["orientation_w"].as(); + goals_list_.push_back(pose); + } + resetAchievedGoals(); + updateGoalsList(); +} + +void AutowareAutomaticGoalSender::updateAchievedGoalsFile(const unsigned goal_index) +{ + if (!goals_achieved_file_path_.empty()) { + std::ofstream out(goals_achieved_file_path_, std::fstream::app); + std::stringstream ss; + ss << "[" << getTimestamp() << "] Achieved: " << goals_achieved_[goal_index].first; + ss << ", Current number of achievements: " << goals_achieved_[goal_index].second << "\n"; + out << ss.str(); + out.close(); + } +} + +void AutowareAutomaticGoalSender::resetAchievedGoals() +{ + goals_achieved_.clear(); + if (!goals_achieved_file_path_.empty()) { + std::ofstream out(goals_achieved_file_path_, std::fstream::app); + out << "[" << getTimestamp() + << "] GoalsList was loaded from a file or a goal was removed - counters have been reset\n"; + out.close(); + } +} +} // namespace automatic_goal + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + + std::shared_ptr node{nullptr}; + try { + node = std::make_shared(); + node->init(); + } catch (const std::exception & e) { + fprintf(stderr, "%s Exiting...\n", e.what()); + return 1; + } + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp new file mode 100644 index 0000000000000..aacdada352811 --- /dev/null +++ b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp @@ -0,0 +1,174 @@ +// Copyright 2016 Open Source Robotics Foundation, 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 AUTOMATIC_GOAL_SENDER_HPP_ +#define AUTOMATIC_GOAL_SENDER_HPP_ +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace automatic_goal +{ +enum class AutomaticGoalState { + INITIALIZING, + EDITING, + PLANNING, + PLANNED, + STARTING, + STARTED, + ARRIVED, + AUTO_NEXT, + STOPPING, + STOPPED, + CLEARING, + CLEARED, + ERROR, +}; + +class AutowareAutomaticGoalSender : public rclcpp::Node +{ + using State = AutomaticGoalState; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; + using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + using RouteState = autoware_adapi_v1_msgs::msg::RouteState; + using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints; + using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; + +public: + AutowareAutomaticGoalSender(); + void init(); + +protected: + void initCommunication(rclcpp::Node * node); + // Calls + bool callPlanToGoalIndex( + const rclcpp::Client::SharedPtr client, const unsigned goal_index) + { + if (!client->service_is_ready()) { + RCLCPP_WARN(get_logger(), "SetRoutePoints client is unavailable"); + return false; + } + + auto req = std::make_shared(); + req->header = goals_list_.at(goal_index)->header; + req->goal = goals_list_.at(goal_index)->pose; + client->async_send_request( + req, [this](typename rclcpp::Client::SharedFuture result) { + if (result.get()->status.code != 0) state_ = State::ERROR; + printCallResult(result); + onCallResult(); + }); + return true; + } + template + bool callService(const typename rclcpp::Client::SharedPtr client) + { + if (!client->service_is_ready()) { + RCLCPP_WARN(get_logger(), "Client is unavailable"); + return false; + } + + auto req = std::make_shared(); + client->async_send_request(req, [this](typename rclcpp::Client::SharedFuture result) { + if (result.get()->status.code != 0) state_ = State::ERROR; + printCallResult(result); + onCallResult(); + }); + return true; + } + template + void printCallResult(typename rclcpp::Client::SharedFuture result) + { + if (result.get()->status.code != 0) { + RCLCPP_ERROR( + get_logger(), "Service type \"%s\" status: %d, %s", typeid(T).name(), + result.get()->status.code, result.get()->status.message.c_str()); + } else { + RCLCPP_DEBUG( + get_logger(), "Service type \"%s\" status: %d, %s", typeid(T).name(), + result.get()->status.code, result.get()->status.message.c_str()); + } + } + + // Update + void updateGoalsList(); + virtual void updateAutoExecutionTimerTick(); + + // File + void loadGoalsList(const std::string & file_path); + void updateAchievedGoalsFile(const unsigned goal_index); + void resetAchievedGoals(); + static std::string getTimestamp() + { + char buffer[128]; + std::time_t now = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::strftime(&buffer[0], sizeof(buffer), "%Y-%m-%d %H:%M:%S", std::localtime(&now)); + return std::string{buffer}; + } + + // Sub + void onRoute(const RouteState::ConstSharedPtr msg); + void onOperationMode(const OperationModeState::ConstSharedPtr msg); + + // Interface + virtual void onRouteUpdated(const RouteState::ConstSharedPtr) {} + virtual void onOperationModeUpdated(const OperationModeState::ConstSharedPtr) {} + virtual void onCallResult() {} + virtual void onGoalListUpdated() {} + + // Cli + rclcpp::Client::SharedPtr cli_change_to_autonomous_{nullptr}; + rclcpp::Client::SharedPtr cli_change_to_stop_{nullptr}; + rclcpp::Client::SharedPtr cli_clear_route_{nullptr}; + rclcpp::Client::SharedPtr cli_set_route_{nullptr}; + + // Containers + unsigned current_goal_{0}; + State state_{State::INITIALIZING}; + std::vector goals_list_{}; + std::map> goals_achieved_{}; + std::string goals_achieved_file_path_{}; + +private: + void loadParams(rclcpp::Node * node); + + // Sub + rclcpp::Subscription::SharedPtr sub_route_{nullptr}; + rclcpp::Subscription::SharedPtr sub_operation_mode_{nullptr}; + + // Containers + std::string goals_list_file_path_{}; + rclcpp::TimerBase::SharedPtr timer_{nullptr}; +}; +} // namespace automatic_goal +#endif // AUTOMATIC_GOAL_SENDER_HPP_ From 5ec247b87b2eabd866b57cf60f8bf6a4d0e26b20 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 13 Mar 2023 12:39:29 +0900 Subject: [PATCH 020/121] feat(behavior_path_planner): use akima spline for xy only first (#2800) * feat(behavior_path_planner): use akima spline for xy only first Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/behavior_path_planner/parameters.hpp | 4 +++- .../src/behavior_path_planner_node.cpp | 6 ++++-- planning/behavior_path_planner/src/utilities.cpp | 6 +++++- 3 files changed, 12 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 164fb72887cd8..7df7c4c39fff0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -56,7 +56,9 @@ struct BehaviorPathPlannerParameters double turn_signal_shift_length_threshold; bool turn_signal_on_swerving; - double path_interval; + double enable_akima_spline_first; + double input_path_interval; + double output_path_interval; double ego_nearest_dist_threshold; double ego_nearest_yaw_threshold; 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 7fc12eb616da9..5ff95f26fdcad 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -383,7 +383,9 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() declare_parameter("turn_signal_shift_length_threshold", 0.3); p.turn_signal_on_swerving = declare_parameter("turn_signal_on_swerving", true); - p.path_interval = declare_parameter("path_interval"); + p.enable_akima_spline_first = declare_parameter("enable_akima_spline_first"); + p.input_path_interval = declare_parameter("input_path_interval"); + p.output_path_interval = declare_parameter("output_path_interval"); p.visualize_maximum_drivable_area = declare_parameter("visualize_maximum_drivable_area", true); p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); @@ -1270,7 +1272,7 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( } const auto resampled_path = util::resamplePathWithSpline( - connected_path, planner_data_->parameters.path_interval, + connected_path, planner_data_->parameters.output_path_interval, keepInputPoints(module_status_ptr_vec)); return std::make_shared(resampled_path); } diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 9160e4aef11bc..2547a0e1cd681 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -1975,7 +1975,11 @@ PathWithLaneId getCenterLinePath( s_forward = std::min(s_forward, goal_arc_coordinates.length - lane_change_buffer); } - return route_handler.getCenterLinePath(lanelet_sequence, s_backward, s_forward, true); + const auto raw_path_with_lane_id = + route_handler.getCenterLinePath(lanelet_sequence, s_backward, s_forward, true); + const auto resampled_path_with_lane_id = motion_utils::resamplePath( + raw_path_with_lane_id, parameter.input_path_interval, parameter.enable_akima_spline_first); + return raw_path_with_lane_id; } // for lane following From e97ff9d572043193471285cec31295d6d1466021 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Mar 2023 13:01:45 +0900 Subject: [PATCH 021/121] fix(lane_change): lane change module changes output path intentionally without approval (#3051) fix(lane_change): wait approval in onEntry() Signed-off-by: satoshi-ota --- .../src/scene_module/lane_change/lane_change_module.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 0554c5d298aa6..9d7e1672b9213 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -80,6 +80,7 @@ void LaneChangeModule::onEntry() current_state_ = ModuleStatus::SUCCESS; #else current_state_ = ModuleStatus::IDLE; + waitApproval(); #endif current_lane_change_state_ = LaneChangeStates::Normal; updateLaneChangeStatus(); From d8ab5f1ebc9bc64f2366900fc8ae1ccffb9e52e9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 13 Mar 2023 13:38:12 +0900 Subject: [PATCH 022/121] chore(system_error_monitor): supress initial warning (#3056) Signed-off-by: Takayuki Murooka --- system/system_error_monitor/src/system_error_monitor_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 d6cc771e5dbd2..8a4cf3ecbb8d6 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -443,7 +443,7 @@ 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(1000).count(), + get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(), "input data is timeout"); updateTimeoutHazardStatus(); publishHazardStatus(hazard_status_); From 864d97d0a507810c3e65fe87d580fc18f5277a8a Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 13 Mar 2023 15:29:01 +0900 Subject: [PATCH 023/121] fix(mpc): reset prev value when mpc failed (#3062) * fix(mpc): reset prev value when mpc failed Signed-off-by: Takamasa Horibe * fix(mpc): typo Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../include/mpc_lateral_controller/mpc.hpp | 11 +++++++---- control/mpc_lateral_controller/src/mpc.cpp | 10 ++-------- .../src/mpc_lateral_controller.cpp | 9 +++++++++ 3 files changed, 18 insertions(+), 12 deletions(-) diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp index 226dd803e3945..c6a920e347cab 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp @@ -199,10 +199,7 @@ class MPC * @brief set the reference trajectory to follow */ void storeSteerCmd(const double steer); - /** - * @brief reset previous result of MPC - */ - void resetPrevResult(const SteeringReport & current_steer); + /** * @brief set initial condition for mpc * @param [in] data mpc data @@ -393,6 +390,12 @@ class MPC const bool enable_path_smoothing, const int path_filter_moving_ave_num, const int curvature_smoothing_num_traj, const int curvature_smoothing_num_ref_steer, const bool extend_trajectory_for_end_yaw_control); + + /** + * @brief reset previous result of MPC + */ + void resetPrevResult(const SteeringReport & current_steer); + /** * @brief set the vehicle model of this MPC */ diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index ceb5ac5b9c6bc..fb4353d142ee0 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -248,8 +248,8 @@ void MPC::setReferenceTrajectory( void MPC::resetPrevResult(const SteeringReport & current_steer) { - // Consider limit. The prev value larger than limiation brakes the optimization constraint and - // resluts in optimization failure. + // Consider limit. The prev value larger than limitaion brakes the optimization constraint and + // results in optimization failure. const float steer_lim_f = static_cast(m_steer_lim); m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); @@ -264,12 +264,6 @@ bool MPC::getData( if (!MPCUtils::calcNearestPoseInterp( traj, current_pose, &(data->nearest_pose), &(nearest_idx), &(data->nearest_time), ego_nearest_dist_threshold, ego_nearest_yaw_threshold, m_logger, *m_clock)) { - // reset previous MPC result - // Note: When a large deviation from the trajectory occurs, the optimization stops and - // the vehicle will return to the path by re-planning the trajectory or external operation. - // After the recovery, the previous value of the optimization may deviate greatly from - // the actual steer angle, and it may make the optimization result unstable. - resetPrevResult(current_steer); RCLCPP_WARN_SKIPFIRST_THROTTLE( m_logger, *m_clock, duration, "calculateMPC: error in calculating nearest pose. stop mpc."); return false; diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index 192694d48af72..2a129d544587b 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -204,6 +204,15 @@ trajectory_follower::LateralOutput MpcLateralController::run( m_current_steering, m_current_kinematic_state.twist.twist.linear.x, m_current_kinematic_state.pose.pose, ctrl_cmd, predicted_traj, debug_values); + // reset previous MPC result + // Note: When a large deviation from the trajectory occurs, the optimization stops and + // the vehicle will return to the path by re-planning the trajectory or external operation. + // After the recovery, the previous value of the optimization may deviate greatly from + // the actual steer angle, and it may make the optimization result unstable. + if (!is_mpc_solved) { + m_mpc.resetPrevResult(m_current_steering); + } + if (enable_auto_steering_offset_removal_) { steering_offset_->updateOffset( m_current_kinematic_state.twist.twist, From 969dacf6386011bf08fca6963d3cdbf67fe8dddd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Mar 2023 15:38:48 +0900 Subject: [PATCH 024/121] fix(lane_change): use previous output (#3059) Signed-off-by: satoshi-ota --- .../util/lane_change/util.hpp | 13 ++++++ .../lane_change/lane_change_module.cpp | 7 ++++ .../src/util/lane_change/util.cpp | 40 ++++++++++++++++++- 3 files changed, 59 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp index 443ce4d3aaa66..76b0e4b8abb83 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp @@ -78,6 +78,14 @@ std::pair getLaneChangePaths( const double check_distance, LaneChangePaths * candidate_paths, std::unordered_map * debug_data); +std::pair getLaneChangePaths( + const PathWithLaneId & original_path, const RouteHandler & route_handler, + const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, + const Pose & pose, const Twist & twist, const PredictedObjects::ConstSharedPtr dynamic_objects, + const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter, + const double check_distance, LaneChangePaths * candidate_paths, + std::unordered_map * debug_data); + bool isLaneChangePathSafe( const LaneChangePath & lane_change_path, const PredictedObjects::ConstSharedPtr dynamic_objects, const LaneChangeTargetObjectIndices & dynamic_object_indices, const Pose & current_pose, @@ -108,6 +116,11 @@ PathWithLaneId getLaneChangePathPrepareSegment( const double arc_length_from_current, const double backward_path_length, const double prepare_distance, const double prepare_speed); +PathWithLaneId getLaneChangePathPrepareSegment( + const PathWithLaneId & original_path, const lanelet::ConstLanelets & original_lanelets, + const Pose & current_pose, const double backward_path_length, const double prepare_distance, + const double prepare_speed); + PathWithLaneId getLaneChangePathLaneChangingSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets, const double forward_path_length, const double arc_length_from_target, diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 9d7e1672b9213..fbc3bc88f22a0 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -438,10 +438,17 @@ std::pair LaneChangeModule::getSafePath( // find candidate paths LaneChangePaths valid_paths; +#ifdef USE_OLD_ARCHITECTURE const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths( *route_handler, current_lanes, lane_change_lanes, current_pose, current_twist, planner_data_->dynamic_object, common_parameters, *parameters_, check_distance, &valid_paths, &object_debug_); +#else + const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths( + *getPreviousModuleOutput().path, *route_handler, current_lanes, lane_change_lanes, current_pose, + current_twist, planner_data_->dynamic_object, common_parameters, *parameters_, check_distance, + &valid_paths, &object_debug_); +#endif debug_valid_path_ = valid_paths; if (parameters_->publish_debug_marker) { diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index 4c48c16179586..14a54907e29b0 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -268,6 +268,7 @@ std::optional constructCandidatePath( return std::optional{candidate_path}; } +#ifdef USE_OLD_ARCHITECTURE std::pair getLaneChangePaths( const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, const Pose & pose, const Twist & twist, @@ -275,6 +276,15 @@ std::pair getLaneChangePaths( const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter, const double check_distance, LaneChangePaths * candidate_paths, std::unordered_map * debug_data) +#else +std::pair getLaneChangePaths( + const PathWithLaneId & original_path, const RouteHandler & route_handler, + const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, + const Pose & pose, const Twist & twist, const PredictedObjects::ConstSharedPtr dynamic_objects, + const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter, + const double check_distance, LaneChangePaths * candidate_paths, + std::unordered_map * debug_data) +#endif { debug_data->clear(); if (original_lanelets.empty() || target_lanelets.empty()) { @@ -320,7 +330,8 @@ std::pair getLaneChangePaths( const auto required_total_min_distance = util::calcLaneChangeBuffer(common_parameter, num_to_preferred_lane); - const auto arc_position_from_current = lanelet::utils::getArcCoordinates(original_lanelets, pose); + [[maybe_unused]] const auto arc_position_from_current = + lanelet::utils::getArcCoordinates(original_lanelets, pose); const auto arc_position_from_target = lanelet::utils::getArcCoordinates(target_lanelets, pose); const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanelets); @@ -352,9 +363,15 @@ std::pair getLaneChangePaths( continue; } +#ifdef USE_OLD_ARCHITECTURE const auto prepare_segment_reference = getLaneChangePathPrepareSegment( route_handler, original_lanelets, arc_position_from_current.length, backward_path_length, prepare_distance, std::max(prepare_speed, minimum_lane_change_velocity)); +#else + const auto prepare_segment_reference = getLaneChangePathPrepareSegment( + original_path, original_lanelets, pose, backward_path_length, prepare_distance, + std::max(prepare_speed, minimum_lane_change_velocity)); +#endif const auto estimated_shift_length = lanelet::utils::getArcCoordinates( target_lanelets, prepare_segment_reference.points.front().point.pose); @@ -667,6 +684,27 @@ PathWithLaneId getLaneChangePathPrepareSegment( return prepare_segment; } +PathWithLaneId getLaneChangePathPrepareSegment( + const PathWithLaneId & original_path, const lanelet::ConstLanelets & original_lanelets, + const Pose & current_pose, const double backward_path_length, const double prepare_distance, + const double prepare_speed) +{ + if (original_lanelets.empty()) { + return PathWithLaneId(); + } + + auto prepare_segment = original_path; + const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prepare_segment.points, current_pose, 3.0, 1.0); + util::clipPathLength(prepare_segment, current_seg_idx, prepare_distance, backward_path_length); + + prepare_segment.points.back().point.longitudinal_velocity_mps = std::min( + prepare_segment.points.back().point.longitudinal_velocity_mps, + static_cast(prepare_speed)); + + return prepare_segment; +} + std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( const double velocity, const double shift_length, const double deceleration, const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param, From 5ca8e689bf431413c1072fd8d9b523536beed129 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Mar 2023 15:42:47 +0900 Subject: [PATCH 025/121] fix(avoidance): use previous module output (#3043) fix(avoidance): use previous module output for get current lanelet Signed-off-by: satoshi-ota --- .../scene_module/avoidance/avoidance_module.cpp | 15 +++++++++++++++ 1 file changed, 15 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 3928f7f9f2b15..9dfed422d5ff9 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 @@ -114,7 +114,12 @@ bool AvoidanceModule::isExecutionRequested() const } // Check ego is in preferred lane +#ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); +#else + const auto current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif lanelet::ConstLanelet current_lane; lanelet::utils::query::getClosestLanelet( current_lanes, planner_data_->self_odometry->pose.pose, ¤t_lane); @@ -235,9 +240,14 @@ AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & deb calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); // lanelet info +#ifdef USE_OLD_ARCHITECTURE data.current_lanelets = util::calcLaneAroundPose( planner_data_->route_handler, reference_pose, planner_data_->parameters.forward_path_length, planner_data_->parameters.backward_path_length); +#else + data.current_lanelets = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif // keep avoidance state data.state = avoidance_data_.state; @@ -2955,8 +2965,13 @@ PathWithLaneId AvoidanceModule::calcCenterLinePath( "p.backward_path_length = %f, longest_dist_to_shift_line = %f, backward_length = %f", p.backward_path_length, longest_dist_to_shift_line, backward_length); +#ifdef USE_OLD_ARCHITECTURE const lanelet::ConstLanelets current_lanes = util::calcLaneAroundPose(route_handler, pose, p.forward_path_length, backward_length); +#else + const lanelet::ConstLanelets current_lanes = + util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); +#endif centerline_path = util::getCenterLinePath( *route_handler, current_lanes, pose, backward_length, p.forward_path_length, p); From e6615b331cc443fc9e14618e2c51fffbf3f5a2a6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Mar 2023 18:53:19 +0900 Subject: [PATCH 026/121] fix(lane_change): update lane change status in planWaitingApproval() (#3061) Signed-off-by: satoshi-ota --- .../src/scene_module/lane_change/lane_change_module.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index fbc3bc88f22a0..91fdc77369dd5 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -257,8 +257,13 @@ CandidateOutput LaneChangeModule::planCandidate() const #endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); +#ifdef USE_OLD_ARCHITECTURE [[maybe_unused]] const auto [found_valid_path, found_safe_path] = getSafePath(lane_change_lanes, check_distance_, selected_path); +#else + selected_path = status_.lane_change_path; +#endif + selected_path.path.header = planner_data_->route_handler->getRouteHeader(); if (isAbortState()) { @@ -295,6 +300,10 @@ BehaviorModuleOutput LaneChangeModule::planWaitingApproval() out.path = std::make_shared(prev_approved_path_); out.reference_path = getPreviousModuleOutput().reference_path; +#ifndef USE_OLD_ARCHITECTURE + updateLaneChangeStatus(); +#endif + const auto candidate = planCandidate(); path_candidate_ = std::make_shared(candidate.path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; From b2790e99d6b2428fbb11ef31e85fa14855a03e47 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Mar 2023 19:17:04 +0900 Subject: [PATCH 027/121] fix(avoidance): be able to execute lc + avoidance simlutaneously (#3066) fix(avoidance): be able to execute lc + avoidance Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 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 9dfed422d5ff9..b83b9a57f0934 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 @@ -116,10 +116,6 @@ bool AvoidanceModule::isExecutionRequested() const // Check ego is in preferred lane #ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); -#else - const auto current_lanes = - util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); -#endif lanelet::ConstLanelet current_lane; lanelet::utils::query::getClosestLanelet( current_lanes, planner_data_->self_odometry->pose.pose, ¤t_lane); @@ -128,6 +124,7 @@ bool AvoidanceModule::isExecutionRequested() const if (num != 0) { return false; } +#endif // Check avoidance targets exist const auto avoid_data = calcAvoidancePlanningData(debug_data_); From be0929bd42b74b98d5a7fb238bc309c2ebb098ef Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Mon, 13 Mar 2023 19:43:21 +0900 Subject: [PATCH 028/121] fix(tensorrt_yolox): resolve all output labels become unknown (#3064) Signed-off-by: ktro2828 --- perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp index a10e8e6332488..8d03bfaee1877 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -148,8 +148,8 @@ void TrtYoloXNode::replaceLabelMap() if (label == "PERSON") { label = "PEDESTRIAN"; } else if ( - label != "CAR" || label != "PEDESTRIAN" || label != "BUS" || label != "TRUCK" || - label != "BICYCLE" || label != "MOTORCYCLE") { + label != "CAR" && label != "PEDESTRIAN" && label != "BUS" && label != "TRUCK" && + label != "BICYCLE" && label != "MOTORCYCLE") { label = "UNKNOWN"; } } From ad413be319bad571296862979c0c1cb9be7cbb24 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 14 Mar 2023 10:37:09 +0900 Subject: [PATCH 029/121] feat(behavior_path_planner): use efficient lateral distance calculation (#3041) --- .../include/behavior_path_planner/utilities.hpp | 3 +++ .../src/util/lane_change/util.cpp | 6 +++--- planning/behavior_path_planner/src/utilities.cpp | 12 ++++++++++++ 3 files changed, 18 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp index c0598ed7f04d8..f374246c44b7d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp @@ -534,6 +534,9 @@ double calcLaneChangeBuffer( lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); + +double calcLateralDistanceToLanelet( + const lanelet::ConstLanelets & lanelet_sequence, const geometry_msgs::msg::Pose & pose); } // namespace behavior_path_planner::util #endif // BEHAVIOR_PATH_PLANNER__UTILITIES_HPP_ diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index 14a54907e29b0..3bd7549bf3677 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -373,13 +373,13 @@ std::pair getLaneChangePaths( std::max(prepare_speed, minimum_lane_change_velocity)); #endif - const auto estimated_shift_length = lanelet::utils::getArcCoordinates( + const auto estimated_shift_length = util::calcLateralDistanceToLanelet( target_lanelets, prepare_segment_reference.points.front().point.pose); const auto [lane_changing_speed, lane_changing_distance] = calcLaneChangingSpeedAndDistanceWhenDecelerate( - prepare_speed, estimated_shift_length.distance, acceleration, end_of_lane_dist, - common_parameter, parameter); + prepare_speed, estimated_shift_length, acceleration, end_of_lane_dist, common_parameter, + parameter); const auto lc_dist = LaneChangePhaseInfo{prepare_distance, lane_changing_distance}; diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 2547a0e1cd681..de43052b79662 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -2691,4 +2691,16 @@ lanelet::ConstLanelets getLaneletsFromPath( return lanelets; } + +double calcLateralDistanceToLanelet( + const lanelet::ConstLanelets & lanelet_sequence, const geometry_msgs::msg::Pose & pose) +{ + lanelet::ConstLanelet closest_lanelet; + lanelet::utils::query::getClosestLanelet(lanelet_sequence, pose, &closest_lanelet); + const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline()); + + const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(pose.position); + return lanelet::geometry::signedDistance( + centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint()); +} } // namespace behavior_path_planner::util From 1b4fa2b287377cc372ef44c4f68d9f70c6e53591 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 14 Mar 2023 10:43:37 +0900 Subject: [PATCH 030/121] fix(avoidance): fix shift line merging logic (#2882) fix(avoidance): fix bug in shift line generation logic Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 b83b9a57f0934..60811e5c4469f 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 @@ -1376,7 +1376,7 @@ void AvoidanceModule::generateTotalShiftLine( for (size_t i = 1; i < N; ++i) { bool has_object = false; for (const auto & al : avoid_lines) { - if (al.start_idx < i && i < al.end_idx) { + if (al.start_idx <= i && i <= al.end_idx) { has_object = true; break; } From 87e44224310d151738aac212056be1487a23147c Mon Sep 17 00:00:00 2001 From: David Wong <33114676+drwnz@users.noreply.github.com> Date: Tue, 14 Mar 2023 10:52:56 +0900 Subject: [PATCH 031/121] fix(velodyne_monitor): add fmt package to dependencies (#3069) Co-authored-by: ito-san <57388357+ito-san@users.noreply.github.com> --- system/velodyne_monitor/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/system/velodyne_monitor/CMakeLists.txt b/system/velodyne_monitor/CMakeLists.txt index d3238a0fd0d5b..c7511bf572f4a 100644 --- a/system/velodyne_monitor/CMakeLists.txt +++ b/system/velodyne_monitor/CMakeLists.txt @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.14) project(velodyne_monitor) find_package(autoware_cmake REQUIRED) +find_package(fmt) autoware_package() ### Target executable From 4342bdc27d7f5afb2ade97ca66bc4146c7e14325 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 14 Mar 2023 13:07:38 +0900 Subject: [PATCH 032/121] fix(lane_change): use previous module turn signal in waiting approval (#3072) Signed-off-by: satoshi-ota --- .../src/scene_module/lane_change/lane_change_module.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 91fdc77369dd5..f9510ecd7e8e5 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -299,6 +299,7 @@ BehaviorModuleOutput LaneChangeModule::planWaitingApproval() BehaviorModuleOutput out; out.path = std::make_shared(prev_approved_path_); out.reference_path = getPreviousModuleOutput().reference_path; + out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; #ifndef USE_OLD_ARCHITECTURE updateLaneChangeStatus(); From 38032f114d8d9023019526b6a7b517d8ff89416d Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 14 Mar 2023 13:32:52 +0900 Subject: [PATCH 033/121] feat(planning_evaluator): add modified goal deviation (#3053) * feat(planning_evaluator): add modified goal deviation Signed-off-by: kosuke55 * add abs Signed-off-by: kosuke55 * remove setModifiedGoal Signed-off-by: kosuke55 * use Point and rename func Signed-off-by: kosuke55 * fix func docs Signed-off-by: kosuke55 * fix and add tests Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../metrics/deviation_metrics.hpp | 26 ++++++ .../planning_evaluator/metrics/metric.hpp | 18 +++- .../planning_evaluator/metrics_calculator.hpp | 18 +++- .../planning_evaluator_node.hpp | 22 ++++- .../launch/planning_evaluator.launch.xml | 4 + evaluator/planning_evaluator/package.xml | 1 + .../param/planning_evaluator.defaults.yaml | 3 + .../src/metrics/deviation_metrics.cpp | 20 +++++ .../src/metrics_calculator.cpp | 27 ++++-- .../src/motion_evaluator_node.cpp | 4 +- .../src/planning_evaluator_node.cpp | 88 +++++++++++++----- .../test/test_planning_evaluator_node.cpp | 89 +++++++++++++++---- 12 files changed, 268 insertions(+), 52 deletions(-) diff --git a/evaluator/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp b/evaluator/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp index e71b887ff3a10..04a5b758d62e1 100644 --- a/evaluator/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp @@ -26,6 +26,8 @@ namespace metrics { using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; /** * @brief calculate lateral deviation of the given trajectory from the reference trajectory @@ -51,6 +53,30 @@ Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj); */ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj); +/** + * @brief calculate longitudinal deviation of the given ego pose from the modified goal pose + * @param [in] base_pose base pose + * @param [in] target_point target point + * @return calculated statistics + */ +Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point); + +/** + * @brief calculate lateral deviation of the given ego pose from the modified goal pose + * @param [in] base_pose base pose + * @param [in] target_point target point + * @return calculated statistics + */ +Stat calcLateralDeviation(const Pose & base_pose, const Point & target_point); + +/** + * @brief calculate yaw deviation of the given ego pose from the modified goal pose + * @param [in] base_pose base pose + * @param [in] target_pose target pose + * @return calculated statistics + */ +Stat calcYawDeviation(const Pose & base_pose, const Pose & target_pose); + } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/planning_evaluator/include/planning_evaluator/metrics/metric.hpp b/evaluator/planning_evaluator/include/planning_evaluator/metrics/metric.hpp index 16811f91b32b1..e1ec69dbaef5c 100644 --- a/evaluator/planning_evaluator/include/planning_evaluator/metrics/metric.hpp +++ b/evaluator/planning_evaluator/include/planning_evaluator/metrics/metric.hpp @@ -41,6 +41,9 @@ enum class Metric { stability_frechet, obstacle_distance, obstacle_ttc, + modified_goal_longitudinal_deviation, + modified_goal_lateral_deviation, + modified_goal_yaw_deviation, SIZE, }; @@ -63,7 +66,10 @@ static const std::unordered_map str_to_metric = { {"stability_frechet", Metric::stability_frechet}, {"obstacle_distance", Metric::obstacle_distance}, {"obstacle_ttc", Metric::obstacle_ttc}, -}; + {"modified_goal_longitudinal_deviation", Metric::modified_goal_longitudinal_deviation}, + {"modified_goal_lateral_deviation", Metric::modified_goal_lateral_deviation}, + {"modified_goal_yaw_deviation", Metric::modified_goal_yaw_deviation}}; + static const std::unordered_map metric_to_str = { {Metric::curvature, "curvature"}, {Metric::point_interval, "point_interval"}, @@ -79,7 +85,10 @@ static const std::unordered_map metric_to_str = { {Metric::stability, "stability"}, {Metric::stability_frechet, "stability_frechet"}, {Metric::obstacle_distance, "obstacle_distance"}, - {Metric::obstacle_ttc, "obstacle_ttc"}}; + {Metric::obstacle_ttc, "obstacle_ttc"}, + {Metric::modified_goal_longitudinal_deviation, "modified_goal_longitudinal_deviation"}, + {Metric::modified_goal_lateral_deviation, "modified_goal_lateral_deviation"}, + {Metric::modified_goal_yaw_deviation, "modified_goal_yaw_deviation"}}; // Metrics descriptions static const std::unordered_map metric_descriptions = { @@ -97,7 +106,10 @@ static const std::unordered_map metric_descriptions = { {Metric::stability, "Stability[m]"}, {Metric::stability_frechet, "StabilityFrechet[m]"}, {Metric::obstacle_distance, "Obstacle_distance[m]"}, - {Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}}; + {Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}, + {Metric::modified_goal_longitudinal_deviation, "Modified_goal_longitudinal_deviation[m]"}, + {Metric::modified_goal_lateral_deviation, "Modified_goal_lateral_deviation[m]"}, + {Metric::modified_goal_yaw_deviation, "Modified_goal_yaw_deviation[rad]"}}; namespace details { diff --git a/evaluator/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp b/evaluator/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp index 0ed2af7b3862e..851678e55d755 100644 --- a/evaluator/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp +++ b/evaluator/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp @@ -14,7 +14,6 @@ #ifndef PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ #define PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ - #include "planning_evaluator/metrics/metric.hpp" #include "planning_evaluator/parameters.hpp" #include "planning_evaluator/stat.hpp" @@ -22,13 +21,19 @@ #include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" #include "autoware_auto_planning_msgs/msg/trajectory.hpp" #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp" #include "geometry_msgs/msg/pose.hpp" +#include + namespace planning_diagnostics { using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_planning_msgs::msg::PoseWithUuidStamped; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; class MetricsCalculator { @@ -42,7 +47,9 @@ class MetricsCalculator * @param [in] metric Metric enum value * @return string describing the requested metric */ - Stat calculate(const Metric metric, const Trajectory & traj) const; + std::optional> calculate(const Metric metric, const Trajectory & traj) const; + std::optional> calculate( + const Metric metric, const Pose & base_pose, const Pose & target_pose) const; /** * @brief set the reference trajectory used to calculate the deviation metrics @@ -68,6 +75,12 @@ class MetricsCalculator */ void setEgoPose(const geometry_msgs::msg::Pose & pose); + /** + * @brief get the ego pose + * @return ego pose + */ + Pose getEgoPose(); + private: /** * @brief trim a trajectory from the current ego pose to some fixed time or distance @@ -86,6 +99,7 @@ class MetricsCalculator Trajectory previous_trajectory_lookahead_; PredictedObjects dynamic_objects_; geometry_msgs::msg::Pose ego_pose_; + PoseWithUuidStamped modified_goal_; }; // class MetricsCalculator } // namespace planning_diagnostics diff --git a/evaluator/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp b/evaluator/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp index e9fd82c85cf7b..888eea855295c 100644 --- a/evaluator/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp @@ -24,7 +24,9 @@ #include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" #include "autoware_auto_planning_msgs/msg/trajectory.hpp" #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp" #include "diagnostic_msgs/msg/diagnostic_array.hpp" +#include "nav_msgs/msg/odometry.hpp" #include #include @@ -37,8 +39,10 @@ namespace planning_diagnostics using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_planning_msgs::msg::PoseWithUuidStamped; using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; +using nav_msgs::msg::Odometry; /** * @brief Node for planning evaluation @@ -49,6 +53,12 @@ class PlanningEvaluatorNode : public rclcpp::Node explicit PlanningEvaluatorNode(const rclcpp::NodeOptions & node_options); ~PlanningEvaluatorNode(); + /** + * @brief callback on receiving an odometry + * @param [in] odometry_msg received odometry message + */ + void onOdometry(const Odometry::ConstSharedPtr odometry_msg); + /** * @brief callback on receiving a trajectory * @param [in] traj_msg received trajectory message @@ -68,9 +78,10 @@ class PlanningEvaluatorNode : public rclcpp::Node void onObjects(const PredictedObjects::ConstSharedPtr objects_msg); /** - * @brief update the ego pose stored in the MetricsCalculator + * @brief callback on receiving a modified goal + * @param [in] modified_goal_msg received modified goal message */ - void updateCalculatorEgoPose(const std::string & target_frame); + void onModifiedGoal(const PoseWithUuidStamped::ConstSharedPtr modified_goal_msg); /** * @brief publish the given metric statistic @@ -80,11 +91,15 @@ class PlanningEvaluatorNode : public rclcpp::Node private: static bool isFinite(const TrajectoryPoint & p); + void publishModifiedGoalDeviationMetrics(); // ROS rclcpp::Subscription::SharedPtr traj_sub_; rclcpp::Subscription::SharedPtr ref_sub_; rclcpp::Subscription::SharedPtr objects_sub_; + rclcpp::Subscription::SharedPtr modified_goal_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + rclcpp::Publisher::SharedPtr metrics_pub_; std::shared_ptr transform_listener_{nullptr}; std::unique_ptr tf_buffer_; @@ -99,6 +114,9 @@ class PlanningEvaluatorNode : public rclcpp::Node std::vector metrics_; std::deque stamps_; std::array>, static_cast(Metric::SIZE)> metric_stats_; + + Odometry::ConstSharedPtr ego_state_ptr_; + PoseWithUuidStamped::ConstSharedPtr modified_goal_ptr_; }; } // namespace planning_diagnostics diff --git a/evaluator/planning_evaluator/launch/planning_evaluator.launch.xml b/evaluator/planning_evaluator/launch/planning_evaluator.launch.xml index af7c5369f7422..1b7510c2ced69 100644 --- a/evaluator/planning_evaluator/launch/planning_evaluator.launch.xml +++ b/evaluator/planning_evaluator/launch/planning_evaluator.launch.xml @@ -1,15 +1,19 @@ + + + + diff --git a/evaluator/planning_evaluator/package.xml b/evaluator/planning_evaluator/package.xml index 73186f6b20e88..ef2bca288c8b0 100644 --- a/evaluator/planning_evaluator/package.xml +++ b/evaluator/planning_evaluator/package.xml @@ -16,6 +16,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_msgs diagnostic_msgs eigen geometry_msgs diff --git a/evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml b/evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml index bd47deedb282f..2e92a174ca79f 100644 --- a/evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml +++ b/evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml @@ -19,6 +19,9 @@ - stability_frechet - obstacle_distance - obstacle_ttc + - modified_goal_longitudinal_deviation + - modified_goal_lateral_deviation + - modified_goal_yaw_deviation trajectory: min_point_dist_m: 0.1 # [m] minimum distance between two successive points to use for angle calculation diff --git a/evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp index d6d8aa661e5ea..5146fcd3ec0f2 100644 --- a/evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp @@ -77,5 +77,25 @@ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr return stat; } +Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point) +{ + Stat stat; + stat.add(std::abs(tier4_autoware_utils::calcLongitudinalDeviation(base_pose, target_point))); + return stat; +} + +Stat calcLateralDeviation(const Pose & base_pose, const Point & target_point) +{ + Stat stat; + stat.add(std::abs(tier4_autoware_utils::calcLateralDeviation(base_pose, target_point))); + return stat; +} + +Stat calcYawDeviation(const Pose & base_pose, const Pose & target_pose) +{ + Stat stat; + stat.add(std::abs(tier4_autoware_utils::calcYawDeviation(base_pose, target_pose))); + return stat; +} } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/planning_evaluator/src/metrics_calculator.cpp b/evaluator/planning_evaluator/src/metrics_calculator.cpp index 802e1dde94fd1..adfdddd7d2c5e 100644 --- a/evaluator/planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/planning_evaluator/src/metrics_calculator.cpp @@ -23,9 +23,10 @@ namespace planning_diagnostics { -Stat MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const +std::optional> MetricsCalculator::calculate( + const Metric metric, const Trajectory & traj) const { - // Functions to calculate metrics + // Functions to calculate trajectory metrics switch (metric) { case Metric::curvature: return metrics::calcTrajectoryCurvature(traj); @@ -70,9 +71,23 @@ Stat MetricsCalculator::calculate(const Metric metric, const Trajectory case Metric::obstacle_ttc: return metrics::calcTimeToCollision(dynamic_objects_, traj, parameters.obstacle.dist_thr_m); default: - throw std::runtime_error( - "[MetricsCalculator][calculate()] unknown Metric " + - std::to_string(static_cast(metric))); + return {}; + } +} + +std::optional> MetricsCalculator::calculate( + const Metric metric, const Pose & base_pose, const Pose & target_pose) const +{ + // Functions to calculate pose metrics + switch (metric) { + case Metric::modified_goal_longitudinal_deviation: + return metrics::calcLongitudinalDeviation(base_pose, target_pose.position); + case Metric::modified_goal_lateral_deviation: + return metrics::calcLateralDeviation(base_pose, target_pose.position); + case Metric::modified_goal_yaw_deviation: + return metrics::calcYawDeviation(base_pose, target_pose); + default: + return {}; } } @@ -93,6 +108,8 @@ void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects) void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose) { ego_pose_ = pose; } +Pose MetricsCalculator::getEgoPose() { return ego_pose_; } + Trajectory MetricsCalculator::getLookaheadTrajectory( const Trajectory & traj, const double max_dist_m, const double max_time_s) const { diff --git a/evaluator/planning_evaluator/src/motion_evaluator_node.cpp b/evaluator/planning_evaluator/src/motion_evaluator_node.cpp index 56b08fca81f9f..9a103890d53ac 100644 --- a/evaluator/planning_evaluator/src/motion_evaluator_node.cpp +++ b/evaluator/planning_evaluator/src/motion_evaluator_node.cpp @@ -55,7 +55,9 @@ MotionEvaluatorNode::~MotionEvaluatorNode() f << std::endl; for (Metric metric : metrics_) { const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_); - f /* << std::setw(3 * column_width) */ << stat << " "; + if (stat) { + f /* << std::setw(3 * column_width) */ << *stat << " "; + } } f.close(); } diff --git a/evaluator/planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/planning_evaluator/src/planning_evaluator_node.cpp index 663f0482cf77b..346b029922e3e 100644 --- a/evaluator/planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/planning_evaluator/src/planning_evaluator_node.cpp @@ -40,6 +40,13 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op objects_sub_ = create_subscription( "~/input/objects", 1, std::bind(&PlanningEvaluatorNode::onObjects, this, _1)); + + modified_goal_sub_ = create_subscription( + "~/input/modified_goal", 1, std::bind(&PlanningEvaluatorNode::onModifiedGoal, this, _1)); + + odom_sub_ = create_subscription( + "~/input/odometry", 1, std::bind(&PlanningEvaluatorNode::onOdometry, this, _1)); + tf_buffer_ = std::make_unique(this->get_clock()); transform_listener_ = std::make_shared(*tf_buffer_); @@ -98,24 +105,6 @@ PlanningEvaluatorNode::~PlanningEvaluatorNode() } } -void PlanningEvaluatorNode::updateCalculatorEgoPose(const std::string & target_frame) -{ - try { - const geometry_msgs::msg::TransformStamped transform = - tf_buffer_->lookupTransform(target_frame, ego_frame_str_, tf2::TimePointZero); - geometry_msgs::msg::Pose ego_pose; - ego_pose.position.x = transform.transform.translation.x; - ego_pose.position.y = transform.transform.translation.y; - ego_pose.position.z = transform.transform.translation.z; - ego_pose.orientation = transform.transform.rotation; - metrics_calculator_.setEgoPose(ego_pose); - } catch (tf2::TransformException & ex) { - RCLCPP_INFO( - this->get_logger(), "Cannot set ego pose: could not transform %s to %s: %s", - target_frame.c_str(), ego_frame_str_.c_str(), ex.what()); - } -} - DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticStatus( const Metric & metric, const Stat & metric_stat) const { @@ -137,18 +126,24 @@ DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticStatus( void PlanningEvaluatorNode::onTrajectory(const Trajectory::ConstSharedPtr traj_msg) { + if (!ego_state_ptr_) { + return; + } + auto start = now(); stamps_.push_back(traj_msg->header.stamp); - updateCalculatorEgoPose(traj_msg->header.frame_id); - DiagnosticArray metrics_msg; metrics_msg.header.stamp = now(); for (Metric metric : metrics_) { - const Stat metric_stat = metrics_calculator_.calculate(Metric(metric), *traj_msg); - metric_stats_[static_cast(metric)].push_back(metric_stat); - if (metric_stat.count() > 0) { - metrics_msg.status.push_back(generateDiagnosticStatus(metric, metric_stat)); + const auto metric_stat = metrics_calculator_.calculate(Metric(metric), *traj_msg); + if (!metric_stat) { + continue; + } + + metric_stats_[static_cast(metric)].push_back(*metric_stat); + if (metric_stat->count() > 0) { + metrics_msg.status.push_back(generateDiagnosticStatus(metric, *metric_stat)); } } if (!metrics_msg.status.empty()) { @@ -159,6 +154,51 @@ void PlanningEvaluatorNode::onTrajectory(const Trajectory::ConstSharedPtr traj_m RCLCPP_DEBUG(get_logger(), "Planning evaluation calculation time: %2.2f ms", runtime * 1e3); } +void PlanningEvaluatorNode::onModifiedGoal( + const PoseWithUuidStamped::ConstSharedPtr modified_goal_msg) +{ + modified_goal_ptr_ = modified_goal_msg; + if (ego_state_ptr_) { + publishModifiedGoalDeviationMetrics(); + } +} + +void PlanningEvaluatorNode::onOdometry(const Odometry::ConstSharedPtr odometry_msg) +{ + ego_state_ptr_ = odometry_msg; + metrics_calculator_.setEgoPose(odometry_msg->pose.pose); + + if (modified_goal_ptr_) { + publishModifiedGoalDeviationMetrics(); + } +} + +void PlanningEvaluatorNode::publishModifiedGoalDeviationMetrics() +{ + auto start = now(); + + DiagnosticArray metrics_msg; + metrics_msg.header.stamp = now(); + for (Metric metric : metrics_) { + const auto metric_stat = metrics_calculator_.calculate( + Metric(metric), modified_goal_ptr_->pose, ego_state_ptr_->pose.pose); + if (!metric_stat) { + continue; + } + metric_stats_[static_cast(metric)].push_back(*metric_stat); + if (metric_stat->count() > 0) { + metrics_msg.status.push_back(generateDiagnosticStatus(metric, *metric_stat)); + } + } + if (!metrics_msg.status.empty()) { + metrics_pub_->publish(metrics_msg); + } + auto runtime = (now() - start).seconds(); + RCLCPP_DEBUG( + get_logger(), "Planning evaluation modified goal deviation calculation time: %2.2f ms", + runtime * 1e3); +} + void PlanningEvaluatorNode::onReferenceTrajectory(const Trajectory::ConstSharedPtr traj_msg) { metrics_calculator_.setReferenceTrajectory(*traj_msg); diff --git a/evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp b/evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp index 8e9bcdd734222..4f2ab014a79d6 100644 --- a/evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp +++ b/evaluator/planning_evaluator/test/test_planning_evaluator_node.cpp @@ -36,7 +36,11 @@ using EvalNode = planning_diagnostics::PlanningEvaluatorNode; using Trajectory = autoware_auto_planning_msgs::msg::Trajectory; using TrajectoryPoint = autoware_auto_planning_msgs::msg::TrajectoryPoint; using Objects = autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_planning_msgs::msg::PoseWithUuidStamped; using diagnostic_msgs::msg::DiagnosticArray; +using nav_msgs::msg::Odometry; + +constexpr double epsilon = 1e-6; class EvalTest : public ::testing::Test { @@ -70,6 +74,10 @@ class EvalTest : public ::testing::Test dummy_node, "/planning_evaluator/input/reference_trajectory", 1); objects_pub_ = rclcpp::create_publisher(dummy_node, "/planning_evaluator/input/objects", 1); + odom_pub_ = + rclcpp::create_publisher(dummy_node, "/planning_evaluator/input/odometry", 1); + modified_goal_pub_ = rclcpp::create_publisher( + dummy_node, "/planning_evaluator/input/modified_goal", 1); tf_broadcaster_ = std::make_unique(dummy_node); publishEgoPose(0.0, 0.0, 0.0); @@ -139,28 +147,51 @@ class EvalTest : public ::testing::Test return metric_value_; } - void publishEgoPose(const double x, const double y, const double yaw) + double publishModifiedGoalAndGetMetric(const double x, const double y, const double yaw) { - geometry_msgs::msg::TransformStamped t; + metric_updated_ = false; - // Read message content and assign it to - // corresponding tf variables - t.header.stamp = dummy_node->now(); - t.header.frame_id = "map"; - t.child_frame_id = "base_link"; + PoseWithUuidStamped goal; + goal.header.frame_id = "map"; + goal.header.stamp = dummy_node->now(); + goal.pose.position.x = x; + goal.pose.position.y = y; + goal.pose.position.z = 0.0; + tf2::Quaternion q; + q.setRPY(0.0, 0.0, yaw); + goal.pose.orientation.x = q.x(); + goal.pose.orientation.y = q.y(); + goal.pose.orientation.z = q.z(); + goal.pose.orientation.w = q.w(); + modified_goal_pub_->publish(goal); - t.transform.translation.x = x; - t.transform.translation.y = y; - t.transform.translation.z = 0.0; + while (!metric_updated_) { + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + return metric_value_; + } + void publishEgoPose(const double x, const double y, const double yaw) + { + Odometry odom; + odom.header.frame_id = "map"; + odom.header.stamp = dummy_node->now(); + odom.pose.pose.position.x = x; + odom.pose.pose.position.y = y; + odom.pose.pose.position.z = 0.0; tf2::Quaternion q; q.setRPY(0.0, 0.0, yaw); - t.transform.rotation.x = q.x(); - t.transform.rotation.y = q.y(); - t.transform.rotation.z = q.z(); - t.transform.rotation.w = q.w(); + odom.pose.pose.orientation.x = q.x(); + odom.pose.pose.orientation.y = q.y(); + odom.pose.pose.orientation.z = q.z(); + odom.pose.pose.orientation.w = q.w(); - tf_broadcaster_->sendTransform(t); + odom_pub_->publish(odom); + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); } // Latest metric value @@ -173,6 +204,8 @@ class EvalTest : public ::testing::Test rclcpp::Publisher::SharedPtr traj_pub_; rclcpp::Publisher::SharedPtr ref_traj_pub_; rclcpp::Publisher::SharedPtr objects_pub_; + rclcpp::Publisher::SharedPtr modified_goal_pub_; + rclcpp::Publisher::SharedPtr odom_pub_; rclcpp::Subscription::SharedPtr metric_sub_; // TF broadcaster std::unique_ptr tf_broadcaster_; @@ -407,3 +440,29 @@ TEST_F(EvalTest, TestObstacleTTC) t.points[1].pose.position.x = 1.0; EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 2.0); } + +TEST_F(EvalTest, TestModifiedGoalLongitudinalDeviation) +{ + setTargetMetric(planning_diagnostics::Metric::modified_goal_longitudinal_deviation); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 0.0, 0.0), 1.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 0.0, M_PI_2), 0.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(0.0, 1.0, 0.0), 0.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(0.0, 1.0, M_PI_2), 1.0, epsilon); +} + +TEST_F(EvalTest, TestModifiedGoalLateralDeviation) +{ + setTargetMetric(planning_diagnostics::Metric::modified_goal_lateral_deviation); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 0.0, 0.0), 0.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 0.0, M_PI_2), 1.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(0.0, 1.0, 0.0), 1.0, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(0.0, 1.0, M_PI_2), 0.0, epsilon); +} + +TEST_F(EvalTest, TestModifiedGoalYawDeviation) +{ + setTargetMetric(planning_diagnostics::Metric::modified_goal_yaw_deviation); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(0.0, 0.0, M_PI_2), M_PI_2, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 1.0, -M_PI_2), M_PI_2, epsilon); + EXPECT_NEAR(publishModifiedGoalAndGetMetric(1.0, 1.0, -M_PI_4), M_PI_4, epsilon); +} From d19c6c46f78d08ce49ee75e8a28c77c843f74fed Mon Sep 17 00:00:00 2001 From: David Wong <33114676+drwnz@users.noreply.github.com> Date: Tue, 14 Mar 2023 14:33:02 +0900 Subject: [PATCH 034/121] fix(pointcloud_preprocessor): pointcloud preprocessor pcl headers (#3073) fix(pointcloud_preprocessor): add missing header file for centroid Signed-off-by: David Wong --- .../vector_map_filter/lanelet2_map_filter_nodelet.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp index 568384509d4da..ed0d753a68ecc 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include From c1d28c9947207bd6f0a21ec12992e907603f1309 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Tue, 14 Mar 2023 16:14:44 +0900 Subject: [PATCH 035/121] feat(lidar_centerpoint): add build only option for tensorrt engine (#2677) * feat(lidar_centerpoint): add build only option for tensorrt engine Signed-off-by: yukke42 * fix typo Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * style(pre-commit): autofix * chore: add description Signed-off-by: yukke42 * chore: shutdown node Signed-off-by: yukke42 * feat: use tensorrt_commom Signed-off-by: yukke42 * fix: resolve the crash when shutting down the node Signed-off-by: yukke42 * chore: fix typo Co-authored-by: Kenzo Lobos Tsunekawa * style(pre-commit): autofix --------- Signed-off-by: yukke42 Signed-off-by: yukke42 Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- perception/lidar_centerpoint/README.md | 1 + .../lidar_centerpoint/centerpoint_trt.hpp | 1 - .../lidar_centerpoint/network/network_trt.hpp | 4 +- .../network/tensorrt_wrapper.hpp | 44 +++------------ .../launch/lidar_centerpoint.launch.xml | 2 + .../lidar_centerpoint/lib/centerpoint_trt.cpp | 4 +- .../lib/network/network_trt.cpp | 5 +- .../lib/network/tensorrt_wrapper.cpp | 55 ++++++++++--------- perception/lidar_centerpoint/package.xml | 1 + perception/lidar_centerpoint/src/node.cpp | 5 ++ 10 files changed, 52 insertions(+), 70 deletions(-) diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md index baaea06e59346..f03e5bb777299 100644 --- a/perception/lidar_centerpoint/README.md +++ b/perception/lidar_centerpoint/README.md @@ -43,6 +43,7 @@ We trained the models using . | `nms_iou_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression | | `nms_iou_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. | | `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | +| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | ## Assumptions / Known limits diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp index 25891958f9194..fee17f1c0156a 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp @@ -81,7 +81,6 @@ class CenterPointTRT std::unique_ptr post_proc_ptr_{nullptr}; cudaStream_t stream_{nullptr}; - bool verbose_{false}; std::size_t class_size_{0}; CenterPointConfig config_; std::size_t num_voxels_{0}; diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp index c2c2dbc179361..639aa0ba8bad3 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp @@ -38,9 +38,7 @@ class HeadTRT : public TensorRTWrapper public: using TensorRTWrapper::TensorRTWrapper; - HeadTRT( - const std::vector & out_channel_sizes, const CenterPointConfig & config, - const bool verbose); + HeadTRT(const std::vector & out_channel_sizes, const CenterPointConfig & config); protected: bool setProfile( diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp index 2cd05400bc9af..7f55ab6f5e414 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp @@ -16,6 +16,7 @@ #define LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ #include +#include #include @@ -25,45 +26,18 @@ namespace centerpoint { -struct Deleter -{ - template - void operator()(T * obj) const - { - if (obj) { - delete obj; - } - } -}; - -template -using unique_ptr = std::unique_ptr; - -class Logger : public nvinfer1::ILogger -{ -public: - explicit Logger(bool verbose) : verbose_(verbose) {} - - void log(Severity severity, const char * msg) noexcept override - { - if (verbose_ || ((severity != Severity::kINFO) && (severity != Severity::kVERBOSE))) { - std::cout << msg << std::endl; - } - } - -private: - bool verbose_{false}; -}; class TensorRTWrapper { public: - explicit TensorRTWrapper(const CenterPointConfig & config, const bool verbose); + explicit TensorRTWrapper(const CenterPointConfig & config); + + ~TensorRTWrapper(); bool init( const std::string & onnx_path, const std::string & engine_path, const std::string & precision); - unique_ptr context_ = nullptr; + tensorrt_common::TrtUniquePtr context_{nullptr}; protected: virtual bool setProfile( @@ -71,7 +45,7 @@ class TensorRTWrapper nvinfer1::IBuilderConfig & config) = 0; CenterPointConfig config_; - Logger logger_; + tensorrt_common::Logger logger_; private: bool parseONNX( @@ -84,9 +58,9 @@ class TensorRTWrapper bool createContext(); - unique_ptr runtime_ = nullptr; - unique_ptr plan_ = nullptr; - unique_ptr engine_ = nullptr; + tensorrt_common::TrtUniquePtr runtime_{nullptr}; + tensorrt_common::TrtUniquePtr plan_{nullptr}; + tensorrt_common::TrtUniquePtr engine_{nullptr}; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index 522b488429c62..d552cb702b980 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -8,6 +8,7 @@ + @@ -21,6 +22,7 @@ + diff --git a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp index a489be9e86538..9b01ea8f53675 100644 --- a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp @@ -35,7 +35,7 @@ CenterPointTRT::CenterPointTRT( post_proc_ptr_ = std::make_unique(config_); // encoder - encoder_trt_ptr_ = std::make_unique(config_, verbose_); + encoder_trt_ptr_ = std::make_unique(config_); encoder_trt_ptr_->init( encoder_param.onnx_path(), encoder_param.engine_path(), encoder_param.trt_precision()); encoder_trt_ptr_->context_->setBindingDimensions( @@ -47,7 +47,7 @@ CenterPointTRT::CenterPointTRT( std::vector out_channel_sizes = { config_.class_size_, config_.head_out_offset_size_, config_.head_out_z_size_, config_.head_out_dim_size_, config_.head_out_rot_size_, config_.head_out_vel_size_}; - head_trt_ptr_ = std::make_unique(out_channel_sizes, config_, verbose_); + head_trt_ptr_ = std::make_unique(out_channel_sizes, config_); head_trt_ptr_->init(head_param.onnx_path(), head_param.engine_path(), head_param.trt_precision()); head_trt_ptr_->context_->setBindingDimensions( 0, nvinfer1::Dims4( diff --git a/perception/lidar_centerpoint/lib/network/network_trt.cpp b/perception/lidar_centerpoint/lib/network/network_trt.cpp index ffc4ac4a2eef0..88319ff51fe35 100644 --- a/perception/lidar_centerpoint/lib/network/network_trt.cpp +++ b/perception/lidar_centerpoint/lib/network/network_trt.cpp @@ -39,9 +39,8 @@ bool VoxelEncoderTRT::setProfile( } HeadTRT::HeadTRT( - const std::vector & out_channel_sizes, const CenterPointConfig & config, - const bool verbose) -: TensorRTWrapper(config, verbose), out_channel_sizes_(out_channel_sizes) + const std::vector & out_channel_sizes, const CenterPointConfig & config) +: TensorRTWrapper(config), out_channel_sizes_(out_channel_sizes) { } diff --git a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp index a175079ab0348..079c41d06c6e0 100644 --- a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp @@ -22,15 +22,21 @@ namespace centerpoint { -TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config, const bool verbose) -: config_(config), logger_(Logger(verbose)) +TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config) : config_(config) {} + +TensorRTWrapper::~TensorRTWrapper() { + context_.reset(); + runtime_.reset(); + plan_.reset(); + engine_.reset(); } bool TensorRTWrapper::init( const std::string & onnx_path, const std::string & engine_path, const std::string & precision) { - runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger_)); + runtime_ = + tensorrt_common::TrtUniquePtr(nvinfer1::createInferRuntime(logger_)); if (!runtime_) { std::cout << "Fail to create runtime" << std::endl; return false; @@ -55,7 +61,8 @@ bool TensorRTWrapper::createContext() return false; } - context_ = unique_ptr(engine_->createExecutionContext()); + context_ = + tensorrt_common::TrtUniquePtr(engine_->createExecutionContext()); if (!context_) { std::cout << "Fail to create context" << std::endl; return false; @@ -68,13 +75,15 @@ bool TensorRTWrapper::parseONNX( const std::string & onnx_path, const std::string & engine_path, const std::string & precision, const size_t workspace_size) { - auto builder = unique_ptr(nvinfer1::createInferBuilder(logger_)); + auto builder = + tensorrt_common::TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); if (!builder) { std::cout << "Fail to create builder" << std::endl; return false; } - auto config = unique_ptr(builder->createBuilderConfig()); + auto config = + tensorrt_common::TrtUniquePtr(builder->createBuilderConfig()); if (!config) { std::cout << "Fail to create config" << std::endl; return false; @@ -95,13 +104,15 @@ bool TensorRTWrapper::parseONNX( const auto flag = 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = unique_ptr(builder->createNetworkV2(flag)); + auto network = + tensorrt_common::TrtUniquePtr(builder->createNetworkV2(flag)); if (!network) { std::cout << "Fail to create network" << std::endl; return false; } - auto parser = unique_ptr(nvonnxparser::createParser(*network, logger_)); + auto parser = tensorrt_common::TrtUniquePtr( + nvonnxparser::createParser(*network, logger_)); parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); if (!setProfile(*builder, *network, *config)) { @@ -111,12 +122,13 @@ bool TensorRTWrapper::parseONNX( std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..." << std::endl; - plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + plan_ = tensorrt_common::TrtUniquePtr( + builder->buildSerializedNetwork(*network, *config)); if (!plan_) { std::cout << "Fail to create serialized network" << std::endl; return false; } - engine_ = unique_ptr( + engine_ = tensorrt_common::TrtUniquePtr( runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; @@ -136,22 +148,13 @@ bool TensorRTWrapper::saveEngine(const std::string & engine_path) bool TensorRTWrapper::loadEngine(const std::string & engine_path) { - std::ifstream file(engine_path, std::ios::in | std::ios::binary); - file.seekg(0, std::ifstream::end); - const size_t size = file.tellg(); - file.seekg(0, std::ifstream::beg); - - std::unique_ptr buffer{new char[size]}; - file.read(buffer.get(), size); - file.close(); - - if (!runtime_) { - std::cout << "Fail to load engine: Runtime isn't created" << std::endl; - return false; - } - - std::cout << "Loading from " << engine_path << std::endl; - engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size)); + std::ifstream engine_file(engine_path); + std::stringstream engine_buffer; + engine_buffer << engine_file.rdbuf(); + std::string engine_str = engine_buffer.str(); + engine_ = tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( + reinterpret_cast(engine_str.data()), engine_str.size())); + std::cout << "Loaded engine from " << engine_path << std::endl; return true; } diff --git a/perception/lidar_centerpoint/package.xml b/perception/lidar_centerpoint/package.xml index 970f69921c6e2..879013189b246 100644 --- a/perception/lidar_centerpoint/package.xml +++ b/perception/lidar_centerpoint/package.xml @@ -19,6 +19,7 @@ python3-open3d rclcpp rclcpp_components + tensorrt_common tf2_eigen tf2_geometry_msgs tier4_autoware_utils diff --git a/perception/lidar_centerpoint/src/node.cpp b/perception/lidar_centerpoint/src/node.cpp index da4000b450858..39683755bcaf0 100644 --- a/perception/lidar_centerpoint/src/node.cpp +++ b/perception/lidar_centerpoint/src/node.cpp @@ -121,6 +121,11 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } + + if (this->declare_parameter("build_only", false)) { + RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node."); + rclcpp::shutdown(); + } } void LidarCenterPointNode::pointCloudCallback( From c9f6ba2f1d0b1db7da6fa3bcd5528f2246c44384 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Mar 2023 16:15:26 +0900 Subject: [PATCH 036/121] refactor(lane change): lane change class rework (#3060) * refactor(lane change): lane change class rework Signed-off-by: Muhammad Zulfaqar * fix lane change module search Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/route_handler/include/route_handler/route_handler.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * Update planning/route_handler/include/route_handler/route_handler.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * set the COMPILE_WITH_OLD_ARCHITECTURE to true Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../behavior_path_planner/parameters.hpp | 5 +- .../lane_change/lane_change_module.hpp | 27 ++++--- .../scene_module/lane_change/manager.hpp | 9 ++- .../lane_change/lane_change_module_data.hpp | 5 ++ .../util/lane_change/util.hpp | 3 + .../src/behavior_path_planner_node.cpp | 38 ++++++++-- .../src/planner_manager.cpp | 2 +- .../lane_change/lane_change_module.cpp | 60 ++++++++++----- .../src/scene_module/lane_change/manager.cpp | 13 ++-- .../src/util/lane_change/util.cpp | 10 +++ .../include/route_handler/route_handler.hpp | 20 +++-- planning/route_handler/src/route_handler.cpp | 75 +++++++++++-------- 12 files changed, 181 insertions(+), 86 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 7df7c4c39fff0..8277ae102b312 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -33,7 +33,10 @@ struct BehaviorPathPlannerParameters ModuleConfigParameters config_pull_out; ModuleConfigParameters config_pull_over; ModuleConfigParameters config_side_shift; - ModuleConfigParameters config_lane_change; + ModuleConfigParameters config_lane_change_left; + ModuleConfigParameters config_lane_change_right; + ModuleConfigParameters config_external_lane_change_left; + ModuleConfigParameters config_external_lane_change_right; double backward_path_length; double forward_path_length; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp index 489dbfd3b5764..bbdc7c14435d7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp @@ -45,6 +45,7 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using marker_utils::CollisionCheckDebug; +using route_handler::Direction; using tier4_planning_msgs::msg::LaneChangeDebugMsg; using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; @@ -59,8 +60,7 @@ class LaneChangeModule : public SceneModuleInterface LaneChangeModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & rtc_interface_left, - const std::shared_ptr & rtc_interface_right); + const std::shared_ptr & rtc_interface, Direction direction); #endif bool isExecutionRequested() const override; bool isExecutionReady() const override; @@ -75,13 +75,7 @@ class LaneChangeModule : public SceneModuleInterface void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override; -#ifndef USE_OLD_ARCHITECTURE - void updateModuleParams(const std::shared_ptr & parameters) - { - parameters_ = parameters; - } -#endif - +#ifdef USE_OLD_ARCHITECTURE void publishRTCStatus() override { rtc_interface_left_->publishCooperateStatus(clock_->now()); @@ -110,6 +104,12 @@ class LaneChangeModule : public SceneModuleInterface rtc_interface_left_->unlockCommandUpdate(); rtc_interface_right_->unlockCommandUpdate(); } +#else + void updateModuleParams(const std::shared_ptr & parameters) + { + parameters_ = parameters; + } +#endif private: std::shared_ptr parameters_; @@ -125,16 +125,21 @@ class LaneChangeModule : public SceneModuleInterface bool is_abort_path_approved_{false}; bool is_abort_approval_requested_{false}; bool is_abort_condition_satisfied_{false}; - bool is_activated_ = false; + bool is_activated_{false}; +#ifdef USE_OLD_ARCHITECTURE std::shared_ptr rtc_interface_left_; std::shared_ptr rtc_interface_right_; UUID uuid_left_; UUID uuid_right_; UUID candidate_uuid_; +#else + Direction direction_{Direction::NONE}; +#endif void resetParameters(); +#ifdef USE_OLD_ARCHITECTURE void waitApprovalLeft(const double start_distance, const double finish_distance) { rtc_interface_left_->updateCooperateStatus( @@ -190,8 +195,8 @@ class LaneChangeModule : public SceneModuleInterface rtc_interface_right_->removeCooperateStatus(uuid_right_); } } +#endif - lanelet::ConstLanelets get_original_lanes() const; PathWithLaneId getReferencePath() const; lanelet::ConstLanelets getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index 87e5d42688d06..ecb2164855bb0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -33,23 +33,24 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface public: LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters); + std::shared_ptr parameters, Direction direction); std::shared_ptr createNewSceneModuleInstance() override { return std::make_shared( - name_, *node_, parameters_, rtc_interface_left_, rtc_interface_right_); + name_, *node_, parameters_, rtc_interface_, direction_); } void updateModuleParams(const std::vector & parameters) override; private: - std::shared_ptr rtc_interface_left_; - std::shared_ptr rtc_interface_right_; + std::shared_ptr rtc_interface_; std::shared_ptr parameters_; std::vector> registered_modules_; + + Direction direction_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp index 1d16f1bd84046..7ef20d546327b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp @@ -79,6 +79,11 @@ struct LaneChangeTargetObjectIndices std::vector target_lane{}; std::vector other_lane{}; }; + +enum class LaneChangeType { + Normal = 0, + ExternalRequest = 1, +}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__UTIL__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp index 76b0e4b8abb83..1efc82aca1ee8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp @@ -45,6 +45,7 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using marker_utils::CollisionCheckDebug; +using route_handler::Direction; using tier4_autoware_utils::Polygon2d; PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWithLaneId & path2); @@ -162,5 +163,7 @@ LaneChangeTargetObjectIndices filterObjectIndices( double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer = 0.0); +std::string getStrDirection(const std::string name, const Direction direction); + } // namespace behavior_path_planner::lane_change_utils #endif // BEHAVIOR_PATH_PLANNER__UTIL__LANE_CHANGE__UTIL_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 5ff95f26fdcad..be99d578e1856 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -234,10 +234,23 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod "side_shift", create_publisher(path_reference_name_space + "side_shift", 1)); } - if (p.config_lane_change.enable_module) { - const std::string module_topic = "lane_change"; + if (p.config_lane_change_left.enable_module) { + const std::string module_topic = "lane_change_left"; auto manager = std::make_shared( - this, module_topic, p.config_lane_change, lane_change_param_ptr_); + this, module_topic, p.config_lane_change_left, lane_change_param_ptr_, + route_handler::Direction::LEFT); + planner_manager_->registerSceneModuleManager(manager); + path_candidate_publishers_.emplace( + module_topic, create_publisher(path_candidate_name_space + module_topic, 1)); + path_reference_publishers_.emplace( + module_topic, create_publisher(path_reference_name_space + module_topic, 1)); + } + + if (p.config_lane_change_right.enable_module) { + const std::string module_topic = "lane_change_right"; + auto manager = std::make_shared( + this, module_topic, p.config_lane_change_right, lane_change_param_ptr_, + route_handler::Direction::RIGHT); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( module_topic, create_publisher(path_candidate_name_space + module_topic, 1)); @@ -316,12 +329,21 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() } { - const std::string ns = "lane_change."; - p.config_lane_change.enable_module = declare_parameter(ns + "enable_module"); - p.config_lane_change.enable_simultaneous_execution = + const std::string ns = "lane_change_left."; + p.config_lane_change_left.enable_module = declare_parameter(ns + "enable_module"); + p.config_lane_change_left.enable_simultaneous_execution = + declare_parameter(ns + "enable_simultaneous_execution"); + p.config_lane_change_left.priority = declare_parameter(ns + "priority"); + p.config_lane_change_left.max_module_size = declare_parameter(ns + "max_module_size"); + } + + { + const std::string ns = "lane_change_right."; + p.config_lane_change_right.enable_module = declare_parameter(ns + "enable_module"); + p.config_lane_change_right.enable_simultaneous_execution = declare_parameter(ns + "enable_simultaneous_execution"); - p.config_lane_change.priority = declare_parameter(ns + "priority"); - p.config_lane_change.max_module_size = declare_parameter(ns + "max_module_size"); + p.config_lane_change_right.priority = declare_parameter(ns + "priority"); + p.config_lane_change_right.max_module_size = declare_parameter(ns + "max_module_size"); } { diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index a90e1cef71cf8..767369904a466 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -281,7 +281,7 @@ BehaviorModuleOutput PlannerManager::update(const std::shared_ptr & if ((*itr)->getCurrentStatus() != ModuleStatus::RUNNING) { if (itr == approved_module_ptrs_.begin()) { // update root lanelet when the lane change is done. - if (name == "lane_change") { + if (name.find("lane_change") != std::string::npos) { root_lanelet_ = updateRootLanelet(data); } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index f9510ecd7e8e5..99c0ff5ddd467 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -31,15 +31,6 @@ #include #include -std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) -{ - std::stringstream ss; - for (auto i = 0; i < 16; ++i) { - ss << std::hex << std::setfill('0') << std::setw(2) << +uuid.uuid[i]; - } - return ss.str(); -} - namespace behavior_path_planner { using autoware_auto_perception_msgs::msg::ObjectClassification; @@ -60,15 +51,10 @@ LaneChangeModule::LaneChangeModule( LaneChangeModule::LaneChangeModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & rtc_interface_left, - const std::shared_ptr & rtc_interface_right) -: SceneModuleInterface{name, node}, - parameters_{parameters}, - rtc_interface_left_{rtc_interface_left}, - rtc_interface_right_{rtc_interface_right}, - uuid_left_{generateUUID()}, - uuid_right_{generateUUID()} + const std::shared_ptr & rtc_interface, Direction direction) +: SceneModuleInterface{name, node}, parameters_{parameters}, direction_{direction} { + rtc_interface_ptr_ = rtc_interface; steering_factor_interface_ptr_ = std::make_unique(&node, "lane_change"); } #endif @@ -107,6 +93,10 @@ bool LaneChangeModule::isExecutionRequested() const #endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); + if (lane_change_lanes.empty()) { + return false; + } + LaneChangePath selected_path; const auto [found_valid_path, found_safe_path] = getSafePath(lane_change_lanes, check_distance_, selected_path); @@ -128,6 +118,10 @@ bool LaneChangeModule::isExecutionReady() const #endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); + if (lane_change_lanes.empty()) { + return false; + } + LaneChangePath selected_path; const auto [found_valid_path, found_safe_path] = getSafePath(lane_change_lanes, check_distance_, selected_path); @@ -218,6 +212,7 @@ BehaviorModuleOutput LaneChangeModule::plan() void LaneChangeModule::resetPathIfAbort() { if (!is_abort_approval_requested_) { +#ifdef USE_OLD_ARCHITECTURE const auto lateral_shift = lane_change_utils::getLateralShift(*abort_path_); if (lateral_shift > 0.0) { removePreviousRTCStatusRight(); @@ -226,6 +221,9 @@ void LaneChangeModule::resetPathIfAbort() removePreviousRTCStatusLeft(); uuid_left_ = generateUUID(); } +#else + removeRTCStatus(); +#endif RCLCPP_DEBUG(getLogger(), "[abort] uuid is reset to request abort approval."); is_abort_approval_requested_ = true; is_abort_path_approved_ = false; @@ -257,6 +255,10 @@ CandidateOutput LaneChangeModule::planCandidate() const #endif const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); + if (lane_change_lanes.empty()) { + return output; + } + #ifdef USE_OLD_ARCHITECTURE [[maybe_unused]] const auto [found_valid_path, found_safe_path] = getSafePath(lane_change_lanes, check_distance_, selected_path); @@ -308,9 +310,15 @@ BehaviorModuleOutput LaneChangeModule::planWaitingApproval() const auto candidate = planCandidate(); path_candidate_ = std::make_shared(candidate.path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; +#ifdef USE_OLD_ARCHITECTURE updateRTCStatus(candidate); waitApproval(); +#else + updateRTCStatus( + candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); +#endif is_abort_path_approved_ = false; + return out; } @@ -416,7 +424,11 @@ lanelet::ConstLanelets LaneChangeModule::getLaneChangeLanes( lanelet::ConstLanelets current_check_lanes = route_handler->getLaneletSequence(current_lane, current_pose, 0.0, lane_change_prepare_length); lanelet::ConstLanelet lane_change_lane; +#ifdef USE_OLD_ARCHITECTURE if (route_handler->getLaneChangeTarget(current_check_lanes, &lane_change_lane)) { +#else + if (route_handler->getLaneChangeTarget(current_check_lanes, &lane_change_lane, direction_)) { +#endif lane_change_lanes = route_handler->getLaneletSequence( lane_change_lane, current_pose, lane_change_lane_length, lane_change_lane_length); } else { @@ -667,13 +679,14 @@ std::shared_ptr LaneChangeModule::get_debug_msg_array() void LaneChangeModule::updateSteeringFactorPtr(const BehaviorModuleOutput & output) { - const auto turn_signal_info = output.turn_signal_info; const auto current_pose = getEgoPose(); const double start_distance = motion_utils::calcSignedArcLength( output.path->points, current_pose.position, status_.lane_change_path.shift_line.start.position); const double finish_distance = motion_utils::calcSignedArcLength( output.path->points, current_pose.position, status_.lane_change_path.shift_line.end.position); +#ifdef USE_OLD_ARCHITECTURE + const auto turn_signal_info = output.turn_signal_info; const uint16_t steering_factor_direction = std::invoke([this, &start_distance, &finish_distance, &turn_signal_info]() { if (turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { @@ -686,6 +699,17 @@ void LaneChangeModule::updateSteeringFactorPtr(const BehaviorModuleOutput & outp } return SteeringFactor::UNKNOWN; }); +#else + const auto steering_factor_direction = std::invoke([&]() { + if (direction_ == Direction::LEFT) { + return SteeringFactor::LEFT; + } + if (direction_ == Direction::RIGHT) { + return SteeringFactor::RIGHT; + } + return SteeringFactor::UNKNOWN; + }); +#endif // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( 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 79bc075de2ffe..13bb4c7db5b4c 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 @@ -23,14 +23,15 @@ namespace behavior_path_planner { - +using route_handler::Direction; LaneChangeModuleManager::LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters) -: SceneModuleManagerInterface(node, name, config), parameters_{std::move(parameters)} + std::shared_ptr parameters, Direction direction) +: SceneModuleManagerInterface(node, name, config), + parameters_{std::move(parameters)}, + direction_{direction} { - rtc_interface_left_ = std::make_shared(node, name + "_left"); - rtc_interface_right_ = std::make_shared(node, name + "_right"); + rtc_interface_ = std::make_shared(node, name); } void LaneChangeModuleManager::updateModuleParams( @@ -40,7 +41,7 @@ void LaneChangeModuleManager::updateModuleParams( [[maybe_unused]] auto p = parameters_; - [[maybe_unused]] std::string ns = "lane_change."; + [[maybe_unused]] const std::string ns = name_ + "."; // updateParam(parameters, ns + ..., ...); std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index 3bd7549bf3677..550185992f1a5 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -1163,4 +1163,14 @@ double calcLateralBufferForFiltering(const double vehicle_width, const double la return lateral_buffer + 0.5 * vehicle_width; } +std::string getStrDirection(const std::string & name, const Direction direction) +{ + if (direction == Direction::LEFT) { + return name + "_left"; + } + if (direction == Direction::RIGHT) { + return name + "_right"; + } + return ""; +} } // namespace behavior_path_planner::lane_change_utils diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 52f8082f125e4..89e052b439f78 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -54,7 +54,7 @@ using std_msgs::msg::Header; using unique_identifier_msgs::msg::UUID; using RouteSections = std::vector; -enum class LaneChangeDirection { NONE, LEFT, RIGHT }; +enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; @@ -259,9 +259,19 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, const double length, const lanelet::ConstLanelets & exclude_lanelets = {}) const; - int getNumLaneToPreferredLane(const lanelet::ConstLanelet & lanelet) const; + /** + * Query input lanelet to see whether it exist in the preferred lane. If it doesn't exist, return + * the number of lane-changeable lane to the preferred lane. + * @param Desired lanelet to query + * @param lane change direction + * @return number of lanes from input to the preferred lane + */ + int getNumLaneToPreferredLane( + const lanelet::ConstLanelet & lanelet, const Direction direction = Direction::NONE) const; + bool getClosestLaneletWithinRoute( const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const; + lanelet::ConstLanelet getLaneletsFromId(const lanelet::Id id) const; lanelet::ConstLanelets getLaneletsFromIds(const lanelet::Ids & ids) const; lanelet::ConstLanelets getLaneletSequence( @@ -287,7 +297,8 @@ class RouteHandler const lanelet::ConstLanelets & lanelet_sequence, const double s_start, const double s_end, bool use_exact = true) const; bool getLaneChangeTarget( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; + const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet, + const Direction direction = Direction::NONE) const; bool getRightLaneChangeTargetExceptPreferredLane( const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; bool getLeftLaneChangeTargetExceptPreferredLane( @@ -298,8 +309,7 @@ class RouteHandler static bool getPullOutStartLane( const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width, lanelet::ConstLanelet * target_lanelet); - double getLaneChangeableDistance( - const Pose & current_pose, const LaneChangeDirection & direction) const; + double getLaneChangeableDistance(const Pose & current_pose, const Direction & direction) const; lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; private: diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index d2ea4c65adaa9..2fe8e3549b661 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1106,30 +1106,33 @@ std::vector RouteHandler::getPrecedingLaneletSequence( } bool RouteHandler::getLaneChangeTarget( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const + const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet, + const Direction direction) const { for (const auto & lanelet : lanelets) { - const int num = getNumLaneToPreferredLane(lanelet); + const int num = getNumLaneToPreferredLane(lanelet, direction); if (num == 0) { continue; } - if (num < 0) { - if (!!routing_graph_ptr_->right(lanelet)) { - const auto right_lanelet = routing_graph_ptr_->right(lanelet); - *target_lanelet = right_lanelet.get(); - return true; + if (direction == Direction::NONE || direction == Direction::RIGHT) { + if (num < 0) { + if (!!routing_graph_ptr_->right(lanelet)) { + const auto right_lanelet = routing_graph_ptr_->right(lanelet); + *target_lanelet = right_lanelet.get(); + return true; + } } - continue; } - if (num > 0) { - if (!!routing_graph_ptr_->left(lanelet)) { - const auto left_lanelet = routing_graph_ptr_->left(lanelet); - *target_lanelet = left_lanelet.get(); - return true; + if (direction == Direction::NONE || direction == Direction::LEFT) { + if (num > 0) { + if (!!routing_graph_ptr_->left(lanelet)) { + const auto left_lanelet = routing_graph_ptr_->left(lanelet); + *target_lanelet = left_lanelet.get(); + return true; + } } - continue; } } @@ -1212,26 +1215,34 @@ lanelet::ConstLanelets RouteHandler::getClosestLaneletSequence(const Pose & pose return getLaneletSequence(lanelet); } -int RouteHandler::getNumLaneToPreferredLane(const lanelet::ConstLanelet & lanelet) const +int RouteHandler::getNumLaneToPreferredLane( + const lanelet::ConstLanelet & lanelet, const Direction direction) const { - int num = 0; if (exists(preferred_lanelets_, lanelet)) { - return num; + return 0; } - const auto & right_lanes = - lanelet::utils::query::getAllNeighborsRight(routing_graph_ptr_, lanelet); - for (const auto & right : right_lanes) { - num--; - if (exists(preferred_lanelets_, right)) { - return num; + + if ((direction == Direction::NONE) || (direction == Direction::RIGHT)) { + int num{0}; + const auto & right_lanes = + lanelet::utils::query::getAllNeighborsRight(routing_graph_ptr_, lanelet); + for (const auto & right : right_lanes) { + num--; + if (exists(preferred_lanelets_, right)) { + return num; + } } } - const auto & left_lanes = lanelet::utils::query::getAllNeighborsLeft(routing_graph_ptr_, lanelet); - num = 0; - for (const auto & left : left_lanes) { - num++; - if (exists(preferred_lanelets_, left)) { - return num; + + if ((direction == Direction::NONE) || (direction == Direction::LEFT)) { + const auto & left_lanes = + lanelet::utils::query::getAllNeighborsLeft(routing_graph_ptr_, lanelet); + int num = 0; + for (const auto & left : left_lanes) { + num++; + if (exists(preferred_lanelets_, left)) { + return num; + } } } @@ -1368,7 +1379,7 @@ lanelet::ConstLanelets RouteHandler::getLaneChangeTargetLanes(const Pose & pose) } double RouteHandler::getLaneChangeableDistance( - const Pose & current_pose, const LaneChangeDirection & direction) const + const Pose & current_pose, const Direction & direction) const { lanelet::ConstLanelet current_lane; if (!getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { @@ -1382,12 +1393,12 @@ double RouteHandler::getLaneChangeableDistance( double accumulated_distance = 0; for (const auto & lane : lanelet_sequence) { lanelet::ConstLanelet target_lane; - if (direction == LaneChangeDirection::RIGHT) { + if (direction == Direction::RIGHT) { if (!getRightLaneletWithinRoute(lane, &target_lane)) { break; } } - if (direction == LaneChangeDirection::LEFT) { + if (direction == Direction::LEFT) { if (!getLeftLaneletWithinRoute(lane, &target_lane)) { break; } From b0ead6babde7c4cd6b47db9e80b7ef55b43a0eba Mon Sep 17 00:00:00 2001 From: NorahXiong <103234047+NorahXiong@users.noreply.github.com> Date: Tue, 14 Mar 2023 16:18:55 +0800 Subject: [PATCH 037/121] =?UTF-8?q?fix(freespace=5Fplanning=5Falgorithms):?= =?UTF-8?q?=20remove=20duplicate=20candidates=20in=20tr=E2=80=A6=20(#2355)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix(freespace_planning_algorithms): remove duplicate candidates in transition table Signed-off-by: NorahXiong --- planning/freespace_planning_algorithms/src/astar_search.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/freespace_planning_algorithms/src/astar_search.cpp b/planning/freespace_planning_algorithms/src/astar_search.cpp index 5686d7eee26e0..b2b2321adacd0 100644 --- a/planning/freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/freespace_planning_algorithms/src/astar_search.cpp @@ -76,13 +76,13 @@ AstarSearch::TransitionTable createTransitionTable( const auto & R_min = minimum_turning_radius; const auto & R_max = maximum_turning_radius; const double step_min = R_min * dtheta; - const double dR = (R_max - R_min) / turning_radius_size; + const double dR = (R_max - R_min) / std::max(turning_radius_size - 1, 1); // NodeUpdate actions std::vector forward_node_candidates; const NodeUpdate forward_straight{step_min, 0.0, 0.0, step_min, false, false}; forward_node_candidates.push_back(forward_straight); - for (int i = 0; i < turning_radius_size + 1; ++i) { + for (int i = 0; i < turning_radius_size; ++i) { double R = R_min + i * dR; double step = R * dtheta; const NodeUpdate forward_left{ From 07b7837d42309376dc55bf576e9bcba1497c1799 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 14 Mar 2023 17:33:18 +0900 Subject: [PATCH 038/121] feat(pose_initializer): enable pose initialization while running (only for sim) (#3038) * feat(pose_initializer): enable pose initialization while running (only for sim) Signed-off-by: kminoda * both logsim and psim params Signed-off-by: kminoda * only one pose_initializer_param_path arg Signed-off-by: kminoda * use two param files for pose_initializer Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .../launch/localization.launch.xml | 2 ++ .../launch/util/util.launch.xml | 6 ++-- .../launch/simulator.launch.xml | 8 +++--- .../launch/system.launch.xml | 3 +- .../config/pose_initializer.param.yaml | 26 +++-------------- .../config/pose_initializer_common.param.yaml | 26 +++++++++++++++++ .../launch/pose_initializer.launch.xml | 12 ++------ .../config/topics.yaml | 28 +++++++++---------- 8 files changed, 56 insertions(+), 55 deletions(-) create mode 100644 localization/pose_initializer/config/pose_initializer_common.param.yaml diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index 14fe9c55f7e5d..12ad512557cb1 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -6,6 +6,8 @@ + + diff --git a/launch/tier4_localization_launch/launch/util/util.launch.xml b/launch/tier4_localization_launch/launch/util/util.launch.xml index d820e06deb614..31a453c082522 100644 --- a/launch/tier4_localization_launch/launch/util/util.launch.xml +++ b/launch/tier4_localization_launch/launch/util/util.launch.xml @@ -14,10 +14,8 @@ - - - - + + diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 9769a6a36332f..70b77eb60cb12 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -2,6 +2,8 @@ + + @@ -98,10 +100,8 @@ - - - - + + diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 8e674b0435528..016d613cfa72d 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -21,7 +21,7 @@ - + @@ -66,6 +66,7 @@ + diff --git a/localization/pose_initializer/config/pose_initializer.param.yaml b/localization/pose_initializer/config/pose_initializer.param.yaml index e94f86c8d6c7e..c1486b71aae9c 100644 --- a/localization/pose_initializer/config/pose_initializer.param.yaml +++ b/localization/pose_initializer/config/pose_initializer.param.yaml @@ -1,24 +1,6 @@ /**: ros__parameters: - - # from gnss - gnss_particle_covariance: - [ - 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 10.0, - ] - - # output - output_pose_covariance: - [ - 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, - ] + gnss_enabled: true + ndt_enabled: true + ekf_enabled: true + stop_check_enabled: true diff --git a/localization/pose_initializer/config/pose_initializer_common.param.yaml b/localization/pose_initializer/config/pose_initializer_common.param.yaml new file mode 100644 index 0000000000000..a05cc7c35cb1a --- /dev/null +++ b/localization/pose_initializer/config/pose_initializer_common.param.yaml @@ -0,0 +1,26 @@ +/**: + ros__parameters: + gnss_pose_timeout: 3.0 # [sec] + stop_check_duration: 3.0 # [sec] + + # from gnss + gnss_particle_covariance: + [ + 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 10.0, + ] + + # output + output_pose_covariance: + [ + 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, + ] diff --git a/localization/pose_initializer/launch/pose_initializer.launch.xml b/localization/pose_initializer/launch/pose_initializer.launch.xml index 9483ff47bc093..6558b578e6386 100644 --- a/localization/pose_initializer/launch/pose_initializer.launch.xml +++ b/localization/pose_initializer/launch/pose_initializer.launch.xml @@ -1,20 +1,12 @@ + - - - - + - - - - - - diff --git a/system/component_state_monitor/config/topics.yaml b/system/component_state_monitor/config/topics.yaml index 5a5f2e880bcae..c00203dbb6073 100644 --- a/system/component_state_monitor/config/topics.yaml +++ b/system/component_state_monitor/config/topics.yaml @@ -1,5 +1,5 @@ - module: map - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: launch args: node_name_suffix: vector_map @@ -12,7 +12,7 @@ timeout: 0.0 - module: map - mode: [online] + mode: [online, logging_simulation] type: launch args: node_name_suffix: pointcloud_map @@ -25,7 +25,7 @@ timeout: 0.0 - module: localization - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: initialpose3d @@ -38,7 +38,7 @@ timeout: 0.0 - module: localization - mode: [online] + mode: [online, logging_simulation] type: autonomous args: node_name_suffix: pose_twist_fusion_filter_pose @@ -51,7 +51,7 @@ timeout: 1.0 - module: perception - mode: [online] + mode: [online, logging_simulation] type: launch args: node_name_suffix: obstacle_segmentation_pointcloud @@ -64,7 +64,7 @@ timeout: 1.0 - module: perception - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: object_recognition_objects @@ -77,7 +77,7 @@ timeout: 1.0 - module: planning - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: mission_planning_route @@ -90,7 +90,7 @@ timeout: 0.0 - module: planning - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: scenario_planning_trajectory @@ -103,7 +103,7 @@ timeout: 1.0 - module: control - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: trajectory_follower_control_cmd @@ -116,7 +116,7 @@ timeout: 1.0 - module: control - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: control_command_control_cmd @@ -129,7 +129,7 @@ timeout: 1.0 - module: vehicle - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: vehicle_status_velocity_status @@ -142,7 +142,7 @@ timeout: 1.0 - module: vehicle - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: vehicle_status_steering_status @@ -155,7 +155,7 @@ timeout: 1.0 - module: system - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: launch args: node_name_suffix: system_emergency_control_cmd @@ -168,7 +168,7 @@ timeout: 1.0 - module: localization - mode: [online, planning_simulation] + mode: [online, logging_simulation, planning_simulation] type: autonomous args: node_name_suffix: transform_map_to_base_link From 7a0f84ce6a03b7f7b0449dbd2dbcf2091f26aa68 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 14 Mar 2023 18:02:13 +0900 Subject: [PATCH 039/121] feat(probablisitic_occupancy_grid_map): add scan_frame option for gridmap generation (#3032) * add scan_frame and raytrace center Signed-off-by: yoshiri * add scan frame to laserscan based method Signed-off-by: yoshiri * update readme Signed-off-by: yoshiri * fix typo Signed-off-by: yoshiri * update laucher in perception_launch Signed-off-by: yoshiri * fix config and launch file Signed-off-by: yoshiri * fixed laserscan based launcher Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- ...serscan_based_occupancy_grid_map.launch.py | 64 ++++++++------- ...ntcloud_based_occupancy_grid_map.launch.py | 60 ++++++++------ .../launch/perception.launch.xml | 1 + .../CMakeLists.txt | 1 + .../README.md | 10 ++- ...erscan_based_occupancy_grid_map.param.yaml | 6 +- ...tcloud_based_occupancy_grid_map.param.yaml | 8 +- .../image/gridmap_frame_settings.drawio.svg | 80 +++++++++++++++++++ ...aserscan_based_occupancy_grid_map_node.hpp | 3 +- .../occupancy_grid_map.hpp | 2 +- ...intcloud_based_occupancy_grid_map_node.hpp | 3 +- ...serscan_based_occupancy_grid_map.launch.py | 79 +++++++++--------- ...ntcloud_based_occupancy_grid_map.launch.py | 64 +++++++-------- ...aserscan_based_occupancy_grid_map_node.cpp | 37 ++++++--- .../occupancy_grid_map.cpp | 57 ++++++++++--- ...intcloud_based_occupancy_grid_map_node.cpp | 24 ++++-- 16 files changed, 329 insertions(+), 170 deletions(-) create mode 100644 perception/probabilistic_occupancy_grid_map/image/gridmap_frame_settings.drawio.svg diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py index d371fa43986ab..7ed97fe6c0ebd 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py @@ -14,6 +14,7 @@ from launch import LaunchDescription from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition @@ -21,22 +22,19 @@ from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +import yaml -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), +def launch_setup(context, *args, **kwargs): + # load parameter files + param_file = LaunchConfiguration("param_file").perform(context) + with open(param_file, "r") as f: + laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] + laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool( + LaunchConfiguration("input_obstacle_pointcloud").perform(context) ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), + laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool( + LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context) ) composable_nodes = [ @@ -53,7 +51,9 @@ def add_launch_arg(name: str, default_value=None): ], parameters=[ { - "target_frame": "base_link", # Leave disabled to output scan in pointcloud frame + "target_frame": laserscan_based_occupancy_grid_map_node_params[ + "scan_origin_frame" + ], # Leave disabled to output scan in pointcloud frame "transform_tolerance": 0.01, "min_height": 0.0, "max_height": 2.0, @@ -85,16 +85,7 @@ def add_launch_arg(name: str, default_value=None): ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], - parameters=[ - { - "map_resolution": 0.5, - "use_height_filter": True, - "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), - "input_obstacle_and_raw_pointcloud": LaunchConfiguration( - "input_obstacle_and_raw_pointcloud" - ), - } - ], + parameters=[laserscan_based_occupancy_grid_map_node_params], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ] @@ -115,6 +106,25 @@ def add_launch_arg(name: str, default_value=None): condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) + return [occupancy_grid_map_container, load_composable_nodes] + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + return LaunchDescription( [ add_launch_arg("use_multithread", "false"), @@ -128,11 +138,11 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output/stixel", "virtual_scan/stixel"), add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), - add_launch_arg("use_pointcloud_container", "False"), + add_launch_arg("param_file", "config/laserscan_based_occupancy_grid_map.param.yaml"), + add_launch_arg("use_pointcloud_container", "false"), add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, ] + + [OpaqueFunction(function=launch_setup)] ) diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py b/launch/tier4_perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py index 2feefdfb1053d..e8a9e173cfe0a 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py @@ -14,6 +14,7 @@ from launch import LaunchDescription from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition @@ -21,23 +22,16 @@ from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +import yaml -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) +def launch_setup(context, *args, **kwargs): + # load parameter files + param_file = LaunchConfiguration("param_file").perform(context) + with open(param_file, "r") as f: + pointcloud_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"][ + "ros__parameters" + ] composable_nodes = [ ComposableNode( @@ -49,12 +43,7 @@ def add_launch_arg(name: str, default_value=None): ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], - parameters=[ - { - "map_resolution": 0.5, - "use_height_filter": True, - } - ], + parameters=[pointcloud_based_occupancy_grid_map_node_params], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ] @@ -75,18 +64,37 @@ def add_launch_arg(name: str, default_value=None): condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) + return [occupancy_grid_map_container, load_composable_nodes] + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + return LaunchDescription( [ - add_launch_arg("use_multithread", "False"), - add_launch_arg("use_intra_process", "True"), - add_launch_arg("use_pointcloud_container", "False"), + add_launch_arg("use_multithread", "false"), + add_launch_arg("use_intra_process", "true"), + add_launch_arg("use_pointcloud_container", "false"), add_launch_arg("container_name", "occupancy_grid_map_container"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), add_launch_arg("output", "occupancy_grid"), + add_launch_arg("param_file", "config/pointcloud_based_occupancy_grid_map.param.yaml"), set_container_executable, set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, ] + + [OpaqueFunction(function=launch_setup)] ) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index ffc6f908983bb..b2a800c5b278d 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -76,6 +76,7 @@ + diff --git a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt index 89906f86c5ce5..df0090d1b6cee 100644 --- a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt @@ -48,4 +48,5 @@ rclcpp_components_register_node(laserscan_based_occupancy_grid_map ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/perception/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md index 655846f5cade1..d0fa909d58b40 100644 --- a/perception/probabilistic_occupancy_grid_map/README.md +++ b/perception/probabilistic_occupancy_grid_map/README.md @@ -9,7 +9,9 @@ This package outputs the probability of having an obstacle as occupancy grid map Occupancy grid map is generated on `map_frame`, and grid orientation is fixed. -You may need to choose `output_frame` which means grid map origin. Default is `base_link`, but your main LiDAR sensor frame (e.g. `velodyne_top` in sample_vehicle) would be the better choice. +You may need to choose `scan_origin_frame` and `gridmap_origin_frame` which means sensor origin and gridmap origin respectively. Especially, set your main LiDAR sensor frame (e.g. `velodyne_top` in sample_vehicle) as a `scan_origin_frame` would result in better performance. + +![image_for_frame_parameter_visualization](./image/gridmap_frame_settings.drawio.svg) ### Each config paramters @@ -21,7 +23,8 @@ Config parameters are managed in `config/*.yaml` and here shows its outline. | --------------------------------- | ------------- | | map_frame | "map" | | base_link_frame | "base_link" | -| output_frame | "base_link" | +| scan_origin_frame | "base_link" | +| gridmap_origin_frame | "base_link" | | use_height_filter | true | | enable_single_frame_mode | false | | map_length | 100.0 [m] | @@ -40,7 +43,8 @@ Config parameters are managed in `config/*.yaml` and here shows its outline. | enable_single_frame_mode | false | | map_frame | "map" | | base_link_frame | "base_link" | -| output_frame | "base_link" | +| scan_origin_frame | "base_link" | +| gridmap_origin_frame | "base_link" | ## References/External links diff --git a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml index c3e498b3e3320..8c8f1857ce279 100644 --- a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml @@ -2,8 +2,10 @@ ros__parameters: map_frame: "map" base_link_frame: "base_link" - output_frame: "base_link" - # using top of the main lidar frame is appropriate. ex) velodyne_top + # center of the grid map + gridmap_origin_frame: "base_link" + # ray-tracing center: main sensor frame is preferable like: "velodyne_top" + scan_origin_frame: "base_link" use_height_filter: true enable_single_frame_mode: false diff --git a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 3b84200d118af..49a1a7097d308 100644 --- a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - map_length: 100 # [m] + map_length: 100.0 # [m] map_resolution: 0.5 # [m] use_height_filter: true @@ -9,5 +9,7 @@ # grid map coordinate map_frame: "map" base_link_frame: "base_link" - output_frame: "base_link" - # center of grid_map. Main LiDAR frame is preferable like: "velodyne_top" + # center of the grid map + gridmap_origin_frame: "base_link" + # ray-tracing center: main sensor frame is preferable like: "velodyne_top" + scan_origin_frame: "base_link" diff --git a/perception/probabilistic_occupancy_grid_map/image/gridmap_frame_settings.drawio.svg b/perception/probabilistic_occupancy_grid_map/image/gridmap_frame_settings.drawio.svg new file mode 100644 index 0000000000000..d1aaaa2c51176 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/image/gridmap_frame_settings.drawio.svg @@ -0,0 +1,80 @@ + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ scan_origin_frame +
+
+
+
+ scan_origin_frame +
+
+ + + +
+
+
+ gridmap_origin_frame +
+
+
+
+ gridmap_origin_frame +
+
+ + + + +
+
+
+ gridmap_origin = center of the gridmap +
+
+
+
+ gridmap_origin = center of the gridmap +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp index 857d657618d20..fbef72e29e0f2 100644 --- a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp @@ -92,7 +92,8 @@ class LaserscanBasedOccupancyGridMapNode : public rclcpp::Node // ROS Parameters std::string map_frame_; std::string base_link_frame_; - std::string output_frame_; + std::string gridmap_origin_frame_; + std::string scan_origin_frame_; bool use_height_filter_; bool enable_single_frame_mode_; }; diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp index a8def3560f86f..88f2cfbc146f3 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp @@ -72,7 +72,7 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D void updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, - const Pose & robot_pose, const Pose & gridmap_origin); + const Pose & robot_pose, const Pose & scan_origin); void updateOrigin(double new_origin_x, double new_origin_y) override; diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index 68aed57677909..5b7571fa8abcc 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -82,7 +82,8 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node // ROS Parameters std::string map_frame_; std::string base_link_frame_; - std::string output_frame_; + std::string gridmap_origin_frame_; + std::string scan_origin_frame_; bool use_height_filter_; bool enable_single_frame_mode_; }; diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py index 1e7bbef48338c..7ed97fe6c0ebd 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py @@ -12,15 +12,11 @@ # See the License for the specific language governing permissions and # limitations under the License. -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import LaunchConfigurationNotEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -29,29 +25,17 @@ import yaml -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - +def launch_setup(context, *args, **kwargs): # load parameter files - param_file = os.path.join( - get_package_share_directory("probablistic_occupancy_grid_map"), - "config/laserscan_based_occupancy_grid_map.param.yaml", - ) + param_file = LaunchConfiguration("param_file").perform(context) with open(param_file, "r") as f: laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] + laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool( + LaunchConfiguration("input_obstacle_pointcloud").perform(context) + ) + laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool( + LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context) + ) composable_nodes = [ ComposableNode( @@ -68,7 +52,7 @@ def add_launch_arg(name: str, default_value=None): parameters=[ { "target_frame": laserscan_based_occupancy_grid_map_node_params[ - "output_frame" + "scan_origin_frame" ], # Leave disabled to output scan in pointcloud frame "transform_tolerance": 0.01, "min_height": 0.0, @@ -101,37 +85,48 @@ def add_launch_arg(name: str, default_value=None): ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], - parameters=[ - { - "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), - "input_obstacle_and_raw_pointcloud": LaunchConfiguration( - "input_obstacle_and_raw_pointcloud" - ), - }.update(laserscan_based_occupancy_grid_map_node_params) - ], + parameters=[laserscan_based_occupancy_grid_map_node_params], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ] occupancy_grid_map_container = ComposableNodeContainer( - condition=LaunchConfigurationEquals("container", ""), - name="occupancy_grid_map_container", + name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals("container", ""), composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container"), + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + return [occupancy_grid_map_container, load_composable_nodes] + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) return LaunchDescription( [ - add_launch_arg("container", ""), add_launch_arg("use_multithread", "false"), add_launch_arg("use_intra_process", "false"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), @@ -143,9 +138,11 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output/stixel", "virtual_scan/stixel"), add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), + add_launch_arg("param_file", "config/laserscan_based_occupancy_grid_map.param.yaml"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, ] + + [OpaqueFunction(function=launch_setup)] ) diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index af5ecdfa02873..e8a9e173cfe0a 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -12,15 +12,11 @@ # See the License for the specific language governing permissions and # limitations under the License. -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import LaunchConfigurationNotEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -29,27 +25,9 @@ import yaml -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - +def launch_setup(context, *args, **kwargs): # load parameter files - param_file = os.path.join( - get_package_share_directory("probablistic_occupancy_grid_map"), - "config/pointcloud_based_occupancy_grid_map.param.yaml", - ) + param_file = LaunchConfiguration("param_file").perform(context) with open(param_file, "r") as f: pointcloud_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"][ "ros__parameters" @@ -71,32 +49,52 @@ def add_launch_arg(name: str, default_value=None): ] occupancy_grid_map_container = ComposableNodeContainer( - condition=LaunchConfigurationEquals("container", ""), - name="occupancy_grid_map_container", + name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals("container", ""), composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container"), + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + return [occupancy_grid_map_container, load_composable_nodes] + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) return LaunchDescription( [ - add_launch_arg("container", ""), add_launch_arg("use_multithread", "false"), - add_launch_arg("use_intra_process", "false"), + add_launch_arg("use_intra_process", "true"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("container_name", "occupancy_grid_map_container"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), add_launch_arg("output", "occupancy_grid"), + add_launch_arg("param_file", "config/pointcloud_based_occupancy_grid_map.param.yaml"), set_container_executable, set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, ] + + [OpaqueFunction(function=launch_setup)] ) diff --git a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp index b65dfb97e2f84..2ded71a0ec0b4 100644 --- a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp @@ -93,6 +93,18 @@ bool cropPointcloudByHeight( pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); return pose; } + +geometry_msgs::msg::Pose getPose( + const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, + const std::string & source_frame, const std::string & target_frame) +{ + geometry_msgs::msg::Pose pose; + geometry_msgs::msg::TransformStamped tf_stamped; + tf_stamped = + tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); + pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); + return pose; +} } // namespace namespace occupancy_grid_map @@ -112,7 +124,8 @@ LaserscanBasedOccupancyGridMapNode::LaserscanBasedOccupancyGridMapNode( /* params */ map_frame_ = declare_parameter("map_frame", "map"); base_link_frame_ = declare_parameter("base_link_frame", "base_link"); - output_frame_ = declare_parameter("output_frame", "base_link"); + gridmap_origin_frame_ = declare_parameter("gridmap_origin_frame", "base_link"); + scan_origin_frame_ = declare_parameter("scan_origin_frame", "base_link"); use_height_filter_ = declare_parameter("use_height_filter", true); enable_single_frame_mode_ = declare_parameter("enable_single_frame_mode", false); const double map_length{declare_parameter("map_length", 100.0)}; @@ -209,17 +222,15 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa PointCloud2 trans_laserscan_pc{}; PointCloud2 trans_obstacle_pc{}; PointCloud2 trans_raw_pc{}; - Pose pose{}; + Pose gridmap_origin{}; + Pose scan_origin{}; try { transformPointcloud(*laserscan_pc_ptr, *tf2_, map_frame_, trans_laserscan_pc); transformPointcloud(filtered_obstacle_pc, *tf2_, map_frame_, trans_obstacle_pc); transformPointcloud(filtered_raw_pc, *tf2_, map_frame_, trans_raw_pc); - // pose = getPose(laserscan_pc_ptr->header, *tf2_, map_frame_); - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2_->lookupTransform( - map_frame_, output_frame_, laserscan_pc_ptr->header.stamp, - rclcpp::Duration::from_seconds(0.5)); - pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); + gridmap_origin = + getPose(laserscan_pc_ptr->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + scan_origin = getPose(laserscan_pc_ptr->header.stamp, *tf2_, scan_origin_frame_, map_frame_); } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(get_logger(), ex.what()); return; @@ -231,16 +242,16 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa occupancy_grid_map_updater_ptr_->getSizeInCellsY(), occupancy_grid_map_updater_ptr_->getResolution()); single_frame_occupancy_grid_map.updateOrigin( - pose.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, - pose.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); + gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, + gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); single_frame_occupancy_grid_map.updateFreespaceCells(trans_raw_pc); - single_frame_occupancy_grid_map.raytrace2D(trans_laserscan_pc, pose); + single_frame_occupancy_grid_map.raytrace2D(trans_laserscan_pc, scan_origin); single_frame_occupancy_grid_map.updateOccupiedCells(trans_obstacle_pc); if (enable_single_frame_mode_) { // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( - map_frame_, laserscan_pc_ptr->header.stamp, pose.position.z, + map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, single_frame_occupancy_grid_map)); } else { // Update with bayes filter @@ -248,7 +259,7 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( - map_frame_, laserscan_pc_ptr->header.stamp, pose.position.z, + map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, *occupancy_grid_map_updater_ptr_)); } } diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp index 213db4330f850..b6b69ebf44391 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp @@ -81,6 +81,30 @@ void transformPointcloud( output.header.stamp = input.header.stamp; output.header.frame_id = ""; } + +/** + * @brief Get the Inverse Pose object + * + * @param input + * @return geometry_msgs::msg::Pose inverted pose + */ +geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose) +{ + tf2::Vector3 position(pose.position.x, pose.position.y, pose.position.z); + tf2::Quaternion orientation( + pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); + tf2::Transform tf(orientation, position); + const auto inv_tf = tf.inverse(); + geometry_msgs::msg::Pose inv_pose; + inv_pose.position.x = inv_tf.getOrigin().x(); + inv_pose.position.y = inv_tf.getOrigin().y(); + inv_pose.position.z = inv_tf.getOrigin().z(); + inv_pose.orientation.x = inv_tf.getRotation().x(); + inv_pose.orientation.y = inv_tf.getRotation().y(); + inv_pose.orientation.z = inv_tf.getRotation().z(); + inv_pose.orientation.w = inv_tf.getRotation().w(); + return inv_pose; +} } // namespace namespace costmap_2d @@ -165,22 +189,28 @@ void OccupancyGridMap::updateOrigin(double new_origin_x, double new_origin_y) * * @param raw_pointcloud raw point cloud on a certain frame (usually base_link) * @param obstacle_pointcloud raw point cloud on a certain frame (usually base_link) - * @param robot_pose frame of point cloud (usually base_link) - * @param gridmap_origin manually chosen grid map origin frame + * @param robot_pose frame of the input point cloud (usually base_link) + * @param scan_origin manually chosen grid map origin frame */ void OccupancyGridMap::updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, - const Pose & robot_pose, const Pose & gridmap_origin) + const Pose & robot_pose, const Pose & scan_origin) { constexpr double min_angle = tier4_autoware_utils::deg2rad(-180.0); constexpr double max_angle = tier4_autoware_utils::deg2rad(180.0); constexpr double angle_increment = tier4_autoware_utils::deg2rad(0.1); const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/); - // Transform to map frame - PointCloud2 trans_raw_pointcloud, trans_obstacle_pointcloud; - transformPointcloud(raw_pointcloud, robot_pose, trans_raw_pointcloud); - transformPointcloud(obstacle_pointcloud, robot_pose, trans_obstacle_pointcloud); + // Transform from base_link to map frame + PointCloud2 map_raw_pointcloud, map_obstacle_pointcloud; // point cloud in map frame + transformPointcloud(raw_pointcloud, robot_pose, map_raw_pointcloud); + transformPointcloud(obstacle_pointcloud, robot_pose, map_obstacle_pointcloud); + + // Transform from map frame to scan frame + PointCloud2 scan_raw_pointcloud, scan_obstacle_pointcloud; // point cloud in scan frame + const auto scan2map_pose = getInversePose(scan_origin); // scan -> map transform pose + transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); + transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); // Create angle bins struct BinInfo @@ -198,17 +228,18 @@ void OccupancyGridMap::updateWithPointCloud( std::vector> raw_pointcloud_angle_bins; obstacle_pointcloud_angle_bins.resize(angle_bin_size); raw_pointcloud_angle_bins.resize(angle_bin_size); - for (PointCloud2ConstIterator iter_x(raw_pointcloud, "x"), iter_y(raw_pointcloud, "y"), - iter_wx(trans_raw_pointcloud, "x"), iter_wy(trans_raw_pointcloud, "y"); + for (PointCloud2ConstIterator iter_x(scan_raw_pointcloud, "x"), + iter_y(scan_raw_pointcloud, "y"), iter_wx(map_raw_pointcloud, "x"), + iter_wy(map_raw_pointcloud, "y"); iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy) { const double angle = atan2(*iter_y, *iter_x); const int angle_bin_index = (angle - min_angle) / angle_increment; raw_pointcloud_angle_bins.at(angle_bin_index) .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); } - for (PointCloud2ConstIterator iter_x(obstacle_pointcloud, "x"), - iter_y(obstacle_pointcloud, "y"), iter_wx(trans_obstacle_pointcloud, "x"), - iter_wy(trans_obstacle_pointcloud, "y"); + for (PointCloud2ConstIterator iter_x(scan_obstacle_pointcloud, "x"), + iter_y(scan_obstacle_pointcloud, "y"), iter_wx(map_obstacle_pointcloud, "x"), + iter_wy(map_obstacle_pointcloud, "y"); iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy) { const double angle = atan2(*iter_y, *iter_x); int angle_bin_index = (angle - min_angle) / angle_increment; @@ -248,7 +279,7 @@ void OccupancyGridMap::updateWithPointCloud( : obstacle_pointcloud_angle_bin.back(); } raytrace( - gridmap_origin.position.x, gridmap_origin.position.y, end_distance.wx, end_distance.wy, + scan_origin.position.x, scan_origin.position.y, end_distance.wx, end_distance.wy, occupancy_cost_value::FREE_SPACE); } diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index cbfcce22d1b61..c594a0be0703f 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -93,6 +93,18 @@ geometry_msgs::msg::Pose getPose( pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); return pose; } + +geometry_msgs::msg::Pose getPose( + const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, + const std::string & source_frame, const std::string & target_frame) +{ + geometry_msgs::msg::Pose pose; + geometry_msgs::msg::TransformStamped tf_stamped; + tf_stamped = + tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); + pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); + return pose; +} } // namespace namespace occupancy_grid_map @@ -111,7 +123,8 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( /* params */ map_frame_ = declare_parameter("map_frame", "map"); base_link_frame_ = declare_parameter("base_link_frame", "base_link"); - output_frame_ = declare_parameter("output_frame", "base_link"); + gridmap_origin_frame_ = declare_parameter("gridmap_origin_frame", "base_link"); + scan_origin_frame_ = declare_parameter("scan_origin_frame", "base_link"); use_height_filter_ = declare_parameter("use_height_filter", true); enable_single_frame_mode_ = declare_parameter("enable_single_frame_mode", false); const double map_length{declare_parameter("map_length", 100.0)}; @@ -174,12 +187,11 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( // Get from map to sensor frame pose Pose robot_pose{}; Pose gridmap_origin{}; + Pose scan_origin{}; try { robot_pose = getPose(input_raw_msg->header, *tf2_, map_frame_); - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2_->lookupTransform( - map_frame_, output_frame_, input_raw_msg->header.stamp, rclcpp::Duration::from_seconds(0.5)); - gridmap_origin = tier4_autoware_utils::transform2pose(tf_stamped.transform); + gridmap_origin = getPose(input_raw_msg->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + scan_origin = getPose(input_raw_msg->header.stamp, *tf2_, scan_origin_frame_, map_frame_); } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(get_logger(), ex.what()); return; @@ -194,7 +206,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); single_frame_occupancy_grid_map.updateWithPointCloud( - filtered_raw_pc, filtered_obstacle_pc, robot_pose, gridmap_origin); + filtered_raw_pc, filtered_obstacle_pc, robot_pose, scan_origin); if (enable_single_frame_mode_) { // publish From fc32b0fc826bafef0231c3b09fd9917e750ef2e2 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 14 Mar 2023 20:47:11 +0900 Subject: [PATCH 040/121] refactor(trajectory_follower_node): remove unnecessary cmake code (#2769) Signed-off-by: Takamasa Horibe --- control/trajectory_follower_node/CMakeLists.txt | 4 ---- 1 file changed, 4 deletions(-) diff --git a/control/trajectory_follower_node/CMakeLists.txt b/control/trajectory_follower_node/CMakeLists.txt index a2316a6db30d2..4ba5bee16eb2d 100644 --- a/control/trajectory_follower_node/CMakeLists.txt +++ b/control/trajectory_follower_node/CMakeLists.txt @@ -10,7 +10,6 @@ ament_auto_add_library(${CONTROLLER_NODE} SHARED src/controller_node.cpp ) -target_compile_options(${CONTROLLER_NODE} PRIVATE -Wno-error=old-style-cast) rclcpp_components_register_node(${CONTROLLER_NODE} PLUGIN "autoware::motion::control::trajectory_follower_node::Controller" EXECUTABLE ${CONTROLLER_NODE}_exe @@ -23,9 +22,6 @@ ament_auto_add_library(${SIMPLE_TRAJECTORY_FOLLOWER_NODE} SHARED src/simple_trajectory_follower.cpp ) -# TODO(simple_trajectory_follower) : RCLCPP_ERROR_THROTTLE() has built-in old-style casts. -# TODO(simple_trajectory_follower) : Temporary workaround until this is fixed. -target_compile_options(${SIMPLE_TRAJECTORY_FOLLOWER_NODE} PRIVATE -Wno-error=old-style-cast) rclcpp_components_register_node(${SIMPLE_TRAJECTORY_FOLLOWER_NODE} PLUGIN "simple_trajectory_follower::SimpleTrajectoryFollower" EXECUTABLE ${SIMPLE_TRAJECTORY_FOLLOWER_NODE}_exe From 5e29ea07f1c1eeb2103df4c22372c0a9173ac20b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 14 Mar 2023 22:00:34 +0900 Subject: [PATCH 041/121] fix(lane_departure_checker): use kinematic state for ego pose (#3057) Signed-off-by: Takayuki Murooka --- .../lane_departure_checker.hpp | 1 - .../lane_departure_checker_node.hpp | 3 --- .../lane_departure_checker.cpp | 2 +- .../lane_departure_checker_node.cpp | 15 ++------------- 4 files changed, 3 insertions(+), 18 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 9605f53cde1d3..244e75210cec3 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 @@ -66,7 +66,6 @@ struct Param struct Input { - geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose{}; nav_msgs::msg::Odometry::ConstSharedPtr current_odom{}; lanelet::LaneletMapPtr lanelet_map{}; LaneletRoute::ConstSharedPtr route{}; diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp index 6d8f267384075..85fd73c63f544 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp @@ -23,7 +23,6 @@ #include #include #include -#include #include #include @@ -61,7 +60,6 @@ class LaneDepartureCheckerNode : public rclcpp::Node private: // Subscriber - tier4_autoware_utils::SelfPoseListener self_pose_listener_{this}; rclcpp::Subscription::SharedPtr sub_odom_; rclcpp::Subscription::SharedPtr sub_lanelet_map_bin_; rclcpp::Subscription::SharedPtr sub_route_; @@ -69,7 +67,6 @@ class LaneDepartureCheckerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_predicted_trajectory_; // Data Buffer - geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; nav_msgs::msg::Odometry::ConstSharedPtr current_odom_; lanelet::LaneletMapPtr lanelet_map_; lanelet::ConstLanelets shoulder_lanelets_; 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 1d594180a638b..1a63fb3eb395b 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 @@ -100,7 +100,7 @@ Output LaneDepartureChecker::update(const Input & input) tier4_autoware_utils::StopWatch stop_watch; output.trajectory_deviation = calcTrajectoryDeviation( - *input.reference_trajectory, input.current_pose->pose, param_.ego_nearest_dist_threshold, + *input.reference_trajectory, input.current_odom->pose.pose, param_.ego_nearest_dist_threshold, param_.ego_nearest_yaw_threshold); output.processing_time_map["calcTrajectoryDeviation"] = stop_watch.toc(true); diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index c60cf59de2407..a3508018e0869 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -183,9 +183,6 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o updater_.add("trajectory_deviation", this, &LaneDepartureCheckerNode::checkTrajectoryDeviation); - // Wait for first self pose - self_pose_listener_.waitForFirstPose(); - // Timer const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); timer_ = rclcpp::create_timer( @@ -221,11 +218,6 @@ void LaneDepartureCheckerNode::onPredictedTrajectory(const Trajectory::ConstShar bool LaneDepartureCheckerNode::isDataReady() { - if (!current_pose_) { - RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for current_pose..."); - return false; - } - if (!current_odom_) { RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting for current_twist msg..."); return false; @@ -261,7 +253,7 @@ bool LaneDepartureCheckerNode::isDataTimeout() const auto now = this->now(); constexpr double th_pose_timeout = 1.0; - const auto pose_time_diff = rclcpp::Time(current_pose_->header.stamp) - now; + const auto pose_time_diff = rclcpp::Time(current_odom_->header.stamp) - now; if (pose_time_diff.seconds() > th_pose_timeout) { RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "pose is timeout..."); return true; @@ -293,8 +285,6 @@ void LaneDepartureCheckerNode::onTimer() tier4_autoware_utils::StopWatch stop_watch; stop_watch.tic("Total"); - current_pose_ = self_pose_listener_.getCurrentPose(); - if (!isDataReady()) { return; } @@ -337,7 +327,6 @@ void LaneDepartureCheckerNode::onTimer() processing_time_map["Node: getRouteLanelets"] = stop_watch.toc(true); input_.current_odom = current_odom_; - input_.current_pose = current_pose_; input_.lanelet_map = lanelet_map_; input_.route = route_; input_.route_lanelets = route_lanelets_; @@ -471,7 +460,7 @@ visualization_msgs::msg::MarkerArray LaneDepartureCheckerNode::createMarkerArray visualization_msgs::msg::MarkerArray marker_array; - const auto base_link_z = current_pose_->pose.position.z; + const auto base_link_z = current_odom_->pose.pose.position.z; if (node_param_.visualize_lanelet) { // Route Lanelets From 5a0d672a96a4bc9c307c966d8ad271d81a3d145e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 14 Mar 2023 23:17:43 +0900 Subject: [PATCH 042/121] feat(tier4_autoware_utils): add expandPolygon function (#3052) * feat(tier4_autoware_utils): add expandPolygon function Signed-off-by: Takayuki Murooka * update comments Signed-off-by: Takayuki Murooka * add test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../geometry/boost_polygon_utils.hpp | 2 +- .../src/geometry/boost_polygon_utils.cpp | 33 +++++++++++++++ .../src/geometry/test_boost_polygon_utils.cpp | 42 +++++++++++++++++++ .../src/util/avoidance/util.cpp | 38 ++--------------- 4 files changed, 80 insertions(+), 35 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp index 14026d47abdbb..99e3018962eb2 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp @@ -44,7 +44,7 @@ Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::DetectedObject & Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::TrackedObject & object); Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::PredictedObject & object); double getArea(const autoware_auto_perception_msgs::msg::Shape & shape); - +Polygon2d expandPolygon(const Polygon2d & input_polygon, const double offset); } // namespace tier4_autoware_utils #endif // TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp b/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp index c08fd6c22c357..2cdb385d19ad6 100644 --- a/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp +++ b/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp @@ -210,4 +210,37 @@ double getArea(const autoware_auto_perception_msgs::msg::Shape & shape) throw std::logic_error("The shape type is not supported in tier4_autoware_utils."); } + +// NOTE: The number of vertices on the expanded polygon by boost::geometry::buffer +// is larger than the original one. +// This function fixes the issue. +Polygon2d expandPolygon(const Polygon2d & input_polygon, const double offset) +{ + // NOTE: input_polygon is supposed to have a duplicated point. + const size_t num_points = input_polygon.outer().size() - 1; + + Polygon2d expanded_polygon; + for (size_t i = 0; i < num_points; ++i) { + const auto & curr_p = input_polygon.outer().at(i); + const auto & next_p = input_polygon.outer().at(i + 1); + const auto & prev_p = + i == 0 ? input_polygon.outer().at(num_points - 1) : input_polygon.outer().at(i - 1); + + Eigen::Vector2d current_to_next(next_p.x() - curr_p.x(), next_p.y() - curr_p.y()); + Eigen::Vector2d current_to_prev(prev_p.x() - curr_p.x(), prev_p.y() - curr_p.y()); + current_to_next.normalize(); + current_to_prev.normalize(); + + const Eigen::Vector2d offset_vector = (-current_to_next - current_to_prev).normalized(); + const double theta = std::acos(offset_vector.dot(current_to_next)); + const double scaled_offset = offset / std::sin(theta); + const Eigen::Vector2d offset_point = + Eigen::Vector2d(curr_p.x(), curr_p.y()) + offset_vector * scaled_offset; + + expanded_polygon.outer().push_back(Point2d(offset_point.x(), offset_point.y())); + } + + boost::geometry::correct(expanded_polygon); + return expanded_polygon; +} } // namespace tier4_autoware_utils diff --git a/common/tier4_autoware_utils/test/src/geometry/test_boost_polygon_utils.cpp b/common/tier4_autoware_utils/test/src/geometry/test_boost_polygon_utils.cpp index 421e434c60e1e..3e028a481e380 100644 --- a/common/tier4_autoware_utils/test/src/geometry/test_boost_polygon_utils.cpp +++ b/common/tier4_autoware_utils/test/src/geometry/test_boost_polygon_utils.cpp @@ -259,3 +259,45 @@ TEST(boost_geometry, boost_getArea) EXPECT_DOUBLE_EQ(anti_clock_wise_area, x * y); } } + +TEST(boost_geometry, boost_expandPolygon) +{ + using tier4_autoware_utils::expandPolygon; + + { // box with a certain offset + Polygon2d box_poly{{{-1.0, -1.0}, {-1.0, 1.0}, {1.0, 1.0}, {1.0, -1.0}, {-1.0, -1.0}}}; + const auto expanded_poly = expandPolygon(box_poly, 1.0); + + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(0).x(), -2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(0).y(), -2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(1).x(), -2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(1).y(), 2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(2).x(), 2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(2).y(), 2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(3).x(), 2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(3).y(), -2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(4).x(), -2.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(4).y(), -2.0); + } + + { // box with no offset + Polygon2d box_poly{{{-1.0, -1.0}, {-1.0, 1.0}, {1.0, 1.0}, {1.0, -1.0}, {-1.0, -1.0}}}; + const auto expanded_poly = expandPolygon(box_poly, 0.0); + + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(0).x(), -1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(0).y(), -1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(1).x(), -1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(1).y(), 1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(2).x(), 1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(2).y(), 1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(3).x(), 1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(3).y(), -1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(4).x(), -1.0); + EXPECT_DOUBLE_EQ(expanded_poly.outer().at(4).y(), -1.0); + } + + { // empty polygon + Polygon2d empty_poly; + EXPECT_THROW(expandPolygon(empty_poly, 1.0), std::out_of_range); + } +} diff --git a/planning/behavior_path_planner/src/util/avoidance/util.cpp b/planning/behavior_path_planner/src/util/avoidance/util.cpp index b1d1c5d2017fe..6681fd19e7d00 100644 --- a/planning/behavior_path_planner/src/util/avoidance/util.cpp +++ b/planning/behavior_path_planner/src/util/avoidance/util.cpp @@ -230,38 +230,6 @@ double calcDecelDistPlanType3(const double v0, const double a0, const double ja) return x1; } -tier4_autoware_utils::Polygon2d expandPolygon( - const tier4_autoware_utils::Polygon2d & input_polygon, const double offset) -{ - // NOTE: There is a duplicated point. - const size_t num_points = input_polygon.outer().size() - 1; - - tier4_autoware_utils::Polygon2d expanded_polygon; - for (size_t i = 0; i < num_points; ++i) { - const auto & curr_p = input_polygon.outer().at(i); - const auto & next_p = input_polygon.outer().at(i + 1); - const auto & prev_p = - i == 0 ? input_polygon.outer().at(num_points - 1) : input_polygon.outer().at(i - 1); - - Eigen::Vector2d current_to_next(next_p.x() - curr_p.x(), next_p.y() - curr_p.y()); - Eigen::Vector2d current_to_prev(prev_p.x() - curr_p.x(), prev_p.y() - curr_p.y()); - current_to_next.normalize(); - current_to_prev.normalize(); - - const Eigen::Vector2d offset_vector = (-current_to_next - current_to_prev).normalized(); - const double theta = std::acos(offset_vector.dot(current_to_next)); - const double scaled_offset = offset / std::sin(theta); - const Eigen::Vector2d offset_point = - Eigen::Vector2d(curr_p.x(), curr_p.y()) + offset_vector * scaled_offset; - - expanded_polygon.outer().push_back( - tier4_autoware_utils::Point2d(offset_point.x(), offset_point.y())); - } - - boost::geometry::correct(expanded_polygon); - return expanded_polygon; -} - boost::optional intersect( const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4) @@ -834,7 +802,8 @@ Polygon2d createEnvelopePolygon( tf2::doTransform( toMsg(envelope_poly, closest_pose.position.z), envelope_ros_polygon, geometry_tf); - const auto expanded_polygon = expandPolygon(toPolygon2d(envelope_ros_polygon), envelope_buffer); + const auto expanded_polygon = + tier4_autoware_utils::expandPolygon(toPolygon2d(envelope_ros_polygon), envelope_buffer); return expanded_polygon; } @@ -869,7 +838,8 @@ void generateDrivableArea( const auto & obj_pose = object.object.kinematics.initial_pose_with_covariance.pose; const double diff_poly_buffer = object.avoid_margin.get() - original_object_buffer - planner_data->parameters.vehicle_width / 2.0; - const auto obj_poly = expandPolygon(object.envelope_poly, diff_poly_buffer); + const auto obj_poly = + tier4_autoware_utils::expandPolygon(object.envelope_poly, diff_poly_buffer); // get edge points of the object const size_t nearest_path_idx = motion_utils::findNearestIndex( From edafc462c3a33474d6059034254fb22388c17d41 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 15 Mar 2023 09:52:45 +0900 Subject: [PATCH 043/121] docs(obstacle avoidance planner): update the docs (#2963) * update doc for obstacle_avoidance_planner Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update rviz config Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner/CMakeLists.txt | 7 +- planning/obstacle_avoidance_planner/README.md | 54 +- .../obstacle_avoidance_planner/docs/debug.md | 235 ++- .../obstacle_avoidance_planner/docs/eb.md | 45 +- .../obstacle_avoidance_planner/docs/mpt.md | 39 - .../launch/launch_visualization.launch.xml | 18 + .../media/area_with_objects.png | Bin 67477 -> 0 bytes .../media/behavior_path.png | Bin 14745 -> 0 bytes .../media/bounds.png | Bin 18960 -> 0 bytes .../media/bounds_line.png | Bin 113616 -> 0 bytes .../media/calculation_cost_plot.svg | 1257 -------------- .../media/clearance_map.png | Bin 101878 -> 0 bytes .../media/debug/bounds_visualization.png | Bin 0 -> 153970 bytes .../media/debug/calculation_time_plot.png | Bin 0 -> 48642 bytes .../debug/drivable_area_visualization.png | Bin 0 -> 151456 bytes .../debug/eb_fixed_traj_visualization.png | Bin 0 -> 152554 bytes .../media/debug/eb_traj_visualization.png | Bin 0 -> 184033 bytes .../debug/mpt_fixed_traj_visualization.png | Bin 0 -> 152291 bytes .../debug/mpt_ref_traj_visualization.png | Bin 0 -> 181075 bytes .../media/debug/mpt_traj_visualization.png | Bin 0 -> 184562 bytes .../debug/path_footprint_visualization.png | Bin 0 -> 188692 bytes .../media/debug/path_visualization.png | Bin 0 -> 151456 bytes .../debug/traj_footprint_visualization.png | Bin 0 -> 201639 bytes .../media/debug/traj_visualization.png | Bin 0 -> 151456 bytes .../debug/vehicle_circles_visualization.png | Bin 0 -> 127430 bytes .../vehicle_traj_circles_visualization.png | Bin 0 -> 212424 bytes .../media/drivable_area.png | Bin 14299 -> 0 bytes .../media/eb_traj.png | Bin 15264 -> 0 bytes .../media/interpolated_points_marker.png | Bin 82506 -> 0 bytes .../media/mpt_fixed_traj.png | Bin 13916 -> 0 bytes .../media/mpt_ref_traj.png | Bin 14982 -> 0 bytes .../media/mpt_traj.png | Bin 16265 -> 0 bytes .../media/object_clearance_map.png | Bin 329688 -> 0 bytes .../media/object_clearance_map_updates.png | Bin 166998 -> 0 bytes ...cle_avoidance_planner_flowchart.drawio.svg | 445 ----- .../media/obstacle_to_avoid.drawio.svg | 205 --- .../media/optimized_points_marker.png | Bin 127072 -> 0 bytes .../media/output_traj.png | Bin 17862 -> 0 bytes .../media/smoothed_points_text.png | Bin 113393 -> 0 bytes .../media/trajectory_with_footprint.png | Bin 129006 -> 0 bytes .../rviz/obstacle_avoidance_planner.rviz | 1467 +++++++++++++++++ .../scripts/calclation_time_plotter.py | 7 +- .../src/debug_marker.cpp | 6 +- 43 files changed, 1712 insertions(+), 2073 deletions(-) create mode 100644 planning/obstacle_avoidance_planner/launch/launch_visualization.launch.xml delete mode 100644 planning/obstacle_avoidance_planner/media/area_with_objects.png delete mode 100644 planning/obstacle_avoidance_planner/media/behavior_path.png delete mode 100644 planning/obstacle_avoidance_planner/media/bounds.png delete mode 100644 planning/obstacle_avoidance_planner/media/bounds_line.png delete mode 100644 planning/obstacle_avoidance_planner/media/calculation_cost_plot.svg delete mode 100644 planning/obstacle_avoidance_planner/media/clearance_map.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/bounds_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/calculation_time_plot.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/drivable_area_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/eb_fixed_traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/eb_traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/mpt_fixed_traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/mpt_ref_traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/mpt_traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/path_footprint_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/path_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/traj_footprint_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/traj_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/vehicle_circles_visualization.png create mode 100644 planning/obstacle_avoidance_planner/media/debug/vehicle_traj_circles_visualization.png delete mode 100644 planning/obstacle_avoidance_planner/media/drivable_area.png delete mode 100644 planning/obstacle_avoidance_planner/media/eb_traj.png delete mode 100644 planning/obstacle_avoidance_planner/media/interpolated_points_marker.png delete mode 100644 planning/obstacle_avoidance_planner/media/mpt_fixed_traj.png delete mode 100644 planning/obstacle_avoidance_planner/media/mpt_ref_traj.png delete mode 100644 planning/obstacle_avoidance_planner/media/mpt_traj.png delete mode 100644 planning/obstacle_avoidance_planner/media/object_clearance_map.png delete mode 100644 planning/obstacle_avoidance_planner/media/object_clearance_map_updates.png delete mode 100644 planning/obstacle_avoidance_planner/media/obstacle_avoidance_planner_flowchart.drawio.svg delete mode 100644 planning/obstacle_avoidance_planner/media/obstacle_to_avoid.drawio.svg delete mode 100644 planning/obstacle_avoidance_planner/media/optimized_points_marker.png delete mode 100644 planning/obstacle_avoidance_planner/media/output_traj.png delete mode 100644 planning/obstacle_avoidance_planner/media/smoothed_points_text.png delete mode 100644 planning/obstacle_avoidance_planner/media/trajectory_with_footprint.png create mode 100644 planning/obstacle_avoidance_planner/rviz/obstacle_avoidance_planner.rviz mode change 100644 => 100755 planning/obstacle_avoidance_planner/scripts/calclation_time_plotter.py diff --git a/planning/obstacle_avoidance_planner/CMakeLists.txt b/planning/obstacle_avoidance_planner/CMakeLists.txt index 89fa09e23dce4..c851de40aa9ec 100644 --- a/planning/obstacle_avoidance_planner/CMakeLists.txt +++ b/planning/obstacle_avoidance_planner/CMakeLists.txt @@ -49,6 +49,11 @@ rclcpp_components_register_node(obstacle_avoidance_planner ament_auto_package( INSTALL_TO_SHARE launch - scripts config + rviz +) + +install(PROGRAMS + scripts/calclation_time_plotter.py + DESTINATION lib/${PROJECT_NAME} ) diff --git a/planning/obstacle_avoidance_planner/README.md b/planning/obstacle_avoidance_planner/README.md index 1a03b695aa699..200e1f9d26eb0 100644 --- a/planning/obstacle_avoidance_planner/README.md +++ b/planning/obstacle_avoidance_planner/README.md @@ -132,6 +132,11 @@ Some examples are shown in the following figure, and it is shown that the trajec More details can be seen [here](docs/mpt.md). +### applyInputVelocity + +Velocity is assigned in the optimized trajectory from the velocity in the behavior path. +The shapes of the optimized trajectory and the path are different, therefore the each nearest trajectory point to the path is searched and the velocity is interpolated with zero-order hold. + ### insertZeroVelocityOutsideDrivableArea Optimized trajectory is too short for velocity planning, therefore extend the trajectory by concatenating the optimized trajectory and the behavior path considering drivability. @@ -155,11 +160,6 @@ _Rationale_ In the current design, since there are some modelling errors, the constraints are considered to be soft constraints. Therefore, we have to make sure that the optimized trajectory is inside the drivable area or not after optimization. -### alignVelocity - -Velocity is assigned in the result trajectory from the velocity in the behavior path. -The shapes of the trajectory and the path are different, therefore the each nearest trajectory point to the path is searched and interpolated linearly. - ## Limitation - Computation cost is sometimes high. @@ -192,41 +192,21 @@ Although it has a cons to converge to the local minima, it can get a good soluti ### Drivability in narrow roads -- set `option.drivability_check.use_vehicle_circles` true - - use a set of circles as a shape of the vehicle when checking if the generated trajectory will be outside the drivable area. -- make `mpt.clearance.soft_clearance_from_road` smaller -- make `mpt.kinematics.optimization_center_offset` different +- modify `mpt.clearance.soft_clearance_from_road` + - This parameter describes how much margin to make between the trajectory and road boundaries. + - Due to the model error for optimization, the constraint such as collision-free is not fully met. + - By making this parameter larger, the is for narrow-road driving may be resolved. 12180 +- modify `mpt.kinematics.optimization_center_offset` - - The point on the vehicle, offset forward from the base link` tries to follow the reference path. + - The point on the vehicle, offset forward with this parameter from the base link` tries to follow the reference path. - - This may cause the a part of generated trajectory will be outside the drivable area. +- change or tune the method to approximate footprints with a set of circles. + - See [here](https://autowarefoundation.github.io/autoware.universe/main/planning/obstacle_avoidance_planner/docs/mpt/#collision-free) + - Tuning means changing the ratio of circle's radius. ### Computation time -- Loose EB optimization - - - 1. make `eb.common.delta_arc_length` large and `eb.common.num_points` small - - This makes the number of design variables smaller - - Be careful about the trajectory length between MPT and EB as shown in Assumptions. - - However, empirically this causes large turn at the corner (e.g. The vehicle turns a steering wheel to the opposite side (=left) a bit just before the corner turning to right) - - 2. make `eb.qp.eps_abs` and `eb.qp.eps_rel` small - - This causes very unstable reference path generation for MPT, or turning a steering wheel a little bit larger - -- Enable computation reduction flag - - - 1. set l_inf_norm true (by default) - - use L-inf norm optimization for MPT w.r.t. slack variables, resulting in lower number of design variables - - 2. set enable_warm_start true - - 3. set enable_manual_warm_start true (by default) - - 4. set steer_limit_constraint false - - This causes no assumption for trajectory generation where steering angle will not exceeds its hardware limitation - - 5. make the number of collision-free constraints small - - How to change parameters depend on the type of collision-free constraints - - If - - This may cause the trajectory generation where a part of ego vehicle is out of drivable area - -- Disable publishing debug visualization markers - - set `option.is_publishing_*` false +- under construction ### Robustness @@ -243,10 +223,6 @@ Although it has a cons to converge to the local minima, it can get a good soluti - EB is not required if the reference path for MPT is smooth enough and does not change its shape suddenly - `option.enable_calculation_time_info` enables showing each calculation time for functions and total calculation time on the terminal. - `option.enable_outside_drivable_area_stop` enables stopping just before the generated trajectory point will be outside the drivable area. -- `mpt.option.plan_from_ego` enables planning from the ego pose when the ego's velocity is zero. -- `mpt.option.max_plan_from_ego_length` maximum length threshold to plan from ego. it is enabled when the length of trajectory is shorter than this value. -- `mpt.option.two_step_soft_constraint` enables two step of soft constraints for collision free - - `mpt.option.soft_clearance_from_road` and `mpt.option.soft_second_clearance_from_road` are the weight. ## How To Debug diff --git a/planning/obstacle_avoidance_planner/docs/debug.md b/planning/obstacle_avoidance_planner/docs/debug.md index 4c8b6eb910bcc..9ee18b732d375 100644 --- a/planning/obstacle_avoidance_planner/docs/debug.md +++ b/planning/obstacle_avoidance_planner/docs/debug.md @@ -2,116 +2,189 @@ ## Debug visualization -Topics for debugging will be explained in this section. +The visualization markers of the planning flow (Input, Elastic Band, Model Predictive Trajectory, and Output) are explained here. -- **Drivable area** - - Drivable area to cover the road. Whether this area is continuous and covers the road can be checked. - - `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/drivable_area`, whose type is `nav_msgs/msg/OccupancyGrid` +All the following markers can be visualized by -![drivable_area](../media/drivable_area.png) +```bash +ros2 launch obstacle_avoidance_planner launch_visualiation.launch.xml vehilce_model:=sample_vehicle +``` + +The `vehicle_model` must be specified to make footprints with vehicle's size. + +### Input + +- **Path** + - The path generated in the `behavior` planner. + - The semitransparent and thick, green and red band, that is visualized by default. + +![path](../media/debug/path_visualization.png) + +- **Path Footprint** + - The path generated in the `behavior` planner is converted to footprints. + - NOTE: + - Check if there is no high curvature. + - The path may be outside the drivable area in some cases, but it is okay to ignore it since the `behavior` planner does not support it. + +![path_footprint](../media/debug/path_footprint_visualization.png) + +- **Drivalbe Area** + - The Drivable area generated in the `behavior` planner. + - The skyblue left and right line strings, that is visualized by default. + - NOTE: + - Check if the path is almost inside the drivable area. + - Then, the `obstacle_avoidance_planner` will try to make the trajectory fully inside the drivable area. + - During avoidance or lane change by the `behavior` planner, please make sure that the drivable area is expanded correctly. + +![drivable_area](../media/debug/drivable_area_visualization.png) + +### Elastic Band (EB) + +- **EB Fixed Trajectory** + - The fixed trajectory points as a constraint of elastic band. + +![eb_fixed_traj](../media/debug/eb_fixed_traj_visualization.png) + +- **EB Trajectory** + - The optimized trajectory points by elastic band. + +![eb_traj](../media/debug/eb_traj_visualization.png) + +### Model Predictive Trajectory (MPT) + +- **MPT Reference Trajectory** + - The reference trajectory points of model predictive trajectory. + +![mpt_ref_traj](../media/debug/mpt_ref_traj_visualization.png) + +- **MPT Fixed Trajectory** + - The fixed trajectory points as a constraint of model predictive trajectory. -- **Path from behavior** - - The input path of obstacle_avoidance_planner. Whether this path is continuous and the curvature is not so high can be checked. - - `Path` or `PathFootprint` rviz plugin. +![mpt_fixed_traj](../media/debug/mpt_fixed_traj_visualization.png) -![behavior_path](../media/behavior_path.png) +- **Boundaries' Width** + - The boundaries' width is calculated from the drivable area line strings. -- **EB trajectory** - - The output trajectory of elastic band. Whether this trajectory is very smooth and a sampling width is constant can be checked. - - `Trajectory` or `TrajectoryFootprint` rviz plugin. +![bounds](../media/debug/bounds_visualization.png) -![eb_traj](../media/eb_traj.png) +- **Vehicle Circles** + - The vehicle's shape is represented by a set of circles. + - The `obstcle_avoidance_planner` will try to make the these circles inside the above boundaries' width. -- **MPT reference trajectory** - - The reference trajectory of model predictive trajectory. Whether this trajectory is very smooth and a sampling width is constant can be checked. - - `Trajectory` or `TrajectoryFootprint` rviz plugin. +![vehicle_circles](../media/debug/vehicle_circles_visualization.png) -![mpt_ref_traj](../media/mpt_ref_traj.png) +- **Vehicle Circles on Trajectory** + - The vehicle's circles on the MPT trajectory. + - Check if the circles are not so big compared to the road's width. -- **MPT fixed trajectory** - - The fixed trajectory around the ego of model predictive trajectory. - - `Trajectory` or `TrajectoryFootprint` rviz plugin. +![vehicle_traj_circles](../media/debug/vehicle_traj_circles_visualization.png) -![mpt_fixed_traj](../media/mpt_fixed_traj.png) +- **MPT Trajectory** + - The optimized trajectory points by model predictive trajectory. + - The footprints are supposed to be fully inside the drivable area. -- **bounds** - - Lateral Distance to the road or object boundaries to check collision in model predictive trajectory. - - Whether these lines' ends align the road or obstacle boundaries can be checked. - - `bounds*` of `/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker` whose type is `visualization_msgs/msg/MarkerArray` +![mpt_traj](../media/debug/mpt_traj_visualization.png) -![bounds](../media/bounds.png) +### Output -- **MPT trajectory** - - The output of model predictive trajectory. Whether this trajectory is smooth enough and inside the drivable area can be checked. - - `Trajectory` or `TrajectoryFootprint` rviz plugin. +- **Trajectory** + - The output trajectory. + - The dark and thin, green and red band, that is visualized by default. -![mpt_traj](../media/mpt_traj.png) +![traj](../media/debug/traj_visualization.png) -- **Output trajectory** - - The output of obstacle_avoidance_planner. Whether this trajectory is smooth enough can be checked. - - `Trajectory` or `TrajectoryFootprint` rviz plugin. +- **Trajectory Footprint** + - The output trajectory is converted to footprints. -![output_traj](../media/output_traj.png) +![traj_footprint](../media/debug/traj_footprint_visualization.png) -## Calculation cost +## Calculation time -Obstacle avoidance planner consists of many functions such as clearance map generation, boundary search, reference path smoothing, trajectory optimization, ... +The `obstacle_avoidance_planner` consists of many functions such as boundaries' width calculation, reference path smoothing, collision-free planning, etc. We can see the calculation time for each function as follows. ### Raw data +Enable `option.enable_calculation_time_info` or echo the topic as follows. + ```sh $ ros2 topic echo /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/calculation_time --field data - - getDrivableAreaInCV:= 0.21 [ms] - getClearanceMap:= 1.327 [ms] - drawObstaclesOnImage:= 0.436 [ms] - getAreaWithObjects:= 0.029 [ms] - getClearanceMap:= 2.186 [ms] - getMaps:= 4.213 [ms] - calculateTrajectory:= 2.417 [ms] - getOptimizedTrajectory:= 5.203 [ms] - getEBTrajectory:= 5.231 [ms] - calcBounds:= 0.821 [ms] - calcVehicleBounds:= 0.27 [ms] - getReferencePoints:= 2.866 [ms] - generateMPTMatrix:= 0.195 [ms] - generateValueMatrix:= 0.019 [ms] - getObjectiveMatrix:= 0.559 [ms] - getConstraintMatrix:= 1.776 [ms] - initOsqp:= 9.074 [ms] - solveOsqp:= 3.809 [ms] - executeOptimization:= 15.46 [ms] - getMPTPoints:= 0.049 [ms] - getModelPredictiveTrajectory:= 18.928 [ms] - optimizeTrajectory:= 24.234 [ms] - insertZeroVelocityOutsideDrivableArea:= 0.023 [ms] - getDebugVisualizationMarker:= 0.446 [ms] - publishDebugVisualizationMarker:= 2.146 [ms] - getDebugVisualizationWallMarker:= 0.001 [ms] - publishDebugVisualizationWallMarker:= 0.013 [ms] - publishDebugDataInOptimization:= 2.696 [ms] - getExtendedTrajectory:= 0.016 [ms] - generateFineTrajectoryPoints:= 0.118 [ms] - alignVelocity:= 1.227 [ms] - generatePostProcessedTrajectory:= 1.375 [ms] - makePrevTrajectories:= 1.411 [ms] - generateOptimizedTrajectory:= 33.284 [ms] - getExtendedTrajectory:= 0.018 [ms] - generateFineTrajectoryPoints:= 0.084 [ms] - alignVelocity:= 1.109 [ms] - generatePostProcessedTrajectory:= 1.217 [ms] - getDebugCostMap * 3:= 0 [ms] - publishDebugDataInMain:= 0.023 [ms] -pathCallback:= 34.614 [ms] +--- + insertFixedPoint:= 0.008 [ms] + getPaddedTrajectoryPoints:= 0.002 [ms] + updateConstraint:= 0.741 [ms] + optimizeTrajectory:= 0.101 [ms] + convertOptimizedPointsToTrajectory:= 0.014 [ms] + getEBTrajectory:= 0.991 [ms] + resampleReferencePoints:= 0.058 [ms] + updateFixedPoint:= 0.237 [ms] + updateBounds:= 0.22 [ms] + updateVehicleBounds:= 0.509 [ms] + calcReferencePoints:= 1.649 [ms] + calcMatrix:= 0.209 [ms] + calcValueMatrix:= 0.015 [ms] + calcObjectiveMatrix:= 0.305 [ms] + calcConstraintMatrix:= 0.641 [ms] + initOsqp:= 6.896 [ms] + solveOsqp:= 2.796 [ms] + calcOptimizedSteerAngles:= 9.856 [ms] + calcMPTPoints:= 0.04 [ms] + getModelPredictiveTrajectory:= 12.782 [ms] + optimizeTrajectory:= 12.981 [ms] + applyInputVelocity:= 0.577 [ms] + insertZeroVelocityOutsideDrivableArea:= 0.81 [ms] + getDebugMarker:= 0.684 [ms] + publishDebugMarker:= 4.354 [ms] + publishDebugMarkerOfOptimization:= 5.047 [ms] + generateOptimizedTrajectory:= 20.374 [ms] + extendTrajectory:= 0.326 [ms] + publishDebugData:= 0.008 [ms] +onPath:= 20.737 [ms] ``` ### Plot -With a script, we can plot some of above time as follows. +With the following script, any calculation time of the above functions can be plot. ```sh -python3 scripts/calclation_time_analyzer.py -f "solveOsqp,initOsqp,pathCallback" +ros2 run obstacle_avoidance_planner calclation_time_plotter.py ``` -![calculation_cost_plot](../media/calculation_cost_plot.svg) +![calculation_time_plot](../media/debug/calculation_time_plot.png) + +You can specify functions to plot with the `-f` option. + +```sh +ros2 run obstacle_avoidance_planner calclation_time_plotter.py -f "onPath, generateOptimizedTrajectory, calcReferencePoints" +``` + +## Q&A for Debug + +### The output frequency is low + +Check the function which is comparatively heavy according to [this information](.#calculation-time). + +For your information, the following functions for optimization and its initialization may be heavy in some complicated cases. + +- MPT + - `initOsqp` + - `solveOsqp` +- EB + - `optimizeTrajectory` + +### When a part of the trajectory has high curvature + +Some of the following may have an issue. +Please check if there is something weird by the visualization. + +- Input Path +- Drivable Area +- Boundaries' Width + +### When the trajectory's shape is zigzag + +Some of the following may have an issue. +Please check if there is something weird by the visualization. + +- EB Trajectory +- Vehicle Circles on Trajectory diff --git a/planning/obstacle_avoidance_planner/docs/eb.md b/planning/obstacle_avoidance_planner/docs/eb.md index 6becc8b03cc24..7efb1edaa62db 100644 --- a/planning/obstacle_avoidance_planner/docs/eb.md +++ b/planning/obstacle_avoidance_planner/docs/eb.md @@ -16,25 +16,64 @@ title getEBTrajectory start :crop trajectory; +note right +Forward length is eb.common.num_points * eb.common.delta_arc_length. +Backward length is common.output_backward_traj_length. +end note :insertFixedPoint; :resample trajectory; +note right +Resampling interval is eb.common.delta_arc_length. +end note -:getPaddedTrajectoryPoints +:getPaddedTrajectoryPoints; +note right +Pad the last optimization point so that the number will be always eb.common.num_points. +This is for enabling warm start. +end note :updateConstraint; :optimizeTrajectory; :convertOptimizedPointsToTrajectory; +note right +The validation function is contained. +When eb.option.enable_optimization_validation is true, the optimization result will be ignored if the validation fails. +end note stop @enduml ``` +### General parameters + +| Parameter | Type | Description | +| ---------------------------- | ------ | ---------------------------------------------- | +| `eb.common.num_points` | int | points for elastic band optimization | +| `eb.common.delta_arc_length` | double | delta arc length for elastic band optimization | + +### Parameters for optimization + +| Parameter | Type | Description | +| ----------------------------- | ------ | --------------------------------------- | +| `eb.option.enable_warm_start` | bool | flag to use warm start | +| `eb.weight.smooth_weight` | double | weight for smoothing | +| `eb.weight.lat_error_weight` | double | weight for minimizing the lateral error | + +### Parameters for validation + +| Parameter | Type | Description | +| ------------------------------------------ | ------ | --------------------------------- | +| `eb.option.enable_optimization_validation` | bool | flag to validate optimization | +| `eb.validation.max_error` | double | max lateral error by optimization | + ## Formulation +### Objective function + We formulate a quadratic problem minimizing the diagonal length of the rhombus on each point generated by the current point and its previous and next points, shown as the red vector's length. ![eb](../media/eb.svg){: style="width:600px"} @@ -102,7 +141,9 @@ $$ \end{align} $$ -Regarding the constraint, the distance that each point can move is limited so that the path will not changed a lot but will be smoother. +### Constraint + +The distance that each point can move is limited so that the path will not changed a lot but will be smoother. In detail, the longitudinal distance that each point can move is zero, and the lateral distance is parameterized as `eb.clearance.clearance_for_fix`, `eb.clearance.clearance_for_joint` and `eb.clearance.clearance_for_smooth`. The following figure describes how to constrain the lateral distance to move. diff --git a/planning/obstacle_avoidance_planner/docs/mpt.md b/planning/obstacle_avoidance_planner/docs/mpt.md index 6c07244bdb45e..f76115b8da1cb 100644 --- a/planning/obstacle_avoidance_planner/docs/mpt.md +++ b/planning/obstacle_avoidance_planner/docs/mpt.md @@ -443,42 +443,3 @@ $$ \in \boldsymbol{R}^{3N_{ref} \times D_v + N_{ref}} \end{align} $$ - -#### Two-step soft constraints - -$$ -\begin{align} -\boldsymbol{v}' = - \begin{pmatrix} - \boldsymbol{v} \\ - \boldsymbol{\lambda}^{soft_1} \\ - \boldsymbol{\lambda}^{soft_2} \\ - \end{pmatrix} - \in \boldsymbol{R}^{D_v + 2N_{slack}} -\end{align} -$$ - -$*$ depends on whether to use L2 norm or L-infinity optimization. - -$$ -\begin{align} - A_{blk} & = - \begin{pmatrix} - A^{soft_1}_{blk} \\ - A^{soft_2}_{blk} \\ - \end{pmatrix}\\ - & = - \begin{pmatrix} - C_1^{soft_1} B & & \\ - -C_1^{soft_1} B & \Huge{*} & \Huge{O} \\ - O & & \\ - C_1^{soft_2} B & & \\ - -C_1^{soft_2} B & \Huge{O} & \Huge{*} \\ - O & & - \end{pmatrix} - \in \boldsymbol{R}^{6 N_{ref} \times D_v + 2 N_{slack}} -\end{align} -$$ - -$N_{slack}$ is $N_{circle}$ when L2 optimization, or $1$ when L-infinity optimization. -$N_{circle}$ is the number of circles to check collision. diff --git a/planning/obstacle_avoidance_planner/launch/launch_visualization.launch.xml b/planning/obstacle_avoidance_planner/launch/launch_visualization.launch.xml new file mode 100644 index 0000000000000..d8320e09cc001 --- /dev/null +++ b/planning/obstacle_avoidance_planner/launch/launch_visualization.launch.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/planning/obstacle_avoidance_planner/media/area_with_objects.png b/planning/obstacle_avoidance_planner/media/area_with_objects.png deleted file mode 100644 index 41a950452c7832effb18bf5be0d94aa54c05c9fb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 67477 zcmY(r1yoc~_da~-Qb8F)L_)ezK@e#qh8z%(4gsY*q>&J%LqI^fyIWEz5s(G}5$To~ zYKZR)zVG|{f3sM!WZir2IXj>I?0x4wLRt1YAr&D6LD%7OPt_m@Hv@t&iScp4U-oUB zCBZLjCrP+EKKOXyo4y18zwIoo<^0UQFg6JUlQwjCgpEhT8?HJsXR*np*-EXmld{6pbTs-itU<%pjMy^p#QNz>D zlb(knt2c<@>3iOVX?x&o(o`mlHT{I>i#Zm5dEFgKz8_;QrN!Ti3qO4L@YRI3g927S z(wRls?)&sF%0fMlQLSATPfh*oKsXXjT-i$C>8e zVS<;&qusY9$3l8q z2+|(0tf zkD!=O`eF&C8|!;}4>BzMrdOF0=@>C=`I42qcRMM7pdcfjpIfy$CGn!?2hT=wAn4Yj zvhNU&TDgO>bGB_=-+Rg8CHGX^0Es`{N(_9x3Pv%@4j7BiW9a2>b;~~xr{}|ndMlqJ zNdbd?8>ts*)aY=D_+HF7vq64=4W9%h3e@FS>U}D^k=|lM3pw6;&{S1lukeJ+*amW( z#$=A=+6eVD6A+&tTi72gh&o2ID5tNlZ`8LH2-%Rkd$)v0Nq8dGOjkFE1CGb6CNz)x zh5(^x@yYaC-*Jf}6V;C*;8&N%NgY*z- z_BsEF-WRMs+(SyOqEXSZCJ8s-%{L|)e+-M>KK~={x8N2CE@wpxertcB0U8rMT3zjN zzW&~c`c>JJ(kR+5^Y-)8UwA(s-QOoklEY?cE2Rp5+j4o~IRd=phIoTs?mjtWPcn&x z19c|!Id}z|YMaN@EZle-@HCPI9w4#Tt;a|m?AgQxEq~~1a_g>4#)8U;`(HleF>K+} z2QFOTv6ABE?BVeZ{q%Zu$$UQlSf$9d#!~C<@uj7uZyPx`ljKlD%2CwQ6-o&Z-NLt} z2a!9FU-QR^KUtx7A%yAX8%)11^FBv^o{aD_S~dn0It|^|BiQ>|yOkodhr#+tk`-!e z;SC{%5YAVZs@0Q|%pLJl=REAV(Fs(&b_)mr;!jrUYQ=;IOU5kM4h}}0Z$o|}Y7vz^|RW~gpB4T!p7NU;o2tu^1By(dt{%XJq6_H3{K!#-pPxXJH&N*jgi_;9ILX3;#OXDztjHU+Rd?lT z+VcaAo-MNYL7v7uFh6O05be;{-tNSMShHDFQp@oOp&RP+;8@_(lN=jMDzl3L5xy4z zkD4STlRRlD8?rZTytWAQ%z!vMM8WYzua5r|93QeDzxxiou6rN?^7A$V=92zSr-a<( z82a7TkV_;NvxB0Fn8b_IV0Pnf*nT;;9>&V*i_>P_H+U?rzjmWdseJY&Bp2}2^Pe!rvE2JH0V|2@qdc%Mfz4R|2rs9O@h zMs@3%SYgq`&V9A(N1E($iV5IUept`A6F@W}LR(qXJJ+TX;3g_!=c8zIzD8Gqu}tz5 z&wP#5ac>;TgUVsB82P}j3rqc)1zQryBJZ- zEI3b6BGw*25Kb3b0@2kvTp+}?-3=nh5T0NNlzf4oiB<>%J$iWe3m(+=xg!uE9y3XV zw!biTMf|14 zQknK1=i99K-46dmg9(na8Gs2b{&K!Xs}GhoBP5l?fII3ZG$YzDtR5v(UBg9(IUvRF zmUYvXH9Eis{o=qy4W&hN_=*W{FoFKloBwYo_h4IhrzDF?R@I& zWQR8}A;<9hz@U}L?geHN5n335o9n5o3#dDKv5v8Dh#HH z34mBe7aac<;XaRQS-XX>4_m|v$xvV)rjY8MOM?ps!V4y4Y+)`{i3;+3iEu(aO;Wa)S19$1E!_ zK}01TD8{;DPu=ZI03D{QvpYDFKv7hO65t9`p|_FTz)rdGGyJaqAi$x<1@0)WqpYla zd>aeu3Ae2I21F}zQe}0D6^XGhZcA#hb zzoHlYb34dG(bK8HBM(nh42tC2zR2~#NrIq*sec(6gN_M(2jBlA;2Ll$#vvS>#Wqo? zm`q$o?aGabhed{2Gr@?qmMiIkb9ox0y_yGvBz=V3cTvfh;?&nXN#1Taa4(zCdlU2@ zfE=#N=JvI{0fvaM&QXKg{rY?#NI%^VoN3h`IEG}??D*Q+nuLo)j`xd{*wwX%HzVY{ zY>wWP+1y_g3dB5o-;5Bih?8e>bph4`^;Bo8^bDk#+tlcs9*n4vHit`f!w>%avC`Gc zZK;)x+aURNgJ_~_wfbZ=@&!M zF&5u5slvM630E=76iq#B#-3z7^dT$I_oL@AiZ!J#Bkp=*ab&94Rz`sU6b zA*XwXC*osIdjISb7)67dT2?mp)`y*M3({={VM4%(Ch>w$lSsy2^l4A$5;#+y%2wV$ zTA}7qw5$6(t$aFCKk?OHN1LhWM*kNms1 z!G2{n4nrc2lp()BIO7HP!(vw44GO#6W)E7H4mCV^2@lrCiq!3hAc#6%N%^lsCcig4 z&D?wMZ^p&>QjpJ4I+YKK-H^P2)A#7fAFeYGF)=XnK z{pTJXMwH8rh^GvIYjhg6SwoXs&|A!C`G$KFE(F-+ZaHebz-9cdE2^BKH|I}& zz6y<~=?n)%SCy-eF!Vi2Sp&rmPQohTdr9f<#eH zmB7jsvduV36&d02J<|P$&TOSv+ZYceG1lIvJ@sAbC5`J_`WkT#(yG2oQ`H2m=oam|R-m4YGjeDGsXmduSO z7r5dMZZA#Vo|EU>2v?6Jh6EK^x|K$lAjrPkb1)S|7HG0b&s7pb+t`xl!-_jdsWBf; z;U3wqMwGLpC_`D4TFRIT)VOz$sMCW_t?GCXW6_ZLYT8BG+*JZdB%ZqzPxC#=5j|O; zMVp@>Z;+6ujdr|sU%Z(%VHU!eGKrf2=Q;ZhPhb+RN}zIZUXRJH@Zhr?y?9e*M9IX4 z2XZ0OvsE7wclakO^zjvYm!_=I`2UD;_C~6o_rAASjmco6Bz`J_H#dLie^yWT zy6EFblwZ_mda{Q;I{C?D#z(caya??NWWpl=0>&Z{FyI@|W0xRXg z0W|Uvw3iv6vArW)Li%<-rA|6TjX+ot?~cXfM7O$WtqsRDDSsB24p=}wC$q?Q;>z8w z5*G(Ls5BpKCi2Lq~7W5DQRus}`uoEC@E;JrJr}M|yIUJ)(&mTYAcH z*yccemzK7w=~~c=zFX$<0`rF$xc@hks2*rPWh#M=&q{kJAJjb2e~pw zpjJnR7w|z{C63U;y;m!!)fmjmHiu6+^rOP0`f5cpuRi^f6+^ib#{G`!cZ27gbQ6{N zoZYW6!Gdn|^*TID^Vw}c`x#ysh?e4-Tj$nC-1=&%EB(qdSlXu3ZnAqe_saCuHs44l z$z%Z1x~L3JY-{L~5M`EmXgwzI1P(i`1Cf|9;)r0O9Ob>2Mt2;7?;yO8T6EW!^? z`CAUB}g@3kmd?ky5C5w9X)E0k6JZwgJWowYTK`^JI z9xvz3z~I19KJt3ucAy>tjOcMgzY#SBN7a=$+^BZ!YhPrG%^0%~dyM znOJJf5H2INU|+1(VA=>X%82wm=kPvoYmMTYQq=?$n~5xG)MFrWbfpN?k@ER}VGW?W z8uJW{TL(a8{GKO(wp%~K!!5$#-Kih?ae`wK3qifFk62WYO}=M%S5o{ALNr>PzvEBh zxM)tU+*q5oD{}WLR=GIFL(^*I(RyJE`+AYetl8Y6@;n4BJ4Ko$>xI)w2ldc) znQGZakzLCpG;W7zs&#}sooqop*7n97$mFU{4pL^NlU}g526fd7Bts!)-1G%2( zzj*FBC~05-QbSPsN9Bm*)7^ix4b~n2!&e3NMpoMSj59$UU}fZeU~_;E@!J%%;B$6& zF}o`M`2Oc?VBIK-hDidPP4lA_&n*N1 zQcf0jg9dj3$WP*GSq9Hn{&ZX=uGc>-*EakAxql#<4f^~|8XsrzHXvlspEmAao`;HQ zXS>8#s<#STkfQ(Ey@l2^uU43U81ZbYXf^(HVP?-QRXaRCAwbcWCI`HWc2E>JD8z|*I>(mq$`CO3-pF9Ej7W&6z z;9c!am;sbT>1qWZxzYHK;Q!sb|JC06It4}PtQZb!ml|irpjc(9>i|EZcMeRjEOZIZ>+4D5PukViHHh&`ibKuEV<9 z6t2ZneZ&{1T4_F~4KuCRcMNuFTu{h_@stfN!3@6VqX=Kq zTlC#-S(v1X+(|8l%4sQ{Cjh7L>v)H!u!~@$A>X1pGlid-SkzLTwjd>Kt=h@bN-sVx z7{@aPDde8se2G3PE8)?fKldsEa&B55x0I!muO4jj?Sk-K36NaD)XeVS90qhp8^%e- zuijYJJtq64`SNV#hwV(WGGp)5z3(B*{>2u4()KveN%s{eR`0&?PU61zS+duT*U!L> z2CB$lAf+2>&92!iJcj5B?9g(GQrJHSW%c~$>G}Z(!!s9+{W#j8n8g<6WW>ezMG)OI zC7S08`5w8j?``7xwpUgpeW{IwN3- z#2J3~0I_2vQ=&7b&2rha1W~6-OOVpXK4yu_y>L8DTzjBa#abM*jjP$$g>g$0L;L|6 z8Ktzko1o3*mIQu~y4P8<;Tmunv=u{8gZShJ;&6E>o<<&}1ml@X2fr{(Y=9I}Qxd^` z{GO6X((?zGuUP1U%Jgt2d+3J-pf;{SbmkorKh0ot#$ zVw&Bm48bpfHdjG(dx%~{5bR5MZsczm=^^V4P+OriiZoru*MN4#yGR5v>WMiH zwT%0NG>80uu>Yj1zLi1dX9XbHl_2JUATUGTH6uVS!D~v63Is;AesCOsYdzSwU77UR zYyVI#riQtC`0Sv2!pWFyo(v&)MQ`4uhmpTn0RX-y`K0ZAIRV__`A@({G+U!sVZ#?}^pd39p-K!hI#T00B>(+(S*J*MAdr^tXIy_L9X(Vj|R z#ZP9nhEpOqL+Oa*u+dekble)6^9X;-00Q58P~w%-hI{CvT@3V@vMhctUi7>Cefm34 z|;?6q3!~?Clu(8VixR8T>kZ9@7ojZVic~HTL;H`h$!(0 z)S&1p9?flvvp=|tCdcQ^>zW@kOA$=)AFYM^&V-+yRUJ7ep4IPvt+hd-0R5S?Uc(^b zdxCa?r@yfwxxsJS92ORSovY%eIB4;>BMQ{Fkv_Ir(LUl1bBIi}R4+u!4vY3cJ3Z_h zGrHa`(kK$za0X(brp9D}^)9S4xOkj#VuYAa486gAE{6$Lq0_FhVu{FCVK+by`2R^9@@I2p}F%Hk#R)___FO)Qa(N?biXo3%ma@)%RVlrSI zDTK~miD-$`Eg@BT%Uoy+gY-4AHG(=>TV|IElAqpV#XxYL`}k&UmOXJ(mvN{q zM>iVl8v*)?BEnW~bNm;MrVMODJq;@UBA@Eu7w)~%M(o9Q+igtmv^2RzNeU1^Gqo11 zF>xkG9=)$<=kza)rKq}F$^aYm(J0%%;iP2{bX(dCZVF;dTc|H5v}AYRYR4g8Kw(b* zWXcy>AH7u)ly2JaYDaWrWzH+7JCb$>>5B0&4s;k3qD(``2-kYlj`=`JrtAXih*NFK z#*!+5y=@yf8zzC+cB_sve|`1E;ks&BuH|K}Lf&vmzL&JDf*KW);oRQCvhmvQ8;x*g ze7K*f>D5ssNI(FPBLe`#dDKeQ<6;lMa?ql}Ro)|>r2 zzj(M5sD5;0_sdfS5IvxZZ;%n_#g-uOEADd!q&MVu$5{Xag{(i7OECZh7b^)(g(_c> zWMS4X(_&isu^0WP6{45RMPIQZvm+8r%_Ze9q2O>5cC5)0=Sehq|50`l+f=G)cwBqO z>zpiFSGW>$E%EKMQ@76HoK%a4kSKg3TPwdG{1TeO&6=l0qM+Es1Bwhy%9uv@M zpmW&$@p9rX(|dcyJ`5t}va|KKT)bN zYSrb~Z9X^oFeYX4CP1x0_;vW)pS6Rdt$5X=?v>iYIU04gUaqLzD!m2yZGKb2uh|*$ z${ISC3ifIB-9TQhiCyr7+L;iyca=;}&zpRUQDe&?>EPjN{_fQ5d3WUKyrgta*w)rr z1d}xVc-c4J^n9|}fM?f4UgzgfZN#~`qhp(`Y-Jg(&K7RoE@WM*Z?RGA)^ZU7`32PU zzixdk*a=!8ZS)R2+}y50;yUeJp#RUf2D*!J3wZ_8$)9+2DdHzvBB4A|A8?nL>H=g?)-;^0wEmQ zg*p#zJr(y|^C?}mV~Ir+`&L}n0R6a&`m7lRC>`0YFKa+cHrqs{Aus&+FT zo-`dXERku9uAERWyr_ziN1rJksKMS=szq77Pv{w3e0FBeJrr=TLd!0ahRdugdjhQ7Eky+ zqmCD${>%WE^i(T-VcPC$(%pSrt!e0m3b{i~3`KDfTM-|eZ18NKU(`vmS&Z{{vWh|C z;|&Q3p%is<6LcAEUn{wqMZLY9W+a4WIgWO}YykSz57SBH`GSLxzFAL%MY(!``b%SF za-om8JS!qbg%c46XG?$yg^lx>#{i8uzDlso#oGICybQJ3cez(C|Fux%Zki^PTXJVf zRuHhO{abpb`w5^4`rxK8fa!(+#)=PgV&yqDc(Lf|9MooW-HA=;_9H+^09lPTx>9X- z1P1|#{lH{OG@oyV=HDtDRSU;{QfAY&)ZH(6)RmR6@<0n7p6v2)i%OiVB$NQvnaWI; z7aycF<4rn*PSOC8cHW~emsivjWojCYj*G-#4RNzlasK6L(ij%r!M0(zc}{@~u~sX- z1vtWrj~ZR|#V769#th#{lcg9ryo#t(n+N=F(g}JB*53PcFq`&!V{){-!k{h>uE7)9 zN=@Q6DVUxg{TRUpiDy2zEr}5v(TtdKOxw;?`uZiuu|bi7)KwCkic()G(doYdHH-4m ziD+(>C7bA7NYUsMh;VQ`TFHui0&%^cZ$_r35*aa>XNV<8qnrYj+FoF5K!mnwsPy5d zK$i890RW$KzTidm)3$8c5`ms z8g<=LSO{zFDZIE`v-uC_HPWnrRDOvMxTm)aGSL`vxU)*ZOW8v`XA>RnFt%IZ!B(4A zk{!pjaD06Y=mGNvcsNWn{AI?6b0ji=Cj$m$FaIm?iOe1ZVzvR^=$^f#=Iau~b#g$|2gn8_LR`!}^7e&-F=birZ#Pn3DVHX2mX_Y~Oq@41J=Cl_h-@sw(9FRkG8 zuZsPw8SI5#Z^=(P6ZB-_L}K+Z+x==74l#jPTV5_{8S0A&=*uv3Q7y=J!ywpTdk{k0 zpqyg8mJf@iF*zg$P$7TT9}Jn$Xt3xjjaf3bGWW)xtuvYvmNXeZ%b$E-uttz4S4FC- z$w!b4QOf)dWE${T*(eJPDBtJKLkZ_{t~O#usRWl3vs>)nederyA$|d*fiAcR(!{^c z?+V-b)-B~a>8es%2-9RcZgMi%`xCHSn5sN$h85_gV#~*=W&dc{HcHyD4q=pzF`E?; z;1emcQQ|Rl6oEVe-lOAjb+^9PhWTJA>PUjgOto&5^W(h_n0|Uarua3XX6Upu#dGVi z&rSbu_tK_0y8!PwgH+H4_Gz7@SJ!z%x^PhbU3Y-dTF8}Q>@z%F9cddmm>fP3YwN<> zuh+`uqdYy#Xq}`_v*Q(F7I4@VoQvwsR6A3_+;M$kHcp4mJ;iOha@F z)YYCGdt)VA*05`X^`wvB751q0FC{$D_qyG?u_r*4bl;}1eM zcP-EKk?n%D2jv-mEf_`ajtZ);BDbPEi@^_a%Cg^&;h&v)Fw4O+osFpK-NUmW^+1Jobf}_|0u` za~!&t8hNAFfYz;p0P!eD>Y4E;W5jE+TIm=VCh1jR)V&}>>A4N3RCqK_H}l;Y6QB^D zZPcrXC?Yet^pm`2j~T@vENpBNs5y!FpK_z3c**6IzOXgsLPif0i84StekShFARq8# z@;Q|b!6VgoEH7+sy&>JBr=csEApkwG_^qI%J7aDu^-gy+uvJ(&F+uB&eEML8-dJOv zkE8o^eI4+9QJF6K&o)0|`n~@igxH@v!Deiwu$=y35$)5e@;mS>i70COlbGSy?HsZv zDdbyGNv&R|7h%g%G)k?n2tFYY|6^((>P#h{_*?2rT}?GCxe9&~Riy=aCh$Nt2ryxU zZQJ1BVA_GvMnKuFaBimv{7h^B5njfhchHm&1e5F0%$-!TeoS(ene`CsU|GbORf29% zH+_nFJngEn8*cgi%TIvbPeBHyV_24AD{|T=%5dS9Il*B43^ty+aX*6iV^zOF{;?>_ z`yT}8pgei(`KYDJVyq>1>Rq$+!ZG<~U}Kevr7CaDYNH<@*m+{xDZ<5`rKESf4u(vwX6$837Mc4jcbMUy-Q=)tD~++VlvO+3d$r+3(h$ zy3OCL7q%EckF5;KpmcVP5=#Z&)A>R4OxKLF;_S>?aRmQbd<=dbw5Yi(nSXiUd$ALf zZD-*1s{R(8ZmwsB>-7}S%3!=HG;c3m;Y)#ysQPWuxui3C0=rWua6O;1)4yPHOP3r2 zc4(wsbeAOtq9YUjoM}Jq{ftzNYpj@hqo@c_t>PF@!_9}en7D4_;pak&;>%!cqwevc zse{>he(6Hj?)Z+%D)vn6!J2z@=EL>Vpp)%fZGn-Pf&Ak)EPj zREqtPd$Ax-x4mnAi=e$ceSW&S<5RIGBwLeY@Y$m#F9h1Bo{rz}h;iQe0X!9LJwh1M zTI9l=UC5H3w`^YoNG8D?%X*8-pQf2+8tlw(!;0E{<)?i3K`xnuZ^-oSIMl=|XG=pUKn^JRgO%98%A1d{)|32~D zEpH+Kqsf;KsFg9?Vf^j;t;}pVX3L>N>^H>exbhyr*@hN(UV6Sk@8w8q%|| zUKFGCz0~zbQ8vlAD!V@{M%sEEti!wK2lz4FhjxxYVtT&8o65jK z?|Tv*Npant3#Qg~c@RKK4MkbG-^s!=3RgN*VX|NG`IkqUXz_bOH=^WYit`qxGd}RG zB{h-{iQrHdg9+UN6!z1F-H%2D4PdTZ<4|GG+c)d4Me=X90i<4d_ZL(=fq0!$W>AVs zs8ANUvvPmw!&!ow{D<;H9bAoRdqFon0Jq#3XLK|Qg3zJFe0irN+uF z(&9KU-DS|ZaIaFD7_k>r_Z2kyPGf}dVi~RWw1^$ZGnWXCb>6QHGLEh0`>f;qg!f%3 zGg$HK{h!2gL1aXQn|Vara(5Mm^yJ8HsbMt47m%Ra-0SP0soJJ9z3tv;H!*Urwm(eY zC=n>LYJl7mCjm#L0(2~vd{R$3?OS^VqJi?R3AP{|M@PXC z%~_4la(y16U8|GFJ*lDm;p~4e!U;MN6ApW_RAzl7klZ!C}hnCR&NT zT##qWHfPA&j^-B=BT7E{v)yIYBh%$3DeBw)4!*|SF-#WJ(@OlO6c_1tc-fw%AjHWN zH$8OTf2Axk^0;B{PQhS#)$~5;QZC z`GjxbEXt|rjH+qdJNB4t%Jyj`<5b10`o%~^He8(ldR|vqNl+cd4~-xZ_syAeiN7zb zOFnxQ+RW)43RT-S8H?4FiX*z|nw!;>ywl6N~`93Gz z>7(d3q^$!CMFWMataehY8hs_gX z#Jk^@`sk$okHmN-3CD$|Kj)_Z4o%yqe|6liOQ@)WZF@%i&m(uum9EqTrLrCUV6C_f zRloS`Aw4ZK_#RcLRB5^sDxM4Ov)Pz6xipd>AD%o-#a&-=vY>RS@2bu3`uV~?o$I1y zzq`m_!VO1~8T0EgB~+%bp=xy`$!aJC=k{LW0@&G@F?tYK1GgGTo<2dFdL;VXJIn{NXziVV@y0oLZ?sj(6 zNbk^=Sw)}D>?Vl*>Q9@QI&^TD*eLV7>nu6XYeOmwpCU}l1-jYX)|6G_eBJ2OKyD~n zRXA<2?ZM%uvUD5Nltk{JG56j^ve?3ijJOED5K2$S&+`k4ce$j~4*q*oEq8++c0=Bv zDHST7$e(a=aEWa8@59WPH2hJ#9;QQ~+%K8ez+Iq+s{%MfTg5NAzpHv%u@#F%+>a4g zvjI<%eNqUD>}kE0-pp1Pa-FXQizRcL?4~?UX!U9f6vhz@m6^pj>RK=@d_X429}#iT zAG!mkvi+wXy#{j>>%@48#AxfR{nW+9=f7eI?;0RP1_Ye@hzF@r1^t z+X3a4{9UUU^^yNAGP_=2Ka=ape09S@1U0i<@4U1)4MvEQg%54^CVNa)HEn|sn|_k2 ziUBO}pluH@*jL{4SCA>TpW-mhd)6n>BS05Chu z*0(gd2n(~npnH@P@WIEUe= zwCv$lSY`2a!%$@ei`A4vyt7fxo-Cg;KSqPpWZ>tFB0?zpe@w`1xd|bg?oqMp*pj=i z%%`JMr*8Fx;gVQsTwAd(_!&{2)7UC%K0qyuS%w9Lqpe9>7D+o#lW-JtL^SO@nxABh z9uV$7$%%K->MZk}dzJg|DId6qb+}TRAA=G+Bk@Mj@LBZ7#fp=m>vT@5A3H=gZwX=) zXuEC){$OA&i;B@ny8I@5-^minUg~#uG{7IF9xFh$VUdvPWHo>DxSKSDkK9}ZjA>R&Ob&@c?8&Ysk z+1?4(bXPB%Ajt4Tg@k|C6=dfbM^@)Qw0sm}r!Po0Yn!SAbA}6~s6&E>zAirW`v z!*om3V?}=7cq5ggHm15I*Dk1dUK`~-jjIxS*;VzIpv}18s(tpTal4wdx6;;?pX=uk zj5f!uJ5xEg!9?*3n?gl}=Lo`T$Of~A8Z+;Uz2nSio}m{QATgEWb2Ciy^^UXf-4yjOO3n0cv*x( zz4LF^H4mYu(%XBOhi3EnpUqNK_jd%Fg&PTy<6UIA2pi*Pnf=a_-YU&Ez*?B?G3|Zf z*jh2!4S(5nNDUlHv3c|UTjxg`ZYFkoa?w}FP0O+KMCEQM$>%ETlE9V-Er=hy`E4Pv z>AqMP6m{O7IayR?Jfg_3eFx!rLe5#_{(jfc7+xQJ3UaWx^= zEJSV-U^vTd+7G%)6?GTlB}C|^;Mu4*Q;zfyZLQIITsPrY|1ivU{f)W|0JQi zRKRS_^)Fu&mz6_Q4PQ2Z&iaj?QBE=KDsofUCK!!|Y=b1MTp#yy z8^S32@l=RxU(LU6VWKDVTk44DykLfSe=Fx{$YaDmeHY~Q`oHuB9T#!#YgTQmiwYDX zO`CST+ne@$8$qmNQ$W5}a@ZOJD?lv+5#%h0Ml!$yHE<-s0ENv@BAP81|cp zNM+|m+70B`K6XS%=Dk44Ka_Q^a6L2Zd(cA@rQCHMX%_gf9Z8*^In|qV756=?$^@>b zESL7}h_{8W35oz-qU~OtWHHLs=%xX^@&C%_w%qvH{*zAY9O=jkY4`Y+zV3=OlrmOf zI)z+}b$2v>yjL0HlWG{8P=?{8v`o(AaVmrK@N1IZT2AelnUIIcr4Jfx6iU6~W~N7? zfokqq71L3(U+a#^{&AQ2)Iq~vcCRl2ykHn1-yOm?e)K$z%d1s5$VrZv9(D@=c~UTb zoHf4nN@pyGueH@;3`tJ?YTjo3w6V!cQGDP#uu3J~rQR>W>(1y=#i&eF;B)NfZEuXb zVXoDiE4|0+R0cPekP4MuE$lfV{_|Sxuk)kL*s3M9U9+opg!X1*zQt8`IHaf37OHU< zxz9vxxL4XJ)Y=s3arc#Z>{+YCn}JAT`}mqvFF_8g8lwdtRl(dw!Q9<%uAJeSZ#)7@ zalf>5(5bCnTe=IcWC)S~W9QjFRkdy5F=o9ko5@WQd<_hvvv}-dMUI@k;g(c*5z0IU z)@SZI6!K=w)%QLs!{}kIk`vEd!626O*j4RC`s7zfv*K`vzVgPQ02g&{-3yk{N|S+9 zGqdF>@+dTaB>pR#Oz)-+nM##oaT%qQhN82Qjm_NPoywOMN zGPT1&d7UgQp!e}jPqnu@3emPgji&IW^=#YeN>kl<>h5SO70I$J52YBc?zvPUN z`mIK?(H*=$9IEbFd04zYC#V-~y%oXmI3mZ=tj{TDrtX;(c>j^(gsCz00lJ)7erY^9 zQ<`_YG~v5i0vGj`-G1240Bc&Hu)&U1|ON4gc^Ov3~fc7Rwxl zyBby@9d(P5-a$i%2rH{mV!mOy7^aEcMWNDcxrl{t71r9dC35qeUWsQamDZ@`9bGO3 zAlrDe0=1$ZBsF~a$L()O;S(RYDs0UdwKa8Awj{4ISJW?5@XJGCB&#=uuO5G?zP3xM zz@SJWrfW!UN5|L2`+_ma*#xcz>#gvbiWgbiq>6mCqRniA$tA6tZZ8~fWayVTBb3}3&t;mTvH+HMXzH`WCYsB7o9{NubBkJ7q8LM z$pXLMD<+%c7nUKBG=2i`!jS?;nbcp?8(_!*nVYpY?kcK;m8m7}vf?~wXu(pUd%v8Ge9{h`hVSt3) z107zVH$Zrdz6Re2Fcz1|t4^uyG2)&zpI*j#%@p3)NM-q>X*gL~1(0~_$VR|Z`_sj& zGzt}t0mGD8kn_pO?iz~jFk)n(?yIz(Qe`YtAGe3)Tk8_O#nLv;my3QI@J7D0D1Gi( znG-jgTJI5Ac?6HR-v$`UEqT zIJ(2<`F!$3VfD`{uM!^&*Sh)@!+RYen3Pz`NadU%9^M zXt}|YX)ffaQbp`VjT2IgsC@-qY{q$0C`)$2pzT|TOC^*x1< z%nErXmG-~OpDIim2>qiod1H1w9raia?|+pU*K6I?q!*kV(VCW z?9JIo;FoFd7^KTUXELh=UQ%(<18>)BN9XJq#*GTO=N{^+EGAg4M_7l;O1XpRf6axT zy2xu3ywDflfe6@+^XgXRrBP|DDYctuyg{8MN7xbVKW~4S;c|-Q(xmUg&3&L*m0<*1 z?KeulNavYzaUP@X+4tg??5t8gGR&p(M`J(V;Y!so~9nh!&FH5=@k9nb)&}{Q9 zo3KNP?qDmS%(SMck^1uoYgt!VFH)qTwutqbStLV^rP4`6iR~pG zJpL@CEWP#O(>iDJP&JB0ol+*G0~A^x!y<{Kz+2JMs%UFtQ=?Sw`Z`sc6FLxQs`Be4 ze4QA#kndZijc%O0G{x+GuR+$2=(CE=AF3qR$gTx6)qK4W@%Anq=sZE1H<`Om@qMT? zRRYz+j#Kk~!LNMfJ8w+2$lEWFb|!q;};?yE1isekzyixEYz| zoE(me?x|h#2txgaRPW}ZURBBnmW6A1WGYexYrTmLKfYCN!u97DmyXR2O=&VgAcVbb z6udM@-6(K#XP$Ok)XACpC^ZqX_@wsRSV*ysMkS|){L)5QI3E>G3=@dgYT4~Z>BhV< zpy*)=|5DMh@duQ-ltEO%Cerhafd|$WKbm9Af`?xh|6E98rMw0cy_87ZVWYgZbec+y z{{8^RS?jN2Q~8*Q?UT)CXtp-PEbE|@N4Kukf}E3U)l_HPxW+szEl2U(=Z!z81i_3O zZj>%RTqi3mPUetKr&Lvj)4Gwhw~U{gF)kyq-S zVJxV|7qKX}*9>PtOdXCDK7zgVM&dnJkfqg$=bCWQ;6B;&HjKU({#HslI!mIgh>lXF zPKk!IzX4u|}9xM9Er;)@aMRJ6xzDvhvpff`S5 zg>^I1RUylkbubxQM3vGK_L>UWMHS3&(jvCjv8%7tiopdh_4VEsB$t#PnJ7uFcpbaz z5!-rJ!`S?|^)spY?1h)&i>#`NR}*Q;$@YDfHYWz~NLrE4En6U^v~Y8CJG;7yPKCO7 z(^~McQ{f%DokruHM|%x6-}pv-Qp(ibkcy;$w-{EeT$tFK(65n%UquE zZXM~izv>Vap3(U=@yGf6u6*b8bgblnhv_gf99cDjIp?wU3*&0dwI-ey{377lYjFKP z{Q>S*+h^bikU}9!e}A@@58NrROnkVhF|eFB@l@+w<+DXTjpvNKcy|-_c2QB)@~&pl zISM5ONanNrVLI-x_#bo=aVmf8n=8n7>5249z2-k}WT<;Q&7SP8uZu?Wd_aAJ_J)MyLeJlL?^mm=v1mnfCkLopy!6Hti`*LGea}Jw}3Cj{aD+XsX z<_?Et$4MOrKE(vS<0}~hQt?~Y-Z|InBeln6C)o+L9JT3N;e{?KHF9xv z@X{gWTMI!JXV{2!$V4H}oCd??El#RetZqz!odN|2cn7zcU!&j@hy5kZ^w|Fk`gKq zXjv}Wxr~UEB$H&@C|kZw4!OAhD1)D(SFE^ppV}Z&IW0*UCkm#%ER~2+_s^6{;)B%~ zdl)qT&6R2)vmgur^|0ccNJ~pTz?co+;o3_ZX=3?w#?T|(bc+Me)c9$|;J>;wpQ+gE#oxB#U`!<)jRP?%9&H z%aq~W36VOGr$l(*!6I9}gKlM$rtyaTYfLMgb=grZE^MtELnS4wr=lnkRr&oox_TP@D9#LG z{(Nk9fLdo<FDx|94cd0oOR7&vt{PA>{X*oH? zYUS*mtdh-Id7CZ5B#0@5Hj#`26-}emwEO%Tl8Tr^JC}T zD=jIN?e$}*usdeY&l)4P0r_b4JZ8M+(@dw2 zwIlg8e|C4_9ApI{Wk`94-A#z|pugyEVh zn+R4=X!lfF5h#G%#fn;+I+%Q@oS#gEm&gq%L}cxrD8&DuNvG8#D)<(8C<#5t39b8BlWh{C*HOQ+c(`2P9?7+a&Mrzfb2oyu+6 zxtb#*Ia%^*>cH8;b)jydyk`~`97Wr2ud_c*++d?lyHuN zuA7EQ9G5l;;CRH96Fnp!FAjOuk-Db}-I^>YXat08?h~$D=gtZ$v0GVGFaCbM=gMcL z{4O!IV};ZWTedTWd`&h9JmEN*qSvHpe{wneI&Wjp{!D+581wV`^ka@Y)jO~A&qGP< z4JN>K=^E$afT3zv1W@;y-}INp`oMVjWd&M$H2TEwpP{HU-9DjYNJt&yD^JY#ul&IX zRAKGfdU^``Y|=|L5pW*MZ($B-@JPzvQuMszSTRBB#>Ra!8@dk$!bD=$A6L5R2Mxva zZ6_sRrP8Nfs4iL{09syo4dEx~*$J0!l7pq_m1Ic3`QeBHw6sSGXdq-dicln{dqiP! zSY#gwd>#%_vUukzRX765BRmZHnzD-I4L&`?mdsKmG&B=LE#~!5Ku3vAm5380{jhGZ z_V@m+wzl?#$H(MggCeya6^JQprymFAC6c|P83!ky6C5LL+bl7?Qjngd~Qv&Nn z_LZqQCtMCI>?$A%0N)p>+@D60K?Y}f@uzmZ zoxd9cik=)Vv2NaKLYNlEE8ZSHZ|l7LGr58}ifpKAaF_3f>zA>_5DNVotx%dMt)B(4 z-*00PA2-$=&>bjrsbNZ6)a}*b+?9?=+OiV!_qUs`yN{s=H@+dkBp7+k`1+5f-5=XV zGy$^l>z{ax+W3W$RzjDgU220}H9yd-KED23tmd|i?IDHH4PFQX!QvO>OAlzF)pL*# z!|etf(OfVHa<==YplKy8vM)}nUZNRVw7g$c(~=m)gpC5fY^2~q0xmE6EZM#)W|C5Zz$8Rl^nk_?@4in^O^n4E;dTyd)Unl43V|q#K6$Ngb3Ab ztu?m7uG{s??r$8BA$brI#Xm2y0ekyp28B{gWh6Q|3cAlmv}q>ur>}+?WZjg0^YfZAgKUJNzYi`&WH2ozULh13 zPQ(US;wdvEHL-X8oKE@-Tzbdm;ReCJ*w`>Vk%;|i=FN8^S#=B|$N|D(`U~E04=hsp zH9sC*^;=d}47#H6%t!8Qy8tPed&6&|g#YlFc=R+C?-XbNr4I`;$h3cY;FV6~o4x5! zj{Yj4o17Y5>*S<)O=3A~Y3;=0wl(t}j&3-2a`BrK1x#d=k;8a)@A`UvX~AgCy(xNl z=|KP%kI`t`b??f0onB|FZ>WA7TNIwvyTWDYLln}(_eofYC|yC7Mu60dDgm!cE)~Z} zgZ~YMl4xGOhTpv1;iNey7~$&5wM4B<^*z3@5`BtsoWzhDzjcO>tDj1Z`__&gCCDp) z{1>;cZ=-nGbT=n*#X(hT>o=PZPFkb_ojKAHMfBf{c?MIZNj~!k%Y>QGeq@OI5HSEH#YrbNFBi>T=TrU^G#?=k@NT#|R7K z*Yo~Y0H(una5&pCChwKr%(<=jH8+2_y1qsWn3LzyFIyjDSxcp{dpA{X)d0!bRh8d2Lig2k`M}&CqArJ*EqHy@AvXX zH}T0ntyHh8)M#y%C}$ScwiecNp3>qNSOgIiVl ztoq+OhCr>?r~fFvvR7L}wPm$}8}rD39wyn6Zz>3~_o}+IilyZ9`<`knI^K2RywK1o zk#CuJ0qyPW8i@$p+%s{|nwFXXZ~(MataP0cK8Tzcn8zm(-t+`*Ruv8XjD#)(($LWw z86u&>GX#TCDCk5g7yDS{Q33@S;>DDOOLg+0>BaNb>rDh|^>V&0!nO0F;<=Q;WSAkI z@ym2Slo+DhYMG3iI+bmAkgH3QNMUoxGY7XLqoc~-r&3F&$?X0sD4~#%7)~lSf=0@v@ReURC+V5Q2!rZ8?HgC=e z1T|5H`uj9PU{|ij8>=C6$o}hXUgw;;n~THz15pdkfwdCzHl25?{9_4}vT@z$^wzEEj&O3}5Sdtza~S)UvT!_Ri#TGw){+ZpG42&z#ja{YUT} zJBFHSB!38DSS9NoP^hvfwY~kk)31F(5k?s_3b%i^J0SXvR9*uY(-5t46i`rPUopUx z>!D%BM@qaCKdZCiE_W!;2uy3)2>n<=%6>Mry>XcOo02JCUUfXljvk*>ut5 z>)$8HB~oj=C|mKtP}W`SbuO9#O7tE>9X&j3;`yRrip8diK%3rfU`kuh^+VI!B*WiF zF0oLYV3DiWU{Nr#kBb-TqYrmG`TlDZLn1%JzeG4JAmv9v(7zsV9%Xq& z(1@C{c&jPVQ_wT}+s^$(3n@1@H+y3O6upNP_@piZz^%}{d$&N-+OUHbDf;>4WfNQ5 z=-QVrm0Zhf!mk1Y_D7DA>1!e%Y78HW8_UofU(R+j-7*X zy#M=1o0l@h>sGBTLOip+O)kleIu23IxEHPyb!>z}|6Nc%V6~&CUraZPt*f?_a$|87 zC=6Sku3x5)au6g>< z@Wr7i_D)hJEs6cuRh7X+LDU)OV`s7+27p)CNShlf4OP_Ks~~#_TF@R->gr#*a}5F*G%jq`1A6~`o77? z1h#IW10%%>pY*w3QM6DUmfvE3LV+mVtf6z2Q(^>?She&{iJN^la*^1mA65f=+@v%hIHqSvF4iKLT~dq*w;4XvCsX1^=E^%QdMp3_{2J< zY1yax>Ac1k&d6;QhBrCNfBrQKD={b0H!~-j7;6)d$4Xgq5afwzV(Dr#ygJ8iKFwQN zP2VJPXgp29JuNK4Mx$OO?-07xHOh9b4mj(|z;KRw{ap!Ouv0ifG2MQ*MTvOy z?;%>rc2G{hT%u=o7Goj8^t%DvPXm*@f2AX@WGhw+8bmlgzu;#k)@8crC^cc8CvFD^ ze_x7G?VRmG{*3+a?vxkmqcE&|Okd3ame1>>A5BXjgh6SVVG`o>yxH3OrMi%;%>zfQ z=Y90_>gg{I*=eg#A(m+10-u zy~Eg{Fmt*vi}ai9Z#IiTB7QalMoEULL=&PwEy!72_GN?1kjQ}O)Sm9cDW`ECwU*uA zOS}eUST&$T(44lxPs@;gN=|!RGlSDm3+q}yhYR$NG1d;sBePRM5?O;78nl{#!&xJV z=&;8zs$M1dle}|CU<_9nv{!kC_^GTm=W7A=hJ}LcC|MH&i~p3 zr_(g~%4wF>I3ko)8HUK75beWc=(|}*f=Ysek>R>ozgUygW$dJmfgAn6gR!7QFj79G;&8H$|AH74jnp}4qe`tGjosFK?9CfK}7N;uodz2_4HSt?vRHapOvh?0nL3y)8e2=~zWhGI5r-HO zt=$U-Dxh}i^|0gKr*MXxWXK6d7~S~L!8G*s0a9bENg&h5Okb==)#8dhTmu#brgMRM zc(Yl`FS+FFK+b4?))TgydYiMgf+ozPDOm*YjZP(YiX%aa8%PC=+jfP^)t2&6kWS8x zKcWc|jvb+jVj`G014K}zVX96i4BQ1>1d)SxayXrJy#K`!g{MNtu#@daJ=28aZ>s#q zI#$>RSqV}V$?4=fcOyefAxM$Wcb{}7&p#F4vG7Y3?vwb$+Mu3aolhCaj(vW;w_;Io zkRi|8a0bhef1%t2vEf;c6tdVy)^4g+xd*&alDB|_P=px%KIFvW%_EL_lv@Ie%7NQM zP$^Da7)VY&^|8m{Hmk;;QO2i)86;g;wTjbsbJE1vkZ}uTWP7eccj67vQG8JShK8)! z`*D@Z=i5%V_N(!?Z(?8Qxkoj=Ht4kOOm0`)pZO zd#bGi$PIj4P|~L6&+e)-tlTy8LXnxr&)sgPb7Z%#(L6|7vTO}k`Ic`kN0ty=xw%j8 zy;bpyh-oG`Pwz;@)^J~WG)sw@qpnGFly;h!8YR34RRe*j*iAlFd^^ZRQTjKOu6wo{gUKAQqeN|=B{Ubu&+cE| zgeWt~Sd7K@Sjxh(9be#!BulgUfn8MPS@ z3cPxSPTpp+InQF^(AFHX^RNE*@DAM%-J2>tM-j?i1VDriF0nvL!XkyjAhCTJh6W>1 zc>ln~%!Xe<<%Vy#OnssD3LyW)c!y@4uYxe7Jl8^UXB@1Hq(!bt#xcjTt!`VwZCYE{ zoCUSRc-I@J+Uj?9VEzq()%QzFOV=K!{)4xO0dX6Nm4CVJJp8_lJA>{%Dpl1r{n~#Z zQC=%Z%%8S|Ai;}*(&5Ey)ATyO30JZ6OM;Q4=pi|EI3MkYp!Q)x#dCtbRzZ4eDe=ytL)0VK8;Hk;S2qIa_%+Ay#bW#+GHjsOxQ z6`TdiZ^vr4g@9pAkd~1qInP!zZ(YZ&qA#}I_~_hgi(=pNmv`MP(nhFXX_lWDeLk6q z2(bTR>7Z4@zKr>YH({(vAH%i1=+jaNi@3*F`|Z+6TweR83V&`iD-HQfP{~yNM{~fQ zgxD}JZ3t6jwg=-|wQH#?osvjirQE`6XGqj%XRLVuYTN$T3!uhko0rOp`4hgiR(nFgzI?O0fHZ)Eoa{VNkoFH#qqdoART^`<&vH13N z)`H?m5RU-GzmIZO4^J#(GZqc$K~NlI!?wEc5G)Q@ER=>a=ckKoT5eraQ|cuZOiV_) zbJfh*89$V2kW9c$xNLIljy_4IZt=+C@B)5>EJ5Sot)Hc@0}{(bkP!_t5|&)n6ifIGqA{su=SsqH4}A4^jeIEZ12}D zbvz*mJv|J}nE>)_>CE@KHX48Q0hdEs<}{~1+*xn(gwCdN)MS1!X^sRwsdhc=4@STp z*iMZ`deT}VUH5c!0JM8R?M*%^Ph36y2}&Em6&~I+_97n=QnG#q^Ot2^t&Ijfb&HVE zzrq}*KyRUgfr8=p4GxnGiRS%f3T`A`Y7`R_YTWNLGcy{#H{itI63AYkC=;qgh1TXT~+QQE%?#;=JtNWX0xE$WEBHT)51CAn(G?)e)N{8HSI$m>ZF z(+Wi4hfXwsN1}N9i6e@)gZzwj>ox!Pv9x#_l`^%t*#3e9*b5}cf;`8`M(Gxe@Gn>=lpIuXD+DBig$N}qFT;S?M@#@5XM^6BGLQ3cb zRU@wZL9(T+TpW~gx`d5>8mTz3%|&o7)7%+^yc2f)S$%9IcQxOR=0Ftd3$i|)ZiCq> z(10ImiR7UVJuC;&c^ct}(T^MxHTtz(Qs|J)ALMM7D>;CK?Tm}wCF303066ZnQ>#Gqv2 zO^=VEaDFZ<&|sZTL-x__=cRTdT$Rn6@$>M@-XcHuG!mTg@Bb3xU4`6NMC!F76vt_A z-3BMWDrZI$k4jhln3L3V(AC-5R6E+JiCF7T_4K0Y-?a}-O_ak;$W*3!RKUrO)*5in z52gVGt(RK)Re5A)?xp?%?AdMZ7!8?;ye#i>dcG3jU;E=p-{dOcH@^0l!{%$TRE*hmJZ7E$XEChc3(15bI3&n8e;#h3e5|VieL1|_xMM7Vd?#c` z{@c2DZ2@1f@RzX+uV>NT$Je+^3X@+&b=81LCP7OgOkUhVT9#}(uMCj@ij#!)GG$lujW(~bRjkUa?Z0Aa!)Z? z+E^y_8p=`Pd5xMOHrNmceK)}A&M9|h=fxmwvR*AKGaPy)N=d=jBR-Yb=~6hIrmue*_X`1&k)ZFnTd^CCzn0I*1M;`;#f zR3d39SrlHMSSZVId|8@aPtX$)%qCZ0+R0P_w-y5|?4AAhG~D8bVmgKPnhOTHf0Qv= z?FzXFIz946iv6o!aZ65ReruvB&3p93k`uEK)TNilop&ys>riI;RXb<*5`C7CH!lkk zeixwKFmAz50fw47hmP&XruMV-<=1ZW2F#)*s~g5fy~dyi$NgkV+4J-cASc>K{{TT> zx8IiDdER3W0lpdv4i1isdv8E+`Td zM%Y_WU(aQ`+>)eA6k_=6?v4+bMy9Ia+KiRb>!U4gv=#6!)0rc=ylD5WsCY zq_KGY#TXeG0gjd%u=<205#$Wyh_*p9ud6zqPe5$4-LY_CPLVmL>6?|RJep=!k-W&& z0KgDHguMfJoj)%PE$sBs`}NZ!eGk`^4tiZx7_0=Apzu$B`uUI$%a_N8OY%OP&b^S1 z1T8KJq9naslt2_5(*1cxcRh%Y_bJx(5yt&HZ?XzoOQlkC+w7}o!`7)eHIh}11j!qu>K9Qp3kibUl!J~ zZ3@s*Sz00yx}P7Po0}sKXLe;g2U;v^m&NV)079KVumP;=^5!JmMb=_0U4CX>^`K8n z;wRK7E?bsF)p^@5pBGu&|NBRY+=bUvO7jxdB)iDEaD|+qiIjZ3r0Y9NQac~EXMsAS zz61sdVCCD+jjs-Mt1@1i3z5mccSxXVORZZe%nO2k=;*T4In)DtXc!kM*7EriT^os& z@L4Nu|M1yE81Jczk)c-kM5xNV{aXrWa^g+N#wll9r2eaG-ts@6ciHUA>0zPyfbRon zyw5+>N*Qy&^DQ%DV4Me;dD*ic{i+@gqM$CakjF#Jr=tWtaQI?#?hLrMW?}Vk%InPL zt&))}YZSPPP6(-O7+p!Yr>{@a1?00PX1kG4gTpfasWy3=JEd*(Uc-y1fM0_-$(L~H z^8QPkX#}Dmo!LHT-5@ZM$k(+89T2eZX=wepo3(KD#4MVc0x+>4`vJ2aU{DHBKvPNO z0kF7d&xsHDn@Y=4xprd>M%zPQR$@G%o*Vr5`OVEnOf5h5$x1t*%Eh1(h3YB+AyO2) z4YK8VO9b%Et&JF=?O;N^pU%34iGYouFj0ygC_sU%Y}SoNeX$By`3joBq1W*US5&t2 zzoScse{w#j3zm0|SlE=l%;4?e2mPM|4Gvvgf}g^^gC3;x`+qi2S%5ahZ_^s8t1_?ZeOf^))r! z7%Xjm7U^`b8jNzlk73s5TB+0A4PcP6OkQHQH2S5_#UDvv?r&jY+r!x~QHV(E^7cZ# zm9?$y8L;uJs-dC3tg>TB(f3Z}t)Q2N#&y&ip46<>h6$#Gyu67Djb-bxlpp!Te`aGc)(=WmlGZkaMH!wS`^4i!@3T z>nbZU_9eIAf%#R+Gv*2T;*Z)aM+HLxfc@ywWY$tBA6 z59%hecz4o886jEJ1DPmszU*fS4r<@{LF=Hd;!BJocGMLm;c!v1N&DK_Q#U6Di9Q=~ z1#`K@!pVk)hSZFR&; z*|xb(0B*K#*IhfGqKxZR9QP+8lq?dL3nXK1{`Fu36b{HHD_-aFdLDb!E56U(m_2Jz zJS%Hmfv8^px=`VO+~09GUCB;_>2}h7?RR5T0WCEkLRr0ExyEYBmPkuW`&&P&x6y+w z1T_01m$@f_f{IwD)g?;1(e^Jd7U0?Oy7~Jp?O^b{tyDlV&Q9OGjT>9N_CeBPfum6%PZ5uz5fN?`>&4WO!#?ozXEh&Jjg6(c356mv z__?1DDqnlQZEVog(dbT3qxEGlL8HAUVzE&!l4GU30tu|!^HTgQkbHXc_s{6vh>#F- zQ5`5BZDXhhuVXz*D$TMGE7CX`!-l@8lxU^y&Gl#VR8Km-DzH-7ES9x?OPdfy^obnr zVX>LhO35$h-t}TL9lz!0@R-crGAe|4<{FM>EYMH0I&zt{Bg1_6N89|1>fOxUbPWF7mZgxMX$=)$x z^Ex;<5ODiP-nwhaNql&81Z>q}lTRQADaio;yZsa6lZYk;=X$*KcPuMk!)TG4rSpNE zpPwIDUFGd0C(zEWsR^)12fjsskITx+dTqVe|BEVg)1`4b#ENOV)YJv!E;6rw@a=k) zUuUiG#8dSA5Sp(4z5PLoC*OH{WcLxq^wO{&wE&+CRx8l|wkliy!H~zKST`izreHxE$iQ#3pGApsQ7NUNx77nf zw7!V9Um3>e4+Yi8A+euLcyn&> zmWg!XV9_;R1#Xu^-ZB5pU|QaYrnHH+2AWhWTbp|LWYdTE-H8kQ4|o1x1kyCM{euUtQ|~z{B|o=pKLqa>1^} ziR*s~B-6eo_8&8`usB}sf0mmZIVL!~^awuxIDT%iaDa&FPffaTzxF&Xfy-0PyAu}p6qS@{)Go8dV>2h{TYLhEj4q4zaf!ZT zOxvM1joQFNn6>YphAWKS+_+IPSa5-&GLZ455#~=-J^tG8H_mE1cH+}W76(VhxO?HC z8);Xr4m2oUg}?}*rIy_3Y&QZg3J(w;O&X!pSRWMT?+3g2wkg{Vf8>utcCS1%nM(c$ zWu}OD4NZzEeGX3si=h)k4uh)8EZ%$hJY@r*G+G;JqN&;ME(1{HP-w-$S$(DVt4YrJ zg@t@zBu~iSIgD!iYPSL)7y!%r)q2vQtuaogjF*>aYZ4lhK$X~lk>U5WBt(!Z_<;B7%~#7(n#; zH#e(>{ph9)iL5Y(x1;b26*BhJe~HM^P%C?(sz3&K*P?&2Mk3~*(r?Z8p27p`^#}+E z6qYpw@8FrA{2n-YzaOjMiDL>J3ApS1il`wxJ+FMpJ5eY1Hyt@>DwiIljnJ+-tZXFR zFM_xM&J^FU=zxd*gQrxBemXe$mcWf&U>s2FNIh(?0EEX0p%8lbi#@-%I9xP7I-0eg zIrb{$v^79o-z@?7!|jP;*<>6R1$E7KTyY8BZsMko(ujZ~+bf8&Y!|upZ@LLnfh@D^ zx@zL>{n)$cJm1vplF<6t`ah06iF3R(Rb%uzI#}AFuB(ld>n4VYJ5;P=Kb*x)ITG4_%BtaicJp`g=6-R^p#IY4jW5HE< zXUi?W&aOIWig6UepD89xyAJH6hgOu~esD&bn0u{6%z1`atsItC<}CPTBvgQJIgA-j?;m zTMo@i1ABLu2S9Ru*{o`6Y6`G(C%ztjf#EF&?nhpy#`XLT?N#l5&*FYFo(Mz&jLwGf z@#mq>G7%6m?+eJNX#!pNKY^IrTX)9cAxpL9iiizfV9DvBLT`$mN0>+Zn4-@aF3^q1 z*-h0UI4)luUTp%_HvwD@JewMDnvZ90Xh}l&cj#KW;qQ;ePN7{2N`GA!b30eoVU&7k zl9X=SsjkY~k2C9&VaOQM{+yUfTTxsH5$JFd`*lOEtX;~+@8bM%P{BZxYGt-8e(#h- zCAF!a0mbC(6H6aa^F>}NNiOeL)Wvd`qiE+Rykx-Qph4r7ZNxg)=ge|#7br|V!M5^_ z=1*+DlqQR^n@{Rns-R!C@%-=6b7mA8Wt*Xb_U~5h-PClT17R!YZT^6l5P4$UmqG4h zIUlrzIni`sv#(e=;0qknzsDN|%AO{?fW#NhnEkQgX_b2A{zUF+fAy;A33dQH@=J5r zA`EB~11@SAdSF>z#ld}r@vMt`}GbJg%%zq0Cj`NPb!LYidf>UvbC-qv|TMCyUEp5^)N zPL8A1(dVnqa~$lBN~Ju5OD2))hAxR~hzvaeAz`!q2FmKQ8QH%vp_0k=#&G3V8aG34 zBYf=%za;89A|v+Qk*VE2=riNGU}jFkzkhx*W?*sYC(Xx*askX*01f1g42LR3o<`W} z9Q*Iou2Eu$N|u`~91sed2LT+TXPm62wY8^yh|7BN!{@LhdxgX>n-9xR7aqFSJE8B= z>pE0$$asidUcWo_*eg)Fo#J&ikE$9;N&;yz#O1xC7A6lCHiFbBN(rT9htdt6lcTe7 z7|T^p1+K-WOQ*#Xtd`;hQJ7Y|3!1jX^|?sx+rmLyq^^5)h?5#8ve^_C2m(n4Rgmw9 zsR)0qaWtcd5-qp)C+Aa(g2^ce>8ZpCKoH`leTlC)?&dS_{-mVSlI&O);N&crukoh* z5+4`lWAIR%^`0O}sjZ-L*0|a+!S&%HOz7z?wii>z;}^p<9I7*7)AxP*A`m(zV>Xa* zKX0)=N-{IxEwy^)lh;&oJJg9%>E8|i z`@_dYO$L_w>Ya~E#|*2Ft@o*8BzmqPJWm6zw-=Hzw@<4-AeT0JkIopw_yTv;<0p^m z2S2=wam`-6urbN!{DIC#ZLZ`_gR^}*%?lT*WAAYocT?Bp>eAZj@h7E!c2C79InP2| zLoD@G`+|?oDXpt*eG9%#V@oW@6q|h=S3{0=k9v8rjV}kCbAXy`!>mmm4<;;m`%zX- z_J@PbHyB|`sOcxh$!;);Afa=cYs-$Ln@EEOiz_fZPo z@T@)}F`^e~Xuu6ywkNDWUmIVPG6Wt8P@Te|RjmLN_?Gm6XjVv`tQZ8T zE7(z*wD>q7dSx;*`MiP(2IQ~o#Jj^o+*vP~KDsq%-_;8xIFFob)1mZ3N6uK)lt`wm zc-%%5yw}$^=&T-(@u>s+av%y;OvJ^8J?i>bZ=xi0u=f=S=AN4R-}`Q`_3yt$7uV!; zfA-ZkxNoiXy1FwH(~UTKwu4yB6rZW(l&|ItH03v)sW;xfD#w>K-I-EFz$K!Lrc4aL_jZ~?&o!|@Y(LXKmf(Sm_rzk$<_6>D5jxMP;2n)|~ zxZQZF&)-je_+Hsiy)!0w@2$0@)B0NS>;(-Z&Vx3^>3_LnJFHKgGs@{!)V2@eEq%?j z?#v92fPQD?-ti>-9K=ULfg}^TGURykCv=q4h^UW8i@HsfzhH!BJqN^W>` z0o7{lpY)YH)VcY#=-N;94FP$=uPMY%Z+*UeDz1*&8}Dkmo(96-4OU&RVjtkG{o$5Q zK^^a~?FE(aL;plMoHq$D-dsU`#Ez6OrGeL|xcyb~t&_0jBQ_5Hh+;f{R#q&6ed3Ic zq8&U--GEQ9DEn=fNW5TZ~lDiEq<6K06L6d%8P<&9h z4rD&>bi&nlU$evK(b~#J6bo}>=Ntdw_Zg)!V-y3vP&!ELH31O;B_=2e(5gr5FvY{`s$XB(-;w!V?K%|_~oC)T8 zbt~e|o1?`yPZpfDj18!tV;0V#-{oaKHcZHQfF7LgC4T<8lnn!#Jq+zO* zs*sRyiIvvC6U}UUElH2V`$r#|@Yf+Cwey7lfj9TnVqPv;(VU(5^T#tiVu(}de!(#R z19mh{DLKJ+3Gwd_#%uSX^cYG5?UQ0Jd1ahd1}&f=Oc@Je^p0aWI#x|=jy>!S2OquV zq~*uc7{27&GQq9Y-i19>y04L zCy0}LzFwO`nae*@UaNju^RyD-H6F$vAIL1CeyH?Em*l!PGb7gH%DntEp})N?eN)@| zl;(rUsN||{NaxZ*H+o{b=(broD3PIR_9l~6X=Fr|x6(87GoC5J^yvgTEl+rg`pEdyhEEt+ zsxTaGLwK?6p5A*z==yQJUJQ(M(*d;0G&7_{XDnWO&gDn|;Ka(@a#*JTA#HcP1qE!Z zdVkfNaVB=nvgi-IY~WITK-J4(#iV7*7pEHy?z(QH694W{Dpsx|I8gpyNuQ#;6KaY{ zamrO^|F2tC3K=I~IJf(+xC@}h#F{4JfeFAk5t_!(aTtD{XjeBO_nbjoS5~0wS9B`9 z;T*n~89xKVMseR8Oy>ugn-IpB=I=6deBJgA$Gq-e}&-w%*&1VSZor@~4## zPLmYt)wYfU-zHfiZ|>qS+&{A~y-NrSXg)p5S0Y;UI;+p^f1TWaRLUovsK@Z@E6twg zH)wgX;-N4fHqcEFpo~%|0*>l1C@y^-7kh4QwL|xVt?He-k$4KMi{21hKK+y?7z2R zPQ;^{e?8y&N3R2yY|=}=TEbhx_dfM?{>&zpU|cI%TN5l(5=NR(OOyJ1>u@66`YVAP z2Y%3i4lC;2ghYp!215r!23Qd%m|fEhFG7)0Z;YsUC{o}xhGMBXKAP$~Fjba>zZhT2 zL4OPXG3n;m7S7m9mMn0eS${aoyc+q(o~dkWYv)k!5+zfPfF8gaih7e^*pPP|f9;(` z`mMYxab_-E2{#3TkT;R8G`P3(Yk-wSf^;SaSdL)NopW08o+kT*;4Z7~0fLmr15A2L z$8))C(qA<`JpXeb?}W{Tmt4r^^FuB)FM*zgd&@b&OMc1gsDzVrj8mQ=X-IWh30Lx} zW%)QxbgZr~O0QG0Y?-*Tf&2Shi)OJ23q^r7*wkI~|?-sG& zi<}BP#|Nt*rPO-AT;u#iIZ3*B=iqS2W=g3S*S zM2cv2<*>}_((0?tpZD^sj(ab!uc%A9H{=|rin!g|rNOm|G^1iw1ipjJz?3U5nl>Ra z9Ikl%okD>zId5C5s$aOBakzr-NJ6R*!ZI$h z!+1Lpw!6Zl(lI}};NHq@xR~qJ9>GfWy|T`tLmhy!)cU`{U#|6DBk{_nyuV$K_CyW) z|5e)jW`3v&q1}xyyIFHN;+}H3+G`|46h!PT227Q8SMMN5r6&CCL|$^$za-xZRJKqA zISczK&1LvOMs?Kv+*dNaW;&welySVUsX0D<%9CVbbqtwEucDaHjW_s`5{=qXBVG(S zv-C~r3NnqWlGMR4Jam!60Q7bOcGpOic13%)Qc9R=UXbkfXEEhO`PJ3coECCkn+XfD%{L-uhyScJ$|br&Ez(@KRH~6wsjI8n?@7bxm#U9#+f%^0ni|`@?7Z zpnFk7*YffAm2KUlt9o15&sT!OPuhnXLVxd~4n{H>Z)OyEQg5MD1P;llboyZH49vIu zrw3BMAEdK#ZEEgj*ZGudg*wNNueU8aREnL-ztvF&BoA(!{8(ee{;IxVh3zOPc0;4y zm$L)0b3B+~8d|pUI{Qm=-dTr%AT#SR7xDI9C=>SNk>I;i`6!U=b z|6Xdfb*Ti^nF1Zr+mugYnF)M(sy@MHp%!oRVx=ZV^9@6S`lF zi&pqh{nU*>&Z`$L_5V@zm0?kSPuL(x35YaEh|=KF-7Vb+ zOG&fz(v7sFNH@{~E{JrCfJiRAG?GiFbiEJ${_lHT?k@&mZU&(zBF)mfeH!f4(X)oXxXDRG%K$&zalEk?aKX6~a% z1i{0I5TU~H@94i9i(Gy$jD;LD4=+;}@95#AjN2uLjL=dkpA5z*Zk;qWHT|sR#C_7N z2o%_jrdO)Dewikf8!e{&GBxT)Ib@kz3rbG$ukt@|T~PfOT#MVV1X8QSBZNdgiHpdt ztE%;s_n-HU4|8aOY0Ykp(5h=AVMZHHnL5avuQ1&x{mUIMu6ys`scSyr=OKosHC%V| zV*Y;QzFODoAlN}FbjsYU4;ayM-;Ysax~M?j^`yP2<6ES`)9KqJAK#Bkg34%>H@{v1 z_ru`1TiY+heIMb{rAXfKCMM%T@Y=em8qLBVd|a5MR8+)1_u9j|j6TH0HLlz} zkk!3=$lO$|V@I>144bMw-yn~#QXU-pnFvG@Z1I;Bx203qNakHLew^1~ zJ#hXhhaOwHOWxIf5%OS>WA>_p58Utd&g?u8cGlO076Y#xfoL|0Qp%T(x`CiOL(@MC zUJX8n?;2a(U#8w2lPU-K#AFFLAFssN-^}DazS#42F|)D?H@(g?-N3y6Hbi^xd`KJM z_v84OMEv4&AI$Jx!q1ClUEg=g=k9t@SNTn~g8aTR%)p?f!l9qv>bVg=c?l6%J_wo-=hE22H(*)rvTZ z=Sp6F$d7C+Mf%*YcwT9J%77!YMJecv7p|3}ziQ1d1>_LP|Pvhn^s`YbB( zd#kyeXlA;4nS~Qj`zHcvEakgb>zYP&sf6$WPtJ6g(5S94hmuu)u*@?I6Q}_v| z&Vd})9??yz-K3ALZ-rjvqk(UTwg3!cs`qQa^6LKbk8^Gg#%~i>ZSkQJ0|nFciiyJrB^FV5 z7nCZIUW!HT8(t3v+1Ie_Ie z@U7$2549I58o-yk`M1i`!5?!czUUcBfE{n0!qi`|^6P&YavQ(P5)$yjuEHGi`gM}W4g7Dx+#2jjwbmM{l@X62)ymla$J{2t*2dmeW=Lm}|{Yh`L*GbS5 zg5lSJzVCacPdbEUdH-0CSwR_?zIw7&$lUnXKs&3hFE5y0ag3n+bcLcsu4Zu#RK>?% z&L+C+6w~PXqKh*l8pqJlmZ?D z403m(ZSf;5t&nVVM)Vsj!I?2*YkHtaHPn!vyFKCY62VyM11HKrJIcQXPnrK zPI&V9wQqSl1cOrEGIZBj@VMnS&mA}d<8QI^f!+JClRz`}WfgJ8R|Vct^NTvI+~rYq zTfixEO0|Oi-PHU(!)^o5HLm#>Y-opGXJ&GNXyCc16ncSI`hK{*?GkmPL$q`6mC#EB zs;K9E_ah6;6LhH&qIam>u&L()&Dt~CyZUt0dF6Ef1C>M{!>z$`UD>oiSUZi*t;B1SJ(!Rp{F9XMpS(=<9FJ zAK+q4ccDfGF0&VpgKC2Kf3aJ%u2O%y=w^oBnTDqTlSMgexG=?C@a?}0j*OT9$#Qy^ z*&lTGBMfh)0}h?VzpGX}lm0NFRn}cu4INfdKlfvi-hJb%OQL%{(U3VoZmg^GYox!) z%YsO1a*v&H17$febwb~~(VxcRB!VgV8cKfcZGT{zpig{r}|v-h;tYj)(2Fz zSP9L6At`;9An%~kI+Mh^ol)BrX8m#3r)}I%%LT4?_RdC}G%M?VeP;(I4QmoFH?uAO z=>ZM47?I)Sd#)HUL)w_Sr)It^Y{;MFfn>qQ*uX_MFU`!$v+?#$4-Q5Zh40LZ3ktqT zq_;0m(0dZ{9+?-^PGn6j;u%{Nbh|V0);KJQy2=7SmHax#p!E{yNQ)9K;2YZ!7(eeF zH=lnEl%ef<=g@Ppkj7+-`FRfHot#Ru{&yWBb9K9S!n7+WjLlMnYMb8MRfOqDij|wO zhMv?Q`>6ZOZ1^JjHILJPR=a{tkJig5z8mz6j1Z(ppV~$9&z)Vm>cdEfxl!{-g9<3{WDjA$rOJQy+bkl??Y_waD?!Njgzp+zL1y3i6q+_C=eoZU_&$W8h!?EEReHoPu? zN-=x@P=Em-P^=XNP_+K>F9{sReHK*fR_9pU@{6t%KkQZef+oT@B#htirzH_Q;2Hve z={bliu;5N~eYW>d;1oeOb5zg@Auw+6|n>__;Tdz)Rt40?Ff}sngmh$J}TQk96AqhoiRcxLdNv` zm4Y1wvv9Y^40JQk%-!#8q>VQ$3ayDMa-a_1mV9|$V2}5g7LiEH!Q%1R7O>t*cTMVQ z>~-LENwV~`2VDDZ$j#KN!i>x;EsNYfnJls9dqy9PLb3D0rWqI9^7(o0A+J&$mH%OZ zQKky@W@iRIFGqOTBY<3Plj{@VchHt5(6*)OovR?8*UO2U>$}a8IkZu7u3M%f73x^hXGekB_gp3aOB258^$ef6^UQqLkCucN-SR zIxy+OIzWQc^YYRt{_AS}BcgDpa1iv-kTp>;aVq599DclGs8WoiN|!9^q#cP2j5v(> z^L}0VnIRvAv0+-O18L1qE=I^8gGPFn3OEAE+~7VK98{YcS3gK zB8J+j3OC{f1G1uE`Rkpc>-wp^JwLuJ@T|kQ0d~h!8F|dg-xH`;U9ukJaH1W~o9!XN zP=BCM1*?xPNP#b;=|$CvQTp!je7P2v${zW^2d$X>x_lXi&8v}Y;j;1o}pa_b{v|YgMA0)MCG~V1K4=__h!VoGJxJHjr>3p)<_BC z4>~dr`Ude-3>q-R3IDuKrf29jxeQD{Mh@o~)^xZw;X2Gut@*nD z7IE+Uht$FdP==78#f5>)3H`#hPNh(+uBsY@gyb;wyF1G$<4DFgnb@AmbhVkb@A3`u zZIROr2YUU*EQ$1HK%*E3{+OLcT)a2}b-2YY1=9!q_RT&IV~06;)F%H*rZDbgbLqHq zhpP8qg(QEeA#wJU&orN~LO$qL5Ju9OkrT>kf*A^V1OI5lFaZ+A<^|TsX@*wWa3BJa z5;#iY@-@)EA}e#0TACu78JklVb=(DNXwQ#pp~~5KB_yvYOCHf!*=F7H0?WlA^2O(* zM20xZjGri~{wS1j=qi!cI~M-r=+mC@!~49lin3JU`qq>wvSyM5yqe^e-+d^}e7iYu z1)K&-J55uTCJ<{vZ18Us6pePPd8+WI2Ju9x&sA$9WbOL{C5elp{+JiIBu@Fy$!f;w zR&Y8nyx+dFAeV=Gzv_h^ZhPSGF3in{V}d$AQ z10J-Vv;!uLFGVR_iJ|So>#U&?u^SF^fM8QxT+Dav3&ajZmN?ki0k`JcMm1dQd_Hro z87a|r+|RZ{;|7I(>gnm>YkW5lfPV zWog6_&qp2T>E*-Tnn<{V&w1Xq+~?Re;Od~q@y^>eT-y6aJJ2M`7RLVF@k}6n%#SS1 zyg=hJAp0yeq9dlOxdSRe#@p^KfPeFeNHMA|P*^|s(=w&K!j)kkc!}GESCh_Gx8>>o*6p8Xz?5O=Xa>>z$yCj9#*g{3zAoUp z;p^T`>P(w+*LP0#Crc*{Uk^%a*NFZZAQhHyD}$}WB}Y5OY7+K=*(rFeNVtyl!!<9U zt<|y}U(4bUhug<5NQpl;TV?qmQVfdIcsT?Ch2_;Uz(fkv1m55z-PTp(e% zQY%`8aU5IaMwnNugXfK1@#CfKe8mNLZN;OC26B6nyxk`p37CoNRwaoK?l_k|Rndme zgj!C?@^!5EITcR2-{DI$WqZf^Jq^~^npKnE*kgbuOlIkl!lixOuXQSN3LYhMPZ__n zmnKSuXu>8T{LgXmK7RGvw1Y&^kFuvIkJyEKJK5ok*OOCGNwWcH79s*oi7-3`&sK7& z5dxiMN+9NQp2+j?sHmu6pn#dXR4v!?zETmWn>i5$>eep(+e=Tn^ky|Xs;5%}I%m`o zzB_GuxU!X#oNIQwrVd}JB~k4oh)l2{eM}Edg1rHM);eF658kP7&I6|7`QcUCbTTXg zHTIgDwcaJx!e)4QteqP-SL_bQi>e8m8Xb2X^UdzdxbVldT484I&8%4b#Bq8wpy<|c z&FoyM48|s-cq346m>DNhpPl2apoCZMQ8m=HiRv;~ltN%!Sl>o#T<$Uut>v4m8Zf4l zYOZ87)1w@BQh1?s46ct`j#VYUL?tlt~1%$w+{lmLy< z2o#x547T4srED^)tU0g@U13rMOOZmqOZ;ChfP1ygqLTp@&Nz3AG*M4R%l@y^ZC*E_ zMETI8YA#8jPQi@WteN6#KArTBay`g~YmPxN!kmNwOQ_q79*MSZHdqYr(@*&%dfcPucsIT|vN8m` zN0j1~p5NGs!hhDQe9uV9qZt1t+)F`2Q!?Y=2`Zm!^AiB{;R~RHoKcZJdqF|Eq*R-U zf_)q$GmZDvxt8PAZV<8j8s;(CQiAeRS=_D{S$$gMCF%{e?Vsp~|w28FLz_FQ$CJnT<5DA*@UKO!w+};zPT;>?lyGgUuP`-jB2g?iJIO z6{KE|%EAbxcV%r#N_{qiF|XTj>AH2tVl7OB{V z$eA&i&N)*CxbKb!8V3fLA5Si{u*~w$=v{moUWRac-HDzck%nf;%GH8z7*|c)Rl!W% z(1~#xr*Hb*U;T0_ts~4zbcG{+zPMfFR8i^D$1WCTnNWJc$I1C#D*^sAVQ52x6)y|? zr1wOWyD|oOxpimQU{xa&V*OsrT^OXxN|H#gXrmMUEHwp#Mu`GYWL}R`rD5GJ#=7cC zEJg?`L^r5*3SEk*7iwSxrpJ<&T(#yVS9%8GAX0cnPg%<-l>~qKt<@->TR1bY{pln3 zowgdVf&8^wkjN|BNqeBv05tJkrde~z6w=9xe5+o`%(G!pCK!_77QJ^-MIv3t+UM>Y zs>jx0gZuR9_@O9kG2tgii%e1qM2|C2yh~Ep)diG0iDx->T-P=qc(i%4@nOt3kPdv; zP=b!D3gp*W`}kx4l>eL)9-ep1Ko<~X+s9RJLyp!t_w7U|4>1OgVLQs)cMkG9bg87q z(~l)5p`frvhki~@1h${wy@k(u(Z7==KonTlG{N4YIu(N}_I{o2Cv*IVW;P|NM*sBi zlnT0D5I7Om1es@N^vLl>)5l}4VvX09O^A(f^>j)pc`fuE^1!t+vWx1!p=hS-;X&fw zRuIXdVnnO_>Ul$Gmtxf)6BDM{4R}~hM)>3PeT|@0#~Q8Vq7myyQH+`pwnk<(8QR|O zF0Zp>F!2wMk5K?zGq$ z(w`H%Ls)B#eHj=^A9WM}G)6rV`>50us}(J%DC|}yOxER9%+!YPb96sS`^kytPG#Xq z)-fSAoFk$z(d@!L+FY72C>g94no?9T{%&e0VKdBuKPPgn86TRRFn~M^$fJ+%v;K~Y zj|XU0@5>7|OKu84FMbCYUN2XzU5qftc{Ro8bSRCj49z~7TZyp|)qw|e_R^$F&%3!I zwAS33^yb=G>zWm)m>?c05THy3T#8y`Cx-BpOOY?;DNO#!IkxwaMl5;?veV@+t`5^% z?T+E7LH=kT?s3?=ZWu3-`O=L1G=Qvk5KMuP>!-FYXP40{3U@V!5f~Ph-YyCQmhgL% z#uPt%l@KtKVU1et2RuSTGY3{5Vg!@hj+MTgw_S^gEd>Dq23NW3f2K69&z|?9m#Mw~ zy#2BT=&qa}dMza4M`N{-Zm2KGv~}4Kjr{Z_EZ;nM%-D<2n?{Y#@d;+_ECS*W#~ds7 zM0iRT8+UP6%D}+IS|Bt^xbx>XhCgQF?#-EY z>rq`**SVN`SC^-e(fEsKY20Ei<4C(2setxA+x+)tE%u-rlY^5XrSwES#I&d1od!no z%ZDDm-5>o~Q*fBnvSnH17?Tv)tdf61jR;|*wwY!hW^l3`dezt}Rg#!-x$r`L+v2Te zctaR*utGQ;he#E|%#!O1pS)5Tcm!ifQ`WJsbH7&{Bcg#!iR5)?W!5f2dQYFY%+^V_ zjU6gjh^SRCm?l)p?C5!DAZUbpw^@V1&X7G0;g5)%tR#A~GM$x)GVR^mdATMdYj;a@ zpp?k}qhLH24CwS#Gt=!**P&f>sX!3cCR3#+VJZU+G^6RQ$1eObF3k~dQENuf%QYlV zG|tYj2n+@!79gtdlc|daMP&|#;F?m>C-bH{ya{^N)gd{nL!b2^|8BtOvnJ} z?u;(0SqnoYHZsT31^5rt)NQ+=#$T^kQn#7t>U*{y+=>1sjTf&k|KXM#U#ZT~zxHCS z+jc!&WX?0+d~=go9SP{)d}aW>V|$1#nTsT|k>KynbY*O91#-w?K~vhikLfG-z6H4w z@7 zk1ys|Jv;k2`q*KyK9ww*A{7v*G$USl+YdPOdKD`IV-{gjlIv*{oOBU-& zeO6pS@8Y%Pr~EvZ|7m~5^t^g3!05s&tqxwiumPfrvLH=UTEleJkLb%4^ZTuj4^8|t z4S8>qsfXlJf@BW;_5U)C^DOj*3L+l}fdWh*$x<^z9@_%G2R~ql5ePL1Mq_mm%+*)p zhH5os>sbPA)hcdHs`a~_9_vf-{NPrJP*7+Ds+|nsQra-RsMYjuqc6@V{ja+RV)tgl zA(@cR6cO2i(2y+W_REkecuI2-K|e1j$a=7+JTFr!NiZJKW{L&%;m^FU{RGQ>Vl`9$ zKL=m%RJx_9t0$CBta>}G1+UUHNmAJ;dc2h3{ewE}9zNMiGhLaivGG0}7NPiUUFPSJ zyvoh5U$k-k1)Y#rk+6C#B|R(G+TS6zbA@2J9Hn0a!;IW>gRfIbOhbB>k)!Q(4pYi7 z#u&s3|sAA$C)vr8K_oVNe9rQ#Y{4r6>b;(2kGyZqTo;n zrSUR;j?o*B%=Xbtxd{&>E7*C$rOe(|+pj7opzfd)8Az;Ol2Ly>o?xrma+Eh!LHpgr zW5(BhbJ4SK>irfO_MWG2CMUj-&oMd>(TmN>|9qk!AvOJXJi|z7c@}^64U&hi@LSHy z5(OQMV59}Ji&2(*VU)$3<#z)B)CK869J~uCKvUrsqQ}Z7F=RbrpUj{Osc;s(0 zJw$ZRW^}IGJRH`Im=o-n0oQ9q{yXDg#@xFWYGT{VN_EDh&R)}&d~~qLPoVaf;lsZ} zh}Ss@5Winbns0TMFc1jE-)W2p#?MR_{>97AKG)O#RHNEBwckp#YWVjdR!_c}T?$TI z1YiPwzIcKAXjl4K@mNfcajz;G?O3W^Iok}d+03|_O3#=eJ!(`6-B3#Lcj?`*OEo1H z?it+p)xhj z_Mn+tv^hUt5ZP~%JFVR?^ob$?hmMM4MKgbRlNcsnC`BbFt0~K$B()P3=64>ANZOIL)4goX#(0Rv-)}_%6Lx|y`dG0MJ7mmI=-){quU{YUEiUZ_FI;eF< zWsXJss)r+y9^0cTz5;jgDigDhI8q~`VD`|3s+5PR|NB=yx7zxF`r)ui5E^KtF z?v_ycYvVkMoyZ%$$SmVdfZ*IujcCqjNebIy zEU@D#5C&tBBkm28`u3f+m=jNqSgu=9g+EI%2=fi$u3EKRJn_=^*_06_H) z2BbK0BVvSKc360Uurr53Z|`qGd?!X3{-pe^>uzYX1Ylqa66h6y@T~*m9QH7%NbFj9 z2ff%qL(zs>YPyJmS5s*e_Yt7nhO9$pPHJ-Ask4CHn#WwYVMR|kRfyP>rt>IXSj^%I zQf#Ctu}`H6HE_a#II^()lLi<1fgYn{gYBWg@I=7ST***iL|8f6-HpprA)1PmzD)8I z73fKfIuT0#3tr@b$Zhx3Lh08lsCDxnKSu}0*gH2bqP_m-PU$EY6Sn;NWyP3GP!LJ0 zaPcDvE)fYKPoQs%z{c5bR{&)df~)ciKhVb??RWq|d~8Zp_Blo;-LWvU^juSCOv>kB z&-Wx>shJlDzKkL&V3yC2_r*6UeM|?XDpWL_^T5=nJbW(Ro`)d>;T*HOR-iSEp)M^fqJ0U z96c_dxSvy_UWQm9hr;Ar^M;Zcc%$49yoY5NsRKg*b>u*J^xfz8JIz3k+;`Q#H-BSM z+F}gV5`wTs%tEZlac$+MfEpo2w{^lM|6J$xtCz@98y2-#00d(fNj!N@g7287EI!)< zr1wvg2yUTeCwcs1xlbmkL3JJb_-XX||5Q}mmxI@sky1|=^n+8;HEzB5SUDsv1ZZc@ zEFOZ5ZFHCW_;o6p70l8}o%my_Dfs_`n0;V1H%k=L>26GN%;aYJ9=9<~ar@yl>YNLFk7_{I)I$bJJeZ{lO* z^NHfDG6YjY?dJeT^j9^|&qh!YfDcE{htzIA<&RCdMgT3rM>FgvbAi?((iDslkbKC_T8eY`@xq0L61Ugz_xAL}-70cBnrUWbJe&(Bgbn{XC??W3Ql!OZbq)!3 zYsRh$0uxiL4445eNQ@bi^J4&-!|U(B)gqtAoYG$J=xI-rJf&EgS*}(2E|WB(tjv$* z#LbPo|3%bGYj`f&K=%kGf;S2;)SqAZ*9l7o1~N^I5ax3_!9oaYx;}h{Pa_26t$&>Z zJs{qho12FsTLVBsVY9ZNWE~0YQHiv%Ky|NM5r?3*EB>lx6`(uOi9WE!(!00_KeqOY zGGL4=PyUUEwX`D-b}he+2x~s*bSVLyey+;&-Z<%84>0PwrMTNejOiGY`!TH~you>{ zO|`CbH(0{P7Op^zZu$Deo4;;ha6sRmrXOa*MDvFfMh zcv@;<3~~P8#bY0*&l|9qgNR7A=-vV!W#%NNS5yII)uZs@C8;pxyjm9o#aR={6i+Iq zT0N701~|S}%qxNs`+v%IRyTa94}FhIJS4O$axp6%@&c_gwyvmptu1ZSee3!)^4}0E zz|5&tCvblYI?dug0|X>Tnx=~vXrMFq-8M25Xg*JlAw@uduDV^v`k6Uxz`H$iwHe4y zkjq`fVW5S|*-cX73;`aJNu5%9H@OnvEtf#F&P6GufNKpj1&fV~g=w)5BES30KWZ8M0;oVmlA+WrWe5q`gN= z=N@h?i0SSAf3%r_<&($JXpdco7?Er-DjdV5 zy2@a$4P8|9IK~plJ90)%;$of(_gOp8DCGd>Z$U;Ogqgc{*zz(Rz;W;}wrbJ~*E4LV zkD~a!&N2kouGAr?pf09B2doY#tA~4BL(Pk|GFFX=AI1l`g2~*rn3C~X;$HA`5wVLE z!L7cU*__V++H`IDd2>T0Okrj2j$2F|XI-d0n%vDLMKE#*bohEBQzB1^yCqwipKUe% zT5asb2Sm8Ud+eUYy5pb0ByE8!e4%PbUZ_4My^?z45f~=E{uA6o}MN0amkk8F>3tY zXPsG^Z!@;$v-~*U9AaXvK6P`ISk+CH=;fwG6#0QtrpWsxvtXA-U<;t#ALKKaX0-d6 zHgV$6`ZrvnxwtZSkBwU%T zZ(b<*w~GX6tI>~Okz*a829iACO3$^}ikyA43|g??DwDuspz4S>ta-4%DKsN=Br|8R za(BFolF@S`mhS=Ry0X9K;NceyL0+;`FgT1`y84IAgom>&HcV#HS_#>s5slX)=BH9w zaE*?t-@5%Kcr;Ba)1(+8AL?)RUe=zHGCLUcxFl*-a8ovEz!HlR4=~o6?-w%3Qs}Yk zt@3fvLTh1pd(%MIbCTX1p|`1K1oD~{&3%uG$1Y9#UwlAwb&3df$mNU$xM|G?M3JiI zgu5y`H?U8`2)o)1wLRH1D(Q7MAy1$;)$*;@Eq(VXT@tjIA#a*%_C)x>yM;~J@{&_h zZl7~^KQ`J|Va7(OjNjStSo|Em-jltI>qk5LWTY%`tg1sTLZ4MGPMLfkm;)3jN&pFq<49NW{HhAO3ZZpJ4!bEViG)$ zf24IBlb|Fv(Zjl1q&Dmpegiz1lM%G1XMPj_rEpU8WGrSkXIidJ?-eCQXPv{gQ3sul z1VpdAyV4^ICm*DDODv~p^Cyi!AbOKERnP=x;c+jbW?p7XjEDz9L2XIT?}Pr4CJ?zm z(!OL#`9G;JcIY*$H2PW1j^Qd4fr$eg^tqpbd1Q+%mPhq=DKk#-?ILOOVrX22Ypcd1 z%?E4sa3fjxwIS|eI{q|5{vU{#)bnF}R}E}dngOjN_|4`i5C*?)BL+04T?q5aTI`LN zy2Ee;-2~vz_OEk830DP&Gp|7c^H@JWkE=s@Dy_# zmK|wy-FOE|hAYPLF#L8LwD8vpc@N+3K7F@9uq{2Q9w#3P%#&F-apA#_+t`pPjKK~; zfuGkq1U z(g49qfzrUhyzg2`AcxGudqm#nj@+93)NM#H>pvYKRsZ+yU8)=cyBgqNKRk~#Bma;0 z2|T;Pnz;P}U{YR&`@}E0+5;;9e#fr8~^hMUt z%5`8z+DpK|tYczawV^-!$p`A*S?2c-5c=ObJR{g(DhX%c+q#?-hT}!2jzC?EK0mhZ zy5+&Yyidgr-~GQ2`3jhPxq|QkALu?+-H?v5ms>a?2a&QooGS|;eye|1>6^19JA~KT z+5!~~MgP4YDz=IJz_G!q&a9mye%RslgzZl|X{`;?Sfdq2WiIdFH2-5|0sj|2j-3xG zzABs38x99(o`BM<)&ZFwwF6;Ug^hnn$rUhE2(>S(W0lTC$S0)i1j%vTNSNTzG1T7R ztCf_k$SDDFI*I<@36WVmpwoXRwj!@ro=owaqN#vD30#Uz*BxhHreltnZu~FTxx+cE zs%i{HAqgKPeXW31O=NJ^yt?|o*Q`Xmt(yFQyQe(N{)7&s^soU^btZ-S%o<>m{d28< z&sHi{uDT%i8r-f`1y-9u1Cy-qwi`kY8j1L+tHiT98w7n-)3wtt1$jmHpEFw!APm`{ zU#aI;&qj(P>J4w(oombDjP_n%!_M_RGbnfi@+3jTpFBCCYFnTBPhzG&)zgQ~0?{?; z4>^ke+Y#ToZ?)a8BR~EHZu8$1t!Uc2gZ8|Jj?34)q3^Ytx+{;c@A~GJhV$-+6ny?Z zF`afN@VGbjIvF?!k}xAb8ms87W{+tIM0WWf7`Dfl-k;yc%hzB_@+U2m1zokxd;G;8 zR#W{1NBSUMIj^34l=ww^yKYLrbbKB8@50nMDdZi-iS&3roFoiLj5Cl;7{h~b+9ZDcrJ0ctIV+?h%a%JOS^WK z<+SnV?lxO6z}GOZhQM(B{}?5nX6K4&X_SPHNe%rZSMa}Q4Dl{t=1OFI^3HayN3 z;Q6=LmxF2TzrEU)Q{ST0He@7%&^BF{_l_)g%=P1*kAUXw|@*TW*8n)aeI)9_=78_z|)4n zq_PWHMp&ejm#yM0x#IadyxE;ajond|eD3W<9-#c!lg z;4yvStFG3)Wr3r&c^87T*OB+~3+G>SDyZf=o{n=0zdi+`Ei)<+NYg;<_k|7f(U8nm z|CLF#&Bu_)t@jE+vCg8mj)C_wv;`ZJ zGkpBN?k{*~|Crv?Y=lK$yCjr3E?6^9)&sJzZF%!RE z@69mOe-UrNDBr8kn&Pu`f5XO(D7S@`P44*LZaKR-S+84O`Yw-8|Hg9myHIU)xe;7n z$EjR>xCbFx(f8{DcV5;T8yZSSs}hHyt*b3d{m70R!D6NGj{Dux%TEVE0v$JZPY)+* z)Gf#vtJ)64ORQ}!Dmrdukv@!yKLN69;5wQ_FCd)1n<*abeRa?UF}(faWgj0mkL3-xMYVe5Hh5IO>SF{dt} z1eh2K%9XP$=ZzzPYF07{Qnw%Ky<656y+2mw4Xq70FRQU(Ng0@T>!pqbQW%D$7O!6U z?;rJ+O^zdZ6X2`D_*FrFP{mJ*IgZcsE_p*kZU>#G&R-OlS7o z)(-OnIiz+8fUwX%TizXi*zVO)x}>~0J;rl~BUi1_y4(A74fD6Po7i>2gZ`Dd6T|su z*$K%F19u>}i+LmWI|j z;QFS5Ab3pAh()L3{>S8@enxNL2s_-6$yW6UJXJAjN?HR*_ zp~u8Y+*yAk8gy8JJMv(H<7IA=3YlWJ>dvCO4HW|uf(YPKV$$yUaX0jo(u1{?w#d2hJKD(v@{ec zCRT864?n-({HS>@8n`NP=k!oo^4^S`%ps}44*_y&+hV*swz#iDRxkOVQK)5$_q=*4 zF&HUv1Wm2bEfBO0gjOSus&d7{muxwOMdz{0D;X5DuATBXWfUo=3Yr{UXMX$2?f^N0Qng9OVT>#bf$FmBtzD;YoJY4>t zZ2`<-C@>M%`k>NSB}ZcEp!mb{`K>aZR^odxzjmZ>O|Y+u z;kOu=7*vn6!4m2;J;D+ta6_OGu9=`2OkqA83IN7M?GiJJ-8L zDiS6cdN7O^PuJK3Q;mDnKTr>RX9qazfd7Q|3rfYEF(}tCC(x8tHZv3Bgs|lmmT7&k zRqti4&uVl)nlJ=_{-MPfk_S`dRpew#o{^e*v6m$ZLVgz?Sq^+-umAe7=o7U9C+mIT zvDE3t(e|4x?}9Zn{N>YmHx9)_fCjD*A78!0M7zHJGq1){LZS6q*Y&(3Y>RPT>=5*z zCdO>}`*uxN{=of%KOu6L55;`Az1jy4UoBZ~wj+JCmzf%6?g>5ytYVYGAJd1rrB653 zzpU|!?mO^_^0f-v+X6R{>sVWq=$3D$#WX*#{>RV0+Hy7tTeH@qn%LG=>|+5ql>d%0CMmBo zCeYLu6G-G(W7uf&0Qrvqla$8UGu3@YTr}26y9dZmu!7-rKPqz7 z78d`yDh#K~rNWCPY+9;lp=7#mJGa-R`VGXVX-WCn!!2*5*URr*q`l{!xm8Zin^m|A zwlcZ@5xVQM$^|_7093>;XW#{O8xQy1cy+aPxf5~xC*b^0C@?N9X6f_IXu~nu(;FLk zjL1ug_TyW@rEBbx9f`;9m%FL1F5!f_HR$(Cm=}HLcWg9ncdtJR+&L$f^x3Xc>t7q~ zwEP^0J8A&xa!f)bE(S2VBo2jQgIN|gZY6m0n&Li+ zT`5wY2ZdB0T(i>N-Y(gAI>jTzykk$U12gh3toKDu=0wjfk=|Pq$m#nhdFJOq_w*lc z7n#k7p>PqruTe}*HAg1Lrq_YucV!AJPXlt$B+i8*)IW0HZ|2+vxcx)&-BxqQ1OUj# zhTbLtX#1aI=J494RjE<%$6%zX^71tCCFY-{yZxXS>82tUzfS`0{#Hp0=G~n}Rx4~% z-ORv=R1Y==OTA7y#IFodreC!{Rwk zbX-~E-`&_;wtc)+PHlH*^9x$5SaS}SxXod>YrKoevDm*0HYE2MAHZ$hKk(jg|80AU zP06vpv2@!>CK-f^g6POtu~$nBxL~^(I#|EBISw*EcnUw7k91m3GQEFiuWn#1evERx zbS*a@%HzMxX1dWm%CUTfPkRL;6uu-vnb@UYXNu=MJ{%Yfx+1qNV`v1yi9xO-o z>J`z1*vEY7YQUZSZ(HUil~T9?vwLe2(HMMbqmX`Ebxy>NYc#g{H5g;qJEb3iA8OJh z#=ee4it(G;sN3bGt3aMYFXLSw^cT$)?-Ns>uq}yMg}vg1_b+Qoag~xf0x<6Xk}Hn* z4cXlSo%Ge-Se$wOTD-wIOHjCsdL`D2yYVEfSab$0hTKzjIUZuZln-@kv@xBuInN(N z_xk=wa=%2V^{r=qO9*2Qb8C`?;HvJf`D&sG5#81L%}>!+U0q~L8V_P0?4XRLo3hv- zZG^xHuX}6ppE;)k<>3$Ub;7O5ox(Dl$Fix7>SW|}hJ*9DYUqZ&@p72YZU><#CHJtXQ^&t!K9MAO`E^FX*xWu>(((ruVsl5dHJ24G0yaW zK+a2g8Zjgjm?M)sv&>7&r|gLt=t+R>@5Ymz;p!jhzMF+_Dvm#T+^@#@mE5Yw(o3SZ zOu|R~z_UGRzc*G>F9d%mx19bB8YA^{^cu!Vc_GuwdAE&^$diFn) zC;g#_gp{T2tbNL{*&~gc?{3hTUBX1aB}Z@btbODQo;>H4tfsI3*O~?2-ia@Z6lyzr z%Edci?3Ss0<+?oWmk4;Yy+V`L@{e3GK#Tyvs2`Gv&!+lC9Pv6(cVo(+T9=?Qx&55n-h}*3?;qLGNsH`7H!jvdGIs+*6Dn(eE9 z(|Nkn2Qe+CGpfXh@E~jAuBfpY^@VH7zu$0FLoOfL+799_tLgZ$l@L$A+FA{{ydh~< zk~R`Ul5J2>(Cq(1=^vl_|80nLIxO0Xk`ua>#=fg$4*VI@5a5 zwuJ(2)X(YPw(tPJGM>*vW9K}VVzd_qHoK}csHpzz7kY6X-#2(wb;d0qbC5wOsE;sP zQGhYf^*{7>rV_0TQb{fuMXD{B)GVvSpzew*r@MkR+cO@X+&p!4h?(*kSXoY4K$D0r z&xyHG?!eRrclGPJ8ffwmeNs0_giM4?p}jj5meuFvQGvQ5oqHnDjoQe;{7sSnO$hz_ z`zC)0T~LM8VRmE~n11*`6t2w*@vSbNpDD=<3Y0RG0`EENr6@TT;UaiKyhjGpmq0X(Q=SzN7{Ss$l9s(unri<+w9d~<%eAmAw z#X8@zE{xA->D3+G%#TnDf#X?ixqtpDs>k`D-d*QiUSBOf;nV&b*Lt*WDFklxOc5R;6=uf$Xi?S1{-23p5wb&2cP%7sh3)0C$bQ?|9q6xLAYeSA^EmnDdUIUBGJVJXwR6GG9kvOSE% z()*f@MEdn7kjJxQH8bkvS+iQKDPxhLHm6U6E)TY7#qK%0#9?jK`9arPK~--nTMI6| zT4e?#{!drm9Z&W9{{ONvB0|}rgeW5w*(;)OjF8Mkc3DUEA#Ho4;uzUvC4`Kqqmn%{ zE7_~;?RULS@Av!jef-X&e|kKe*Xz2k@w}ebb=~K_cOEBw-VQ!DJmD~Xk1c<@%1hX8 z_^n`@{Yb&(wbw1XVYL{C+${5(n#~GTDKoW8{43jYE@|4%hVg+rT$N*4wK)U3c?ywb zdNk+Ud{&-6=-woFYjg~7`&^X34|Kck#bvez>LfSqzWb_kr{5>QP+_}QAu|O(BLCy* zo6WohgWstWT>;+%JIh~7e9>vn*{xce+zfmd=vyAkS7OrdtDV98X0dX6s@#6G>XJ1W zC9T))oaaD(`E*=UymLG$QhZKd@bavwI>o6p*nF>!eFZ1Zth&=WzT!1tAa6X7D#lJ3 zHazn{zxw<5$08{cvG)rD=`G#V(gM4Km-&x9(iQ}5em5vf?+>ihSrHvdlN|Kd4P1!d z<=7dHuYF~)RX_2jwDh=!=EzEx&p_bT5xL(xfw`?aPeiAk*DNCW;IvTB?N|qkn(ToA zg|xlR1=)Oy&k*x&4qxec#l+{ z1o@5UdsnYjb4ZYs``DM(R=iqSNYr<5m|1Dm>!-;~&wo_Qjv%wo3_giJ!l}G4MXZiZ zvX*BZ@%`Br5jg$4^>TLfkC3UethWSWCvwEzpE;eY#&zySW>)EOI?k$I-<@J@hHM!^ zvu@j{PFi}4lAD>f%8N9XFWV_uDImH#Fgo79pK4H&^46Mq&V+PVGl^-vmi5) zW3gRf(KZpVb=CjJh`$c~h<}xc|KhEgwcXKP&jm9tVc2@xlTl*gcxJ^hc`tEz<99=D z>|u{gJwy5U-i3gTOPedAegP9_%99leEA-3*^F=2YvySw1kg?g6(NwOLNlxBX*zAl> zUsTqh$VwU6T8v+w65Y)_Cn?!I@Kvx=Sg<5+gh_F(AW-;O$Kkb0NB7k%ZLfKZeDs|R zsaFjZ=3`SAJl*o-r&Z;5mnJJ-jXu(7DQTf}_ISZ}W!7}5p?_>b&-YBMcXsv*dvQ+4Q}sh27Wk8|CtV1sr?k7P~PDJx*3?drb=Kls?OiBUvLG4GNg*b_@Ur zS;V-_>E7jhg-UTXh2*9wXZo58d%u!*k}KWjUSwuwF4ykS@1+f|^psBtTkO3s-~2(Z zzD7rrb4zwDad_p^v9cya**+1^r%R(5eI%OGBS@ZxrERoMO|jllhONqCVCeZ5SNG=) ziL1t-89sY|YqKd2pUH`;q`dtTtxS=LiXs+m%aICgnWx#t7AZFFFGzqUcr+ZF@3+J@ zc__cnb;9~e#z=l|-mR=kb>h!6a8MLzKXStC-ROaxovhvPn$4RQBh)E;pSRv8>Rr>{ zobQ0UF3Qy%_qx4mPH9y7?40%A@*NpE-@9gUN4IIB#Xi+oue!YrA8+1i=9Sc)T)VAa zxt%k{ar08fGG*ZM6|?F9v*@ll?8=tKPOkiJNrZiwnETI#3$cUVjdNv}>O!~0~1Yk1qV}2W&r&$24dAs!njh(sAv5?AJ9qxXOnz>Gyt7 zcG;a<;n@4JU&cy5dBMvge{QBAaC>5NcW*OtyLoP8;@Vu_6+Dne&?p%`HiC5TK|D+PV zTbwqYw%|Wv9M17^;ev6fTuA*5PD$K!(->F9Ob7<~Y2DyiDyC3aYS@H5f#4oim>16c z!`w5Az7-JEGlLveO>$GmIK z^U7BL>%n_0E8|&vVS`P#qVxv1E)ThQO?ZF%NSCn`G{5`6!azGP{ikE#waoaAyu#|T zi96S>UGtUKVHY{c5hpgU^87Q4K{joHBPZ`g#wx?QJNZ%^tEF5vnAcmSTx&0PqkYR@UO67SnB7+4hW@Z}N!|mU$ zxwO-Z778Ud3CAZG3dQN=7daHcF-u6xI-ok(% z?u!-+_g^F==nKUeu1@FoZ#PhSZYyE{T>Y3AsOI98Yp<&^6c2;#M8o_=9FWt8{j zvWoCK^hM_&t(G(&wZ3A9o#Yjfxa+;to`by}23CZWUTl{V zoRAec6F#wN%uE`rJ|aF`jn!R0g0MzB@=#v!skWZG*WcHNsdyvj&iQ{=gTk8Jk==%oUiH9f zU9-I2<+#GYxs{2pf_P1PEY>hXPb0c(V=j6*vTJ8%>xxIqiMN&6!(D6?y(78#Rg3-G zKYdF*#~#n`)m3kPN%l9>%)r*@baoC{8J|lSTB=THv5nKygx|z}nOOP)$8yXk+@VdQ z)qun9k84CoM`Zg}=WP>)1LNzNBR_O&ShRNDXS-`YU{q+<>0EBu&HAS_e~4u<=1uaA zL6S#&kok&}$&hG4iLYE2vv#ZoXI8rA=A4`9gTL2J=;-J)eIC1VJA98nO9D=Y=%l_S z<{mAFq2zv2>?d`8Rhb0A2@Y@-+$i~`fA5slU=Uox^Zf1L>fVKwncW|8O+LFBEGwD5 z3*B=QE^#xJpgI#16Fo_)Wx~KhTlK`P&e_>lG~Vh8OS{Q^Q*JMwKX32qiVav+Khi_y zHI(lmo!>H^xl7OqP^2H)+UK2=_3hhLt(zsAb;lNZs)pZjRnFJohBxp}Xe!M-J#?=r zV6CSK6(28XX=zO@b{oMZO%=Mnqh|_4@Ea}fdfuGtSi&z?eieJ)D@AZQ?)+#=iRAOg zCoEUazc0CAjJ;JQ_Nd?7v#RoVr$RL0|nRz}eXuZa}toch@&6G_ST_>#*{v zPMTh+T-b6PXG4Sky{PXi*_j#nPE}b?9=|_G5(cpEHi5*iaT&mTe8zP;8(uP zkGMBnel`+p)q7kET?4~+_F6`Fie}omcf_kF)Q_N%?)m2xoEy|qE0AX15-=z>mU192 zCVX_-OIbs2XJhW5Q<+MzhDQYL;_^)3E$6@;D~upB;q=eB=zIPc1WEj$O8CQdli5O# z^Kd=a@i=Wq2P5Qo*tl=vbNm%Acl~Qsr1|L~J~7gn%&jhRtIE8W`#EM_BqwzC*H8>r zU07+cvmE3<=ll?ds8T-m=|VgXO&FIX~K#Md-bb^hAZlZ97?|G9LwRChAJgjX>t~xt8%~qr&eZBz~ z28n)NTHUSw47~WyN0zb5f?ytuG~Ten)Q~@>oj%|KJDfVXZ%0nD5)3@t#`Z%F2p9{-!Alr(A0ZWB5f$O1`_V3JSDS zq8pr_pUPm*xrpWAl;qUN>J&Qs1kl0ZTtXvzx1`3$>$=~Z48J+`U{5fKvwZy~Lc;sQ zJL${VYm}@P3AuOOd#`IImH0x_QCiXz_xgv6g@H?HgqLJ*cGxJ(FQ@TejbAV8T&f;k z-NUkNylwC>$?@=MHI_%RB&YW;j8;Z+XIS2fG_1;>?x;AHTyB~lzWk0{_=jio{y*e= zqj2x?FR5@E{cxtTP@!jRHkOO;y=t1ieB84lWt^If{NQO8r%B@7FW^+N!>Ox>ONSz0FL6o-y_fb(M)`FeQZ6w@hhYu z&5Z7;%b6-U9OQ1j>Kvru(p@rIDPGTXy}FNQTq+!x$?2UbCOZ(tP*yi7#WLD(n?#QK z=V^1tXti(n^DUNRcNhG6ABB6qz}WQNP8X#G8mp=poL=Fxl8YWvH(*0M7O}S;;T(?` zk9sG;d3AOw*Aax^{L-lLLABzLQ@O|PU_Mi}AiLW}aONpfG5nVs-E?X!9{|8EZE|^7 z(XL1*aILI*wq3~BqI~$6&nqHy;H{eJ0pHoik-ZodF2`6FG1*obtYU`+f5eZ2;i^w2 zyaC)_o9#n*)cW>QKp)`IePE5OK78C|S~jnl_NP=T@r>Ll+;e|TmLy1JoedXp{z_;* zXdrRbYUq85MKoD;T5vocIbZZpBw8`m9yQk;=9J-VZZx^N0W3$Evr!|Psj=NP9 zi^d9YLJFvJfeYte;PItq`;;G6V-Or)!X1IGBHz^L??sl!B=GuJpEGIu%gsmHOS(In610JyNB|Hw(N$?yI3i%@-%ADE%LHuNfu4&jE+AasR~Tm)!bQrRxvfZ-2Cd# z9QZJzp{iui=k+M0-JUc%;CI)8A1Q8!zx$hNA35^yv~{RvMl>3r;_p$BqP1j0UTErQ zZN^4LX=X(nQe0`^4;BddyuAD-GqYnBSMo`%jk)ZPcg=!ua_d4D6}&!lz`a#2OZ|xV z2P_-a2~?11ho8J%_h)j&^xKvnu5x|+EJniop6Mm*pvxVw;Tw4ycG^kW!7qugdu9b6 zc%-X)d08U)e0v26LIoF-zj^cKMinh`aH)=rz7HUzhx@ZS6?hK2@c!V}&u61rzuh*A z8z1ksE9b{V`A=O|1C;pQxH{`~^o}w)9Jyzneei|q%}znWgqbwYCsGhF8mBGDNkF00 z8Xk=Bw`fvbvB=BQ%juKy6r}4X`xqdgdUZU+w>kP1_nA{CPhRY35vUF6JyL`(E>8HP$Hl=m`V`iZ2U1p|UG26s_wX&5 zcY`yn$g+3RmP5riyCjm?-sYV+(ML@I<(7u;##p@POnx~OCcFex=Zse!jrs-$Z-~aG z8%XERkMqB0y8fUVBS|~$CY?WIrWG%0@$`+C-*DQ3B`qjCE3S27Dund*Q5F%?HaJ?; zsfsp));ASFG;W*DLyFD3ThReN3YC|Ydbt3k7RZo+JE-3NY?Iwtbq8KnMx0duxH|G zAFsD#*-$Snq9n>_U3w*`8l(8`g1>0j+sZ@{i<--mbU9pH?a7lT(6K;}r|C6JJ1tLR zU+$g#(A@L0J*eMk3X}Tr>7^MfD0iE4h`XRzVqxP%m;`#5^YSM3io=mDxd8?HRRvOby$dWmL{0TaALUQ z7vWZDZl}Gov+sSvu9-H#!PQO4Y_V{9)Fj#jAFA$KN(9SuWYh^03*=nF6GP_%8|OE~ z6FcFOLc4gTpYPZF$Cftmy=(|>^z=VYfG|iD%;cJiNJP^kkyJe@g4Ww)q6{wBb2g#8 zk;u`LcJdLigtrI$3Q(fHoUK@)xq+l#C*Oky;WC&l-3WH{Jk7Q4rcGfK) zKVZ-Wjr7($Icf)`>DcqtkvLipa7yi_CD~J_PJ!bg3@SUIZsdcRpmMf(xujSKu{tz> z)=ClP5Ki~=4T)*2WQ5HdC z_ApAnNU9NMZ)Pp&q$~A(lf>sg+fJ`l1jGP$cO~#<>JmF5c3|6&1e9|}Ih({c)nsNy zsHHh?*v>ecs!r_nw^w|hKg;+kXIYt6xLt^z^r-J!uPOACuVwNeMQ)oCSmQMR2HxW+ zKLq!7zZMY)q&JVP^3ie0ZX_g}CiD^r`%;-ufsyNc+z8LEGLy0f0AT%e`jEB~!zYO( z`9Dz+n$f#sg*!As68w*Wvew!EpO_9sA1$@th^q9Ks6ok4$A){k$t$Xh1u-5n6iPfA zi=j{$9Mh;=?u(J(-uu<+f4OEM;;kO>g)g7{``xpsc0Nlvm&c^zzf)7~w+?;$@g=bn zd^0p^RBABi0K)oY7j%jI6g1#vwywl|p7xUAlJtmP#mdkL%YA&SMSSAwl57MTyT&wE zsE$MMvSxu8W1yyOD%FAK9Njfi!H^y`f&Xi#T99Zf+aN;w2mHfSSwv?%&^5 zUy4x3$x_&|*N_a((zvgU<{(7(2D*Awu28yT8wldcT*;uRNifgW*vFnlEfMb6C#Rw- zXJKmUv#p__S2a}DvGT!O@G>JF;tALTj;LOmu|wPDY`c;}heJ0owJnd{Ozu zzJFh09jYszoQ0~ukf;JJ!I=1*oE$vn(|S$I$ymt8CygkOhe!XfQQ)XLBDEZ6{Y;5G zOu*d75ZZW25)A^o%%8#PVBQDMEH@)Xc>ei|HgoFX!NE6Xq&V@%Tf>qe55(0fOj}U3 zJhZ0eMlAI<(FH!d+h$I|A42*QPF3p{fjIhZjK*stQGGKJpa`A=${flYyQ>##R>J6@ zqis^K4`Hx@V@H&!k=qUg)_^2n)h(W8EH+*D*ab)dX9!jx z7Rq1o zLAAtB@HEqS$w7lKTumLOMx*7=1%}eU%XC1suAVgU4O}=9*>TAZ;GsYiV^x1n-(n#D zSFZHi6Vf0#P7pN^q~pYklQOA%Ii0*A%5Im1Jmx&4na;POAmx`_pdQMy7fynxef&$8 znGwsQroC|!-f$F_hYAUDRDhA!Anluhy^DDm7Mi?FR#i();~O$TJC-*BrSxyp5Fzux z-V7soknHFb6ZghsYHMEaOjg0cx<72z1}6`rsQZxQf3~eh6=ZPXXvnmOw8@CEk#DtJ z@e=PhkS6h+`;FgxLsZGq_;3+9LQ>Y~w5RVj9>&g5KfRNlK7EQ#ST8d4dR`HUpSn+q zsA}^mXB$?X5=ibX?e`qW;2FP9myD&(caOUHaZ&GnEQ-^*j#1R*}B6Mh0eXiwWpCHrE ze1?*OwRuL?7yXlKONb5{8aY!5K5@M_FoIv(r}P=Z4o*5l`7_mk2YRhqBh8ZWW2d8VT+}Fc69( znm)y+y1=ah$Txz7Gv{b$Z&aM0%AFHpFnj>xVJ~_ApU1d|mexC4{d^cRF0kWui0TP> zGE*rO--J4|vgm1EgOcv9?ZL!g?Ubp(H*;BqH)158 z94}5Fjx?5Jb)bWd@<~2}T8_sI5S6x3Y>mCWb8bqU1NY(TEevw+J!=&uf{20CoQ*Ke zM|gt34MwFPhRQCHAm0_Es8j!%RxSFi*nvZdq`t{&Cnw26{z|AyRRtQcVtMZBhkG-$ zb4F6e>wBZZZYq7#(mQHHW`89Co>wX_Q35HZNn{QIloW`uZeF*?pPv`7=(>c#=Fx9z zic=-_@28Otn$r`rs#0H|gP5Fl^c>!%&rxt|b(bR*)|5fTkmVsA z&DM{B$em-v-jG;zU>m2aj`8~St9)Vod2;f|Qn7ZHidSq|0}u_B-{f{%;VW=60I}Zq zzzWBDu2(Z5miJ~V7iD$gG%vs<_t^6=zCM`4;7|@jKsWWDigi>`jGV^rtJmV30H zIPN!~8Mx9qAWW`d9!#KcZI2A5JDkpX)>NLf_od}XJs2L{<*y#1Q}=^t#+wn8h$UaB zIOP3DH5=53rBN+ME=KT^r`f<56iCNjFU^Mjf!2_@s_JZ!C$qMucSe|Wh>EyeXex4(`O45Hg{4#6^u z9+^^=a`>i3p7}?F?_#qMx*;0B{*O)g?R`a=k8QjhO>y8K5voL$=2j55LWD4 zXUAs!=IvWMG);xV&BH)IGtVN(D|a)aF}JJtl!J=>5M<^ki!yKJfq}I%(`Fb~rFC!v z20E0BgisST5|tzx=hS=qWV4|@{Ptfa(4~Cfa2^TaEtG9UD(*zFsMqr^u|n_@F$n2vrVADFmqxMwck|>7w55O4ZT9FuJ^t zw4q-!aS`%9FG3$1?k~C2a&l7W{|* zFJhI?Uem%CiY$1)8gglTU3!OeNVZYVmOn<9-~D&35Lzk>U&Ok9bXGNMqrSd&mc;ev zR?XsuY!Co1A=b`>2 z<~GfPeVDnG)s|k4tir7~tkr;ek)}{3qLC;z<)v~EqKE%PG;h~R>DeK#)@t7)1Gmj6 zsuicsFzr+4O=$iCMGzZVP8?>tkfGAx=g{OfKV`DaGieS2M{cgh7 z)@DZ+tcxWj>;!TsA0Wq&6|GS}OtLM>F%`LqI@?#G+6>WPxNLGm1AM)FBS@+GO#D7tX&Ix1ErTJNR$#$0shf|NE|^(d z8(1L8{|KCIcsd8{~C6 z#gicqD?VkO&BqR4siS%p0;DIyTm#pbNV?3G1S}WOLNFY-DWdqS9kos@2uh4X$%qJe zUHfL*+P=Af>4;&+(r-J^5m{gwVd4pR(VY2Dxh78hu5m?yaO;vmj)4>Gx`Nl;$52B5 z>^&g(m;GZwKVshO@IU`;FS?3`=J#}>K}zD{4#hRuK-xxq`ufS&GH5EBs_~uYS{Gkc z9&!qB*{%D1f{N6e&?z9l*iLP9$ORIXA1PxUYudkXPweRy%|wj3oAshu_1V#!N9QY( z!z1Pec)a~aCXVtVmcNLvt1`*wZ*)ajNvKx(zt(&^<+`fuJhKqMo?g54dF5@VjU-Bd zEUJ%KbAhC{eTWb>G(DaB&*Ve=&^K4V2O68^*-qztE!X*+YY$@OjN*^@x&>dkcdc+B zW?>7U)l#FD=?klM6*G9zUqtjyx(WY7_PLpPL2y|EFH1Yz1clwad3LbA)a_sDU=ZtZ zmq|}wAg>p)><%2kJ zT%kXJ!ZGT0@_EcVz;}w%; z4l06e>!hWfNf2EiJLstCUNBk{iYuOGVv0W!xY!o4*0^+>By9~z4Ee8f@PV1A9vF5) znE=B{^cx3RHng)FSVtY*-8->t&r(vDKCQ9UQhvVy@P{sq=kw+d{S3WgQ)+}~`Y5+D zk>z~*;TlWKC&f^PEQWD!6{11d{>wWFX3Z$i1JG0f%oBe~kKAUDqECI1p9w|$f$ck0 zLrIori-P6_khBh`b5~BfS(71_vP3g5_Ii2+1L$Z!#$yh;cC}=sFVg)$pZgM8v+$~x11#bU8a9b) zzf=VI=ttL(Q1Eh~Jt&9xfT<;Wj6Pp*Dq`%Kxp^7L&J%q7pmP2#r^&DN^+DVb_2${o z=s4dK<%`$8>C~7M8?dI&S#ucG4u~}w@l%+Y=BY3VqDm)|s(gP)=k7|S+(r$W@2T4s zLauwuB9@%Q73S_5%lCSs+d3ac8ha>n-K)m5_i)!zA~AI++Crn|s)Apxfe`Uw8Yj^T zF8`+=)M%-P(CS<}r`~ zK@7Wan+P|ShtM(#V9PcyFE4bA452-B7>|)MjjiXbOh!UTj)6Cgc8x$NC^8c*##v1D z4=EpSn>f`JTwTd;lp)-SiZly4F!{QXD=D7s?8 zyJ~MkERFS2uSEc-8juOR_5*Mj^n;`N#|u(1mI}}rRV=1Xz283NVPKILG1dq3UhRP2 z_)sN=>>-zu3A^MJrr&ZT3{V-I5)pv`2f|SB*Uh~079iG5flHtQ~ja;j^qf5KYV$Q85Ec7>RB(!?Kk=-znm6#I=nlZBbp zgT4?9v0D52p;bmfQsH;AHRR*M@-d$`u*GC%^;g9a@Hij?cTgz)pp4@;>tzzIb7O-|Q_bvZk{z=bm*7%J<_6rU~_)exZtH=b6QeI>Fi;W+TO63Z=-4^vvcT>~m79kThtsBqSD`rW zQc3k~grwW0oH}_GI0TwE6ad!{mGAc{5k=Ft1x*34rX$5uA?y#V2oThB-Js4bdAP;R z__x2s-&qchmDr(laVUMkSIiAcIg!fSCFYxYfTMQp5551hKfYw>vIbeLo#J6*Iid!V z{j{~QxiIGT9C$tM&b`0Z>l`T#uv_c&xt276D!T*T#F30Spg7C=uRcJssFKRc+`nZu z&ZfAZx|>*C$#%I@&fSB(&@U43RZ|rJzk1+--40>tEmBhvBV@R@kdQb0k_uooeRq3TP{C;R_zz;-LN3G32F4}(W1s_v2faJ&>- zt=Hwy5wb|W9iUtY0Zsvf@g#yPhLQN}15zCMlWwV+8Ar#;g(Tkx0Rit%WMc#;!Jp>6 zx2IYIObDzMNix%n$3%(AkP$ju*Z(YU?IS^?Xi=3KZ3Tj#@~V< z1)lgoe&KS)OPGdlBuGZYY;7d_#HQFFq$qw_!uBRvXbkaS!5VNvCh#|`+A>V@cwI-= zVM8Nq%_E!0r&LP8R%x}pMuC{``F~Y6IozWcilab2^nCg97@8-rxsLDhOXX~dxW{nz zbomlN1h4HVRK0Twj$Oz%e3D|5Y+f!fvIbLIl(F@oTvv>G=YSwwxdL>x?#|!%MoVgb zLG0+d$z0jvrH=`OKX?$TGC9d-_7T3(tT$t83IR2O@Q_fmm)BJOXAB(mLoS+h9z0(j-iftJ>R@A&s3xY{FafYjJL~bNC(EN!xb~ZX6n8h_jh!V zqU8S+6e0%QdDO&iW<~(y(6~W?EA;9tR@u9zaG*srZ>~ZnV#Q1GEIS?S$iv^O^#|;n z%IO<-RY57b{|I0)-!eoqoR+Vc*j{n`vbp0WV`8p1~!fQqAP;XRX}b?6DPlfhWe z+JLh1qeZa1pQjdiVF(95S@Qgj4=%e!3$^XOhv;5_Ff|q7ygc>r;)~M<(o>lDYW719 z3!zH;J2`3jn>QE~qK2tGGxgZk39|yje?-ixuv)zfmGaBQ(Pb=OBm=HDNFq|ubo*zN zb&=}7$vwjV(l9SaFUQW?`>L?8a9I)zWuzw^>@#$Pgc(VUT-chOM3Bow z_t($^PUU@MD-~*8DEq^%Z=36(IUSG(L}Q>pTRwbRL?9>EMHr4jhp5FsNZMdc^dsS`u;vXo5qddzG5)h`pX9%o{#lGli5Z_wzPp^*{&_8|H&_mAS)yf`THkiXL`J|Oj3 z$Dl}ePCbyiIl8tgL6}?|Ys#&b54aVHt@59Z@^c;KNJeN7wNI?>vmBhz@25lkHyYme z8HS>wq65%$zfF@$m-;lXJIHGrI9Ql9=LOSMWmIp3h~{20#Ht>=p)Q@68zRr_aI^{k zjTC`Hm3WNAy?U)7ogFSrnA&LDeAbZPh(bGkcJ{(OAefE)cPS958b5ha>rk}sN!`x< znK)@?%zyO?wQHQF&E!ll_$JkrezzBp{hVA}_#H%xPd2^MW0_jl1u%L!`;kzf(NDJi?7;_ec-;`|#0h*hK<{5F;1n?NTD?iW4?c z3t(v&AGbZ($Pb(tC)aGN|4-TsL30W+U}$Ja^%CJZ$}b;&D-c6v)h<$Z z1xMCFMg~&ip!_lonpWPv_cZIC@r0TgEtn687c)3im{d<)Hv@#plA5~*mBc3e@a`g` zvLJ$^L!->{8blei<^S^X?}#;hD(sdBA~8s7Z~O9$EW0Kq1Y@NFLjC|^WL@FTfH1g( zsWqUJoe&x&W+Y_5*h{&YnFfu`q(%UJ>c8OVn&k6fVM}21T@kr_wadZ>3wV_u%F&D7 zFUdmx?|eAZ3w$Ml^cm)LLr(zy@nf40B4UZfp2~DIDSTRIaMMqw%>^OtQAwf%7i=N5 zTqtQMbf_r~L9iT`r~s{~wUFa@*^t*2ERVsrUIsyjT+AL$A46?S3r(J1QU_2OKYdbx zEcc~OQq`!ywB7U4Tv5$}x`U`e8#O>K4=GWsRE7JkuAJzz8RP-RP}n(oY>4`-AkJsH zSioaraqMD?a5?k?C&>+EiV&p18tU7+Oh0+<&udrFT~Ux!AtQe~NP+N*z1GfFB8i0` zysW>ce^o0kttHUKx26mZqPUEvQA?Gy_U{w0i{L>DfI__$AJLh zUEsIJ89Lze^KsTw;OjK>j?UvVKnXtcG=_>wm`X=O{c%9%`jmOxQ}a+PnOJ8zX(l5w z^5uJP@2am;;2YUYX`P*L)yt=2&OgO#o>%0c{XpkV9rz=HnlHs>=Qd3sDVKRqhxO$Z zqi@3ZPBD#My=*R`l$jSj?|!QtK|qxC_5xL@e&h334Xyp^XfkYLZjih~k^3SeGuNdm zDw2CiHf%?2$OG62Bg zhRDl*(BW*UV(~^y1e2XI`=&9Vw2o7^^vZMy1*!oH8~(+{){?Pv`VZECGQUs*S-COX zGBo51ZrZ7Y@}a8_fOK!z;!tsX8cdbV91b>^Q z*>+IboSUf=oU-v(Ordq~iq}oaquLG(IXD6jX(dPG(!8m%3w1$EG}I_5f;%Am6(TCg zf;;nx9BZ%t!Y8KjYMb!ojZ<&LMa8^Jsz-BLY8N%a<@;M_
Z{>2=@neKAo(^xj$& zxby4twca2lc=8Um-L};a#|GW(2Co+V4ZY3{=2tI zPCYt%LlJ)0W_~p1W6OEXkj3$Oit`70S zY|hn!Q&VsLTK6q_bt#}=TX_t)SXAzdw`o+3}VYV(IZ0$8ZIPWj$GE8>P6}?-6j>$?--_?pGz& z77j#$WY=weG>40N?(j!L<`qqA*J@subSgUZb$_uw(iuyR4xKycR{>P$>AlOJhruCC zI*IQbc^FG+nWBzzLsGa>bSmR)elMVkZH2{T;1u+l;JWGrMW0F zJ!AwiNF(A5a!z_A9f!h%y-)`U_sa&4w4aLNq=N1!4XSs240_=IqkTsp<)%amd-V+E zI7IhJUjnC*q*o_%FVsmMUAyoVflplEnU{*8f2AJN2_KoZ5dWsw0RN%Kasw?LC6g(J z$;#uID(PF?y-H7JIdf>={b6yY)qW|)wfcU+NGrF|F%M!wk*;|TXB^zvl9%%Pbxw?k zTAN{cZPhEB;%~ffnWSx(FaM2d~}xIx_-!;V5i_m(-a!XueV^ewTz8^B&<{W8V)I>wrSLWKJE*{o)q2jn<+u=;InpIpZ}Oq<1y&|-GJGRDTmr6{fGPa z#0%H8*S$Zuhy9?z&15p{cFkVqbd!MaCoL$!aWfQZ2=A{%YEPJG-rVg&@kOb_>E>VrbsQL8G|Mss$o-fh9p?G9yL}%R< z!kULsk-~ERSr6`t5tXj`sK~mjh_62N&kv@+_IYqi>N-=batHUBuH#mFYa2QXDUrIESW96x30jU&T^|exB!1#?$Msyc*$WXsCiQ!e;L zR&NJ|aHewhkm7{TT#Xmk!;*b!{Y7-;M9Z$lwLXbSdbN{moF0D_L1Yt^Mi7}(vC4`A z8wrqmu^bLe->#*($+`GX)V5RJs^7ky?l_4GO05f|8S#e*aJhZ5L9#^|-xy-34rCtL zS@u(Q7o5Z~5>e;^%bHQuQQUfbOoG*)T_1rvkO==HJDqb0+N%%>=0=r;^X=+{A_oWL>z_};b20Nd{vPxYS ze--=qhN|B;c#*B!d6OIb1jTJQ@WL@5Oz9q*=^D&4(M4>^m^v_}mQ`&O4i@&ulN0$a zhbW^};p6lgI@!9O)rB>u%B;*kS(F-%%2eTZ0!P~niyn7Z#65kB8xKe6-J9&&Tgw%& z%1$y4ib_hHToLzZ9QIwkfqsNEHMf=^Z^h!$I#p0IEt$%Mc|;(qbY}bNR3<2LVTZGC zON<-Y;(vz$-43ymic6h21;7phN_#MvZzahK%$@v|cBBz}n6QkFk*j*j+7 z@4>JbUsT7@doj;%wN>B*X*V-*ic0ihmRQ(_h_0*s3gf~1$m53u@k0taz&9py-S&`h zHAA6yVRc$<4~5Bw{aB1YX3yR;KA1hUPaqlx@{3@;%t};p+RW;Pove{hC8oBT6UX>Q z-1K))s|JET(<32`ziQM54%2O7ZI2cl4?L$%bjf|YdvepcXq6Bi1YxNYEkJ~nsUbH9 z+`gN~D;%_jjniYz<}yyaPtFb)(>?vQq#QD3js~p<=*u8+L~Pj6v&PCrlDI=_Y*6sc ziGbXZrFI({474%!I5-7~0XJ`r9P4ssWG_W$hkS?p?xITmqCKQwsMH-*c`Dkc zsJLcS#4&HK-ps6S_f;O)kf!&0&tGL+5i-A_9xlzoT{vVl9g62|$Vh7WGJ!&8hmz^0 zrlqHBSiy%(;cg?-E!>48c)3+a=P8To`(_eJRmHX?-c=cc4K>}#82VaINyrZB2KK0# zAbl_JvPVt#bWQ3m){+TUJ0PyQ3c8?-vp`eU43EN&eB~>?Jcbv zytRQSt>IEH@-SOzls>;Dox#hmQ49X*!G~yVjj30;YS>l_6&n&0=Ln>3KUXkygz~+5 zvHaV|@~CNoWJF;b=GZ4Y*|oPOR1iv>nclng6?RE^i_+qGlFNMDNd#l_`B?dgRoX`< zN35a5twa4VO0G7XKC_SfV#K$R6m%#xs)DDjfS|g%c5Yw~Qz>Lrj39WnAn4pLT-L2w zbV#cza#PE*;-+gO*U=urr|}o^#mbiFbj)b2%|e8y_~y+}@-7b<6)36p*rjnvVcHZq zvWGn0oc`e1mAe^A5qh3kdt{ES72IA76HFl5Cs5K)$*F6I&e6A(=v1?dt*=y98b2(B`oMi}wV7vZrr58gTPq6XlMJFAE!Wn}Naoe`aHd z$Hnr^o5!{}gH3H13MJSN&oX?c+N52FNw;6wQV2WW->>rfASCDVY=g@ye0=}{Jvew? z?@`_@Ta&s{)Yq0peGxhXE&eOGO@5@Fz4x3tkMh)HqfWZ>n!C`u%hCpFSNjZ=rzCyD zXd`A@G`K5mP4<*ny14mqnAojU>QdHMg`%OX3{qK<0Qlcvg8~W zyknms;cf!=?p}KmJR*u0D)(>DH{f`TIxXc`t6)X9rpP(+b#j&9z2HhExd0Wo@ZIQ= zY8lBTG}?qDk8Oakr@eA!JqTNYorG=|Zq5(QsV*~`H_d|fVvibasea+6)P~1S1`9WB zCIg(q?ha=B>y#!*LAtRAV$G4aXoJi$-osr@bj?a9L+^+&Co-`0HGn1)=dCrvTnVCK@!cbtxozBN|JG&PMU z)P_#thP$pD_=fN!{eQT-+rO&y?n^`r*8}(`!QOTf5%zt-^EV&{w9L<+o?(+Zn51vLa8rGjU$VM}VD!&p%gcNH2D1Nz#}ceL3&8T;3T$8F|v zdQR9nDEMr;f<4Tf!zdVtKtl53slI-tZ#CfDUj)17>N`_40iOQZ*};V8bGS=~MbHIJ zc-UOJY!_6tM#vXV-OEzj9QQz1t~6CJHR*@V)! z;o$zLI-2k7I$3{VEAQsfsnk@{z7|OVV>YmGWM;iG(~TrLzT0ljsfzc#>H$|RCO1vX z%&|<$YK(Yy=e%3$DmjbPyCAk5s9OHMUpW>t5m>A6m9oI1x(A{l)#N16@;UC~wz#yXd&paEx{%FlndR;K25 z!Sa@<+5tOf1|xqJD<)J=Lon$-Ta(KUpjG@%(x!4VQ*R1oTqH0J$3Yb$J?bQ&P`)a z-ZI^L$AQ`LQccxDF>%M{FfmdLvh@nuC)@ZDL?~=s#z5hd;PA>$P)S+I_0c5f{Qpr` z*GI~%aEd4ufQJDkYK_i_5ko)ZT}YU_AF1VlNKo*sn6$bKR&IkZO4>HbmF26fPhmn> z(gvo!@3pVGCaq<0t~&+Jf$^rpA8emN*8AP6lovvSs{;klzFo-yaEPMsT+)NF!Zv9m z-;i9bTF&xs;!&0D3yqrUC>y#U7~Tum=PrUYk?!0}bw$Q&^jRKbJd(H55lkm> z4pQ(|=|zp(x4sNO<63zHX{6TJq``258UH7eQO6&{u>8#LA1b)+L`MZK;iR)mqQ7#Y z>Dtl66wC-;~W9c|a!B?zrnx+D78z-@z&K?GAW=d1tW7Y8~IR+ZP? zo&R!7ukQ`G$# zqqA-H>~I-jUw--#UoUGe^z~wXl_N>}E8-c>0g^*n%xLKAxtI)p5AWyeAMPu%<-xOt!dliJSxx8>>&anR>Zhi_>Vx zNpwIqdbFG%2_L9oY(k-GZQ z3Op3LuG8ol2^z_t{#M2Na4z6>!&Db%N}q13%Pk8`F8q-V^e>v%@*jzq|lpvb~zf z#Upq!W~E69JiRTr)a*V#k8fN!rKb3Et(7|hUsphI#7K7VVO>@u z>WHVP%n?a!SpSip>w4?w6l~rExrP@Vvpe?}Fo}v@2!TRH#dfM4#)}pDSAaOF~SPz9-zGy2}a`3@4QYhW#MJlLx>cCx?H0k!tdnDoCRdtv+`spaQ%V0*}p z9=V-+0Q!FIp=sX369|8_jZav)ym6o3Zba~-Thq9}Rp?|`^!($9L>K#Z9tBp2b*ihG z0N6P$TfvS5;<;Dx$|8^9cDl2fTTfD)RAEJ9?e=L_!}-wvo2#FB`?{}&3}|Q*KAwNz zTOh$M?4Xx#=u|~NEh{&u2nIJ1>sLN{aeT|Vw%0(Emu-4pl`y?M*7Z<6DpjATqVNP$ z>q9`0ii&SV&|{~#PpNS$2%Z(2omZ*=n2gBk_Q1X#a}b7JSnmlZ7uR*tORZA96lZ+} zoy3cP8-DXcKOY<5=KLkJ0a6-2p3Dp%Yyb|s9U3a?y9flyQYZEdb@`I<8_AzWh2gO2 zPo^ky)lFD4R>-Dew8*g;dCmI9 zD1TBqdv-!G`^A14&`2lb`{$(1<<}C~KOj%)!)n#Q+K8pSGJOv1+Qsej?unwg|E|;; z^Zc}-ErX=0FhVoZ5nm|jkWrnF&e21T-`s;#isblCUdTph1(7NQ zj(M_1A-02HB*w*JC@|m&Yug(knb5sonCmG$(~%1y?f37QJmq$HCdZ3$zC#-SkI(Xk zPuCw@g(ap=d7^bjjRK>>T^rvI>s2q5C(Tt9y?Udw1=ra_Kc%2%t+g-ONgp@b1ihvy zMwd))6@fRtwSC@ecdVvLz8{%$O|foocb@$MTKWZ795HEu2ZmrjxUlM5I{eQ0|LfVU zRVa>*5wL~HhpDzEHe*VQ(D8Db+k2H94UM=FzoSdFCb0h1zl!`+H0}Hzb#=Lx!8`!%icC43?rtH) zp4&Exo7ErO`F{ z$v7DP+@V}2mD>*IH^n-6`bPgW_cjYt8)m9#7S zUOc6pw>W}&+Z6w9db>6 zc8+ZiO!1$XAKOBXx=B*1{43Ea0ac>Y-MJ~9=_`y*jd9y0bWKNv^q?TfZIp?SE!YbA z3(s-7J^w<@JHhqNtNjHa|MdLNE(gD%mACUuK0TqKiwFn~L2%Vhd)4g(=t$x)1=&bN z#H9Yb`Tw_~jy+o`l@>3P)5!rx;Fh@7s{D-x?k}a6a(dNQ^v5a0XRMVt>j|~?9H5Hy z`{y}CnM{eCFm;rL8pH^R%{3^-h8-T=ReL0px-}M`Al3C&&F*I7()BljhVyp7YK``d z#r1;FX%&H+^8&pK4K8#;-U-c@AD$62&I#CfkOkNL<0t$r-AdzQ6Zs?SKM6vHr6%aC z$C!zg#%^+O?_#6V;aBlXvPR?&$CG;C2Ma+-4qC}U3+P>s-boVsFso|ov3KNky;p(j zsP~J#N4gf6)j}0Pyfk`Cu!7hBfWsWY5;5@e-NaAQ{OtLKO+--2{YQS=zSdk0y(w2T zZO$=Q8Qw=A{xiX$^Fh>ox_xrRTLB(kIk2dZHTepCk8@ci3`{rF>%yiVQ!S(!UBoIP z`Q*bDe?G#g=Zkd6vJ_{R4F@eeUyVNi)I{x+m7g`{rk&t>wAGJuQ$RWT}swP&g(s^J&JH85a{WN z*NL=HVt2%U@na=z6^aTs`p1`>b`Rlr@Sf@Bl5wj-41MkNQQwpPYu$X2ur9kygKh;- zKIk0ofkfS{f=kUs4All-vCGH9lU#(cO{{*opr4ZVS6x6Z#W_$zk= zt=%T-?7qew_qKFRPX2yWo@gEz?IPP=CTQ)X~;c6 z9DVGI(au5%bPfAdR6H7gv;b=csuY5eaR6fJ*NXpj(v!x?VT)J^@koi@N34a9Z#<4N zPDemib^^K4Z@H9)VPkjoU}OJ<(|b!*GAa=-yV=Lau=!)IgR#ot09#5b{OwXPxHI-r zXe5(~to1WPAp2n3aKa!pPUi}?wmC`_l9QzSsDKbM94Ff6fT`W_;U>$m?$cg4)iw1p zr`*i)oaosI#q`sGMqyfbUu`3X;@N;V5v}3EXSh4qT6y{^G!cJd>3>TibbD;^VTHJZ zhX;#p6t4DkXruwJW9gNW$AW<@L0x&;JRK1fWG2IkcuHGJ*wq4oDKi^|>1fZY4j<(K zKEfsR@EY~w>Mh7RAJbAbIPq%I)5$L?V`?;arAS-n&+>=TlXs0 zIv?6dUj7$7A|gv`-e^Tlw6{F|VtZLqR z#xAY+mK5D$)P*3$s5S}oKt){k)ZrL3(4ACo_^+RU%uGpl?iOO)=6n=l^_tQNNM9Ozsw3&gAC(V_;_+)m1uaQJ z)gx_wRr%|L{|#_FW#Zi|&MEk2#R z=@?LvhA*Mx-tC2zf8XnZputp$!ZEnVVRBLH%-2&wlVp?0l%r$qgPqzui0PTZxI#*L#ngSn-3ZpGtJfsmUmc4rS6y12g#@lJ)NF5Zc4 zwY!aQ47iYx;1T-0w~Zlt@^IeX7L18V154X>}CVg*O*{QQ=RpOWnzASX9dX?sVWZEc^;2t_qf?rR~ z4wLY^iX&Dss*`>F2mOAvDT`7PBe%zBxdmH88 z@7&LR_X&Hq7R|!IePUwmM|8|Ki|^9XOlluMB`;y1z!3C1LH9WHzVHg5TOs^bBeSbr z#xI41&jfR}Df@d8-_Bnz)rt*@CL?xq#s3+P0rc=L=R>0DU*IIB0z7IADuN|>A;tob zd?=})pSzpPcwi$%>>&`gCF)N$2q&hwG=oK_f*XXusZ&foK?|f2kD6%eoHl1?V=88o{=pj39b-lMwv6NKV zv0}xNqaP|Uz*V%3j6)X$a8IQ`1$o_!ad;+A>4jsT_P!6q84fmJ+rb-CjrW8bXSC0P zQSONzNEMcyuH;CX(djYCRK@5EFNIrtt$>d$tGMf8A~74*ci7MCcgfyR;_h!UON4i1cK6x>^#w)`N-cImS zVQMeCw5=Z8_$k~5;r~`clv#@Qd6Ox0a!5x+Q3S(|SF|yk$yboF!2U!s{Ar{5hnMp< z7!$sVtTK0%fCT?`vRAT$K_aJ)R8Ng8jq?%D`@)y2SeL6*_R26W8irU(44DiHqX)T^|rLIpU9b(0s zS1$x|;*(inBqQ%1>VtM|mX3>FN~J zQ#X|L*`1rM6Lfh;+HD}dPxxU0-rr__11h*Cu3E!1?h$rg+F1TfOYiy>@V-yBf$?nN zAchR0Gl;_}284#kw(?2t3rJj~lVW)+W(+uX<%W*uv>)G~1}vJKYojWo?c+KT@ve?= zMM<&sQ#41HpFDQsHYwh_kexSvKDqpk2cx`#=T9FR&UWP!EE;?1j968JK+{PjQLULP zrEyr0XYKj)awP=y#kNXwesU#5>yK)z3YLojqOj?JCQb6y@j~`j@_J3}H@|qBg8sIJ zVt#&sL?thZS9bF7Dbw_a2U(Ytr&tL3YHe4~W;ZnSXUpBG_1ig40)Jj{(_?zye|1VJn_A}y%eXoU;{iL`l4;AP5WX>4K_6Pa_=*qg!uRy!!PkKi4^{I@`{g& zkBYUcXH@X^PqryNF1J|7?Pmp|isMOeoz$tiz=+Eadn(?8Fg=x-IoHaE4M$J8k3A>* zAm7@{DVYze9CC}EogjbfyYf}1%^R8+n5UQSe7Z?L^L-F$AEA#}*n=nZNPM!qsQmqm z81pHG+-^n&hIg0qs0hIothB)D!5dHKR$Q!Mpnd3QJU@EYs_6_OdBu+}PE4rQ``4HUb2GfCnsb8P=u{wuio~*%r1Ni8O4l zXliO*Z?FUq?ySP2KO5^jnOK=DSQ|D9S@%US_`%!t{t3`PAh;!U<46#Yulw z*8;fIMa~RMlDOy_5f)a~&EV{*DeF_{Oa131VHZreO!oE&SHpJ43aV7BD_Uk($BmCS z^qYDJn*@g@3k|`Ctq4Hf8RXAbD-Q$}x@oJbD>Z*LgMi#?95lB_7K9rA)2ZeK*goq`>$E6pdfft9_r_)fSNzrgRa{ZWC+UF=6L% zv|hE(H$$4OEbxll1q0J5cbl!>=3R$mol(Sfp z?*r-+Ko}$6&2yOsPG&BOud5y_C?o==YyXvm++47xfnN`8)DSF*(Rm@R-7>nDP~XLS zO}q^M1J81mo?CW|#?$q~=IekTap}Pi@@MUy$!DC72p`fd-i9~q+1xfT8w6d_bEuGO zXFb&o9h?=6=;CH@iyrbn3xz@ffuaKwV(I*8!7@OHS-jU2Z5f`i2uQ&?b&K7x)3|6I zrWWn&Pz?tUc(s@t0I%%O?E;@%f>D#J#=t*ent7#P6`F}#{+ZJYG^%M@3{MPwQA zaK3>XyFm`!B5n>3-k=yHTzCUd{(+AC<@A135HXg$2*;fsaD7)idAbpN()2=h}N^e})r2 z@%)-_Nz~=`w>Knv^BTByuQ0vF?R5-Vs~Af>%Rd(6BJe~A?Im61y+jv0Qc(Rv>S8mXYLy4EDCUv1HO3XpU4!E4C7gv5@s zLlzgjH$eW1^mkDfm*5T-rJP;Y8}@k}yyEObr|E@NSLb-L-@l*A3gV{s^QY(MUxSV+ zb(po6{!cTL!a0B<#2 z7^QhnMci*`WVIqUU{kOLyE3P0 zwL5zZP(@wV>9Xeu$JKsD(3iFPTCY|s4_jCvnKs2A?YMF?Ra=a;JaPHd)pj6L#%hzs zewF53A0fby7S7>hbu-co__syo3aPEMuYfmAlMNg!HPEchQ+bnx+>6sO&anc#%YaPc3#3HnE)$My(>a#xI?L@xKzaBdCiy&lFYC5J|+bE_Miu(P5)*NOm%b-!bwa(Q=Nn+{7pdsNQ!-JNIL_*C?dog!0a7y>u*7Eok{ zrWOhr*!5H}VYUF5xx*!n+6vPSor0jP+$3xa+L4MgK1C+QwbbIJ#y#U~=zOcLH?%c{ zk4oQP{8;_y{X(GG$25lRl4{ZH(?*gJj-$ynjb9pPlpWDFBfj}5IF`F0bgKYeG6HvA zlWmw|Ub7W2vdpu%hIMk^Ut5)pq4ycLF1hYymFjv6Ac@h{weZ+#+Rz!JdDrTE3BAozT7P!i zEi`i1o*pB88FHtYx!(zZk)q;EIKI9X-nzIzGUTU6D>^(6o#6y2iIZ<}QcWt5oS+qgQBwFMG73wkvPqW_ty&STLWO6n3U00cP%7CmtYTy+nHy z*e!IV=3n^uEdT zML6t4S8Vd&X||;hYfMtwvvZ00*A32ZVvkupNkJ#8xs;~R1#pDO&HrNtQ#<^_4liPl zHlr1X?S1W&_bp-<@~(6@${t>zTF7E{!Y2WpB;?!HsJs$&G~@xz>elY&u^m@HIxMwf5eFp6g3 z5ES;%!%}M&G97N;G;HPk2~o&{Rg5IwWfmu03y)ahU9IMY;|9TCL1MM(Xl5qA+eI-$ zyT{e0lDMN8g;d4qhx@JB0tS!lCVK)Wn-538nEtRp#&OnwJM`rW*HWdRdjYl)!&6rZ zTQTzF>=`jp89s(xAV=U|M?6ZN0m$Td%{66pr(aw{5`o*6w5=lnT1IAAXMCtFj0Y|D zpfxL3Wm2i0#=jRIT;RU?!(C3AJF~m>iTU0R4BTL}u^BJeWGjeMjEcwKYVtyL)*KUq z9w37szI&xEBdl|NPVwsX{9(A@!-qMtb+zCc4acu{D*Pi4v|2M#P4^}Z+p@z*(h*ZV z#30X;@hfvDbs^q2L5%YY*|_<=S=Pfi`T7q%MYi7MWm!JW7uat9$E}K8l;}mR?M{e_ z^{~{_%Gpz9=65>pB>Q^4*7wAQO5)Hi-!UFx-?`|R{St`Y&yRbdO2`YpTv#If<| zDW?I;Ke;o1R~1O0DYKm9M=o=9QGG&TNXJx!1k3Kk+8W{9Vr(ViUAG%xI{;QfW`^Il z_Jh@fzxfu(GtXzYTw^k6!0U(C6<9;>k5(l#MZ{$CNp$`RN+^l)jTA3=4OEJm1L9B& zpiEp+OOVC{2It~!es2|R3I-#zQFJ!jIJdHZ;G>&i)Rb8QBM;H|=s-1LQ_De*Xj=bQ zWP3RxtVqx}UX4+4IjoOyD*g$-G13J8(=6ITRc6t6vx`+Ag* zSew3f0E$cKQR@4ZO+6LW<1OA|_vIgIxZO%**e=9&YIC3-vw|1&o8AhDLz1@kW#Hry zwLO)?4A0{&`TAW^N>O0e`p^7UVW;^aqrtrm0B8 zo)yqJsz0_G@)wqSVc+eRg_U*Po1T7vHIVi3HK&L-G0B@qE(T2l*-_1Vowk=%A2Dt2Zm(*8E{=>cZvAJT?}JZJz-4CGfyRM%U0# z1Ta;o_i7G6o=&EyKKAgRej5Av_?&)Eja{yYi2(^^khc>mZ^}w^CNrvg%3%nl1D1h; z&hx{n>-3koEZr(QN16_99WQH#$>EE-TFYxZW#P#gwRPiAp8K* zmPoumF#RH=ij7dB+TnD`(njykj9M#=>SW$PwR4GE|}{*lUj`X4qTy`cE3Bg4o) zC={_h3bM{_)uXQF$SyB2qHaRvD64G;-FP~MBke*#3{&vJfM;w1XW}73v zp1FOJQO87l{4mWUk&s>^$$S=9_s%+4SxBIh$(g^d{IN!DwW^ciaZ$Z8<#s>`S;*c_ zl*2<->3)gwMjSt6^{180J?ag{34ZQR67ir5dSu#nUlK1q2IY2ce;3jZ=59@2Xl^NL zEoG_YVySHEaheL1{w!rFwWXm0m^tQF%l>g>;<&Rz{q04^{f{5mVpz|$PDTYdezUf81!heDU{uaAC zew=XNm%v1vDXP?Uwy+7CgI8A8vVFpQe`ZPzaI6OKw)Drqiu#v7+X|&?` z>Yts80|?s>GbKcimlz~m!u~V8K`yeED0qcvu#Ag!fc54mOS&|{u@&q8?Du9fAo|&x zUDwv?zobC$Nm!X8fzP}7;jAI^%~$W-90%b|hyqzS3&NJ=7h}ZD|1&jsJ}~C=?=Guv z{@>F?+R>fEu-<%aV*2k?uh913-7CIE{=d)g?@I7{cmu`juLKO`m1XBiz^5&Qm7~`k zHZSVW2Iq9(!D?{goL0(!AH!@66_$p9YbgOa?M5Nted}q1#SgU&IB$A0y&Fzr#ct2V znh!0PGm1);{`Mjg-zuY*gqOhQWSM!1jJz3+R9*;5v63SM7`yVx$9(g*pbL{6h^Jy_OW3J?OtEOI&v^If1F!Tbv$)d-M10Yak@tt>Tq8Jmyi5Q;}$DN+4w~h0Ea*iJf|M_K=kJ^ zyNzAd59gy!s*Z|!l|CI=UR2?OC;NxENoN_$ABD&a22xfBknT@f#d_gNBEv}%NYjw8 z%>iH6$i+&^l@5%7B|%YY1{mdv(VXL|i}WFZwLQdN@{kbq37{TR1EofF({l5AIU_2U_%jiOtSJ(o4Y$hd;C`0GJhOv(OK}{H`9=mMGZGQ*O6M z?V#ZE%sHUiHKdH6#|@%ziDMG2EAryk53c~NHaw8$FphDyFBSXJ=-%VAWRDNIo`yn| zejP~q8%}7O#$-qs3|Dc$G=`<>>4>gfiLJ7aOB$6DiJh_h!<(MN9+q(F!z_X;4<55lgRe@iFP9&|`yRk{JURb#x9m}SXc_*2R$FD|lKY=CuHdBBv%6Ded82DU z@R8jC3`gW?6q_fT$U3wB;qwYN5Lj!Nrby{qNHzvBJ8a%Wu7z*hC@;H&FAwv7OaWCg zuwAZi?{PuV7I$W^8?t5|^Yq%qmn(q;KxLSl9|Z(A6!T}fiKUM=Rcu1%!1&*{IWEYSqz^gP4)leq zoGECQ6$6YbXKe59<~rD~jkem`KO0}s&YA3-KY$;z+-R~XtTVlyT!i%wCcEpvfl4_8 z;6t^`6>GjfWQTxEkI{Q1&pxve`=^Tslp>gKCe;7OIYs^E_= ztF&X?T};Uc;}u;I+;`Q(I}np8=^DLgu{LMS@yQ3Te!@4ZfckWd0^uWC5-Jvf^>0+3 zF7IJhP^(pZ+?BsG+0pMov95N(ev-_69(Di(&=}m^OFal*x3}*=*BoJT_u-N-N!ck< z-Hx048yA}G?MI{TsT77HxW%f!zh+?kn(v1;h*$#s_M}`&%oW}#tY>O_*6r7I_{g315k$Fmsgy=>ecse=)Kq)@^t~36Z4U+C z?Z{W3Hpt)Ec{%TS#=`-YfjKTz{Y#l+*=leswG5W^nTj4C(T;~!)QqvLg*h9;=F6s`DUN z+3w_9*DkM=a!!%)%Rs(8XWH*53*a9=GpBrC8F;2NCfY#*&OWybFdaRBCSA5I`wH%* z{n8lsak-D{^bI78Uv=O80bi49KJ18g1hAX6GIx=)#8TEU$h$3|qbLbxx z!hEM(om{C_>z4Z$(Zy~?X-+yGYM-(%oqVmRj~y3r%5E_Iw%Ysj$rvwb#=2}T6u2mox{J(t=JAUn6}xId+6JTJM1 zWTx8r|ELkYuu2tzdAq^4e@INZSUO&3X3Ul*U#2WPEcl6nmj7(bt=DW@&hoE}I*lEX z{Fy$+=*VLTuG9gd?WEX=x}9KX*+c)tJ_^G=WT}ig?Q+9!hdnK|S_969c)24E$MSz{ z-)psiMHw1^UexCeMqBq*_2&*VUOD`1jSn%_JJ1YDa4TkEK0AJN~O$4>X)J9gcpl1l^WW&q8_8pVT#>FVih$Ke$D zva!Ea_S)*+-GO3rn~qE5WXNn(M^oH2P^UtqRlhWQRAkkkan82rMs|$Ns~|u|LU(WP zZWZqHg+pPGxdn{JPyu|nOgvQL&|EXA>7gwzyG4lpnu6Z9zl5#D7TocZ{|A0RdrQ%)M~{ z&SPTsS1v>dm~_N-%lUL=U*>e;YIXh>g&{zn9%oL)$H<7!qJo&GLD^}2Z#(7@r-x~~ zEZ$V?ENog?9ns*Ev_C&j7OM1{WD1Ej_8GBH-OBSUxDjcA1nT$|HR@3 zIV6U~?*XKAV-KsP5bKDT1#Uck>v)IthMIMd04xBIpj{YDbcETY-_qRoSh*b?9AcBen}5f3p^4s_KTa7GhQ`2Nyy zbx0jHJCF*o5*B?rloM9#;mt6eD{w^14MOQu-qXwiab9TOBKgf(`TJ9io$g-f zdgtv_KK=UCx>PtL_;bSgC3}-~d8Fp6gXs0mV<=+*W(X3RcYDmr@4*Z_6-wkpsNl>y z{K^WOIaxYia(uFxM4eqcmEWkSRA5;L>A_wCTBUwl!Uk+~<%aCUNKk+_6z>&Q(^ zrRJY5pI(x=mpG?{IsvSC0LfFh6s(ot1cw24u+~kE633BA@|$1tAKmTd^uQtri0-si z$emAzD)&E7@0bRnvWFCsYyN7%!;$%N_-&*{%k1*)ubF)TMKZ^E?>cdhL5r$%l~Wc% zNpY@G;VCqrg^@BP-fi{_dLd^nVUP7kw|ZIsLFg$zcQm;3+ArjFXDLhU`x_-Y)(8lz z=%jinZ$8fk1&#l6NLXJS_Td0iycsAN1<`1^g?5quD}?wo9!=H+sobQv{j~06eLHlMpC`2_YDsX0H*+?oZg_~I+F!w9rqGP5M4jyTf`YumVEg*1wcA$J+lQgT_#ha6dhj|dHvpAnNKQP zpItti1iufLDi_aS*s>XxKKAcbdfG2i@5UzT_(XUO=s3e#_kGcNXyA$O<#bi}!YS_G zOu{@Jo!4G7J_kDd%K_a!mv5|A4EfFN%)Q!Z(Ktg_0!#bdm!r?*4(-emi`RE|+r|YH zDTu{$Mi3K07^X$rH$log?9KUEZ2WRZT?WPN(ah!b7*nj3BC`Q<3l<-E1gVM%btV{G-f@46xY$;H1wHtF>NKW}}!qd^3)wm7FK5fh}Q1;jZ*!Cb1@RYe` zGD|E37jimpc)|Y>#rJ=ysLOLh`$5~R4U+}!g+IPDfoXkrD2i09bM&?>RaEl4y)Kk| zITcmsXJ~S~p;X;nRS__sX8}RT`g2_kybT7Hi%dhTf>p|?-PI1shXi`)keVt=oFzBR zo1A%X{KXitup)yKCyvh9ArTqpSEk7FRm)a0Re$bpkR6gd|d1MkP$CP(i zek)ML!vPQ9bg~JzzqtZu=nuW%VH%SO!A1+a&bK7nm@aYPy0|QFt&Ky$PrwK4Kf$k< zOMWN>>cxd5U=!X*#PLsGcyclKTl%*4U0t!1JW%IRB$8lh8goj$D0<(_q>TNc4Ud{w zrSf$(&x5!j^(-lF;?|2BrgBdp>qsOhGMBpM@{VX^8x1`EPP=NC3eQ^FUo(}M3=jQ& zouLDAHbuX3jr(+O^nl|-zaAQgj|mRqXlQQ=Yn9U{!8%xx;POiPoBj8;?tx<);8~}h zMuYp68+muWf#(UgJID9z9A12HFv)bWa-fr1Sk!28IC9$bMZPx~bVo^j*lV>XC<$d> z_9Xo|6N{g%&EnqO(m~iba21gxzpa18Gt4FRbWPUWl2j~R$^XK?OMNA?ncQO%Lpv6g zgc;b?U2Hu`tj?8L8BnX#x>Cr99o=mVj~*(KgiB(pg<7_S_dDrccyTdjpFVy^rZiGh za9CU-OOXwmsn(b4a}0#V=H3k61d2*AE+uAZ^ zz#1>-ThU)yw;E0Y|IN~kcEHumo&&%5@ay2Y(%b8fE1J`6hQJ7p2EJm}%4%QlkN$5y z`$pFn&_5UZ!x4A~osU;=7z8Gtqb7jU%oaS!)+Q67WX%)3GO{XLbTXd^2Lyt=OULj?54*9P{B+&4du3Vw~K4jhaeK ztgZdanH2vci>-KE2ug?Jt7(UloKOu&)ucTa9ckwkTen4@BiBdds6jH^yIvRh#win0 z7S&Se_a_q#VaM>YiV9QT=#@t;x`{-?tdj>Pzl6Y3lBWzMBfp`whn~QMz`LR+NS_md zOA(@0lqHAa@ZZ|bQVQRQ&b;D7Neg_6c)|*V>jfq#>MJ+#t%M?19On_SYGkJKSOt37 zy=2HNOwQ*-)5-WwBB(-W(!4!XF@a=TPhM}E9VYdPVO%?&b`SdV!^Tt>&LrzQmYN#T z^5PlWpBiZa9ZCf+Rnzk+cXZu~-|?at)wb7!JLnJsy1KfMb<+-&WvOtw;~L*zUV3jb zH5PLTu}8fUUK9E-+qA6yd(@Z{l-IZO*(!ZP+W^hFzGAx;BOuBI4&aQ zUqA$N5|3Y4dmm2c#2)qh0yis9H#q`^NQ@3lu&e6(>m7(g&^3%ERsoVLr2TR#+mebN zdEKwaI6dQG&FUpYB`M6Q4lkzlnOXR9yU9mN@nw{E$L-SpsDY#al{e0z5Vk^N2tolc0^ z0>ay8eMElWfTpXb{eh;^4LP~1@l>pU@F4)$iLWgC;w!SQS5Zi)1zA}4BsmVw5*H(y zI6cXf{^yQS*(k;fe~ow@Wk)(1*&Po zRm06H!`e27&(m4|5wD9sT@}M$u;(j|n1+#ntxNGp{_B+#v8|+?#=S+dAAIJ3;Bq$m zB~vp%N+%0vYo+(&wp>e&Tyn4b)rVJs^P9$bxP(`5k=!hn${N$OL#;o) z$T2uEqzon_26_3J2z2Bkp~OWrMOUDT+lA2N0*BEuvqN$VGsg`CgKkC-r zL}P#(FTaQOND!V(d)bHqK3Pl@ER;>i)!@uPeWl&bJR%Oy>>Ax{8CjCgSBO9}jzmGK z=49!0uj5@mv}KL%Aj`54VwdxdY?GI^DEe|p+Qn48+-RZBv0B$+n|{rJX z5yVxcWl(!s3(BkfA#;jCv7}X2QJxy(`jhO@_#Zz$=&%siifM}#q_F=;rG_wz8L z`dpw&@giY;tZsSuEO8-cZ%?G**f`A6+F+Du{umziYH6gHp0B)e=n6LiHRLtp zQnM}hf%T+-$+a;)WYYf7e*KQ!aOTY^&!J+pT`OZbDPBZVdz_jY2 zauytxboE+I|KYLu_6rd@$F%>zJ~r_3=>ZXKHWd>;Ec z)E`?7Mh^=GGDs@dV6~t9OYnGgd1rIavcSKYqFsp$G#GKw%XuO&BIpz&LP_51+9ab4 zxZIrRjop|(yk*A0tH3bi9;hiF)b~vVVeV%bzY}XX3){|cW&en6`#jBZ+|6MLVrZ_EodX*G^mGRDH-p@sWFPcn5&ufzUrey`%#5CbHx)3&eYa0x zdK0*Mf-T=Cb(8>YPZ^K7O7F_#Q4-mN3IfM_ez`t&3dnITa>kT}D3^%p(0{e!NF8Q1CHyZwblH#j3hKQke?|wIS7`rte z?6beX@|wk=4k|z9{Qdo$Ibi7QjO%g+Nv!T>|2C=SBqps_CFHPcJs`%AC3GcnG(d1m zGY-YFq3D-s?d^ieEjM4P#d+okaC3(8fHimK16{mXvg&-i#LDF_^-oePx>?$$4U{k+ zd-0eF+s3fLK^%>WSUpng6jW>nqGthLz7OD{qcZ0yc%^^aUf3FMD8i(Q88zu|>Sm0> zOk-u0&f7%duG>w|;vlxwoQxRHX1J+lovP-5{?#LD97qf+N97+q>d*k7t+GiQb8s7ccNF6aQF)wB?a0FZkL&qL zFlSTHBHy^Sed{}>tQlsq+9Tt-tnT97G_o;?a<{c#{Z=VQ46Ty}BcE9?g*Vfg2T@`- z*3_vz-IVkjvvRPYiWQ&XvR8Uh?}oR*dmzpezmTVVQ_r<@q^<14qpPLB=9(v!IpDVB za<&f21=hS7G{sw_nv5PXVJUd286UkBP5Ju_gcfKIks`w>Cv>4SDdJPf%9o%CeG~n5 zc^tX)UeubW&{oXWZ&%YgDQDj6y&Fw&rz`JFRkw){TkWd}(z91Ax2bLiKU5Oj?+k2v zKD0Te*_MaD54TU>SQLH8ha}ZAfR_P)^{c2QuY%6ip$+U-c@tfY~KD#W_A{Xa> z>AK#PGeil^(EefUFHgumtVs+@piwE+)G^XwkgDCa4%z0_OtWQ$5#5D~hBgH{c=&*B zFLhV0%#q_BbH^?&e75xgo4LtSEPWRTzOpH9d&Lt3>OG9qzh)SdJ^i*9T|uHEEN0QAt}6fHA~Y zBR8D<@~)Wg5`zR^doehl|6okCI!Pz2_9}bf4OA2T>MOvbwC&aYeEZgghRLP%Ro^pHw>4YG?=CgzIK+ z9#vj@f}>9aLRI!a>&-IcYL(NqQY-kl^LX5+5A5ee_qw1luK!OPBH*vPjC(@-;`G&=9F0j6lZ(dt}SBucc5NE{P^bGbK_b$5tpf2%DVb!BK0S=H-YO9wzy-Y+6RFJ&2kmyy`uppR1cGQg^{fgY_#A1rdJnAjm7Q=R!JS2FF@`1|KA z;!S=f7_ZZ+a-b;SmB~N~r<0NLEsAi?p$Tr0&l+m5uk+x-HHi=L>5rxLvphSW5G$OU zNoO93>YTZ$woD$evTQg$j5w>9TP~B}9<^5|MXflDZ*eX;E<`O<17+juMj(B5kuTSz zS;0vxx`v57wko3ddL=*0|KCu|t+zkCQ3U%#AdrhY|7b*t9JVRYc`Dp={!495e}s-= zENkAf5Y>Hid|Jf^NLCpnWGIq$YDylR|ND3uX{p)mK07+rkiB4x(TzE9!ppx9?!M~h zn*&2O79t)%X}MTkaN7|*`Owd{yE--YTDcrwYPq22G*-i^ceXry9Id~GAmpr318AWZhSc?#S z&J#IOdLctJ#T7YT>b!qUTtEB2WbeC%@;`;fssafaGM}NkiSYf|PsaF)Rvm#HH>uE} zCsOX)D{J^gM{!Wj`%UFl^B$GgPF$3i8xS*ju3h%ddIM?>;T=$1g3VnFNtsD|m`{>a zy?8FFttaXlp0mTTX&4bB$oh~fzuGw#a-l;b#=*_&WpYa@qU%gIHniTpDKF|G_Pa>* z?_+~s@y+thFRy|REhBNh3%(CSlrl-CMVdiH}CCu67Sy6M9yUR*W&R418$ zvZQa#u)%o>I_c8u@P{{RU#N1FEqmGYJZ3=$Lj#^vX`T4aR3vjAGT*<_j_uX^{$(?a z9-vQ`!+GGT8rHrV*4X#fprVaj&}&1Lfb8KM@BGZ@d?eI%sL`!(?_twaa9e~Z7I@g> z|CWSPgx_ighcgRL#`9F-G#f7=ZklsG6k!10W(K7kgOKitsn5G*(0Y@tEi6icQ%54i zCCC}Pf4G#+<*36HJ1JljPE}NfXK5vB`1w1%dkfWFkEqPIAO~mv1Y6M1&K3RB;nT%h zmOm0|!)7j3oJ#o5$Re+}mt-+AV$21~vQvAp6%W5cvDFNLtgSwYs>{Ov$yomSxmI~% zg;&=T3TusL!p(-kRFjA9GE>R4ELAIdxX)v2&xTJ^^psQ?I<(}a&*DRTDJ?(>7#K=Y zs3Qlq?B>c?H#*kUFTJ7;+0qOnx3iCMWu4{ab6C(S3^ zD#0C&V*vj7o!1;QWBo z?3n$Ud-J(H{^G?M?o##plsDqM!X4uU1{*EO6GHY7GLMuD^PONOl8N-s!Xv}HlCkXk zcpFo5GRp>M>{^J$-dS6d631aKxb$+cn(0}BgNPe# z*VModU3EGJ1{N;FIwNE(kcu(;WtPCNh7)%a5TuH|#LoSU!$T}mj{zw4&yVy9DG|dE z^IYzXmI2c*V}u@&S8w&PjYw-Uff>_c|RF%ZS^%>3?KkIba&}D#(Q581LFI?3A zt2_L4C{BM6+#G@lgr9#DzUX^ReRsR^F4bzig+0~cTOm`bsAyVd^GD59jZm>1Utx+e z-Eu{)tNsNGH5MahuE1jf55h(6+C?74C84%+1@0SmnD*;a)oiVXwRBTQ6|-S;i%kKl zR1v<>jZ9fj9uSc$)c`W8i#~hJ3-s-SpfD!Ru&!#0*#`LMza{olq!ss_DDxIfmyX{A zu5T&^++Xh_I@dV=@(sHc>;z3GRpogpq9U1U(G)L~(xcHbKGc*Jd!n!d$h^C?#%r4Z zJNpQWEvp3KYv5H=VIUQ8!{e!(&OCU)B$AbLR_U?OI3e4Uvg6ejx6+m&zlfb(ebB0P zj3D2%7v(f}EEiop?ch*~Ukv!8jbw=_vx&u#?BIsucQ22>b3}wBhr8pn84gW2Xi~cz zVd1ZAUt;DT(|~V-J@w(YZGCr^B0FWCUqjEY*COsl7X!?;(fRcqG3DU+Afwc)G11jY z(W08m)t^S}s%tuMD3z08^LfMCwX0G`OZy$70lU|?O#|rd$WnVeTH;!}{AezK4kN7JfZt4Qrv@{$fkpFuqs3|Gcf@LWCfQDgqPvs9g zDK%R2P!O>2r46}3SW&(UKKl0U!omcA znuXsA{!?E!p!`{inYf6rqENT^0-li2YR;*#8H13aB3T&IFr9PSC9N$L_YaB6Wkch4 zX!Tb=33ZteHQQjWpvd)o50ROP-Jgu^0dMccQ z>`T-4$9bqs!(({S`NJRef%=mL6x zjh(L^OQ*dw;gz~;VAu2g)-TPq@m@1`qaTjI=c1+U=Zh{W=e~C{htvF}YooRUfCtyv zhk&$wAv<5rpdyY+%_FW$s@8zCU&kfeAu62*3U}M|Lk3&-mT1HM12_>?euJJla~w{f z_S&J5(&K+UsF=p64Xo6!7Zqq-20;B+pkAv0VB-@M_(&xF2bA3HVNlYLkdgu)Fe+Nu zJ9zxcrM;6?8)$DrC|@IOK{?koGW4d_5=@J3fy6?|g%z$qJgAJ#&r*AuWpDd?FY0di z=kUa;i_n4l-Na_w{;zDy{k5hn!2oK6jBoa;(V&768{3U=xi)DpcXdLHfvxsZe+iio zUM_*FOe&G}nWv4JNNlUh&HLa6iq^Ap*kRjzu3x{bvEuHZ=D}LkC=5lNz3KY{ewgYu zxrMmgo7Vi%CSm4p^S_t7s@ZmIX>U|HD%)I1x$CDH-ASS7uxYmT-}HqQ!ZNiS4gI|; zmdOTM_gtr(G>>ilojsdR9|4ymD}e+16k|Ryeub!bOCCU4!zXsqHeo@d-N*;q^w3HvB;cNAs784;9E* zo$Ob}@HxMT^s+VSp8JY4jx;6j1EXH~ee=>G*JUDr!POBCT93T~vU=L4EOBS;x89*=`lPZq_P!Z0;?O?-JV~;c$dSsP)@|)|y_p1>GEge^{Ei#bf?Rj1;h%Ea~B@yt; zi?;m_lJ`;|R1=?w#|f^75(2NBqQYNX%EpQFbh@#42MC;3C&^dhSVFUj(1&Xdw4KLX zvSk{`7)jB9ig<5%r(!-LZ2~q5=jPI}p$Y-a^5Qwro1;@Vp$6GQ{cU9eG;Z;$`UeWC)~o60PQqj+k#y04)k!HR+b~>7bhNB(0vBDX@jShwWNk09`tjnBp{j zYJ83a>`A4i-2&7@$RzZjy=)_TxG;lhuzVja%a_Tf;eM8(1F#F76D2{mxfpX8)W^C2 zL8b;d7RhzY>{QjqKqC&QzVxs9pU;X$4Q2`762z}-#o81 zdW?OnQu+oZ+>F{|?C?GkX!5#sDIDlAvAAW7S1bU=MQkV%H)(8NZytb84Y^nOM6{Nh zz^b6P=^)(BQ+?kslfdK4)7V}}?|yO@~?M-YTlQ z)Kr1skOyQH&BF~lmLg*aVQ8mHCVxhnPYttc#=RE8^^dVm zf7vI|VA%GF3A2tC+dg1P$pt4ZbQbwRJYmka^`}iYs86!Q@OOqrmy13kqd7fc?UO3+ zHmvx?2SdV*crlhbH%~!1NpWy0?iTD>>EFe|dW8L7HoK8s)m%H+f7ky{6aTe|8&4Ml zyzDm^LF50$df@_uDQ7`ff;9A}7V6Ur%AN9nk$9P58LBPuuY@BhKTC?LM6&-gM}lL>nlvVW1I>sUa%lz9LWJ-YQ%Z-Li+TO6X=}qs9faEENgU^FI;b#`K z)b2Bf1~?P8b>pJ&l6Sn;Prus*tGdY$sTb$BP@tK7@Sy->=ajOM5&E{$KKjs*biBny zT*PsF%{6N|a+rmUax_9cQ8e|Y^7g`)O*hoR;wRACLQHD$vHs!v=|QBgd;P#L`-cgFF>-5Xhn(kYPtxU^ji`1jsbYf}Z}HHEPb zpDs&X0Rz>~PTXIuG2rE8(9~ho-5wTAUw)Fzj}uR^ZNblpcyDz>e>we+6@el8ZOdbL@$Wj48N)xFY#4unpFLcD_nBSTf#C*r(9~-J819k ze^bR8Yv)a7L0A$*Vq_8&kH#il`)d1h#ZFAXurnuun8;@=tOcs6>t7uvvO=VSzx+0c zS*~4(bIt0sEJ};DqM?)HD#_{jNaPNp?qQ^jGRvoxvf1r7D5+1B92;+dT=zB)x+M3= z*7i?+%GMNPLH)KOI#hlVGqRSL_{a3d6#i&_u(FNYlIi)kTt10iiEsW%@~=x@RUU5G zwH1W{p9G4PFkLdY@CiS4BFeWckF#Enk!>resW9G*IC_;uE7GEA^5>%WyRZZBU39jV zkUB}p!L=%}o3)8@f0j`fmI|dp_>?B|^W8L-nY(tS%DK$4jSq(RpKN$__05vAiV)D) zeyQKZAVZO;fT)y(#ln&tZA_E+i!Tny);>y`EM;3@x~>pkya~A zgBTIH)0hW5Wy^auR`!}|<+peu0q||&OW}oM%-2 z8wu5X0a{!X)&fjnV2>xx+WDTO2ywka7V%dTOsVRssxRdmuLj;{W-fVm$`*80cHG3y z9U46D!UL0lkM{%eY;3eg-{df^h$(+;Y5avn*Hefp1%(}j{gFLl`^4XUOSJ=IL1Jx( zmY6O~4?o99mW<90^wu^@D-BisP1T&(&F+K_8uV~O6R*V{`E;PXyeTzTGfq15s}_PB zjCFbCuCvUrkIjG3wWWK^7|bjZVm2a6s8Sbv>*+r`2#;~p9w&b)=7KBQiTvPDO3-X~ z;IaLxd)k#`p-B~1IYeakJe(EcT(5vg{jNQlQS6J<(D#?!zf7svOOhq{WsVrSPII9~ zq2)OxZ7*1(8HU1I7%1F$iLEwn)2MSH5+2o6L;2Bc5?5=16cvzVN)bahr7iX9`t4ntXwNzU<;cbc ztsRRU50&?_bL3{aKs+SH#mkGceWb?InveMAuvFo31sd3Q-Er>!cs3U}2n9Z5tr?xX zxE>3ojAn6D`-kzCpMQVh(J^@0+C-vf6o+ui%VHfj`y}b3^lJ}Wl`pO$rfHlA)O~RC z-#oCcYh`lWWY>ELvuw7RgxK;iouT-STcktn9UQ8YLTa_m8l4fUGu?7e#d3?+Wtt9& zbT43~cHn?EiBxmz0<8O>zCKB=?b^CJ#0s~`+#Y|!=!%COW<~KmAY|})sCDP;EHTl* zhQ=hcwz&B$S6-Fb9!D*Gu%u}KH9@+^S0y*L`%=G-9o5|?%lP1x1um%?I mfuCVyfOBc8korzS;6TUl8-)UF*$!upIk zKQbxnej^c#h(HMW42WT(tr%>=5PF$cvk!^tLhkt2H)Yvp3&01gD2JQ=2&2F1J>dOL z(V1>w!U}?F{Xc~dIFs0b?DTD~f1;&?DEzX6{>)YwvFEKI>|OX$rnybDCvWAIr;fIP z`7wUG(#b895HKpfRjcZvQ+ji8g|XEiGCVF~KP70Lmz=-vOW{=2j3h37&~hyqGfRPq!tAT3&k~|)zvg&sXiW&AsK&+m*cD$qtX>`7@BIN+6g~#P(lF+uY z`JCISDv%XYUFQ1O9ngpo+*2jiTgtzCL`^Wq?Ncri^2pv1hugA$8YfM2QkvGWv%Lyw z^pK09ID5_gSBi{S+D#l=34cr%6)-;0`1o&}J#GUZjQp-ulAQd`BvL69t`^y@@bPmw z>x3dMvI#_Qf{xaa!NS^{h}HaEX(CR#JA z=Fg(v%pNzXl(|lH*SNz{nIJY1dv$GXC{riC9}igth)hb5zKYapV4*=lh0r>B@MJ}m zYLfzlJxpK*zwqWTlpLnu~{gslM7F zvr|DOW)3&7oJsFQ~p>1?iT{8WPgEgqYdXpy1)_8sqx<`XcmavZKc1px-okct&TC2Wof( z+`B?4`Lo}Rb!bcJ7xecLE5yKKKbIb_RBye%$xxFTg3&?nu^kAn_%Fja9lhg!Iu^@Y zh`Q-ngX_6}pCiB@e7{>YWC%~JQ?&p%ggT0a{N&EibCOSyP>ex|W9D8puA2|z2G~oo z=*xZ6e&Ml}mq(e*o{+LlhBJbF*^lyLQ$Y(Ay~34GakJoMCz4xwAE#zR%kL>_9h+zAxRKzoB7F|{%*wd*`_7kMB}1NQZ5Y_ zcKt*RC+;!)K*Yle;q{A&PD$dfVB{kTxS%p1W z1&i4|!k}9=Y-LuCTEhfpe3E)Z?(%osdWn`VXt`8@P1ri+mscwn%j#Stv$uvv_BGY) zF;)mdb}goyMA-KpxPsW|+Qj!XAoe6?qrNX}2#}vX-@Cf{ZHAw+L)oBPhlkH}7SeY| zn=+2-8O-&X7+fO?)U7(NDoTJY7-)_8>$hG_;+T z{A#aHFxBEcC7z1xw~a)m7*>`qu4%MURg@GEZR6kqaXq{os}vl^*u^bf>~bWz&0A{C zZ>pr@TNb0M)8qP~KXBJIf~Yz6^LQ60-uY0?P1otPJeFa=@~{;Yj_x{aS<|? ziwM+!bJ&`4<#bew$UR-50}sHE;0D!xsgUdr_icRPDK}a>G)adHsbYKM17CoC`<&8L z@)stAkbwZ76ITX<>I(h6j!G(-dj#k@vPPg^g6{uq^KF8fN0v4@s=Pd1drEo=PU**9 zd))F`_{CvDgeIQ4f#Kof0xS${X7VK9Z&92&8^a7^+hAyv!e*B-BqA4Y`d24gaY zf0eua;99==j9+Ln#7X;|mh0^y-BOldQQ?I8XSN^V<|8`Mq--lO0~#L8B^p%C3R;c^ zABJdPkZ$gg!Q?6DIs$|7;DzZLT_4>FScDhxMYrKh_eQ?vOPTE$fXMBg+=KPtWEumn z%pw1gZh0Z`NNRxlz$|}3%c^d}67R0g5T)Az{Km^`6=_uCpM`?o znsW5D*nv1gxUUKQRB`?^u*@3BXwI8Fvz%?juVt|m8X{6kW}#_kEzQ#LaT}a$9N=Bi zGnh0wBVtQ@LbXLg!m9lHy8y$|yhh%$IYj&$`=ax&1m$ zpX^8D8DDVoK-Gy7WM@dAs%n#cF%IW(k@9T6HZ%|}R)CawRWF^@(aU}V4 z()}q$PA3?SycT)sgCtcTCY~{3kzyzpM)=$rUiV5H$uaDUob8N;8&!4=aDR8}OGKXp z(HM3~vXZ*D%I>X}u+TR(p*cW3YoiK@`BwR z_4+nw8*4sKnTL>^$yU%wQ{e>Z#q%!`@Z6C~nUISPB3gDHcD}+3ib{e&>vHt*g>aG7 zHt3@o4oozQJ?O`f2x1X-{GwqIgX&1e7l@UEM1ZnN{mc^8$+;U+HQ46D(Eg0D`o4m{n?>$uj^1C$qn+Ha49*I2w00012@|wvW z004xG#2x?u0D!Se*k;%v1SYee(fxHk#{~ccZ|KBc{y4Au3C7sNbc|vsiXhTOXpPQ)(G)N2qlOvnUD!s-SdjJ3cxZ3B%>O?=!&4nGn zESTg2+|4h}r=|LsBe|VA2UB&v~-%<)r({q5_tNMvw{pZD+5_Uw- z%HF^0&x^H7%b%6K*VkFDUmOLe=~+K1y5qd89+N9!M`rps&HDBMI zRlVPK1*Ov;ZkianYQK#7{Lxw8un8=$B%5@3KkC$b@r$Fo+^g+X?fepLe(f%c@l{Lq!W57RETWGSZhd8;NVZ8it$+wH=Q^HthOQl##Bx3e3UF0a2`Dw)#VrMp_a zyW-n!RZ?My^^J4;Vs=C|Nj0;nuUsj;n&_#osojUY`a{8S6^r`x>l^ORE8AU^Ke)T0 zML9CpdVgps+x0Aeyd+hfiq2&#Ww|$^#uo#iEEdoH&#Zr#t;2G5lV+tlXW4aF@}zuX$Ek6WfT`_8e^mZOAi zs^GXv*{(M0eetx)O4t$K^0ysRZ`u_tZ`~cJPuUI6@~henyS~fX6`ba!@$|Rr?3c~D z>AOFp(KY?*e?HL3$w^OnXFsPbSIb+2U#obPM_Z0kw(Glne(gFoFaH0DXRUwv=0&`I z{l%;NI?Elk&5Qqkxiwhl6=&!8z3sT3`?FK;bsQG#sNQxep7qk@$Kk*G;_cTTe|MZI z+tu>cU_ZR9zx(x@?|vKQ`a0#E^=-fZQ2i3ElD3Vdf%2#vZC{)}w`E_e zU7}Ueipu(_5m&lZ)V8rUu*}QKhi$iQtod$-UwNnfN~^4GBYv&*dBt1l+BbgX*NMk( zKX=FZQzPcP+?&LCn;9Sc`h(Um4P&vGHXr;zUw!>I#VynGK`UjsDmd=T8;oq-9H{Rv z3z}D~owAhW>Rh(xw)k!1I9(^sY2X+Cn^vXghw0T{rg^)&^=H_FkZ6@uF>FO!jw*&d zaMFv)k)+U1hMhS2#NR#v+(;1ir@LpZ$GD7MeSWA_9o%Fa@qduj@Rqj%Jpw@86ST5 z;ZTV^NqYSFv7S76GRk-WKoW^PV4C?Q1g}c$`Lzqe`|rQ6Pd@o1@b#dr`{B*&fnrh~ z+$JRs%!YgS?rC##Q(t`XMcAPL2-&n>Uv`gn!wvzLV2nM?1Wq)wXJKhUrD{nBM+aet z61dD!ChQP^vFUzu>paA9ur}V<(9ZFW_73(!i{Uof&2zmD%j?PDW@zQOdVBcVL%maa zN5A{%cVUNu0Py?)U{cKe=A+*X-MD0y^!tx~Kf-XP11E7Hc<&v(CrSG2SAPvT5&*Mk z{lU6E{oAL?=CWaj0*nRsuj99Sw5wnI*Du)j0DwTvy~>5=_{A|7DgXcg0PwJr-O+>8 z17)(joeuyA#w*PYesp}Ku>e4i_2hckApn?B*@LXo>%mWC1ONa41nHF$djJrW z+c35sfbi_)_LSO4g&hWf8JEds^zgNZVTS<#m|-OL00000AOJi2?N4z500;_+Jpcdz z00_v#6mRSS0D?ne4*&q%I@ug!>;VW~CY#Ytb|>sG001-Wl@fdTUT#mRbtcdN5Ufl#qo4oh&%+J_05GHe Y4Hrst`;Yb1@c;k-07*qoM6N<$f}Pq9i2wiq diff --git a/planning/obstacle_avoidance_planner/media/bounds_line.png b/planning/obstacle_avoidance_planner/media/bounds_line.png deleted file mode 100644 index 532d572c3d845ad0ecbc414542bbc554561a3690..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 113616 zcmZs?cRZZi_CKygFVTW%A!;IeuL;2sEyC!%hS7WPK@g%u?-9L48J&n8jBc3Gi8jXQ zgHe9Yx%ZrVzrXugf6P43^M37T?X}lhd#}CrdOp6@P$nUKOo)MjL89`<>vtF!xak-e zn5y`=_fLchXQ20gI3DsUI{5b#h;JQpe^2MBsPC!mV(aN+;ckOr=j`HS^TNZ*-Nwe* zGa~;&)7xu+VmCGRqCb2?OH^hRW+#I=(skODa{?dcoT$q{KFO?|L`lVD;ir7zA-3{||N z9%joNW>|jM%Q$|tPU`m5v|}`#(rjx3sqGsdL+>N*6EpPlvj5IlC{qoK)&2K1JmjVp z^CGVMB2Lx$W6VEf%zj=^|Ae)6@DsgQiw|(*u8$e`ICzGqwy;-=f&0K z&VckKV)B2eHT*9K4-YT!`e^Wfq5trU8T!C&Ownp7d$sd4At8aco$kN7srVOku-rM) z8%@UdKhQty$jOt4v|HHz(~^~yro>fcGq%-j0~d9$)V^=~AC5!R-~NOo#Kl)P66L!7 z2l_7wU-PQ1B@a;_PbxFJd3t&-j6M8^WzzG%Aa~S(36pG~@Bcvm;TIEQobi)A>G|fs zC;G+vajnm0`A(csvxkI4p>)+jc`H~UnkLakZdhl(gJKujbO%hYrxt*Nu z{btvB2fc=kEbxS)Pm{5lG?(LFBI>dFPq^L(w*6nebpPJ;rBE@g8`GO==s}4p5!JZI z$5$JE%f%Q|i9sh9*|)6_y}O-V$fDn?4Ml9ZyVC7umBPY*q!@w?uM(s$;gkEhh5XFN zINZLzWN+R)ljNHS(CyE^J6tb>o#1rvLG#pMP@hRJ$Ec8TLZbY^>1VXvyXJ@XEbLrm zRDa8HS#s}Yej`CfKiU0GI{#SR3SPf@>nQX-fOlyuK;MHoNv881ba z6VWoSlw$xT>>r1#O}jVn=Ed%{l|${|Ux}CZvybBIW!G`3;%zYjV|cdk=#FUb52Rux zwwZ0rq#fXZ#H2WgPinFJ-}2z!>(UQ?-wX02hz;$n6R!KYOEccPB^eC9cb_hb6yjx_ zcEIUJg1vEFHKN=Xlz;U+Ni69vuKCBM*K{G?e|cb%%Mbp~LfwMnIdXx>vpch!xJIiT zuf|<_r@9cAqwb^qXFtZgWq`RifeQ^<5V`Bhlf?1thoV`aBEb$!r+>YE z;_t2QY|T*JtFgak_;pl zSOu%-JAp3A=sK~RUw^%lKam6aOO_SyFF(hlP6nchtmPKmuk()mJHF-G9{LNEIR+NJ z)%ep^Yw+)V*hS+0=blzb$0>as1A><~6u10L64RRyBMx_4jq4)~ED%MAkpG~W?+U0X z;PP8g;muO~U>nMN`H0401ccf$gI1p~hB$zj;1Q^wnO+%F(jG>d!8RZbJl{i98m#*} zQ%%j7UPkrcM#mXRX;7;`s$=)))Zx)xQ|nBefLxFW+>f5l>S9Cg){2yjOkkkSn0EmN z>ortOv$_6lcFW$duwS3e&3eB`{i(CK882oc zK1$xsij7l_4wQNo%BDnS9KCeHNx!zTCCL=*FlUQnE4_) zUp)9m`An$!sFUnw&dCY3eUh+SD=R^tc6(O9dVJ@rRB+*P3-H}*y<0KUdU7e8ZSni= zSgx76pwLPA{avUWdWE-}^+fZIv)f_(&hHXIPJRh`+roDI=wHjqG2(mm(~AzswwJg| zK*x}DE&Qk+6l8!1nRW7?w687d~m?jFEz{;D!p_X zV1za7RJ#JKWE!t3MKB7RxX#>W)<9e@{2%g?gYJSP%SIOiktuv*mvHk9zieQTuTYhG z2y!BSsV3x2K$oi>1i6+HZR;e}YZH9@+eg?w1nIzuwF){L}c)Ij;#YLcsZE?y7&PcGC+sw;Q+&cN!o6_aJ01 zZ`m~80h$qtrJb?oUHh_~zffHt&$>n%xBWtV6HI5@Mm@l&spXC!sT*^h5OCz2dMufLJoej9Tb%0B<++(W3rNI zW9rs&YJ4KiPUT5Skz)>j}iJH0beykkhTT_3C#6 zsc2?dQajXmEuV5IYTe%p%y%q)Xuk{Az>ytpj<#Vg35K7l2W6Z70Eq@2A8d)8888PQ zogSRWRbj7kMjM^q0DJS9OdT)f0y>rxn1k9RZLI-`r*R{;XRgBx0qGY@N zfcx1T3pJ1nSlaz(grL-EW$i5uQhBNzSBmzKEa z9#?&zKV~!*kEC++`gFb39RfTK727iI24mZro?P+40Lx-YM83%9E3&5U3hQyvKI4Yt z6VpGN<@}fHkOL=TcGLXx8|cbXlOZ4SC5eDEk4nN7k^3m~FWPkP5MZoux54o=F#&wN z^0{0`^3dH4`E;RqlYo-#IZn)#3Tgr8H=8uH@mFZGW<9r1uVmBsgzOkcx5*znt#f{+ zfHg>gRL94T{u+RO9ZdKKtg)E;N|%!3$XDsN19fbrRA29PqDr#Qj0J%i&nT$)Wp} za+LM0W+r2=^|)mXJXa95+-%d{f2P4ySXC=%HH1;dmU7D=NhGp)5E=+&XviRgtcX6<1HqWJ|J}|SdS!JDe zn_=Lk&QkwENme=fWHMdnD5Q12WCVUFN_OIH0PEhrd6e{A{hzSNxUIQ*e$xqvgqi!Q z+2!AS-hqd_8Ne>$VpZ2J68|ZI_tH2dx~yxG*M^^VZ-?9_@GPn?0DcnI9E{hc$m?I@ zsiBDT=kir8w@D_kzVq)m_IS$FhqF^Y)Ju|Sg~|XA7?vG#aDfRS=DGVCCHl+mo`xQgY z;qqijE^{ZrTWN{T0(ZYr3rF1=UxME-46@nFGjNJSa8yP2Dbe)iqfj$fA_u7u#&#BW zFPUlwmDiheI<0KSX>B7WOm1fb$&c>cJ*o0(!As>$uU3crYRfeDYrmhlyJSP7l*W>r z8XSFYYBS4r1lVAtWxN3_1bZ}%D0Vj_xH55M_ah?u(nEAFgj|;4YTWVKNn<1pwhcRP z1|481YZ{}aUH!4Z4-S@(Uak&P4!RROn#Lus@pHV3w>P2}z15e=8nX`;F?)a8aDyDZ z9_wK7#s942C6vfK+J3pM2Pf<@H~=@b*=slFxacl530>5Iu6rUOd*Th18+62)TO|_9 zOoVd%I1vH~gPHwwaX#((Ry|^aE0)<6Q61-Zzz z2<62VzfLpWivxdwR0CX=Iv#1Hni8VNi78pS^qFexWmUd&yg_aR|8)p{rS*vUJaZ|= z{8we1pL64$4T0^|3lTJOJFLg={xjc5M<4ek^+}0m6HD&GG$!1;ck9HoC@C^xj{ErC z@owsz2NGd6q0&ETVR(cr7qbDOC~6FrnbcW|?karSu%+_Dt^o`H=6w9aERFMLC|W)9 zu?nL(bNn8mtjJ(l>|)AkIhVW-UA1D%!&ztJN>+L`#U zT_GUf41hF0hMy{IF8UiOm`k`MXwnRL;{A&J(aV?ZS8YG1d6>h58YWmOJZoZ)jOD_z zBX&!sP$r*~AjT!i$%A?`R(fp1%YtN!Dje{`+G5L|wY%|T>nS>apF17wjeePR(d4Iq zU%cy(B|<$A+QdHcAYNIb`{KjK!BQ-n26_XE7_n`N6IePQg$DGHnGq*^K-od4p`oR6 ziDPCadWfzMTW&3g;Ds}Ir_?#F2N;xvnig-&H-IpAZ=FmbT+AsR#0vziZg%1!%b$;v zInU|X%;E}S#+7y#Nf(0(YRuC<*fKE>y&2gaBxqWA`khY9n_*5#93GRyPDU`NPmF8F z=tiYYt{t86p2Ff&FOEWtk}qWv$J3lRey;>E0^Zoe*JHOCwv1zED}kh01*HqH6m#94 z@zpG$fww_+;Nd3V=t;d?*V5TaWXG6$_k7Evy*B5>a&}+M5Xp_ydM=fvJqBG9R!Q-I zrEC_QM+O>)V?Me`+wrV;EUSAIq44ikt@`yDe1{A1Eu)z8-#_zadGXl|?r%z1ZMZ>} z3;j>&#Dc(r`bCyeag@PpPg&vO1?x-xVKLI#e{VQ1bz7?5R5Z6HudCao1-uq@&ZB8p zkAD8c{tbh&I1sJjkiw~s2TZH-Y7@iMj2C&d&2UB;qpdnbF|eCD#E#KoDZf5AFF8O? z*@_?Eqf0&@Rps>ALyWZ$7%iipguZm=+Yx{8-VaE zp3TQk*du$X^*k{Yb>*BRLLJ=Yzj8L8*hy5zr2KH#O|ns4Cy%H|dWj!)B&!dkMaZ}1 zzqN~Eb2Di`|G>>MAIMz0B~9S|oEvrP>xuLl4Dyp-Suo+X+WTrGU4EYV1(mU1!e-xh zJVV(!d*x`5%qNG0P(l+9BD%@e6mQ#MI9oaF}E1d_!R4 zzz$Stak+qBD90Mw3;`MJUB{)(9HjZMnD6G^Qg6!0% zNwL2sVOkLc$Je4V4_?zcth0S+(*1CoMW^ej16b%FbBQC84+9` zYS16`MFu>W!>QjF2ngVI%i*UJ8A(_47@IqDxNGy4(0b(eOWz=db+yyef@s$sa2cTI=-HUbA7U>M-bADjD~* zmV6!N_GyWc>SLTrWJX4d#=;-fHSqH#7i+Kre&a@$nb4z)itLco?=tsbA> z%_MZVvVAql`83qYJ`>i*5kEzqX!qcxgQMn=y12Dqj#sh$n?=#Zg>&?ff~hXUi|5|n z-Z92#lZ8Ax$|ow*TkXXBU51R1^Lb9(F3C)CW|&+3@gidcm~ z`!}^pa!mzYJUfUW4d0H$Eyq$lMJ*DmD)G>U-m{VV5$FwVEBBlMmPqg;fydv(x3Atl zo6sSh2f(Z++$c?BIP?WS7e6`-qQ?8-xpJmVZuJMnbYu0BrFJXkbS_7Ma7p>ISjuT1 zFwEN)MmjCF@Lhd%UZd9&NtYvX@eF|)#JV^a2bB+5V}VE(Sz&-@O;2-^1oIKALEy7q zZr%ifP1hEh=g01(W# z;YlxLFpZcT63oBP<+7>|Rsy{rT8o?+I=y}T6B+>6g$-s+=yvPaEa;fc7FMen0tP%G zK_TY~w8TJ~L)o|JwrZS8v5G>hFpe2QmWLgj2~fDXFru;x9~TLn!Y>*+zn|@&CKxk& zUbg*|h^qxo`O+59@;uOq3pP}v1ZOyWWC7-(C2(81h-_)nMjq2|jXm^cITZVinLj4D z&czXnHRrFS^zdW5q%&`&SK3&ppp(Q1k)f|1R?3YJxooxt@_Lxzd)-x`O-n zZl$Jdgp`3d0DXKl%c*V$6#tmTl51<_DA9wC-FqdUF&Mv&qphSi#aQ%}QOSFX_-KX% z_UMTj6~j$nR5`4$C#OG~LN6i?d#F!vE?eX^9gy7Y{Kimm804i3 z7z<2mUQ0HEn}=K+#!PluY#VmCbr)iV*7F=Sl~%kd*xd(#$yaC7`-{Kkv+3)nV|K&VB2ahSabHWI-(UmC+h(Bz+06PJzdcs-+LaCS(`5%aXoL}u zbP3&f{AAxbk_^&>Xvqzfu+3UzGs95|kobC(D>{k^(tvP&hb5fTgx*|YD1E7z`dv)($n&{Vbd4}Z6ieg22Gauyrg z*9~VGdRk(o=vH7A-TKtr4wn~bPK;92)!NMWs)Nehl9PjmcJ+@A&s=bf*5eKfW zZ-w$TTfD1(8jf2oGnPy+*2uoEaL~-^(}yWqhKVPrqxy>+d%(9q~^vr2i)t9`p{o?d8R|`PhlW^oj zt=*Mzw*Ackn`AHix8-+TYa9MlU@hzms8HWTEPr>>RKp-OUS8?oh0jl#`E^?0n*o)8 z8;cl)@H01Ntjh^wSmDhI)MOCKU;CVN4}0;|;k-!%Liu!*8e}+oSnM3=j`zU^COd6$ z$ZQ49j%!+Vn|AF6=L1{DN~loSi6C>xr|~D!YJW^evc(^L=%F!J^SDco?I6HT zjy30zNi0ltZ~{iDSC6;)~K_is4i<#nLeaWxy(922sbs8@f41QNdn!Ew!y^MR&z zX^v8>on{XRvroKx)%=j(g{cK<+WDpn+Bjn^*IUZD_I_powu6Oo4C^eM=)uq}U-7u= zY_F1b>XNeg&b9gOBy&!WbpkaPVG>@r#AGn7j#5}Ac>XSURQ6?No&KVEGRMOw>PnRf z>k9k;wXVbXJ3a#%-fS9L;aNBHz=qmcpT^|E|7 zJHeN$enOoDz@l>oDg2EsS=9)yagFUt2yXq)x7H7|HiyzgPA(b5@<6jzHRVZaqhl@ns$ zzs=QY0LmxKxo%4{m(aSZvKlttoOxxX1`2Gx!qY+P?H zZm=HznKJ$>U3C1Sv6^zLVqvknva7q+(92Q(c2P^tK|VG~&RRHoT_|IVvPkk<4KUg9 zO|Xs-QzBhAuso4rE%(9fEy1K+bNOC!t)0+7yMWCDmG2NwM-A0IUzOcAmP%BKi5OSr z{f4S^zbn^v9Vb^5hB3Uj1jP41ra$Q7JjT!_AErNJ2Ex8WAE+;R&s8RZyWi#MhD~?d zjT(MQ7U`-D-$B&|G0Fdkw*5oSDjP%+k)&}Lw#wodMN$GE6{GdgXz#sppCDEd&Aky- ziFse4s@uDWnIZV|3Ws>Hi}Iuxq0l^M>HWU4Cu^dwJ+P??duj{aPkP>y?O1mUF#nuO zt0WM)!!q!q9Et|D^qE%@_!%fj^q&-G9`Fq4AKN@(jHs2d*iQHLnIW@>0PKjpyU5ns zLI)#jl5HCfEC6PnTkpN?tq;f0g(D##J&pObtlnpJK&;T0REj}f(FB#xn5?oMVrCVP zX93%@AIZ}Ok~$b~{=gw_0F99k^wC33T|*ZAedjfRymij|t?my8Xw5Yke!qsKSsRE2 zjad2YgK%U@%peOkbH>(JX^5H+%3kV zErc3o!{p2Yw&Gy>YNe?*{l3DiMvo%lcf?|{Y_V476mcii006ln`R`t{WHrjYHrt%O z886BqWw&^Nw6=;e`S;J5KNS}ADRbKhV-YV4+sTQJ6=WS*hodl~qbnRC&4kw!lw2T& z5sLz-+I%oWdq+k0GH8_Mimo>^v+ZF}%hFnv1^?)Kd?y>ofSo%vzZZ+nPPb6>7te{v zV>bqE0JV()MZPS@1(x>cr89#zo7HFvdX&cM;sDLoePp!1)UA26F#df3%Qle!(Jf?S z@Gg!0A?>FDec&a}8-CiUPWTV6^T4rU9xBmcBh`Phf>j2$Qxvyb98%|>Pkm#9as=;> zD>Q)T&gwBPv`PU2!+C3`l{wZ9A34(^xhGSC5<=2Eqyt{s+VV^*yW$@O$2UYx)keiM z47}5-t`Ie+PK`Wc>bH2Zk<uWx$P zZ?AZDB)4x4l<$^mkDBi|LMCd?Z=Vg!zv`~q{q-7ZUPSIU4)#n0HhZHrj9k*-EU+?M zcYN19p`RA7Iv023_n!SETtf(zn z?YRt4aw$=A)`m+Mm%I88OWYo#6@_IPv!(HJpz?~(O0!#2Vu?(RdW$gr3o*&fak0f) z#jOxGi^G+!Sb}+f6CbHAI&*2rIqnL#Q{C(mvt#zHpDNm z{ubfYD3`7rz)e)Od_(;0lWWq~ftQ2^rW9L)eT4&$;|A->umu40zeLgN0ylLfz-Vjz zFQUXBf9|>Yx->Lxh_uLpa4)wX>>#w9f39%&J;qhL+3sX?o@s`a!?PxE@4QSl6bfqK zwi%P>E9DQdq~;!8X1&iOf1wFO`}tk0+l~2MH!-gVqm@(5LR8K-AImaY)W>s~QD8LZ zq~ywSjHJaYS#{JNd42LqP#$nkPGDiQLcAzZ1UK?zq^f>UKi2*0%l41FsWl8g#;4bt3Cc)5~m1#k&9pk@I+B*33ZY${n#hDE;6 zs2Ez@EIiy*biC}j22KK=<;p2gN`H8@y|YJiuCDlKBASuWiUi~kkqj~{rB5ElQ2Y)p zafxV^bU47AsxDuC?ERp_0P6@UOPn51;;l6Dq{Bff9fk6d@RPnxdX6~`Hwf;AOXOinSoH;}-d67TMq$qgY2Fae zI#Ty&UHa*;-B`C-iG;Hol~A0OtyVm2;eoTj3snvqaErbm*z?}jPyVSV@x!bwQaGoF z&&UjpEy&rS8nBD{Q`bvZV=`Mz&b?7T=)GM&Wgci8f>;|$eVMt6*i}8Iu8WqfFCNC6 zGkD=He5LRa>a`K+J_nP1l>fB`X0%KZeHERE<}WLH(wDb87TzBS7Ju>a7f#EAxmEQK zpDIgweI!h2etcEXM;|B9Y)+(Y%%HSDS#`9Ta>d=ev17s#=ghOR%?eTivB&f7&$&Mx>z<^{$7TMcL=Qx=+?OfLG zd^K>=6m+lxqcHyK+N@t?!2y`Z9dxWh zONyrzF8bRl1V2jIAH)B`zOTjI=+4sFT4i`k>9$-J3O(Phwf&l;^ zHCErSJR|x!76uYV0g2468M-bcwwB1myS(GvoO*EfH1F=Wg7IPg?k{Ds-m*R25<{*Y z=QQ$utm?J(7*L$U4Px46I1#r^V&h-JcJ{CeCj7BBoNk1AwV8cir1sYd-low`y}~D_ zO=ThJ8dnR`L+q5 z#Wnt*b9)<-&JT(|_Zb?Yu(D#}K~ffF3I1?vA?rFoj$3^ybRP-!<+ox8ZY<8D>f>N1 zCHR<|+#-+=Q$Jd^VO5s>u&0zgQxzZ6QVD08SeuFtq9d6}YiAkHOdMbfjm@u#nDFO+ z2&39Npt;;~+;+vs*)9a(z!>m0prm(pA2cvKn01~QG*pDrEjF^@)OD4YU@9Qs7Q3oa zr-nfXO4kx=vv2h#t*ZOy0jrI=UJc&erCZ&@?_=qyBUu^MoS?I0?4t7nTPJJYZRd|N zS)`nwMORdWKaBawJDjj_$T-p?l{XvoF$-+3;31dVBnm<^h@z|-NX9c{iF?`z#wGK% zchL>wI))irLR47#)3`+HI5Pm0Nc$!%h!Bn<+4Dbysf@{zRhEus{)|U_Q8h9O68$7- zmk#{-Z8qqGsh~%Y0L|i#zt`vkNUOn%Ca*bJd#K?@s;fI<=H3OTNWcz5xJ%b_+_hK~ zlMz_JA`CMbgLi=?GnXRwQL620IVQHs@gJhNF;zWt2Klbuue=M~$e|F#wIPsH)`4c}A{Az=o;@kA567xsOeP2F|~zk9{vM zhnG~FJOSvj0}S4Nq4vwGT~aNtftTzx5Ead7Os$GL;T$c!Oytwwx`BLKIrZ7ep8pN3y?t@k;PU2d$DT*s2MW zJzrlH6C@eW=%mXm!|+y*mSs1j?cO~ymTL2{HGAE~{bv?g-luisDU->+3+haXKB(0W zRxdCgE_be&A6w%YDXSf0*AG&g*_kC@*A*;Fu`=HZcGMh=eUhvjNG{>NKb{pDxQg_2 zYuFvFv3#Swmh*dvQ2<@RmZ;HUc1N*Tq2P8uUP5IZdC5_ekmNVU>C&S-)@3RFLF%!BX3n0UOcH8?xryVIbv?wh-*g4{qVqUrMa#9-PuvNNqsMIO%uPSj{Ptr*RP1gDuo4-%G&j<~}nj$GfmQ zmAX$az#F(zfDfdaZQ<~hsV*9l;I=ap>s<@Z6WjNoUpJz)wSdEks;`w93spI^#+fA} z{Lz3vmd;w4@^by|SkYky0P);~BZRW$Q#+%4uZKHML^f9y-z@Uhd!f>rK@5)V?Rwxj z8v`;Q(dV&IEEBH&-J>8UXQKE#_wUlr-y3=ab1w*0CFGt+B#p-eX;7uTm3LyT`u^H` zDw5yicHWtQA!<22OeGV3o0HT-i%WRU$m2 zi@6Bvf5#LtQizOu@K-vNt(6Ll#GSVXp4}KgL;xn*%{?iIaH*^}6}&?yJ=)CxO@M(G zggTBV)aVA5zWu<2!_$q1$1D8!t?F(bcp8dc zK6bVo8nik-%HV8A$H#@cCAl4Lo}^1zu#T(zy+O^jZ>DCICxgzbWjn|CzWhTsrYPQ$Ji>sFDfW(_Lh%wPOfb z!9nnoUY3#yQDdVQ5I_U5Llj6y+^I{>k=e6*+2^&^4Bk7p8f zHZ)6;(5OpDBI7FaNq9RsgG_K=`}e|l*5k>TubtRaJlYd%D}Pqq|BLiS%UXsHj=T3%JYOAVVxkdI1!bjYS``p}R zj*7WF<(x#%td4l;Pc3WPy4ACBJagkH8%CB+WlDybc-?`RuXodVZYXU7CpCe(r~6Dh z52a-m9C>&x66M`=lKv-9*2mo25##+ z4H}w@uuVe`)z=(j8e6ruy}(9RumDOCR6s1WFg;7dAkHHJ%1hw$**J)C-u*7MG_UhE!(^W!pK%JAbF=8a@E1nkfiCf&0W&QEJqW5aq)RAjxXWs&#Kuc-SMqlYd)=k>$M=0jMqq$QyNT z!m}zWxMLZ%vz+{yGpMO$eSZ~|7q#WtuqAzP6uDl+|3jG)|8oMTPH`Q!mf+75>_7$~ z?25LZkJ#NztTZ*bPuMrQZ!|{_0-1>~Le8IhrxPV;+P2{3gL*^TN^-r-O~>8l$Zytb zRZ=34eAV#7q*g9Np?Fg$+0|f^24maTDM2}5xp>{{S!dSG&J6*9YJzg?vYp*$8L=Ha ze->XA!i~2}uTTH}h`=R-SI2*Q*yR{}glC++XuXGGq1Esk?Y&G-wHaPMV_b)0`aCQP z`jJMy=39!Gc#{q8#Q!B}J{2!5>n!$`vL6v78;5D?W{&-2IzQf3SV1{d7l{KbAfd`hC$q z#wjY)a3%fAg5!Yaino-v_h9?*xB<2BaxDfe0syOzIwLGTsi+1oY}Gkz$8XzjKT#H^ zM>#gy8%cp|UT+JRw-1iG2G~7M1+jB21&x4BJA1QAN*O+Pk-)IREjn}oR^XkQ=^p54 z+F6w?ncegFpXYwrZ#Y+?c<4twPx5HC>ICkdP!UE9)G#(#B&|W)a9M2i5ht#t>QZb= zprG&cD=y>fK|kmdQC=&gNSQfdmUlkgg|}B#GGP4<`vkyYA=zbp$NCi;E6IboHrds^ zD2I4e2w5ql`ovn6^J5lT2vLl1^?sngfr}o=w5qc`yy`&CPB4ympU>xa)-HlxK0Brc z5k)}lzmYA9FMfq)^MA}fIN{ZF=lw9RtXv?--ocR8b?+Wrj0x(tfAARyPOQKsK|)t7z^CZ@b@7^ zc8naOt)xcj9F_usZU=l06pN`Vws#j-sy=bnHIzt5UR(cI$;pY zU$vLVMG|&AA5P&=t8l~>Rv=PTiEMIPIbzJ4ieL_fADDEt-vysMzXol$5lRrb=lXy&TJ%3=$Wf1>4DR<>b*-6QFV!W;g@!X zo?yVfvcSeXR{UY;Q}RMlE7YJnapdrZ7vq!hv`yMrkQ76Kh5oP()g`ox1R}6}M4K|r zs6TyIUEv)yqQ5a0UUp7=ij<n<24D!FyQcrA7S&i6 zjh}~c5Pk-Rk2BxJUggmf9(_&PX<-g`5wK$As?}TS20D&euQ9IO^Il<#UrL7?bSM@j zvr9-6#d2-Mv8DDpY~ouc2x@yW-*wQNm8Ifv)cdQ8h&ZnKOeC~6Pxek?I<~&tSa5(s zkJ=YXSZs?Mhrs?06-H4Jj?H@`y29-hPMs;2WWeEM@hLHGSdovdu)3TRd}f09_pnd;CmVq>@XjJYIKE5?T@e%uHj^b&1p+0l>IALK_b^V;YL0y%DrP-@I z@?`Q!)C%Vt?XB*!0G+07XfIki_yWIPVz-BB7O`SiJ0za@B15`OImyNsX~471lkSmb zphVqYJe;}(TSyK*)?@JRZOUF*gTMbZ9=?|HY)ee;qV|ujYbgyBYC%HMa{G3i&$n1H z@4gOq$Y>`NJ9sql?~mM$qiE&YdJk@3fj;N3>nFEP&Iv98aZEzZWW&sUOyGp_#ObZz zH^mvbFLN=q)EK{5A8}7C3fbqfBv=_Upu8k{D{_R+7;w*v;QQ=o>lA}&@&(Bn*+E!; zCdkEBXPoefyj0_4H3|i8WOXm8#VF5|6WQN6|Hjl|SB(hRAu$=W*2^S^*4YJEHhHt* zt|hy@l-|K%7Rg1&^$Xx+t>N2C>JCo7H1Vr&5IOzQkj72<8Y3MHIEhvS^q|-U}!T z$}xnQ7Mp5hOJHgI%G=h@qnjPb&e+Cq zN}Cyy|MamYFh-9K%Fnu+=L1oI$jCgOtK=4q$XYwq@b1V0g^X3dXl`W+g?f~LY!EkB z`}Lv@;WKNkqL_Ko~f&cNhhs5?B%Oxq(F`Y|W?Upx1 z4$V5uNqh~mVh7>H{elKYTdpo%_a}c&?C}!K6tW2*in$4q4GDN*r^QISmU)D1n z3F5KvrngL`FS3f>U?}W_S9zN6vN>OP=`2F!f}-CUDG_Yl5L z=!r;g4;O}A)VTi3eN8*Hf z**)*9G6Lw4tT2<7&fmm@z4CC_lf@@xc?OBovrO z{)t0P;m1C+W!If7Bm^BDxjHO|rUoD+ZuadiB4E;8Crl8gpoKuw9{*BrUHJ=t)I_(z&*Qmt1sBX!?#NOYOw|jG_i-n%rBfN%uOJ%9+6qwxGA8fVp z|1RxJa`}!}+B_DeyLTWwWw~`9&O65D%g~OY%k>5{Pmq!XGiCBii4${&_422ml%-oQ z>AsmfQ0WDq118pEl8b9MLoFDUc4+n`k;-Zd%@6{qryb=(aa&B1Cwt@#dqe|Y$!pL~ zS428>!f}_gH%j1KyCC1zHCaO-I$>(|CQ(<6mJ=ohh?xgOihq!5Tq$f;K=DB-qCaQyq22g=En;IV=n!xD(FWKFVd-0^N6Y{5^} zAI^OJ#Ki2<+{w$tB@(l;I`HTV=L}$aa%K5>*}{rtwWYmx8=*LuC>2~>v`y@%9Eyi( z9_>C_#Ay({X>fv_!be^%o7R`@leaWO$`KAmbinG$mbHp#B zo(+7kArraOYikPR-vH9mkUMBn3`*B1QJp_d+6PpDB07*0wBfL+9N~+m}bO4I` ztW#{iq0ZXOo;O!b!FMzx>?2i|KAsZ!Liyu|0|K9{&Ig`4@-NbU+t(Plk=*vvuq1Bi zDB=-}?GN9)-8SdRjJB3sTZM}3TZi9tuGrmf5=i-J++NC2a8MQ9VapomrbQlF|&KAV(mPA-gVi9WoSg88Dh6L1Pfv z%X@D6%ijN2QHB-cvyQ?DxFlC*((pIS;;4tJUvm(W^9fq?v>TRAJhe08^$Dz&HPOFG zt-eRIzhKoW2sKvZsrPs%(g|YhY0(vR7jaw$|F}f^>qK{Et8VksLYNW^K**xL=K0`&+J=0TtC3Ndk)+FU5Kr zKaI5CREio|Y+J$KY~AH#7T-Nc`MVaNlt(q$T7~VAUqUaAOObePQ0$P>AAE|NEK`X` zCNa+vU4DjLDuzwaDek+liPt>!thws?o~T>Xpuh0}>yxNJ&tvRn=jj~VQPA&h%ZZvM zQW84tZpgdpj~YC=2hNI%G%7NFSvgd~i)E`#rx&Eh*2$R|B((~0Wa?lfbl{L9_vQ#^xl zQN%5RcUPU%6mNiIN39M^?Z#a&e@)=nsk>^Y)UH>wXKYbwV(=xwd;Ex$SmR`IP=uA# zjKAFYnS``-Uv_`7)<+{7fHf1;ol82sm4PxnJSl$CJM@b(&O7o!0mI#dcKL5qZQjqz zs52>i-BtEyZVL3M^wk6G&xT7r7Atb*!5p#%zU)N#z|V^HHopKj#L|#{6Cfb z5)eq=yFQjy22$FU>kQny&--2c#$q9jW#NQ@8^_N%W{pQxB{lOz#E<>k4>w0?m-y7= zrD2>FQ+D0dU&B2xQdZnt9RGU) z^9du%#oQW@IFI3^C)b5P=ORZM9hq{|9_Ybudw5+dMr@wQB&MLrd$w~#-HSXy8@nDU z>ix^^|Lp)~SRLBeq}^X`qot{kZlDYbc=E(@|CqdnMxL8McG31jD%tdWw*4h$!N8zM z<{U5Lm3R0X4k}+-@)B)eFS1RYCTfVM44*zz=>B4`Z_tciRrk>elmB_1Yw|V2_{rQ} zRZ~}zKoB)Y!XLk5KaSyE0(v(}>T4tB_P*_LL9MkB2Nm`0hF_#wI84|hC|)$FKfGYG z8D?$oo0Bz2OR{@l_&ktnag-yvumhi+W*&Qq0>|uj`n#`b?PZVKLuCroO3fH4P=rqC}VQ4&^CP z%FXL=;s1}VcM7aDY}N%k?4)C-;}vz(v2EM7*|BZgHdkz0E4Gb})v+df@A+rWnKO6m zVqHE}Z&f|`f^@C8&ptNT`>FT4Rb`F->iT-(jx9*6=FnyDh*Luzl+^1%;~ROmR9{ps zGG=s_N8LNyh=_~=f&c@M(xp%h8dK&6is45Y(%^)&bQp>DI$?jECjOW+<+g;A73y1R zZvhv&09dLLxr@+1T|1KOFRdx=eAwcvlwdh&jk53n5Mkor0ptVh4Ne@Om$9Md2KhB4KI~ z1)O4|B2tJ-sqV$P`V`OIlyuLblnTzXE-B^{1S>b5v$Myu4CxA3cfj&lTX|JI4MMyg zI;ll~ie}tgoYWE1K(qCijn3{ltSZ^Fl8O=lRlUEn!iqC#Y^dF$n}v(JMI#}ekaqGf z0lqIV98dzjJnX9N<$A(1zwj#pU|m~KIkktjp#!wxKV8=hSZ ze&x!Bl$oW^-_61Lv4+V|hntZ7&OFqc88EPMt!>OzC{$QQ1z;gp!@Q4?DS^Y*>JdSA z|AZXotTvZ{27&Pk)WNm3I7jd8=W4+DGg0y4aVyx0NqX8PVf@1K1mlI%g5hgQND&R@ zAO#J~vbjOCFFT{c6T3gLEb939P&U6jl}H9zv}EP}cvVFW8QEGrj!F7A?GctkcA$&J zwHMO#9p_Ehx8d)simRj6L7r}+@wB7FwY1*jqa+g2G-Pa$%X%072+O}2&6Be<$TzIp zb;&A9uowoy)tT7Yo=<-ldIaunh?6g!hG&}0x*w0%tE2L)D_T|ml3d2XTbJOhyY19i zGUSkLZ?9`8lxRpoxg2&-+uv`D$2zNXkbY39s;`78eDOdFcUt7ah3h=pT66Sv&ag4D zwTQJnR!iic+1z&;;<8B8WebW7Us6SLgbulGtvIP9jaKHUpNQI3gAfV09T|inua?R9 z@|M{AptE~cWC5>ZGwz+QH*h{#l_B)#KitG=TuUMg|6&`>qg5x3Zzz-Y5) z!wCTh!hrMjc6dipM2y~LsaqXkVMT)$*15R8okI^pUIzC$Q|98!*%r@r;^ zJaj+H5coa;20Dq}`96L}UVWl%eO$Ue-4T8UeQzL%SnafUEc5WS^NG4^fRpWc_T+xQ z+&23+`@NU$FKh`xF2?^4_=c`U|2;l;nSEw0-+LbDPTbv*xMY2Y$3i=ZA=-?Fjf_*I zG``fQjt$OoxFo2<*2OL~5s>2i7IS8x7E+~&Qm71D!5Tof>3?C|g3VbN(u#`1=q^h& zt$x%RlSvWkvpA!IyR04Nj5wzTc2z_Fmo6Mz0rtDo8Dw_>jq(V6`r%J-&c`H0g!CdR zS0zDZdpYJZMgRvId$nA8Q7c3+GB_Muu_TR!0T*JuLQ+~!GL?d4qM61#Eg1X=$+ylG zic!1~0Ekh0#E2f7*+x-PfU`fIwY_n+FN&KfC<%>18B8^e@rRf3N#Zf(Y`7>@E<4u< zZkkt!r&ZUI*Sav*Mo?pUsB!Xy<#9fjUi(j9+G6?ORN^#N{Yja9nI(bZr*_8evvHGb z5{n~S@4#YIQJCms${fCF_Lc1{vjmusz{%+lh|KxK$?0~JYA;(rAg6u0YR>!kwfkLr zfV^hOEIyeE*GH0}L@fogVB}GbZJUR7(czqlPRCzdnTZHLT0<9Wxbh#O0=?X_f1Cvk zw6Z;t-N9gl!XR>H%ts)ADAnI_@W3=Jtk+rZ6~T*DN-tv0cJnkG1=q;)sD)OfuNgBTpkVP6yM;rqsXe2m3TtY1r*Ck&6C6x=&MAgh(UWS$(DZPbC|`AzX4 zNW_l>n$%v}>jyfmB)LABUwG;Pw9FN&ubv3=57uic!Nvm#Ly7K2bbfp`TeiN4_4cOM zPGcW7q9ENLxVP&muQFFwDVNu$?3OG5#hQOZ#H_Y-#f!;87TAct$Lj~{fe1f^a@JQ= zw}8E@B6BQKcbYBcO;qBaRIgdKrJG^jH*(B@2;feY+sX94kl;FPW{pJ>g~8!1MJP|K zMZvn070=ex^BKy??PaQSE4t!T+J-jyl3*2sAf|%C!ox^vs-hUFfh9RHA?$LKHCFCv zyW(O61B_q=TWG;TZ9;CsmbE}ofq59V9k)Ows@ji6R{Ot6bFI~pPCVAYC@rqy36`|y zA3H88uC}I#GG&&zRTzdQ78`p!olT$_M~d5xR_sZ~Tkc<)!hWW%zPUPD35P#T%17_2 zEI{>@sm4l~`j%*NHp_K3jFK?^SFh&48|_qfS@k5S`BivOJ$qEn9>Q>IU)&VrBGFXr zPq;qwE6l)mp_uJ2bD7iFJM&>W@_Dvbf1@HjEabrMH%gnNIq8qRZNT=s&eZ26ANdF9 zGxg>Pn=Yo7E_beQMCQNY`v0s}UqAMfduwJopNfadTBnh6K99NE-w;pC`?R%d*{9l$ zH^`%<_WIDXQz@7mt`k5*981@IYxs7I zF@@Y9HObu-Rs-w;mY{qCb-WRgJbRr`m(Yb_O|&fC-E%5QgFP*cwSqW99WeQP8n)J4 zRB!;P;9qi8jB)r*MA<$zh6=wvs3|6&_veJxd?tVI_^|2zsQWfOUpcf~xDaKi{I ztAKF+GrXYQMc1)}pdsesu+XAI^xtSjajpK@-9)W>(}W=6V1=F z#Coh@`PHh7C#EPibZXYPWB2u}n_AT%8;fcUzB6HZvXq z&%sDTl5z(dv*ty~%9Hg~8xP<6XG<*Wbx+l?nrZrY%NEnhR>?obnIF0dlA__H@-U4W zISZ$vzab?uz?bS1?n4^#C0O!<4u1-kC!vq`&HWh16AMV5j;ql2ZAb0ZPv6bNgaUsgF?aZX>i+?0x=gYuGAHyctr4(CWGgL;QM+qzQq@UrA} zGLacU(?Sz|2Azykxik1MYv14Zmf%%8V2jP#B~Ohw^vvK&7i0f$>DcX>nf=%^Vv)rl zXVlp+LW7A}@34s#0;VW=%WZZ&|M@-NA&18!c7hNYiJbfGBo;RJ)7YrzYmAJ@(LVjZ z7ykb&K9*ki;)R*L$WotB+nJvb1vg28CUGmRawF)k8M{CLJIC~p5oTKA_|(j*ZPF03 zlnaIttj-XECV*=uLZJ;Le5o>+ps;Fuo1on6rN1fMR5ynFme6|R)hbG*f=;GsRnN?l zt6{3WkX&JZRn#O%*`@5+blXT1PWHQq3^uSfB+F{$tYUaVz_WDVC(0T}(s{#P$Nf~;0vL9&6 z8x@m9ZH`t-a$*MRmdb{}&FrTx^`!}7DxX#F6Oi$;_=E->$3yMzEy36OuaPa!TZc$)SLau?*xCskaOeAgA*Qj9u8y+&J)`$!yyIAl z7=w8gov=0J6L53uk-qv=Q~xy;d1r-flV3c>2eK2eS5z&d9+H3p=Z0;p<5ycF9_A7q zP0CxELJFzz0wOwxM#ez}o0)kJi8XT|bu!jUN_4ID7XrZxd2hW5N9tsxiPtSMjCc1c zbs9UOk{yaI8okZ&`7>InC8^PWoEWdLs;?b-5#%Rrc9P%+A1YroHcK$3K!$G-wbTux zxZL6>GdT6nf_;m82KOVn4lhijh+tP|sBTtajIj|ac5%>YaaUD+M@XJ4&jJXg1)&0u zAwBh(0FefDX$Glin9~62Qn!4{LYH#07qN^Ga~wvcMsXQ1w#>lF>Z58B5iQbn@_-Za z=35&J-JG%)=b4L5Rrj2u`4Kooq><>1I`^u+<_locX#HX0aN!yVS;|T{QC*2mr_FuC zO>ef6M&Vba%!OyUjg^q0!o`^2Uxaz5Hr=x{*GlmQypD@o;Hf^SzOED5#@)D|TopAL zj)JL(HvWEzR=Sg{RQ!)TTZF$W(5nBpx)$LDZu_0R2*DoN`1W|CZ7_5_Y5pItz2Mcm zB*m=UY*qU^hnbA;CK4#=5V!)!38b*Eub$+pIdL$QFmJyFcE3$CFGLuq=LGr!)DnGt@#zyG!AzVYlC z5fc%;@qMQgzT=3oVak;G%7^^xH25*?E6$o$+xiG?%X~QG`bq2R^Y)9q;aKg#;Oor! zf9}rV_FV3X*BrHnwh}CoHH=15Kr-xodkaCVf#NRu%s-xcOCj8T-%CGr) zlHWqISel#ENrZLrw5o!t03&s<`G$uO)Qru18EP(G^x#=p+h}Fz=T+Uxb!J18ESNmr z*vQD4LWyp1--(VMETZ9eXjx=6XUz27pypU>`EpNU%m6eD6QW+J^8^MD4G0tvXQT@+ z2-7zgIzbjg*`2XfmTfeQUZ4fHSs$)Wk}Y7YZH6r^pcswhmIizh^ zC4;ana!wt&Mwnz`yMoDH>EAs)S)I3G%g5_*Hz{+M0_(Y70e~ zxhqbO#(&Vcm2D`g8OtI!MG4EIQ-hLvAto57b{d%uD4`(U%3$2+f|=6%bu zhjvdw3+J?bm#l+M#{>-s6F@RL2U$9v?@eD|!9-Nd4?JJ2lq`7ZVvhjJm^QD=yEvkS z83@sKCHI7EC%X1#G}zVISDLxg=B^<|pq`@yF(xnrBoz198A%J6Z>EZnjZLN$O4wx` z5y@He`KnH>#OJ%X_Yy~P>3#0-5q(}=-7|)yeIA77n1||w3fRf35T&sDl^kAg^zIC< zakV=?e!K9#P?lc#WODJHf3-uk!e6QX@A>_I8X_H~?XRnwr7_p%%R{7V;nCG|NbjTF zSKePAOmiI(SxIf|W>m7A_T23ulF^WjbK*dh6l?I(7Nx}!7P;@|Wf0mUXUI};XE%~B znL_2LAkA1UdmYnCQ*}p8ZR}-7;FGvShQ5Twg1B;sjSYNxg(4X&WQvKujiKd&Bs<}hClF(5>IZH#nO%-h^3)xOIo(6F5InMa%>L!rez^d#=u&x>CiH>(KP)K zgXL@~4_~#^U1?ydnmhu1AHhD=#T8uythwvMn!Pc7I%;olqOhXgCV%Efd{-7p=9;~X z5-U%~NtetcSNE0f?dFe6?J?(NaQylba!YC7aPltX{=xA9oh(%1G^X z_U7Ie(rOz+vzH7$lwbYM1Z-K0Xk@TsM_?$!6Ctz7WjcFA?WvfkAZ3w zPX#pwDxZ=Zzt9{9|t@1H}p4`6!#aIG8hV$A1!W%I? zCzk&e|2I~{*#|sZ;oT#T<6i`u#rQlZ*9e0)^wBoadp~G?UP`-jN#eY?%|k{$kHy3Q zJd(>`29T(VfhE9cyv#fJkV3n{c$PK6sa3f@C6;Qwb9+B_Y+KV*5!Z{1q9|F&J(odD zM*#}pX0yE*uNPLC7RHC!Oi7LyrZ9uQ+1XoT%`w|p6~G`7a(b2g;a?V2a@PFnylj3k z{-bvh5JQlcY`egfIahsLH=#u-qL74MtU$0*Pc-gm{oQnxQj=em2HqYs4TdHot6rSa zX$#va_}3^9uNb{tnq32r1T)TrL!x`f`HY3uhi0_k81HJ1Ft#Bg zL92j#5&8|b3k=Z{^l7*~5o!8H8Jg0A1Oa5`h%%XjBrlSO3^BimF5g0s~gu?qAv*|bsE>U<*9{_fOThlqiZ*3humJc9Az z@VG0j-ApDMX&R2=F;0L)<5(O^zzNyuADhLN=>Fh5IKRo7g-X^I9e%yDNiAC`VvPzsL@Y`TEgU_^Bn_GH^SNhFEo6g z{%34kmaKxNqlZ_NPMdXfLQv1!p;)K=6>a`mJ`_C7*!!Is_X7mpI$5i8XyIN<+vlv_ zjyvtwp71kPe(g<{vKZUzmdW&ykfFyrH@m^i>uE=4>)qmul3I!RKXx*nZsS&b-$Yls zp6T7~&Plq@Q<&0!`~!i@kCfY-$EgiSH;=aY{$G#5Fsz42X?{})4O|(#t)kT%=ai6% zgf5v>$RQ%v6t5yJY{~@ZulUkY43d*y7>54&Je%v+BPlH*0p6O6XAF;t5pW zJW>oK1n_>T#{{a9VeXiNtqGD$p7;R%SmUnOudZej1&7BTsN6_cuWKMQC{aSRU$8wI z7dmJTIUmgNZ;B?#?qk{|YG|w+4s)NL)hi=_Iq>ogXOMDxdkj98=I$MHXj;8VCO0{) zk;;#g$tV}bA!8RvQbt#dwjA;-QuN~K{b^%Aa!^R-;31BbgdRZgd?mRRMhOAi-;85v z+}sJ*G%A6G#@y9k;YJesK6n=}zYi4{@kf&;Dza;r=={K}6=9xn`>`%4G-anXvBEdS z_I{33V2$Iu>znBWK{tjxCQ>VRq<8{$G8Z0Su0nn9y-ZJAcmK^qghqml^9Anub+VBU zzI#J{!xC-FQNCS9NB7<-x!v+5W9kCB-xB!pd{!=b=d-C)zGA$bz_;V$h|TbZ;bfU% zg5%P&WX&HHy3Hw8$(IYql8hGf@8r)vxLTt1E!TdtmUf`7kJL3B6Q$&;a43pPYMYvb zovB0aLl7WxGwKxFqIRh8Ntrx7gX>k0-53EY$D7qkM39>*wOcxL(N!{(#kHr|4&t!_ zumn-#$zT(+brK?#yrxG85EUc=`!LgY$h&^VF5&dtC=v5XBHdBQ|c6L1Z5)G7tR{N-5%qZG_V7J}%I(Nq;f{Vp#R z3e=XI(=2((qRQ}_|FvB@ApUV5%Q-Fx1b9*vZt#?CozR!yOAi};a~U?8nwsX|;t}~F zQSHd4|qKJp%(R(yz-+h7hV=2s=NJwDN&)9_t&hltIx98<5BJ=%ULlz(G6P z#kM+2_FU@vvLeOPT=2h+K^xeWLHJ zH4a{RtB)CAgtV839CaM$^r|ajSu1H+WxO^UeLQb%rfIAtb)4Wka!qW8>?aDi`?J$L zrcE0v2$hH6R1XwE@-@^@YVV!oo=L1XCEps6%{Pft*DkE%@nh&lBRHn@CQt%o0dpyY^0tz@#0e~FF2iw&!$>r{02;6wRzK3D_QEC!R zltUji!tR1Yd`tNE)oS{+8KiZ+PE=eW7aJN$YtL(q$V;N>FB*Y9A{7JjquBvU!(e~K z-OOjJtVAuIXML_~qG8(KMT_%C+3&9PaI?l;i#r)?2Z$)m@)^W77x@RoUE|!2oZvz@ zYkagMlRk zw6YIT)t|CKC7e*^oRI{RXXgNlh@_P2#}~<9z7j7=F3o*9S^w=FiL{2FV|;O+r2U5U zFcQI}0)~__n&_e^DP+cL$X}U0ic@ChP9yv|jT^B6!)Q`#ZR7=$y6f-7e_MqXHreo& zZQ9qJ@$^punjrDC5++eM?$E}Gm@VG@R=xUGQbIa^fSWcz8ENIc&$LQztQ+~-#U?f| z>2mvu#vgO@@d&{5Z56i2C+cXE#_;XReZF9A@bZXkb;Po}`%6#hSHo7iDd>l>e-04t zN4bh$_J}`phq}eq^`0k*#a( z`#-q(DG#-V29!c~eq3~{v@kJ#Nj1#Gdg4y*5YSqSDW0ihTLe`VBGpjeN zl*dyIv|Zx#4qK)&bjU=Z`x7N+h8Ju3zBw6fZ-2~V;k_?ie33us!5rDT*)Vjs;GlYn z)82EId}Z9{;9h(D03vh2q`{xkBHcM*+ZS5ZjpvIs`7g)Kq%;F+91gBVBno ztNBoZX2FeO6Q#?{57=Vm4&PMC?8W(q?1{>OCtV_U`+uE)>Jq{%Y(<%%bA0$QVi9EM zDA&Lgg;pShrHT6P&O@052BHjJ={^<{G)X4WKMr>WBl@V+AhhHR!7x*T^_Xar^^zj0 z7$yA3$`4(1s1KO8_{iSF2XB8PgfT^SzUUdrc(Q=PW5)=Gh~rFN2k+oBX9?69a#op< z+KJ@t_1rV^f6i4Gt_4<}cFJNss7@n;8*}I9R0Zk`1l2tZnH*1AgAs}GLg>ept2(hR z$5pcFi%yI0!>x1`&pm5>nbmBE?und09*>{HaiRe7!CMhnq1I{`}ZT)pL z1qH$ok;DVzB-})qx_h)NVxtk(Y9?*Y_)X6Fpzb9Z?SY3CE8wJEJaTKye4J=W%uz=+ z*(8?>jw8VOz)AMx6!8?BiSvl-0!&`S)M1sfH<3uXPr1j zMqZD8ZtRBES7?L!o!jHjobWdmh8CXgx&Jvq4nAGoTj{|Gnc(WRpzSq*>tobd5_Z;n ze?#j6eH-hUd3{ssgzkllzcDiW_-;SZqvJv2Lw0TVk7SE{hXEEggD_&1x~t?A-ZWO}iWBNt!ulENF(%9@qGT%#p)x(*<=F-DG1UEq> zwJb?@fE&oo_v$8M&;Q|x00LPrXM3M6aQ6)qrIznIxN*3%|LAu7kIkL=8M6R6tC9qI zDU9pta(63qFh)EJiZheBxf<@hfACS^hk*tRAig=gzfdYz6=%fJUfb1T(*^|@JdN}< zswREH#R6<>Lzbihb`Pw|mE-23M%STsy6pLgg!AMnplmbS;{p z5|KtX5i{n$1TO~cMDXC+%Ld#8B)`w3xW07Xun`|W$H)-0i{xel!{q70i_KH$Ftjo1 zAe~es@9&}Ex|fo*I;nsPv_DzYCx5XJhj7xF4~b}^B57I`Axp8jEtbx~#l&EW1JY=B z{tD|y#%+2#)=KX&tlp?;f-u7o@wNz9w(T}qY4i3*vFiu?0a^X=19>sKL1ha+rG)A( zR$$iCx;i8NP)RX;l1lYUto`}3UVLjc^v?G1=X~85HY-=y94JoA?!zhsyRTV8KBXHDol(jpni7i7JFSkWc&oma+2^-_W&S-xNHV4FDm#)E8C?k} zs_O?kR&Q;VQN(07@s~7w;}$D{m95lu-n<|G=3L^ZOL$VkwfZ%@j0>(l4maI)ddWTjjS5O)E6QdazvL zt*AVh7-B!48ZovDP&Ci+dPy^zje1Q)X&L64_(gJ#pNkX#7I>TxUo5fxj5r^O1wT(& zARaHMdZw|jjkkZbWqNasPi*Jsc6>$uJVa>s6G)(E_U~X$4ZD(7YG={qu+B2bS7lve zU$1Ti>0gj<^&<|%Tip|_FRkGR8gxw-7{LT~i(FXGDXshIgKd!4{V}_r(!0>jSGlMk z)Esm^pmY{{Z}q=T|KpqQc(Wq7-5w+Pu*&i2YkIx!6JXwlyZ(*ejg!)Y+yBhT(){1z zR_h@dAB2Pc5f8?Loqs4-7(JlETb+8wL!)Okw;LGG1cObw^fsoTxGVy(r`OOUV;5(A z5pn;x#m_A(d68M{l42914qFrSqBgzHRcc$N>kxb+H)9^XUn#uZ#&3PkO&2#YBo8GC za#tD?rc86p#S}mG*uj`{&eC>vli^x2q#blp1(5gL2@=P!{d=8LOM4~-K5Kff&deH9 zQ;83Wy`#9|(5VUDFz?JIsDQ{pHU;H{@|I)TjdS=AmNJ5rK+d2*TSM|iVWmot7FGpL z3;AcvntnNz;sgh82HUUeSh*kooY4O5*c|PC*FC#zW)Sr^gI4Yp`?DDPax9ggd7^)~ zO-d`|S*p-QC`fUWNKci%>T-MgS zyH+WjBegFU-l4ZE)A;YZ+L2Dxx!WAnlX&y5j9!f{qfo`CYLz3VJCE48Y(|r!uYzGf zyO+gNNs7-upE*1;DAI$FN;b+C%j1N*)qZ*X>sAV1-QTcFU*nEwE(ACQ$|A5PcR&aTS*+Z%f3ph8N2qJ0eU4__u75>5C@Xp*BxA>(R!Sj9zjyLsc7j)@gd zKJv%CUaB4$(PSVbWYoml7x!P`I^afhWA~mNN6KO*Mn|5c)4yLwWhML!?43auJh zhOa?y`^R^>%vCC`XM**cW$nM~ORL^8$PNv;#?aHM5g{qIcGP(kN#t8i9*Pe}<=rdD z$)i;)b~@7gV&jQ$=RX2)HMEC2*oQ>F&2!!>Y2VQ0PCMjO6vDAwM$okVI3?HT4li9A z$+r${CDX$3h6MeJSgMXvhJ^BZ?S?v!WNHS0B}oHAYou~LogIpLAh``dk@#$EjZeXa zuiN;x@2A@PesR@CtcgX$+nLhBuZ-2rFOJ;EkNSt#^cOqFzq5u|eZ1$%%azE`O~`!X z$SMd^$R3~hTk8vxzV2SlS=JXut8_J*l80pJ+ye+L>K9d=fKX;4%?PqP1?p6DaiUG) zKxPoyQvg|8qr~BY0BDQqZx~Dlqg6t=%*P2PLxCn~5^}(^*RUZk6SOISofEA{VeCD$ z1qFtNo19BP>8*sSi4a~hXnq%eUy&}t5Hm7tAdshE1$%m6#x5QoKUCG!Mx_XiMnyKD zcn-FrRn|SG5%RSq3(?^5S_Wy^UffV7$AspHton1n3K5@7-7UEaNLd*1LVc0hEmTQ+*rJ6^>rdTs3KPiV zafp?57M#wuXw25C@H#!DHR84Y-z>vIGngvp|GsqV-V)%*JHZsl=Ct3J%1Em$ThPw* zi%4e9ZH^G0|Cz=pvL778DvIyF6Pf|c-IeJan~03}GC6uk#~_o5U^Z~!5X-BJL>xa2 zM#8MyU*l8UrJae%1{GpLcxaNgE@KPcE!Om`Pw(51QjUjc zaC$pIs)jGFE#Q0O2Y&UV+1)0$9qUZRyC0^x!LT#{*`$eW3QPF-_`KUClpZEy zB`{OGL@`+$fSVv~1p|@Gw(XUTCHBkf_D1adnYYipzXh6=4;6y>XT3PZFV8UJKJKjA z#NQWD;C%;wl~94{Tb_}tmp0=!-Y!RStT7s~HFUa^4&@KYy8CB;3yS~8_Rx0iM;%4_ zpE{@^s}k|Mck*Lta+mL%#vSwAaM2^7R^mOxqTm{7gU8+`q|rk~)LI-8JiiS}5%eK$uu4R7=!oCg*{za+@D+kK+Pn1b1En_6rM- zHVchlz6%NAS@@H24|B1(igCd}KpXf$LqilML>xgWaGTJ>2yoC8z(EJr3duSnG@lhI z;e%kQij@?Ytz{GrjNM}{V5~=o@zOZxx0q<(i>?K%j9O(;gJ1-xr{tpRww)(6(Z}dJ^U)Qu;z$`pwiJm9ZoHI6NLOolK?(Hd)kl*DiO>JuBX}$lr53jX{f${2v7@t1 zcqNV2|JbMRc_iG-l)vPFyM(>3`!8SNJ=Rm?R72M>>iZ$7!DrO6Ct zjzXcr_#3pOR6z(@NRF5)#h&?;f~qQ2ZBT=Bp0g-Q+CA>>zCrrie5Xp4E=j`LdKgMl z^DomDxl?2VqNx7HE_#d!o7Ar_LME{hY#jgDNhi}RMyvNwN^>qr5+pt;Q)SuU}UYR@D0yF{bJuB3#Jip=QY!8$fSEj1wgvs7;zxR%pAl-z7DTzfBdx|^eh+q z{`E{O6pmCPj)9T+KKze*k`C-j%`N1ArlWsPi3F5xr_Ox`ePR+ z?WMn@9WT+f;`dA);9e$ZqskM6qK_ea>T65rRA3z?xtPdUDgVU4TOP3Alq@fpF@dch zl@7sUZ}|h>QfHJ*Y+}H(T1KNTqJbi5UZ|)jnNMZ%T}4AgBd>8U(>KxngK&f7%P)-> z3jZAt(=Y~qbN~LRNJR%*LzL2sjEJA=$~II{?0Df0T3FpxS*m(JdpvdhH@^I^>$S9q zBzmJuz$(T<+; zTLrtUijO@ygPt%R!8u8pj>_ym106l}_T@@XGGw1bR|WL2rBdjKPW}ig(fIvu9N_Go z`z|l~^<32v*2xln`dA~nsNXd!hm&)ywo53^ErFRh817pN_Ib=A1`0~PnifIywBJC2 zEc1hP`1Lea$sT*<0a@bxW9UH>!21>a_VCDpBxlbRNBJ) zK@gs^z_GuC54UcZUMq~Z*zyYD>>#aqk5j#u2evv%E?PAZmt^>yCp75$q>4-mHauU#B~u{oEjZ62vKUF|D4_Reu(8eH1~>?sL?&0 z75w5|p2iFD9ViT2o?`Uhu|7yoh~6 zuwr2dR=)DqI5DeGqkHU>F&&-fuwzh$lQYa$fnR0df~TyIr=qd?(^-UObGTd?63Icq6{6JuQ}PHx=wX1lL}^@w<1=87p$REufeX7 zBHP3(faE3Dt=j>gYy4e`%a_=+2)#B~&Q0;nzf;NjC(Y&$c>v;AWHmhP5Q4~% zAB)u(T!(45sW<6S;}-NV;YU!BB7^1!s6k-%=nY}SAqL{?FiY02GG0ZPH>7zA+!p*# zq6#YtViqI{u1vPy z+Ov8jJ2zKL8Iqq3mo)kQaE@-r6k5?JrV^>!LP{qEGSPr8A)z#)+S>m(J0lr7~!OAziP&E$^3)q5nOAD zhULt->23wFMs54W1bY6bZhRVTwf3Y6u1bqbKeO%6(`xcCX|qO_qRPQ|-4nFU z%Y~OK1U{Dgoa$so40&)evh-SZj-H}g>n)BIA<}q2qU5|9OW(r8MTL&yxas-U`|$eP z7}96Z?j@KV{?_4u$gq7*-5Cc3NHE%!qm6>=0JZn&FN2bW!j|{ozZ07`u2SufPBprF z_5Uy`BimFPzdr{)lDzicztnfC;+$bjR+B zHgku+)5%#UyhHJoUuvBxhV8YX4Z?JW@FeG> zK!LFHuU}VS9JZb4Zq!;>iimoPPZ|AahX|{=1NVEogW_OE3;s76j4o6uM~n5PwF&q- zNkttoPUrBX!}7PKjm1qylmdXH+E{Uh8!E8v6f)pgjE>WyL7V|QW`zqoVK}1W@qxA3 zWqkoIlr?a+$ih{I)1UPw>j*9+5KNHE++fcD0U9hNDSJf~e@Lm)$HqBeza2s0FT3n7 z@8ivi8r8FHSuItoZUTncI0chmUFtt+DB;WJySB*yA%WG;wLXmvg}NjAWI@gF}3LXV8EIk06py--{0?yue}a@u<}Q`*;TQn(aN?5HvUUfb4%JIF2u@P|ZDePSLF_R4U z0S2fTB>|&&sr{_?5<=|xOZ7F*jQ9IqCTaw54Xtm0^ahq#4LFZB zy!%FO&HkcZ#^~)&1qPl*7Z)$Xxz-87f*&28jQ8D*?-Wm-xUM_rIk>B2R=FfVh;Cs^ zjUVY!(TSU=u_&SayjzX>${+S5PI|lLLeqU^+V>Hc9Q#8*SpWOWjnxcf30#f5+CCa` zAG?qLqQ5)-sT`ChEm^(yz|In%uG!WoQ8lf$v$QCmN!W&rUw0N*{|)!hX3Gnu#b6G$tFSK*`iF8>!?WLCmEu_H+rKFH6o!>;HY0Xyduo{4 zrlY3=NKX$@7Z>G|*c9Pe#aQKdspyDm*#_W%8Y|rCd!fgbj9puF4AA67PI1t}zZ$l9 zaZ$tfuDNM4rKfjoh$915AnUMzT-M}ySrEsZFUbKIoE_bdQfxCQ! z`HxIrNsT;DHAu)KC~q}L%0aJ$ImI=0f+Vy&!qOS+fqnY)*znMSeb@O<$o_A0O!G(y zm#;!qcF^4RdNc7l3Gs$ykL-@IZXl#GQUg8S-7&M+KaZ6LdftqN+=$mmoOvu*FES6p zzL>q^LjE{3>!Lq2AfJJwreb(AkD)M5s(JWFOSp!0G#mILD2Zc1>=E+e#1h0wb6;Oy zKn9nRJR*txOQ%i8}c`k=9raJGFi@pxby0bf<#x-T)1@SXh5-t^MfKOb@qC_ ze0>#LBfJY70Qvc2S?MI17sMT%MgdHnRI;2{XWKVfL#0MR`i~ZX1CSr(jMrVCNVPM<^)(A-(AEF14(Tbzx`Qa4(N#9ttk1Y-$OeFSd&8(xmU zty&0ud8QFA$Z}V~8-qf^{GBS>eiXs3w558X;`&I0sFs4(AYqbmtidiTQ*3R?))8We zvG2NZTJJ1Cja70gDBo@E6Un?u<*=&j^N#VF)F#oiL_I|XO$)DmAmLFRd<-atswo{+ z`}&Ut?Z1O#?XU&g6cgEj@goa`1uMaT$h&7%U{*!m|WfaP~M<$pot!j7%HMA}@_{i7K9q-t+ZBp~uYpBe5qDgDdOe zI%q_4NYQIa5=A}1Zku5D(UO@F{=R2=d^kcy4EYg>0bSl|gCc4yjQRwpw@a8I)Dt4#>vrUKm z$^LFE{HyD#QJVw_qU)-++h~yNe*jIGqf|$E68T@?rX3LaFuDhzzUO+MC(^#4oWnn| zD^Isx%cTt-XK9I*3D=$B?+{c)pv5eUd4e|@R>`GUIM*wSxX;YhUr3H~{c_=0kh9l8 zN*_8-!ayEXLS-O{AU18_5U3Sb(y*AJ60nH=5-%^cR%^XQiIUXXU?bFhp14sGCBYze zbiRXrorJEAc>lej-aMvTISdG65~Lw54eI>0(RquYZcsf$wUu&( zt>35&pB9G0Y>`0+iy)5&xt-Q+eXcOYCk5|&x*Mq^Q{~Oa!m3jFt1?Z6l>HmGe2sg> z*~;PS$x#H5&&%W^tj9^BaRE9Zf?xniPIYHOo-%8^O9 z0kHuOXM@7GRfl;(zdMd|CuIAexcPAtHa&A;+9K;&$`NPWGeRJ3wl25G?~>bkTxBbr z=89zDvO{-_%Cl6ss6$ZFak8CU{PuErp@k^X}*HlWWvQ&C-W+x=RZ4DMW{)wWp7$6=fLggsg^UPkwfZ zd4>&jiif9`j!7-tzKT;rr8~B5pWWW-51uX8JQc9*{5oN(W637vf8i;Kq+CQxdRSSE z_?dC@!Q`UrEpxoXk@Z&lZtr%~&%}n23Xk-Ig!U)=BP69yaC^Mi=T}eN-De_O?Tq^` z5c2-`L<@b3J!K-2*-tm)eX<*DX<4a60)1BT9ZPY(@vblXA}f86h!L8sU-I$gyYdoy zvF0~?7qUuKyTu*e3sNt&@JGCuz9y)NKz%X(zo`1^pf$cDW#l6MdwYYn6D8WN; zC@#TW3dM^R0>w*lmk`{FLviHFS$zxmB%CX+w&ob&9x);jC#)$c|2o8lT# zdG`)ojDV;w*y#YMY(r{YQc9^0A3RFg6qGS+Sg@x8z3cKrrE0(VCO^fx&O zD--DyKQs4zU!_Exs8>5Q<9!tN{WjD6=E3!1U?bZ2h!`%;aDg+26OPLPKsOrOc*1ca zoo%+UKg8|r)L92SCDggsjh}jf`0y=ghIxF>oxN0aCY8GMI0Zlc#0G(Cu9Uw~W7-(K zx5rENWc`+Dn+p(X0IrNEJuqnOMXME-0ODZ>O%qAku+gsCEt8v?ho$G*6?OoyYCbwR z037zrs8uaf&1!q7DzIHb!Hxq>s$uNl@CuD6ZF!j&ZPP;7d~DxQ5Li07zn(Z&s;msS zQl*)E6hKoj@aO2cLI>vrEV!QLEJ?Q+EzfJtGVRlZIo^PLwY~jQkJWx>ul#I(Bpa{A z1~@n)|9!$Xq25x(XeuG8vv&tckM;$Y<5FlHZ6=w zTY!Wk2m1e~Cw**N)i6CoEUy zFKXGTTFhst^_~lh$7Q$`B-MERw&2EewzvDHQ#JLSF%C=U?oqxeTjIS6ZGlcW5+Utp zNt;yk^jITtGTZEy-oSevhUk}&RoctDQ1z_w#?S@}uZB0^f&YMmzdKkX%Pwv^FF5?E ze;XTU!g9RdJ}q*8<=2Zyby=72H%S<{Yri}Vd44zg-fx5x_2BLCId*Ysi1aX_dcY&9 zXS)&j;$%dy~NFSuz_^ z5zMaYP*555sY@Vi7%tU_D@r5kaBDLMwHw?At>-)IX5(A(+$$BQX{@6T1}>T*GKWNb6a!9_(^Ng~gRjA9y}X-ol%D=HN$m6ID8LUF#0)v368g25x# z>!QkUZNS{((nm*Iw8v0Bx z*je8450~S|?`2m?bFf%~?pIge-FiwG>$71gr*bOz)sZ<3&fXr! zMe9CniTlC628?8U@3_4+-E!bNbbV-;x`i~a$U^ul6nq&iPTSay6sS{*54A4D^=8Zm z#jT3rEa?u7A43VWPnq^TsX3-Ur!y>c=bw4xs|4CA&`B$uTRKJp?l?h$$^?uot;TSj z$!hR!&2&(IyZnG7HFbQesjUl1cEKHcN%27=^&?EQR`q|*1^{smht zCC_x{KN-!0M6sm@-aPs?1zw}SQq(JB4K)#bhXigHf95Yv^r1V61-cZwf-ab^l(o&Wfh~81sn6zJnWD+o-z@nXNzB6BcuI` zmF%^0u-xXl1MX5`bz4IJr%mD7A9O*p)l@5mlZF(9v4QagwSY1GUQemQ*-pO_97zKC z7>~)UVXN20>w}#~?kUtQH44dBjDh9RIk69Zp8H z4BDo?$QglmS(!+s6Q22aM3cKj-_1VcAZMPfub8N zr#cL2satCPs0Lj+e(s{m$EPNR#z>fAi=xZt&rdV#i+3+gZqq1IrlCRFTWWUBuV~x6 zud*b(FW=y@JyCoGxOh2toDMKE78W8RBiHW&#-%G~^Y1Q0mx+x}mgA1ExhDi6y>*5k zHGT$^r#xQAfCFWN@-}XQ80LM0-Ov2tXxx79{!dNBxPPB2dM%)Oe0(XG+V(rn=pGH7 z;l95;&mBh=c=x-*XK-T_3+z)GXJ;^g1!RVXaWf7v&ee8&pCO^92LKzYhn!(UBP-$% zDC(z|gq~*qHIB3%oY* zroJdZ`C~O{V>u6Vxay()-b59v`*k@vC4KY{Xl}L4p^^)mY1oY7q{~x+kWVC+OJ(_^ zv~v-k=7E{_>Xl+*DxG3#biUV?pa%;J%jf0aZ>;x*VDO$aZ^Cz;A1vn+uWJvz&-G~o z_FU`^9kwe9%reWIy`njZJ6iz*qPW%gWr)_a!gB6@}-oIX>= zg~^dzQ#5wS@p+8t^(k2$3(O*$n0m)V8+7ut7BS!MqcuN+UCAIAD}!V05w^_hpOK_D z@uD2<2P*U$~w(Sxv2$852k4KCzzH#_z>Wt_rebfr!Yq)D&low{y;r&uYhvgr)a z3-@okeo>(L0Z8p8P1a+bFDMpH1&9F!k8y9q&xJi+DiAbYLK9gkZ59UAS@>^qziaXV zr1GbX9v+A`)g*%kEOx6@a^GgCRn_wv!p04{TaM2sxi#~#$jb?D&&7oGxHyllCY0vI z?B|K7U#zEExIkt&CT#ZfJg2%YW<`8l&H4;x6kR}29TUsh)MxpS4ZXy`%I$UcE^t|Z zZq%tIp}le+Z^;~N3eB8zKa@Si5o^8GkUWuu=?8!E{=CF z_!72A4|8~5-Q!#>N_{zCw=_<%V*l&@MCdf#N%0jeo4M@mCii+`r*k-1IdEN1RPOYV z$k&|9PcOCy_H7#z!Tk{>7G-1RR?zKf%PQuRjK`tO3+`>b79~3pH2u6Tp*Q5ekCc_r zT7rJn@zz8!6Yn{Y^bPH^*<`-btjpoqudipfpIMdx)Tu&Dx+o-1Ci zjl^e;?*KURh0`bI(Wv8(dUc`@r)a@MbTeni*(SJJ5F<7~XE&@2U;-i-#^`l=!ykbi zxcb4hm`rcA7hGr4XsA0u__}!$WNT|h)@~)*Zk@3TyDB zXk5-0eS<-bES2-^7GH}>qq@U|7r1p45o-PF@q-DrKy%q1NC$gLQtV@9`g`D_T?=f+ zNniJf0@LT)&x!#qz!Z=Lf|z(RRA@E6X6eJGvHN~pP1R)2?G+~ZIX^|qmp+}mx-o#* zFKK+88TR8s^E>OhiJw5#oZO2fJF#hG!b(kdiSja#fqF8enoP$stA*#qfrKAMyG>C- z0iMyr$ohPCfRT!e@N;R@Ke+vJz^9VgeJM87AMt`wsVW6K-On4tYqH|?MC6RSv5iCO zP=eA^`UY>y0v|D~sutN8>JB|0yzCUtGC3i$Ig)hf&}5bX(|9A!JCycb)-T`8tX|!@ z7S#4cQJn)IWQwoG{d(y3&F=}{pF_94@`yzw#!5vd{F~;(3%pipVZFS1@C-5a zq^|)`XCYC6v)7^_PFzGvA((xlNxN3B+Kh`xS*kvUkfY>S`x6W>u7%nGs~BmqyA?ia<^l@b2-?RYVHsJf>B#GaZ#8-X|(aJ3(7YZCi7^5rBxAUXl z4#YY|__&oqa8v$DTK@sB&MzH1yv}lV@7wQUh~jn@{A1-M-f7|^zhI_{!uPnKUZIW7 zZSX`>r;L|}Gu*yOrW+y<&+8M9Gt=q=Ge(|gnJ=Z=E+5F% z;cAFg=1F*P6|VPjZ$)GU;BayB#L|+z9)3HFeNJL)M|h`&uVZhVcLZ&LMOhMl3eRV^x6w>_O-5Wc)_2ILz>Gfo zCDy*h(c?iOc%P$7YB3G_oM?!*a@HA3NhoJ8Htn8eG<(yykw|HnuaHqW`#^nmeEuoF zwTzjCl|5-hrZGU%|7Iyz!$<;4^e59#SF&}%PFVSr5bE5%t&9KEt(j+%DKVD3vzw7h z+HrbvVxFchEi|7q>+Z!LS_i(A{XE=P&F-{*9#zMh$f9>r3Bd!mPg6R|o zr`H(_EZ7!Pj+vw7p@^L!bAYLV+j3D~5Z-S}1-A5~8!A^NSxpHI_~G*MejR+pHcS~N_bm{VPK`TXCt6lZeyDXb%0|h+*N;PotwZ2Lqboq@r8H z>x9&kyuFZ@Q0R>4%>k|sBQXi&c|{K^N?^_;uSbXeS%DU-tR#fRNkT9O@fgyFBYvVr zT2QN{4$wl6HUzQSR{vt_CQ=94m+2tI#d;+5Y_alVqaW5u;n%khh)le=E&-t&mi>>E zZBxw$yn-oh_+2^zfXQu!l!>OT=a)AK6<`t*#x9XQay=P%5uSY0>R1S#&(M`KXMx+?01T)ReRjT;-6? z^;$6(dG$&X)qaTP^<+Cf8x7ekb>!DU>IBS!T0zCAwymVfzPnG4duZ!Be#|V%e^f^y z>l4JB*r_V!AK~*0cAYQ>zxFP8;SfPcWx$oN|I4iBaYL;4_q)Rf{Ybg#Uo?|RRD|gJ zbY_nM?`P$hf(%Lh=eEYzaMDY1_#fnCpYnjmd+&bz8S;_wcYxpNnVT|UMmEv9cO=@D0;-oXp=*&3eB@J7?uWf_2{zc3Z_p4gwFeC7KL&}L~cZ! z+<8XmqA3#8=>2+U1$PlajIeF=qmn_5Jc#=}u9-yTe>T};(Mffg{{I#{lLp16TIv}E=Sxr5DP3H}+$cf!Ts*9ULNAov>_O@74bS8lH{IEz*JZc%AATtbuC6{4e?`KRuRE;maRW?0D@#W zAX*mV_tBt_z$2T&kCNclH{Hy@Pj*%go)CwId3x4eB7f(an>MwOL9`cr9?{%%sD-i_ zx|LD_?muO}cMkwQZPkV4a^~O% z&8a%HC;dTDdF9g*Q14de_Fi0FTqH-}fN0T!yt9_kf2Fk^tt&z>7BPZo4!h5N=bAh( z{{9}03&tZ}eAo!QV_oqN>`t#-Ju`3e&H@tM-!pTHi~N>BWROCLINxvg@#>dzYpcZ7 zdT%B9x)W<2zA?D^@S%mdiJo|vxTEn*&^S~dsPP%*z=kYir8NAgCuKK$Kg0hA4iamQ( z`a*|+$+sfCi4k6{jM{A`-SQ;pUhokvI@-0eOdmr-@o?}m*0zZ6)j5j4QNW|n>iy$Y zH(15uxz5L_H9%9q_h3}X^2**W;j@pd|0%>xy|=l!M)y85f$x+*1fa6r;s|wtoA$8ZA8XicH763 zqS1{?tep$d?sJUu+?q^IiIA@EA8|X8;!3%fr4hCkoo-r+X2C)^hg zoVWDc#&v2FTVFoSaKgV9P$!plF|wz{2)R55Z#_)cU8%xr>?Z5PENUdTrVBG5+)}@& z1}1*-p(&9_)2D2Ak94;PIv%*b2`zQ7znOP8Ok`SdT)r<4qiT*tTqZ4H;4qA>KcdB9g&&dIa9s=5HgiiNfd@o%;W;i48XEDM#I3RW>`>a68E9C!_ zbvjviP#2+$IHru_Y`ac$YP%7u_7C1e6V?$RTyDiOWBJBBOp#+33yqEPy8VOF=6^}Q z4G+?&Y;FoBPPwb#S#pYLu=w}*@!$P~SUhDOMACl>xkwxbmx8u=tfSsMU>y%ekf^`wJ zLn0o=c0QKJXy6&~)nd2B+Jryd7^wH+#7Ae(BPh*F+jEiab3XId)R5T^*f_&Gd$Z=P zg|pe@?leGC{h*!U*gPGMp_Jr8nu>{Ss>aO}<@3QQD*f>N%~`mgWfsgZ6m{ni_3`(r zXraj9#QWao(xarG(@i-ayrHZ&eU(Ug@qU+r-&etq#erVQQ8OV52CkjX-?K6+k2#Vd zDrzhn`Po+N+H9O#w+=-He>BqM1H5e`3L>myp%ea-xk8r33I#YZy2$xwamFiuTKKc~ zwnx%DU^mtL>|ZGh@hG(JUQmH}X#uVv?^Q$T6@H57(wg*84AE>j8>UeSqYYkVG>C0q zhOd$BIoW8)go~<-zW4z_`1f5B>r}eI)p1t1@)sBtPQP<3hD=iPy}$JHfWD34aa`YK z%v|-z013j>w#Qq$o!Ffhg^0=kar=zvb7Pq6`y=-VucI@4_4H3l;K=w%eCsaS$EiE$ zUyAw9D*g++1-idpWz&jw-e(hv_)~6m?`rP9xOeV{OLzl-K5xZd8_m02ib2Dw14bJI z(9we_F-}i*hn_nf=nB?^EMe!kh8^A=oKtQH77Kuq4k-j0 zU#77e?dyi;dkPBYl{E}oSp=pVk8oQLZoPXO-jAvqm?Kh-YN0<$pWpMTI(0297BCpu zP}S0Xl*rL~Q6t4`<0@Wm-zsi7-VjP99pU|hNsn-IL8i@N-)XY8l+3&nBQyWePNZL& zktyM_v7VM{F_2n1lw(?_B${#lPU05tV{L>ZV{i?rtS0!$S_895!W+^UFlDcu@f})` zyKtq-ku`Cf+w$;dS-|g^(Lz-FXomPFEjk@o2>oEaoBL+}=Z?tP9}?>1!8ha}_2`sJ zLwW_M^!lpd;_v{D_tsk5ffrbjx z;^hvXK2qCq&FKrLl=YnX8w4unP7eB0|FK?n8%E_N@o($8tdAL$C{U+5=~!NY(g z+ongi!zR|FtAhRNvoXorw)@ud&m5t?2(QW1zHXRxIbXGdD{tm$Q7VwaUH4^yF_won zkD*B)+IC?d*^yr`mi-^4@q~CX(OwRrlxLT#{(W)TPs{^X>}vL1A@7elH93d)hTi@| zVH+4m>uxOnWf1BwM=uhjsbUR3+4Q@)4SqQ0nYwE^4+!=&83#8DMn-=X6ddf)pcpW~ z4jk+3-P*jn0^PfHO2)+_=GbVjC4IY!J&N5t-RL_wI{Ga*@&_w9RW02Xs1>3@y3f4) z3|m$2#Y__f`bUZR6iR5dZ>*-MkDGLcxa5)TcdN7gqb*=EjAXX-Vd_@f#z{F%x;|RP zusn)~{V+v5dSTn{$F0EZ49e!9@BMeD74`0kugxm6EB*rDGKqwZMl4ng9Jq}}VZ;I7 zDWJMW!LD8_d<;k|0oyMycTR5rYLcdWEE+}$tP^T=Gq+_~WWP-so@KjZ>dKk0%IB>< zbUuA#DougT`&#Q0sZ&VwM#)&A@~QMm`~WGRS>E-_1X+XeRj>=U3eE(?!Vr` z0YLihz9M{l3)NLAL8%bP7qc4+1kMs#1{X8vIn)g&Y8KmkV>Ptg61T|JUw*5-{Aa6v zg20$#vRTSuVCRJ=4$r-|el=B%H&^3JaZhC6zRCyn@Yj|i5dhUDSS763xV2cf+d-pz zM(e<5JjZByi*+b@mc8+-i-wivf+*&t8z}7?y2Z)lO=z{AKWctJ8ZwuHG~3Yn{3N6G z(4T|*4Cku8mUFw1qc1Fn{kuY0W3tQCg(Ds#(p_EM5z4Q+#H3s#f9@|Hh5fgNpX4;E zsg#up9~>UTA2*Y#NV&A`P=60>FrH`S9}&vm^x*e`$?#Rp3o8Gpti&qf$*~bJ<97<` z_hi+W+l2fmrob)li!s>fw?7*+l@QkElF-$vc6J|!5uH$H$E>f^K z{G!Yy_QNazbaqPlorS&c?a_&|r&Z$-ce6~NpEcU6ECbRzNkjxS*Z2_)+*eH6R9iO7 zVIm3ASD!rISiw==9P7Fbuu1>i%-r=Fe*8LkW{5=H5Y1_|)!<4xJAsvpmfmWjw8^cvNH@TPvZd*l9DLvIhK(iSMD~+B?;e;bd+_ z-cg6#BR$)@qZ#WmCN^7fDWESW7*s}Qqhh1mH;tz8CO7%dX;mC8Z+qYaqyu>5>vHlY zXzm#IuGMXEyAQeZQ{47@GW8Vqa|Byl#;oC7I^M7_+Hj#)=TK-$VxVRZ<@9DlzHOoT$^kR(HOS(c`dp4etWkN&h_J2XNGF^v5SeF zr1n9BVBE=lLC|?0VF*Rq2OB5nlnm7sEzK}lDT zp+JkVu4~DF!w13{pl&O#s!OuTZVSml5IxD^{TJMnBj&(i)BTp!h|>8Zge1Sl?=A1O zX!sv&+(6`Fx|Ve@mYFK^kRfsKDAayCpG}k8V{jq1ecbDJ)l4avo%y{SS&7;EUM*by z!AcZt#8u0ounEAh#Y%JvIBQg?+_tbwmf0L)n)WX)ber{g%ZLV>zOPcW@>(|e>gc(b zgp};fo^ZyeA(BnWX5=?H`^E8UhHqD8C`l)!nG$FNRwIP76yHNessbvLh?FkUX87M= z)Q1wj!ti&pYyxfw505*#w@PE+Vg8Jt8Aj69Z0=E)X=?RZ%xzj0J~UGOvT> zh%v%Qw@|;{j{U_k*y(LYJT6xa5ge#`TtKoj#=u*~ImmG70Jh)VaDAv$=s7|}hAL&V zK>#(2tJ`D#VaIpK&BWa_zB>g(%y_vJ;tL!RTb_ww#VKD&kD{-km;!Z-{QH^8j9&$G zZ9P4z{dSbB)N_cFGL@3*GHd#w7MbvEVXfG;CLhJwoTaPsOS63rC{)LlvTQ1QkY7Ww zGMSz8oPJVQJm(G(2v8y7f8_Hdj_1P7iJZ2?O>nn->E^n1+PD94KQhsrmoh|PKB{tj z7t~?IY8{M0ycPG&Hb2rK{J8DGqjbvanQ45$71_bzxU1nxW>$jNkh{B6C^?5@1P$NH z@AWr@0wzsX-TCT-f4xS3CGP9rAQP7^(!Xva!~k4!WU5h7Hk;GvBT631QSXO8e3cvl z-C%NAYec?}G%D|JZ;H6^Z0;)g{g0p{~!f!H;oST8ucD5 zD|KvEKE)f3J}WJ9WFr2iReaJq7tb+n!sX`|Fk_&43c>!O9b7CN^y}vvzB%S$!qOL` z$^9+L?6JQH>j7V@w0=hEP%4cn@%TQ)DmZ#rdkae`C??W1z&^9{zQcNx(#tGz24D=yrw@2rYb#U3TI~__FhZ%2!wYMpOj524z&& zvq%W)^&q(op%>?`Rh%EVECv@x$&@yA_lkl3q)P8&J7JX6uTruzS_`eVJgRyYxyvZy z#z3;oR#fweT3n1J)?wn^df*L*fIOsJyGrb&gqKRi>$NjEdq62 zn)CLgHOaq4D-#YY(Kd^5Y?nx@5`EcIs! z_gb>`>Tx?Uah+HC_h;=bM~%&Ksx8(wP0efw}=dpmnQ2Cma53>PkHyd4u#x zv@7VO9~G~zxa6$fMIx!Khh=iTAsB7zQxXoZ*ls1dW%0^jZ*1A2ZrcNF1CZB^)Rf6l z6!sZ|G8Tm+i~wz^W~eQ-h}1}6xD;%M{dOrgfVnG3qi@@Uu7OADVG8yz>;U}UNPC-A|SBj9gy!x4#Cidq$Kg}s;nz;DHPVXkh^rbi74o=Mn zM7-Jl=P32~SGFqR1*{?;y|DeR)m7N()P4S!XMrLs`KMI8BmAQ7?!Uh+!9DeLUb#dI ziSIko6kY6^z(Ti*)k)*RcpK%P?HWpk`6K(Lzn#ZMaoaalO(ZM{1+u9#b=JF+$djxqt3I9;pzu+-i{8K3m!1xrcH;6{VPRR4RBMjQ zBpRJ5gR7_)X6I^V+7FIuNHiz_%+h&=%r2NPJu>jfX#{_kP zW67N47na>Q?$&8Yi?6!+ET(o5+7N=U%owNNIDfpjTST+93}$(%l)~qvAhW@T$h!ON z|Ir(PjN2N@Vai$+mb<4M2zJL#UXP3n3BngzxN@(h-8Kg!@}PbALA+mnf*b&W7SbhQtj?T{@!>sfvHgbaLb-{R75)li zj&OvV*|w)V?}jdri*EJt9VUh4_hKo%!NPJ;Vu1FA?j7WTF;vg4bqAQJRv3a~vd9mC z?p#yEZgiN9$h~n%w6xP+ey+n+E=q5fNp5P_95->&71-eQMN_8)@lc^)f| z`aAL=CTmsRRw|JW1OkoKhsQM0N(aWO<_F^?%Ps!?d!i9L*2? zPS*mry_jq+9HUOJ*Ma-S86ci%d&3VCKIJl2U&9ZLvX|N2v-d$=A)Ui0TF3X?0zL~5 zfAGZuSt2KofeMooXu&lHG-5`EBrLt3Reswjv!mo_*{#n{*tw&#G9QtI{-~*%N+qh~ z_0ZQiyc5?Ns;$1p_6Cy++dn&TlAxm3|nzSfJbtNU>aYDQUl_+KxcUpgE4kMtRi* z41?%3g`Y)A=hzqGqynt)lU^41?M7~uLFegIQWi%Fr@qLSO9P_kpzB5~PORw}vxY2% zS<{m1g1Xv&sDM{_ynw-G~w zf6pTlSwnIB9=e>qwPbGe82T+2mcGKc2q?Z7mO9%nXl&kJAD5R$C7UhZkW!%+WU&ZdrgH`~bN3tu1dWSxs4IhM{zf zU9s3~LvjK93zoL38#uo~;#)TK`&mrtMT&}M+M*?SH4X}y^)9q2BAMIWlO&iK+1cgp zMv+_{@A0j$8?EzeR&9_q2ynZ(Yb}Ik=GSs-+6cqA$lhAeOR1%Tpr%W#_EdRX_D(u3flcF2U~MR+|Wkf$jQ(ZoCmq^U>p%(FuW zul1Hz>bNJ54QVbj&~!_?j{a1`)`2YQL%N)*#tS(eC1~P34LN*>``(K_#Ea$rpGzrQzh>wqS_8z{WAgX`DwEhp5`TNx+){}^5?5@}H zWmi!At_z7x-R$O*ES;W5+WN0fdadU)&}s+t(W@N~-?>;so~TWU=r@aU9hsil5*xZt zd_2br3b!P8R~q@T?A=)-V{I$^Wd|e;e~R_LSXJOdl$_v&8>ASb^~`MLTT08o_trzZ z$FPL?J@%qa$GpzFBCG9Kqu2F=mazkUZ+vF$Y1J=u1V0W|UR+V`S_GCUmmCWxK}|!S z9X8D0IhEgShm7&Rita7$&pk@yu%&(8;vJ|m$DDss=ER`K<#PB-A8{|H z;%mWktkZ9ay#_`8^nRTtB_-Dc;{tas8FZ8;I{QRN19hF=Kf9 zdkVQAD!MpzoDOMkJ#h5u+sMbmbkslREmK0}P-&!!bm59FLDQ0sAzQZHBY;Wt!_=_l zXP)jGG^>E-po?Pa*h-zN(-F9?HcB=Es9$BRM(jFx{(TQfZm%>U0hnBYs@%c=e_k3j@--ShN}+ znUw7&^N)&Zz_)pFLxPz<6v@Kn#vVn2^?r>hhWJ2iaz(@m!qmWEc*kHvF*?* z3K5L`rZQ3q`x@r^AI5eve)4NJ_Mg6Z6{db@x?6hW6j&*5C2YpK)S1W+#)BX2kcWhb zx9w0PD-20{&@DTrIM&No&h|x$-6K+j(KjXWqk=xCnq9%3{FyNsZPJz$+X9CdB(5Tm zmJH?{Gw6~>y9x!;1FE(4Y*oi$LSD=y;voLbMwND5mvdeYx5zg8T()(Pr!xy_iY>j$ z;JSuG^5FSB+d!#p5TISpxvjBTMq3dB$4@)7&9x!e|0WGt{t z*6f#D+4ZxvbC3ajk~j8KAA!i}I)%7(Y1CWv3k#!_0~6}5>~XO2dNyqrWJ4c^%vnsE z_MLj-c@j^*=(?1?GMtA{$)1osK!H)>8uf(R{<5Z35=KZ^#cW?giFt7<$>+IDidf$+ zcQOG~71c>sl*zs8_9nG}+um*Bxsls64FGF~8a6p{QBMW}C%&R7X9cE?kb$b}?>V49 za2SZmGFL~CD8m*z5fb#j2ua}AY%1s`>@E^l1v8swHZpF0BCOiP=^mMyj%9+1FETb# zPGyut%ghB(s4jy3d_ooJ3ZR6Sj57|p)<@MyO?11gwLkYEiY2s)DH>_ESAvo5b~%8N z9wMA_bz&#)$EGh^SsT+9mIS_(I?PEwY6UiyhcVs@T)^LL8`xzQSeK}|B*)=B4 zRglH7Ppp<#EWfelP#s;y>dM?p1UiB-d0z*FslRlnEFj?V1BGQNXFYOM*5=t4zGHx5 zY6nA6@AseDS|%O|Uxg+^vw|>)zo^>e*r9y{`!3Vtvb|~GSE8rWKcw#i#{=+KhDFtw z>K((iQpr?=lip90?f-{Vx>9AfO9UKwE{lze>AzO9{Q+#m8t0U*Dw z@o`@cj$S%AuYX!ht(LHKl^)x(FP4g06J!U>wv_(H$#*tfZyZrrUz2oaTGBMV4-Mk#a3^z4%M{wGt`vTu%l>|P$~XUcf#^)x zvZTx^Oz+|1&b+CWPg;RXp7~1^xmF?-j#pOt5f8#^A_o+mCNC@F*w(aPe2>2I`#$NP z4*CC)f-Y4W-F?fIe1A9Mp3Uy=Taj?uQ2HG=v8)3zgiWD#)>}5^d8~8v??$&0sr&}W z&m-YZ_x`$Em-KwI-`*W$5il?i>bS8M^&!PlG;2vgq!ap3?2@CMifh0&*>GYxVmi5T zFQ)>{H+C@F>TB_kb)8^MxG<+5G4LyDjo1obI?S2A)$&jO)S6A8iXv?;e zU}2urDsBj>cEdBjLSYr~+>eKCYeDl%;teSnm1y5PR+l~5N5>*;o9EER)gZlJJ3{;je4l)j4R}2SLrpTv+M!|3I{LFqUP}BaE7o99Kvd=LgIO}o zU~fP87b_sVln&k%P7OF0j4|+q?b9RkPzV`i=E=^0xtSRrpi==gSSC%JQLzRntWU*+ z+ZgfTA@d0sOJ5!H0qw0L=$-?-`gFF7QSZC=z+&$fVR-u6ft1)-|2Xj|U!*gwqI~i- zghz?Fc81V`860PR{L=F}hJ=Eo{lRNh|DBRyYaPjnlWAl@&_(oK$`^EeH-)QUL;fH(JA8Ld>VHSmHZSWm%;UAaus|)MX0n< z_9~f=bi<3Bg8^6S%&+eB*lC9vqbu|0|Egh_9b6#0VWZPIkXt%>O_*$Mv?}xqJzGI7 z8tSmUxH$`F6+U)30iYnz1HJklZcq$`JeQ_oS7hU$)KYe*(|8#0M%6eJ>E{2m>KEWI zAWgv64B>Zt3LCkC4TA(M%|EkGZY*yyRH`s@YEd+6pWZIecz$0DQ^#>#E6?8+W|fHp zrW2_XSI}0c(r8Q5z1vQlqbp6BqJdGIv6!otvkt)*YhnoNp48TeV}E#PA0R2Y;`mi27qN^7v^CmO~;R2Ib z>N~#0IL8WBuzM@?Er|Im+vl_}CWVQdFEgRF5fQvNwW?!nV+m9IF7^ zzjE1kd2Qu5XpN&*n9TzJ{9U=>(xEx_E6d@CC{NcPzo9RapBH=G{MQRW-DcY2)PVhZ zLvy7P$cWdswV5ZzP7$Q@x|~l~`K}~cx_=2w|CaNUd#Sl9=iKsL%w#m?1rjFqtG}E# zOr%Q}GcfP1IQb)y=GVTz|2!`T?gbLmceXEb|{(9ZfNHxcW|; zKX{oCKWAZE)N48iB$ zuEcNrtPsv&kycQAW`mc_@+bGUNp+{U-frU?>m;iKG{3Z&d4@2&9b{eFnxdWH2!FJ1 zk}sX-IDW1AzBFR+5t_W8kNYIPo-4D%YIFAa`B201{YOk{( zjz?h3yI0QlN9-eMP_JjrD=uw-*Uu5@$W*G^c8j|KrAH=~hIWj-uEz^SR@d>Of2rto z(zQXsU;eqK0#J z>Cp4yRqKE+Zno*49DjsV=0n})8-obo~pDg{4e)0u|vbDP7D)+_W`;}b%%K`G=XJIr0H(O z;+iGn{Y-RGGSFk&NF{2oHyjoH@YR`V@*z|GtzruQZ3oU0o*n7JG$`s zCQnKfX$ExROipkKp5Z?pmFSG#!|(ZDH~mX7ysGZ&$pYd%4m)VZ(VirHoz8rfUAC_L zX;R2YW)q-<^T+%j8@-ejq+(>12&FXmWcA-Rw5{|t*f9G!?{hu;MV z$-aNDmT;Bjl;O(8ER`q8y>?T}i4*ae&@0{SYXlOp~Nz2hJzRP}*Q0lFo_BP=*}_ zy&8~A8#`69+?eY-**rZvw7?3f9~$4#1DU-EGyUgNd?M2_=Z+8i=|FNHX9#K_77LAF zkAGo?`~R5ws-QU6rrW^>A2hhTTd?4+K?1=&KyY^r4DRk8Ah^4`ySo!ygWDl{@9(cu zH8)c=7xTPNzpJ}fukPM4@r=M>B@*-kW}iglsH8K+Ra*W48kCKi@Z8pP@Nn88i&WuG z$c@Cor427D^7f*7Kere6@}$T{ovvI_f*M@mpa>uxJW%LNDifc zz7f~UwZ;|X(YD_|^Q?P5!WxPJV{oif`IBM~^|8q?Z#-o?-Rrx)a8Mr$NSqmo@2N9|A{DPvh>~I>qdPmQQB}xty@b&jy$6M=alhf0Yqb@9!u;`7auF~ zo1bR{&V&HUfEQtOFQySTW4YWpl>vk{`5mg8jKN7RCbjY)^}4-Es9sN4$S!-tsGp?; zifATE;dWot`BpofAN!p~?Yg(8V=ie2<^*IYh{*bDbh!Ngy&{9;c-;fxzK|dLNrG>b z?Y9vw*G^xx$IbMM40V^$eSM?R>lcVp1DAYEY94=`CREKRZ4-vs$N)9sr;V0g80hpc zoUnny@K*aJu*X(fZDyl_nu?`mcsb3;6f3p*`FQqnYq%(DtZ`VQZ6qItzd+Dn1YvLJ zO2hM{b;FR>uX;9}HK}+GKcvz{{Aw_jjc+Sj>7&fYWB}M{gFT%rttLZ3m8bi{43J>8 z3hLm)Z+o|FK~Q0`a0pR>rvI}tGn18DNuK)6CH`nK&)+Q_5P;yA@Lgo%?TFpzFe&Ik z2B~Jdf!(>EGuY);9$SBsjYIGxY$`-(3AEt4@-sOF!p2leN%`HBGsVp6I8~Dx;F3hi z)>T@|%~xvOjVZqckt4kM8m=KIxJ%2G41BO$EpR*o`zn{Bvv_neS@)2;!elfug%VLH zB@K?l`Y{Ly&EX5(z*e@ccUQaNDDl@8Nvms8W+?Zt(WbUlU_0rMA!Pei2cNnJeE728 zB-RFD*&)y=LejnTu;iD>J^&de`)*wx{j44&0;CRu(Z3tVCo4vku3^-G0w{D9pZn?=v#_Lh-M^v{WTqFcvGDFTDDTO^C& z>l=Z75(Zpe`sr6EkzF>8dLcaxx+C|~9BqY@X0^Hml;9x|;Bx(0j(o6t00tOyYVC-8 zqkY8ypz$9BXvEyvHgrg_A=PB977_pXB=J+Q$cfw~9Qc#wlAP6*nkN#O6kTcfmO-q6 zyYc`AMaYqto6}SWg^s-M`j>o}7GoUs&rhnTKUeY0(L>Ggxw7I)-K=!w@IU26U`>fI z7jr_RC;7%*!+bR>!1r7}!`a`o3kpmQpM)ZfPXT@TqnH00P;7x{Z%|ZisWIiTRKrE2 zfSp(cP>)2!8X%GBK4>Zr6PoHKM7Xb9BPIK&UTr)|N`{|xDEh=<_ueGX!!nw&6Ud+R zkDc+bfH4(=g@rObXnU$dl{!cv2f2sjE19=WZu1FO_BkV~edYxqJ<&$$?BJ}?^GR=! zpKR3IRZt4w7b~(gSV~_{m$jM!TZ@xa&NNh4)GaPUw~A3_EZcvtQrhIKRJ&MjQO)rq z1%R3cMg$Bjkr^2ve1*yp(E@Dw6%Z{4iXs*dZ^y|%hGU3Y zz#qC5s1Tbbx=7&cF0*`iNM&de^YNixf)6e|4rUA83rx^;M$ffXavJ}ka#Nlsag?=J z*3;vSXNF>L;g*_j5t!(Y1aP;XUEH`z`h&ysEDgqJcfwsquvPkX%eRR&tXK8?`GIe` zTr@}S13cO)m>5P)bOq7!WehP{MHJ(;vsRkxlpQK}fgGbaJ3BcKILISm?BfbhHPD_d zCzRDkw4r+&8Kh!oO|$MP$JVj<&CIcCdk zjrRP^qi#||+iPpr#KiFEW{4gncByB?__+KH!eHs%t&TT5;OqU5I_dWm#O{^LtflE@ zj=eC6j7%PoCF;WuS|FoA^?kf`peTRTC(FC5eNqTC=xG0%0LmejeCESx4E(1G z82sVMAp16yx-=zkz}3;pQ|P8lXO)$&=qVduQPL{Svc|}=4hSmM6z4`u-CVEI=SXVe<+ie7M%`Ni(8FF7M^+<|N4bmyJ)?@%VlA& zCZfkSI*jv3Z2YMbFO+J1Xm9Li{QGm2_ZBiSFpKb3;6U6PVX35`vJ1{JM)}TJ%cu?+ zTq?%-uHn*I=)zok{P5${&6NGAZz@by5G^b&o^^DbwNF|5M zrk*kJvAZv0)wtR6X1$2!**4caXWPqdi2SwPRW-s zpM_2e=0H$ZO(l1(=h8Q3Ey`a`E1^#pYy@m$L(mjgkYiT7xnV+aZr-zJ>$z<3fBGcM zeVmXOg1RW-6Hd_9*vm5D+sjY$sJ}3#KX07E%ot>-y`l06b61k#A^j@6KmsnAj zD9Sj}U}3Kt$GobPFI(py|rQo9QE9t&#vI1nM=vf^_z-WX}qVe8~ zX)pkrKr{t%`Ze?jVXC&A0G3&A14LAD zk+_Vmg+!Y)XeDc%*Fc@d$?vbiDTb;5gQtTnW3~LUpk)GQOY@o^yxlm4X3MN3mc3a2EZk28_b7&3iI zo_`LD;F$Cdu9xOv&NP#u=L7wqbGgBakTF=Y z&m;Y>L0Y?)H3t-&k>+~snqLN+`mX|69Nh`SZs%5+)}kzK+((_DSOQU2XHaexdHQGE z!Ur5pS@lLswW6o}j8+uCpV>J6C~B4{#XHM2jEWhlfEmtD0)O}xa zS`qS6!V#W-SgCT;deRcCyzQ?gj4E0KOg1RQ7DIL4?80Vs++$wr2b$I>ur%KxB>9^* z`kX`b|K@6BCWe$6Ua5~@K^Cov>V^$E*Uao%GHFfht`r4!m~*H5anJB;bql8q%bh*&( zReel#7N}|yAlekb`NCg8J||g9F}=tM3J7Zpo0e?4Hd;|3tivpJ*Ge2l4~Ax|Dza!G zwaB@K_RI&l#A8@n7j*7eKN+GV<)Qr>5g6c@e0c^6cHi~hP4@VhX$$%W_>jK#$vF97 zY-ksn0em~U_3Fysj2?I9Z#D+*7OZ>Lt5Ex6yuSPQSBnT^=UDA*e->@2zj2}c-nT<0 z6!8Q9BP7|6p>GH@-7nX0mBf;bcI`r#{mI&&?Yt{Ql@nLU_?24FW7r^SFh)2kOFnG- znK~|XYbG&?eUlho4jpSSO;d@gb3R#?Zw~dYj+lvgl3pv$p7Ex5qEWVq^LeN+wGG5(oi_bRJ!Oo%@RT zf+(?L0$VW@SlxdvoLe07AwQR%eAF2&Z|lLmA?ZwD{Rhd!2_$w> zvj6WO*Q#SG7Og;xzP}LNFeV6k1K8|X_1;%R9B=ga_}XmW*)*xb*zBCn-*hl9uiV1j zL+#jizrl<91OxYoGdd#QfF0;Q%vm<*4VAZb1ONnE92L_FO@q5o zY8$!_mMfWA^8A7ZYMHH(-f^Psn?=Z*RKo%#(Jpi9w>DdIra=^1)Ru`1DToJa_x|Ex z*n=6f4$YU9*psg6gre3{ZB~oTE4d$^EpQ^n_m5L`k;{Zcc6tEH27TeJ=0vmZL!?qJ zB#oKN*MszTT^G4My* z!`-3)`(@m!47C0MF913iARW?)uEF$ElVOoT0;k|lr8}W+xLEe{i?F7kHn{(j-PbrM zz6t+oLUrYBa{;Kp8+UN4)*WomHu~R0W0kj}GK4u3$>GV<1rb)$M6ilp5Ci&~^r!}f z^=W9mbILrLzz-1_nhS0PMD?Km8`T0~8q#xaKnRsqeD)OSRH#BU^UVP6tUUq!yJJ^d>BEG4flq6T`8)m+6ugz6Aumv+N z^zU9G$Wb&>F$$5z#kc6QV+5HJ%QfRP9lY+bCr*6Gg^i@aYxofD{KGS62^B86R8CgL z3CTV3%gLePgTS{~pvkYoqa`DRllj&AM@KiMwMI<>=D8K+wR6ZFpEA$e1**^{tubgoUeOX;};Fy4vC0z zbs*D(ryOjjQfd9->Gy7qmNS)1>*BB3+Nx$5-VV~fn8W4tbEp6sEBsT@&%|`f!3-a& zYyp6{=*jEW*0LH$A+bbKU}2}6gXoQ^KwzRT5+oqxfa!$?c78m6q^>D->@w_wS}<*Y zUv|{BH)@hFc*_=;4`hPxbWZ$LwQMw>rKpr9^@P21i=_#NN|AHf9QsOzAdH1tXgMK6 z+gl&D-EVlt#=yk-PlWh>ouz~A2v$_<{VOEEU&9lfa&pfvur{rn3XPmwR(d4QOqeeQ zRu3*0cb7lz6+SKGA%=9MdjfH#qzoVuJNqsmf`MK(!7~q{t;e1i!x0Ab_++scTSmbc z(WvT`EIl{~Xas*YbFvnm(6h>2DhWZ5u88Mc6_QJmd+_UwWj>Kn2;@dkdYcLh7Q5?} zsfeAtRC56y+RFDMmJyT=KTUj3PCD~6C`NLUtQUMsH{6_Z%!ZEZ!aWk4(=9?O=&e^& z2}+stWENLonoV_j^6zH^?JjGX^#=gkzqqj*3}+W$@JVf*$u7riypf4J?s3ku0`u7( z1XkjwkA^H-RIyjxn{ZObm>W-j9pS03ef9DzVK{GJLGdd$-BUv@)`=dfSupbmO+F@JoK@LT%GURUTeNCpGB08gSKW4a+=$zy=kA97eaK;BtUDQd^TRn^T4i?pd}c>NOeMHSGSAE(Bun|M9T<}kRXxM5>1qntS)^#bUXYh_nPDV!zzE{j2u0HXzb!-n9ktp zI=b51q4cf(G?F`0!m7#bx%WYM^Ml<6irUHnBlCdh_DhHKQ?nrgcx(! zOUe2tC56QJ$^|@qZAyLSedO{rBuP09VJ8ll(tM24V(pY>%3`d(bpB-8ElQ^ zhv&&(gQG@o9E-GDwHQh?1uV9HlSSLk;8^cpbw8qm6#xJ(;~W6Qz*TQ|71K0&PYnT{F z5=ss>0N?kS9(sn~KUDa_*+7sCKIuWAkqWfEPj!k{j=m!zYxa%+`SS7%jP22{W<{~w z-#&F-PsBB6wWgfyP)=?mz%HakN=G=^Xb5G$}c#---KmqY)I$$2?$HC{E z;ov}s-ltqH>taG31&gE?E9Hx3`TygbGqLyo;ck+5NFt4Zq$K%Z5M*LPxaB;urwpxn zVnPyWZYuS-C8z&Rvct#HwCi9VfzQfz)T}z1iqS4{oRc77(Q^`QcxoDn+Q-$30hftQ~N2yhCI?}QR@1*msJQ%^FkjZu`DYd zbkBgc1cO%kgv#o)E>z*;x8*{2C(zVc$`iFCKmzWZtY`Vm99OL^MStuuJe(^9m!KXQ zQM4k-TpDH)=8;l;uFQmgSgsPW0zdYt4j2K)fYR2;BrLo04NsL`@hQv5UI#m4-N9B9dEvfFRq?d#V}k+oKLSSZOjcGrO-_Jq6ee zeIE9b-dUB%o%dNJTf4i^<;R?O3k{~v8{xvKOMEpNO;M+r7^2M7yzp{QB2=x;3=!72 z{PlHjIyEhd>Mh$;M?1TtqK+T^jP7E+S%I+%aE=CVuRTGEGcSJ=Rtr?}Umkk!=&J0}MYG-L}Dl76aT9A9SoOd$)u}>Oc?Z zghgcj7XC|gCgIOnu2>`axOjO*ysv-3{QdiPr4|0d!h-AX443yQ1rWIPDPGy`9kZv& z1)E|G1I~S^NlUtw70jtU=q0yV>gos5o$y8^>6BbgW5|H)jbqX{{@yt(lQtsvHeCl} znXRye3cK^enYq@)NZ?2{D9}J!pN#CCOQQ(|V6MM2Y`?fa3#0~P4oFL>ix*=OaU$ls zczXwKRc_t+_%}M5!1wllToJ$1fA+*C0iml5RZ4`Cd_$9CyJL&R_N`Q3HTKcuF$kwF z3>u!f3#qPFT`@bVi`P{ntsdGF-FE6)oAFL=^7>x|ZHYw?El!8)he0xwKJJeyi`Vdi z!;|wjv2!vuU~m=!u}^Y+Ve^>8tFqTa!JUETZPupby~{fc!$!6Gm|P5E0K8kokyTNH9-9B?(9fGGB-j zKK5H4E6qsD?B|AHVK(S%_(UXubBd0)yCwdmvw4S=@wB;(mI|+V93Dsg!9>$R0 znmjhy@~dOP5!k68y=zhZdLJc>N+i_wboO<*?fhF4paxVS7LO>cJgluh+}(^os=wsS zB++M=?!i&SJp?aF=SD<0(6zLLo6EgC*2O5^hU#{p*@zC^@_W;m1x_d#R^ao*xOtzG zO)d@6^;6Z7M@Tadr_zp`o88O@L6S9TQnm!d&>LMGJETMI&d)zP`S_G0?DULl#P= zt-wS|0I@-|L;eh7-TP5@Q!hrQuQBlD=m^`i!c$gH<1lT7pNjs8cbM=V%mCE>} z(;Ve6d#&c>=M&lS(`TBY9pQ(hYe)SWRIApg3OE+AH3SD5pR?Z)nI7wETye;*n&N%f zQXI{f@$>wM?2W3yT63C#Bj=?mM(iSWecrF-6{fBL{qHcz((t^vLcue=%;&=VwT13G z5zB0>SxNh}k!Xdv($8(@!rFQ^d53WRJKRm#KZDvwps8MXFhzuD6T%b$o6RAtYt^NE zF4@1a&@ZqbwYkM{eQPcl&;K)+4YNhfwgaLpq!6bxjvLV6VC z_QGdYSrVlKIi#m&?Ud;q8y#eJB0paI3X*~iUIWw&rbAJTVC2>m?W~54GJ3@09Kd*M zrhWkE8jo<;kz16>d;Ph@;nYZ8a)AC*THDUM##w=AO&V|yAf_-Vkb=lIOa=G?WFWb9 zI(r&yl}a=Kt`cvb1p3~zmnZn2oq4k~v7~WUJm}Vc09d*!%mYPtSid7Wu|@;J4;2)} zJ3Y@+5|6iw0T)8)+XViaEuPP`nOkpkbF5NP4X_aWmnioB_U^jupNbxMLu$`suFL=#f0%E^>z!lQWHQThrk(U12fcxdAPG)ZePkyY+mk#LH{dO=Vhh8r`{C#FnO=j5f62Xsi@(U=}NVTP} zLSjnjUloAAxUJoqQt!lN1KG;ld6E`Bj)kdEoV2FlDPv4!8-jRjg%7H_dwu`qh7IaR z3;i6-|K_nyx1yTrnJI$e42J4e$R(y-F-(J0Vq};4q{Q#?!Q_4;Anmj#CU(4XB_BLP zrKxp>mSWPaNM|$F?MP)o8tu)sPXKY@h@*qi+S3W1;Ji$9m1TSBwpT&Y($UR=%XB9L z|N0RXfMr6Ad5xa#dis}T9R7HW>ow(eEKC>$LoCh~K1jv&86oxeH5IA!9Ue#K7eF>H z^dksh>DlLsMEc63a>TlDkf6q&82IpPGuLmGIwBR)JPu2TB%`OblATB5DuF{lpb-XT3`(D!` zo9N~lQaK3}1gw@(0OdXilNi2#kf(FA-q<&He3Z*O9;c3NG!+1uFSV=Xj%`}Bg7Ah& ztq^1*^5qUir;szro0@DIw?h+~6DBz7=!%`5oIOJ3E*kY~%-))>PmWPNLHSnB`MyXZ zf86=C$M#7e+dXgaa>!OceS#{&(Xhe0gB8NbB_3r7_v)<27n?*W7YNg(CPT}+@=mWd zUcT13M&JyQIldVegC2=p%iUg!V1{%d`Wp%?;jfd~*pdEMbzCCNd#XSah$1cR4ko`r z+kn_avH}OA+eAur2SpJDWwgdQ)|DCO#jvAuXg{tC!W$`}>>i`(R3nxLtg?Fa#Oe%AR{1UlVLeJf zjFkb^B1OnpX!P|%yk?eLrY83t5bs?JHk+CD9f<1znQg8iL#qQblBm~}KcG9mvbw)A z-0W*tB^}tGv2Cf$UUMW4t|($9BA^zirs3X0P@tV~gW&?|bz=rE!e6J3=bT4RKK>uu zVsS}o^0x+A+UsK0_|ATMbjnB=ZFGO*h2fVAJd@GDnI~ujeFiUF;f@~)#AA_j>$82O9Y_9$N9*ZLK~a~%V^-@)A=Z;((l@?M}Xw4V|%jKCAu3x!xwQYjT!oaDC^gz5Y^+S{o3;!0;t%g z5{5x^7o2B6l=B+&f97d`vmeRQE*L;2B8EnWWyqGfe+;`0`iW~TG7?1ZUb)pd-`#6D zY}rxss2gfKc`U=K@KCLU^Jyv&G}q(c_VY31*~%x;Z?cOPlpKV%XQ3By(=8R8U2 zH$~>=Lm0CVwgJ^ZGJj*g>>W>f3|zJE)4Wl7SP*v~OzEIRa4+}HlfWC9=`yXjm5fPo zeXoUfST@c0bd@pwfLMVy)adnw;YMJ#zj#PhyHHoa-$vf<4gTDH=(PlAWH%9rB@Ef!tK zm9_9&+M4-eZL$KI1e(~uYn3L&WCrR=3V+m{P zy!FPXPG>?U4i{<~fjle{!7l%I#XNXlSvx*&)2nB~*c^z+`>NA|4Sb8(`)VcxB)Opj z75LN(Z}dr*Xbh#Xp*1Y(Gc|(b@iw`X!Y1G9!TBvWEDnU-mmjU0w+d8JEDQi4N84Ie z)dmlE1O2N4=j}XQZO03ZsRG>tdNjZ%0=0!NtqGk0eNp8~*dNTwi zQ+}!FCRSMR2!2~4QMR~o(72y*ENFeoRn)C-w`^*25|W8JS@8}$rgc1SDLq0v(KzH~nC ztIXu$QL`4tzw8KIl^fjhreDgW)H4F5B(Cy|DZB=nv6IlDtm)sMMTm= zAU#eQ$YX-(1qktIv4-s_9s6`}{tr+3UbGNyZ%;TU8It-<6PhiAg9OLT!_#HU-8*y$ z55{ym3+(PiSv-pgKmVo>mG13R*{G;9RE6l}6fFBk5%Ou6<-T`hk2mRresw1VX< zT{Q_xJuiWhuYY0Ue4A&Jx3Zi~6SF{jxnH={CU0_2Zm65OF1NHJ9wpo=cRuX*lq5ui zB&k4E`~I*lN7gziupIvDcH@C_zttWwwVFezXEQO~aT9Ee1vzagpwR0Caxbc+D9pQZ zwxQw~2X8{uxxoB;yZ@q*34FWbE4r930z5h-D8Tr$3*0+6WEq98zbuv*hEt zKXPOBN_Uhc1}$i3~V#y1+0d5ULa(V9b1D^;@5A)MW3!`x!}HHtMXdK zM6BCrBA;F$g-(m$y9_CYX)Bi0*~Q%X4t-zwvDz~FD>otFq|Ac7St*U@^ZnHsD>3e4s6@c6OVGSqX3%7l{ zt>EZZ&tJVE2J4a&#y@!T*Ly@}u21?`qUV8rkdQ*4+isH8V;FrAa_W)65f9n;Vt#LD z+W^k?&-LG0Ka0j`qmTC)mJp7q&j%$?6jP0Omh%qsyXZ{|XtwECE#zJ`%-_P~Dl36L zDupx$vX`8C{)iIZxhcVS2v8R>KU&?ys)f)zF~hZREAZtVlIa+hS`LdjAz?>kEEFav56C8tpT)m?Y|#y++DJwQLVAg5Eet|ydO1TYuCXPhqY)$~W!A z0Y_nQ$rcQZOak{gJgp$^_3x*HQ?qRWwNW89ER6e{19Cc=0w-&1x^hAd1TuBT^xBb{ zX~nsqIg{g0CnPdc2od-jCrdALtU=f{Imn>m@S!%;B+6{Tx z>gTJh($kSX5kfdDR=$g6{^Qdfzyzrwmy^r*;;d3wRIF>}6DOVp4t(qd7hwP4z zthgm9v8YLb(oaHf?^;W>&pSD7u3RA?2@Q*>{DqdD#Vm59>ASXHAJ`b^7F62+CSztF zi3^s+?7kI~y2O5#+mpaR>*nZCS#bd>LyI#BVJzB1t*4K!|5sK0=f6ArzTZn--){dT ziSzhAp&t@5gixZB44=t8zj~N1sFR$cKV>k=z@}#=<(58brfP|qoK+H&Iw$(^1z7?s z1R-lF5xeNWcNQ}t_I;b^yO-D~nD-JP zZ>ZJXytwOi5W-BC4V4z?rhV!nJ~`s;krgQ>-u|f4x=kH_9VR)5r&k0*$PU+<$mhyX zyMM?21tiK17JXaCdXN5+p@g>3m7gEW)4EtJE|HUwsgwLV9REFzYxoNqm|A}cn}R`# zR6obE68^jH3KK%uxxl*qN3;VRzNpA89Du%a&DMFfh>Aq{0%LfgtwA-P39Q_gL{y~| z=5qy{k%i%pbq$Eezv#>E5X{~-m#SB zaVl%`zUiOr#kdjiTm1!j^+kZFheQCjwXO-_OU821I!NJ;QWq6tAK1gbjRGJpwd(i!VE z&W+qL7?>6z7R;JH$cRL`Y{%1Rh1Izu8o|Nq(}NX;w?#W*S2PIqCe4nkREzMy0j6H(Xtz1#?mWkY4P>!A7UUNJ@#SV2INF|v?sKBqV`_iXTpB@U zX>~pb$Q&CjZnKMJ)op0uXr#)jy*aj^egc~JQ~gtJuhA0FW;fvdTl702=NhLJxd-+D z^q!U%E>3EgSqS9~VqlV5S4l8JSh#jUv{LFqd8{S+R(Y5o5w!{IY-*4m@ev%b7(Z8+ zf0+{nn`zL|q`YJ&%yt@%uE8VJZ=Wp4T3d(WYR#1MG;~ zIpau5d2WMgpv8h*ejfX|dx49BbH7{>uubKY=WHw77%}Jz@gxYNHU%Yi4rRY&e9VON zO;nQxhOo#*CeZL0C}E1=h-}1=ff7BEScBfn(Eow$y9|2WmWKR=dB;LZJ^J%i&Er^w zH_U{9SLScZ;1d?qutJOgrA!WOAVk`kbLp#F0`@%KqlI|aYK5(d!5EvP0jN+#X>PFq5k zq$~L8{PaU*dDHm0v zuXdQ*)Bk4d|2y<5LJ(Oy!KaE7W>7B#83lQU!sm<eXd@3Bh}qNA99{?53pH)1^v% z6zV)tM0CFfcmC6+n5)IgB7Poswbf~<>$){7#iWF3gsPn6*C=R!ZKWkjL(+dC2_C%B@%^abD) zgnaR3fPse>hExV3DZn=RxD)Gn-V*$DW8|^TIl+<1hb?7codnmg==prN9L}zfa;)lF z`brAQOwY8o{cR!5M!7}vfH|V6W6z1{RleIai~hO1iYIW=y@BeN8gxy+;bXYvySj!l zDC`9+$B$cw?--r2K|@ixq7Tz<^x^7B%* z0l4!2V!7mqC5u7nrtzbv%w-X?5uT9v))RA5G|J;id6J}VT_ALdIFOLMKE(Tg)sHT&67-*Q%VuE=(+Yrgo?y*Xf8 z7!gjoB<-NA&XB);Q98BNg>%fa{)e`T?3As+CvBS+L2x`I3ggBdS3`k^$1gfwRYmJ< z`4Sj;c@X6IgBKW?OtXJbfv=izM5dQsys^0z8f|O#8YDhsH*yG!(RwXMqy3P$*A?4d zWWEnHunXb&E`YVFu?8amP0eBa50q*oidF>?(q#o_3Gt9Zj(#EM>cZy4q;0*PbGdlj z!3PM@h;YB>5xqE~V$o*md|32i-biUjB9qFI!Ue6Eh;-a06L~BB^&f(GPE?|>btb-z z=-h>VL{8M3v((06V!x!Za2de6iFRLeQ8!$VS1XatQ1u#V4O7mTyQvAi=B#sNV@0YV zrdiNx7o6h-+7p0hM373_6&8+4u2~^(x*#b9^I<-*-dsaU6H!uIqrI~z@$tc)YwM{e za=;($l(vRRd(bP)cOJsr1D?+#x3FxI@9jQ+UrL9OReg5pEZld0vCmX_=6cwG)ICOp z(=x$I6a^83<4M6F1S(yWc&m+q^RWW@f(rW26|p32N2<{;B?0T5KSb#R``9zmSI=tS zGG(8rY|Gp$Zl1j4Z01oRc7O6DVKVj;@<10MY$xa5v^2>1nCp z!<>79%1gzc+lCWi>#h~Q+ukR$gaL;RBD26lp=QPGO*;n8BtmBd&4-jQ$kRq&{qKN<(ov#F9MGOV9sBh?C+5|D<+;u5Mh@lZp(~v%l z{C`~H`=Lh>p8E!TU;?<|W2k`26hsW1mg$rHKwxyJK^&qnR;H{0rf~OXdlvYq?{4N1 zv+-6n3YXg`@$$jig@wQIzYkp{eff}#t=3NRXH^+zn=|ofqI(EFud`0$yax9v|{}e;W@6?@4t}{>#w+ zMvN8?z|V>{!(^m;IB7+>o&1_J|U39FW&4N;&`K2Sqa zY=}G~D5<18FP7w6kN{ZF;*_F9Bl(ZO(ytH36;H*LDzl1@YWdDBKM}>s>EP9sfToMD z<#?i02A8e99@0`VNU@}T$K*=_B%Mv}FVF zh8sY8WXjUB!$}{*q$7YrO+;)Vf;!L;od{6s{X4UqN$5%hN$Z3&W_G1^@t#R&%WNK* z;Lb3(!V4%ENd1wLGbgEREEq&e=2{-MWEt7c)mh{M z3kd!OAcZE2!EqQYpqM}h42sbr6okZ#NcXhN!4&YuM`c^rgQ-doa<&t`bJ2X9nva*? zrQ`i(Spov~9GZ-aQ&;t2k`-av6e&xoQ6;sR(C>aP-WQ&ZNNSK=k#lu3z~fGG2@QQG|# zmDVbsR@*xBoJr&EyZRmH@bMAlF_{mFfkyP4;)m%uu4k7w*}?_MUkXHRh8<*zW|{R{6kY2*dm1tVxJYscuEnMCS+E7rSI zW9XZoKp;->HAi7AOuh;e5dG+6t=Y6EP~wZ5;q z01vVE&0lpGZ$^yq;>XovFa&obl-VcWQvkqI5dM6nf#UPY_9xlh8*^p^an7?W;yCmn z2EYFrRv-%l6}kR-&k2Yt<`Bbs(4gV@+@FEWSsneJ0#GnR!P{~a@7&f;lB@;>`UYWX z*<6J^KH#azy)(koJVf~0#)tDzaO9zS=<{MYgiPNEe|-4HiBX00E?bx~jD=ic*+%uBu-Dym(c1Tmalzj`Ky z1YU&&|Kx}n`#oDH_bk<0-C@3%(8r@4;bJePtu~cdf20fM5a(W$=+fBiNv zNN#%%Xgw~koE^}qGi7}*f5vxjt3L7!1OyuaJ6!hz7#=y=i0Q-T#EHN9oMMY8vlWj0 zUUR++lPuqtkH2Xmy9`WBgnl+raJq7DL@@%<0^Zy)u2WZH#F=jZ9#p^mz|m=cv@#+PIel7XOs2Ed_M+K)X+5vmmzVa`ipB+ERw z-mcD=si{Z=N*bb!F!^+NUF{Anx8PdHf8r6|uXiMtjJ=ux}o$gz9mcxEGV!Q#&cjez-PIAu$wphq9{%a6`65R>rYk;t^DaM(#|FoP=mL|e zGBq*Gj975?{poslo7?$;_2S(8UX_koDLn!IRq>ONum2eW@E137WJw0!0dN)Nn zFLt44E(vrwd)KCOoNl;NR|(7v3i&=G_2rJt4W}cG2;qN$aoPNuVh!k!QIW7vvT_Ox5yg{KxTYu#gx)u8q9Fap1}V3L4+ ztyZFy_uVMa?zsi|#W4qPmeCCb#Ai!TYmu0Vx==mux!#JOE(v%$dZ0eP_d35bWK(d_ zjSa^pmI=h0Q{`!$f4zeX5lTuw%g9c;tX!Fewn8~634}1WAkTm&Cmg&8ri7vl#1AnX zamtqH_kKlKWlGX30-WA#&W7Mb7Nb$;5Jgl*M|*d_L-|VGzN)tSQ0K;7)rx#agDUSF z)|z9lxow!b$-QB9tpWSBZw3A6s?0?JtW;s|Be+rk(dn3bD#R3NJ)c=erxklRYS3p$ z5WCb|&pB`6D1%8%jM5+HCX?3qnOe+O_ai>3$bCb(lZ2)R3Vn7s<2^!VffoToODPS) zh_I<`yBlz%LBE7 ze(0<~@PGo5!EHXO>3onq`RE*y7oH)}7)#n`mWJ|h2`}#14<>Tf!&Wk@fAL)b7;BP$Y|=N9cpTPHC8>K6<9ipuP$gr*>+8nZBMrAWY=WdHm92Gnrz$d$;!&dB6Aj z7k=1#?X}lln{Myw9ap*a!yN0!f}crRsnN4$ST<1-ErJYL#3<=`#^u|=HDUizCY*&l#Z3HkDT<;D=MUGF z(RVC!3k!(|D-xE|JD}}e#{N~A%t4WJXnD|U(EmE(r4(N=?YrOZ6E!B|z22$acC;6hHiZ{5sEkwOb zIaHgnGfyI@aFC}9y>HAz14>~sp#1Jnox?u~aqjOYkMJM42ah7dNz&dp>ffb+kM3 zNM)ZX(p*+-PKhk)sOtLMphPL0?o6q>K2tKG@gwQor9gzmI6mSiiCDt%a)k9bN-rzK9SYt5w5)15Pn#=t7x#5YwGIgQm6_T+AF zrMm|&k4hs|p(=Y@D|6lgQ69UIRIQ>90nb|;C7g_AXdyk6FRZxRBv5eS8YRkKVor^Y z?xsbqeMICX!aDTIKcY5>j$Xlu^x4n$_B{5w()$jn`~RJX{SSMw0v#XWaN`)2xhdoQ zdN7nGXO=c$?tc9U?_diI$&(C%djAxb zn(OQ;_u8{M7oyKn2pn4#T0EVvi)9EhU?c=iIAzHotrN(A8%~ySPIt_5X=2m+KfgU4 z(EPn<>CF%Wyh%mP4Wa2a71D*WBjg7Dg3m_G2NzeACh5TlF@`0s1-|=Ey@-RMOirQ3 zRO3w{wCVv+!RTpjJPFr+ps>Jv(hw}I;`?_7u)zix*;|1huTBn%lkKpdb-$CrdY(rS z_&=!QEP!}-;GfV+cZKEgsj+bqV#f`yIal}*3n_}tHr@-br{5j${mxJZ|B_;tTihlT zZl_NLG6=&z4D}^wI+i(i>T57*(Kpn?!U!(&EK+SI&@5$EL=(jqQ}c343!9sjYB-!G z)8xaKH$fY1rZ(xP7RlUl1T0S{=}F08)C3t)q;I!llw;7n38cA+Unef5pQFHMb{olq z4og)R#Gsi&^*8>m=RC`w-gwZDd}$lf;MKoYUq*Rz>E^k0ay~lWf|77V7Wc)%s?nq@ zaOL~?;x$boo6I>MM5)R_LmO03;-mUJn=zb32$|rmyihF*_NM?fk$P~Nbqwrg6Mk@y z#jZqU{B55voEXaeY8P4AWsMAn zXbZOCl8|gUGF2;HT$UlfR5hXLVrNrjrwI5)T}9^9YSZ;xZdVEK9c&I^=q=|z&mSFg zm97mdNW69+Icbl4KqR%0t= z)R&PpS?fuEI^&!)+AbX{DerQ`%F`h___Er3=K%}C_;bGd#@5#Q%h?OZ?+Ules?@YZ zMf5Fk*7d5eGz}X3lLdY@*zrx<`wyfyEB(Vo^e?QXM5g&8O=1>a1tb&3fsRWFUec(^ zhX{B%BUpN;5G>UH6iplAMS;_e{Jea;h0pN?!c#7C9FdFeKev3XVMgb&oYSJWFJldJs!nr+52}0KLc2x#c=a2KlJ_*ZIut z$@>g`iADJr)vqv;UD5g3PL9aC6};X%XT8zpdFk@0nNA|Q8Z=!=VbiV(zh-v^Q)()o ztw_i1wQ@3@+YA9uU?(`(Hl^yHq9EI~v?(AQ>E+o0LPw?dZ9}!-JxuYr@lar)QA?uI zo?zPE|2OxAXa!yx#f(fqG1cgkH5o0(KwH8;{)&CNLA|d8hxo#RrI9wI((lUJGKhto z^$VJYqA2c!Sp%rb6=J8{@bk|lsk zhNyVL=DZ+r3V%_ar#VlOm+?Yib)-tWDXo@Yt}ULsgh4loK?hd52l3n-GVgV~83-FD ze3Q31>}n`MdPdzpo$?81(IwJ4e4)vD%TKqDElFL+EJ;bUd}kG)OR>|?r~U3`TTl*L z3<1YskIsZke*f^0i|*kD|08fj4#D?8I@J;C!ZkMO6vmMFoV2I&4D~{NY>$i!1RW8HExiTv`9zCWYuYf9> z4A8|UDAm%b$h>N#AUuDG6it0=$;c>6_d-@ftW8F-6gR9`RH|O?$ZcveaXIlQV+TG)#}wYoI1Jfc8NNhkaQG z-)R|BPX>ul-8QfSR>eo3;Z*T~bt0z|*4*5olxxuTjQa1$BO2A7OjZS4C$&FeFsc$1 zt^|%8utia<`y1s_SSJw_m{-cJ*VPCv>f@i+^H5Hc`%k?RGKRe1_`l%b^MloY_rAJH z{qy|SnY}NqddGv2V5}$Dg?K7Z;c{nUYFh_syGyXApZHsYH>!WmQlE1Q`S3jqqfH={ zJXQpPrrr>bfXmIayLLzzM~t(JbD>kT0BTu^?T;WcP{J`UWQ%b-(WKpRocjVqK|>kG zhoVMP4hHSUM8q1Lg(3J{H`&CG0^qk9;GM19-La`NWpEP|n#vhMGt&vqeanl4SN;0z zl?f5;(|4=KpV=3W_EhX}ea&~;&jS|PX!+m)VF8Xfa!J7@<1#bZ(RfoorQoJSf!-8W zH(gnc_6togAVpH#k0)J#JrRnZ=|NAA-><&wK#`p(wl;L^>VQO>Px z*IsXXD+E}7ph^c8X8?&1C|iN|Jd}q~Q-@b^Sti^tO=K5j1h|&`w=;^9Em9}Zl|tO( zq0!@uD0_(R&HD~_Q;zb*A6y<_q;F7QceywAfxnbUXFw0Y?Cy_#f%w)IAbVHD9b=fd zVqHuRV^EIHo=frlZH)BZZl=J^+G~Y4N6@G3x+!pOpNJZ&gn|M>DU-Qokp*5h!(9~} zCUy8=-t@_p8j9l0o~1w^Ju5FB#ebV79G4l-(A=OJ$?Iy(1@O>2CK)pk_4R%;u zdy;_O%M+4%DKM@8$0+{ZgY}CNoYZtqaDb#rY^F(DHBsEkR&fvoVf?M`O80EUtaF_! z9(vdPp$1kH11c6wb>f)@7`kNE?X!DegoCG1MwpCr`K!B{Uzh=BFjwZ^Oz);oP0^Jh z6Jy2pqou-U5JBw$sybrR*^19tnv93+=PE>*|Z zom;`s6*`pRWvZs3213e%6+z@C%leAD1DggZ2xpIx<8Xvd!><^$<B==7e4@=pm%8lJteXtGHb1`cjjX;dWqdw2th7Dz*sQ|r5Eo<*>hz3u6B}mm z>D&KRL)yKY^!;li*cEsumv5Ed08Mv7=_`eV^%?_Kr5M2*(RY7}JdRVs#F{p7=f zkO#EEL5N^sI75CH-MQnIEInL#nR>af78dR92CA`#IeI@fogvZ*R{kMNyCq%q`m~-& znZqDypSaAvi-m^h@Vj0Fr5xBbkweSE6#oh9<#*p;@P+lc3wisM_mi*Du@LbJ`{B< zO17^{Zs_EHbP$Fd=|^k$1y(5;pRc`$%u5 zKSaD_P$^d=cpH0IGonHCl;=6Tm94u-cxuCK2Fx=EbGQ8kodr_^VTP}eWkn`pfzL~T za_$eRz^zQxY9ze|1-owZq;SXe6C-q1jm&wtsxQ-KFtaF`Qa0Pdy>R#%dq`%^O}z{> z2qw=n&(nfRs4R83^A-l4CAmq9VCv!W!mu@h>qrMGk4uQDP#bK4BoSvi`42g2@*kD= zn0tO~4@ddpW$$QokB#{iG}Mu^i(i74~$u5?9Jndgy7lwS7>_{GlzH4!u1JFv}@76{YHu z*LVPX>~whTIxg_@4QuKVzh`P({+-M;A$UEP5%*o@gq3L(x?}AiwsxL2-s}{8!DAhe z1nsslT4qqS=Zqm7jzB9EOto^f3^{lPU6_ac>OJKvl4_d?Q^SAPUq9i}qMVP9SUUA% z>MyL>dArr!ZR$vop09)KOT7(Zj}A}9R-O!-$Vabf6K)RfoeR-)E{2_x^J0Z*TSy$? z&a0d>n&G{4EYiklT#ZpbR0PYnX7az*&xh8YH)aT?(j{;!jBYwo9hbpetgz7kGGbJM zi(JExk=tK*ANx+OvW2CkS_V!3 z09VJQ)~AoN=F_wHDg#1=6$jsP?+dOj+^a!PwOf#SW+6%XLz5);W0%Bl3aUuVbZ2fy zXn{`OW{}C#m6^oDRecim7YFqvk5%nWRhvnQf1-irf8L}w$bEx6Bs~i)j6!!q0w$qb z&st|i3lKoJup>k!J8&v%4Ky?keUl}uF#x7gp9UZUi`^!e$?iT!q+*I zeAkWC#e~w+JqjoyBcEu(xk#`jo4$K|_eA{$7-+6s#wuX^s59lXi~GJ`!K<<88{bsv zEiqWafGe@sHr-}g#=)ACHln~>olAzI^wdjT68+|pQ_zd5b7&VoXrVV~J+hBi(;_}o zvouFnlvb?#@&1lDew}hdtj7`L$+{tWcg8y>(%~(=ptLAh%DN&x-7o! z77rMA0CY7Hk7Y(LN$zk!&^~d_TMTtr%ST}Q>s8-((|#gP z#w!708tB>2eF+Xct@}^6@Rg=QOn5sKa(&LWdyCOakxLk_tHLuI^IP-fT+uV3B75g7d`dFRJw^CwB?>Z&8y4}0ikiLc zw1YX^#ru(-u3KNan8?l|6*JarJUdf5njk+y+;xG4TxHOEy$91skhFf{bBW4JhS#1s zV^%CRYc%qQ6K)aMSvefhQugb5MiEly_N&J^myv`;a8X76yg}#8T#$weHRS3wXB$)KapK4CBMNe zMfZ~YIe=c-xz6kwVuM*Y8N|h9diQMRRWkB`S$#o=N~0%*zeQFK2UtJyR+h277yJfxtPDae7l~wdE@rb%OHHnWK;6v)W=*Z2k4dp`VzxO z*S?O9WYI&ySgI~@K;;d-?TNvtz^fioifFPnaXg#o8lb@??BI|(XIodpMFU}Fh|bP8 zEhK9lG-1H?ecyS?_gINQJ-Z3NcA{xCZW=wYLs2f(W!fwQoUV?{hU`7|{_H0F^C!Dh za>DkXg|WsS;!yt7UjCD}XUQFe$-c%Ri?}BGqy)lOr2f&ax^#x6p%|TVzwB%8c$kAd zBR;F=*8LSiE>GeJKgE$N_#Q+ZBMF?4NUNzI(?1Z{EuU=C<`V46^epw(=iY6pYZYcbu6tH44XK!s9uwd^k#Eow{k+$;4+4^Oex%H;{`qYlO6vB&tgL) z45WdaII(G1H64iWQRS0r)dfFsJ}1+Eg$C#dI%sz4_M|vM0&UHi`eM)&CCSZb{*sjC z6ZPq)1u0Z=n<@;L#g{D2ViL*XoU_y7Z;k3T!^@o8QrO0t8ovL8lM(*=77D7>PHv^B z(M!8A{ku05o6aX_*Q`)r7&mZ>v>-&EnImPzeAs&$UyVgD$y9Cg5q+572){fu{2zSt zpC9T0O@AnpRO8@EvCEd~j)6ub|CFilF7W;3K;igE5JESoFYzp9=yi9>ckoQ9_k^6w zpW@=nvHRz^Ct#XKI6O&+{&UrzzL)n1Yaf1+@Gy)>=i-(obyMAf#u?pRb|PAw*|!b` zh(wvx1$w<3(Kh6%_Vm^good^*IMjmGr|1y!X6H+gR#UPVww|mcIH(ySF*vA3J#ft-7cgWq&7_g)r{@5MGhsQQd z#;yUPFH*`HHDoGbar%ZJ!DGB+h?QMTb5$n-=l15mT7c+Lkoka5{(E%g!_r-o?1xKl z!d0Kvoi6G_Xvp6r1etfMk()&0_oK-kOtwU~&qXaBx3@tTo21oqR4(3|8@MD>On(`) zH{|W<^!K#y@71A(wH=OKRaDadb4hv>nNh_z zo$%N@@Y$RGm&@iY%|pdryi-pVVK#e3U)$X*Y8VWRQB(L6hS%w~8h zWr9!Sd6Zx16IEu}P5C!zY}VHL{NzLSP-+{*nl=qCK^c@g&; z*}jl&yKjtaJ#%2oQF@0rRN%y%zSff%hG|5))=1Y{M^gRl zPm&|sQ7HO^Nc~ny@K)&7Om@WNP z=9gd{?2!PAx&PFGbY};_Wem0N)IW7qooTl(B-zq78eTM6*jvPn&)i1KO-$#q@@jFF zH47Lu@dWDJRaet=pRD zbbT=o8B%5>A92tMm-dw7pTK68R2J{)U@0zGXV4z_Y18rD3Nd~SHLfD|XGe0iJJ~nf zDEyZ(YYxJT%Q0eKu=*RM=mmN#8KUpLvd!Hh?CYcmtb=^Uufj*?n1)xJ2S0f?1pEiG zx>mECrmyb}2L1~b#-bmS{9%`H9O+Y*!u=R1g@_KXfBD`_oqwdLyz^;MWii=eesD-I ztuLPLdtCcrp1!^}qfV+GM^S&lDR~KdKyT~uKVYVeXUT;nzVW>kyoJ&#iqC%j>Ss@a zYJn`cZVc!m%cfbc7Rf02T^A?t7B@C#9202#94OenceTi(lfX=h@}Pp}@o?Ef-gDmY zZO;!9Vvchv#=bS0ZP)&QUk>34SkZN{)jgG9&a{3%sTVsYg^O3ES2;9J_e*J7N37P8 z2MJUx*P(3BDnd}PI-kj()D(LVv4I3pQ1ud&r?~EHy@#3Pvr z+-bWT-(u9w6H*ye@nsdD) znmgiz6~?#JIE(x4XHX!}E3YSALGrM^A_iTohTm;0V+n0ryfS6Do~LDlL>n_y@tp`) zPz0~R!V~r2UipuR z*U4>I1aS#sl2Tw5%+KCg#}Qzz-(=o*l2a6(T-k6huP9H!4TAs}&!1TPua|_qo!?v; z-(%kB`#-Lme~R0A;QvpaqEE3;(g%3@kd9gR=!Y>?d{=%?`1UU9_l7FB<%WE)RZVyb zd;6GVjR;vo6MAjG)bw^B1BX(B;78h3){O(aUmNt(UoX|C>NzTTRmdU}y?I;()g*-9 zq?MjI=7C5Xg>&v5+K_?oY<03b#O>=Ips?Sm+c*Iw$`SA2MTUdh4npQ1ggJzMQf*bJRRn{$ z#}>%uPBua%9O${gSw$LS9E6=`YG37@QuJ7SsiNFKXo|LV2hb@+b=fU(w~Fd{@Tp_B zju1I)VdsuniK*=-kjdEbdVlWPEsg-R^r;g=OQp=fiD~H>;Wg~+9KX0o@|Vu-s6GGX zkHFN24p~ZoX_)Lx$=fuGsv%EgOr$nN9SAZE6Z*qP#DVZBEccr(ojXS@ZM7(>iz*ui zCNV(tzCK~ivhP$<>4TFX)JlFB20V7SqZW7@2!#n#S9B&7CrKW&Lzg`G266LMjUtd< z`Q)n7ypL6n?O!8qeXhLZlO)B*K6Px}jhyN-U?*VR+%P5OBhN>N`{Q5vYX|* zzRKsNA!BG1@fCu0^k?=48|AG7DH!Mh>LvY~@dMEI3d7au# zq9WTVZJUA%4cw)2Q|NB}-ud}@wwc6igZ$9Och;PLXS%OJ z?KYpgGt}hN-zF(S4HLu7qfd}5Qvk>ujAG2E9KJsc+tIE2K1q7TI1N!fwn&&C6&6!= z@KMbpOfs=M?gBtZf-Ax-DhSSPyCb*gyuYR_*o~NRRKH6pFG7gFm`fu{Z^6yk%-{R8 zW@yBx9?N0WHU$p^zG`X!w^0_G^#>fdO;|g1^wY7^K9u8H?SdPX%#2S%z*L%6s$YcJ z3Gq0Wuun}n?_3f&MGeDhg4E`I9`GVE)xK6<>4xnlgMKnVy>;R@JQ1P~{S-|@%8>yB zB&Bi*q|(j|{C(gZ^i2D1R;&qE$hqhd;cLc0d!NBxDa@hP#$o0i@SJWW|1bKNK$b^=<&S zm+f+e_e*?_8`-D%ov(X-z2&s8Z)0~_21NcN#Z(j!z?~gmOt-5XHOdMVKpinWo5ZX` z8eG=@r;gC$p|hh(*anRiyRvSC=Rxq51v}Rl@#vM6F=#@5sC4PHRCE-Xzn9+VIfQV*f=ACHcI$)Hafjv0&LHYhf0@d_Z(bEH(@UTqEZ zJ7)6{Bn=lLc%~PgFnZ6Lu@LpUWF;z=v)-yijio0 zRt@K^lCE);YchrNb++GI9_^6(G`b-@gph?D<;lAYqKR1Qb-WM*^2n3!&!6+kGYC=vd^-7JM2wQ4 z9g1u`Z^@s$xmmH12}JynmqEc!ado`1y9;J{r+@gcubC8|)p<*Gh{gOZektQr>V`uOv= z9Mmgywr7r_3yA(YHuekf{pfE5Ms{&anEcU9jmOf_JVd}f`44?~XhtYT}tQAe7r8~LSE-uK%6 zX$1?eZdY4Mm-xU%GD*1Ij!_s>xH~C9)>P~X`N2)1h$_OTUaBLB(tO9qB3xkPX@*Yjw%J8bQx;5Wr46IPd#U zAzbS%^O`|nu+j4`+Vw~T3})0*nRkF*{huBK-k;L;nZZaMA!8BKvgvsUs)2IXpb`^e zzOd@NZ!otj6sl}(&E9CWyNN)*sp&OCdp}|~ZedegZJGo{hj<+a508<}O~Jw$hrVG) zJ^ZU9wS7C!A9_vAszJBaaFMXvN0VcrgYA^&vvMs`wsUl4{0ew$qdOf!nKfo6_*Tct zm#rRzeLZ1yR=8TfI|&WbVk)O>QA$?->eyxK)Aql$Rgp_wX0PSl+g&v&x4@Bxq042swq!x^^XWMP z%Z94@CKjI)hs^n3L^h{TKCWO-A?EP=tuPz-V-bH9Vz^^fa)8Kn_mQ+2vB;%DVpoq^ z*>mN&Jo(deKKFW0(>Nm8^1|-_e%iM5c8nm_B{Zw@Ch5a)mA(?kUP5^Trz!}Yu0TzW zco-l^E>`2_uTrC66uGcHuoNp{-?0iFo;_)1l}dC3Ti~|qAGD?h>01(KA-kiIlF(I~ z9z6S#&_OMX8mqwZ8@kh}F@+~3*fj{Rf54+W6VCUA`cq1&sFs8!2HiwDwPho_fi^xx zX(VGIL$LhZyt{7LGDOY-qF7+9Ve3;yuD#l42!59c$f>F09mI)plYqY9iDr}kNr(TX znragEUb=T4_a0i@KmrBne*xsu1D~b*>gk2hsGusDzq>hK?fb}>p!p}YGUtOUc_xIJr8nhK`^z6A8PQ6@WI~l# zZI#dtF6+6z*W8F#tomUhtYe)c{*X$`{c3%ql}r=Wi4meV1Q3GhkB|IzeQC!#XHp&r zYqd%j}xh0g+0_+{?rK3M;qfA1nx zF8=t2Y3k{G>-&&P-WtQpT_Et}3b!IN*Uy@`~N=*r=^= zyA@^@9SlTV=MTzJ<^32ERgsLQTFHKKmSL`lOmxNY0cj*rLI*^Ygz0rUP%dlISi2}? zvhgO&ty$CY5teYsxB?Q>$#~fZZ{&a=1@*?S#lcjOw4JD9?>Ehirg{atf(4}0t;0Ap z@jw}6cI+R*d0{qP^~GIkS^o~%KaVSJ&mapD7=qI2i_0cz~wNA5&?ZlKRy zeHDKa!SwkBKb_5oxt&(ROH8x|eF-jq@RpWpYyIh^D18tlY2yd(tVDY3YH#ZNZZY{U z6Z}b^jM0h4a7<;@q=}}UO>K!#GNwm;g-DtebsR`k$hmp%>1=F!Hjuwx!7<;SEmoi+ zM6DB&q>5cH!l?8Os}#P^5>YPJ8V4dCeBCff4R#kUO3~5DV#}2~cJ*q>8FOga$Sj}v zo{9J}!O*HQ<5^y3MlhL%#k*3TqJ_TFudXLO^^?;@(K`aROqr=BhzxVyaV8boUk z0tVU%p6z&>D0hcAHyL#{mPT&q zEu$AbCMf_wK_eE4LM7Th7u|+ga^Zpo+Sn8uM|txOi4(VBRTx#pjYyKSyE3h2kOf#Q|?S7aq>NGY zz5DNk#CfQ-Gw^BIerlfMxJEdmD}tLN+iMiZFLhD!Z{qYe^xnx`(5R3=aojNgf@Ui! zIQ6G4Zods3{ubpnkK&~Km0laqi8M#=nQutYdP~f|?X2eWzTdWF?GGwN!>HkfS@-ET zVkxVLC!+~DoXoC-OQp1uPLDV5Jz)0rECdWS0XSl=poQ)C<#s0BxlWUf5@?u7p;}7+@`-;ixlKzYY-0w*cyL-*ePvyB3^^5^A5n`jDE=8* z^A+zIG92Sa;k%Wo`$kfTP2N^w3vzU$brOe2HTYW>RJ_D1?EvL31I(k4WtQ|Hf>%y# zUtV8<-k)MWn~Cm!gy!wkGv!`w$H4Z(LBYQ09^UBqr%!$JW~%wPGRJ;R{N6g|jCHkr z5%;5cY8`w1$9}mjA`AKREy0Ct7YxkCt~N_&x^|9SYwFZ}BW5s|+TvVhP(=Y@G7aM) zys|Vh46?4owq!W4MUtoNWoi1ZUDR;iM&>|Y=a?**UNr2}p?ln- zfdSMermJnc6so!~*DegUNGcCH6V^Nl0&hpzG)xnJvbVoN4M+-D@s`JdA|N18-IO-v zRzUJ@lEf9nabU^4j0|KU%h{EQLf6YbZhd%fm!0g`cG6^% z#hZHP3M#qxXtXfuftyC|?xLtrCdc5q-F;$@)JzOe00Jj0C>pY0Nly`^;(C?=u`|s=ca=(u2ZI4-PjTJ&$Z2Wy^!e>6c}X)*&4n$IIe00WZkXFjf>EgK+yIUdZjxij{9fucC0yeqm@?ejqT9x3; zt<{B@Jc=OYmzkRa3F_H}RgPdTsk1PKnD_Gm#m5o0Tg6WI#}2r+<08Kr#~IjjCH#6# zUrKs`f-z&18(WQ{vHqzOu902U1kzgaA|me>2{>;FOrBp*(w0Hf(Y)HHyv{~EQUmQE zPdG<_)M!b|{JAsgeyejeMl$W!-xxTiDw4BNN%kNUz!?nL5 z_j_x8T)+C>A`_SoqxO1_S1s3zkv{HFSUhbKCR+`>a`40cI$miEoi>5(Ufs93sb~G0 zXDU{~9k?T6wjubUfbv`j50nTYlHUFl>6Pvm~5ULv9u!XoJ} zVifDDKnV)0BWY*a;KI5t`c?LquZoe<17iRJRyE-C7xkw`UL1a|rh{G$Kayi4Yr{&c zpc7x2XUG-)Lq{)tyP5TqT01nDV2^e2ExA}ck$LJ-E@8)HbS<@o2~V+fR#~$PhFUx7 znn6YF7e8k(P?XbM<#uX!OEBn#UqJrIRYzy3Ctm&ni53bZ$W0=JM&#qtT= z@8HX%`f2ZBskwuFhahaG=r^a|gDlnIY=```#6+L9IZLzg;eiXO@-1xgf^?2W}7HJa=T zchFBFh;$Ty$U7TV&J#QIlpGV}NOqdZn!`#&3Tc|zMtr@A<8dbHTvp}*<6jm12hXpz zTVI!kRF6f0G`kOUIPLgjfE=|40*eTVflyES!KQ0CPrz_?yW6G4jWFBTOW0nJUd>v^ zVI?PfbBZlND7g9-RM7ZEcJCeL?Gn3m9Ynza5o-H5gs+v#=_Zeoo>U zR?mRYwRb)e4mOVzFH-m(4@cP#C3^<`9Jb*wMs@d2LMUde=Cq?kehhisXYm6MvQI>^ zfeVOpkXbKXJ7-;8F)R!Do#GbmD$kSc9h}5SJC=JSpAZyz;}nD;%cy&ge2;VcVqL=4 z?BcOqvC2_A^CZm)CmX$?aqsY{Zq%(yP?%QnIV6dbq+`6ekYFElH+YzCK^%QWkQ=zQn)8;kdA>=&){ah+X9M zI+Z6~Yd=efu+tA}BGfk;l#xC_U>sbr*GS3vR5vp2MZ9L^e}Rnz;FYBeZ3|hDIYp^a zRoOD+6eSGxiY2NEr>@kIfO2I?$R9gNwXI8l=8u&;zf(dCR4Qc9NF%mNm30yz8Z1O1 zY!OP5hJI$B;`yZf)v6P8aFUZ|S?l03T#t-WbT2M7VS;~}LGc@Aj>IF9QI>AokbhT{ z^11oJ8;pa%?{yyq3wlf1V?Hq8Ka>oWq`Ap5EQvGy({>X#vLgUP{6^I=27Fuz+4`fe zPvYw{vwSP<%cjSL*mE4cub<7)rTy8t{lDd4ioJgem)L7v>?;bg`3<@#O3b_u8J9u1 zIT#eZ`}=KBsDzt?mmFJEeKVQv9l(o-&nUKBupG(rleRPcQjDq0+y53vHIhmY+>GNg zC`o#Z5^{^X4MNg9F)o>-@#!A2!pw8FE0Wz!tKU;$)D5*O9n0G?Xa60XAU91Ex1)x6e(Kr0n$_vYmlBtPHM=yMKO1q0Hrp~r(K~JEM$RDZS$7?4FsC- zzTuXCPo8}kg-ibEp#J`kpXhO`#*BQ^r-Hwd8EbpCt5=7N8%iU6tY2i#g_iO`6;Anv zz$u1P>EuH%5liaTC9!v6QpdjbX%}RIFHFfN9iHYb^jDinWvvB4+(@ccGK0&WwHv$+q{T8rk6nRA&w zshO%9MN!MFKVj%tH$2$b*aTHV4(#tg?q6+lndJ zIt<4O%huHw?IJisE}f&PX7h4^UjU-9Z++mMdQ)&~YO%kUMq^>v`7aO0RK(xio1|jygVf`r@-Dz~)sKIJ~geiMEZD`Y5 z2}+ZEiI>92f6G8YXqXhvw=~DC5Zk_EQ&0Ukl>dP^LtUtYF>o~4FM=bs091I@?Oi}D z#^4?Mdzz<<(!5l-bpADjR2PFvUqHNwW(o_TVbQrhECx0Bv1F+xvS~<>^g{Jz;&iUV ztoo^T?V|kWW~C@$f>YoSny{k`^@X5!^G@wP_vB%djA8ims^9C8%=>HZE1O{E_|v{o zZ|-Jyv?TU4aY4f&b2RN$3vb1Zc~E;Z+#AtLB>a>-(_^dmPv2#RCBx4&eZXPV8|2s1 zyY>4Zn-I?yG++LP_e%JP0lvrBpHF-jFB8n%f>!ThHNTP)dLzc zx33qUMu&!|!wE{LW=)q^<)wpN!0h%py`V0N1P=F;1jfy;lb(S@s_3#Bd(OCPqGia# zuBZorg<1sq=$6LoY_DMcOnX_AK&t?6&o`+R$l!?w-*b{-iG^e3oi)Exj)q> z&t^Z>cnWhsPcHb{8ZXdfTN*)Qb0yn)w;cNPTJ$NBL!?*Nt>-T7)ahQuP0;Ppr1udl zQlyo>rtzsY{K%wG@-uoE{dcQ2Uf{*eS_0h#Xc#l7FgtA}v(H^AxZ}&jA$Qu&vth%h z?4vYQ+Dk_7u>?^q*%Ok;7t;&4pJ~ekvrZP>Y)&R7*Bkn;taZ|2QSne7*w_9~e@jqV zW67cvZEGc(UBhClh9V}!AB@CPZ=+SsTuv99PRCrGZiS3|Zc`fCgL?Htlq6-=aifcl z55YkC-x&@B->6c4?QvUY=H_NyZq5+S&M@i=@EqK4GQL^Fxc0Pimscm=1G3(>OZ!6~ zj@}PHO4tNUFCUF7sWoZO$_@T+CdV4%lB{!^yqR+$?*~>FqVuP_o&DtW;qVq}`r} zptd#d3Q_e%tz%d34L|?XXT#%<4kMt*gfla~__LgbrX-~>#6cTkk*4vUGUwmy`#7z^ zxofj9fPIwse6}+l{x>^Bo!RT$?#awo!rnDdW#>g?y)I2ba5gib2Th$Q1FE*J%O3LD$i&zfMJRc!D zu5xg!9eJy3Yc6x_wn^yGwl4VTTJr2;88<(z4Ae9`>M)U%$Q?R=4m|v3X=9fHWZOAG z1V>I2#gswkRG6#i%ue81WC?`mc>ss^Mx@%4I3pHeOPYfw>2CHKZuXOS&c;C=-KVC` zrx`5RJW;)iwF@<$!&rb3jPg8GANKl{s1@%B)PR^JaHPoKK)MayA}vyCmp3~G|3*h9 zkLu7O3P#*LRN?*2YPBtmj)*gL@NA`;||pMJWF0}|q%2zyoY?YAWQ!9_{s zTPi@sYI-!f2>ilo55J}NOIp+;b(9ObYB^$B`Sqo1$g46Rx*cgpU(|`J(Szci1hj@b z^l4f)04r=X)*<0eZb zt5%{lko0S}J9E(~BOV{&+k40!v>h`yO;Vci{~>PwH`ESXBPG7?Cp}h*7%dsbg7B7 zW3u8(cfQ5+6T)1?$@CLPT=!qXTr-$ zc)6ty#sXf?MjZ<`i4vvQq&#gAgI#edyuH$I2A9p|*ThZt*}F7A;=`@8#uZknB~?C7 zduHtgq!t{}&6z_gc&<+PzpskAQG>>!3fJ1Xomcpd(4jM~^lE0*yB~~B+jJPew)Hu- z8gV<%tU?-v^zj0f{o*3k0(W(37WlnZcR*1*7Lg()%ZYx~=I)7cqNh%8o8!O+N<6$Z zovBJMn%-Ipsen<8V%!ZEonAPYYQ`8A{TFg6C0b)%E!ItdgKo`?0s#d%fT)Wx27Nlt zRO{Po7SIEU^c$;i4n?^}G(1vl?vfGqVEZZFL+Z6_8by}=;g)W?Dw)iXydUis|RQQV`jV?st7B(o54Wal<&TUCEu#-3Q8WCQYK@Kl)@!Ysr#1 zDWj~7U!Jse3zO9gYg!+po?7pPeOT}Ueu~^$q*%V|+1l42{AP`Nk@$2o2zevYYS|T{ zlaI+|cA%&?_qg~StTc7Y81PE8JcZ_rHK!3l9q|>QCjt$0_9pg(+;@oe$jS>Sn2?Px z%Fx10QN((R84VR22KgPlsb%B{-tnqF3@E4lZnEcgSNh#b@_)Gc>YzB_X3600i|gVL z+=9EiyGxMG65QS0T@&01?hxD^mf-FdJoxeM>fQV9rfUD+-I|(T&rDBue)$O*f^nL| z>RoG-fca6B9UAe&v66Gm>FLYA+mu=||4~-IzY-sX_?QuhiobSueI-3kL&ZRVP|3(- z5y|f@&-15v{&EH*eXYeajfvT~^nLsP$>*-G*?g*K655xBL5lwj-|3`#Stu9II$GND zyHuE{@~rY56LSiLSN6B)3M*l~TwYQ2TX;O1%91rcI~>x88^hM;H^_=iJVSYPI1!aSecA zj$I=g*}0;`%W^LDZ1Y?`oxD>h&y5r=rP2BrF4tp^N4H{tBj9I>IP`}ygsXHCwWXAY zK=sGKc=O}sq;?cfv(hp#Yo(0yopFt0tmb<4>lTLYy^2ToXxc#65k8BvPhIwYyC})}2RPymAUe@#^bQz|?faus zg%B#;P*0Gk)4HB41ubdZMDYm3~)x( zx{9oXUg*;*@v}BhjvwY09^ed6K5;=KmT?Ucd0Rqxe*)KdLY&0(jo9y+L*NVgv6C3l z#0OK}%zpr(`**aqq+hycj#CuM5d^HxH55?yRuIK(Q^DE3f?-utY(61A6A$C}){k+V zxVT}h?vVO7qeXvuZ1k8=rN^tUL&p7xeEooF{GV?E$Ky55#o7IjC5r$`1r6!#oa?cV zYoKD>(vJzl-Ui0e%l)R~^)25+o{x*wW?Boz|5v%0G2iwwE{2~ew!U|~BZ#2CF%$*) zKHy>OlK-?Ea(;z-A_==8%T=@Qgzla4PTJ!dB<*mqjE^J3JhtL=(YVUPi##FiPZmY& zt#1%5LEm*DpT3#-*zQAX$n|W7`>}9Ik&`;V>&dU32h4>A@<05FC?o)y_nD5$@(aG1 z#3Q|*;W>WDjfCY1>Rb~csxm;;bhov_w&~1q2!PpCxD^$Z@>G%w3?{h4`)dEDw%5GMih%d3iLXX&>OGw{}ge*1^dh*phE&^uI zqjrl^-(GOaKPoI%eP&U-?1+NM@bF78OUmN;x!Pi3~2 zR;xC2>d}x{3b9IlccskmvM~coWUOq>pn6sWK~}37G`&zGJTcDUWC+pb=#lql{=$@LqUI0iqfg!Xc{~% zP}|L0{$?T@s9JDMk1d}_i)4#k$j!u1V=*k|=5@p*MUAvOi}~FjBf#5nWV-OhxWHwI zQH`nK#a#zwGW2gmC;EI59$#gG_vEbRje7X@_+@&F0L$(b)awp4wz_?5IXLUYXV(tb z!N+If8^4+0#^Ku=RAgAPA~qAg;8|PS(xFQq1rkBAnWG8}gEPB;&wIQqKvIR=F+pk# zt(16a?Ap!ZKWDq1v5$V)tIV{^6clYOef}#lh`qz!?|7_ltbeshrQb3TM#HIRi9`Kvn7+iiafBG$b7U2}sm0(kMy~R@c8X|eAwe7@)FNQx_g_5FoeJnoskh8t zg;4)%rbW4aE~QR10}JWd_bILYc3ZME``|8z-}JysWJKFUSh319Uuy#``*pRaDKl^N6q7$jagYLEWenD43b1^@4{B%Re{I z8)AewW`S{O9#$giJ97BADq?|^z@_$fOXR)@F~kfjVPWJKC_U_7@~|GheTo#bHmS2$ z9Yr53kjumY_BfZng5)VR{jcC3o!Yh7NsL#=@EOhxO0f1HGc}`XprI2R0j6Ex$$jKH zyKUNb5t4X7Hf==NluVJrPlE+Au{$-SMxKvpWcw;eB)`2a4ZNSw+2y?UaK%V!V2 zx79OGmRr-aeGKPT#}VL`G|=UGGqBu2O}4o($N0v)aQTN%(U;3d-pWQ=L&0w7Hf1ueuwYG ze!U|7MqXzTLK_PHQ}`E~z^9;b)`Q!(e?KZtNtosGo?AOux{qeDU?`nf!&czSDg`$j z0dvQ94CMT*;1FkbdF&DrhmccTc#fuUOw8|pO_58m5Z-4d9yJbdPh9x5@>19kXZC(R z8h){$hkZ9sx*pvnOm7jVomUvzC1sg1;?G4FC{VO zWlDS=+`V7Ry7{?E9NXpkisp;&yZ?Y%NK<&^Ldz$}CLTrD7fod`6SiaRvinTP$O%i6 zl}|jpjL50m41@?-x;Uc?4kP+6o%HyUfHqg5=S!}2eyo~6LTJH=$^eTc#9WgWU#tLR zS$wjFc|N)Z*v(T1_cLHE*v7-x;;jUw5%L}%UP=F1|EDPY!|JZE#K6_J?*&Oil;rk^AHDz zK6B@jvI$(k<`+`$QHU5Q7tDrL#s(Jrn6>j{)_G8wB`U|VZ^m|yaU5_|%o$j$%ii&2 z;kWgveKWcd#6XJqdF{s!?FTsQ$(3gaQpEBmRmNA?@O6k!)bVDVEFegvK5NBZKMxFh zbkfVkDeMhccIy3;sQ4jYdWA#gLfzv2@aKJ7g)dj}kzUP*2TeCesPuV%6KBIaJ=p&r zsdqyu{qSIibB80z>;`j*$Qw;E+s@l4U8ncWAq~@aLT$tP|8rdUzjJ-xfVPWs5)I-U z-;@1Hd@#;OULs^x#n<@QEToAu5QzPD!ph?$?^zh_(oC-!{T~=If5N%!oY#IQ&ez zg^1{gR!olM6ZFH5vh|uoZ00hCo>qq)#$lef7~-c)@|~T9gw!@CEv<`)yTul~-F`1D9~^JSRev14jOl(P6pfYM;>GpP~#HXzJ&;8{}qhK-1QFW&G09@XQ!dUh z5~VB>wv?q^Rb3;)za8F^8oNFU%4v>!v%eQzHSM;4#y2V}D?%!$zZoSTQh)qsK$#>I zsf4(hd8%((+?QrZv8JZqr=1L(gg*()p!qc+&vB} zdHVk+cF}&3eyt!k?w8m)&QTfMOwLy5cD|D797gE;?w_wR=3nq)6QrN#aGQ&z4>@|K z(NW=I1TQE!DcYw6oZIo=N;pe{PAVvE)bCw-K~Tkvo)zTIto~cw>If-HvUlF3y(z}{ zf*y6l_M1M3~aA zS(7EE%SE#Se_dbFgF9wOp4CpDn&x(zA|^>1qI9$H%Vt#*9j{HtK7KuZRZ4xVI!4d0 zaHGC5n&2YKWUo=&mUQ)t1<@pPf|3jMKXu`TE0kF)zD7$E2QskK6Drcwwu%PhexhDr zIFQ-W?x|I50&b<$pv{i>2(+vW!?6vgu#vv3fDhE41!*E|IpS9pzIwPIDVsi5owse>WvYZIss$lw%1Lmrvseg^HlTAK(vleA8Q8{17{50hL{!yD@ zQO9uYzA@ZPl){A7r&WIuEz=wUwqNvdfzW%^d!5P=y$D{w@|j1@?bHFm#~;)WgWlqs z{m^6^F&$@Kj|XOwCdO`~#Nsx8{S5g!P+FOAbwS(FaeX=r0FtVgtHLIPVM?us8N#jx;WlBi}s*C0%4KXb4 zMA65ME)lBB70|ndXx_Z7U#zSyJ)B#wT(n(*vj^uA9g)i%$0&@_2Gk@0gL|^bKtve} z#cDHtnNOjbBlVKC=?+b5QCTHZnN;5gw{l6amAy~o?=;kr16>*^KWS;Pb7Wbd9^48? za{r+g`W=2jW@JssYSLXa;#}oQ?tlo3p`yZ@J((@7FeT$$6C83jYEeK<`+kO#q~b5m zMaY?{C^u)h^|o^)T)Fuwytt?^cQc$L=vlu+iGlHVFDd*#V^}BZX`B15ACxBylFdQ+ z*Ze5#R8iKCe8WpEoM#b-+{i#U?OZ>BrO4?h&#*+$A+nwh=aSrAT3u%eXLKTnW1A$#U$DfaU`c;Fhs*!v}eF=xaeWc)sIN<`FE+rLk)+iuov9nbREWAWRq-TZEE8lvqC@D!R=6~na}HE4cu@^`Y?`BP`6&OO46pH#TEth z1?_FLQMoH}j8cHMb6&Xw@dQ#;G4R>3kc>Muqrnc%v~yJFZ(SIOy1oLzuqp^rNux%R z949SHt;ZpbfaTRCj*lx7coI=i&xo*LB-d0f#O?5$(1}2hNhFZRkv}cKaXjO4e;YEG zgb(-O8DFJSS(BF8gjX%@clhQjt=37X{@WsxO^+E<{O0ypgUt7ZYG;-JSoC}jwkv=W z3usE9(YW44P-I#AJ~JEtw$7a9`O@5z~Cy>&RyzWHp z4KfGzkg<^GI=l%dfDw}@5F?WRFk~kY7=cdOzj9>qHpOe|T8!3nL-dPWoJSy_q69(D z>x|P=b~8*&u9K204@Jz@PgXA=+MJcz1rr2r!oWPtGFI&$lsqzqBA-VG6yi3ckorFX z-A9Yxd;zxr`Ex&&@&&qFOO??^3Gt>^FgSh~XROJLi^$Q1pH^w-g5P>#d*(>E&#G$- zlh!nKlTF#0f>GM`Bt?!i6A-XbR3ic?3?#K4JGN| z+gN1ew+7hx>^;TN5kJTBDUy+@laNxT-ZOyQ=9kvve8CUPu;0|_HgKP*DbTK=X?IO+ zYCoY`wwdxH9SQs(b*p1?pWgz*cXohV%qr29K`X@W?&EC&dTVT|!PN0Bb?QRU!;Wdq zZ56=1tbiW&u*4C=p6KC^j@bV%BqEx>xNOKMwnY{{Wt#wJTD4vLIH|~(l;8!O*YsiI zNq*I?luWW49tEB*W(<{DOcE2zV`j&g175obGJ~1T*Loffz0R0xfBx}CW#BElzi|2Sv(x;xiN9PsooS5 ze$N@bLrKbi`4^|{_0rt;U%CCC(L+muKEFYl-*X3?^(VisOo!U^dxWX~^+VrA_|@O! z`Y3)Q@S#SQmRqYPvD}<-iau*a!S}*UR8p3${bHn;)HXQa^p?b6X=0E;UcTy=c36i-Qnsg5J<%}M&W$DAyk*&;eC?_D9bZ^=<}HL0LcVfG1jPBmN4^@ zsTn*Aub~emRyFcm_EaU1M@wvk3S{WH&x=yZwA&h8eKQG_r@sO~{RWqLQ0D2fE7HT{ zw{wkm&^gQeFgW#7HGCcJeO{^TM0}JCgydg%V2#?@+`CQ{P7pO>*n83Ry2KI7DwXUy z&|L@k4b+&-jk|pUS*WhBgV^dMBQ+QYhSOTVXMiJ%Vrk3n)bg2D@L@M@kii|6wbK{a zs&54Y8vejml*g9EU#p|ez3yafE+NfAi=uG$LdWXscT;eI8)tv=AbYN|wZQ`u7cm&+ zDQ|jpN-jus`4OI4_+1Jy>}ArpFc*AET5@jAy}Ggm4$?pX3b95qWg|^9#kYV2V5NtA z2+(BXM@0;^T*8R*pM|Tab>^1!<`iUxBC00+!5Puz1vY86&i7SAbLSr_3)W3T1;;jJ z6k&N|2}Jbr4~|g4NT(uYgO&;VJ6|J6Kv5%<8vaRhO8ddn3k{VS!#HwPrJB_lu5R$) zqS5E^q;T5^Jwqr=qS&EjrVvqNF-9@2yO>Yk5^+A!q|Mq4v@`L6)o0}xc)kAd4BpY$ zCjE9$dqnsA7`u?n_XE}nNNg~ik3Kf`D8 zZ>5ZXD1S9#L4fo~3$KUEStr}I$L`a;AX^quD3vUVoK zLJyCEmM+z$A78Aa=8U^0VB-QwJ*n2 zHx~OQy~*nuJ2(DGekyEy4f6f+34Ee7?t_&uwXvOt_Q7qh3YEG~Qr~Pfwd#peK@;!D z)N&2|jUA7xE$<@1G8$%+G{>+^yURYfa(&-noswzgmSe6&JVBP#3RHyOUY|@0z2pB5 zkXy>h14mE?xcERr78QeHk^A)L;qq5&uTR^hL9vr?_4OGJk!Xg@>W%oYf)iLk`bmGMgjFi*!Y%MwRtd=&SM%l9|H=x)sLIr=O& zFis<7wp&V?={ScN$?&Sqryron?i3Fb#QWd(-O|2sGtk;+Ty0I8-JITs&kyDrwKlS{ z7lZeco}{=M@e9ifcRv}bzj`Y%Ig(s$Pv-@P@^({b{-iS8j}Vu%!2(v7@L>K#3i@&E z5yHszvmA+0=Jby+-@+TXnPx5#owTj7bUp6LZYOz2POQo=wHS+j zSlLK8;~yhEcVOBZLh{$a_udZw8~h@EIx;0B&EFn^ZsoU)w5m|*@-^MhbX5gd!y=FI z1JR#1o<=t@S@Jgc5il_RD~El8|4R6c6;C)6M_VdzFx-#U#jQ5K53Os7b_;NVk@eu7v8Fu4`x3SaO1;xJq7QU|L>N9-W2b zSSxq=HF5&$Q)+u_s;Spo=_Ts@LnULDh=Iwyb##)7uumN@^bgtqf>=Zyv|J1YeBrFp z31u}mr2SJ4fExl?KMQSzqWC6D_aST$nM?qLH6w7bxZu8@F?>4AD(`H}2R4eApWEz~ zG<`aGa{8RQI)pF%&>UKs*`yC(sxg|WtNLncT_Y^F6_ixDh+Iu0$1$u=KOW^m>v_6C z*j~dh9y4kw&o$ZBHukvX9nb5@=5~U39`r-5o)x~^0O#Xi&8~_Gi`FvJh?A^M{I-y` z*l3O_NuRRx-ACWhP9U%{bs;HI95sJLH&pWjhtcjdSRejjG)wgt&(Q7rV;Vv$9P07; z*Cw_l%=Gs~s#Sk?dl9$Ri$(iQBT?Ucn9GpJ}hC#*2eFC8t+b?i6 zn`Xs{4*sE_=7egJW$#lb7Bf|-Qq7gQjUF`jc| z)3K}O?O;9QAt5?n5ALet8BkXk0H?TQ6R+f5x~>?J53;)&VUguJX0^A66j4QGgT5xS zf7F~b+@9z4&Gj$L)M>9;qa+m-Lj)fM2_O~79w+-6jRIRJLj}|i{%wtK~B8w~X zW9-J1%Z4n0Sx~tPVcGa%HuiKb69Y3^O8!O{gz=ssYSc1d%OQ75lv- z;6Kt3e#z0{A+37QdAHj`YuMdt^_7eaJtR1~;EPr44{rZER=MQwEoKJrB z@5*|Ql}k)0cq{C7)dJ!)YPhy5-AW__j!ns>yn~p>is|5r5!fr=2Q}i2?BX6aAC$Gq z06G?&5;Jk4Qkr}w7RiE+4<3|94m%jb1xl;zf`W~NB4g#U`RMl#Xx7trkwZU>c5{-% zPqW$~1Qu-VLksZp6U+Jv+G#9CIZY1EyFu@L*k!-5Y@w5=X;8(BQY3#qpNOFL>m(^; zyEwqvgxaNuhp!lb*q>9VXBg@~)pO8ASp>03f2mtc`y!VFD=Be6GReMTsukN5=3?l0 zOR=}z!C6I5Ux`_2DA&GaRTpB|wMFmYo*zg|3{iG%GG5TtQQ=uEr4t`E^~-)j{PZ8kGXw zo+h=maHZC^&g3n$w!k>>1BrdUiS_3KhkP}IJqYmIL&xQs(TY8}h|9UM$-P7N(m))x zbxZHBbLL5BW?rNZL%W1Zt)|`SdU~}$sE)6AgDC?sb1A8b09q+sB`{4Ob9pcUh$+zM z@{c2?w;!wVY5SMKEuhP4Kg+sA_5k||!O58KH@57_^3$=`nlenabOMV=X$$C6#C+^t zIoE-f%UrhDbqP?+PfeKx*VvSL1(f#KkJj7uJmR{7avJ6LYuF;184CgSTs5{Wx!gKk zM&qn*4$)^+@kX8)t&!z#(nKLJ!nKct{rbEj?ZfkrLPMv-!q4IHBkwoiIVtIy>PbZm zYG-*!Ktp-WV!+boD^5+%D^!F3KY_V@wB7i(v=JNyGWU@GJyY06n8m@WDt~9|`;o=vl8uKq+l&RrnxvA6Z>`v;hx1!L<7g9@p6`5z7_}SnI9*Gx zj9o)EiKUAk-r??OV3c%jjE)6U!5~Q{iEV=jV1Nqb&Z?*}a;U3es6>ttBSyoE;nuZa zZ!ekQhWxpRc7lSHZv(h1Q3%Un%N%`D17O2nC@Od6FwK@;*r z%ZK6-@)QMEm1RFdv|>>Kj2sJEtBW(6g=%AWZNJIDFYU(GKVZ_vxeG^W&-JosspU{( zvdhbr*gEld?UBR-6|Sg5MBVQ+dBnC=mGx@zLhe(>D;0|57$&(#Wq(ZajiMF|ERxL@ zNQS_PS+0l?N%ajyu1+WZ>M(olub_e#dy?3jy07!CyEo#V`K981&c@rFZ^Qp>bL&qx z#U1$d7wOpr`DHGC((?lk_xMwxi4n?N(SfRdCvSa=gRHw%b`SMhrfGZEx-sR5{i}e( z>u01=m=TZ|_ANg#K#2%lGmS=l!N!0Ch0001kF5v*m5DynG&H932Y963aDF!q9#{w4 ztlVp`G~1qkl9mfXr!qfI5s<^ifwlOC`BU+HMNfg32xq3Khck>w%=C-xjoq#+nFX4b zmV^YE8I!hb0ev3;j>ui5qM~m{wy?fpq&}y;hWp&cFzZXfoqwhN20rFKW&HKPGQq6_2O_nPmxSJ7xHpBRgIS96=~Oj(*orqGz9{&am{`nA8|m+f&#cDX$H z`?ZyeP359tWE!c0P&>uQx5$QTncix}MWb;*HhDz_WNG0I@>ie+e<;?{0;iqDo%(uMHs1V#W?J8y~%TCEeFb$ucIQW+?$=DUO_h)?kT!-#_0e>v{v8cwrIx+C@+BB7N=lZ35-Tp}lLifaa_V}s(!#WYWBs+7~z zTBInpB%vGO9VC)itGaBjVPC0^R3iz7Bcutr7!tU%(U@WA?fX!eJ@A}aG0ncAj6(YE z_yaD^+BpWIJZS-)#A|QILKqXuhWfK&#!7BIVHKYKdad|FQM!|97VXO3t`xcc_s1y( zB+JC|OAO57ziBL`S66VGE^6eD=CIrpgj88|c_us>t)(fV4xnT40Fi=TD!?-k(xhP~ zjZ~H)V=G>fW2b%Qs75B0vCCN#YUTQtG>#!cO{^jpNB454;y<-Ie#o@6R8+|BNWz(` zNW`5+fe1b2|E@AyYTfy;>py+;SQ^91N+|SN8vM}LZ$U2DwzvHsaTU6?sQ4}@?2+X& zVAA#8gY83d%{t~kXmty4&Jj~@@B-E?L2dfpLaBUf+RK)BC_}mY*6YYuiG@aXxx9I$ z;4j!0rP?*we7bm&G>BF0bPc4xG;IM!gxjVI<7H;AT|!_j8dQH;a=1ItN~ zGO_j9cfQCQdxoKiMD1()t;!s=rmNhKc)hi?fB;Gp>{2`-FJ-P->Rmf$ofU)cS(Cl# zFPKA6LEZR|A{8n~ldVUw)LS zDQRNz6|>6r8ns=I@Vk|n=gxf z{+6c=HV8D(DOyYL3J=j(pUPtyub0%*#iwy3a0CQmL(LwK{(xc7uN=sma%^M4NbvG4 zAo*mZLCDFw&{Pg$6n&U#fpx7^Tu@r4EJV{%{M`#F9pY+)YiTCw;1yq-Q00He{zUGN-1AT1-xNkh ze(u$m_gjSv-#3ghb0v<<4+2r2C71YE7;JXl-@Og*BIJwrBi6*q505?Hw|EbaPL}^l z#4EIZzQfLbfm-{c|H;WKVz@vJw%7eae}#W~zuh65bSmFmLC1iV|Icm^m!G_7raj!MAhhEGXYTZ`VwlA{Uj$ z^I&Kj>$7T})$N0nR}P1wJ`%^}hU4lB(dv@mIDSnU z?QJwEM(hBif1E%yIiCJ8K%&nIEW&K8{7KawOBKVU+onfXZ3DqXk#B4I;BIT| zW|q)qQlN^%7HC|#TB=K2H}#}3XHpkS%FC$AF^oo&z~=M_4nte1nQD$OA!ba*Wyp@w zN5Pk0)PJ3v91GIQYhdKq^9bYj4p7vnI0YHME&5YG9rwuObnoV6`rnB-Xc^qH`VTE1 z_K4zwXy=jUmvfFi_U4jHG_obLk=G&M!uKzW*3o8#$uy4M~S9!{hGv(N4C-&OvL zT&%OJ&ydBWHem~FC8)r9B#T!8&Fd(A z!!>^L-oVS7o=>MPY(g98_bs-;5f=*g>zc;mTu@T`>Nt9Rf#$`a@7XKlXlcZyjrkRBfxID?sxs;UrCU+#q`4D*ELzo-+sk%1xc(>eZouwPinT zj9;|j9!Xuhw`X1FM*r#|TiY+c7Y$ab>EILagShx!x}_4Wnoh6+YKiW6uD`DS2D5w% z=i;BS9*;d+gYEcOBApC@W7{75){FDsNLCu{CVQG$R7BRZ07<_}^Z52ysn&fPwlh}x zJiH{E+JPKdAw*`NitI4dCFNXtWpgaMO=e#~%1tFFE@C6`~H#G|ifW#3W>__B%H&r@e0W zuz?H~=DbfkBZ&&tPKskC_ShxmR|pW@dO^BrXUHk{vX@fm9Rj``4NbnHnBb z?UaCh^R_*H)`$>GEz7D{8eBX+qC&DxiIkEx!}SCaPw{^{eD|Yt1M?pj`tPtpdG%#z zgVE^|toc~DC`Fh>bfr0YBz)qZ^L`OcdXz|q97kNgM12U?PN)_AGw!y$Jv(gKl*EWP z*!lpU@!tu^ZZgRK2G_2j{$C&(UyIhQT(ndfw9v!iBlx6H@SUb?T6`m3WJ{LFuUv$N zFrI*pQ&-whY8n&j54++*#_lM?mu1{>K?z}(B3a^Ad{H9+A_%Dv5wnI2wghP}TbWrS zoEv|Kp^1ezsdNSwDB&C;sXBJ^C2JlZm|-8h|Et1s^IuExQ3EuaTSA{4;a4s5AUyAC9! zM6?gVLk+Dct?=8(GRzan7->;EuF=cW4C#;6Q=|6VuglFh5)+%|T1{?pSKbj-Stafx z0yAKNyKH-V|56Z9JC9I{w=3DIh%6nMqUPYuhbd%!Xq z>B7(d5I8*ap$i**)F>Ei=-5QXh!^^QsRzT~3A>doV}`SL^W)w~0~^a!-tjlI<2?@F zB<$_&bx(1J@gHPqaf~abBX<$YVcVF>>Vq8Fq`ExP(`Dk->OO%mwM`q{PVguq3Y4Ns zXn)cDQ0V;{b0BS`p3d#;{oxXZ2>VlrvLaqLbXs?5srJjyrLx2Zv^v(4PMI%PjL?-@ zs4juSzThHJxlr~Jh1Alf4H}#xQDmgnTiO10ZBvVJn-n*^!yRM`><^DkePS0QcgsXu zJ3%QWJ3-(zOT-C3s2lP{c~SC)yN6ww#wzCcBm)sxc9ONIq~v)vQcf*Lubp;mGiBE# z&ek7i&-NH$s+o|7yYPANh}TB&`RQ~-cf55;ip&Mc4py^V z#@oxiamyV^6Zl@J_w_W~|M~rLSxEMf&h4A`VrR3IxqzgG0(3;|roMu{)A1g)UQ8imOK$<=aprMh6 z4_VNZ>Xj$8(2Qw+A3KJa)KY zHRLFrHG|2ocYn|s+pIh&qwuDbdKuSo+fHWRa|$+kmRl_;DTZ#~VS|!ECxs59&9K_D zCsuo@ zzIlk@_S<=mdhnGRYQO9bi%>;T(UwwuI%wb<4MxQ6u&IDez?2VV$1_Tg6GehHq4 z{5JOvs~*G+7>&ZO$~eX;ArYWNmhHC~+JOQ&JC=Ihrc!>7QwsUBagF<$>t!eVb5&DO zUH)Tio!M*_D>Yv$wS!3iu-Fq^herdepQZ}G*5kjU58mb`TKph2b^2xM8hk;Y0+i;>z^ijn~6m*ZXs0w2o`$z zV8resfrW-~MWyo`C;JRH`gR43qTYO|>t4mjo&|fgbr0%%Y{ znwaN&hwxF9O7>wP{S>ZN?@+e)aKy#)$8{?-4osF-_0BJrWT?;esws}Ov0FBb9m24x zn(WeCMK!p(78xoO-xfJdX$C}LM*IlsZr{(h!dJmfzXA_ zvZs)*$1e=UqKx|~A`mxFFS^)3*o#tX5o09_nxV7P^y|gu4>S^XE+5L(CrRd&kIx4% z#yyuHkfyi#C0&^P7~>fh`2b7+_JPo&w?aN&Syu4#^$ z`vf4p8V(LLu@nbO>dINH@1;}i_R5H>CwcOC~gmI#NF{+J&`p&}Eh_qKstFsM~iX_csvnFKc zV27MD6w3#(qBozZjHz+_UgAY8_{pviF1sfY-fw}!tio1aZ$UPXFKN%m+gD!yRpy7k zpo;8;zYzN0Yi0l64)BT?Q3c|2Lt&kjZ}eup&_%%Vj`lG4ENCSB)k<5JYre&T>`0^D zLkbh*VyI4&W^Oim8^ofQcn(($2hfwol!7%wln-#|-A;3XlJST*xNP!>EdMC=QR>K_ zO#yk=X)hM?j)UqVe7xabmOh{NWt4Y|8Yy1d^PN5Bxo4;wvoFpX#CNOnG~ z^SSEP8P?3`Q-yxqpF6pENdgc;da)jqrHy`d*4W`sOhbxr_SGM>vhJb*g!mLjAtKB2 zvDQ+;w-3LQRjtKZx|FCROL}~lkW63a;M!F#h6gMb7rIx<=&2o?mn(+vE7Q@jl)^_c zUk_VGXn1zN$1kc3d$^F?%98L0+4AcMgvs2RT$UnRnIeRCSOdPNv#)TH@Nv!Fvm$^wkU?Q>u$G`lP1FeatNGqe2 zft0fESq6(8zC}hg8|#%-NLM2eM90j>&f+11N+d6=eubLSDq?n7k>d{}EjF z3{Fr-!v{&YgEu$5ui)?>m1F6s<$1~5ty~J#?GQLVe1B@VA=@p^8& z@x^@_S0fx{b7^_=I!zAC*L(MjIK~pkF|RJ^iTDgnxG!Q8?PIcdC^76+APMyvsO^-3 zQ{oVp6L#YGwL0Ej={hR4c`VkY&q)Q;FN>^gZ5~6qxhA~i7HOe z%eQ$r#?C?&{ZKXoOqN>)CWbcnj{j?CDzC)Gm4Zz~QOwT69v)-`)6urpPq*<*^Km>R zehmYg$L(&#$i|gTWM%zKvi&}Bg$DTWBy({9i*6D`V|H|*z-nhH-)$o{@c8CRnCR_| zaLVbZ9)035*;!?AHSLKfRj86W&AQ{KiV~MDG)*|Dso^d-JWV6{T#3zKSW()1At!L( z>?zLxjf*LRC65@ghDoJHa{YH(Ncn=>Wb=zf+qoM{@>da>c>J~e4e~!Qs#UQX2&f0} zR@)J@vkUP^DdM;0Z{mp8smI^aKPmjGCvwrkYs>C%D>|UgqhM_R;iiBo4U+VW?$M0Zqd)oz*Y`xoE*2i}PF6u%B%6ezV; zHMF}^MZ!YDSelabg1Y<~_KV0^{;5&kIr|Ql85;n%q;&Grtgdu9l?~a3_t4?AS5rG` zfK)l{fKAp4*W`N)Pt1_gyRUf3GC7Sz!7my<(Lh_fJ%WICTh)h^#@C3F?@-MIe<1hO z(EQrv<6g^gwtqUyy8Koj&_x?1l@%xqbWRZn7NG5h&qq$H>sB-aU+d!H4h-`;^j(?T zs6!;>LjiGrZOCC~>8EVIHIV8l>$H^PM9OW?Iaas{E6EG4R_T3}h;Wtv42lHD7#dN{ zJG!rj@t*Qodz-Cx{JEQIvXR@~Xa@y3+z3A`0ibwdevO&O4B72!%6!#uA2ltjh^m03 zXoc3L@lWfqq-(kkdNmc)*c}cJ$?j%IJcvOnORcQrvOT&(VL(TxACbZ!cy#w_m@K@^0XosySClIRGrVB zKDPhovB1AVYpg2TI99v1QkO5kZS)q}!%u0;eIV*u_OO`f(0{LM8-96qg^UyF~go+GK zk&cCzFe*j1c!7~}7_QCDJOKtN^iS#wNk9{%xN@camikm($TGrpbKz%2i%IR!=eROdIR(wgR56dlc`fF$`$X;=Ma8NU;M@;xWML zgYaXD@oz7hN?(^^X5OiuhMDO(rN>dNcu*5RCCw&C+G3RoU7MX6Dx3{cwOtuJd?7Oo zkA+{de^|W0h|4A6-5~bnr4{9}X}DzlHj*Q(*2v18%ezeKJfH7sd;IhqTVa0_(*`-O zJNI98b{f{?j9YQGH+jwz;pvNqw<^^=7U@vit09SB3`lSQPiT|duV%$gBaC%}>w|=z zC!gCUzqDL}zreda{Nwp1!D7&{t@37M0npWI0*seej1N zeTVrXj<88hl6_8;%uNtY*Y#@mIHr#ox8aT;NUfreK#2fWQr`99XBFc~yW0}X_AMgQ z(Q*zYE1OzOS9=i?%ED8WWs@iiDPKz3=Y#$Bh90ARSAJ`uOpTsrs0t?DYK4W9sQo*u z(gd&whrDma(42>=;`743LaUG1?YB^DWY`>@I24YDRR7rzrVtV zYcc*m(#5~n-)@+9Eojm1B4W(2R=<8*(rg;N0&f-xANHS9u86L9s+N-W%_D^-%Uneh z<4X_S+PDSE>{>9f zVV5fI3qcNYQhlF74-IQTQFqe+tFW&Oi>q1I1w!!P9wbQc5Zv9}-QArG4g-PU5=d|h z!3TGD50+qqy95S@K{5gE@a?nrxpJQ8)}Qrb*7T~bs_w3?eyjR~OKE1`+5Okc5*VH) z88R}g{YMooVCTIv3nl1D9R`m%MvyAOL#^vszaS?ktK2Cr6l zf)69Ne$?~oHr-o^DZG;GgcTV(n=ZevGDQr8gRX4g1-4J4OX}Isvl{~p)4tdX+8Tb3 zka;<^+zl#eFq81H&Q$S<6papU0yR5SVwYfW*h-j61>^vk&pZRwPv!Ja%>rKwP9t~xO8VU%Le)0nyx5H6?)AzAZKMK{)f_RU<}{Y}3Sth{M#7F+crm!J zkWfF6YnmQSRnFtlMadMnY+WM*{M#k-`8VO)cfz#fwwsYTC*|((q!aGOO}o*=s-&#| zUNj0z`cHH&MqcIGFohUgFYs+}K98J0u@*20a=dh@EgY4AgDfdT%dyNHD`f97{96wL zqP6b|)?AJhXyukMbaf(5)rF&ci#%15Np=lSov@qEbhU*i=F`0(84|b{%9U?8N|f)x z`m*R->%7ibMz4!>;AwnCMatITAW{os^kiI-kc*VU9fISH2SzRCm>RJS-u0}hylzk( z6{R*+?zcj;G)#u~`Lz0A8_|uHo5NptDkT|Xgeegk`tf@Fqd_quz*W3R77a9JvK>Mt zB!TX>^N5rYapC{#P;cwv^~Z|CkzP8ntcQ)o(yZC}m7Lg?Wd7K;AWSlo&ryOEvXX?% zKOi3uVTb^)uy=$?BZP5T(ad2nwa|%|BQ}!7N@d@y*2*&w_>%P^!vLFd-9>C9yZi6< zFTXOy*DfTh(0MA!%DIBsZt+xG%F<29MJ6vhznQpqd#kIJOcn?0Vw+m<##?`6T3=j; zeF%{zbREXpJFz6F;{{mq4rf^YHO5qVDd(Vr=1KYnnbh@{D$4t%&jM8#()@^y+RQ&( z3bil-%J**Wi}H`~pi6GFdJuAhmVYHmAAH|d2j*UgQOhi1AUivG=)x3Jn zA1z2L*UrAUrZ^Flx+m#ZkZPm+E@@WpQj&yU$^`z~UYCne)3a9Yd-JVEfSh8(+Z61^ zs?g)F9&l@|j56y~As5;LOMtN5)Uek?#$iAzXFAcq~~$Q_RD21RkY0&iN$}9ZU>cr(oR|y=trRejdED3 z1YLAO^qo(f&J<&?Or8&=$sIM!Y{K(sLJB`q%#k(LZN{9=Vr=^^yY|3UEJ z#+%9n7^f*@Rjr0T5c)YngT81xB88XpE$_JTfqi@*Mu#!vfLI{!XkPM&FL#}9>;srH z;sc^{!P{lh54Lz(bhK#AA9rUCF={7);S)N>v2m`AhhK7KGq0*RwdZr8{~oX%GiGA;2}~mMayL8Z=GzmHb1NL=&}V z989>);_2_SMkrTLdPMy#GER7Wg(K8@rlm*R+Nz;j&F$rMQIS&h!qUe}LW}2sQJ#*a zQ^I##at3`uBD6SchFo+?a@AK}d)3MKtn{vJf-x?C9AHFqk`bDCatf6W^bRv!6*CUs zh0a`<@hsl>4`~^vz0?Bri3vdIB{E4~5S0<8fXZ!UcCt8Pedg4^kCl@|AR0OIV0`{v zqM%nySb$qSWsqh4F}AikCe=nJfnDjSy`+-WMR>tqauPAcp-F=Di{sj*ciS$)95H_SLUWo`kC@Xdi=CYlPDWD) zls-q=EYr64a*63>1YH$(FOc_@+-NTq**dMXfN#-j^(66;)hspj1e-|#BM3iqRjPOa zRhfCCiT$`%>aL6(=93Mx)xvLX@_?xU_ABPW#Trq;yj4EOi=UOFc2>TZMmRe%L3D^) zeUCl|9AbV^F)n}SuKcQnQ`cqrHWBF9$|^bQ%pL&h1s?@wM=uNi%)6)NDmi-}rme~g zR$>;ml0`$D!IPFN+1mgBh<+(8`18%T~J|tH2Zq2_Hisif_sE4`J#8IT$%IF`wc{5Rs zr&$$!c>g@!St!77!xa0f} z2V`A$T-I?^PsLrrkmRfOE8$1c0}*9iXulmlNpd5TWUbv5u`^0HDPmiuthj+3OFB!ZtvrUi{-0V=eL-DX)NRJ96o-C3or@hl$9b{Ni2E3cT%JKHPU~Bro zyYw~NDdkTvLV3kedBBl~F)!@z5pe1%+Xg4o2Iu}DVWZc*<{Z{_>%Y_D&Sja@cf+^; zgk2`~;wfQtGt%}Lrvr>~2HA=Yjmbn%_fVAThDL9SI)AB2Zjb-vX0v9-VA#OXuGGW7 zeRXIW$v~Gt_K8fhnMhF;b-N&Vw3bT*B(@{v`Dt!9ejM*%k#U^MWMb4{L|bDBU6+&~ zo{^@eCpl?|5Kk)XRW-I|tPdCIN>^%KTJs36P@JQ50qEqn=zV+w&7qm|H;BWatW+6C zHKjCWe8oVGMSp*U@_L|ESyZyKuz@Q#^4f&enXfQdKHfVw9g36}@QHU`9tDka&Qd2H zdcyG8$^0aoaUz)DX)#E7_@|0Y(_(dLi^W3bw89pViTY^Z53aE6^a2iWby|6!Tl%oSF?IAjnv6b-M89$0xxFo9ehVk zil_goaZPuaUZroDNHuxbez^a6F(PzTx~9c%$A2(0yWYWhdh&CeA8m}BVeF{c0QCw| zi(d3Xit{C#TiP*x4566T{pg&03Qu8%3J0ea5dl7T1w*_TK00ABBTi(kIVx;QkRn-8 z+u5*2Xj{6nhBwP{CC9jvVR?Gft;3E6KQzJfw9xlP$sNmIcQXjaNnTe>S5X38RieR- zS^H~qA_-4GA?rB2SvJ)niwocBn_1;0koxu@fHisLqFtaEU)1Mq;mtSD7#I?t+}f?` zf5Gwv;*QT~eY|d+Vi(=>;fZrtBILTL{8}aZhRh_-y6UYbI=iCBRNa>HcN`NcQ521D z^feLmu<_%iX{7C;hI>^4ezW-vgPO#+MNyw?Zj-JUAtT)A~W&*Ea`$ zW1og=)~QDZRMmC3j!Soaz)NeFubjIHQ+Lj-r+WJ zm?|%M(R#vR>YtYx;bs{x!+$H{+esa;#}ePy8ekkua6TtaYpcswpiLS2$&S5nQyP3@ z@5tB!)bo_9%wO%Y^M{`NmBQ?khIQheuWRczxSCdK2#AfOm|_So!vOX^!5S$|=v{sZ zAddJrd7XKx1%V&GLIXQqE`6h=9^5CLN1U@EWGaoM58pBy6W;K0F{uo1<;&$%MfH9? zO0Ot4^WjH}^j*`uPUKQ;$cYcV#B60f zab*3f7?6cg&=6E}v+pI*N&6{GQ zjaQX$wwf*3DfS-b>3I=P!;f2evM$Wm_j(Q-5?zNmy3F@ylWDvjX0kfX-%6$wyUwS( zzVovf3qNjSahUQr`Qa$Ns3ZS_uKEB1r26rrTqD%OmsH_PBX(-aS4^2oUK4T_l@xt_ ztEa7bkVzIv&qK%4aIF5+Y0LUJes3nu)J^{D)9?dow@rXY8qHc9+V2T!(&OLv)#g`+ z+TF>%Qk$ilYBF%zgaEEAF{fnB?B(q-qu$%z;q>!R?ryC{E)1cn-R(dnUGOGC2?v3kdY+6U;BJ z1`bFOHy0Y4;sGIL<1CS#wWA*f$Y$Ptg*T; z7YC=hd2!b2eN0(fYRf5v4&V0^MCll3c{_xlHQ&Q0!IljORMJI>FKxs3(WjXhZD906 zhNi}54F=no6<@S%%q> zj4=)qQ567|!()t_mvzRvK@F9VP50$L{qLegPOLqdNn6akrwkua5>bN&`E)11iTyaP$acP87OJAFrA@9H;v^pY)4U5-S??+5 zz^R4;YA5!A(QyOu!=w=ZtRF~cqS|arug!O?#1B3LhUMjt^?#npqS(^Ij-MQQXd-&E00ujw0ZxRgY z_WQtm-xq2(bRmQJ4^iTDPw(&hcg%U%9=`YeHq@idjmWFLL4D^=5 z%jppT&FN)K90r$2?`*%UEyt( zBTSy(h08!lUgfC=YQ>ln4qO@Z6^Rq^4&ZI*!?{21jTfYFQRejlBgb) z!Aowm*Qm~>Z+7LwU|*ywn`{hYFG|Y&>PXdv@n(>$Rrt-PXHp2<^2MF81iZI9603^(&DrNX<3jtEix8D8Fy+djol+0* z(+`sCE5x5DMs-Ul((CFmI(LVJ^)D)$;u&A|fd@#Io2{4Tq+KRYvrD*z7Q%xw4NvsJ zPph5!UDbc;zJr!Ok?spGB;j~1`j}_8{w!VlWSAUKopl3{{UL&YKpv$iBdPPgrijui zUML!gW7smf=)}V)GzM>WVsd7mLvj1fP5Z4+bslC#)x>4D*{zM$?}KEK{8z~i>hp&< zG}lK*srx?mA%8jbR!_a;8)_?0j?JfGMo zSHC-gJmo*3LP*>2@&S%SgQzDT=FP`-E8zUv)>H zA5fK!V#R|=q@t=wFwAFpVUpN*X?jE$K%6q7U`b#S!I|c{Er7wiBboFg&?}wWQ#3Ik z%&B(Bf@@eLsQ2!iCK$<@4g5D^ybF;NnY{$?_DGIY@+!Gb%uP&xgz-!&S^pO+CHolU zfDLJ&CLZV;1ngq5Jp6%sL1wvbs7K}l5uwrHe)4O7aCo{nM#|tTgMsug#FFek0pEYu zI&aJ)PRo_G@J%aN8DF4+J1PGDt;*J|*YB}f-gWdSjWVRyYL8pgPj23z%rfS6JfgpL zzb19L$)uY1rm8ZZ_E<>CR7ig7@%|v-;vGXFUF4~^iMW+C&Sm?Kco97R%JNoUg*=c) zG-MDrX3~UQ3>n{Pko(s#%Xh^NK_ugc zCr6$|*5`h~C~s`%`agoUvt7H8{DlP~@tEvak}b8St{M(BhsA?dy+-ZfWbsFPQ`T6O zuBC)K5o|5E%lAr0C$Bhp3PRsT@G1eLG~^gyQD0L>EIP6pn;Y7y`yGH&EadG+Xu^p3 z(^5=!TRPxF(G5>mJ784HeT?C+wzWMXF^Cz7ly_tnGfKu_$q(AdHh-t>RY5zFo1z#| zxkAoJOaboA^Pdgf>((OdOPw4;i}>bLPyE1+$iv2d(t*dkooziiUEPRH$d3fC35(C4 z?IUqToWrGaI{K%kP&#nvhJ`BY*4h@R4gwy$Y?+*ZMImu&P0G!Q z{**RTt$d*cAMeLTZ{1YWJ1`%-{%^W8o_IM>r@Q-xR)z74o1w0*%nD;fuZ>6*nB=Ip znuV2?gDQbz(%N;DQ0jR3D9dS(=a0}G8er|!FAES7_cGnBwA{;MYN~D3*t+U!zc}bY zIJIbhF`4ca83&a(gN@+)FJy6e{iH_B+7by~wWBTS?Ajr#H>%7mWmyG$;ht+D!Xcf+ z?u`w>laX=Rz{E^pCW?;H4yaf~yxW#6R4Dj-1ly33VZKQxd2wwdwC;qX>_j4?p#@7( zsS(?JVW0s8g2t(ZzzN}0EX9iZINjp2*yfiEV)4`+d#xyCm{ysT)T%+)DY$0s2V*x^ zXDva+8I>A(DSX>@5?U`vP22!X250rZP1c`VU#B|jc@k@JTN64f5ovjkPutDXml=fq zc;(N(Ipmj|n*E+O=Val5A~osa;lNq`m=`!FQfzfmRC_UwMwYLKekc2}MK^3?mIY6J zh2c{uE$yW&bORe}ojoJyGW4j<_URXU)WS?hqjZWvQ0CR|4cYfbvLl@T?9j3Sry z(Yo}KK}cW`PD@)Km^48SYk=x7BuSvD=uqxK&QNw6KV{Hz9K)K8fnhU_S-|3aZbl%PwcUCvpg?2q&E-9y!T>Y(~mh4UVwp@TpP^il3yOpo-&QdL%l@QJ`#@ z_RH~E3Dj8K`!U3C4{3k~W)zz-yvAaU+R5h2eWWSAO#Brx+-pV$5rmgHNIQTAsh5OI z`RQ!;zpPZW*A<__rxQrWl^%A;;b2ZAO@e?JI3gUP#fssHh3I9=2@NGwR-6&d{H^@p zg+<**T$+H9AX|da_x4LxubGw@KG!$j3zC>MS$=IQL9b;SuCz{|QT}4rDw73Z+oi;Gg3olqX)psL{TJ%-df{ThHQ*N2+TEpL=TAg~CrN+>9`f_L|egr0j*0g{> zP=u{rS->RS(ETR}!_$ZA52&&tB1^70|HXoz71|&|YK_O&Nq}v;#gDdlT%-{8ATJ*u zHkjietfUUFcQd}AQb~&+hTyUAbNc93)!KMV|Ghf=SmEm|y9F(IW&RxG6-SmIya>cF zm3-eEy@7R`_|oQy1g`a1}E7(T8ZwK6lH{0Nm}>jZ`VT>FCQcQK1hA66I5j7QcV@`hgsO9L>k%(CcN+!oY0yGJQ8mdx z$|=Ag|8rKv50b@tJ^9VW+11X0DF&KRvoLlStdIP&JbvTE9 zf0F;M;!_u4Hnvy8T|akSy%Ed8#!qt{U*r)3RMd6YCz|vA+V3rv#6n94tTs{vv_t#N zIEd6pG;$!tE}Ynhua0<2!5Mhn!Za&q^F-vZIilA+z-&^wJ&)%1VqL(&nkW6>r|mr| zlAe%WM(T|L65{Z!-`{$huI?r#{dH55NwKEpd0*P%W&bGu5uHsd|6!}Eu zPN&Zqr8lcGiTX!tnj%A!BpNGPtc5JKV26)fv$>9Ifw*;{+|cgdP^|@2 ze@ca+Xjf1*TO>ln5yr0roz%U{V$~G3TvZ`y?>yduLT>a}ZZ`l_P}{JYkMdS7LiK7EiM zu=J)42PD?B?SIU$V;mL|Fe*cH=FaDHzb-IdjyH>rNp3V%5A5R2UO%M)N2qZQF3o4d4&@l$m*wQ*oV=1QDl;K?13vJ?;z2Z|pN3eT2652yeSSO1gMydB(1+Fj9*a@jHtXpF0Pj5JM;zo0YtNoj6Me`6azjYC2yqrGm3 z|Fs48?o>GYi3u*dMESxQDJV5mCV;$Rn4X9FObGpL?Ohp?%UUMo-89-d>r_iW^m)M!j;QVSplXu7d6%OP+^k{4M=%`AAZ^Z$tm_K8VqgBW2`lt5bNUK%2 z#qDVQ*GXk;^S<4(ZHMEr8H|yDmZf!hma|M1Y0*m3U=Rn*_7ZTrT!~xxZP|goQ$_u9 zn;xyF-Z{}hVl*PRekcKGsrG{_BC0C%m(_%R)VqhrN*0^PyJk(5K;jSHY@a?(CZs?m zEnI)nscT#5CLcg6;v9?8$?GYC3@>(nSyy^zEMnn}n!H_I_17f?F#4kvyymNBiLHLA z+hj0yU=kc`Y|UK3Y@99s_l94afk3^+zAeyK2$O!<`R&AwgmIVE#9!~MpG*thV)N3! zKHU)Q9-0izu3lvV%Y@?r3YH1ku2-wh^){!zfSd=I2;aOoH205vnaCHr-@U7ok#s!6 zGjgtds0-XLu(ePb7RG;ke**|>X&K2t;BZ>DAD#G`E7?VD9SQ=;ZF1bK*vcpV!=HDKElFvtc!nABnuP<%ai%d>zb4iZCg3z{E~0fz|oSh~>y z#=t2-RCrXdX^D@Fq1A?Xb4j3sec4rkWg}NTNqoZ|Hp3t@V8k8&4L#(hMIHII$n5vy zsoNW^WkpJ?5vYmBP)1SCRALjSio866%k7cVa6Q}D$j<4kXGodw3zOdm8C~)X&JN72 z(~r6nGUyF^VL9peeF`KLO_XyM*nY=gJ}RrMk_1!RW} z4ApI9`TGLRyI@TbQB8l+LrSCd=hBjUhainuA!z2EuBA`X)0WG}JKYnZ!^bNTx6s`+ zk7L2{ROF$koAPPFNtl>=M*!0fR&#IiFD32uYo~jB*Jk~-vu<+(u5AhJF9H{C zE~Hj)?nt}Qqr8(4zXoyyja$T098eTA(lC7VIMRghFxNd`+_ zfc(saxmBhvc2nQLC56J3xl9bF#xWr#>|57fcuf>y1(Gg*y!l{M%Hap4JyxrD!dYep z=whcBb?0ro9NntLj}Jn$#&H>aRDAJ^qbxzXcqm~%{9+9(W+l#(CtrWaZM;XpVkbq( zh6)9O87S79Dr@YO4+>HLR>p?yfVXF6=PgGYw3GZgU9iJ&_ z=vfbUY)U{EEG$Ga_m_%~KuZmlvZed7JFp*2+g)bf1So$cV?WOU>wpF_PO-a5&kCBU zSzjdr&{9jF8i0m_DXpZ_COoQjXM*xSLba-kDYis1q*OmE8$t>ih@Bx@_c>Ju^-4L} zCk=e(2v|L!Tm95uJ{^Ji>_M*f{`vL~OZ5+3e=c~cq%+wn+C@_shK^%Yqq#FBYWV5z z#7J7UFD$2*IlfzVXxLRx1KH1wAW=It#_el*=B7QJ+k&nc^Ey}11`iiQ{S?Bj8M`;? z!ITWL9DQuv>Y=0}!mmFYZd5VKaab-8Be}f#?e_k!2_SI3zShbg!AdajIO6GMqy&2y zX{~u~uh62l0g%v_oqHPc0FSWv6j0WIjsP#w_9CD>xmCcn1jPCc5rMXZaTsuZ`U@37 zvOavD1K-HQ&l}R`K<7A9VvWY9cfnbHQbcyepuvNBZW0PHp)CQRCb+wY^t!1zjRpNc zxB#q&Y$MMq)qW2q-yAdX^Pll=Ji3_*d|Yf_$tPKVm#Hh8K%6FP@if4Ig(iVv$Hy-^ z&<1eL#g!2=`jxl$rpRymx2-e%WDre7bDs)7XJ`|;dWfbt)v4Po1l%VPkC;A{ST$yO zkh{JeP_oqj*?*-6d^~Mu(CK4Q<_4QYCMgl%4({gI|F);6d9hGoP(5%CWl2P=g5msvGqsG2lhkdv|K(VrZ1D(FHh=h%V zv-f-e>I(4q|L{`XVxeW!Xr;f5ZTCLF-ngIg{nz{fpFv*c0KV~@t)oM_VfecEA$Ryq zdp5KCJzuc&MQ#o;oyI469v|6w!VNvn2efmw=VO!~C($9fJ+Axh$rG_K#;()c(ukP2 zz7ah2kcUv^u8rDtVB8C_Z|Se==RBVZ&GZFl$HlEXo)+qEg+bNlV_$rk|DF)6T*1!n zt&^H=-PvEJjBiae+3R4fXIBUy-!+m2KuIP|QY)J8je(?Z;#fD%a$C0hAMRJ&^E9E` zrMGPS8yW#`roTDS;TcN)<7L1djp$LmhJ&)~6-x~IJ z!sSR#Lp#(VZb|wIRU@U<2P4IMq9kgSa{<0>{f_Y9c#$ol7)6FqSEDz~j&&mV%^Whfte=YV-zvW>7 zGO}`ax@MoADSFbC2QGDIqiVr<&)$5v##pi9ebp^B0uCd?LSb12YY|{E}}`wfFpWxU>wM+X8RdpVe z`~iGYrlp-e97jt~gXp;WYn}wh+zgCQ6+8X`AFQF_-CK1-tK5@q$y(eu#Lh~dO$|;t z*GhbMvhNTJmKXM*R$Wi$Jw$L z79)Jc{)gTdkJh0D99}*C_ z6F$o7;_I9Kn%^zQm;1kjWLB0B2WGE!_$KA%Qs#-km#<`8DgD0d&At~P(033^=Pk$# zAO4*_LiU({br-&yK4TQWNAEIAs?e|T^7C7KsX~JczkLPX@6)^$2=t#fJ0;*|Yi8+t zy1F$}tbDMB^)CZRCUFzWy==&Th-cNWuI=iYl&20Je0&ViuX_F>yb)Q=%^d5%Kv-us z+q0OIraBP+EhpMiPuPuXWmD(F&5B8z*QY2PYA+9u-kTe~DM7c5?#cNIeZqDBCxg&9691XpM!So+r{r zDxFng(i8HKW6T0)J3wpidBgJ$b*6~@`AxU(e?Zy&aN>S7C47beS1$wtA+;6|5ZGMr z3Jm&tF>`0DZ>wfz@|yS%kZ}M{b@A>YT zjompo8=WXVzP@dqJH!7che-behyJft+q|Qc)7f+XW8=@QuuA;D9e-x^-z3NjXQL*} zxW%omsR{7^=g^D}9-4jh=a+ou@n2--{cQ3Cfq{VsYsmj@7cLBp|3Mi4{?GGM?d0jj YnVD|L>Razu2yjxARg!wxBvhE diff --git a/planning/obstacle_avoidance_planner/media/calculation_cost_plot.svg b/planning/obstacle_avoidance_planner/media/calculation_cost_plot.svg deleted file mode 100644 index 54f119daffbd2..0000000000000 --- a/planning/obstacle_avoidance_planner/media/calculation_cost_plot.svg +++ /dev/null @@ -1,1257 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning/obstacle_avoidance_planner/media/clearance_map.png b/planning/obstacle_avoidance_planner/media/clearance_map.png deleted file mode 100644 index c9bfc70ec01b1fbc0a8074b1c79b1e13025ee1ad..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 101878 zcmY&M=Z?6dZYcfIS~;mV3K7^tMEFfcF}vS3LS7#Kui7#P?DWJKVVu;19f`xU3p7 z@Z*JS90vSP;w1IeN!9kdldGYF35=W(rpQQE69%Si7dVOPNahI?nGgL}B56<2ma0v1wYHXiL$omvD#7To9q&06g z=gx;*=2DmAWkJhbZ_|G_k$Zg3!y_Z(UmmW@+vk5j9{4_0YA|vR4h}Xsd%QasWyEI~ zWFU@`NtxKy)JK&~88!|W6!potGQo~#K5`+O5WdkVaMaP&-5O3{=oqZiVqI-b#!!Ky1MV)gMwnM>}opv z%2LO^YwEuNH5Y1?fA>ZS!cS5!4IVa*2fj=k85D$#prN6msV{EMCn{R(=#MSVQgn%l z7{Pm{S~^GEu8eC@PntINeLh+2^;)Apz!&8cA%k+w8&?ixRCczv-za5^jNNkq@7^kV zAi;fPfCGKD`+X>lEF18>HvG)(^`XSUxn{ui+9;qnvwE!`df@QLNVK{YYiV|D@vy(j zB=AiuBGSN@i9|<7*L1*(qoPot2Vvuima9j4zXQ?X0-uPvxNv;E9E_P02-{`GH*$}Q zD$%Z99GGidg$V~bo3W^W{p9N+Y3yBG2KIsz?Nn(oLVL^DgR#YjVD}7QROxVVgSE;L z2MsmE!5ObcU0pTyCJDk;;cL1`!Nx_n20`uY?Yn!%gRtXiOHgfc68vLNxwTm?LkEN84l0*jG1z?6?$RFTg)oWqY-mx5vQZw}mpa=D#9lS2{vFiB^hz=E4 zITG&&+*gy)iB5J``8yMD`%7hwq8xBwAOBjY9qjwxmaH`^;{>For_3yV< zxlywYz1@eP#K@T$Re^RC5Z(8$zW&&_gwpHJOuKd0X8va=vNjZ;5{32o^-&u@vr0}R0{+BWBJT@(*JwZKY-DXKhg)m4@Bt^ zM}4j3lwEx_w)i;;ff#I&D~OKthY>ZMz}WW$8e&jTpM2?D-bXMp3gC3+^U2C?Y;0_k zHjSyI;n?C1=yM;#{{|=`iuV{qJS^(O5xZzM zOO~Qotf`MUj4jQ9Z6sYfH{CIQ378recpF0u<

3ctpgAKJx+I9<+lj&3+grr-R?$ zlPAS4*({?O)`)L2rwndHTcUJmU!|KLtCQm1Gf?h&JPVQx1Y8*f^VNXy=&$#Rn+gwa zwA~nxq4MsdfO68VPat7YZnkbb*=%pfYL`^A&dD!9ZyqSmgvzg|R|ZAOf^jeeh`FmU zB{)d05bxnI)n1u?(VMJ!%?GzZ&qv0ll#9^)6?5Ch+4-xR_!6d z(t|4x=8bgT=|%qv8g^@1Yhq!E?GQ{vaq!`5{^$l=wyC3I{J%tIjE;ts7MH{qZ>mk_ z9uvV>u+iZy*ys!!UlY19zR%Infv?R%h&JKKDd1eMb?0-v zvqN`zgX_3wFxe%5-d)1GpQ2ZT2&dV*M{E{a334(uQ|m-65pn=y&`&~AJe(SiSLNbGL6TVESh1m z#_8jN_y#HK);D(bUeCXd$g{JB$Nic3=hV=n|`Ur&fx;IV&nMW5~vxpr1^)fm=cNY_) zF;p+NgSXvSJ~_f6J>{gRP?xwM;T;#A?1{#h;u&XBhvjcnob^?n+1mj(g5+v2-YH|> z|EG2jAs8`$k*mfTl#n?gx3^!(lGw$oC)v!fT64adVF_sWv1W{hT?5s0P}{bh;K6kV zrvbwgyh2!E_ZAguJZQ%U4+GTitx(ZN(EXFo4#h5gqC%U;^^)n?lnm7!<*Nna38zh- z!o*udHS4g_t;L?E6!#2HyX_-VDZ^vyfMgmh`yd_>-ZnY$3EQ50aR1H3wl`|R1V0OY z$*eL<9THiPQ%!IE;Mo}`fDu$J-_;F@n6G+%5wTqsk9t=ynA*}0pN_yB*Xnw*-F~w! zcl0nqM=0|0cyYUzALErzR6~cUopSgwd01`*oX%B`v64Fz0}o^dDxh-EC!n|*QRS$Y z8gf%oh{Psh0=dDxR}DLyIpfFRw|A--ONg}ahu!s3(>=}T*0~|pz1a{5q&z1L(SAij z16dV6XtV=nfuLXB5~)Rg=_r>L%V?|J^M->Q)85fBVUl1;j95DeXWS&q`&!crLbieY zxF!|4T`oLH=#pC-x=6*EEH~jP&tQ)9nznIYa|*wF>)OEF+)tI9PXbzgcuXIDU{@gl z+lezrDX>L8c~bQ6jSdC^PAlLW-Lr%?zOzRz)jDjAaRr8s?lXiBZI{z>ZZA(aj$39C zXe+9XiNk~qkY#a~o$zh`d;{66oO@Tlbp@<3!5;>v`Rb*bqOtK-2A5bU61V|03@R2q zs|O_rFHJ+ruiKWlNc)M*@L`eR2k|*n$(MBF@gFa(H#=Yk@fKb38X0oINt1~0k)~Ph zh`!gRzJzx|R%8#WoxW5r#~V+r@*RQ-o=r!8zH1wYe*!BRA+@0IHd!?NTO9mnIg01R zLH==F_!BaUG@&ywkj$5lT(%@K!};mmr(tV{t=si@vr(|9OZ@xqUFyVxo{Gr(`1Kw|I{7228;70Go`U^FJr40G}ym9dkcA7GG1R4$;Mxw zu4w93E_jPROv|xv^Ks-PVmO@}r5cPd=U4cubuLAAu+?okM+mm{ut0BSk-Q(e|`T$(+mp z|6+=#R)K%bpoFbL{yWo*Ss58SEdvUb3m2=!bU}^;R#Xpmt5uOrN7Y|h?10kKxb86u zNle@gluCin`|FE(?v7KeHajBuo-_F39=J{uTAZ^L5S4%brtCT7k=8UYgR;v-&O3V> zMP_(R@<8od(iaDwwY+M_tXBC21CtRE_^B`ez;R(*j?=>3JA-FRq^pbwAK6uA51gez zg_0R~+A}2q1xUA5iorPmUKMgbr)#))%Nn-l64jtpF4@Uj2~@k#IxA2kjzGs;Se&*! z>Mj5W+x3(zZ5yyY9F`t}6t&@jL`%PAT>W*kI}i!L2Tg5lm%>TTsR52YKG9Uqr=iu^ zyeHxwQ(-g(2a--*`d}nJmy#Tbj71m?A;c=oUPI=es2LHp-tu8`8B?P4iU=x{+h2`` zpn9ttU(3~dE$UT@*tTgT#@vJyom|T?6|HV$-{}Ul)uuHlCnU!Dgw-qqX^ME`Zrru* zL={*rV?&qh<0pWBtk7f6BS<{RDI7)R+nQ#sxm*?yJ>ykQ;G+-scDlU=OG2L~)#t?5MNz z{Z?_YkNxEHVz9m>@naBj6jY}2YZDS9s!qwESOCO}>W-B3`sOiHE918nK0(1+E@2gH zZAl>VN4TPq-cD>=PYsO_zP3Ul4=f$eSCyvcPYpCHwDS8&Q)WSp8$N={oyk{=hVM+s z2d&?hj|tY`Mf_Tx8@k3mNze8fwdd0;StJ3fuiz>ef%j9cUS;xcJ|kRNIs^#i(?>KNAG3N|R77j}0ELJ)TR?$Nx zCL9xb2Iz;TI3Q<>Grm$$pOAac&d%0f7UrRAN3G;sA z9;jPk->N2NBtK-?BdiF__FRbQfYPz<+@Fgr*y%NB+KF$DttqFj+LjC5{2qz86&POf!+*=M#A&pj)y}68~lYM_u1Pi~1G?0u?cn6$7jz zbsZKWq)K~kOg8K!DPwlLXh@D$IoDMjLRetqqc#>T?nrRF)M^La7=l~YzKdGv7a*ql z%ov<9rru;&{o2Z#pfp2k4I8Cw>CZi!bbe^1{x;a(AN=!*DBggBxS-=(jCc!adhjKe zkx>lbh}{O8Q1%@sRyKM|@n|wjk(=g;t*4uf4Ut_wn}uY+?`HMp%f!&2b<_pFLL5Vjm>j`Ltj|H!kmsj|+XT_OgvD{0Etj!K_Kv0~ zy`gxPL(c4pB@J`zBb@I@9>i9bWDQ*%Bj^o(PnDgSaPk%pM54vZ)gg+$c>tM^Hv_fG zu2g@=^6&5X2E|}b#k&&n!7d8dhy)gZascqs?P)I->|q4?2tr>UighfqzXVgfJOjOq zjLhvVBql1F^$p9mDVE_qZNe<8-%GUcvIIuIwr39OA&q>HKJk_gy=?$kx#zfSyj9|n z0Z8$Uj=gOOF6DTxe>9dPqV*VQe+O*YqwR9J?-x)1Q5JgzPGJEAgB;De)dp@Zlik>U zOI9J@Kj;T%mCi8((DC=21&bnrxV$C{;og-;)&{j~bQN5qtOu>=IZas8OXHN;4ij@0 zeklC!Gq)c;oiS%_ZA3-vxK0dCdWUiJ_-ID~*Hw|+M_bXnvaDUUYb`%5{YMMtWyt}k zgMjnFooG5zGNYl%aToJ>oBi3S@cr;1e~19Tblz66qU;DDvGB#z#_O}Y z313Pe#p!Kt^mdF;ZifZT9euos1VhL*FlhV2Szj&u*CG6`QEI6GdIgv#RlY%RSPF*~ z^~xjjiU4fjBshGL!LZ>JPf(P@#n51}jb4v0k+!z64TS$Aee&pA>s+ynS^DZ$btE8N z4NHaCn0_E4u>epp%`a`txSIx?e;uo>u2{Uhyd8u1_Qj@pvMuxB6^!)Oxkd8g_g7cW z`x_*QZ75JIDv>^_$8M@Vw-46_7HBiGtUl4sIOC~Tbz4Qoi%6h>M1$AE1@L{}Wwc({9^JE=aW&^Dp!sI+OYG=cY|Mg5y>8L5=L;4*vP zgyZ^FXGzkikU_#|h@?YA)ZjO6QjFK+;TkXyo=6!Hd_8$^rQ*!iJV|IVvd9B)6-H5r zkqJ51$g~-wRn{d;-&U$p>yBQ#EU&9leT6H*ivZc*ieL7V^lyXpyV7kt!n+M}gvYUf z=8hP_5=&Du6pozNsU*)JLEck7KnzLZ2d2x zhzM4&Q|k~7YSL3;nop;#kZlB>w(7qn@-Z&adKT8f0I2z{|F)qpKRx$t z|1)LlNk?R*@6$oJw~R`kHCCqTCo5l|Jns06*skL}8HifL8 z(7YjX#MeZkFv>L`7enpo;+RyNdhPhoGuOcy%1d<1)F*H@Don{e_~c)Xm{CwE6dwME z<&XvNWnCz#^u%7X^8umHWj^JjoPC=+@K5-PLZGFh-0csdse2?4+TGpqP#5 z+L>>uG{cnV#ed>vaq`J@OeI>^zCR)0qBdhn5Rd4zf>3`0(X$1UQp`6U9$g{fCx|u& zU|6N5j)*3NwYIQebBVza-B+y2XAO#EYFV2d{TmMnL7bulo`CtBuBf>F*RVRMz3g@g zvg>oadpfUe>mGfU{*oqb@#Zf9+ROaLy>?SeOHb#^&5Pch58<}8rnNmXP*QShLT!Y2 zqqqg@KF2w(dh;dG!%?7v7*!}ja+(4lc6>n)K7e_PLzPN6kCVKNVQw+xN;TjkM_i_$ z5ge08a48ZwA7p*}&g_?REOhDU@XwIO*})-TFor7h-fB@-$v!ODaGF(_MGaWLFx}e% zs*$6yhFp4Z_vD1{^Tlmx=Y8o{czrg$Ib%@K453B9Vvns3X4*=+QEnO+8q{#NN;d9i ztc^f)x^yWK!V;xV{mvt~k64hCpQ8?ej%{pRPN09#_hy|MWp0#UbBYj-rYQ_f^ny?o zD(EyB>=qicYKF=;i25JGNeowyWvRty&QG7^m&My_1xny}0I2winYLnC zZ}GrNMU7>iUCR&J{T~k?ka|di<{9>+ma*LfaE|L9 z2jz?7$vj0@aDE1_F$2<7AejkYY^fE%)b`p!)9(VXf|sjm?R+?ijsAyJ`O~!%p9Mw} zZSqdmikI0}?9RePp#YXF%=WmyG|z!3 zSZ4MKPfSD#i#$PXzWGX5JWoBSz8^#w?Hn51URT{3ufSv zkz@W8*w{7n=*1S7%8(pgb5pV4kr1b4R>lGUV{E`k#^P@r29?jjFDz)$F0Hy=ms2v; zS?{fZ`c!7lB+qnCLyKyT4E-(g!}}+x>mj%{3cuRA&t4zsX8|$~8R)T$!brb}z7~_vsXsepl^8Dil^6@i=Xe;m_IB?D>63m|uM+@;xIu1E@N>c#C@Q=Me$VlAw!M zvi530ebWW1F{U0Z*W9|;W>09&l^JYYXT+EJkGB91t1ebZPG z0He*gzKm*ZNK|wk#+(7S-f;|cw5})X{Rs?8Z**<-ICW1k5d&v~k)t6N=T)@rdtuNx zc@?UD;ZEjh4@k1_U9!Eqd$_Id!%EzQ6o3<_38&Xw`a3MBs7*a!&Ejm z9Sj>fLs>$Z9&duL-nbHF;-3WXW0VU$j^lt5@^Pvr1g9thp{52}tHVlIL0$;~%4R1; z`V6jvIobzvG^qU4zZlv5d`4#_r$zepj@#|XTho`rY!eR*DZFVaQJ=OOtt=OH216`S znWmMbMU7vdrMmCO(zpE@lqEv>!r=snX(n5tx$dDj=mi<%q(PV%gi+sV$47@Tj{A7z zJ@Ts%e)8Lu#`*S&5w0&REacKI+N`w%1GHS=2jUUJtYI3T>m0o4eAHdPPHZvHlC3lH zvM+W#^6zeO{Aq@S;Reh=s`DK=c~?56ZF%~7ldo>0&>xS8HZyI|7TGHOKCyV5H||-~ zfWrdNi((bSnv|8gvv>t%Ec{4B$9NIp$dJf>rPtPeFZ!(sQL)qI!;@N&V`|$9?Jxdp z1#u6cQ#RsC-OP^>neM1ef0rsfon*aw`&0jpAb)$@!DFJ1F7;U{=8XEE1EK z;)dU)ByJa}B?{Hy_Yu%!dh1j!;I*_oiX%zD14QWSe8=CV)mlfj8{Qr#_ucllw0-1L zC0Dxmg@9ezVx8%~EnkFP&uab6`8toFy2q={c%^)X`&QxKa&frV-T+89AMWws7`r&7l_D>Gxk@zltN)G)P+qOWL>s-PypxSNfhE+2m}h-wXgV3vh2K zNcS+mSAUzwHilbkNglQK;`bjq3B+~OmJB_qX;~M5ts(2}p49|yMX@$Sp@%r3c5JGb z_CjTWyfNbUrXm-qJw-B~W+-hQ?#egrS#|XEw$nErzgui%BB?Pg$77G1@Y$5)#@b*R zT2Gm|shUONyfI3jnj0&di=Ru15K#()^PFqXP@We+uWi%7sW>K2d)DZr9ES-SV&@P8|#YjDx2seFRG{($;5! zi1fX1I&VBXiEbT#-^1D;3EcEv+duwI)*ldk9(>`uI$=$V&2j~>=L`}_*dEO0V;UY* z&@pt&JM}qE4^B3IdMOY-1T!Q|o*s`cI^iH7zhD)JBY7h4Ocx}`6kqMhjfBo+`1lWw zewV**#02d7ukT@f=$5cXB1Jmao{G$20Eld&-#MUb+!vSBgCC)4F|Fg53`%2St`VNL zpf$0gYP4DF$$q)Zw%jNNe8qfDAZ`~GfY7>`Wpunu1)x=*W5?`BR$&z_M-hN$(SNzp z9~3-kOX!(flu-739Stz9{?_z)o9;{m^o-`7EWQ%L4T6|QaYTCtVg6HQYQHB*<_#Dr zTcontoaD3YBDb5fo8CR!tWLg9Kj1L#9vh2NH$zRB24Cr1k+5~m?V(1mudW6i-)NT; zu6y6;ZXn20x+oRuRwWzd>h7u3!EUKGrhEiOaN7Q(C69*_&t>)e^ZAQCYJABX=@Yxn z#Jn|Km6e}Rm&FxG#qR->CGvdxZNhbm(n8)MQwSKUxIJAhEDVO=Pna;SAHNcdH8n^} zpmEOR(L&QTs7C0p?K<6jGfRR`I=$Mpk%36|1=1(*#{r1*YygC>15ZbEO9&Yv6>`YI_p7W-#pNNY1#d-L}}=d6$(1pK1%LEH4hy%mWA7HPoyggBY8ir3I9j}_!m z?qD4tiU^Ga7IZDVf-i#r2AuNj+V**@69wkBR`j9vN2Rd>PS7RL5)68Dl;y-Kf;qQV z|F8ku4GRpPc&H=siUPveFmS81Q~sDbqRaFi9prUkx=AId*A_liEP35D_ZwBW|MO_4 zEDh`)z}K_s3yE~wP@o_y+D>HbaNIo-IexQRX%omM-c>KwxpBkFRk6LZ1AlX}F*r7+ zuxZK0wF)&SYN@7G+|mgFx=*PUJIV^X>9fXAN6O>X(ZWr6!u!<`qk7j2#~Pn8O_u7z zFW2MF55bOJyDPR`?oB=C?N2ue)UVJe6d(^{SaI>kO{{RHt$UL$*=~;4dT%;kp5!a~ z3AgL|N3(rMUiLg+kZ;Qu6=jh@T74e^$=7~sr#}>$6XepzV*-02skzS)RNfg|u=y@> z%|34S1A}ur*8pZnYSDO)xV~xkME7Pgo+g8Mlr(L5V7Ki;3*%{sW>9iBlbf@1p*MS( zf!khF9g-ax#V2OKCLz6`0SKo@`+7GIDZLiVVkZ^8EznG@1EZ8Z<4;JtTQ=y<<5dJ_ zuwBqYN~KtN>p+RtU)sL5?P7)?@?947EK5iJ2PocS|BAi@q!RYla{30{6%*;Fqmet4 zkm4{uPExlh6}bo_EMq}wwG^1a(%4hT?F_c#`D~&3@g!2TQz?yI-;3l#h*iTLkZXXZ zasom09=yV86Th<-&gs42LMxl6%nW?E2WLi$!*$_6hS&(qonGTDYBGNAsFXL4mqDfW z!H#QBmj}Ihk_0>5l&_+KzkmO3!F{7sJe%iU6Nm7UR(qSqWeA>xQ$>uZaPr8d zK079#u^Pf>_j_D#Hi&f({>-QIge=KaD@VXg>@Qtk4~?W_-xoW4J{_f;g@fFwuaSE^ z;f)QFj`A;zU++tra`+1AF+sxepXCM8W`Dd)%7c+$b}Kd+n_x2DZ{7V$g&2ez)km4y zV=3WGNE3Z-`gu|`60H35*=EAAUc|#0`ZVjH8tQQuese{$M61YHkWlrwzf`&Xps_J= z&xP8}?(Bo2k^inuqyT_pMpQL=;)nj2At{Uje5T_0Q>Vxa1>}HI$_-v)3TKNUV{|X* z66zEIHEwx|rVGBL0a&je2=;ePj0itRx2Lf7xzT9W8&<5_o~~B_QUghJw-Ha^m|{}O zzt!f522Dma%PQBAGDQG0Al7+>@m|Q?^8K*O9MMgTuHF|vrKC@$K@SH%DR2Rm2;t4j z&6%6pkL_1E7QD%nQ~-dxey|Y9@y$K5SfR)!NC=i%UM*);tpF>qgbl+XI(LOmU+hI7 z1ygWDu;q|PEFuF$Uhv^%PJ*mLEX8E?xdo5DrJ!bHqj6|dgB=BmtRRjR9g1fLgnXl) z3>d<(2Jq4PZBF3?CB_jc>UW*Ay$AwoCXm~mm+ERNAT~jPp+M*4N*|jnBkY`fFPl|@ zkOu3$Px~2OL?n0jixiMM2>P6(F%lSIy0kO2gk<7`w(JY{r{?CB3t3S=5#qdAvmtt= zQ)zY;5d!P@=!Cg&W}wC@7gY04s^vk7L3Pc+Y|peENmnKX(wlq8Zkaevl7Q03eg+U0 zA%nzn0Vx&k%*j=~;Js8a{3gLSDbo-gMos()XPWj;U{`XaIg1a~+k5UGU94dKeW2(e zRQn#}mnMPpX7oXhMZ3FyZ4Qb$3XFsry@V(wlCQ%?dY2_u|JZuP82ZbJ*90rVx4IMF zoQia0UzzM=+_r{rpTgLRfp*anRQ8eH(hX0L`xO?19}C0= zWIy?-0}k$ej7y~NP|q+?AM@Bp6{_&PY3llwqcDwRjCv0YFk^k&yMhNP*u80ryE&&x zDXXRpshCz$UH@;LbyD`&8bMu7LQ?s2$d{?D^{q`A`UB@rL9u2{(Lu|jPBhqg`8DQ5 zUz)ucGjK{vQPn3GB4GRoC~)auzxskGeSTfY0a{5mcLjNhW*mS0r{q+fh%0jZ>HdYk zH#8qXx?`4|sejySTQ&gVKb@Uk8>mtwuT{#<5wiA{HDW)H`nYja$HgjayVVWzhELnI zz?4FBMn-^>?uAjgRQ8Z_fGt_>4kdiY^t_8#`B7<@F%q?mh}<&UjEFXOlYz$}$`DW6s-npSFha#K(a z^D2J_$o}7J)>$*TucRqvMxk49D1N8rv1-3!qN8i^Y^~Ya$|A5Q3kBX>exT?pLBDhS z4aSm2K74<>8~EzL;})iFmXGRySQTuT^WHx;KDUIT`b{EJx{!|hTuQ`dj@^VBP9{Er zo$}#P878&PXBM@DV7K%n*40aJB~~Cman0+Z$m?WeJSb%%=l~{u$1{_#4hfb5JzV)x z0G*Bu@yXv7r1u$~Nc9-zepZIQ9$|X@r(Wd(r{>;)qH&ZbJC>9c%oeKJLt)jv({w85 zt&}hz;3J$&{pdqkxk)PjPJ`a5TnB$bV>@0>&&Rs|_fI;t@`=X{WTUNpzl1!8dO3(% z94#Y^628>iUCam}6sS~XXKWHHo6m)apX=!bnV>RQqt-MA5J#i}w7k8PqcWHQr5B^H zJ2wyn`!&=bADALkQ5jaN5hW)fxO^_TmMf>Fzbi2 z_IJP*{@r)^Stm=~HeO$LK-Aagp<^202+L>sP5=+Qy?BmxaVU`7?{Mbcl}OhR8LYYX zVz7OLsb{^r_{MBss7IB zeB=`G@+N9OUACop280F5ZEFA$(tYLT6LhlRsw!&;i*%O70G%REcpBobHS>4+jXyow zZCDHh$8C(u)Lh<=17jwO`rkt1zXXUckyajZsoF?ZPsgyj+G%1db|7biT zU9>U_&@&4MJ9sjYKXhDnumlh&XIQMYhMxVMF=N0vQB9L_XT`M@tSp*ld#0GmNAZuL~$>P5J40DmHJoMFpgPXK<4dRdq^Est*-lcZ)XI&rO1QtwY{uOe4 zif5%R!}Nm`N7#)$yVRsOc#B&D?cv;h^e^trFn0pCY>OGX?r++=b`Bge7$avZY(e+0 zo?+?k&#IngXteZojKzE=Se5OlZTomoV{wuU6fKZ$dJ97CGMH&uI_x1nDV9wY)ibE8 zKGe$>OZdjq8v$m!PS#2e6ZLIaSTxGnS(0ZDBzs-B44paaS{3@G?FRbE?Icu1Vl*yx zT|hAA*kA}XGU)R9>A~%OTo9@ksUTS$oc+~j$Xzd|gIQh2v*5^}YKc-)D($X5D&-{k z!m?kUGdpoSL2}>fb1OO;1v<)S=ig@B2}|ZTglgVU~c(|AJ3r&k{+5} zNv_Y4yLh6FU(q20!pM3NWx)B=Q+=-`QH<U(9q;;vi8f zV`HNr0&Eo64bTDlKweFh9vDJ^ku_Q^U+e$-cz)_nSgXOo6?I~aBU-xnjQHq)V!Q6B zr?V?mDcot#T++u0XNLB{#ENWe#!;v9LfVCBQ^M-{6mJ|POa&t9gGzG?BscxLc0BKo zlG>i#AJTR-a;`gn&dS20d@)_0P?r{;?Tf10!>fB7K?*_Zfe*f%&twz1hiqv0hDu#m zAx5z--`GH)`p<! zxKgXAe}w4yc5-l0OYxQ^0i&2#f%46K-Lc={qCs&b2$KOp_6K(!0xk|3>+mjlun<90 z9qjH_5zNJfCC(_+%D9V|hc59m&{0laPXYm@`D}VGJ@pB8u@*FCNc~K zg6ycDQD8FkiQw}&0GR`zCA99Ptf@k{a5$Ly`4lTb~E2)DClw^cyRN}n*S-gsX6lSyPjm@-P5 z(pzS>v*-J0Y<&~WMCeY&~rgdf;|`?s;tev_}{7suAJ!L9Z2ijtw;qG@QdW>+3r zlO2Q&h&3*NF&Tz-33(&z;grWe0(l#+>0Er21xi^!fWmb3<=31sAGH~Yz6{R8Z}MsZ zJ@@A~FnVuDeIf8q#V@e8!&h>YGC`vWW1bEm%dN&OoNnhSa$5M~jrU6JMnh}6qQP@7 z7wl(;a_sIK$gQ;kQ2WV-217Y`q}?VL`z}hzu(S}bwQ1Uz5Tu$n)9I@xxw10HcEWBctc1n{Cl*3z39brOQc0XMnf-TDRv&fij*NyUmDU z8o)|tjh2c0ry*Cmo>rGOqcN*Bba>BPh^IjKzi}d;)fR&ybXiC7(Ed5W7YUNJuvOwD z+2r2k`~7Lx%nR-4v+0BHF?zZg2KEq!e- zsQ=Kt`y>pjm@`}Avi9ch%Gh_5aiz-ndfXOHeq5&`aj!MZms)QpY~fvZ;zgd% zHuGc=HEsMw-P`dgYE`393fc2VB|Dt&_sN!l9Ow3ju?(Y!Ti|I+437L@CP_X_k(w~J z6;CS7ovaNU4u3mw{o7W#jMoJbIFWbMvsX&fkD!aP6CtO(JqtZ7H6rTC&r9b;lyy)3 zK+b!))3(7O79B=y0p!KlJU~`BXF(iwu~9qn#(puw{BzY?)UFskUm_4S>TVIxJ6VVh zZGAVo{Fs&DAm6Np9U%R|1*UG3^`A#r$o4HE%$gGTZO-C`wXwu-zxZx9efty|p(I^h z9H7FK_-c$*%Gjegkp~EF)+#QlXyh>mqU1fw%C09DZDPvc+x@Q1)d^1V69KGpE893GYU$w>dPkcWndJr zti_=FBkR$;E}`iu(a@KhuVnycVMO(d2Z35edp#91l?A?~3rF4=@VO-5mQD9>0e>=hS$$)^I$fQ`b^Xu?#@r5+2!UUlDR z!`IbHNdG<%Z{wHalJbu0-wQU~p9UH$vf&!&wF+n&I@A1^5ry4!Y%Qil3d+6!$pRiO zc~ttC$K!nTqd}P#4Ql=YZ`>Xw9HTXH;7yMJIxv1zr3zO>opJ{)Sa2}8Q8Zuxs+78w zBb|aonh;|Ogw4TRWZ1K1L5__NYdr!|@m^j?AAMg=bz+jBI$mW)s z*UvK%&@&u#I683m6tu4sq&Cxvg|aC3#{s7qT%I2A#lTo%7X^`LkV+Fz9Omu1P}$$` z$r;9mQMEGf1(Ny3i|Qc>+lgrfG^1KbiNLYTSR0=u@9P!v` zT>SIzUscD(N`06oK+~;WK^CnZh1D7xxV{(HO~6=cXevc) zmkV?lR|v`Vc8S>1Z>M~47p}7YZ(2&>HutrYX3HmTTZ~xpwk()qtlk@FT;7!RDpTIW zRlb*SG60yB;laB?vFY&3qRvVo={Mxrbmwf)mU(DqV6}ED4Y-=oRiFCy}N7=3L} zKC^v}VkP@DP5w^uL(~QH2OsekeG6Gs=vlrTbN7Rk5s**t_tq{a+kj(LM~8pc8sR^4 z+z1hpqvz+kO4D}iCL_u^ef?APe&SAwVaTFBeJ5hqvT;RgcgXEV~c!HQ>w&@yR) zQ~yu3RvN2z>)LVmMKDhEa;DqQPU%<*$Q%8;4_o2lefMK8?-t$lJ!Cz^8e6%eGq#Ho z`eQK>HxQzZ8|dm!U2>`O=!;v62NIYvF0LSxitsDQ)Adro@C%5zojU6Rv4eSGd7G@F zheFN8d_J)WEqMx@EQqmo5J~5kK}s4VYg)V-GqO4a7^dwlRhZ|2``p1Zn6gYP(eu0R z1zz7LD`;bF8ZeCLY>~GI1YnGqCkbCd&V`m~Viw4;r3DHAiA*2g(UehjSR#$A;(L5v z8)mvY(!XY~_PlN8qy@k%{HDdT%?)!&78G%^eOElgq&1dw-o$}}Zlep&8=p(_2i`g6 z%gLPO0m-ftk5qey&#D=B8)iuGP8g25|F-9s!Pc5|wgs1xFP3IJE||P`9ivR~FgY{F zR{E|plu#AAI|1S>37fOqxA;aImYp4*EFBg7PTf93_OVxa6G>|-T-#69%zA>7DQ2); zd>C_XT*6+l|I!8^=9|bNTO7}GduG_aTUNUr$_97y|ITEG+M6{SF|+~qA~Ii+IGjmg zQ;M>RY@%Io`nt%&9LCQ~^G7%j@I5l^I;GCAGj1bpRqRlA#lvb1V-JYeBtPZ2z7Gl2 zb0^L;ZTPlzJiuXP1x<3R%6$hF?G6)~*wSFlx-LpCyE3iXoX|p5*8~S9iLtx4IQ@Vpq+Yy$3KjXMDuJ_dSr#UnIN^T@}QZ z8r~KO*1+8`SdiLpHV$FcysL)6`*mjALU;g+{+HVTmKSJ>P%l5NB!%}w{n z4**Xhxeq}v*Uh7{%VeUG+yR48OGmiRa)>LO&AZEeC$2!Y&|yBl0rda6s5X*#)|!cT1BI>F)dQvM`sPv*y#5(<^X ztZmL7cRYChbv<2?{b@F?ODZG{GoEPNB*Gw)?)Y;z;pP~GZ9qd`?%$5Nfkh1NynyW5 zU+t=fIL|lBkjp!y+r2egNu{`*W!f=ro}^k2X=WDI%lAK@2kuVcOT5%jl7M3?fR#oT zHI@!%K8;ZNSVA-AO+2o!YC8gU3=0CYmS2yCFMM?PSg#eO=G#rLWA7=DX>q^_bC2xb z&J9lAoq^5{Rogo`8S9uDa$F9W?886)N>o})h&HRI>fR(Y;3#+rWmlK} z^Oi6<3-#u7_}|G3x;{N5{3c6eib~GtAw>_v_}OEROr+&7xHD7SP)L_|8CZgw zw3Gs=%Fmz`1dK~Kcm)ICOUpAKgKCP2Vb;IH2ce|9(_ey2?34} z#gG?@p!V$jQ_9co1C)3Fh&%UEIKCQ1UYP3ltZdwd`is==S5)m+`0c_zmTlU>%-;+< z3kCTDhxh0VVt)%DN6g#&R6N0> zQboc`koA}a*DiMvetx+#UMVOrV>N!PBA95nl%{l#UuwwLZm7#aaL7R}2Dh428`yH5 z2w<;ksyO19?e_QVK;v-W?DnL>`7BU$_xMp91&V%ByyNLZY&FV2ITq7sdEBPd=r^3H zx_BRf6}>D1M}W^-#}X^svG`7-@u>)R?(bkX9}g46GRE^Eh8Sx=3QdMC{>8kHFTnlz zhpuv)2OrGo*7WdIAnNZ|)0+@qI8BjeZv|h&d-j~S`kJ}j>aiWq6N=zqK~NoDOo$l1 z?JgwhhA!>HCPW61jY2ghKQR|~glwq%R)KqZQOrg;$JC%I14fkkCCD%)B@ss%8Em&h z--Y8dlv4Yz%@1w-m8z>pnNelCd>Dou8O!3Yf3w`30x+2#eB#N;%I=RM zLT{m=OlYeS9*|!uO-@?_-kxP2KROghx0;*_K3v@%cUbdWXMH|>E=R3>{hZZQV46@h z54$X#Z*cxa7Prk&j}#akq@-C&`XK}#M_x;v8>zrKCqw>=`+bm{2K>2r{6Bi0b$y*`IXQKGzQ?IcBUP)*#>b9bq59;v1`(cMd9}^3MaP>$?Q$aa43iRWT^m6`_{hbwUKqGcy zg7k370;mjndiq&b0U16m zlnR|bm}Z)-vkT56qtaG0NEXu}2~`G1q@wk5s^NV;D&L_XG8}oYi^QSP%M7L6H3RhU z1NMAu={@^O5bH-Eb{y9+(LgJtf|B5!t!2`b%mxumP2YBV!|Sk*C$lR=JudD~Qyjjx z@tAUc8p~QS4vi*{+dZ7_3~lKlsr)CN%$&DXd7NwVwjwPcgh{fU*qnILOna|oXXy7> z^+QQR0qKcfRd=fd!ELfy^(M&@=-C*P!`Z*%$N9ql6>~jKaxY6?-*}Akm3RtJADx0V z0Q@#E$t*MI-bFlwH&XVt38)crp@BkT|4~{eQJS`DNVw5#_Wj` z$v7*-lHMh2OlUtv31!C&YUOYIJuiil5gpu)FNbJg*;*D0)7#cjkx=VF2lMaYC#?+H zA9ZXXV-o7tyVe}-7*p#{25fjUlucnxiyh%K)wT70^FoW|Q(7`;}esHy0M;s26H8;{bfY`xDtRy;3!U)ZA4xm@*^+?lh3`ERls>J z2hYN;%9sp#7vw4+4nuPYW(d!VUWhSsB?Y6_RbZc$1UR1HzJ2U6jA`+46NrS+{{7Ej zU)zkLG0!~4unc$a&slk#$n4GzML%WVivh;?#qk)uS*UX9Nbht@#03P#&4=^prh~ib z7jW`TG)ILCS_A7|doCF}*X{EcaLC_*Xz+54P2l-dRogJ!`Ubdy`yl0kcm~`QHbm?T zpR{$gIx!JMWi2eD$Kz>H+Az?E7&}JgWvS2-+G;E#41ZsX`i34*^P1cv%;}5>Bs&B>ncxDheL9~ZtGLCQtrqS+OiWn`zn{8 z!b%NwRNGcbimx|_V+XlMM9d(lJ@*!^+i|BD7}u>y+IhJtbu_5!HsqKB#F04voBBRR zBX=++jqix1o-&i0v+GXVNV=HB6SA{dvMf4gupO-4DAA?Zgq3SB>}6Y1gtP4Qp6htG zvUZgyknIq0R^XNJFrcwT91V@6Fsc%uGV6Sae!muO_?t7<`BVEJ!mWlc-~}NAvwfIS zm^+PLegiW-*zyg6ZJ51aqM{R=!FEO)_j*lMy zRO)u-HsYY!>I~v2Z)WCU-+g~0^50)t{F*+&Q(c|wyY=gbU@|@84wO$0By4))NaeM} z7%w2+6^d;%=*>Cg&4h1E8IEoJdXZ_OU&aoEf9(x#hZ-+39)iQ}yvTrUoO}yT|C~UZ zJAXmnObhWF_gIvw!CP2JlM;FU4oup~^W}KoYIxR?4&5958X-w@uT-84g}tP$R_l6!8uFLoc3Y{x3N zQt*fT`}KFw#puFDNg(##g(&0fgce5KGT5x;w=`|+hz2?l*(Y%moJ`XJ@|DI4LGi~% zWV0H^U7I+KPhkde1o5P&r0*1v`O0e+F+-o9pT<4FqOzyd?lA=0H7`!I6d?q``=P2V zoc+)=xZrb}Lx>*WVD>|K50!BM+`(j+GbifQN+O*BdnN0t@zZHvN!I5n5NKo{73c!AF^E1pidg< zhOdxZ8mE&*E5_+ls7pZAXpV9lP(|H6~rw^IFFa3Cn0d$b4 zdj0Cuk<8*5+#K=riVPNFgZ?X4GQV}#z@lf|iD>LJnEd+H*N{CT z-FNAA{MP&bJhmR(n3r?GQRW508Pc3jT|~wI1!IBv9P9t*6lKTlmM!pOzm&JCw`3%K z@PkUjiTl3XQVv%r{B4_WmNIr{-wyClX8W^u-175$m#A)==!YR2etE@%11?{vrpi#{&;{|&lD9ALTZV#E@xzPm(A`9CqA%OIWCL|9iRLNBMxv&N zzT+gJ(cpF7m;Zql`=EQ%S>MeQ(vkW3(e;tAJg$xy^}lG!2vb+pdaqmkrbWJO;*qjg8h`hfP@Sr;uRT{nim$qu zzq(nFp658335dN@Wl<0dWGD|(wjMRaw4MR~#&*L*!-~krT?(&xdt`Re+CB+4P?!M+ zs@b@Z9||z9$bLw4W=)|nXw)wuj{WEGO0Rv#tM`LOWtmdGL_)GOJ4~%C0(66sXmzUfWfl_3ArNV%*zk_s zZxcV%l#rkNV*1C%uBQ5^!H2fM={7TZzx^RQ?gMPr&cuRJS7^ZwIWn&CY_ylM zVjQ*NqPRe~w|z6yV7?EQ$qC<#g9z>;Ai|~u$xVuUWY&MvQ^GkAM9!xH3;y?jOxgcH z-_>XOR$Yv3uoWqUL5P?Mha7WyF<}6x#f|Y|+KL0gG4kIWb!b&yVoIY-8Mc|)s>q3> z1_kUgkf9Oef#!M$WmTWj#!8=#hV}u^=T(u+I3iN+pQBH(YB=S_V0=VywBqTz$EXvT zKg#(I|sb3>zRtC5{Vx;*Vy28OL;3-c5w2B!+X1tJ zX{l5`3YJ zMT!pd{9PWcCuz^l*7BWsRT|MS@O0*fNOUrwypY^#v=IkzInZ2vo?dGO3Hl_ri&5ln zyzcmJ;(hAz7&V)^Wqmoa%XvJPP6+92!obMAmB)h7ggt!8qB76$#rzK>QYoxhG;lX3 zQJ>no8S5TNB|yyCzi4zNm(=ohX<8bOnV1(L7lPoOLsn=}q-~X=ITzZ}QVutHGbNyu zY~tNwMhf-Rab{>lhzJIE#gKKe=PCv-jwH6Qq!? zUlQ{)>370A#DI7f&GSCygVS>HM^_2b)nx&C)eYh5);FeJyWQ61e;9amlfPuF0jK-w zI#0bO0k9!vtbVZSHwq*x9{B8G+y`~V6V7XyJg0dte-?;AE|-M#pLzU3P8TFRis9ZP z*snyT;)F?sPhTw|R5mHbglkWhbAXs@`1O4on`|=pUMp*B?m8?^`A`1^%i)VMUxbAI zAP7oTJ^<-)>}wT6;TZ8Gshj~k3+qrhT%01p{$eq6GfVC+?rcgXI@%PE=|`|@t})Q z3aZ-E4|&X!s*A!_hNi>D&H<1IFyw;i1SUqBknQjY7mydss_+ zA#!*~jspl}d_0wstntjxYkQkzC;sb_6h~%G&W>KZm|+bDqEgNbt%vi9&}PiAy5Fj* zMl!0`;Dd57!j7&fc{JbXgd|g$R2lIPYQoQpP!ZS9?4}wOW(FmFeXE%uJ|?EDuZ|88 z4(CW4PRTLo+(3|ws4+rVa%2CPKD&bqPxJ0G@b~iDkqH!RwckpqjTX&MbLz)^FvQ%9 z4FIPwEJN(jEbSB4=-*&eUM{VHsp>M1_-@%Du%hp(c0r}{AP3Nfe|GwviGJ(DkkTyO zlz)AB9{}tGzH#iVQ`|_~M7sr2q=7zdb|M;NOSKJ`xfN1yiFG|if`x_6!7_ssDKv7& zuVEud!^F$tup|p5EFK$NAn;}l=FU~}y2F#^-JAwY+=wjU%mKLo+3iA->8x;?O-L_- z)ttuKZUhU9ayLp{6|`XD{9j>w5IV$9z?r%%+sN;CN=n)*?4*wAUY2v6Jxq_xzE^b{ zrIc&L0S+$lq3#yfoecs?e(X|NADKYH;lEgr3xKR;UCsD=x#fOKql`Jq$*SG$u*oF_ z#&1kcy3M=iC@mwz|BOVI1CfB>W5p)OQ6;*!^O^?Q}sL+t|mP$&sBG<7@J~FZ6b$o_NH~8lzNY z8@$Q#3Fk0kRA0IeiCk18jPP)>4w^5-2i&(=-tLvuAx%L~JJw#=TTpFfD~MsR?y{aI ztGxzo->L4ho9JL03zwsyD{L;gfK2e#rI=MhDUk42Lox^r`mZ5ujL4fYzYKuTmPvw2 zhyOr4^Z!GV$dx)Y#~k1Z2mjN`-s*j0;57}ykK0mpI0A3QdYdQY)4l|HTR z4(~P>8kuSRlInX<@tctEQ(RfV0v>kLc~q*VPf9GQ|vy0RAqY!_6n zLQc2j4ktqO>C2L7{Gic=4$L1L*1zH;?`~f`tL&#FzDEKWkVYSAH_d&ztL3psLUApX z`9wsfo^d0C>*XC6ojp9l*1Q})U2m9^LNYslP)ExXBaho~tqPFAn0Eh(M=)oC7?DD| zE?Lb4}3ZDyjD+7|aWc*IQo&uCbBLx$u&C@xqT{mM-@ z^xYwHXOXTly#~Q?p2;(fsZNENU*yU1_=UFCYVtt8n6rum@ypC?BNiarM9x!+k=Fxz zcpv5DuA5=PrflbArA-V=Zo%O1ZhG7@>Xm^9!STi?p6EnJV6-m63bZrTUvYMyCb!|| z!vPRnB~RK6Ws+VuH6Nw%vhXcbkJCe_^bE&?W(|aDi6(vx_{B(4v?qfZVuxvNeY?)x z)R@yXu%m)IfY{w{f|bLD9CkJV9swD>N#gM!VDFYI7~;Skav}dk`ket0aef8;KP&Dm zv5pFFLvAB|%Z`d>i|oxB;(q$3>=)L}7}VB@d8vPKDcbb**eOESDhZ{Y z<$V5@Ffkaxs;)>1>1r$m?RtB=w)3;0#JbB80ZofF7b!t8X2_9YWXQH@snUN9>fjOV zl`y}4uZE;v5|XV*-tOZb@y*l4mmQ0zw1T_F6Aq8AUC@GVUfenwEH_(?{z3b!^pFA=!hmjs+w znr3;eHoXwD=1P7{GBF`Y2ZG$}27}VtE19%@l{`3D6-1$VA>`-SJVWZakphm9EwYqY z?hfypjLbtrLokuh05?8mA3vr$i0Oh=MWL;-Hp+D{Yt;4l`jV@{mfC9 zJASTe2Un7^EYK)Z7|;GUd!8E)_DCtH5(WB>S5(c``npXK*OzHt4HLoN9@Y%=)NQi} zjLM}#>8JEeFUJp{L(EBSGJ5(E8}bRJ*7ULu5;aQ?eE6zCUZN&uynnu5SPMeBvG8k% z(x`cUowsAWk3E{ZNG&T4Db8P7M)VKJMtJ9k^ublL z*38)d!0V%q-VX?Vbgk1)TRZ0wNWlcSa98)jvpxlQ_xp!CpH4h3?PfI$^;~0@jScl9 z&La6_#hZwPY!mkuH^sTcfFMZ0iv8~1Epc4CF-OLf_0io+26O0Eii%2_>~{{{h4|y& z%sq!KMKVM<{Q#$GqmZrgSn1>))Dn$XDVhGHS1MivTZ39mz6#36rky-*9(F`#vWk*7 z&5sJ~nt*SXWXv+0wH{rzIc|BAr+#%%wj@t@&^CseG1(@@e@{t3?p#y{N43*IYucIL z|3l{Ix+rS%_7^hVjL{q~!~tl96vP?^t-O(vleb%@-pK7H4RXM5uctD!d0hk zJJdkYoIghIGNZ!d)u-#NmMS^1U)kS@|35E4j(H~b(sIfB__I$`^ER+;qD?W!;DPQd z;ebKEgqLWo4#Z)hNy(GyC_sbHBPieMPsq`z_J^wAz4@3&J- zWi+mg*h2{VZ*LgqWx{}XXQRQovA=t*1;vBA-uv!|+0~0vNTxccW;cHNMm1ZyMi&A0 z74*HFW%!D=tLDCsiS-SJtW8tMdc63&BBygX|AAMGs}5WOYXL$Cvss&Nf7v&&z7I0- zk&(NG1GA10qn~%PMC}Y1S2uyc@y^kkidRQ974nQUaZv0g4{Pk_K~ zS;==O;fepliD;LR$=27N!~-Un26VH1@m$$sNerJx6b*(Iwk1nFy}nabY;`Iv@_h9z z=m*z%3Wt*qt&9ol&**Er=<|?1*mE;DFO?OED5Brm=5`6S{cU_y&IQgD;m49^!S|7I zv)3v`Iik&gv})*a2AZSfg^cv8-6;^W)hwz63s5D8?zS31&9Hpzu`>1w>Z1aj*BMYu zPeYw^uqNVe3gCKK1d}u1!Hk0<)+jez{p}C0sBwp9i$K-egls_U?QkxvGhf06?C$jG75r_^Rkph^)Qm;Mhb;88Swf7aJ{; zK1-j5H)*}lwNCqNG+V5VS}W*RfMH2FOX>2%kzbO;9suK63dOhNymTzRl4|Rr4%1m- zZFqM}g1kyb3Ke4h{!+hL{^Li{_w<`m!_Vw%S3_$x;Qk7xG5?34yEpkR386S1rDxaO zgUq$J>!cc9$a67)isj)ekyp-!3&qHq?Pf*IpM%&Q+H}rQqc+nz-F)ro8h)gZKI2s| z5CYcuqo-3Lc8fng(zdm5Y{?zckhS#h;y_HnyADJFRq(fD>UI*Dw{HTVmb1DGe?Pxh zo1}}M;Ft2!K%Y^#$pDbY}jxr zvf9M8B7`v~^ zpPcY~W)3#4Nx5sC74ExMo^ZeSqSB^PDy===`DfGO;8JYLQBlr*(LVMRW-@cE65fgW?rcZ$@I=F zfi*t6b5QlP1Qed|6lZ;PeJ(t?aQV?Km)0m3)|d_+``aOxr0Ej4aB!Elyw6CE8-|{A zr+`RZTreK|1+!r+r6AFmPO=2H){~q$Pj&=SN6h2G9@{y>68~N|Ht^}C{Pe0v8i=|F zwyJjKg@u5bt93J=&a4&;x{}f2qmi;p!=v?@wt^4r#zrStD4((BQ8)*37Q!UCKMJK< zm&IRi(Bo!urGp~6E1EO0ehq0V?rafxPQQn-&MHNDTE_r=7k?G(s)j)`ZFezkoYF3h zbg+gz-iIgWIYF{jzBv6BuCCX6&^i#cVo;)x?sf5M^6z{w`f73G1#|0n`eq>YXe{H+ z9Dv#H694D1v4QZ<*M~z-vMr&vZ_i8dtlxr*OpkruS{wW>pdCGfR z09c;QU7JEAIhkRa_~+M=dP&Ewt(5D*;#Bp z%P)puO{)i$?d-(8%Q!0vlO&?EGH(v0MoS{Ya+3}Ve$_Y$E0NRiS96!+gDDREa`+pi3fJhq zlPzh%D8Cx~r}-9yl_19xcZToYWI7*nhBE9jS?Z0O?R!2}vb>USo3G6{c)u^7X9eFp znV(1Mnr0E&ZVNCH_8NLSwHaPKSEY$G3BddcTP>U{X4b@^@JU`ooh}eS2Xp`u4wgBa zQr2qpN*c`e4ad>Qi^Xicb3D%|CTL1 zfP|?LYu>@b{N?)HJ5k{9Q-9R??uO4O*KBF@l>wnj zo~URculUC5;+1X+sI$6sn{-o~)x@QO00HzKJ0h_fZ#Kw5uwwL5>Zk&9vhsR5#FyWKkR? zd|#>2toNhh#3I}%&z=;VBnqKah=W3)l58-BOJ)*tG^uNI?!|HD=7n}kdA)1Q-J=Y% z&$XqbrnUBeKizR_1QStsNiJaJ?3=EwhXA~8Q}H!b0w1>2-3rShG;*Sw-Fkmt$tmvX zp*jC$ZETRoS~OEuEJa_fb*mg@xb5sQM4HX$yR206g%9Ol!ICx8H$vZ) zgip^bUH3cU%PbR34N=P!k=_l*9TF7mSwO|*YJR`K>iCCgmPV_$(k?g05p4vnmnYXS z%rN{cc>7ns>pn2vPBOQoWFkBP$~Q;yNfNKL7z`)%$bZcu79<#@j7zH`wP!q3eN)Ep zxaM|MS3 z2^O!BHd!j8^qeEmPctIS)ELHh^QDb@ThWuhZ^4dBWQ1=%qS)~fSIMYJRyBv!)$mFQ zg9r?lhUy&1baE%zcXrO+Pjr3r2w9~%{;LwU zUCzg3F5pvK1qN&0w&nb@p+IjrjU*ZQ?y-xU^66jk6s1?A@X2t@ZBfHD+V|pt<$#%&^Jz#^c9hJoZl?=3;8I=Xv5UH$r1W8B$H3q6`xBtHl+lPmT}NOBXMJe zutq^icSpd;>T(&r78o{5v|-stOb>9rc zB)%Ddw7Wx_&r=o9v~bW*x(BXZzvYVRpI@m^>we`$`K)(n5sUzAA@svOArNNz_i%eYDlKHrk z-K*pCdUu6m&KH{@F3CZbrlHlZ-yJ`HX$ZRF}#_ zK0^uT9`NuXE>GMyR^5-{-1Rk7*~s!yB)Sn9bv=ey z%`{E94l$MpCKE+U6B!eG{v?0t^DD1tt;myj2md9qN>VH&nP* zByXfW+$ZU;8i{=OZbKq&3+bP($`^I~Vzr?Q{AFcSHzDR1X)CykUmrUJi839PL~RYs@&{~1v?jK=R~sI zJGZjXFeY0r93{0mvExB$5;HTs-GuVzj$d0`0Bmxt=#HIKZ{6csoPns2mCX;%B8{Zz zu0_qLX1qc4N@ReY{Y3hDiCsSK)`c7|85ixFr?D_+!B6%c>5y5^4sJR2b;5F20ZkmT z`Mr06JNJ4idEK5FblWxrS5Pu6rDUG01#ewASReI6@nf2E@~0ox@KtcQpc;kPll0@Q zN=zSvkjAyqs#-_raJ#wwq+8cnUE$9C-~S%`y}~ zLz(Ewq15PZBoOmN*G8v^h5sHttUDuQfQy|4Z=P!e{kU8)QC{Ro`s)I*Ni#b2j@m$?`_+2*ODGK03}!h43NfS721jcLJp{#R0d z|4o5n+eblO5@V5zU?0cb-x$KH=RE9=)H+3o<6vadY-ZJoV}6u=)4kPvvYiH$a0{SblJ`5&9r^OXR(@{!lCzw}S+{Qj{icoI-5Rg~u zOeh&g^HEo=!Q}ugag5znhTq!$FsP;}UHrXKni-M(V$yX!K|InNFv5$|(X7kQB%|_y zc&>z!S1IIwrCqDu$7p59VWN{n{_F0)f1Be`-~5XAjyVpsYX z$`~2v5oYlDci1=(>wLnD1|w+FRBcu$lOdX>pH0NKIf^(Gr3wQwVoCXv=^mU8qRD<5R@{E}PvOS-SazTx3aDdnIv*JO4v<oVhGsJC>u|u$j8)nd^|6;vUIV73W~&SsY3r(T zs5#jr24CIObbLBSiwHQ?3wn=8M>q;-SN#Ha>W}Z04d#Yqpn@}X4g(&j`-^Iu=>&aWjDgr#-cP+xl21`-nNTg_|=Tw%< zJ%;N|m3ZZ=7WzJ+xO<2DzyeeN0Z#Zw>L{1Vz<Yt+`8LS&J#_{{UV*e2*j&_gSy0esn|b9N zy~&$#XuGiWgl?^Dr6vKNzZ_=wG&$?HK|%t^C)9GozL-}SDI)4uEk4I@@e&ILZ+}bN zH=4mX%oJN^M<<=U+LYvO#fli{KWESF^r0vOEpC&3i{tIdcTnw`y@R#4p2^v6j!i-( z*nG5TBOs(e=X@{5!A7chuV|&NE&!Xn;gxswQnA%gj}jy$El~O1`YFzih>OKcEseov z)lG+FzXe@Gipla?<}c1W5PBjLP60F8T+d3o>^LeslrAaN>Aiqc_=r3QOcCWa7n~kBg=ajNuQp28*ygaNzIg>(nJ?*75y`La>W6gRvqo_SqaN@; zr%#ER>i%gec=K+acMo?phiwE9Koi{V-jq`_7m?4UyX~y@2EcMrWISK!jCuy#|LYb} zr*G&`!n4Hb!JH%z;&d+c37=eE{ZEEV@iIf){rw;0aTB46??MZAODI~; zf!01mt5It9rD5-#w=`X-(+_CBz&JSp=yc#ylA|7iCsLB!S**rsm{ik9C1sw$45eEV z{&-hn*&yD?>b*qf7JVCAdW~9_qeC65Psq0w9j&qQY6HJYG;7-gDLIIPp21H6^9h>L zyYs)nt`)s-t3^xP*y1zC=kPnD0}pEmK|!{Q&gVQqU*(Fn)!pu4;3ZJd2l^A~ zP_T7%tuy}JBY|_U!}_rI0vXP5k%YfHB1;H?(OEe{?phBq#@QF5q19D%|rr;G01%EaD<;W_=G01 z3;&(7t;n{JEqYvQOt0$6p^ZD$XG8qT(o9vAb?wmYuRmq6mHJR8hj>A0XRbv-G#A5o zLv7_c+C*{!B0TmM^++&eaQJp7d8&PlLB@F$W{$?p)0(@nEKk7ijj?u9;G?ae&rS zdixC8??6K~Q~FRjK5z2IPzs6k&7SIGIG<@Y@ZM^(Qh06`*e-`xydzz>FH7WoKK=OS zbTIMtmA)xd)oLuQNq`4cfphc|KfdNMjnRed^hn~q9rnSaNm(lFzOJ-Kq$aBzG4-lE zW`t3F1y1z`DBG!s!!{Jl8iE&HixGYc_~IQnincpFp98m7Zf2i6&(&hr*r5Z}!qK(c z!~J!U?^yH;6{i^KY4OE(q%8-*YKxRHJlUtZAznq>$5e*rDnr8y8r%9Fox{y8k!k}A;;oW}j+j8U0e&W?7hYatIQ{L7-%1888QX5+@EQ8Ar$u*JYU}@(WhYR>}GI zUuTIgHD6-qi%4-x*FZ8OgeVaqe$-%iMp`q5qYeA9W79F$Y8rnMnz3HTsbH7Z{DNFtJYOzs+psRNvz5iei31Htd zeWQGtL;`0SaCte!tg-Avv4bm0hx5I}COjiMF@>l1#6Ilw`IAWu zj>07JQ1`VY{$dZ4{Z5y-Y;6vM6R?v*2a6*q8IJf(0snC@Nn)~;1|wz)D+ApsU1iBQ zT+Fr7Hbc@ZlC1FxK0(x*8gwgeiLgV3x|e{u!$*hm<%?6~E*G({NECAU|9JrkK{0XbsnrJO5ec&aFckE(Pj1u(kSe z%cHt<=lN?tp0iT0%*6mHRb+opV&S(ZsZ;Ym?)~C0%UFg{8nSWOuwb_`i1@#Uc7;`v zIWGpggwLHqH+vJ)+?-}1okB~v9bOh)wd41rn>nZ9t!p;k-;q`t#V#$zyL)2VRn|E6 zb%m@^3W+X@LpHq99Hb;Azw`EczZ>)qx^jT`$;Za&2q-7k|EML%pYQcA!BP9u0-p~( zy(=GxMlXQC?8)3xDqaaOO7vHzpRQ5PdnQO8GHusqDT<) z-9?a}dqjnAfk=hqqC#%lq0kM^mCtDQZjtO?5^+I7zjD=vaTP>c4z~p`IhE~fcoCZ! zYtIIIvBN=k(jlIB@$s1aLP7|#*8+{nub6PuvQtJ>`s8OTI3_V-v zPu%d4_IatM)=&Q+x{R};k?e7Me3_MG^dJvg96d_yd8IYF{&>&G}2b!KPj|W{}RuRlDzSRj!pdQE1}(?QF(+5?vCs8cph%;UnEHv}UZ2o$%P1 z$T$meeCvF=(_nSMg^+lLA}pBShSA*xZ~Ijdw}_06lL z)NXkluPdwr$2qxWHDr!=P?uuZiMIA1Loi`6h3mCAJc*(C8fI~(?ix#x*rb0Tp2$JS z$mI?nyz{!{CSkF(mxd`Z5?l}?b0nVA7m|pgn|HA4be57z*kP3F!``_GG?3!YGw0|@ zqBU!WB=DWZgH<`$BP#D`A}kKcV|l=S9Dnza?;_yDy;qfvVk-h9XC9JV6stCWiy6fR z_`!s*b5P4Rgx}IC(e&0Ct?P0|rbMFA1THtedkyrQr0nqF%yAw+`#4#kET703P8=$W z6+QMs7}OiP!v!|M9^wSOV@~lE=74b9ar^2}*w625#$fUHoPf?qn{9XfD3iDcJ&f+- zRfvr}oE7mv2xi1TTGo28kvK6U0~t{Hzy8anjy-zti)1kGS=bRAfc^UqX3fR>VN3&a zl?9VLVm^Y+^j4r#g~E-^`s>%Puqs>D7QpVq7(QS&{{H|(LA$=dJ;!kzqImqPRwi#W z9E@w_sL=yukpt?w9wDGc5!_{DM8lX7x6E)3E{-LqZuQ_1L5B z3mY)3VZQ4dp@`ThNG{!e(87Dtug>>SC6S~y*E+lk*T@du3iM}mk@7}W`?kP9btd3N zJxbvk1JYO`=%NURtUXF{Fu;hA5CUYD!{H{A!!2lwrC`Gh>AA$wlXU&DSe?;e6FaFlyD8>r4^_!w9>RPB4CxsO z!4qw}GI-ZXh_NV$dC=o_zJt4QRWWWuqHUMAwHRd*ZB_G_TgY{CQ?kKyeuQ551%`ox z-FTm?-cy3mr0xm~Lx7C2%_Hh|12g#6#PL_%VgrJdk{}3>aZDV=gh4^ z6H5yLxURr7O(Z5F@@O;~xwGo&X`NO*V!vi$Sxtht%f(=yAP8tS+jP5^iTNsxW)P{l z>FL=Oz0Mi2ALo<64?~g9F$u+(*+HoL(ufEl1gG}MocxT0B<|y27=jPKdW^eoVi^{O z5rGpCbYM74K5~tRCdSYPDX^m&QO(2gU4#VNt~2z8qzpxZC^;uGxnx5a5GVG|NW?sU z{2sl5&+w{`s5g+I#1_dv5&G2YH5}W)b!!L&mSy7mKECf`7zS~iv`G;7X`6(II7;kv zVT6g<2ZRVNv)=PfNno_1j7zv7z_sZ!Kfqj zeV?H>%*lx{VxvDk0xpZp&?64i91mF?&E^J-Z0Ce!Sy*QAtCnHR2@K`Kg)ylfey zH3^)_nB|Gzs7|8v+y{Empg=os-jRknpsC8iU{;hfN|vkYn}^uA3q5;RTc3xds2bds zm0R$n?-D^i|WSErK@ zV^I)cniC?6fQV;^epof;9ajZ&9-F;0J7fAJviZic4d*&GWQ@D&oVudq`7S$`tk`$m z@g48?@a?nD@aii*p7RufZxhE7O9)J}4pQPeFH#d8X7E1l2bV|8<2r=CiD4KRhJkHb#7KnEB8*)!w|^2!bJ|VdD3EK6>&IQIwJz&qbayFl#LF8zP+p zCoOVxbduIBXf+zxwgVCx%{_*LAx+oh>Z*$YwD%A3{Q%DoF~txh)J+RV#0)x@37J!? z6ZCs2!C+xp4yFK02!w6mm`$LG0IseahW$RKX%fW|y?&3*e|)Xt?281%1_gnGS3&2auQBSB=qC1cO>mtwZzl52R91Z(_CnDnq||oK>=2zosf9 z{gl_fHNBfUz|`+;*>|cc3|uEH$_B`Hk8qz3s^@Kwa<3hq>nC|ba)~50${_nEGdZO6 zvr!r8kZ!v+XM@z1%j(($+?3duS0ZUcCVhFXgjFS8z76B;IvQ@*!Lxd2NMA2p*B%p- zd}aA2hO2Efrr#86Vo2X1h29>+lI`G8|sqtdcIp(wZ5{`lFjD`)UZO}VE=TZoSfLg82!=n~Q zhX#%L06ND`xdc1;pu;bJw95kMFw`=YSVd+$D`_v~%rIHv9NIDh;hAAWnl z$>~e9S}leHNuyrJG%Y+I8V#F<1GW+3xDHJ_1Z>XwF8A(PbO#|9=g)D>I8DYNN7s?b z76qf5HM(b`4Ou@b5>cc)Z-aLg5Jxd0w84@%ZtCHhNDoG7j>4X_^*N#!15JD5BTzBM>-wzD|K@ zS-BLGX$oxH!7)vYdL1F)VE=$tv&HMLe}bn^pYr;{hj>SabbTL&9`_#{6H2%^f6mGM z`#d{8=luC|_74t_u_Tr;Q511{dRp;BZU?r-1h+BhcDo~wbr@TQaWY~s7%&(NFbrcN zS3^+(WPMq!Z*OmJDv2auEP`P$7|`$aIe&gWQLaB2efgqrd`4Xr!Jv{6Y8?~TG*s3* zEDdjdLEE522z08Xh19{6V%*+4JfPK7zRpS=J^@!xyLf46*qBjVeH5mBGpiB+R}K8i zJn40mUB@zdj~U~Z^JDafLUokl|Ba!0AWQI?NEinNSW%8Su4*}nW(Ms*b4rro5k7;8A`yEZCe zTd^~wuNR8iV^$CJEPu@`2F9K7wivfzOy9LdF&5nxRbza0pIfs1t|PTm<%mGMBjBCU z_MCi(Q}O{40)jcEmv&>SVyxkqYMpSO*Lloat2^O5?NQbrO*=<~r8~A2jf#t+8=iMQ z#^vxc*!2e-?w#@A!95;D5y9Xih!exJh;3@M7jWaJho0QR4Lg!g?f z(5%;Jwpuv04G8M>>3^iiXH)S!HtRGLoX->(jmJ((Cmm_9eP#>9Usl zA&R0x&9R$CI;=BXw@$m=!l~(&Zt(qpt8N!B9wa?vW}GOCOwg-PjooE3NHA`gSIZgP zo+0LzVcRyIU!nV?_U~mwAuw~zI@hJVy zK1$cM0e&9+K!xnmvd2_{;^^5eYm0?pn)aBM$eVWF0W*I)KF=G#8@$6~0DhA%%~rt; zurgPbh`GKUH@!Yl&=!x+PdGSz3CFzTg$MWPvq$WAA(j{j>h3)nZiA@*0q0jw==b~7 z+Ac3XJfeBwA?~#~w}w~^3&)z$)G8)_NhGb2Ng=$XZhM5Gl947?B`NcVxmlp`bp!57O?RJ}{-6ZgR4i63xhLIS$Wg@|J{}Zneh7lkC*nPsl z=F!vV5Dp24F_&Er>34CBNO`8^DC9yWc^b0mX!et?p7%L@p@xwpf|%$#^Lnx+)zeOn z{>iZr{OqZge0Rgo3_BcJghm2$P4h|4fV%a9H>vCfFJnwcfZJUnob0P$XM@Jkr zni#&%qw{m55C|b?wOV6&a<>gTf?*1%vPh}{Up2PRDt&YlY)azg;V`kFs!t&$If_LjBS;7*+kFkMHfNQ&QAc$MmX%+q8M6ReDL%khWT9#o`0Q}-}sk! zcHY3ZJi@^vLQl|W-orb)pmX&va9o$8gF{aCPcZ~U#}I$i!GE}q|K9tEY>uuD-P3uz zaH_}i!mMK`di^p`^3ue^k&KZT&FeC0qLCAsOrs41B94iG^Ye2qf^&oreDu+WczwyM zFF(W(0%5rrhCvu6Nu)(6*l*kiDT#(rPG}>J0kHrpb_op+Aq34vlg`x@#9EFAJ(wZ87b2BQlB1g`1PCJ~E2K%gb-?M-5w=s~ zpxwYWz>fM@hDFV-V>>k>-vbGU`-k{pMCAL_noZ&$(SJHPJY?YcfFue6Y{$uE(uYHj zzU$x^f@ja4b9s45b8ioTlhae0jRuXDO?@v(?A+;ekW$j|JrIJIUwWArUwWBuzW*Lq zS65h;g<%-uWXcv{M=&f1-EOxuLLf7=7wuCG?q%{up6`v7%a-f)HM59p5Z?SrWknCP za7vanqq^HjBNl8s*{2QQ&Yqtq#6p$K(p`XCvRoy7R22m6?mK+T*4kpIMU9ZTfC35<5fsdf_%A{dR3p zjH0$ElAVNd#}U1pzOM)s-;HUA2dId8SOu1K+TC}2A$ZJNDV31mxA1uYKFI(t>!+jueJihGsNZ-J+;PSG=a4=+VZ$FV65&}cf88WnJb*pxYRZH~2 zqv1Kx;EZOoL8sH9e>uP#28nSx5=rvq0Gf7f(h(7eMHT`e6U%Rqc$FE3z(nxgd*8uK z6HI>;8MIq%TFoX#Y;t^*7|e&EPpjEL0BuA%k4&N-@Figs@`3~rK$u2R2r2pM_X`~A zG@^a{RQkMrvX6h#r{5c3gcjH_zUL?8NY8?o9Ap$gG$aheJgGA>#3B+uP&p?2NCy{~j-& zobbZY5#M<4J(|rX?RJ~NV6c^mpLYbq1|W{&!rn3?Aj)zp=!AuuTfz6nqaez1D|o)g z&>N1OD|>0~DoUl0(gA1{L7)c?i#VQDkQhB2)8KiAdoLY1=hs)SKG;Cu;(&_zp zSw0HAoca!`ZK57iHPO7wy{(!UIYZe*ud3Xv(nlM>!9EdUBzsg5nV>=_f5()OvhwQR zY^N%f)K7^FF(Nbyg)|q5J8TeHd9vkcaJN6><*1s3&nw+>U8Khyem5#{S0&ok)uC-w z?V=|cg&oCl`_fzuWc<-2YvjKK;V+VsCO(!vw2n#IBN=|Qqt0aj|Qyk#SPC`mZ$sRRi z>~bQHNK!n5jFa36S8qu;0%A$s71Ufi$%7yhd#GzWNF*|p*tVVIc#b7C$AUQG;P3#~ zsZp~XOhd4La6sLuAuw`c!FAk}ND#zvl!k#M5fOe6vA5SIj3O{B%-AE0Vy^mq;#gvt z7M5iZbUGjmE_ywNfe$gfebHfH*a#tT9EaCldyV7cV@^&^I6gk+@#DvI&d%@$Lp(2u z63PB<8}72nYYeIkQifH^9$kkxj@QN$yC@$+6`3(6gXC+}>YGcrz$GCk77C=00J^H7G{jSPf z42!^~8VjfN5ME0Xp$h5*d|Jaf+)N^A)B34ZVN>6YZN+UE(j^-~h~Em-{9*GrBg})H z;kFp7@JRQVO!9um+M_b+K_MRKFit*X(W%RlZ;RM{H_A|z>tvbEfQ@p(VI-+^A9&;X zD2F*vHOejAx2pMHzx*1?uGwvTiuXTg^4U+FGU(fU^ihvidykVni@K9UCL}ul;Po%D z#pRfsk1l&OwpNn3I76dRA3MgV9fRRQaLMWENnS3FC0E^xBx)h6@c5v#-qDmWBNmd} z4EecaR&Vm63n`FsoDdITOe_SkX%a@se!q519LHEEC&ZaOECeI;lBz-&gfUI&Cpilw zgnfzC5D-IP4D)FEpcmtYmmK}-`}ikK&OZAB7f~12s$me*Y&slW^l*9uu1=2dTeZXn zmy!y$?c_i5;NXCR{e2v#hHYBZ92duNFoj9IR!{n|^p?4$4 zFnKiahzy9L7$c6jJb#XX;A$}B?GHXg0=8u(q(=-fiM=)m0^WJ&9pX6V^z;;f)6-Mx zjssCr#!Ztx3n8{nDrrYBRG{1KP9#n4_eWn4JyCKPhK0*|IdxsFKg+GK>Ieay9M~4T z`2}Ug(RQj6xhkW2oaR_)wQyR+*6oQr3%7+;5*xawhT4-Bm$_G!rPRp*-?OyTfD-YrQuhWhkqL*L8 z4m=#oRvhsREX#lxUitXz4EjSH%Or{s%q@7(b3NESu2tXt*x1lsRuSb_>&}kT{Nc@4feEx7)a`OBjYU z+HGpJ8eS9;$1&}8n;-}#iQ4}E%gh9f%F-cgI<$lnK19e?Z6zzH5otHhz zp&8Ei?j6u-re9Hwr0`|HRW~ITY~|Q#qXl#$y;}b=BLr5RTzZkv?^#)dg(h!gxW2+u2wsev)MhsLLzxCxTQlYElU=WN*2*G#`22lLLy||J(&S^+V^g!%e_8WR9jTNmqq>HI<&`e;^`_bG-K2!#(zxw zxyc7xTuycfdOg4-S@F>|9ZA+6W&OU-;tjmJA#O3Y#gM)&&VTc^M^zNsG*PfShmlES z{nV<*+HV)UN_Unib1m~fq!%2c6Nq(%83`qn7X(H%cIybFL{WT+_ z`DmhPghQlVPwD`S-gBf=M}(;2QZV=ovt#Mq9DW!ZS1hvPWB@bE=kw*fM-aW)%G z!YITNiKJ1#*UyOq6N7HIm;ZKC2!bf0^Ym$6fA^}3<9x(0jJW9ak&(m*eWEx9Z-8N0 zI5H-d0-H?AUW}>DWF*7eZ@1VydMNyU3KxI zB}OciB}Rtj${=lDAD6>0jrrdrmvTe8{_2+*)vLUvqJrghFix!_vTmn}q?kwIrAnG= zPU)j*aV`XVxz~hp&g`G!`I3dS=CVmy5%usQL#R}aMf;a-le3O|VIvLcv0^yQC5@y) zB2x_BZVphYsUhXdTRnt5dMSayO@+N7^= zsMqU- zN9u9<*RF{4SdoF!G|WkYVV!%x>x@&=4sNG4utO4txrxTYRT%Axyl(Xz54sobG|zS) z&Lq476B0q>Y~s7I3KS)A zUj=r?+hQojTj`|H3-cx+Rq=L7ImCEd6hvI*#;fc-DecEq()m(IEye-CEFr;sajiRhAf{J}N#hOYV-3BW2JRB*J4$~5O z^Ns;_?Jq@Hz$L#ROrbO_Zb12MMMjh=TwF2nR_-gX1_vUW6ej z{UP^`4taEWg>YSD98qsH5&bTbL>j8!4M9L`*Eu;k$%!19Mw*zWiRXD7A0Kmke9YO| z8N*(WX1$JW+YAPSJQu^ZV4cltTZN2RsLIEnGgrFYQ5c07hEbVN+4sh!k1}H8Hegv6 zrfFg}%(2`RYXL1nAWz_2vkS|0dwn{Ci=@MZl5}ztu?( zbzM2ew3DvQbsVB7!izl&E0syg+TgYlRj(_u!O}Edw`Ke0G1_MPRx!!A4I}7`P$Ls! zNZMnX91IyLAx2V3!c3wPa_Jmoi*_D0q?(sS&A|W0QQ{v$@g?MPDV#0hl5mX3_l`hbtG9#A8Wg>@0c# zK**TGc8jwxgg8RV7%7ZonaSUo1{02qTx2+3t*b51?dVOUiMO6aiX^4$w2b8QyG>2(g zxM@di+9T#6i$a=+{;^n$ypg`|I^+8WPWo1YBE8#1$s3iGTa&hUBE(3h2u4OZ(rAM+ zFBe7nNR>+}EL(J}NCuve{>?^8YbGZ$6N#{mSao~cW$B~qP-dLEsdUSASd+f$Mp%%8 z#e{MHTP5WdDFgNJ4wDtLVA00(X~tK(eySK*TP)jfu4C68#aM+QJ}FQrn~b;*Zg2H@JH5Lux0VO6=}&VnE4*2GU8H)FrYD z$bmedA=?*KkP8~3FvN05$OQ$e+>w5Mp`NR(oQ|q8SzSWVYVRY00XX9iu#*sDWJJ5}^6XON5>nE#F@hM^b@07}gv$P@1VaWXB~P9_;gwfj0pR7AU*^~U`9J5S z*IwHgg_>D#rw9gB7D<&v0>(V-RfD^pTR~mVn5b1@*?Ab|LB_V(4SPf=0Q|k>o%79~ zR8~|Oq!|;i@9j;IXF=YU8`uKjQl1PMN}~WOWsu594t1YCfLj6)k&z0fX-?*=Hpc~=~KIzSqY1xm9O7E2&*(h&wokb+u_{q%fg$}8L0cW{X#@B? zhXUhK4mv53%Oq*X=A=b-Y@9|oFopEe3J`Y$bW##QF~BX2NZ3gqU5~2gTVG#Px4I36 z^krb)p-4YHcHZN+ygeq2`;SV>Et9NxBc33C$HTpn;6oEOfN5~<0kE~0nx2rPLNc;K$?G7U7Sd@<)^QEF@VEZ}OP^Hw-Vn#Bjc=?P231US zy*Q$lHBfdRQ|vYB`8`eUwM-&zOHP}S4WLLao#bxfefcvOJ;rYpv0 zw^pZpq(m(!$M`bfs+;Cn5L$ievTDp;1P8GuQ2+}?gYh<~l0m8>J(PW>Gm<_sO>?qN zs5Eq$rb!&$!9njdhIBoeV-|U%qGMnyjZ?PmP_NgqER!&dunb+dYYOxVmb1~GB7G#% zf6~-skE$e-NXn8OBS!V4AYY~Z1Wk_F?2fB_ed^Z+?owUn(;il~| zPej`4(s(TtHzF&v`y^jbZb(F8w9}1KQ3+Y0pD*oqe<=E)eA_Q~e;M)RDf`}?A-xz| zW-Q!zOw%6Ie&?&k#wvF5g<}vOCh|%E<`(IPl!P8^u_4UnSvdjW6ZP z8BTef<20|stK4TlZLn9wNMh+Sz1WL1zr#7JAs=dc_X&d@zSG9A8dy<>F!B(FNTg?r zk~hzDqRc#46=6;dLN6(+Z0|n5%D3tAOd<(kATxdEiJE14rAiKkEE1wfHc72FOIBPO z6;c?%um*FwIZ>reb^F4a~ z9+qX%YP80p6viSJ)&bW@7`e4H&w_1F81(aq1wHI-3fOy2c@)63(E{_xCH29o+r|4} z-1xqP2nIXNb1+e#TCR-R)z76Kqn%gSA`cxiozYIiFv`DU$_K)=U7BGs3-G*vXXlEl zq&}&LN|vuPs?R#8-Hz`^H6+tV2$Yc&RmR<_P-V@T;U=(c2V!zkfe0+u#d2&6vA~eV z#91Wu9MLp03uKWf+m}VP%7Sr{n$JNaGeFsX1B{UfXFz>TNQ5ff2Isglq^}odZI5{) z&Gf!%$p#U*CovvvVCeN7*X7P-Ng#P6Ca_Xr#lk`>L|<{1*0AHy*WT zZK2$!r}104Lf|(5B%EZVLj(u30g{M^jC@e?J9Oxe5f1_;$%i@G!aDf9U^+yd_aO3! zRfE#eWKWG=(9bK=CHl#eo8_iXqtkK z7P+9yB=ved>S=Q4cDv1BFko+QZ>thK!xj<@RpBLSR6&^}(z+uEg0Tn&wF9(lYb-&C zN&pOpLmKr_ud5oyCUPT)QHR*5H8?s9fFH!dyp=4jD1s`Y71VKT{;mg5(G-)Q;w z{lfUZy?wRfUlSX>wUA3B4Y4VgX42h$NW}{Bi(yTAjL@+4VF|ltE1cOylu1#r_ z#zY;eeL*+As&%OK>(_2ElA*G$DOXgt-glPOVJNJ*5EJ`u0@qzqs7O)%0DXO0?M^*; zQkCIq3kS6ef!d{)MPfkdy|pcedM)V-EW=EmT^}srVwrX_F%L=J=c;#b2Am7Qo|M(( zLBT$ikjT~xiHU-Bq5jQCjcdj@u_E2E);STDVMyPG;HT?`JJTA@uiK|%*H;x|*#?n8 z!8z`DTO9tDAL6(D%s=9v{TF|L$G`xrr9b>* zd9H^y=+NgfB_8O*1?N2Ht*MRM#=!%kFha&)#0EhiFv2ityO?oJ+6V|U!@lyn7GhpV z9-KsNVKQe!r*oN11!XF|1W9sdg-DRu->FVFDkTs|p&ykP%i}mky3J&sxqzvjC;CZ} z=d7+N&4aGv%uW={aJ@1J5SG%An$h1fO{8gI$e1_=ESsp`%ggDG*E(q+rOX{>8;u6N zUT@4XywmB>Y;MO#Z|ew#MPN7_dH1X2gU)7_$s1K2SCvqCngk#9TAf;BWFc0woCBDO zT*tI*SVk}iA@GJC%|->(t`Xzq(&-@MsPrl8k|MY*)(Wifyul%(?OE|dVg&+Qd{Pw^6t9hp=%U!?cNp9SmXN*cRPxfX&F3mV2d#B?&(>=Ri>y zP@u>arBIfWya`DuVbut|5F`7(EAN@~CDNA=%fuPXNuA5|XoalaGP_$g|0~!|<_;`n zo=2eBY$W3il~pPD9XCcg5iN|&6ys$IR+f%dv%#h3kqJ@BOvxi7p9-KqKNlAlJb3Vc zIF8xh-{i= z2U(N?fH1EyTxR!lTImU0az~kn8@^GTXc;DxEpLi}YSl*iGGb#9@Rv{GS*~WinK14u*7~lM@kQL`X;&%heF}1+fXil^{Gzq8Fwn z5jN%BST(kM(wAcs=K9NQi>m%@ff8+71>IPv+_T#8i!@(;9buR_jZ?(HK&E3fv(}*X z>i1x`4~YYx{s(U}eEIjYz1(;! z43kg(kw4F~U;76fyzvA1xrJr(=|BBH@X`Mc5)ZSq#|8yk%!9F6LCLsktjx4T zUP**`;VeXHkFzxDK@^lf=5-Fzs0RV;(N6z0cu9$R0JuuYhYoE729DK2#vU>bsoM}% zz57KMxgePvi>Tz0NawwH_GvgA;yBkN94LWM!g#XfUVk)_((hUDrvkh`wpmth%Sz>t zv^ic*EXXNG0=MyYxY}PR&!qs1lR;XMQA`M>174K}oi;#dHX983zT1 zkMk>k;&<@*|LzwPIhG#O9z3Le?-ic?@-OCP!`>zD{%k@vAO!#9r+$Js@bZ3Ax*;-( zki&@P{ZG?4eHFWP$i2_}ZaQE7O+qeLcLV2uY)gy}Z-EGz)sQ}~;atbAuPVmwJH9@+ zX+I}GPZ(X zm=0z6ob2Ar*cS{_n5LTj8ZwIE%!2*8`*%SEMlWd2B{*sv~W`CBViyctrEc~r^5>2 zIwkMp?Y|NuWZllZgvC730;}O)mk;f`UL}2`Bac{6%k?S0hk6bMb>FlTJ*CWLENGi4 zOVFZ_NKn^v@14}iWatTE;OTj?r{5LT?Z1gwh9UjBXq(-HuNZ1utg`>yP(%9Cq0MvU zLy34KmhYv0gZ41pI^Xl}{tO@egTKvJ{>q<4BKh23_}};~f95ao?2G>w^#`wV^qC*# zm;asLPXB|qG3zaU_;3C?4}a_r@%6XAj0^)BFMgaSzw-C_wg2o75r@e*{q3Lq87{x} zPxJFwjW!?uqkoRy{BQph{^hvhv)w+xuw9P6_lNl8AN!A!b<5%XzyCLQ`)B`aWEc<) z$8X~45B^?+Ve;gc{vLxz?{e?+KSKKx-^*A2@=p;5b3_6!%5b&otBP?~4e9F|X;#)A z^BT#g!ELw2x}wT?2g>`Ss&dm{k@+07NC)|%%yT&`HOgTb*bq6%N)P!JU|wJEbKc@y zb<6_ld%qLgiyjT5fThyWG08DurzvNXCNmagb+M`{+z?ZLmG_+ z=jZ2RQ40qL2lRTkrPH`r+$nW|mSt0Su0Mh0xL8$Q3#&v-()aW!%)8K& zf>=N&5_Ezjob_rb#*f$QD_Sn|tlk-KCy~7yt0p0LZBdL()k$9`5_^%TYL9COZqsek zeDRZf^=Ezx*-bjA^MCd${Ij3>gGtq$xA=#@`xUI#9<}yMfS~)%*Qh^uC9OgtOp9;) z^}m3OMmP9dfBP@y%fhnx{{QOddHj#xgapDpU+eH`#d*Agre)Zq`5o8?k;79%q zKKs*ui>r6O%;SIje~guX_`CivpZZgOk^k>M{QV3by?fo=SuLuDHR?X+nzFNEXS^-O zs)m`{=q$2mR5^_L1}m9rIj832bGPX6OYB!r{< z;ASf0q?QR75QKFgLIkN1Du$3gwr^qwEo9*1$5&&{oKnc-8iXtgR>(>f=jcjU zxf%?^!1w+9q4$Q0_501mU++|y^GVF*kTk?`Oz10l7H*qzb(#E)WzhoqdYN1jjDMVq zWRO-(Y-rb)u1`!-3JdzFT;X{C>d_LP$b`meC;4HkwTuP0!MMcU4za?y=qXM=W_WDk3W@E3+!AI=<(0S475k zH|!;j^O)?#3Fjk^j&-{@rh;a>GeJ|Igplf8GQn zBc)}_LrTe0fBf6XX4puV|LV{1{>3JX&w3e`J{$%Zgl_Q6|MTB*(<|S|=l=EUS^MHA zCRY&$9n&Jxx4X{{`Ta2#hDo$dGox|ViS+&AllRKA(L&?XkxY=LDRKrd3Y| zRbHvO%|$Zq_es$f0}v3_%P`aMarZk4QtcrL*jQg9=(N~uyHw007^y}LWs;!lT|&}{ z$FmcP(c2ooCv18rcG>mmjn>TKZPB85bY180O;?4Ia_ z5=MYWC)uY@8>GY+&3+(3Ich?P1Gv%XdkG>k1C*|Wb_cA=Kv8An$1tqUMb7Qi6YYul zFzh&cVHie;k8FWdGD70|9U_rbD)q@ADJ7Lk1=n?p0K=@|+O=x~^La8zFenS8PN&z) zlSophYqi>#CEhvI?1dP+@nHypAjzcAG>sq#_Kfg7{W@i4m<*D77pF(#SYf#>)5;{$ z9mfd+3&kj&ejTWH`mn%8UcC>ILD~`k8S*l%Ms77D3O0zn4>s(`hhb94Ge(B|m)7)p z<47bGFSc|dpP5dpg=t#M)oPSP8O_fz{2sM#cPf#z&HL1+HH{-kt^^|c*wey(kE||; z^w~mQUo~om(l{vEA{)CQZadNTe9;<7UAgsJ|*1001BWNkl$tc`0yH#CN=PX&L>U8{cnH6q5HkW;2u~svT*!*J z`g9100}fpT8cWtOH0B7hB0wUq0(Opa>j>qb#>Qh^Ds`Xc#^s6ZcVvut8i5R=0o#&N zxrFrk84PLD=JdShc?0Iog~{^)#H2k38jZ$427wxUNXr|k^TSN2)p>P)YT3)>a&r9T z<>i6x({f3pAP52i84&p44I*S@TQj29R!qYdk^GrW+nSpC2!Mp zHtJ}con~{)=to9*u12{MMmC+OzcnI{97F8E<1mZpOOfkWcKfoH)jmarKsMs`nC1xd zEX?Trv9GvZHPWYvWe^)<_9v5Sk0H+(p9R+ZmvH5Qi!49y+gSg*&q5ijg=JoG`YU|u ztuLqk>=*IW2Y!pdap=is!2AnX@4Og)^~0$H2^@I~J$Wl2Xa)b2UT_PI;5ZNdlAvyW zk%oU9B+Tod%uaAN)+j&YAJY8rRU|sqB^P_?2HH=34S?H!;Ag3S z{oVY<>wXO1S-{{ql(dHs%1L!MHJaYb@B}k5Io1@fP?;}@S|V#b3lTuA0T<9{phO#Ce|L)WTI3* zfxz*(aN#_L(?QC4WH6;sS9#yk>a+x&(m?rFx=GLirsq zsSWH*Afli~_?xaYj7|xV=%PQ`SC?f%>tYF%(1ea=AIGqkm8>5T1t0oH*@{k*#Sz*= z#2rKSXfpe&1~)ksdW#m;i3*|t?RJO2X=JXypBT9FWq|AX=%yZJeJHge#I}J0Ddm84 z{$av(6JR(j=yWqn17B7^>|qiNbmPUw3D!!R(+962Plx*Y~mZ z*}uWNc$p{v;J`OLrgmwfrmFN5{X zSZ0&6tII6D`!e0X{uAt_W6ZzohxvmaatOTtN~zYQxxUELpY!+JRR1lme&(-eZf; zRebjvz8j9R*OG^`7&uk2MFYCj-!UM>;=ods^6G4~dG-@cEL?gkM-dNO7=gnH;|LeK z7C~t-Ji(v?(SSg_PWYQ)_pd3_1SdOyAxs-71qdBq*J-!fRO}L(T_Wi9M+-~WMVRKm z>7`%ig$(FA4$Wp8!?L2m<_3sRDoG70#90h!UxqXen>-TCaDYMeSx7_80#GH9U~uHW zI-)-(OK^90m!LsA1b26LJNtRR^K-#q z^hIB=*Pg3p&8nI*9EuRm-Q4B}=F-oC2U<`AnD^(0&Lp4YjniI|h)86|L8mjr#Yy$+ z$oIwj%j|WpyInHTnJjVU>Q!eA4;$lBnE_sG8rDhUMQ`=C)cP>$+{O7n(4yi)@O z-E{s+aQ`|p0q29VJ2`bR$JU+k^JmY_Tu-a`<50=v?!8Zn^6SvNb4TS@k$<~v{&fSF z`^eqfr$WJIPIvNp!Z$fR@y72C9~U3#b9~=z|Bx@5w0Yw9TTgHDgU?=-%g^Y_E-z0a z7A$rCOnT%Tig)QtlSZ*4hZk-w#z%Mg#0bvxz$_B{!?U}wZ#iuW>Jyw71cp}461h~$ zGMW*1a4N+Ezkd1j2*KKNjQ$A>Kefh}noD*Z)97^-CD?2_PjsN5^jjOe*Yd%1 zj@`+@=BLDZqN4Ayzjcm#Rm|s)?@KEgC!LP+;ga~iQWQN*A`I;~l79}yIxoms&ZRlL zN~V7Pj$%T5OUXLFA+G3@*eI4}w2Bg5w^+P(QrC^^J8(=B)+UN#;~m$FT`X?MFwU(g z!Ili{VDS<{G)nuTUwC+Paf&_nn`-*B_sL4ih${jE?0SivQT%m|+bdi7cT9otqZSHB zOA-28jIW8_{KQS7&#o?rVL-vby;y@zKPzdw#*JFn#0Rt%%>}7_LPaKv1@}A;Tt2;VXW)Crb zg9)kQuWT{-`$9N`>G#V&3PcOt87-jw6_8Kd-InW&BDx8KC56zI(1MXlAvPPXq^Ml& z$kb^ncu5@nNFS$MDWIkz>xmnGorJgyA((ixn;7wu2XS5GaX1r%%B))!E8v;^XwBlI zjbBua3e09XarHJCqk&t=e`m*2b_noC=`D(VWk?miD}nmubF94S{tW-xZ@(rD>JGRS z@uCvQJI}c9J1?X;+a25Q>HnJZ{t@#XS=on4i z+L8d@&?!5iMpne?tkA!IqOA91zQm*iu~Tl+6-GZ{;QBKYm~BNoGBXMq1u}`qmUZ~!Vv9t2uw%+dRF43mE~&}+3BPh z_;XegbIhPfDovih|4lCmHG~wG(U2Vmb0A0xQdC})!Ve-1zkp`IEEd19zZ5@E9?rDq zPc_LD^G7IyqYF{>DIZe1`ua<3nh4BtyMP^67100b{KwpI1(Gq&W)RRx9b}pM_4S@) z9iNZ1^xFUYe3ybL)z+i%=N{$z@seL^SWOm6StA@zm zrQQ^)5GstL!(yuND?onyU~#e$+rWVfT0|?Jp1$L1;y9KtZkc6S&I8#sI11q$Hqc}6 zoZgKbA)4p0m|-zEjqQl{OxpAtR%TSCewe(gG|xRoYgBrd4*GU8#z?yV$hXCpmQb;k z+1B?;{c)dkQ@}a(z=_UF@+nhSu6f?l&|`FS{lhVpG;b1f7z*&w8VrNc2WWVad>Vwv6z7uNR#aMEXNRg@_M86?T1I*J6F zXlPXKu?LnNmfoWMoPwpBMIWm~ee=Y}a>6st5A;yE3?G>NBK40MQwX~~ur&6eb>WDMmjV^+X>|4I;=x60*s^a9#@uWS+*=2sPI$6wLIqD~=7Rql@m! zY=b0T?ESjQk!DnPsSw{C|2*I*({pEoFLavP8-DuGg{>X_8Y02E{2y;I*sthz}}0rJk5h-dK&0ns@)6@W=k64o%=+ z&&6{@$?5Y>S6}vx4Nt$GYo*&ww=(gX%*%gCWbxU&S!?_BY}ITSx(=pr3tcXLMSQYfA=Xm7CArUj}3?l|Q%kW8X`St!N@v`hF~SM&$)uSc?fR;C?fO$3;S zP70vY(diN+5^Tr)?C|YrCktD4Tzk|$QI6a5vWRtLN2XjgG6&#*jtN!Go78JF!JRKm zSg4vR->(!pnibsBBM?049gK>%!j>YfJ-Jv3JQC47j}|i6N>JCDvCq`%@CDKLVbT*A*k~9@9XdJvE3`RS5m-IIj8-pP1GD(3{w>I?V~sdwXUh5 z?yEoaMAS~)R;Gg1UMo7Zm`pAPm#BL9jf*J9_{!XMOLfWG_P~=2i@AWW4Vo_76a8dj zmaIKjIjw*BVpsO;b%m+2j$NtyYwh*7RE8^r9FqIU^RGF7xU>&d66COGAetkrttk56cs{ zxm?FE#V65*p=|LGdw(u0$@vHXGpZ?XvkX3@*S~&oZl13S#C*Iak9KwDr}3{%1lmWB zNYtDXD607Zs7@k0G(<4uf)8*Pc!7{miV%#HAXA?b{vB@a3v1gEk%YaTYGLsp?E9D-Hl_STKT~qRWsG*X zK6~ALrQ>6OR&YJIAt|zuYxOq#rxj_Oj;aSCy(#CSH>eLY=^9H%L&F_%3_9g(W7G78 z8fUd%zmG~2wbHt4W|AWemSt6y$|FF-g3CR&XqVEG37$>>NeJYEf^+Ar>HylJWtj#E zM!QOVi;hD?M7dyQp}Q6l3X!tc0aG!J0@Vif+V%p>cI`frDj(Qq7$Qkq*!e8IdH#=h z0E4BZq_*EUf$Qv-d<|sa_9{BBWn`g3Bbn$&69IKXfgURx3)&O2B(NaW#;y_rd-ZVA z{V!Bdy8_F4YpS|_Y^Jbua*vXGpcVfO#qloIgQXpKD%X>MqiSDaV1vJWSz*gfp=Y6d ze{1h0Tc5{7(!1s(UVTZF0%Eg?vqgJzlON}uJAM3}3xSl$j;{cjiykrNbQVI1=5J~wk>4;0i(-rX5)|NMQ5!-29)B>r}%yX zF}@XXNwE;>J__2-@cD06pZhb{$=MWRyVq9_cXsV>B#CvD9w^g9e@V2T*P?4*A~wDXCtR;!aPn>Af?xPL1uWfo85iOH+`e zZmLv;Y)yxOHVIB}xw8QC0mmU|tS@R*k-Q9_VPgKN2kp6+0FQo&HE|<1_D42e8Ik*Y zM;z~xTUX_bhSoVZA_r#OSDX8IU7wo?^oZs(mXpC_6Scz>l`oBmP^Rbdx=dZ!qJO7N zh?k~6{a3z|bTBAU@tLE0&!0cs+$6#!^N*c|#t|5zknF>Sc*8?!h{W)=$dp~Phxo&* ze3)JxPB;}hMbh7;ce`ggP{QeQiH^AgpMXrfeN=|$V!k?ygv61VIm9==DJBI^NN}W?O=r^CkW%)Ad*7Vdw4K`uoY*$(F@D87y4=av`09 zoHNBGc49AwtjL#w^pnR2VK^&G`0wMp>g75P!ond6|IQ5%b&5Qn(vjp$D?Uf@cupN} z%LISHO@(V`<#Ury#9?BRJ={_xMYG|5Al_*iKIuWQP3*!nr9H?%qG`mG5mAu9LgH35 z83PqXXB$^9yXtW(%B#7|E|a>DgrSCjxrw6lw4jb&YE8@2$KBH59EryLC{7iz9=JHE zKhvmOM@3WRudpVUeXG!P{*Y)V8Sv9AF?*eGMZHT7vhyrPgHYm27)`V=GOqfg?<7&h zByP6Y5s`W%?{Mkieuf_753}BxBX#ubZMR;t=;cgm^aGVK?qTVTii1l-V1IdUbrMdS_krTyV`t%2XI>`D@Th3>h)aqi28LS80 zvQ9K6zR2AiF&V^V|D=jt@;$SATO^hRsL&jfH4~0ik<>Gp0AF zM;%+MNg;wh#*h2Xl}GDSKHF@q$B8-nc|BS?73VIRnu5_tx_gbv4OU&rj}wpsry#}W zIle77C2l{P=lj1#=TPwR+0i!-1&+JgZh`qZV?)$Ao2&)n@@K_D=tnKv^l8-b!ugW3 zWe^8}(9W(k$0LmUBbir>Cx|-}r@SDNK$N(nQUb!NwcIybl-mWio0==~NmtK@Ljk|l z%`^wg57FPA3LcE%&qG+X=EVbs_yR=d7M0HppzOVJj>g$Zy7xCD4EYps%gAK&Mu-^3 z6V|^k7E(Kap2I&l?nx-6Z}kSW0K$5w5abIEN_=CR*+aLM2PPM9As5ai&~aRR`gMQ5 zcxyE#pl~{F2Y#JD>vnl1x3zJnyRkdw!lFJ0@NMLpX_od39Au+gu}gfaR$@E8^^%oS z#0v!Ru_I70F-g~Q&c>52<@BqeYds+1H6X#IQ^k> zlwGm;EcG+?ktdGtSBvqTv-y&&J2-`cO?V5o-Y1AZS$+%?$2$3KgNyBrkYNvH7_*30 zA6ac@P#fT=L2zzgq%4jHvxeyTQO-Sm8)F#FCEbqI^fdpD{hBbbK$QMD#+NQe--q`3 zke=HEPi5x$IFwUPoS~;MCue3V=7-Fad4F0fc$RO(iu)5kwXqn8#tT!jMjuF)zGy#P z@%T)l7FI&B<8He=#H|Or>-p(L3c+*z#;h|rFr z1t*$kzeHf`uSc39$u9d%?#Yi{#@1lX6X^EmM_RNVL5?&KD4#nSHMW*;4R(>^+wqq%F@d%S!25SvN=|M^pj%2>1!-*#KPHJ&i|*=I;({9*-Ai-& zaHXHGTLrPSv+LR7`y$d?0{lZcV9#T4`U;PWK&57g5Te~Sy^UrIls!TJA)n_dsOkN3 zpKIy!-4$=Y)SA~Z|6(*ggExASm$ep$JAa|Xnl9LjJpH!8s@QipC_29j>DJv)za-@s zOL~n$4aUwL!Jd(Hy6*U=5`)p`nx4!G@>iy@sgC5fWdo)AE%@q}UBouyvwcm!OFfHS z&SU@k7Vaq#q>ruIuR?a7vf&!94S+gNxhK6S)dz*`Y2yBJp6vxDa{WnejLz=2p3d*L z!Kv-45Z~MQ{dX!m-%)Q*Y5_V$9#8GEG^BeY-Gcuf78TJ1f_m?LfweDYE?~X+MF6zmkomB& zI}@UE#8)Fg&lY+CEC##8u8WkYSC>~;cckh$ko)-iUkR7mZHYhH+EurO6wPJjFG~W@ z%Bftsb`_Bs3w@7ZjC{dr;rwwhZ|jn>qJSWX1(G?t3;Eza& z6;9!~&5{{MUH$1~i)aS0@0750m)B$0|B5N`2GK;~p%d z44<335-}a8%aN9gp?SUCrLOys+d25dN1s);SAjY6RoU|`cy;|-E7q(xD1(O*do+wC zs!sAD%PHB$-$p)oMaNERTi_-e!7XrfVCTe;Ut9|t>ww^T$Ng}YYt$^B`?rlp`HSP4 zv=v9?9;NhjPqf>vfijV$b8H2&t@(V`>jRp3AuQ{YAQpEz61%GcvR9tb}06T<$t|>|1Lh;Lw-K8Ac~H?4TunuD*wRM z=APDlJaksGkKKtZ@L5(plW z@x(=Zhkt%9WQrlhU;GoptZi$PZPTSif(gb9rEP`cA~0NFv#|>)NKh-wKYbxkYt;6g z_-WLQdFY!o-eHb12O4M2(>KV~UiWI?*0JT`{nvs(`@OJ25{-86QLy)55$34V3lP5! zrgVwLiaGhGnZyWWq2un#9`C^O+{MYvyF~XczX_MKF@Fzx`)r){JpI#d|B(Gi=GMpw z#gg*UK?X*N%=T&Cx_wQ04oh9OSH;m|O^h~D<=AmWA^kXAX8o|k2e`~wPNcnMnr$&A z>SvgoUD$L99=g2m7#Letg?)@E_#ScW_ZQs#G4B0_nfR{eq&>DWv!U{~TeN+yXxJnX zpr@Yh-^0z{`q{4T?O*h({Z6O|=7?$@t~4|~f45v;q`qM&g(*7^@OB0wu3x8{%>TRk zFdlmm57A8s#m1M56VIiHpYT%g z;=3g+uqj}JIYBCvUlGO^%~OFrGruYRR{fp1?A~`S^hz4ftKiDLLW9Xaf#nyqGACzd zE>X>Ja4uSzS#Lf0i1`1s0DQ}03@Vs1+TW?JJ85G$w%}7p&DhdXK1r@wh{s{SbAanT8Wc5mar!+u9I6>4EZ1G}ptBMk*<~!VoC#k16An;V7Rw;zs|3^CbvH z@H5E|neoqP9s-?HMuKpD>>tw$;RIV%Z94v3sfLgw;H2}pnE z?-?+u=STNy9%^KdVkXgOH^s%>IaSA%e6lgBS)%gI`FI+S)+EIFM5UL~ucCL{WwN^d zDBM~!y9@7{_|+fD|4p3F8SzC@67GEj`C$g<;w;vmx97GqXZMr;yMXW`xp-avJda-x zId0F$c8*|36vBEV*)x$>+29_&FvgF0o9PY@tb0O{&&TlsEpz@P1y4lPueKt+m@XaQ z%QJV1g4phf=bkW?D#cE(JM5CA_|5yZ4tKSwzu`BqPkP;Ks)F7ME9AJpo_hUK4ewh^ zd@+vlKQG(1xqNHI_7PUPga{toSXaQ_nwW!VRDBLG}yuRNp-q zlMiO=iC0y~LMVWDBO#c^7UW)>nf>RB&y$PDGG zznWuJjVhQb+(uTnYxL{|c+&WWAknRq&1 z?wC#$FYVMZUF1E2d~>v z1wj>P|6V?bO{ySvZTIWG{2P9S?05dy6I!J8>-3kR-+KpDPiW0MxS}&G)ZR0y#s^s7 z^k|w1tc$OC9rlknm)Czd{0i>z3Y-{Id^zlSGZlXB-#2cSAZpJT^3!3IeN8}(CL$0wBLpvg_b_Ndj91W)V5$)#tS{tTR{P^lfcH9J(Zy3i_cw(5jSO^wNS?J;kaL(VkPBpO^s-<0*?gyZL z9=9K~XTP8Y8b)$XiVgpfp;jF5;Gc4*$a2hO{R)eBIHbNG>M1aI$ZDx@y_H^!F+g8B zk6$|ZtvTw({y*xgI+SZb>OS^}&M>MqyZv0&Ti{OwU7uavSVyl1r%d5pJY5j(xqnKS zPEn<2-^if75t531+R#}8!Pc3HnmBkBVPGeEL`&TSX~#HIr3LoblYg8X`xH zm=uC!$Z3{~fyUSb&ged{Q6O&TG)Y<=gUW7KB~BUf6p|=%M!igV;OeNMQ6_w>RUAsJScevj_Q<7SHY#;Z2yHu{fThZ}Y`ni9# z6}uAc(YBG?b624I7}B82?-?R>iv*oUfr0;k zOaBE#epN53KdH?*qHZlsqm3Ijoxc&3g5#4m_$8tysi*fe+T1}UyFjhM=(B`?b7d3H z1)E#jbbCY-?w2ZcDgiBOlPf!R=DoPJTOZ$mxhAI45cqP}K2h4w-}6AvB9iYFrg$M3^IzZ?Z^n0fmr5)v_olf++0ZbnUzT7%tp;f1WBa+gq~|c}y83pJ{Q1!uskN zF>xqW85o9mu^&lGKO|Lk=dBQe&Y!u7(DwHB5?tN9NhgTRXnP&fFrWE*fnL>;%G&Lr zuiHQv6?lzp88{u)H(FVvr4qA6V6{*Nz@+~Pso3KH4Ge>|e<%}XdTbVgeSO%C5%mL5 z=9#Y?g3Z&5t>OIMK?QL539kE$-fW57$iT%fg{E41+Jkc*`UK(qH4&y;kkjh|_07x9|^?G)@8gC9iJMq*dqIrLTiklAiw zmDH84Ch6AFJ67Ay_}9GOx_l0 zTgJ7>M2Dlcr#s?{2{wy~#SKXwoxms_jaFWTEB$DdSSUCHOxQ?4EpArX^fhtcF^|j~ zB#_u6yX=SzLmmjl0N1LdSrebxj4FO@`;AfdljlEIQbkDZX`JQ_IM%E|*3}Mu-u2SA z=fZF#=%|C883h#Upp0{JRDW|r9Tjg*WSl@y@WlShFN-sgN1;U(f8?%Nx#OlzMhzt*eh^8)0h@D1UWD=3pjxDNt)AoW3;}!MXXHxKSaEXp@UZ|yD z+uwMXn15bK8nS#us_|d3MMOT%ay=_w`7Lzneb+$`|3TrS6;!|C%u+kH54#(tkH^Vf zXzS~?^6+H`5Dz+L8g2ScZ@bhuZW}Wtf;Qpa_Sf&%#1QRV8-EI3N&=Jw=5Ipv4vqAR zq#1bu(}v*ULl*(kN(&R87KkE}A9Q18Rj~9&QT&_?y^`fa2X%iie+S(pc(Td*cu*zi zXoaMnZknmKmJeglY)Y%rbKRXHN>HY8;YKT%kTBdfC`@`SR0~zF>i75BDB65g6wV-& zE}1n;2Q814Y6~jR{CFPS5~z0)q~z7*(9_H>bXB`}tishGD{lZ3U*?S24h{nHA%8-g z6GT5V$0vng24>o|Go-iJX1W#hWx21(G9~CU!k}{f=-iO-!u8LNQV}@F^AbZ%V=4iY zqHc?-&kw59uzjgwA{CYN;sv05O;sqb_Dai+DN5n_CfKt89O&B<^{FI4R*uzlL}SMc zPPF@EQpq%~Suhlqz10BnNx|r=PH8NStqSYhK_gL+$j~W=jmtZG!>S6J_Z&~U*~=}+ z8?y*8U}x@GsUC`v+E*>3(0?1I^WKi{b%->@nT;Lxoa29Ui?ADsFjLHVbg8l1^~zVY zn)dT=FAFRpLyC8bK0deGou>gUn{Y~dPs%RY8`~A+%6tCrE9cjNPbeM}b@Lb2=6=x_ z`fnSextpVti7$^uBEzY#G3VJ$-X7)8xUL10&#axX&FlVUy3YR|F6J;WD*fl$#tify z$C0yLf%kv5wZ@s8t!;tL!IiEV%81rmh5r`p&oOChCY zW=6`qhW(MQbuxiRVrVq(Q`F?7RxfW?R0iUOzw7W|h+KiP_cy(TPxVoz?%8!{uOqLG zbj2hIkuLKRRh~8_nT>D}al?wT4>GZWMCZR-=CJcQ1$`@C((kWl4lbs7#{aQ@GsRb| zl$9N1t8;lsX9R0>e*uoQs`%~IApM$B099#VIb+@aXAVEn_aOidChCf^`+U>VH?Uv^ zxdD!OdFTU>HQDFfb)f0??!6kXsjiutV)t_ePNmkpT>x_ah|XfCs(cDtQ1 zcvTNxi(=%?Ibn%o!okc#0O#i{{3r8iZ;EPVmV|E+b?xmDc3Q1=t>mtTZ$^E2rhiH{ z4|BbEfu^7^6%ECP?|l5tg9smTXHdYarEtA0zW?tAkRH(bY5f;D1-Q84ddW07;`-Y9`co)E ziqL{jT#Mgk6>QJydMjW(-nx(V5&j<{0E$r%?0x-){Ix+y%21>SmInEX$)RSt=Q%y` zDV+n7M|ooiMDzP^FTCS3t(3B_&pVzs(rlr@mj(uVM~Z<|$~C!`x!)w5WFft5pT*$O z8fBbCILu-|Ybbl-v5#KJm;_y>>TCwRma;2mSxr+%t#&`u(GOfdc?pG=p;*y9aVoBm zN)h~WTZeBa*FG?3Mykqb`%)fla$3@y%i;=#Xtg-R?hITsgAyF{AK_G18P= zg@i-_=Qv1_%{Wkak}L64(SsQC+!Mm^G^n)$ceP-Q0rt{4E0+$vB{_ruIg0A4s!dO_ z>SM~H!Z|CN?yL}_jc4I5{a6svv@0ou8<1-BYUIsW)HXK41?xH)`(~N{0u!o#ZdA5b zbsFaitb;`@r^ZGF+@gfgmRGCSoqrBr1GWDR1Vc)a(r-Rh#5hb|lYYUiI8jYsy871( zBdLY5dV7f?z_1fPp;b}NpngOew-%aG_s66aF{oX{IjM5C9jTOoVNV`YE|y|$GHbY2S5(g-TP>C z>&{^}@e|qi!>p!HUpk&tcB5yn2abf;_*7-cO}GA%pSmOehZ7AsTiblNYP3B+-s^Xy zrmQdd1u<+@?{;`>zM$MUq5j{==?(bV|Mhq9sS?)9=#EIKpnB+Y<+G-3)s>z`ccf=S zV2`fZWaZ37hDY`IM_bs<4>5~V8&^w&O1fu#KJ+So*DM-bjFP3Z5adzh`L3aF9|elb zaF)SV;=v(fSO_n^I@3vd<##Yp2s|Oo+l7UKE5*Hsfe=`uAPBav>a%}>2~F@bzD`u| zC&dE&8meGJJG&UCwkS+WiVNd@@LDw$jo!>Y@Asf%6O(R%>H*M;nR`D}FeZ$m1stc$ zn8TS=*4PS3W)b=+lkEvSae-a!rfm$!r@a5?hAFOE$f?``!-gDEgrVRSA9Ht>UMbR1so+8 zJzzPHToHC;WF#p6OC(Drtx<%dIx&q8om3m}!ll31qmOL%I z3A04ivPOITc1Zsp6ZS$_tN}2A+Kwr9VN>PRP69d(z?@E_+AJ4?OPC30rIYXtOQG=8 z@GA~@S?wr_VOerl&weQ4?nbefpNnP`MmKZm`np`{oyI|iNmKfAcbSRt48O?!A%!E5 zVuY|eTi%jDe3d)@m{-8fl(ygLPc{y?Zjytz(I(h2GZ2Ic+OZITIDFrsl0Xtu#@4D* zj-gRJ0;*caT#oR4O93gcRTtB^+mV>Vlec@b-~T`=0S3MozQ^P2xaYp}+NkxpHw%V4 z*;-3I65P4RKf%&W*U84I6CM5!xO|lhCw5m`SCMTs&g*{oyS)ohc4Y+K&lH(aCVY0je9u&7J?c$7y~uCv8M*9dk7heQWFI^R9F zRg5_KMc*3Iy~`J^8jiF3q561>58Zq!yT~Rry<#%&SRfM1QW#aAyPr%3>1bj?5tyfj zy?O|wY+>c+cGnmV!7}oXQ09VncGk+I?o=LnVAPpvb}H9L#7-{ zb09$+cFfQHQE0N9ByWle8Dw`EoAG32W;RT*ndT0L3m9x>hJ#T=%65A(L*=3-Wf{+3 zK6N@<;b$K2zXk(h)k`o2AUtGdLhddNNcjR&u}&6Z|;hINj?j$qYX-l@b?)w~!`!l{n3Pqb8SOchJ#JCN=q;0MYXl`f-sYaRiSq zDj-^KOKnHU%Z9KVH8y?PZVGSgqoqeaNgJ{C=M-ODXnKUBK5v$Cn}E zR)^06oo>feg$f`aEkQaoBnHRsvm7xzYZ97;#AHw~D-$0L<_)nbGD& z8}78691J0p@^5%}c$%7;8%s-{0zsm3;g`s5eSmG`-pSdUJa~} z1I&BhV#@I^DK#y<$l_=L?$Kd?wXr%vCm%3`Q`(}UVgF;I9&vF1yDg=9DB0B7L^wabYj}m9w>(=S3`}A zN@kY5*w*!8%PnF(NFxi?@%D&b>lU>fm?{kUuM0abo5XibfGcy8{3m=TSX=l0!E|xt z8k2x_B5D6MPNLR2B!D)mPoP$o``Hb4puQN#aAcryS;aQi2pZ*6D|dOPN_Ls+lRkK4 zZ}xwWcQ`H*`|_ZV-IMhTfJxH(aHVof9J_E@JOKo>*w1&0726)#_e}TdTQ%4C=N2$s z#l-R}`W$`D*@_W7+gR3rl#3w~>c>&e+C4fVnz(gE9WP$AyWV-cUU3=V=u{=l_HqJc z=B^$B!Ky&2<+2f`*t|qd5Kw$|=Qqbp#afnsbF!SMBFEWO))+72SyxnuTCAM3p|@m# zNB71!yZ0ecjnA>9f+40_G7JpKaJiskzkLSJcvSidInGXD2y2hbfAK{>2O{KlJBLr+!v@J@Kb&~|rI6Dcpasz-53N+N!TQ7%*FMY}9T@#(1^ilyY zO*jtSf6TU1C2&T6O(5hS2buzFs1j~5j2)oOMuLoHzrbR|u~~8hp?|Bx^x5bQ4)Jh) zqEoJQ(KC9niIwoi7h(j`A4!K7iTDWMFL~UK*ii4)zr=pBVyAkwwc(=QlmO&J{d%PpK(2g%k2D=SihU? zWwm=($hqNmRX`_gS(r2|A#4>V0=~j0b3w zZp#oYnC{s9b|4tM*fN|PRva~{NWBU`e-f4j^kJ|R_r$3K^~^r&CG*EK$F~+dnSZUC z1|Jr=71h<%fm=rTX$%N*o2$^c6x3se?40bPBptole&;V82xAcnU<^u<(%rP;wkF~$ z#g;#H^R7tw7c4!Wt?r6J75Mu1d1yVyh#(yUZtD7?5Z~1S5%*H&)d(Q2pd*a{`Nk;C z?z;Fq@7169P+9UaxVF@5Z?E*RV`=RWamciyHFX*3>Oz--s%JH)_79_;X|q-h3H@nf z&1Vx6XPd<{2VrTH|Jr~(5GzXSugm8!hKwtV@&R%RO$z*a@_LD&kM!L-#n^$vn3Nu6{0JCyZWkUA_SZQ9aYE(#rk zb4}Jhk8jVOccfD$mkVgE*~%rPa+pnmq%L~OGP_qy(R)z+~_j4+WH3P*mb*(Mgaf zGq1$ zg4qBSl1KDPdiSEncG)PYn$7Pduq{gCXl^v!%Y3xcf-6g%8m|!JdgCLpYqSVsg(vyD zw^91f_q0!iQ;rETrZ%`&Qvac}#)UlU(aQLrI-FQTsOmPzYNBqnTV~;Zshz~INidL3 zpt9j#%#PAd)oSzORYI%@O?_?5$(tJfku?N%QOeZNy zGb*c<@)H3`5sLCsC+wbhp5lkC7En;>LxqXD!gA09b9-WJ8`|2^J+ueOP#oLP4C+0=lYf8ySt1mi2Cwa8a^uydI|Wa`ovFk&jsh%H@f$(0 zA#nk^%DjCO77xL=kZ>3xSSM*uRcUs5_r@%HiGOc~OoRrY;0!*l|8iktA+G7>3xWy= zmP5&y2^;@}Hv;f7cWQdL? zP1?#Srbb%-7EZZr;M$jzf74dLH|J|t(L%gEh5m1#P8-c-J_&VE#OBLD$kJ0=i)n^W zfB>N9p{GxBMXDYwGK6Dy55ge;E+Y$=?)Mx(!Xdzb^Jvpjsi;p6JV4Pu8T8MXS=NQCN9G-17}ti zh~y(mivZCIgT;lSQ~D+IZ#=rTFw5M%*NZ2>q5>9nMc_|eo>wxA9RFW- zQ+@1;FAac zVpDh8NR5Q=2lGJmT`9zJj`bFI?mWRUh|GI#5Ye``Lwk*zT%;T|p*_}!5a#HHha(6W za#|3{3j2ukIuGDDPz{(*xh7oEq$3}-mF{;Kw5W#mZA|k4_sX#;d7fD`whtX7MgMChc|(a5x;@gsx0CYlC>II87s?};2L7*gzBNrS7idFUtFvc?H3^y7Vk?Fc+OWB`q z7vLPA43opPRtGu26`OAIq2sgaZj_Z|=j*aM?~GspYDQhw|M5oXKv%xLr>U!3s9Kgw zETExY<9ImB*lsj^d^^oOO{vV>k*cD`yxxIeZw-uSLo=B^{Dn#@He=V7HnUgSwpV{aCUuIVz*J2X?iSYw4w|oBd;MB8htlq$XS0RL6E^@#f zZx?CgJ6U^QJaFPlNhx8JY%o!QPf&^Cy3}k76oBuTsCj=okK4m{R9lu!jg6@mX-`YO z)J!>V4Nkap2*r>Hg={~qc(1Qx4-QSLQs)1V?h?ijHzY!6uLiPrn=LmH$v%$fn*8LH z+;vI^F7CSK<`8nz?}JhhfSXHB{s^!}XXI34>^~fSI2Wn*aVu(LIb!&}X?==NGN7`` z?PFd3#pf7k*D`)|^sO+dH71hmSzFQ-K%|scx%7*86qa;{F6}A^vT2{0f_~^zKPQc- zeKwt;wEr0y6NE__?>Or!#9-W}YGi2{4seaY5{I_k6qZxJ1&(^RFe2SFK=wcMV^X~x zXDX3fl_q|6T#ccq@kF@s_|C=>qJ@$&)5AgK{_EUgp5ris` zw6M0oCzY+M>eb=0Cpt##t&uk2o`1<6!NG}&z%c8YzAqTJm-{z&7#giM;$U-gSWBKP zNNU&9Nrl0#x0y5Q1Tr+j?zI|2X`j^6Gmx&Sz7dzl-ujC)Y8g+E26%j7^bOQFdc2i(FC!k7f!{Y@IoP@px@5~yrp?V z7=ciS@PKdRLx)=4d{#hGHm#0n= z+u|MhdA8^V=OD2C9c&`)taLIpgYXlOi{W=O!T6u`XQxTJ*hL;UjQ}(=Kg9LhhMDQq z5h9a`D*Dg#|D)+F!=miIa6fc+cM3>{(lxY-3JNIQAPv$rL#MP#cXxMpr*y|lcMlA4 z9{%T?Pki9I80Oi}-g~Y4{;jphiC;j9H@@Dy6y2)_%O?u9%;0z`#Wgb{aD*?YN8ja;g|%c6rSnAhA~H(F$pcg&wc*4!K&ZX#faG?47s+H&iB4!BUQ zOsu9rPKa@L%otSR9;_os`s>Db3SNuxCXi&r9$3g|rH;pf+2e1gY@F=)aH@7|ERzai*Y_>e(zisuNNiiC z=4M|4)sqg26o_E_b&*x+x&ddrTFB)ADXIYX^!1c_VeAn=GW+W}qZnP0msC5g0DZSz zw6i^=a&9Xlf~6OW|MU32I4^MsAA5}C82XhVU2w0Wf?!xwo1__7!LWQucJA6QWyp7t zbnAV6Pmqro19|w(fPzi!8trZQYPxciR(+?APXi}@aW>Ilqs@8GKr`qIq3V0VVBRl% z%Z#3_7DmJiC2tO<^HpLWtRrE!4HA8WS4tC~4Wys3QrETdo?K15@RYv*Jft#Q1aiFi zR`1M@>@1MS%dn_Fkr{VbY=*N1?<3+C;XY8Q-ExcI+~yW(Zah_G0BAD17N0#S0c~vA z>vB{aw(hSzn;2N9Ql4ly7xkO}yd$KQL<4}QW-Lo|52^GEufLb$Nk*x!df3|HuJBIa zFfHs1OlC_zud>AtH=Z`5@1hrq;>o)wzioC*nD31%Ap;AL#9>H0?ZP88+b@Fd35)K%H`=oLo47c5h|DH!q=){;jiq zeYQ>6x6~`mo}5J^0O;=bBKxL|%hTi^C}x^Al@<8-U+n;2Z; zpPMamXE{$6@tFHw8$%GLI$rScu?>*OXq5)7tmu*lO~#n=hPBa$*9{tOUI@v}Dq2eb zNq9*T-gmc8bqQp=ACuij#z#ApJeaVU# z%{{Mo4gF}nqWwnkf7Geg9*^D3mq*h3cXF%u9^TE!pH)*+62Iznt%UE@e~vX>!Q@JB zQk+`--ED?`6^mk!lsB!v!uuqx_E6saKE>&Ej%t8#=NI#hrE{yiJwDF5XI)$yAaJ#QAQ zJX>Tfey+lm%oe3%rHJ79JtApPjo1vot1y4_=>Q4(VGn6h6OkK?#V#}+5twT_!tIns z-5ZOd-Z{{%RHtk8KvRN0qK5_ZjJ8f(Yb|Ol(W-rX*3(GXMlsi|qP-=m;ZmqILuzZe zCTRYZ&OpcOpQ&Y{VRHM8We2D^J{&~0*1L+wfIW;n(8Fuyx+T?Ll_NB+b1&xqHqZ-slr$-qYWY6kBmh5S!upwvcQ9KqKhK) zKf#-nBR;_5%Ni8(fqDnAt)Eiyw84!2TjPsFp7c=oGb0sw#VOH@q+G}J5XLafkL>2_ zuiK~a2PmSKn{(U?zLF8JV)%1~Ok463MO&1Qbf(Q9Kj&4Q7fmXJ#N< zk5{3-dQsND%Ham5*S%QeQR&i`(mY=&$60VaZ?{bJITi90->6P2k${w(vi=>G^L)Bz z;fNfurR(24Qyq`yaePL4LO@NNQKh($jw$%@(~hVmgxCH?f#1$fUER>Tt-6AE{EfKV zCDQjB2IKEgDG8I1OtdpMf*dK2TH6i%%V>L!AkM|j-VC^`260@Oy3xhmLr0)vytQDs zwV)V*H(vX3`C zO{-K+Dk0WX8}xIseQpsi%QTy`G}~{SbdRikbHK~M-}}_OlL^bCVNKu_pOo&LYMlq0 z$_7ioc_((=xOb$dP&gAs{-#T57)Bp_k*qjFKGNR|fi29>S`h2s8;PX}*&v|w%;zgZ z8EV#3G{){j6{MwQ|6$K0DbQ*1boXvIy?<%-MzC|S+b}^!6n^{J&rJ+n`QH^u&V3{8 zU`E^7#jzcf%Fg>x8&Knv|5=;VnUJvU7=&4B{|!7WYsTeif8Yll;8A43-Pr%g@F!xw z-NEEX4e9n~iVWc&4&qy7KGzsw3vkM4e@d9fumi&xtvhr`J1EraBsIAav;g4{8-apg zPFMI^ZwH4X<#Mw*N?T!Z#28YSSleOnhhu(mRlcxdm*BK`=HS1aq-v>u8Hq$bb6T(W z99-XStI{?Jlj*q_dm5G`cA2;|*kFsu(#IxyPb0iSFhnAfv-ca5cIbUQTvY+&7Qg|x zb`4ZsGLyc$0&xe??OhwMOkrK&bDI$xiCzaL6u=n^UJd4GrQcvZ65FLipWK%r@M9#abh4@7w-(0Ka3k_x+0l}K8p>q3krLe3 zU{tkmRN!i8Iq7p_kX}wdCW(B8hg=e&nmd(tcN)*tVNUW(2DWp{^H+%Aio!A z95hjiO1mca{tLloS&}ic>)|m*GeFC@M_^R`_iMT76?&X##qn)JbTlp9{V`UeGuCqw znHG%FTns75eh7tHX`HP2RPv4;|`vo$m-*N}JUwUt7d{aBZ}4s#iLVa%hz#nS7lR zTnWD5SRJV&xb5gGxc0uCA1;XmeKzpp$7Gf>*zUp0=^8;kPqyIDj>798!eMbR5G%V{ zBm)OJN<(Z5i{2Y$2E5!4N-cl*!Zi2&_rl+~ot?~*848Rxjpngbswm^1yO^2f)t1Fs zkv@+FAQbX$;TR#b8WOMP@%l^<@<_mncW3zTb7>qTk}ASM zEOR%)jc?#-{dD`N@eTVS6Ql4~_kIIt!r0)CKOdsVM48&sVMYx%q@;}{fh=O4DAu;+ z!B%fRk)NTyekh4Dai#*f^ZGvrHXCpJFfxe?rrM1o>5dfL+kns-#|r|RyDS2{^ADLo z5h0LFPEB2&F$Vv>3^5|(uF|-_NpgM0^6eU!634ptioXKKa%E~X)*Q zSqy@-Q~`Vq&RC@e5?LSyAeV>!NK(MtKa3EPU_4f6lmNgv|`PPg^6=qe~VsurUQVkCe8xv%_VvvxO zTOfl7Ox&G=fH!+W0FAEUIM`rM~3TCP=E1_L4_E#ky zVoY9aq(+^{ds%5I@5ylcG1)nGzN--e9u@|yzvNt%1011@{}_JY1Ql?_AQDOccdTWV zNqFMhSC1?E`;1hf$^+X+H~|5s&5Tm`$or#|cT5w+KeYVJUBwA%XPjViq>_anThwONTX({x75PvklFV*;x9loj>ns%?uVC5$35k90M*2L(b{Zk%5IpVSZg+t(2TjgFV7GeebtEXO9fk4hTw0 zc*8ZA`wq3048UTYd1oH}?DuC&2g9Do)l;M1$zE1VG7g8Gq%;M?eYk$7{BA*QL2MqI z)>@xkdQDQ%Sh?CbDr}A(;An-ZK)Pyxn$Fd+xKR05zDrNiq&L@J z>+78+U1fQ3$kpvOsnx8rcNOQF%sdrB%6iNp_pcsPdXoB1F0p7J^NfL6qq>7~(Cqmb z8CFi~=}?%L!+`%zFW@*zmAE$r6`(>6_5+)Y#n~&il_hknn2KDv3goSD$X`w^lt* z)t0ADE+xe%9%0a4^;iylUVNdzx@g?Ndht?(mRZ zFe}9sRw|W|f^%t-6Jiv<$*kN%6`=7yq^x~13k9x<&t>nh-Ev07cgV~Qazt@9#@pK% z#c%Ipl>cP=)d%JJoQ-vYehN`m@Q>7vK=mlg+pzq~kfM1o@EPz!o>> zY}e`8ERBA0&IbVqPg`0Y7)uw0%Vpt|bDYhb#?IP$z3H$lyrh*4pCl(zOPCCdN0AEL zNIZTwiql+6F76%tT1AbV>xzZ)?3%UdomZ2^%GX#U|vt^f@&(};89=%e|DLL(#(UWWTUKVpYB z=oR;o3^|>#-uxq<4>lBZLm2Rb6EK{&wk&=9BcKcJ6CX_p)?@{$>vss zo1EaYH;>n%*l6;~YDD?!@6@NU{on@^^^5JX{sXI#Q$(YQ!WJ?451Ak`q;&HG$SYv8 zWDIHb{AS#4-hjP=btEcqIQ4BT>WLO}rNDdO8i23eVVD464aUCF!#$&N%vpvJNoc)M zL5FFw>Uat543aT*fD^^F7Y$|*oes#yT5!qZScn49San<$Oo7t_4u=an?kE>S^ciD1 z78fba%*`{|Fu8Rad>nVjY8TrNii*!3PoZ=#*Ce-IOUMi2UWp`Jb~jiZ^zW?G%8! zH@^L0dsb5FtOE&_n0`kA!r|z>ZP}H8!TO~l$@JV1KxfVE@aBe#Ar3Tqxo+bmv%?1! zVidF4fLQg61b?_q&KG~^1kLqZR!(qFmkIwud;wdMsYIcXVS7Wrdvuow-gO{3a1P1O zKdt+J88p%6JR;?dIwW^ZA|Dq!3=w&WLZzN2Ukx`P2hJE<9hacECjS($+MxF^%ux?U zFcu~f>wUy?LVZ0iRm|v)GhpK?cc=<%f_h2M`pqeBuz(=Uc|p4WN19zfQs_!dx?NKm zQNB6ig=T}bCq(Gf0aGqOUXaPv%&hNHGWC7*k2X+5#i z??%i)AlDUVvXiDmZm-+sHF^HT9$$+!`~Cd$m(2q5`3$*;v!~8~^*iUwYd}*iC|bm{_4<#Au5)LH1<1Q20YdA= zDt7xXMzNx@(pQH&I59DCmbo!oG0Mo?91Wn^KH7N@0Z8sxipanFn z5Fd1Y4!(+saxl4JK7zk%usb?AF>-dUB~bx}P)}_kVeFp+-}8zoB|IU(N_|?zrE@Q4 z*5IsK=%V^fkw$UX_`>b})fIcag+SDw?cPWqSq>`(6n7dl%`-n}`FlyBhPsuTzLonQ zDttu1!suuI$7UUELc!6JFm9XWD8+KqJa61B#WaK|c1eL;mV1UaVtL1&<=`%>>7y z)}>x0`BDGb6~VFW{Z$-I>#Vxjz`OT^KU$LKDEq5mHuUJp-rnA4t3PV1mrVZ%?%99d z#`i0628Kc{L(7_PEEuASTLrhDS0bz4UOf*jX&_zLWJ z?aAh4NdvRk8lIov4*fK)>r`tnRO)^(f1(^=4Nkr>8X7+gAQQv zi2|pn*W;l+8fe*ZT*7T9(flkJ3Jb2Vp_e`jO6#;b|9IzM7u%EO)L#QP@i1RD}L;vO7al05~^%NyF3^NMakFq!` z8QcEJl*lO%IadUJiPzAXa;h0crDZ&RE6b8{KEoL{$CdcW-{;2KeMA%VVJKeeXfOBT zd%&JBtZb@7m9>w>X1DUq*DCEY;gM_l54z*rS{FDH!=bWjc%w}^!VCInOu26sqefW5 zTFlYOW4vT_;(xN5^LCL2&MokRl?A<}*pGKNzK%aH zN)x(ZDi^bg5F>XXPbM;{b6xeBHq% zK^^B?{pW?By^BafU^n&c5&HMJ`iK+4r@K2l(eHDCg3_2l6QFz|U|~TMB+U}nIW&a% zzVmVS|FZyTZkren3&1=dHT7OJ$uoq9|2{u4r+FL{O3UZKGvl8O=H99kg;A_Bz8+|N zIjn(HBG3}56MCTqz_QVw@|)`x4xKH(uri$uL~2h9Ot>p4kqO|)+&AzZwb>tE{7`-? zdG*-S9sU&8^;!Y8RgEJ)D}r!S(7b&ys>Soay;vFGTDt!JIWy^w~HRD%dF@#!XoRCs7Z_*$oYc!lg%9A}8D&w=-x$4<*;PckX{fkX48r(-_eJ?5K~EFPSv_-NPup4Y zujujJ+`tZ;?v7x|D+W#;o~@&WYGGmFju<9ItyzUcWz30_4xC!$syaDu}h6ow1=ILV5dB z)2RnIz$q~V7YMW7{(IxjdV-zJGp{8OXEG^>u3$K+5Fl$AL;R*Vx7j6Q4n zOs!cd$|t3j*Q6Ehl_K`PH5t!Oy)8xER;}RSX7V2r?g>0rJCi$tMcRlnCe8LJs>0JmRR!)92Fmn%LCSSg+P@GtlVO}`>FzzI5# z6+!OGnChXyN!nT`ue|YI%9E+x0}tZNkP`Q)UwJL2>*)RB)u7fqpl0!}15rhuB;5z4 z%+~ZOWn`DcNge&)HXt`B_??p$5&_QqyHhU>6fAfO(=ht_lEK`T0DB%&ob!(accNY# zFlsl(skUlehwywu1Y$kQ=ZQC45G1M-eoCd#mjvl0tcLwh`F%urUnnJ->ByvqT?I^G zeU~QkOs)a7CVGaYva5WQRwed&*rMw{eSSK9d1soNn@c7CeZkzZCzuhkTw2 zB~R87UZOqjmHwd#B|VUTO*Djsgw0c6-C8yh=lZQE zb)y;@d;3a^_V;zlJRw6tD}fZ1Zq4e`)6=wD-i;rdv46fcDR8`=*MPtS-Zd!H?&$mIb~*MOxnfB$?Ad=dbdjAP20@6_^E*F% z7At{5uxP!nR9jBHPrDan^UofIya)wqhtKs7pIOhs&Ch|3`5{o(BiHjxJa6>1ML71@ z+KuAC98c$539I451xLZdezOBm8S}r861E`Kf7c#jt)m0u>nJ#-aR>-l zasxjS@HAbcL8XWm#BVWIgiym-s^x#8Rae!F7qS9DIK4!2|BxYzRi?XSO%*Ao=PEX0 z8yEWDb7$-zPRpghe-po`g5bG^(VE9F61_5Hw^6&@Z!HNwRDvE75H1+!bS9X}G?coF zy75U?Fe8Jmz5j+rS{pD${^Fl!^q43Ha{M{|O>>QEjUc&XFUeDPx}K(2n0pMeBRQD+ zTR$#IP4%z75DS#uMyPh*^j93D^)&L-2(^X$hxd$xD|tto1Kqd;Skae7)bqYp7r)=j z1}c-r#V@geVO$@DRstNyzQWA6+A|)|PWvP5n&?cAwkC6-!HT5McxuJG9__VB=G(5{$Whp|2syVh0Quc!G5HT{0;^E#K56PKVZoOre7ski`gDe85o z{aL2*k!oP&^5etSsjfegPDk;r7xA1OlpNN#bhg%Z$Hivnj=9qs#o&HoIbDBQd5C8! zL5l}|MBf9OXM~dn!(pqdw4`KYm6erzHK!@laF{TmB7=7lYfI?8KMkHdL&{~(aT@^{ zTeWqC6HRWDFRJDWO1l=$Ny*2KHPm-ki?yTC8!5lOIj_uom^DaLygnm${?omlL6{98sT=FOK$8Ooe^mj1{C;Y`(sy?i^s*pOcW$}Dkv zhO%q3F`RYP1SR8_@?z*2-j{!KcU(;zl@Mvb)gqvz?brS^)3`rTMe!uALIF<*Ht|{i ziZSI<`A}BBK5^zqR-gS3<)Z9*%}p>}qYiGZ4o>K@J(3CdK1**_^}fejy70UN_NUwn z?Itn_bn7X(~c{^1!>0;N7O z5KSTwPN9u5Pm6|%Wj8(bB+hFxH#Q((2=Wp*t87e5ETf@{Vm-Jp*z8nRaTeBA)P_%W z`dD!VWSIQ%wNSto~H$LujcbHK9Ow@Js~cqw?DhNECF0 zhnz?yh~9ihg}tu)LmwQwaE4%ApH*5=+n3Jg+-RnNj(<}WDR8s_OZ&h1S0U|9Rxu`; zTNEagS0e|)V`)hm9)O{t`(fg;-!zGq-@}*oezTYD-v3@kxxP&)_e;m&93p$hj@tBO z!!4`z-P^IY1MKPiRX<`+nvxs?F$@!)$_;9%C@n6WxF&XLet+U;G{+dsdbwxU5@VwWD)L2Y(xs^>W% zOFSmPAG;5sqpKXA7u=NUqsDpVhJ;IG?f+kJUer_7zN85+;2o;MJ1 ze)#YKh_+&Et(IK&Kq!EkMT26z}^PuoZYRrG=SAAhOZ~-T`};uv*>8~^Wu}z1axDnQ*uQ67?Q>#b8Q%K7GNoy;)Y^mL z9h+jP=T@X>1p>_6vB#bM?GWTQ#{MG^OEQgl^SxJ6iXzM2i&86sw;EF#_7>^|T&l4L zDzgwZDU9Y^$xjOudnTgj3RuOAs?q5}-<-OK{Sf>{WB+?rbZB38Id62^IpnacahT^n zUzEsA#1^rs&n;@TI3p{jRFe`v?R1sxD;mgM#rB>4j7b#{@47 z$29}4*q@C$1&h?Jt3oa=F7`9(->x4dw)*H#w}26cK=R(Dtko3dI`u*SN&qP}_+AEE z!m%e@^$JZa??59vJ_If1Q!BRE@Q;KP51vbwSME4YCg?y6)38>%&8vy!^;6+j;MLDu z_VRAtJ&eYq${iGkM4OoOR#o*2k@Zo939nhK&>{ZxIU5NJ)g}^V?CJ)oQLcVGgL-!l#kvih&j&wrUz_jh>Hz`zx z=pH(z0u$ZK&xJfaFA0&tBwg7O)^!L^&H9S@x(J|9d0r=o z4TI4L)#0>Y+pS!vi{uL*(`;%rG1JB%6YmwW?ON={4?B+dmKn)&ktvN3U8Ob z@U%k&F{gVAl+=s+O)a(gU9GK!dQ8cj)9Cv=UDSenw0EJnQCr0YE9Y~t?P9vl_;wG% z&ucLA34JkC0SPRf7L4ZEZsDiS>W1OFwuFDk9${2puGjRVMxM7+|;U$53BXmeqQISfs zCxBIPn7`c_4Pz}2kiGb)_7=y|FIoMsa+b!1AX}EBiPc5tXP&Fl_ie#r1aRW+KYsvqDUdiAT7pq-n; zGLTDHbU)gS>g62;R1d!^d7dtJl}$#KUYv{VNWAWo@F04f{?%s5h{arcH;f^b|TPOpO8+J zxxI+s?)avw19dMQJ6Hrtp4fk4OYB{Suv3V)G1A-?@XYH;y&y-bl)&45BLyye+qU#D z#ghR$88^K3f2J)cR}iRBd%!y z)>N^I$H8b`v*N@NJEFL!0g)ABKN}E(@ZJjdVJ;coXUAg)8O}XAxAWlohN=>M)(?|B zpD#a?k@Cd7BY8iYoQPGJqnNX{z-8cQEN;mKn|#UaUJo4dIe9hy_m+N?bgx1QlPO0r zz$&~43myh+9`$LOM)g>mxfZ{+k)I*ZQ*%W%GENTA41c|m3KjEBL-m5kL;5zzrFN3< z)V<(*Qufvb@{J*DH}d^kY5JeVk5d9)wGTOIUu*Hijkz6kRNxtTQMtVOZW7cw3A_6_ zjC^i;qfm8Y;v3PhNFX1oFNg-+!t)T9Yfl8Ih3m}TkEi*7e+=BaXqx&1M_O4!1{sdB zBQ;q2z$M0%$j4>$My4r)n+8D|{A35A1ljMVx-!Nnt;Z zBRWuG>8+->t|x*e58d#yNY@r5eYZUIC34Ha z!GYjrM)1Xp27dQ}bQNoR!Lt(38mrC6v-Iq+)5u6kqeqJD)4W-6p_i0iXa00O@z3|e z6`WY%@jP91HYt+clxRyI2E5MKx_Gf4md78dA*Y#Zmk;U(o!BG6PrCzAv%Edo;552I zHOvL;I_DPMO{dZ@A}@V_-R9)v1c=k4?+GNgKXhIN^)++?g7T}R%vPYrtf>{!bCB`4 zk)|DF*faH-!4gPP;I>R7cW=vf`-L;_78pM^UB~>YN$h`^Qf6wH$oW&NvJkgKGsyW1 zc6;=;dz?E|*A6sJj)wLsXSqFQW=ohX7JyzobZtVmMm%OHSu3g#Ytm0T!e$`|L6+Jb ze^JSA81UYooi>+zb4IalPr@~&7ZO4vSGPdeemu50T_bIT~gj)87QG@L)qW!<}=IL>U%udVe@W-9_6wlJ6KVw70`wcj2v z`Mi#;^tvTerEf7m1gbY`vb zS@3wR!+tmz$l!f@dwV0#m8a*5G6anKopol)N7aOsly1!@Hbp+*Ge`_Atk`OU?`26d zl1#d&581}@9Ym#qFign@LM^|9pH7d`&ni|?;)1kp7#^&4O-8~t_-n#M1ho8Ftqj#> z72Qu-^*^F%nxVSVtZ|&uZ`*PfFR37MZc~rkZOt#OU60@I33aT0BkTO^b*ufEWdvTk zE6Xx>gpM^uFT;|kc+Mygf<+{^9xt+YWR3{RSetuN&HK4If*es@ZPY7w!|R}+tz{RERS^_AHJC(9lRVK{u z`IVh&LOh#MRxtXMmPIamyM@9{G=;{HRvmJ0l+bIw^}c*pL2Z{%x47q*@kIGI-{v)| z3EnC>G}Aw$mWK|;j4k})f0caZ1p9g7d|Jt-eFA$;M|N6Sw_eCY&n>%9;-oi}{mP2@ zIE2tslPDW}PbO(vYjWRfRiQ8Y*o5zI(MkjUO0%be8;Q?RfSwPhj93O|hm~Mv&A*7Z zPk{O{?dgBI`NnXEaYvO!bTSoBn=@ z&hC%#G#QlJFJA)XR4SWI72>#iCP@J6v-LF>s_vi>0;ch>g-u~r0QBYGiP%s1z!Kon zN&c#DyDoiktsPF58(osO-?+F4RX+9gS6pqj_wBsWAN+qqoRGB&+^J`Fh@kq}Eaio;KO=gf4QPtLpXI=PMIz zHDn`jpDkLG?oOg*2p}chC;Ywb&ps5>)(7vf4Q~I`MXL)kq>md^I+Xd5G+SLEv-vv# z($fVAGx`E`lIgN(A)k9vTG9Ay_u7|N&6!D>2L?=t>kd`?cbL5us(=`(yL5906 z9gZAW@bpo!D!j^x1Fni6W)$?K*Vx^AZj$?`0IE!HgbO|9NI*#le+&&lLqkIv)ZoKL z>NO(xrsw`@EM02t{*hYbCo*u)ySq~e2nYac$;G$K#qNH8Wnsck@xRLi*f`o1O?O=>0kdN4roq_3Yu)|#V=grs;+`d3H9ppjS=SFyUAcm>5 zeZl4u_{saR`t52X0OK%8vG|(-p9SL8Pf(mpNC^#nXyoIxB52YGb%=saS9dknlGR8l ziJyLo-VJ~E1jjH+nluSaF)bA7HB!}jNQ6ck@Nhp)>++h5@l55P7_L%plMb=aR@~2C zWG(-b#3-TGL#~)_O#N);m#cerLz`V`mj;G121JTu|3l5qO2p(!~6xHKq~Yaw$*!OYN|9Piy;7*xSqDu6cTd z)%Bo=?~5wE2pS^><<9)Y*|8cI=>PE-GeIaky;H)ltME;#H49q-32l>22?r5CErFwp z?qz+r63F$G$!D$SEr<&I&}R&Lk09p1!|xd}sfZ`-EL3jT#mBeYfyM>c+s$1S?d?&+ z+|Ag)nhlun1LP8bp#rjuEc+k7JPQ@|TIZJ7L1v)&=F^iTkmvxz>7ri15dfbmm^)Na zpAq10xO#X7nZE1P)_=gZ?(ZB~H5}1(KpFbOPrMBRpai$;nQw~MyTMs>=gTy7Vo69d z*phsCYlmvJS^x}0{T)^I`#njAX`B_RVSOxMe&Xg0Z~T82U|~RYMQC|#ss^K%IgJPz zJdo&Rhjk;;&4cAbbd!5{E+bW4wh{K-6iij+BOMR&H)L)uXRWrl(6rOA!p5ZTx4@qF zy0xIWOVn1WR<`g#@X>+o^!p#Vl?_DtQZzwsATWe6h^>@R0!=?FtVGvmP~ zdOHcdL3r+9CF=BFq&gq46je?ZCLz{qxgJK`W4U4>#26VL{}A|7cTU?TI$?E?E#OLx zT^=ljQGza}OcmAQ)UFb95dq$;ZFh9BSznf++cIVahR?=~f4h=y(>`--VY@;@H?%p<7(Pgbvqj+HZXPZkZ zYyY|q z(fvclc(HAJs;!};#LcQ|Gh2>s>E9DhRD$lMBL1URv4-#C*Ccg;> zm14UY7h;MV zGyteG0EC#atgUSW04V^9tE;aEnh^l78Zg z&ZOkU*OMh$ohi<{8BmXL$F!;cG2oM zP%=68=7-TAj*76<8->y%g!Y9?^a^Dp72`!JVhg9ykRP4OdMYF&kz-f!Y;KuC_2yCe za2*4B4f)V)>6tfdUT3-Sq3=cn;=ZV6E>co2ojgQTL!`%iDP=DiX{;tZ8! z6*#}fLF`5;|4zX2=Y6NrTRCjKy-((gyUl;`$zGwhAOyXjdR7oYQD84#)55%e8r~M3 zOvk*hi?2Msoco}uYUV;UT$Q7V^-z+XA)n@~Yp0uj*RD@$u-+anL2657h%^ZC#YxjU zj*w#uBXl3S%i%3TJ1ywx0uv7%eVG|tS#FyQmq51c1 z#S^;Y=h%h0COOH*L!6Gg%UxrEubQ)D=3^-YPm(~QXSh_Sh`q}dF>lH^`2cLYwA*os zTb;ve;APm>)L{S91Tk9@Jh=AA>35n!xoUWL>Psvwt|?c^wawqOUxaW8%+So@dCw#HL9$P{Chj7`ychoL;_*{~&gZG14?XrVe;Q-e$ae zxMb*sq55-(P2_=N3TIn#@LX1=j^9{gRh%eo5#UAIYesg_$bT!g)=D9?9j1Z#p0ATQ zv9cPnpla7hZW|(DAfzQ0Dg*Q-^OH*S&BoMGGehzqHFCa>M8UW;n6-3}0puc!BmlJi zB`ps?xB~$Pkk*cF%=MLfrUQz!e_H5Yk)bPQa2c169bU5{A2749p53TPl-`=;wm z(stW=8X?|ce>BerfU`yQ#E8RH2IPIyx>#9R-#Lwd##4#PK~?0y84}{l;MK$tKm0|T z`Kj;3Dx4T;%8Zs{I6Q3}c)+`3X~&kVL|8hyBRmO{<_ZBw{YybXt4BU80ReeT7CGx` ziEDh{+$c)o$ct@;EnkDA8{K~)sNJv^RAx1l@CvR4G3se-!Usv)S8>vXr=_%QlBqN% zO6=uJG%M?Ykraw@8WOf*5Tia{s<1_ zrIJ$z{R>3q69GeH-#8|s4+FO5qG9Np_dv2{7vVv6pQXa~>!`_2b5;ej5QsAHkqOc= zwV9oPo)Sw7Od*b@q&Zz8mv>#8{ATgW<5j6Eh=M$2LUr#ltCdcKd3`#R`mwEV#dL5Q z79aY@_t5Io_F9!gc9#k=Y4*s$K1>1`V8_w2OzXF_zj8YRZ7cfU5z2v#egsa7r*n)l z&N;J)W))m$fz(UA?Uy&*Ic<0Rv~!}?Xo32y*t!O3zIBo&316HU4*tsC5)zipuip*} z)Hv8q=$-a0_wT5~wRgZa!w-;B3-*1vQ{Gf! z@yhkSd~Nd;(9hXw=pm79)v#xV`yf#=CFv^|#j`eI2=qAMFK z!>H&UmDq%>-0{O*f|!9a`Ut3GkTri)^7(eYp?eHa^tjL%9FQq5M}+I8G*xFw7Ulim zwE7%u$bmAx0geb+Yh5`HHZP0Ecl`VPD*#+|n{MX2so47QazBPpj@C-WYBD0MCi=8A z5GZQr%)Bj25J>7x;rP`dV9BLx;@yKLXadG-ml-3Nb|U9s#9#Xghzl-RsW|k-`|Cs% z1vGEW%;QT5Ew_uDBtBOdPPca=#7>KG#em$oKpONZ>B+a8TWHFz1tiF*y=U2Ufx*1G5}(3RuiZT=K6**Psjo<$Jgxtt|3K|1}|Y@(K}qnt!>x_JRY zR!bA#&|lJ;z7vNUhViTzMH|7)3xI)2!mQ{j_R z-mJtP+#;Wbq(!%ndTHuqgE0H{|1|X#Kvi{7+lQ1c>E?ohNFyOiHzFk>T@p%4Djiq4 zI|W2UkOt|NZloLOmhSrZ)%W}UZ^n5?XWqHzoW0k2*0Z0z!f({U6j^_;#Oa8xQ<`O(}`4bVrg;IbU&>z z+Lphij#jSOEWu@0XEM~eF=PUo8CxhM91KRc7)CBmk@y zXS3L5Gv5xww3@nDzp!0Sl6K_>pQYotJ?)7eK&l?xB?~mXj2gFk3207E^4MFW*5J#T z_oFm-lnN-g-%&HoCe5Hbu(}ki!pmo^3@|G7jT4Q;??dZ^+s|Eodw-hk$2z&=hoZ4iJEd9A&nXV>!n8zTE%*v&ramEWHw(bj&}U#Pufz8v5_4`nTveA-;LD({O%80 zltwo8^VIqNfs0P%!9PgT&c7}1iQ4czH$}@uVyVC?FXX$qFG`hV|0GAHvI@hS4gPxB zMSP#h(o9$j$;c|wwNH(FRkE|#G7&ZRlAbXI6cgZ>b@~$5Pf(pRu(tQK=ujf<&`XG- zB}-3Y3`eqq!3x~{hz)3kgPv?4*THn8R{Ti3M6-2sb2H~X9K3g;io~Gs|BM4XsL|DsOyjY*Jh+r5jlT$tG!8|J(q;%q3hw&%lil?L26TtGWV^w4U zp*TV7nM51tC$5k4r0TcCIPzau<4m>;QwL0pbT0I6UP3-!@MD3uBn}m)?iE<_3I{?t zxX}hXceL8k36hRgRTSEUW1pksem+<5Ywfs@v(OoFFR-9ge?z;)sGgXCY#X&)K{j@6 z*1Kiz2(J`IuG2!Yl7Z+sCuSG~c{Sv~1-_9v25LFuP`Qk^k$Pt^V_C7YtWiPu#Etzf zLt%MT$|nM8Yt#%HxrwPM3lBhzS>Ay5AP7K4mWgT>lS28=mi=TY9L-Vo%8)PESGP-~ zkcHSiTnCpBY{T+DwxMqt{8$-Te2W`8$Q-G=-|d{25y=a!V|sk>31iqQ{+=zasy_0a zr07^RGW|WpO%i!&6Z#}QF6t}Y6O)&6R*{fP{T-2a89CPb!nu{oj|3btbo|A}dc&=e zR`ds{sQ^)vIq6?rp;V9-G=KZ-&+tbj}!bslc`!r zKfx6TJESM^)4n!rXPdORx|X9tYH@m5`huk(LPok3DX!pfTJRC?_)QZ@&(@nOZPaoq z=)+F*6S8ycIb;P=hHpq5;x}|=?~iuphnSqmc=q_3QMbPP6_)oRwCwo&J^bCX3E5 zX-+K!E)x!>v_)Z4QQKXPSdZ^;iahbDEL$YhqC|pYY7>GjkNNkKpw_1*3Y8*fkoPY{ zlRY;H87aD_HWKKIy=Gub>JaX0M5=$%Gqi_o)oB%Z=3!nNJ}QVpD#Jl?s-i?Gcki`+ zfVdR-bAfzB;xl|w#tc4UL?uHXW8E9QhGqq__6RuEn=8^4?=ub%4D!*eaEQu?OzeFPjc+eAq8WE_aQ_ z@n+#cxK*~lKDo=_o)hU$SPy|=$jd|Vh>uhH?PLl{_hSm2O|;O0GecWB0ytZr^70OA zleTUK4k#s}yD=iph(8ANSAMA)P%3Sf+cW%DWHH`ksO`G>EQABrvXwrtTw3j6)nF^4 zGNpbRgQL?B&02IiGvh?&L6@axZK4hxS~fB$16vyWTpcc5@zOiK8pnCxaSt$MbELCT z3qv@u`(REAu39DL1R=O{;)RuHf(lOW4lMb2LI~uk9xgty^vGhhV6(u$i80~9eECwx ziQJ?(3E4dohC$PzH@Id~dw6&VLA4!1O!20eWp@MTirISZ_A($mr|L^Xex_&JZ@PDz zWibZ?qcW38q258I>^Dzj9#@+H8KkVN>=DP#-G3e>^}Gl6K&e9RZ?T+oM22nLL&4L{ z$@Ub%i`7dl$`T(8eH0wEJH7@39>N)RFDF?+7~%@W{nJXSCH_`R7~NA#rIra|Za__~ z5jf*$M{DT+N&k))bs`jMdKiiS6TPdxVjn5aC}T^gdu8Ee)Y=v^IE%X>liT(z`^G(Wwb z7yFQ}Dh$tS4WT>H?pdU- z086v7uUUthILO*G!RDIR;vg$2*E_X(rP_}o_ocXeCB2zIy%+z*9t8%qA%?DQ%`~?| zhiPc7|=Xx``(%G>I5Yenq_%)l%tWf(D zFeLBCh=bdmxX)s3iA&F`b^VRV3#^C`rY#8C?Sf=Mz}vt_a98om6C)xFeWu|LQh9kp zggRBoGC6{ZxPnr%R;EpiG{u8%Nag?V483oCHzunz>tm5Ow<0E~vRjf3f2W03QV~S? zKygn=na9{gi6h>8Xps#~OrJU_-E^RTosP+qg23)0$>o#aXUwfhv>=7uv`3UiKK65y z85uE_U%0iDvuteCKguAkh+;#7UMjzdUn&nnyb>4vGbm=8kl8Zw-w`*Ez=y7MXzG~h&%g=RePEOc7$u>I7g`$}kV=DQ*Jkz~M> z0?Aw8g%5jZZ^*7y2D}f$(DDKF$yqi=p@@%IaX5BNnZEWfE+?=E_!EFCUaUgn|Asz=39*f=u2@{DSVCn& zm~ZzOJXj*)S`^=joBLvWf+iU{Os`&qTAbW`cwFiDtrt-z?#(2Qbtk;?20o-aPV}SM z93%2r^}W9d9CZ+0jWPVlBZ9)xqjiYzXt16PS8qH@=^N;>#IvE8cRPa|2YNphrHfHu z#(;q+iAhNm$2P#HL)qg^qwZk=ocb8~oCuf_A&F$UoVKQJ`?h_jasTW)zD5wLN=@sh z?ma&+8R7X&u2hwDklBPzU-<}22Pe5wd6Uo06D!q4{bd}f?5ZV0v2SfJNX{jbHLIjs zRkYSWqPzcRK2_WMqi_d=T4*f7D_y3Xc=r-j5mH*<0xR9XW`s*V2XG_e%fQ*vd?3b-yRi@Kq=Azf| zDUU3?mR5kJ=PSrfAvD1r*`|E-?VLA?L?+Fb&6{O#cd7LtRg=x!8t_?vu@S#07j7@z zF0-lEav7HFtebibo!KAM;O8#kscB7Kih#Ub?o z28ATpTgXVuwQ#Hx%JsHTcorlt|=rU?Vy6b+b#QLOY{1cdS z_2_K66O8@iq=9dZOge%(??13&_*1&f2MI=-B4KN#f8bgcdCmng;y zBY`A)()@BQiAhM< z9+F9n6j-OD5U!@*V|vhUOAjWUc#+tS?uE9KJ3{}{>1*uuJEP=C%;h@%2M=AT`E@d$ zZ5ysTk+)CUZ+twp?tT-plIwU`o{plRO5gVN{P@Z$vNS25>zTNj z8#tsr9aC42O+vhaKU`-d4*VsM_8+=kFaY@mVWS*w(gJz9&DF04_~*z8$Yjv#Xm5cR zmzrL=*2P8NN-gah5_rMcBs0$S%I$HJKl6RO#iI0!y+$SlB0ZfT{T3sG|H3g|j46iW z2u>uitQoMKB9iE7=LN$9>j-a|c;9SGIjXS6l*$NW!b#e%YPo4B%oY-U-@ltANkvKn z=aotaoTw}g)A!BaVD=C5JcAxJ6(hRD)qzg8p8VZKm=QUFk8U3utZ8WM`WPsa9;y5; z-=`oY6e=zL`KDY&%>EB9A&jh9!Wr3ah^6vDn`471{YsP~O*n$Z^n{(n#gVbCA%{I_1>D5#)InGTbF zs%boXKKpC_4P1_G#JQ|QB$*P+6X(fg#OUiUq@$)usD$H=?=0{}Z1feDywOqxNvvZw zXLpvO`(3?s3v)bGo(7&gW0VlkvGa$A%rB*Q8Mef{YNF`5w?B>m;Z=NsVaE zk(@scp<#j4i%8RG_StxzLP0CWgX_XgM zS3K1~Svk1P9dr;7EVZJzt=E>ICBTSjZldFL79Puf@W$I`AdqWl2Rme5B#4J;W|yl^ zW)-~=AC(&e3>q668u};NAPn>=afmda%`yMrJh-7=UaCS4QLn16yIZ;OJFDte&sP(M zbN~gW;||46=H_A29F{qBCTYFl)tZPqKamiTBYgCZ;C>Fh+b3lDys+MT`dP4kL)G#V zvOQz|OZ}5%FFI549U%M?9vPxwmeM0P(t-c{#$^Jx6x75rDFuX1C*s5^;Z$v-|C0+q zgJ9#n>vXI~iUg?mru@>_|G>m(Q0bGmuHo*_%_&M8C99{m7w8Ic^(S{;ue#8YYlMJ` znf$%J@q=aSP^om3gT+op)==F!cI4{nU+yjh-O%>Q^j!nW?eUFMexdpc$e>ziZchsf zPH)M-NnNakCX_Ku|xVXB~@5r%|K}k1`f{GX;xdb-O{rZdCL=d;T<>&XbQkGiQTdM;WO*j&;b7 zX8jy(g6dn_r2tyF-Ry7QOQE>8x9`rI*&q6r^<0g`Oww0xkzn~ny3wYxl(G1O)>d~t zZIZM14vi%LodFOOKpS*6L8E2#{pYX6ACvp*YTD7r277e{Ct|D!AyE76NnrpN|A9-7 zZ+1qUN6WIr){x-StzS;#ZP;PMU?EgxeNiZTSM_6+Z*_h=G8Z{j)*=!v4<=&G$w7bz zst6Gg_!qiZt~%^5?Z`BD#p6OPm8LYmD&=(S;z`lrd?Rk^T>o+TkeqO1dyD>gH6E-q z6ubY^dTZ{D^8<@TP3#Oho=F_YrNm6k29Ao#N!bUw`lEBuPw;yoMkd)Ka*U_7^RGijMzD06(UQ36?8Ik-%2kca?>CB}g2tA^%>xQu zdPN;LKBX_EoZjEvcou$Iu~227c^yqM`r_?w1lOmxx1E!{hz<){5!Ue8c0CyiWaAk_ z)by9lL}XMg&LDHp`?a z%`IV~7uU6HAQ^>T`q1g?Z+bm{0eYU!ruM888aUMl0#l5=vdhV&TM)TCg#p>)s$1;5 zx_SQapL9c?>2o!P>1zm1{l6AS-LfGR1hT}6A))88tBLZF`O6dCfE-p+cP_ZFc4;q? z^JKBb6PzdoK4dpCRl_ej!v6P}8%A!&@9NJib|%l=_#FCRjA1>%0u355VcALYWy*|T zEBQ@$Wr6!lGD+VdaRVWm-c|aLWFD8p!KYmMJ9mZL($jW26NUw>tAYrVax`C3g?Ll! zy$W?gGo;wO@^#7(ip^Qw3b6_gdSO!eRKfKUk;T?i7W2GAwB!zo6WjeV5#uCODkiX% zkt|>a*)P$5>sKltOxtaYKo(zEpCN)b>sCzcyF7I8Az3{a!sE$_8k5(IG4CpW zua)-petv%S9$FgfNBcwG&uK{bsJNN!$-d#K2Mo0J!zczt6#`WZW#Y(n8ggLwpht=L z&_4kQ@r-qbl&tj(V*msMQk-wxPsA@&XdedDH=`j!d6_wLX|@?o_( z5I9`|b1?730%Ij8t{kWdX<1JI5Q?L=@qT)2ZQqPmPob+Rx@EwUMAm4ExQdhiW0^eh zP$rgvpj5^F_Y{6~lfSjHk~afel4AC8GEHk~W=-0WHl@pUG>>HwFs;9h!VPPV;z~9 zwlHuf$Dg7&(+UlS2k11&2Kiq)-3r+JFOX^g`no)5LOl2^6G^1m@0j5ZnM{xz^C~t) zS?5Pbx`mmtv?p^xQOByB6D$3Jq1NM&#=}*o*C!rfI_-5ulTD3RzFA@Pml`YlHMQ3~ zNe41%vFf#h{`byObV2S$#;)^to<<%`h1jUVWykN4sj~5hB)btI9s|LlFPuzgD$gDKoSOj^bc`lzXfD7R^e-S(xsc5Zw<#?B_J{3{EJs8 zM1%;~jIjL6H3>Z5Y@9#U;E0)kffA8;l2_=h6>{*z5>ZS(h8c617EJ))M4r}r;t@O- zcvjogu?tq#=escmD(xM~Zv`yslk7-JE$4nq7L0{knG8`ZtU*sDTxoU;!R_wcX!34M zR~B<()JVOkhQ|7u`Dj^>W=R@8SMl!oH92WbcBL;?sStLB^=mILug$VMsmXAQas{7% z`Zs_Eg0E_rK&mr|AtnS{4fMW$^!O|jw~zEekkS^TDlYnaJyI>M7EXwVb?b}W=ZIvy zxDdC&KD1Z^mlB63jgTDjM+nsP-lmc5O|qeY{OjL+VuoeJLcT1*K#&`fnJU|5v#Ic< zQYUv}SW}e%&+aH?V`FCz`|GUjlz*KVr>B&q<$*-b1VT0bg&Rh)%REHd!EZlsFU{(7DnU%%nlBY z82MGm&GKNje^s$l$sBU&jvg0BAr-fdJUjLc{p=c!)oDll?RAAawILiEGF+W1TXV^S zX+Ud!j`1JI(#~zoo-goUT_)cZk<6g7I{BGl1lYJEDj7H^fz-!(eP$}AZVdz`A}}OM z0vNhvTN)zZiavrSK+(|QV$E$bY{2tX-U{=BGRneU^dK+Jyxk^FUa<;U9$yoKJtWYv z06pDwW!K{l_P9R&T9eQBJh3ZdoDy$bsp2syz+D!|CL#-%%MfQ*u~;C>ftF4SJagzl zw^ZLSvDgrtx^<6%irAO_Dq~C1QKbZM8jPR#>?-d*lliNDnEaHxYwof9D$hsyes@TG z^^Q~`8i5Y7$+wYI%13VwUU#CgDLo}`3zzO-nmPr!s1bt$=0ZTphj#Z9y9Ve#DYaDW zgomOn-P-QjI8arVibkY&Mzg5Jr+4hI*4C=NJ(I5SIZ_J6$$rn%WM$;c{gB)dr8(co zIr63vgA0k$`9S&Gk)b?kZh%@J_IMme(TBGRFzMh6PwxySJ%wz&@Pe9vwfB@^apYMG z?-EzPm5{Np8d6CyAvK)@iX#~gZyhg#Th!fQ7F>T}6lhU>y2ap?z-kYvM=WVMJ~5fC zN#UeFONSFtV$rK6FM;RilDXIWR8hBAUgw`$TMn{^2Q$NG-Yqma)VEoC9M&)RHx}cX zyUeqRpa->a#;24C$%LegPXX8Uuc?M)~9Pwdql4@9=^V}&00*#Pn12| z3pegJl8a&G2&`+T-DtZra46An|ISKkqzj+EM%ZE)XXY@zv6mlqtwq!7dcLl;JA zvfC8U5=&U%I6#PQ~3$HNEc21NIp4{>}{H4n}s<3Q_KX3ltRXWym zIeP9TeW}o{ScHTEB|HmVKc$HMU@D3$rEj@%-V+_&YRxWX)2@tiaWTyCf_CK2|7U=vAJ(Z zkehO!kznhoJ+zoh&R3H<1g5RFq#;2MzelM`E9f3YS+f__ck1CJC=E~8>oDmC20qkW zmyU@25;4bfbEc~8b)mhQ-c3lhRAci-Lvmfgi}|YWYvGkZge8B<=Ors?e3I%%i zxB3ztNF7=6HVB@ONCk@jv;n&YRgj?~!F7=|_eCD+efcHlKA+Ij^XzTqv`ac3ltEwG zcr?TRzIkT)M;nzjWx|g;GfVMR`jY64C#FJ^sx~il6J%xxEF3hCw~tE#ZrK+F593&9 z>k39Kf&zu-I_u`&Jj(CbFu2VjXF9gi9S@s%n%-wNw0k;!O{@U_i40a+MWmJKYtisV z=gtm08amV@QPouJDt>r#ku}RN(BWkFOSXdVus*1vqFtnRtKNpZvR}z$@L5S`@t4l8 z7YTVYYlqudIOUD(0`s3%?U(8nK0Z{q$aZb<(4(r~e$Qc|9?;BRWSUa;`?8^T?GV1L zoly)yO`b0ZSs((x#H^!S4s?Xi#D3=^l5d^!fNHDc7_IvXD&zfvbLD!3qngj2MKzN~ znQV!4GQ?Y44bVw7Tx&>4iFjNvjcV_=yL{*y?_{heCnR}ETyB;!O;1EyoL`i?7TVF4 z1hWZ|Ac|^B^^=q`LXsAfB7(9QF_8K3!BXo#^uTdLht~P0N%#eRESYgl7)S93iA=3r z`i6?eZ|V=S3sGcS+Nea_1ACp)Vfau#v7-$q$MdXXEB*G=3wMRH-(WdlAHQqB3Czr$ zQuqd^1@)KVI=m6X*f^>kE^`S#{qGHRQYY&ICLb}J&I$WWL5RC^`E8@V-&2K`W-*wt z+loJCX=$nRc*9Y9$}8iArdSlJIQ_S8-(1qsAxJEjFebJE%#0%=BXi`2ASn|vUh<(4 z0=Io5Giu8%rod_UN@>{Fnfe9V%6!X$vbz+D?*(HRFngr`+#Y%bb|yS-D_knXksPCW z`8xZVD4T6^%5J}#b=i#DERGjNL%vl*04(}PdDW7|vG(%Ps)xhf23PekU0wr8X}+Y& zzNK*1Uo?cP)mudi{P7(x^NQ9SJUuzGpTCaiK3Ppc*v(4YDucIR!*0*yB*iDC2Va1n zW~lRqiLgG)ACmg%K(^@5z`V}%PMNBtj83~h2u;;46-z9cj^ddWf52dL8#(l3_PZY?~mQ%u-2_p)y0Xn)_^B9 z7;lLPqJFO;7_QH7NJ&$yU0QAnty;2@EbK!Lbk+aam~xZF`KmvzQ**iclx^+S^cd@+ zRD}k`OaM-6oAsVNv14;z#*UZfsPk)GVex|&U34t$i97!X4kE+{pt(#e962&Q90-ca zlw!K~sl%|a4OhLw`uo;EQ24ijP`8=j)Ov!i+Iihw=ha7EJ7(@0gvgj4eY6b`BHK%6 zU)*Oew56nEmZDOh9Ux1tJhA>GHXN6bknp_!$I+4TM^7C(mHM|hY80xPO$|nayigV# zJaqA_VPGH#XRr-|2p%Z-Fy#KIrFAbMgY}+LSHPr)3VnkDse=NU_kSGbj(xYccjma( z$CLKQRqS|?`?y>nVmJg_q3m2JN6>~;Vn!FW9y`NjCe&SN#M0#DL^19w8GaTv#JUEy z)PaHU;2AmEOJP#mC31GE3fp-y_9+H6WFu}#Of;l0wQKdbnD*+U+SxvI^}Gnvn@{3W z@qV}t*>LL*Wm?69PcXliuUM`}$*pdYTwAP6_NFH4>mqi|8-pqUn#*1sSvQs&fAc7M zdRnK39Qy5TI^7%zBE`01aY2$>sab$`=a!5s6611=45PGG>%D88EfcN~3|k5+FPXab zmickFF1mKn&dP*&jz9R9E$VAri7Dr%LvQLlMZtu%z=vkku53hpXt8L7^5BDNTZ-5I zeo%mQBP=?a{Mi9R$L3iMuv{QxXhC0A%|q=Mpu&C)c#Xm zIx@_U_0K}S@=r_uOxe6xvg;V#wC&*8c~V~$S)PgSlJ?x(PgIsZmmXvJ=;+bzFyvjo zcG-~n>64u)kGJOcY0M3a%4vHqFJ&?mh&t!{x?7nYx7=n!wM*l`(3S3prF1JzHFMZ< z8D+1>i=C>?d{*W^2{5>8zfKt8levKBLIDiVT=ze3@D*4hEK3-_4zo-bEF20C0zX)dS4;>feQ^_iRp7Z{a(4WT z8Gdn*&l|B265y5PYT=jQv>Yw+zL`yGeU|JZ*(J5$#X=-w6v7g`nG#zddQ49Z6GTIEcZ05)>EsF%{=2;pZrl(e<VZy$(GhXL8tCUw>maeRXABB4@@eDb0Wz(8AvT!NEm_5V-s2%ole6#i=Ae zNe%n;Mham!8QUBJ$`U&T$-HD%zhqb2KFP1)nGksVh(mR&V#RtZ#CFm?{Ob1l;rZrP zQPzPM>mt8_0GNBY+TH726%P048y8q(&e|9>;|PUw`=LQlF<s>W+V)csk?!m3 zdVniU=8z!4IVt&pafry!Y4z*O2xH*=Tl#xpYfN=H^QS2L0dSK$Yuo9!SKr)0qs`A9 z{&1s3T>EjS0zIg2$s|hV;?TTI>rFP?GxcU_XD zDcbKKjOkv0d=e*DpdAt#!(%Y4`;ZD<5T!^oB2W(5`-m$5NsNe?sSHfTUS3@EMFyWA zXu;Cn>8#UA8xs5KNY!U4E+77BROGuUEnF0<)fQhP;?*L$`t+*AcGEk-Skc?_frDXX z(V$LCon^z~tEbt+Z!;IY13Oins^vwKK8g}fTcX;0c%d}EJ}ywy*N<5rnPGd9@@i-x zyC>}WEniIrJyE#ycWQQn%fnYa3nOJ4irS+ZCU(uI*Kq^Y`GJzi@xW4thll@Ks?TE_ zC|a#0Evmt}mL1%EExOQ3qeFtwq$8J%bS$v1|Hn$vXA?%`R$(Tqle-@kY#I*nCecf?f z5^~Bv2U|n$;w$@p`ZSyu7P;tus46W_`Rq-|SZ?uLcU*5nJF(AM{iZB^_J3DcNIeJ^X;qY!4&ojvRqwtwANUdapw(;cYX->J& zd+}ei>0zPaXgUcpx;Sb+9L`>zp7D8k56{ONZ^}RPhDuMxffN0pM}4PJJNL$^b*1!A zRXJCjXd#Y2eK}h-Llyg&<#hBNN8azIAo643Kq_kIPFzeuBBgp8oJ4=PxW?P# zrzy5~Yx*?aocIFo_M%{-qtuIBn2g)~Vbs~Tmt9jJDb^@V8?lmN+Ykj@fH11<(rOe*xR?md%HCgG;PjS+k?WhJUJmKewnH_hNKB1bOibXGt zJPrIY$5m7K(1!79U!7Vlsg{Je22dNZUwo9f{MblL5@eDUQ#%zi^YbCQm%XpSqjI$w z!>uZ%w^bEfx^l6bgl+0cNk>xAru8j#k5qLN{3}lOuKCSt=$!e6o1JFkBEGJ2B(5#E zE-Y=9*Nj-?m63)=M6{iHfc7X~IXMQ)Arm;T8@YrjHdJpW^&gaaIFm-dd7;=BH8eP@ z4c`lN=ohjt6c(Byw0fGYc(lCwL1lt*6p=I1y5+?Z;IWsdyJUp&-Bv=+cHBegzYB7w z^qFvxQ@4&@Eg32rA$7_TpxV2-UYz(q-co=980tB4o8-;f^vuqF`j93Yg#;;>XcvrtwtpEGSc3N0yFlU&;6!+w~rF`6L;U!Tbk~ABYW!skN0+RtkpZ;TR;&N;6Vhy zSY;I61HN)lTKU*WW*-j*nTD+p{KB4xRz0lX!FBPs%&5?lXzsq@ojT<^Q1MrAIKS*pIMc!fr1U~tmz$B5<3XKyL!~F^r{4v7 zWmCE;&QBP;8c__eV861qe8~EU@Od?hP_XSC93*`h zBtI$1+Su9xixmPw&;YwRSE5_Kt5g&%oVb$AayoE)ymyW6r*yIz1FSotsAbH7jP~dI z!*K#yI?EFh$o7-^tsJO(Il_WUD$I;tZ~gI0J-+mKEGn8X?|Er$YCTBTxiY%a?T%6}M<}2p zF8U|O-b7ewcjAL(yo9z{*`$()(iDKD;2=O8A~{yMpox#Wm-f!iGGvnN>gq!gqBn`B zxe&y!uGdPJw83|=TGe3Iz7cVc`t!%HCHvnpNnk@Ptm+Lq{deD`Y{<|Re3{fq5KA>6?=>_l_!MH&h7q!*S+1BXvJ5B6Cs@LCFMu$FcKAF`x(XBkbKQy4x++751e}75#9Q1+C--6%J zKVoFSUESL7!zj~{h>#ZgNX|q9W`tZfBLV@P136?B%;7&v{+G@${Qr2^M7hWqz1f}) z+uxU|AZI$90L(d;*fLuZ=`QP05;pAQ`EeC_R#nwu{D=Vr;Z(~@iK}N-ouf``zQ>bH zF1<*V3Km{=xp~X6w9kKc2x-{|oYx~o5F1Rahf}+McE*CBhnFIsaG+w@p`_+W{+Bs{ zDb0ot)e@!gb=Zj9_=6JL?o7|1@#Pr_ed^xzy1g9Cc^% zr5L_qz$^|$a3K~F#MjGIPRHTXi43+Cqx^$~AO&P^;gZ@wrh2*0yIu`^5e%DxhngN? z^M^s}ZFhLl-{eRrWJoa2{+A9?wR_lvo30o*BV z2DmeANZMi(D#M7dy$E6l^cJ15$uD#K7c7O(Bz4@*JY6m?Z)@7mX(G+a9)vH+73jyf z)^o_l?G2jO-)*rnsKhM|r<%(*2K-y!%+DLvP)%jp_| zu|CSmO0ODd%O(|pblYWe9yYyu`r`3vCIb;BOOeNU5*~E<5kNr&393(Odit}<>Ap*K zg$NFGXaaxwJr~mk0aq>Bq8Z;rIIjU?(DSr1^P>q^hn?}42rJ7~y9@v8U%ynBmo5&E zo)_yERq|XmKl-HfO2mx%aEX<%hR>2|n2`+GfgVzWlY2ei3@slTv_c5E= zUF*|8PX`sl2_K*(7H;wEQ9xKWqKwhKKYeVqo{`%U*Jg_DQB!yteJZ@*mdK_qaVcC_T1p9DNy?4c-LcLP?3#q4HrI zvLsRAmO|brQPj9Z`~H4OuNm*g>E)uJQf@7&6blD#UsYMSID0EdVEjP>u9oaU#yi#K3b>8KUxF9?dA2Ie%aU~U^w)g`}v%qmObLQ&{!Ir6<+dffMh+kKwXqr(?N54(v0aq2OFr{_TxqdU$kEdlt% z58r3~WneUiOqSec)9MEVfFH$)U=Df-neGOltXG zK&T!fh16seiM$^H8sl>Mheq_7v&kb$`ESEUv?vg<;t37T-Jta9$VcdJEvl{E!h~6@ z07&Vn`uS&-Q660$UmS#J=Z%7Bz%2(N#a2zofZeA)ZjZ>aOjuO*a4t0+9kXYFhZKSf zh@G&^AA;s5BnT^`Wr7_)cTv!+G}C-ZQKAaN$B7u}16mdmB`Hf0?1i9md_1>~Y-1>bkxsJ~$)=ej zn3cn)!xpX8JGi^m@sc%eLO>a4>HqA1i`xQEvaDKLmmWL;g0!%Gz4OA6te!h@{||mR z;`t_bynFwiIU)i)4G*IJF^=3KqDM?2S9KO?LJN0IW71(HeLzuvX4r3-GitFY*x#Lx zUcYWP{^9J)4rpiyTx71U`XjgCaYrCQ!JjFoioG75 zwOf)`S^zB4eO@%s z>o>3%gl4K>V1?#gM-YQb&)%^6i~tqH`ov&`1CMkUz>Z?xNe$^7lJ|NTc=Uyel(xa7 zr5}{o5_OS!s26cQ6u(HGqcJR;ghfedVAH>~-m5L7(lV^7tBVE61B0(!nbaoxMEgvi z^4|s^dA~s%KdlH6&-oq#E=E1Gw>yFQ49<_$RaF^H5cGJ`9bGcj=~Sr$Fn~Ni3?1&4 zr#7FG@Om8rv#{{&4#|(ihgUtuolHg2LzV9@gzPt(87?|!?K zCnk=PgZL3lqZ1G8`w)otqA%>ZD8pKv^gw)~XPyL6x-G#Y`N!+1Im%e~z*j|XY0SHG z^*Tvidtm-ekGn`hw`$u#??FZt*j$yTtxQOAFaC?56y>iiXyI!vjyzCP_)AmRK1!rV z&l2o}oXP33VEqfqgtpO5( zdZsV|EVhoIi7ycf_TnGLP@Y=1VIMZ^R0OhRhV_1qY|fM_M8_YVi_`JOMJ9ik*>2de7C1bK_|8RUDvc ziXMf$g$#9wISxN(MkjUv+5bhHn8p)Ks}i}_E>BKalpo*BRp_15k?CX=wYA-AbD~qc zziOa=1LWL+fq}=Le*NLLMG{N?KQeUBsRzLStnRUl5EcPi)SLZyB-eqFT$P)fIXKE{s#e)cq4;rwY5)N+}(RG9ifaL@iaJ_!j8IiQ9Bjq zbya+Gd5v9msVV{9*0exYDpt*9dgwi2Q*?>{fF#I-l+5$ye67uLbZcdx!Z?u^0QqAA zb7Xq!?;qsJBt?L90yKXf05Lp2ZgBh`CAEb%m6~OXGX*^(iUI!+lH;$=+A-G#|lZuccDls^>btZ|uchR|ea-yMKps`+}U-bT6W6lE( zXo3$UH;7fJ>kA<~TP8rg0TCtuyZH5b59$wW(I5?KoXs-H(5^+U}G| z(s$*fA2!g+s^^VLnOskN5tN5TDZ-n@z^`X6c8l~G8U9@Yml8}2dh7puLR~E!EHHql zV1R>}Rzl>9W*ifl5z+1U>dXBJM&BB3HE@NXRcJB^6Ui_0kv_mcc5!u8xK0fLA>O+# yM|{AM3lei4dD#v{@}rBaJ;U{A_=j^3E^f0w!kvpx+a>_MK=RT`QiT$RzW)!nG*jUK diff --git a/planning/obstacle_avoidance_planner/media/debug/bounds_visualization.png b/planning/obstacle_avoidance_planner/media/debug/bounds_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..af26553951ee9069125745f409a1d087933d7abb GIT binary patch literal 153970 zcmcG#WmsIxwl)e05TeYP>wwKKM~c&A`&Zus;N3W|w=iFu>Gih+4EIf#LAGcNlb1H)#54-?}?Pyi$2 zR&ErBkL4&7)H^6KK>-D)L;o(tbxzr-MORrHE86S`1|JS?c_v}AHUQBqugs*VFy&z^)sYkoB(fK9E05K z<4bJq<-5zJ33}ylE)S21v%lcVP#$S;&Uae>Y*hI|k@wQmrYJeRJ*!X=H^uVp{(m9j#SVs^mh_(f>yUS_CmC1#Vk$6 zUMa5L0AI27U(B?BO~Q{^H%}MGjF265_vZYHn-io|LxU?OWq4`Mq%VoRFL&*fNOOmgJBt7XvFeseQVy522%Pdv8g}G*wdbr!QM+_*Ng>K~~oR zaDVTS(MDT((X9s8drFSQ*@HN2XsRg$<9T#S;VrmyYjkwK@3i7-N?5Vrl=6uJ{~?3+ zY~9ZoORi`{(ZS}Yo4QR8E(pqh(_L9TRW&<0dK@A%p;x|aP^nvqy9HawmW0w_)Hn$B z){O4J$>n-=W6~>J`qSXg(%_lN$i-@82fAc%+5>^}dic9gzXd^X!T?dD+;Jh6)PO^A z-l1o5kmZz4iF&Mjl2Rqvtbf4}_ej38VG|9uSud#jc;8gD+JbuSvU^3X`K=~b?T-v& z>{DP-PpiJ=0Ww#!-0XqBg!bX^OSDNcV8;s&ttycIl+A>x4ZHbaQRt<=dB_vr_Szpd zfwEBHFD4X1<8eaMJiG0GLM5l9h$S+3pJ_IhIXiuHxM1ZxVd3DY%M$-frk*HNpT5rN zZ>cqYs>NbnI<%d!`$LN^8YpB@PnHmNE2TpbxZY8C&CQ0{A*wfkMpQPR&3dop#kimITUk;ZqZ&I9YyozC!LXCdMtd- zaeZZY?R$-n8vXJkp6fK2q`wh)F_7fiY?ZO#(j^t>Iv;MS1Q)Pf;VAyhjU_L!C3{S9 zmREh`_h&g&X*iOGoF+;mI{Jc(;&A|deTnVLznPXi^6*W|RyYkWL6ps6RSR40IEf4` z)&K;QA2+lfTFBj*Yozho3y)(DP8C-*zNud>Q>=d65eR){;}}86Qo0S}XT7vAfYaat zZ|%rZuS4NueC4!lJ>#C|w0^T}#Q}y(7d9f#%GEzP?a2S~7NaMEf|4R|EP@x#!eV`I zDMFWR%_`Yr+JtFa-QjQ6FL?2C0;$y7WyM~WV2ehXRG5o0Sf-(B?)tN?_iE$&>ENn@O<$ve3-5jO7Zs|bjNJHX>pcOH z2%$oYG=B_CwDH9`*(ng(3_#wRDywO3Ay9n;L z)TgMtSr>|a`4|7AEYEK{?Ka&|;nJ!{DdZr7$ua3#TI!r!^~EK--n{=NYXvueg0zp1IyxMyW^U zDs8y7P9!{8CP$iUw60aj;_LgkM@G(?lGS0Vf`LA~FKMz0d{GHOcHl;R3CIslwma|Y zS&%Slhh{Us3ka>h!g z{q9tD+tG@U$=;N@WpgKn@!iFWc+tsOw%fVO{Gts5N#fMc;TOrbxC&CJ7k(&rmLn7Z ziOOZI%$LK+dH&pu(A<5Vk3=N7=F9QoLbGSMgCt>h4A6Y(_OFsy{2}=GqpeylPjICt5nX3C}eYr?oJ*xZz#LCw}{@)R)I&(W)urNqcUBQwIDHFrjc*zP>J2 zuWc#thhFX_rd{|6S-3uX)2cd`a6I7}uazJe(a&j+s9{~1;(AZ%n|!8FVSZ4jCh3(D zIzdBYQ8GicZOy;IlV4-uD7CL#YoWK|(NVu$)p?F=+ei|^X zSZOSh;SU-y2k0K%UoK%{VZnWLa=M!QP$}c%>nm|{>j@{IQ7Q9kcD+n( zKFm$?(3`6&8@KU1eStb1}YrngsAt;Q_4&u)c%AJM3GPPN7i*TMq375`Z> zp9^SLyM2 zmOWreK8Gn}JZcTcelOs8un{lVwWWXVD@jU6=iTV&=-p8VT4#5+)>K3GmzegUp)e-H zevRy%|BAO@7U>4Jzon58d8SCjW@j+wBVF?C{+(^<^&0?Suopx^f17ms7lGIj|B$e? zUPqXM%1UO-=JP2})n_sNr-%kO_|#kdHaz|_js*>(jF4cK3Mm;`j2*&nfl_raRquiGJO@zN{ z3l~Hg@sYIK=}}ufdXJ@QfHK8&6rITPyAuY>MV`&!H0?3N-|Ou46ofWGNT@aBL%T0! zj}cea)2MYkwmGJm|8{}Anwc3aUaP(EqBIhe(%$z=Wy}WLy412I0>{VeeNHLd_lEpw znl`wbLrIPoIj{ddYd3#Dv7*^-4%VBP;|H`|?i!6+-av6pG^RzkxT(yrip^ip`pzm- zkbVd{*)XwPS~fNd9fB5NG0ltj*f|EIwX$4cN zAKf<5^?|vLn8=0-_0<}qMw&(#;!|UteL{1qJfO1?oj_^u{J7qIY`)#O6 z^x7C)qGIwJ6PS2mDs_tU%u6#*t<=`IHA<1|+eQ(qyHa?1kJ`AR!ZNXERxQ*$n6Dp9 z;l9kc{bLqaMP!;kt9K;4X7lB9^-NE9W0n~7z@i24O8N@9pt$N15LQRJ?}49EiC1X| zCV3o}9i9R_(}U6GNcrGwCDEMva0PQ7x^&AV%3;{)wet#-k_Fc{ppzvW>YiB26>O-B zEfszQ#cA6q<6yyL^fXb;(S1^@+=0KW9WwLhO}3oo8`fBgp3%Zse?N2nlWmHnin~1a z^Mh^hn)^X^K#v$3jfyYtomRWA+2a&WV{$1!Uw`J(;178MdI>M(jzAnnHv&nmq`sSQ zl2`nexlA+6u7I@tI{z(r`>d#te3ew-^U|p&%k@RL?0$La;#@EO#fHyY(w&8#2m1jG z${TRF2iIvYbr_W&%SNCfoS-%oolCZ?*d1cGuLDzc&O(<>a}PFYa_2tCIep`JI!d^h_aw!)o<<{N{B zAVc-du@sNO>Ew5o_0dN&qBQ^>$C*NbyV(e53xhXd4Yk=B?ehPTy#IXG!+rQjYZRbc zW^+ho((Hkx+42kSqn#d$d`&uzt`b(?jHRm6;wxql86giq)xO1@iw!Jj$hcDYy+hA+2`r)v(#R8U4y3lT52SWE zdU{B^nedoi6dMkChIwM>eoGx_f z8cy;--QGdcI3p#j&5QAatHl&z(xPOiOu$5D=Xvm{e8AeJCz|YKcxvc_HU2Rw6!l`; z`>PqSI-YWx+?7EZDc{B&3a;3(Am+DLWebVKGyKdn!k_H$=1#5+lstc)e<0I<7ZYx8 z$ar9_YPe3th9kbpSF%E3#!2h-7Z_jF-!hiWH44%9_L9=_IwEQ$(NC&f>VK5RADBKQ z=VUMC!BjUoOcs88;5KHY^zn~gTAL(9v2M+4o=?Ln0lOh z=%Tpv%-f8f<#v5sa`~^k`l!A7!>a{*vZHs*msfEGRhH4&9;+j+Y!3GBE|82;y;{6T zjL4RR)V?}slYBB^$?#CYqmE*>&N|dx>4cq`;}z;LIRJ`8Cb}K2k1FqsSzPT-*tiDQ zC~An!^Tjb{PFW4(ljM6EnP{g4I@fz5S=dq!6xtrH4XM&5Tzq9s4!H|`)}tEr-@m_6 zD%EmdbPv$gIQhef`el0RTo-k87JBrpR+hVt4XWD5)LMJNl`-KPmufM>u(}KL4I_PQ z*p9@#41arK#HLl?w%Z6Ra-lo{7n-@4!Su=1v|F&D_X6%Di_gLP7KL4w)V#6t4{3Ab zvHh1vZV}DMd7HxisY~UXQU=a#eNgpZ3>yJXzZK>hDJb$nA$1%r2;B>nH#=Q ztZSU|ES&C_yTI(nq|S^K1nf{@`*gKK>1$&z_|sI=FWDnhRRlFYWz(Jp8o4%)Ip;>y zSj@{BG4O%BB4gZ^$Kx$U#C+_}>bk3=qr)0JAe1YkH2OGZOe zlr@0$n+f!c)T+LMM*p%H)&f`@PkB5RS(3^%dtUz{P?0F+>J|OczOosXbUy!a>Kz3u z=uI^IqJ@%#FlxTown{UPb<2m^>gd==zm5fXw7G3~0$j1IM4ltN77lqw19H&!eV^LE zamZ*6XF|gAUh?B>Ba)==>ogiX3*|e+xy0=Ld3hf`ef})ofQ$|z4hanme(e>w+`jtVt2AAEd6xCZ_TJ3Z^vbs_mHEuno&W9eJ4K+Z{>>2bXt7Q z^Oo&92OSU*38ndF-c#capQMPx>*59{(9)O@klu|hUVD1SEf~R3l8vY7n{DfFyXUV% zsDuwTPZ>0nk^9?O{_E+wONQx>-+KH%>U>?!>)9gyr$mYW?Opt*g(%&B!fXFDsekkT zsgth$pQ$kdE-p7hwV|PA03q`!!k(IJ@hfVuR&v+3pgVZvRV9!1ylZ$QK6oRGjosX| z&E4Vz<^_AaF|@ab6`zUWY8B_brQ>p?3$vUGv^gb0ue%ZQ7Bn* z01Vb0T94?;$XGT2%q>6_{z-I+H)%TcJ~W20>kYi28L;mX%jdIM*SMCoO=p=&`zdlt zbI4iY#dobG_gLK8l&(2_%ImAScl$FoSR!Ow1gmc==tJ(CKj~^W#&w_%C2q^BShLjf zKZdMTeT0x6Xbv{~vTJVrE6nx8^`KJ~@dhu`(FCY!`CO^E+Kj#sauPQ5Qz{&U0jK6k zoKHEl>)W$R4E4+Alxn=>t&L8=dtob^c7-Z(LBTJ6pr)85_Ufz-d@z|tFhZ@cuS&~; z_fWpm>W@K9>g!?;q|}opxZ%Og*9{W$!tj-tHKt`v?ez`ru`)EY5Ae@Kz1LbPXmTLv zQRRN1E;@G^XPI&H1?2u_6&sQ#l160s=NV}vs{IUS}I%o{Fr4kNKe0cK-+v^^3VKWj1?TCB|}Q|P<6 z0nnzcU%2wjZFzQe9+E)x3k2r0?wyL5@PCVmvnBbOT3T}ic%O7C1YG=bf;-r?(He0BvXw##V_UihL)W=ITrbC zxOsV}narn{P;aU?{8xrYs5%jDTk1paSQ1e)Z$@V}EOSuQgDh(U0BP(g&Ph!58!Ng^ zH!=iGk{`ihY=d{-rCZg(vcvrfv>V7%iD!i8$c|TuUSC418(fse_Y5P&mD`NV@^rW|Tj@yeTql+vCJpV%SJpKezCa?s|5iNAaWMA? z+xp!-m7QC$^AmZ`v|A6h_Wj`O%-B5S+!*fctKjwv_+c$=_f63m@E$@MgZ(JsVEW{T zU5jqH63oxq%}EtTbUT%{FBM4kUwP8q@nZ=V>9~K7nN3Lp9%VYd{%ZSXp2CY{xTUEx zZ+#EvA(=B3fxm>J-VM_vYeNT>=Uzs@owLB1MLYZ^#)dvLOF#ZCgQ&_anI#S7@PO~Y z>Fvn;C1UkBq7zuspQDA|W530dBiW*a`r2ias8jKvEmHZwKPXt@&YB?MoJjxb2Uy{> zSMze&QsUkX5ve8zbGCxwKJ`G5U^-N> z^PCb=Wf>>7KJln;Z-$eijoXd60u37;S^Z3~Xld&?^ZcT_)~-DUldn`cC!S8W zd(b+DuVpXvP1?rTsz1fa+EZz-s8X}T<%o48LebkECsDPUfHtr-*+N4;;P#1W*?02j zB!QuG0WpR|r18dqoi-5`7ZgEsF9SzMdHlEdw8ea^xkzu_!BSEiRyR#tw~~Z}Ebxi^ zT}Qy(qv^=>yDAF!GTW~gg=eZV-*Q{8!h`P%tgLhalU(ychPCt2=3p%)`h3v=b$3SG za>16{50yNGD{EqFP6ggE-;v+B@>iys59evJ{^E84l+N!9-Q@!$Ah%Zs5cmY+hO}w^ zTdxO2_M;P|rE>bl<(ob}aH2o=vFR~P=Avg9R{5Hf#h9?1?WH;73W&qN>CJtMwzA@q zO1hWaK_nu_$iPv(s@cH*HrTTk)Wn~`oZ5P}k&ZSMv)@(`|=p+cF$*rAeZfQH;v6=_a5&s%mr%TEce>#nle;;LIm19fu6)) zGL668cPXjf@`^*4M+HT?~8=9nlW-EgeDOQg2B3fc_q-Nkt5=^FYIwMPfP#J0SVw53+JgrL^6 zT-gQNIn|*vG_<2$_VH~c-9o`+#WOSg<+i<4nxY4t6i z88m0#D4Y==OjUQJ6i+CoYjbJAZ*EF78!xtiOx#5J%3Sm@$2XpQoK-jC7 zR;Jy{pqJYUU5MRcsL2q?9$Am1JCuW$9xDm1Cb};R(B^vR3385m^lPm>w|!d0?KRI- zXQ0^zC4X#BU@1`UN^~g|=Up7XcPsQ;_8>pyD;);6<`j^vdk8nf3o8-#WK`rU@p{wO z5R&FrOM9Q!n_W|;wd@IHe{mk3vm`Cj-Q4PNw(HkvV7cfNqzy$`yINW2MB12++hm%D z9BaWzYqUM^DdtC2fXI-jM)$W0X0A?sXg5xi@h#$bT29^e7nwtA;T$re$l%i)6cb)w zVOa7x(i;vzIF?Si790S?z7+tqBiu^U*1??~H90WyITfnm9Dy{msl4>!SB<3C*wXz= zvwk`DQipS@aU4=}&{sUYd5pv3>7lqH^|!`%$EABAwj=M>F_z%ZoFm&hZpI3}BkbIs zPTb8URGAUE7sNLFuw?V0i~Tz-{1wK;o6CO3?s{5aC~$54y#r90jON#1RUlUX_foi| zOb%*0dYg z7V4sIXb>=(5_{SFQ>0R!;^{fgD~7q|%!os%q+Omac`N8h2IRgROb!y+3~f&EBk?|9$Oo^)OJB>^yr z(DG1@XldX~+_do)DRII_o%gQtd!0lJ;&%0kemAMEH4d*m?dV0=!+r!uAkop$)j6^1 zcDBi98REcBTV`3mTg8N{GL*G0n%DTzS(npMd(LYZZKNonX6mG0s z2s=O`zNfomyEE7D4!?3!RT}~2MCUga;Qb8~TKG)IUGx(f-^1P!4VTh0%I;j;ZkGY+ zs4sxgb=C+-1&--L8%?cfaa*)~A{1H7pcDk;40n3Dh^Ts>%e z?Ml@=KpW?1S5+z{NyA}~JT?LI7C)mur&LP0+OVA;CY?c~;>g#f)3k>9wA3qjwHZ$) z=v)7gs|Cg0e-0+$TqsteF5J`?@lAIKt2pJsK)w>&$T!$1>CjGF$Mw0OHyy`kaxmAf z$(PWDed7@y2hgR+*EO1=f_hm=l6VW_%;y}I=+p0o?i(M`4)YFxxjJY$!oQnEv0Ra_J&u!Q(>RL517?(ELn%}NRWz6 zcZ)f`$d)wA&OHJzaXXgdgspC2avnGFHRszNvpyz<(0TQCrkiOhC%K@#l<{9no)om? zLSgx(?x8WGN_RfM9Dt_KR$~(^bf{Sz5w< zLwvA18o=P8pSDQ7A(AU42{ZOmXWC6;^@^_3l>Kp4=JW{w_ysvhZEY#-OJ4o4A|H)4Y9Ca*s!B3TB&Lsc(86 zu^sEyLfxl@UqUy^MBW)T4QBP+b&ZkjiqZ}qsC+UWJ*BJhV2;U#j}jH1?^(^4huBIh zCu*4N$d^R(*#b5qR9mfk#I+er7bD!R)#&kJAJ_>S^M;|Ga(tYeGX$tnYvGXuGH{-` zG*bKFI->05g$nLzhgab3%Jz(&Pteudwd0G_TxQokz>=UjkAexDJPk zhhGl$Yi}mi`$QbxX*K%mXLc_{$U3$e7!~n-vM~Y70i}%^j$aetU+X!XzyHY{u1|r{ zCn~ks zvvpuDRQ!vt%zALX3prMn^netzazbGHJt+(onfyXF3iEZ}Fh%^S|N*ll0t+?f1r)-(Mt>1^X zY{9u;_2lj!y@5a*v}i`i8MZs?rU&n!EIf4V(0*^sCcChfq}*5uNGc@Crm9{KmR81y zURz%877ed8mQbv*7Oxbx+u=hlFdT#F+v_GgBV{E?ei5#US4*u0Q)x!DqnuR9 zr4P8e-HuQ$nq&F7La>_BZay$Cwxlh$7kToYCDbEVCo1UlHw!q`)vxSqNm^Zf4pnuF zl%P9cW{}TuV75@@O^%4`l&|i1P57{dOLeWdTmsrX%3FX^f6r!mLiI^ojcUYsP_036F6_%N6 zIka~+^{8+`Xkyt?o+6d2~I2EV6`AfRL_B@6*+C{cmf*}m$P5mj-=WD{@ZXM(dWS4w1Aj8TQkFndb*~+Ff(IHSh}?GC451u zJ2io4(vWk(W~L0gc!tv8RW_5>mu- z5PY=UPf`RX>ye4y!zTwYw}=PXObl`(lQ%+h8&NQIvIu~esW?pZYGZyPqO5}dvTG>N>E;Jfb(H*|7TcbcY)xKZ@F4wdNPcvx>%1OV# zIC1nAO$QHcqtyA11ASv`X+=|;bcx9Vn1*;Sz*rPhxpRa5Ej=)t_Scox1+C=NS@Y9& zP3#*)CF}J}4($8n+o0IUVTv(2FYg--*^bR4MU4AEg89o*K8rcKfd+S^^W53?x%Lb@ zyV1THiw~^X$A32Ygoi~>uQB-gDO;(cf>Tmb;y)|dxDej4qO%1~@e2&ZHc2Ub{{+qH ztoaQ@vLU&N;E%y#(6v8pXD$tV%5U!Z<;KZtMQo0Sv-{V7Neb%q?6(fJN8hf(P3)P- zfKAz=v2b#Iyv>C`kPbuQ8g2l6orGd!tbE=QA@ml)0CU;`P&u#33GEJnQB_+ zjjJ2c%DzuQnG-JcBxD;@F~COic+ofvOQQvgv1zaVDk~&7Xr7Wnm?cZ zB5bAM7cZT6XKX^Wu9Ad$Um*;VV8Xi$!cmo*EKrUB_P)wXPCU9wzi9_8JGP7sy-X51qZN3T@G|4}EqOmKd zl~R;63D?Tuch(%gvXx5nb(z;@SDZXzRd(cw^?1;a*NVNC`oBcfpnXG0sIM*t@(0z4 z#J9UsoSQt+@ZfD!=g`VD1-AZ0ygPW77w3R$|ExId)E68dTp#6mcAe5Lu>mbQvs%92 z3B*-ml|txV_M9AK3edQ_kRpY1d6`M=-+3#iIweVNG%z`dnnv;Mh!r{<9!XCUB73yF zcMWXqzvQlf_PvVH-)1%7uD)p<29g|7Y!&i_-jaA15sW)sZ1DO;Tty8B+LJQy!ge4F z&!We=GloVy9%U_r95Q5NV)CEu4WBKjM!F}nA~~*3uObLHKjP8q^&HPgaA!)o%pN7f`S~fu+mdm$&1D9VzSnxsi=h^wXSG$J zvY%aFdl6?A{^e&LsLN7Y^1Z=Fn3P?3ee&-I3)G{GtMpn22R~C&gw?|F4e_gTq!-53 z!O%zlC+G8K^2hW{?N3l!ekMGJVkTms=Ny<(#2tXteX76Fc6Th{+FtZ=0dAS2|1qqo z>3=PZjsXq$X*?q!7Yc{G$-*@`eF*y${Jq$q;qF#pZjFuER?tyx@$v=HklN4#4LqfB z0+6Uyl{OiyUd+L*ZpC$4+ZQl|!o*a`2%z97yM|#VEbvPTdGZTO6n0pB{l41)stFBO zfz_(4KcK_7P;_^0;!j1|QW0z=e>+T#|EE;%I0#(s&RsrPAUaZSeH&w@{io!u<7Gd& zRLXBsQ+4TvG>1{%ukRiY-t=srMVohG9AA(~oVz4AgDS7~hCJpqTV5^boDjb&LcZTh z`DuZJQ(xObRNXbaC!Bpz%4EL5=HW6HjEmOXp4<^0GRJ_yVLc-?`H?^Le>*-<se4CE6x)2{@DO)37+mp?_x__*FaGCkDIM01pxFt#2J zwA=;IrdR!fg!TqUU*GF6K{&TN&9sM0oZy3#JalF&+(}o(V}w!ij3USw7dV==ZYUiq@ut&uRh-|w{j6Xqm- z!`pOS>bDI|!-E!#P2)VTi4Nc4wO-LCg=a_VN&|ar4W zEG-3kOo_}k*Lus@KpvI80P%bHf2UG8m>H(3!I%<>i&6W&?UeYh1;^7t0Ezw|ZlIcf zQ*ob(R;{Y{>l3t0Y}$I<`YHEl=GZYe&`-HB?GI9RXLebvXIl%@1H1y_vr&;UKHJx23g!CLP+8g6% znN$~!>hl;erBeAgG^?t-y#NThhT)XeQUE@bCT|2N9&N*Y#7AXpp27?3%Y-< zJUk6TmsH~IGR`2nbdMChX+hCdcQzLO83~8ifS$JdF2d1eva2;n3YB$Ige@zoRS96JO8Cg*wmCjjVDdBoYFUHoq31lLi=M z*2C3K6iZAZdI<5!0Iby$jz>*0_J!1!)*Z1AidV)P2p-?6OHuv{6$i>F zKRZ~s4eO7gjFTYaiOB9lBYJ(0UTl45*!;`Mi2abaF#sdv#jc47hhi@l4nmsru%anx3`R zi?N8$8%*Z8PkwXcAlJ{9>9K9_aI>wyh;xjEiDf}CS&COp<)qIFZD8XzgxuYH%%$HF zZr~~Pn$;9;&Blr_b1}KM9mUi3Xaq}X|8lj)MeOc7FifB>fdCMJGk{NBaWsFy+93ia zZq(vri*Sx;^;MUxwPP}+XzFfq;@9)I4q{)t^1FuT%^xqL^0?R^bTdcRreA0;(Z8K3 z+kr7mQX(_lcG4nZiaO>m-HJyStS%6!GbPsn6%xOH4^2cw1ceIV_}KOBExqY|MiB|I zT=LUzuhLR_wxnX20sQAH8BZ`v3=9mLn8JajKq3#7KLyGdW~Uk~s`t3Z?tE8GR#)o^ z(p}JqhiqA>p=gQaqtc&znKR&Xac07o3mYE*<8~YcbAMPee|3m#BHRu{JL#X#tW!1< zKIPJ?Q#1#^KkG<0!PGk&LOS_g14JPYyL8uo~H3 zot=DeC=G7kb)-^Vzke?UTuFcU-mNpvjjxErdz%u6YxPel&4QYWqWg$Q;`NZZm?h2Z z7!;B_nPmD3moZ8UCD}@W_e8eEQAtFYL}+8+=}Za9I*%3pf01b?PslW50&0loV>mB& zSQUW1pY5w;T0_?o^PeZ6jsB=p)2x6TcnXb6ES_6iRc+~^{3X@}TI@2oe%9491B`Lnd8_64gol_FgXUqA=Ifo8nembs4 z_L9Ga`yd(~an6l9!xqCbJ6~gVGU{RO*I#moehUd0fod|>g7JfJV#V3j7>eitMDjmU zmfE70y0IrIhbeFFobwTBp&W>_(A{%cF zU#<~RlkejEj>UVZx63ZC>hdnQs?(h&l`Dq#(k@#p2sc_8DuzHLI9!~9l@rC)n^g;v znxx_W>L`3|CRmUuDw?DG7(Rz~PK3Bc!Fa;U@=)f&gF0n%Zw_dc6Mr5l zUu~ssyPe3qO)mSt1g3PDRj8IaPI)hwek9_*b@Axoa}{9KdY{W>M>reRTe5LndX0gk zF9$hRRW^ZxM|ay*u@P>PoTiGUUicTTXa1)|2o^2VY>m14n7ycVuSyp_D^WL(K77Xx z5M*)jbNt#zWeg-Br-vm~qmXgYwT_;Vc=Re?fXq{!5TBt}Oq_gSCpb5HdsU=TUKDK8 zJ-*O=9Wg5=F513w;2Y?Eo^9Gh49A%toE6V=9w%|qv|SbkB(AW zc49KrG2DK#qmS*c-~9BOq)l^xjvjhh+GL|lQ+Iup`Y@>#gjX7bP}qpZw{^F_zU?bt zZYd&&xVpP5ZeXx(So-&+Gh$-7u_vYzmEcp@T_lLU%ob5ge3>-r=~VgnBM(VKIE>il zzTtdIUAzJ2ADI9VKUujX)+Iv2j!U%LREQ3|6CeJRV0K!Rm;b{|F@()~Y)gE?v4eFv zDtg7F+6`K+sIs170C*h?Wlm1Av!d^(Y?`tLo-VIdT<*r$!T#>ghIZsl%k+=r?}Eu+ zVB?;l@BXoG9Rc&_*=YYvsQ%%}riDvj@Rc1?d@@;5GyVY9*2{kQ*i4T5LEtTDH>9ne zapwn~Dh$__h7!_fg3{vBw!)zO-$=A4zn>5`Z<^}!ljWn)`Xa^l>rB~-VR5By2i(U$ zQDNU{Y@c=~Zh5_<3_OXeR8HF1->F%vyjFvsKWl1kMrtD9ae5ut zVSQow&wN3q-oih$e5It9lek|@8gwu9;3kK89#TUe5Q4uultayR&1? zj0c6z4^W8gaXgHF5y~RfIDqt7)Q)G0pslX01%Lb24uM=3Ogy8w9)}lGdPEc#9*H~` zxLs?+UO_~?-u>_)F7)wImz6D2v(8pPzg$qV&Q~lq(aclRD45h`QKy ze`24-J|N0q#xAUznndsr@=Zvm59^IL4Dp;g!!D_Mb#$Ob3~mkb^<@eA(5Tmda^oiC zeA=u<&ewdhFbJ=*l2LGwIWy3dH_g_z(P~dLwFsF5@Z8F0*L$J2*InCb?hn-nALs;M z{oLM2mW7r0wb4OiN7wUX6_j1vdo-Zvz-J(7_TI7$Y)!28X0tp34Drpp( z%H}tox4fnFMcvc2k#hmJM>A3$P8yyid-_L1cPMw;b6hSchr{&nuGWyq#MR7qLt(Y) zY3px@V7KYq*y1hNVe9LY`A7Qt4VRc3XWBp{t_*D`PhHrVdFGsDv@C51BokJ?A2>gX z)^}m#&}g?MD$#df%;GTD*w$jo*B8%5VN+S?GWqw`g+x(%0HHW7G~ZH*7vMZq-O8>zrhwdnI*s~yzV_Y9dEY_ zpoy?Dv5dCdDp{#r5-QKrG2QuSK@{1SXW0VWvddIm)tx*Vj+i>JO9;!I=s9j4|8VA; z$>tmFf?ssyh9XT9p(E>^5Z7mjB35MV)nTk-IoF-`C=csZTI-$kA>GPM8~u|ke%!#% zuhg38pnJiA)-6g(O1JBcIJdJ=5s3sQe~X2N{F^^;<`{`oGMGxc*;*Uk3{J@gHwy+b zBGy80knqb?RMBD5lH7oHus~tx3q4;gW`+01y0yy?3Q<6#FxnvV+l8ok?#&PjAyK%|dW=~U98yhAxo+BtlMMa4; zKF!I$fqulqQBS&?JVSH+4QC(StBLYzE{UHGQJW#WMv-gwpFVtY#-TxC_=yfg)q^F0 zF{kKDjU_6jEnRM7kF)BU!&i-q?K#(H?#+88r{~;zjIZOneHytDT2@cvGYP2=w`ka| zv9u_z`;`%b!)Asv%yWtyO)e>Sp8tc;e9U772abs!HDQ{*@FAQ9fjR8|X_p(BzPxuMjo@rS5WsVFS^uJFO9euUM2v&DFP zbb!1h7w&1rj%YG)eQH!#tRWjxa+}O$j|Ouk z+nUrcTI!=TH&*UaRebf@;$IZKKs%}5zau=~vKIV}1rRhfRnf$R#zzhe9@yQY0Iu8k zLyyiSWefL4W=qU86) zIuX6dl)ZNnLBE-eenXj|9 zK4%1i0Xei1v-lmD=*Dp(0WiPDbJ6(HN;T(1GG%E7^dJ?6p#V-B`iK(y>+9>3n%@cr zbPswG3J}T+cVO0vOng`|OMZT_DcQSfh=#en(>rxFQ~aeiN<+e)R2%#AZWt zgvNv?Sf7Tb8A9Xbve!R{fgqRgv*z2gW{%|=O~d&|hi!kev*&)_g+=lfeVf=!G4-D~ zY43vow8;ybtZdAD8rY6sd+ASqPc&Z>9fDCyo>u>->nw3uuS742ao+^cIHcn>da!g= zCH&vO8Dip!+d(j)*FQY|^i4G5f93?nKFVKx3+g3gH~&abpDLgu?gBjKLb)YUipqoaU`=# z4`uzFIiI47^OX=fC5Go|U0T{SUudvbiLJhWzM=Hr0uuZYPd$n&Wz%q7)||riYHTd3 z_p;uqx?IsH!ps5>G?d3j>DQv#u1chgISbT(11cfK3$tm1#g@_10?$^P9y{@*@RI)S z?Wz9wHm?GnGlhIK@pa57m@qhqv_ZAfsN4*~L@u3LboA#5_>D@Y5$2_5Y3g080PdN1 z#Y~wA37V%||JaA+Gn>VkMTwoXPik4QLLpPfBR+UFGjMAW1V0V?)a&dW5KPT{GsAh} z)m;=$MwUWU)JCG0BABiW>icHe7JlvL>$h!DUtdS*xKHK{^n71K;@tW{%Hxgqjo@RM z2aDK3qwO#nA`Zw{PF|@E{*>)#B7mW5H>A#0pY;;kh^gpQDmIAp-CPZ0=nd!3%+U}3 zcdhxn0$(3OJ~mp_;Yw{q5X%oDv~aO*{W^}r@7@yJGdd4jrcNGWLB8F{>%p0Bbx^JR z3GK-2Edg3`V^JRl?V@4gwb1-wuQj+Px@wn-wk(rU0Ja+R;NuqoAw+3Rk-InT%BNFD zcVlYFEdg=gRyGQv(N=q{7$cf0zqMKfDAX=+<_Za7Xjxk`0#odW3xk>BVfR#eKv!M}EOwtJ}SJ*{y<5C>B^=O-dN z69c?E4E2;P*1CqNE_Xm7qSLWaQSEWs9(^K2?w#K$<$p~TClyHl6DlB0f11ufIc0vZ z*R+sBK-|GZc|Ogz$)lNyig%>0+mj_<=ZP_jO9`uqv1BDQq^t~`wk;;g(@DohEY}v` zon0=z@HuXt42TDwUL^41q%~1QNDE$2^!4@e9Q}N$ps2{`eq*PY_K$BR+Ai-kyMc2i zYA^63JY$Dpl0!_I&4DL&&qpSH?3ExbzJ!&TXO(+K+pB60vGeMAVi~o5bI+^9V9O#y zLt*Iyo_ucJ*}3{4fE8WCFXE@5<5TXFrz1-&`hTg0IGxDpLj0bbdXBvxZs0@xii1YE zmU*@I+%EEtaGK>aI|_eihz8$?2&BK*4a46)#y&E(e};zL7qx$D>~qt;OM8dFKW{qqJS}H9Los;jz z^7?eH|w zK4@Vf3Vf^Eal$%(Zv6J`&*>1hlTzPX>udjx_=@7Fh-t;~THXYqs>FoF!2)=x#;2q`SMjyBoxzyN4Q57+{EV`@HY-f8(4F=X^R}nE5fk zJNDjduXU|!#Xc#2cT%^?=cdV&^VKrJ7S;G!;AmfbTDPj;gjvdy=oFNP>j``{Vu51; zZ!EJf9C0}qdy~pR;@2?Vi{=MjPo@mgSNkZD+`EJo9k-SO57);3@ur_xO(!!zYaLYO zwS#Y<>*q~-!rz^<)1M8;QE?_m^UTh$dv-Cumt-lP$Is?D<|p1R;3+Q0P+ss##Gvtx z&34oNZn=|7`P3;YL2+~MMb}%Ar{N@=j1^aZBAJUldF?E0ucBStO(gvUyl>YpZWimk z*@*jV=o1*U2Y}jW*!iATVrJ%=1^jOYVSxe=R@9e4J!Muq)dxblqfd%K)%K|~-TaHV zAk@Y?1-71&5)2nQN_abiAt&&Zkk*KQ>3>Nxtq!nh9fe-W0M1(NVtaK7lp5Yd6}EC42!rYX0jfRIdO~{(rDA4I#a~&jt4;RfF<> zSQ2W~$KS2Bj=H;vIO$`kh_(cqvyD6_&=GQX=eC-w=-)bXy87|2dx|2cW{r@?#I2-L zn9iLakX#U5^v&@-v?taMUK-Tt8B+fG_W#f5yncg_81;UTz+pmI%IzsTF0Y@#y?IQF zD$oQ-<_4fY5S%FiwFv zXoszaO+vO3v~BjcqyNp_XUo6sV(iY!3W}1Ip1n9ySEWMV8}v7hIU{78;QjI%jKPug zctf0_kG+}2^2~jcmV&YCM81HzH=;5-F|LjZg>{AMNx__mp|C(AhVvPe^YCWLlxC20 zF3hpbZ)0-7O6=W;3r?ahe?&hTtW>y~y ze@hqo27Z0}GoAI8N8|SF^RYhZK+e-zGYn34s_Fv6b-U#G_$9Zq+L81Y_Sla}d_PBF z(rTy4^=6abgPj=uFTAo=($ts~WH((CGq-&?vec0r4fH4mI@C`!iF(k`0S3yc+XF>9 zqgVZXJBaFl*%Bus`Am5f=esDJkQ7z_cw&kwWCg@D`@;i~gE6{T zD9XfNi@x~3jD$ut$g>e<a(6j)R&Fz4X4vM7Y02cw3!gtSEv|5 zJq>c5yO1vjJeMvp0^PnU!(O-DWV0kTiU${ex8HJey|sQr)Ei?%?YuIP$Xh>aVpWQ0n5d^O9c+rOg!0(t3lx^-?`1rOi6lMKTjO1pn`@ZR}$53WLZFumoWPd4Rj8bcS3^p6%s%1;w zRz@%-#6H>>Q2nI$%jV~a^%4pQ>$sn!>~mi)GgNKN{Yms^-c4U~qbRzjE}xlQLQuJF z^?vN>@$pl}T>rn>tTgGw>WCgKMgb6$%&y?L+u^Nh5=A2h+tf21DdHSoxMxzOcF z`z;%|33^rHN*)enJMN^9@*Y(4tTlYs~l0(Cf0+QRjvZfB$X$J3)DtE;PJNzh)Sn3Ax+FR*yV z5%^@PNZ30!fv27YM1o}SL{Zt95iqVHqW^FS2W*tmpKW)hINWJllm%5AhnF2zlA4sw{voEwA9?tsl1jh z34R^FeCJDNVYLlHVb~0ytK1F{%Z>ylY;pVqHt3A= %tN8cz;z5R%bwEkkr$~ak; zDWzHGa--Pd+vsx)q^6bivuX7_4%0;rxvm*IM+Cht5cCYy9vJN}VH5?Jh)Y%Q)Z%DzAu5g zty`$qKKNtKD;S>)aQ&^qxBb?wn~0_h)2ctHJhPSuqkfhvi~ws=q@|eN&&|Uw!MC%H z8u%H36=Q+gWmYr>^DPPh#T$dn7I5-pV2>jbspFQZX{EfptI9R`dD{Jv(FF5K6OW^K zj3`mi-;jx_Vs|ttWtvIr^ZjDcix<@>%A+Nf0-!Php>p4FGFk05Mzg2$4FzXF9|S3c z5+PZWS?X2a)55VN<+^(c_1Rra_v^yW4RAS!+Dv2H<>4Wh*&Sx`d066g4%c##Jy~j} zTRglXW$3-xV>kpr=4%q>ER|~>biNwP3fjaBX8Wm~yMd^38`DyP#=E?u#fugVSgBo$ zm^aYzSgy-yspY%h64uBKTVOkeOS1CyFo?}gMx#1TztKeyrv1ez1>RbNYDf((v~+Dh+WL8cGyYLp>wIL5s*cnj`+oI!L30gIZ&lYzOnz!1KbFQ5FF z7}UJcrp$FwvUWN(Kz7+!o_;u#@OZk(#JD|;Gr1nao3Yc&&Ypt(H}h%YYrwv2?Lw7V z4X0%LUWhOd=~p-9%)V67$!FAUsfv1qjU%~d4#h|pm|HkT@mop!YzoK_HhZlDN^K%Qq~ zMw+<0X5K>Kx%J57J#(zB{)nNvV2?6bp5`3>e(bsoY7vrZX-GP!Hz2Y`-nYQH)}6d7 zt@F6#t8DmeLzN-(umyXUk1bv>U#D*jVrtiKM>Esyf+_U3EMq4b5@Ef_nWo8@B3mPI z0hg+7R0*?vj!pd{O!YK+C{nsA!4QihJiR3x!8tJdkEM=A%zp2MlM>r8m^rEld+=up z_37(d9``ys?&NxqfW_X7myYRpFtTRyWr(y19aB;BT@gO&2_~;1>_Z&a{5kE!BSU5` zoW#eyqEz$ods|QTRw~j4OQXs+atQRl{F+xm3;bw8?FUiV)h0tZ{UDIB5=GuD(F;Z8`oFaBC*OFSw1qd5;z zUoS;blM8}2URP4H$l-!>c)Zu+rEa(^Z1d9NtRP~i!ubnggM9g6_rCQtQp#vV;%n!P z0&i{YxeJipYb2PAjW@qaYl3WPLbb!L#kSiaES~RL>!H0q#h~uezOnS=#qk~KM}7qS zowdrmB8U(Q>!SG=yjoLXmdg7kCMi88y~?PLSpD3bmV}>-S2I^aX@3#!aeB5 zmS;LaEsp2ul^@x!wW-l~zDiTvBhhW8Nc_F?M6r{aTuMy6GXHMz07u>l8#XjHd-s<-OT|2r#PdJtoH-)(dXa&9ghJD+vAF9lwC! z4VpNFOLBOK`f@LszO1$y8mQersN<~x4-1W$w%O+4sHr!C;EB6hZ@=T`4e~#^iv!I@ zde4+K#VTg39CBtH(Y?W;)S3W_V}F&w}2P7JnK2Re9auMKGLixQUPx zZBA;H-(X+Sdw8?H(^-{88_em8B|)wzWFf}Bq3il@^gSiz%g;|N2@Fig#`g=$H)}7= z92SSdZzrqrBenwxC<AQ=Q&~{K$>U{rwdwxqdbewh(n1&)s+^ zXF(07ov|d+cOd(`dInOY0o8y#h%q4BD6eh4Nz(g0#2+k`NjkbU7v5iqiSaMKD>&Fm zbKq#97J9Zd=z7JK*GvCtsRY^cF0Y97p&c+&Jub!L9p;+hmNGt(-Fc6s?5puLeu#G*15 z$xFB$R=(G`(yV$tRxS_gK5vyDE}hVqdf}Qi2{;Y!DoX+Wq;p+D35Y}Lfhr9}eg~n! z1*(ODiuweo$;a3lhzKk7mRJPnb}4{6$(GL)xc2IB0Z{;pP9Fwzi(zrt9%|=nncaav zTo*h3<`AzW&delZ3}pC<_v@-jEqDpJV(;?UTPM>~B3p-b8I^wNq6^MXS3IVgQpYZ62^Kj zGVUFZ1zG{}in2El{qX3`->MV%bPAsRk5oN?<_hRQ z*Ad=pzZkBrmzy1V9f$t9AMmFp=pWF(qNe8KF|!kZyFD$~C@IOnYHq}>M1fNay?OTN#Ed;mD0(y3|*!t(aEj-&-LQQOStntlV;v&C3=v;TneF^{jovtb}_&r^& zutc#Fd;~?eg{Di@E4^!g;Eb-HYI`WAo=4!^sNcKF26tGK_^JY#GMb~Fd(*^RUXHe1jYluTmTB>qSyO*gpqpHl5!|Rxrn=cL z+Lb`s2b3r8BOYgQ9e(w5I?PzyOBHL6(YfCFhdWAC-9Xjd;fGifI&Mgf_t(r%DFg?8 zn+X_S3`8uuKn3?MdY7*Izh^MSeOyAsZ|~8qJT#WFc7bv;jkD;@JbDo|QM zPB&vGFD4!h*7p-Hz|wMAg`Bf(-veq*Pg6U+`W9`rn$ISzZiK(4?v*qqJ(#>QyF33N zeiMN|Io>Cd67{aHpqYWxEcIoPtld_p+r2B(#g+Oylcxf*lEu3r$@i$H{NrHXTTboTfsgyQhg^_gG*TCIx`#6~)=b~b_zIDm z?uA6VVNH=?2j`>uzkE;KOvZ3$0e&QSqqp;uU7^CYw}1Sj{m(%3y5-dJ4{FSiX^w{< zxBiGjchuCt?;fK2vXJ^XVBh>a=^uF2PWO}`0oTb?o>qKg%%bc>Dv0tuYM0}0nx#j(cv6||H5rhf*1T|WP zLkq9X9@VNI9IG-r>SKIEOh49=t*9d2rg?k)qn5vDsXa4X5q5a!mrkV^GBG7f!t zlbSK_{NlRA1>7B<8=qKiEwd2?$=-Bob5Cq(k??AW)i!U9Exm8v6FyFh7FqBWC}cBX zOM^7BOn4UcUo6*_#kQoC$8p^=02A;X16kdvjm(+BQLH zk$&_$cX|YmMoA9@Unl=OfzfNLi;PJ160Hh8vxRPi^O(|Wf>i8@Eqasff#QA zFbDO{S!`1vXMF~kbo#zAu7i4$%gUI8n7BI3(U6MUxRVO9aEjB2&e$MZ!Nd-X)ZS6~ z^#=*{D(>57w~brNSUSzdZ>?}B?mObQ_^vc!v`KxxDJ_qNiaWb z1GQ341CJE!K4k0_- z@v%IHC*>+LZRS3hj(;=K^K53SWM9l#FBE(uiej+oz~!ZY zYI_@;KZo9Rdo8O2xlibAulMS(B%(9R5T6($OQpGNjWWQ!L$INV46JU|A)m+3+h1LB zw^`(qle8(0&>byM9knBK!E$fCL$`3sSX!7^Y{{@~?3k=XDzt-MdDbSgeGERVD&~W$ zu)}m%(`YUjH)mUIjLxGMZp8p49IdwR8@yD2x{@wYIo?+Yk!)!JbSg))!YZIkF?6}2 z>O=13`W{^Rd}dEVB{#t*`w#E09+vrNS5n_tT+At5biOPH(NMxEc0RrwfBlXh)mHJ< z&Kr`nh;N^Qo*@}hs`XAbM3AY^S(sc7Zydlo*NefmsTGFAX-kn9i?y8od2eVOGq%J9 zZf?!X8e_R($-SqNxdL+cd%9C)N(P)>H=@1pSR5xHJT)Y3zl=_cPq8Xl^^m) zp4xgA{sfuvzGaAQs|#tn+sSM$sx&Sfgv&KWs1N84G(LKzk@$Gg4O6star3iBRRUsA zcND?7x_9(u$c8Xx>x-d1Dmbk!m+a?p1KEN=1E|e7+zdXjwU{`_=4{7<8u|@t!wY<2 zVk|MAYlvv104_1FXj}ogn!(*B2dBID>5Hr$9cQl7oPT@Oxh}oo7O=U4>^A-N69RPg z;VkyT&0dikHOybOBdQTvfi`^h(b?_=6XOS4LNjq4P$psKAo_`|4QyVZwFndVH>6(- z&&x$IvuRPl$AKI*%xcR6U4TU(%2;0$ybZt7o9{5L>aNuXg&gu1oE^TewV}J%g*N%| z+pe}j*Ic)AJTExLLGx9Hg(H-@LIkh&lV(>7N!A)$aRWn#jure;egZCn+2qw?v0uB_cyM&vQQ$;)CfD&@ zgytbKQT}jn`jzHkT)8@y+s)jWm`P%=;+Pi8oV~#bpt6#D5BwEF507@)INBpXu@0dS!RCZ?$aPk0aOz zJXJ<2WOcR^*BQiJ`m@OEV2`A+KFX&%Wc4xn~#+va!vz-g8^&FQH}KL)Jsi z+?O)v+%gK?dNZ<{SE&ba*BnXLSY*l4s_)&)ZI>RZtPj@1U63kxdul?VgVU>XN=NPi zS1$sI(AQM01v}g#-#<83H4mTFOSCPC+`9*RM?k!$ZKYcqDN+srne-0Up_p#)3~sIW zZUgZe2~R~r>L0ka9<#(f`!Y&*UFro~#}GO;8lL1{r>wS}4Un|9`K{btPS3(+FAk;# zHa<9&dDOe7CS1*3Z?-WGg$;eBzshI^l1>N0iNMdUnH&Iwyg$jIAn~b=49mz8~xy`G$zARs1reHOg z94%w@s>Jr^7e1I}u)Yk5RFrM$FtIz4>%GSq7y-BaL>})Y3$J{}hF{teDY1o_!-mP_%4q;9 z^{BVsDJgi4AAPTQ)Xsz-cO1fQaoO>nG95@q>tU7Tzm_R@ymYcDEg6uL>z(^in4fX} znxf)?n_V2Gm>j2~H7{EhA16a+^!vby+o0X#!HjIHi;LNH+}dgPw!WgK@s9(T;+k_U zh%Cr%!85{Vf^-~e>pRLG@9g#qt$|)sRMQC(ox0!7UFOPD@l~Crb-Tng%43h^N-HDP z^Ldo&?B-|bUNEyXD0A4?2)a!+n8|T$s1{{)ZU6IfOuIEVadu+-n#fU874+i>(R`mP zH?Hy~@KTjQG-pEQ7K1)(t|`_1vh>i+LmN?F%b}OPJ7O}z6>?$irfuQM*4W;eQkpB^ z<+njGv;b@Gk2)?gNsSK|T+pQ0CFc$ZdT@9Jvni$8lY2X!TkQGA2Wm-aSB2IK2H8`F z7}%;=x)j{+`!h1Awhh43>S11ePiHk0-~%=?n9Ewgq#^=wIdj(@rE+!#O5KpB(~N+B zn9y+1zRITLT5HyuEZQQty5S}@dit$C@LlcNZfVzqaGvMsbJ9iLcBr!iI>GyWkj#_i zj_xBb8&aw3R5E4o7FzAip{u)Y6uKxg^ZJGkN|e(yq(5|fws$D zsslBjvD_+Qc#aKhXQw=%(UlLI>+v$RU|6t|^S_)^#Nf)DI-mAE??QKkMItcHAW6Y- zk=Dv`g#n&cr55PDifYyeO0xVa712D43Mb zp*>Wf(ns0}sV9g6Lxs%USL(O3+Xc_57DyodcooCin8G|b{n72&yhduIN;xAfN=+44 zlQJ+PKiSmS@xgZxjjTnl2(?$-c5FVK^Qz{HO(pzSwZTJQW&W9~L2CEm!-u_vS{la0 zu`1oW34goH~7rQm4l6fi~4j9Fq&2zBNvl<@cfBwTek_l!tq{^ zF3&H4+1-Azvw(hOBr}8^dU_0w{?u+fg`L#vwA*^AAwsX+quS^GR*omC8sL_h5wO{q#(r5naKkK;+$praNPpfoM zV~70eToO-vPX5`$y%>EO8zbmF16_UtN3bE`^z5vXt}c34U@%TluT&H{f00a$eJejM zKEBd%c|V&h+Mja)3^efzER0g9F@l~gHAqPn4?r$h%zwUCQdX{}M_p8bDhP%|j#S287~f{QH#lBq@igmlbSNO(=D5m1hQW z^WTSTdGimndS9H@ysdn6TaqD5!(dD2;L5llMiog#Dj6??fdugEwu*W2DuSKRTeT+Z z?Bk1lD#b)M3;#j!jEsyl_5K8io|F73ARQ=t?y$cB^y}9zW;A~TW=SCT`~7>lWgCKp zg#|=^VLls9#zfS@USS6%>?CTS8o-<_)FMS=iWXr?GEblhP4v_Q%z_@fXz-(FH2|1_ z%GGww7N_@mm5G4J7%p+_KiCrTy1c#-#4D=WS{5wY-daUeGBN(z9OV{&P4J*2i&gwI{ zBnzJ8cSVl0utlcI-ePO4-V2M=ZBA~*};>av7sQ!Ml? zV6JuT{Wi@sk4mVy&V4k(BpG~_9I56}1u$hkJ~uOx1&>C2{A2vwf1<*^V>Q#c+z&t4 z7Vq6XTfa5SFAwNn*cuLS-!Hg z*snmgTop-UV{THQlw~Mp=BP+auSDS6da1_-kTOA8ehwp|A9$bYUB18=dQfkZ4kK_s zAoG(1I32)roOs!WbIKeyaWuk$82AaT*BsgL5JpiNT5pZIRD*yV@Cgt%pbv&2&t69Q zcsI8|jItUSzOIM$`^WZ${hr@f!g&>S^;+jcHGC$$F(6q_%gd&oBQN*}y_NM6zKXW1 z?J*f<%l~TyopsB0ExKfR0KRWNp#vvDAshvS!RcVQXC0^}7{wGr2dHnc+V#Nhl z3M!}2t5V^W`N&nVw%L}HsZ1>I@1NGh z57>{#V$Ak5r5+xBg@#sBTYKig$31s0b2YHZr<|!YINVaatvLY zlSd-$hq}bZ#UV}y{RG4U7Z2|hMi8J)E9d-2H7S7JQL-QqL;Y7R`c5%fS$4d7JoGIf zSarJ<0;MAjQ6MSGu4}^PU7+rVyzPe+@@PnNsYrwl27yyWGkxy4EbfNAxKA7(u69#B zZ+D^r#Jw-q?CSlj#|w*|jjqxQhmkkRIj# zlQeh44veHp$A+U!OSaSh_S}EUSW^CTHV1Cr2Lca5ux#Gt|>)DEO%NkkhF`v%Nx;i$5r(Y3XsVCWS$w*1PO!)H0nkXq@0~I{q zdkw9ZsIiLPu)o7=T#ERjIUR6-JUuTPDNrY9+^HRNA-F(vuEJe6~k zVdynCXHZPd$D9OVHthTgMj2Jzq}U0r^yxa44tL*Kau4St{#NDYguMfihcKm=@>$!CNmW9ROEq0sHJ zx1K7BE2z{qX{;!1-pSP2`e9S`7!FSzTUksEXCj7pNif`UFCwoByhuba)fR z(gc$Tu)eW-5#{BJYnDoJairg1w`eTyD0ihL;I>bs=V{CGwFigmF?2N9P4r?y#5x5| zEYA<)e9%@Nk|J0eQZ2ls>8~o%;0vRn@J*NRgt2bNT{Jn3SfEL+qTfmw zEolP?!f-jMn#$d~Y^f%|PgM$7zv5ydK=pmwIK3+NYFAlz;sI6)JYRif&WyWAo@X?t zuCRC&Y2gGK-Nfn~@3c(2_7X^AqyhHZr);e5krC(oDy6xgwHut7}GnaHd6r@*vt1uH*{88-B>xtW1nO|ih8QC*; zwWzO$g!FA7ev7P}a!tk~2-eB;K|i%pY;o!eI>S{5-McL$OD}N)xC|(;yLzj)}X&ELAQ|C7aX zbJOPChj#2!@}sMbrg>jHR$ae6cohN9_OwqQW2ZyfW^1pK0ul=3v0Nj832jvVWU>HE zIr0%gSZ3--vM+xe{KV&nbU5Cfl`5WEt(Dv?z}0X4pSb$$a{2Bh%e56+?JMd`%|xST z-J8$bT*hrRS)i|cT;M{tW)(Z~bF%BhaoWu%9jHAv?*Hmjf~-S@`F0HJ?t3(GR9S zvxAgOm%Q{1u`-He*IDc>@4yNf51E{Ltk#7y?FV8o7FWm;8)H`gFyHFnxhq&T%4Ag)}*~-C@Cs-$Gnp!?$N;{j|w7pcmEAt!i?H@$IF`7?Tr+pQumEsf&69DDp|nKOwTV`s37hdGQr9PK}hFLmg=zS3=dCg0w%m2uWkM!fHX_eYdR@eTi90sQC|~QZDEoTR&O4 zr5oTpk~}sO`OyqO&Ng$-p&KB2nHk(pN>4ef?&4WiyjN1BK-Rs8YjlG4>kqL51xCzqZ;YSNyWA=B_Jq1-Zm(3& zvBIW%&z?OeklAi771(LD3i_BAudYz)y`=5BILmTmCewNE6$pQQJ=4o~H5?-Icz`|d zg^1aj`K`t5#A2UBr*FtND*=-mo=R z&++5Wt#rdRR7(y=^Kz2bKcH0T^Hgc*KfVWkA|Z7{Y5J*vg04U;`5rb!h3;wr?|OzV zwKN^4MEj2PtI$_1s`YC>t|v=Uq@xXthZ+_qE6MH;gyWVj^)asELGNzhKJC93R~FXT zYfIx@1TJp8(1~YlAh(=)9HVnWSct+{h=vyS!|xJ*&bg+YzB8OHD*qjht66V~USJWE z89dE^i{hu+%SMQnQz8b~zJO0pWWy9b;1Q9N51eG$#oyi&1`7N1M5IhY6jk9*IiHKM zybS8yc4&6EJDH!?Xbv=|$A23w`D5HvG473*fS^xjXbx_3oz#Z;2sRGr32WwLB1}S6 zRYjE{EZrrqauSkSa}phlcVWdX$$ITY4TVD4*uMlzNL#P@NHv$QozSGqfq(u~z<0m6 z;q&+R53kp})QaMFAKOS_AGwr=-XKk;8S=&V1Rr$eY0vhF&e1f!FZrzO=*a!8NrOH{ zhWaHTPrlO2$6~`@48*c6a@3@zY^h&Vmn?5%rG6`gd=eO4Pks|qjoob!EX~v&XK*l0 z+F@mB{1W##P5#?!dUE_6xgvEQ$q5fM&dqHdQq)Exb7uyyM^WUFGu?NO5cCGPYAeX< z<-p9VP6ch5_+WkEqVa|0f=xC&L}3k`V850j#W}rkx=i?+jtd2fPS+igyXGQ6|T5$7b+n$%a|@kedtBIX86UT20JIVU<-p^S8ikgwa;A+e^Em8V?-Jmzp4 zGRS?Ed}t0I+uj`-h>8IxUy-TI&Ep`dH%?(cWhUfy4)2&KFSAO?PMn%lM!LO8^yD~Y ziX69EJ@chy)9Gch0L`Q{a*2Z` z)R9-^u=CkTmnLzPg^y1rTY)yrv%x%R*hGq!2f)QfEb`2R+nZrbjA2>DDxrXXOC9@$ zIK&`@x?2Gm{9TgjS<((qPQFqxpTvjwnjD*4MYS@GuQ{~lS}CZE8ewbZRHQ!P=&}(` z?3Hw3H9n8izRa><6IJctEcd|3NDM74E!z0cU%HhPq>WkK!r9k@=Cp6)0fU0vzm3EjU z)u&t~N-VD4WOh*9j!MQXTLvj{PImSaFq_3^HXLi49NR2O53jUO^xtxXBqVrCXI|j$ zU415mw_5M+ zQq&#HQZdUd-bGB_psn2xFYTkKxV*n_>Bx>BFkSSfAtGhye%@_CY(b^gU_S*v-ieOV zkrhd|XmXC=uO~ncQLF0^5I?8BE=-mQnQG~XX!JUIBk*`0FEb_1`S^z7=JvAf@+W80 z{rF?hQmRj1I+IQGYkgqBg|QO&6ZJga51Yj7Dj@et#xmdyr@9jp6YoKx47{}29~tME z(LNWva}&@Fc9iN19lnI$$9>MPVV(Yo{;6Am+kZ|a$u1|QC^R%AWDVjkgr&>y%F3Fm z%tAC5y^f9ZS;7S?c~mTi@%68uSbfufb0wn!Rg@!3|J z>*gnon`YVf*q0RHL9HUTsFvo3rkn|K0^XLf%ft*T4h#%RQOEYBXq#KvY^bbR1Wu-X zHH|l5{%&b9V&B(uGj8NUgaW}ty%b23J*pvjQnwheuU2)5O{6o*f8gTV9$GOmug_%M z6mpICMwLq+tFibsa?dXb#A&gp&+tf+>lK(+0!+|3#_I9hRx_Kn3c7QI(U#0~ zp;uZ8SI%Kiiehqcky}+E&1O4(ayM{|WY=5&nwaVOlx{vNEvuEczu}OnRt`D-^Pae$ zbj6Kv#@Wc@DE}PD1h!M2bRTphYlE}IDRaV@?s9ZEJ6=T@5D1z(mtd&eqBv>JK==JE z)AOuzyReYcZpE>;NMQ82LD8YxgRJ@mr~dWF$BVK?`x#5Yx1HW`8>)$piuO#8S6NY| zm7U+%6Lq>9E{S|NG6qY=-XQ~$`K_ugM3fQ@1LN0axa!^jk+_7!P(WGO!tL!XAu(~y zL*~cu8e>-M5axn}U^wfZ#}8``X%3V7wJ%}*9Q!gUqRQWX6ll&!;{^oci>rE<*=Xoa z&6e=n-6aCo2bs_?lZj4txA(Rpg97!z>BS_(NwQIt!LVkdF66<&zsbb1OY`C!NvSmDV-iyXNDU9boBqD{$br zSwa3!B^yL{tGt5Ug&8waR_)J9p>0RKFqT`+lU=++n*zbM=)}izF zC6cD!vp7||Vs{IJ$Lj%gj%SV;gFhJ>FY4FeoO_4~qYi~PAO(|(b*3jQBEBCJu;w`EUELh=U|NQ-&B5d_YaHFYcM zJ3VC%%>gnKcrtXg|(Oy|(h5VCiH+_1jMvMn>$Sz3Wb9@yenmmM=QO?j{uPHfvp zx$Z>BwelccMYwdn65hq4l6kF1=;hQe(dlCoGUX&(QP9`vj`9FyQ4k1}Uc*lwg@YUy z+)o@bxOMFyfE|Jeow^!kPo@TbRUWWW8bH4Gv;cv2>MWo%q4hW;eR2);^#C&gXw6`G zfB^p#jr>yoX)aseMdqVd$3^;yOzXo=WE0bKL!0D?b)HP4a`4ptJI48P|LL2B&3;+S zdRLlxwXilD-K^RhzB)(=XGdeoif+hD$bs?>h*j*4=Y)3&rAJ9jR9P77`%VaQk@S=N zfJCnYsb85T^OD;=iRT&ciVd8DRH?|68Nc z9Z7|F(hHiKlO=x&sp2uyL(BmDkU9BGrRft$MO7Hg7MFIJHd*+M#W_-eRt2A8)JDE@ zC#8;J66v$1oC&3X+qvM+z`($B@4{HN67jPe@iNGT@?c%Swnra0*$$;?*aZ8N8T8}Z z&>W3VCEOc%vQ$6WA{rVvw4_B4m7f&}P<$0a7_U?neT90A1+^2TX_DZHO5!C5{9{ks z0(<(r=sPh^EuVbudQ@MCDhQQ>`U6?PXTQMjx^^>Eo|_Oa_`_CQNzg_4W>ZB9*@PjQ8Ex2z-Mq50vV7O;{uS^)DtZ+V(CrKNoDJsg zU`2d%32|{k5|UCoU7i4u!&z)uRn>mTMK&$#+>wr*4n2UH)kSv#dpF)YOQ%;TX-n2O zE)Dkjtlp$4XO-i@Q%84Rvu#W`=TXclBh553Lhii;^j+@1y`z@+CLD)N*dnE_PJqe( z8!I>Wf(DThkHwVRE{kdKxWcg=MYt$4;MU8og^r-dU5~-QBjnMUfJJBj&MCC`a&z_z zsw2^wcIN3K7%U<$KZ&bef?V9A^yx2QzCe1V@H~o^iqVtor2R;zQUvRJ|Iih5Y4Q^L zk5KRe5h4Itek$$@#iLX7RArNWi&Yi(r-uMq?kA!8#)V0F0nU5A%chTzG%4BG+Tvol zGu)zi3Qzq)lmhTcqOw~BzRr_@!NG3(1w+O}k(V5^)yfm>AE7oo4&0k(Zv9r^U%$c& zBD-np8XEzhg1Pc($vS!^J60lzjqbOe8(}1=Iq$Xy0r!w~=g?@Il`K6-s_eaTYt+(h zp<3p`Aj~6q$t8alTWPLBcQgct23UK1JYenXnORs=V?)eE6aIy}IYh*`%djm0{n1jSA@2n;%g!ABoHd>M z9Kcc&le9SmLAmfT?dUgB7vmeUCItum+H=tmuE8$6|)X`-*!I#0civ> zG-;vcALf%vEQ;wGdW?YHm4V!AbGazrs)U05KKwNZV1d$58G#-kYf(A00I#PqgS`Z> zdV$f5jkUUkGxi<8T3u>ksH)PC7LAVMX%O`u;zmKCGa41kpM}A|8MIH9KABR-8mgKY zQG<(`pEf!xK%EyG0}bQgG_g|H!iS}RO|o9B+b`StW9q2^=W*ogff~Kj;p_S{?7_p? zXp2ch)DS((WRK!x%kh1I4o>_q77mWx7Jc@KEt9Zf^)+}LaxtnO19B*WMruD}n$2ok za&dGZBC`hy2gT25)>BBz4 zZx}3gRP*s%y;TlWfZ~Z#8kg_>QCtyMsdze$rwAQAA`5f&oxx%bEqI!-#2KwLXvTSE zrp4@&A}-)wr4*=+m6izLiiyoR8&wB{h`9K_L!jq;qo*NhttfRGNua*z)d&k!R&k?Zz-lZ$TuySnbh{O_jfU2x35UadAoL?{Z{7VSIt#YIo2V+5BRgolk%R-80>Ht98mQgWf}~oWv8BuPiY{(BRkw1) zJ}rHhv&g7RbH&jLVo;oAMq`tu8$6L4T*wJ7bS%e5dH&lEBkA|mmBYf9#Br_(C1b0l zyO2sft2Zd$m|697V%w>9E!gATG*fHad8=nr--7oMFDd6+oHHk=JLWpf&E~|2yR&+j zF7b}$s~6*gm7xMFvlVAoNFG)VcyFA2>_dwU+I=9owbi%xUutnz^(lih-^v{QAYn#u z-gMclHljacQvLQC;U7c1=<4u>13q=dEdZt%JMYfjwW5JhpHoLmV*M3|q77BTmlMgx z3ROx{W2Kgu;Jy%!6>%jWNjVp*5-oPasm7K zK*~??{4797Sol4y8kq{k?A(*yTSXL<5jG1BU~4dl3jJXocGFBg?rWi~G}^B5m5T%H z)J^Q9`~alih~=aItdxQ-lWg(Q%UG8BSfi}V=f2d52VTKWr~xGQzZq7J2s52M}woi}hp*JW`W`-AZA|`Iq6nidTe>&(r{B&!U#lXjb}HGg0p{5^z;?`KJ_}e8iiIyl3*J4?Hj+E(4~D|2)3m1R#~_j@f1yk+IigLnfH4 z(!;WJ;zjEV%S#S1#bL+=ZD>ylyA_xF`F2}{h~1=7#WP;*#Omp0-L(Hj)ptNs;fH@` zWLGxXk&!KX%WN3gn~ah@uRY4%Dxu7f9YXd>Rubak+B+AQd+m#h`+og?zyJSz-+OX8 zr{kRXj_3P4pYc5Yp29P~C&7R+Fjc#&FTfAa6&`l2ZVJm;}Hhr>37&a2?qM)UXCj69Zc~B z9Q_r@RfrxMjR?M2B%Er%Fi7C92fzOB=1RYS7Hd(HL^0gdORaMZ+Vjs|NbK5tCo|hpu+D{>OE`1~ zhdRShS*3YQeVFXwrBiJuk?lVa%Lb@PWI#VGnW`E_-vi;ja-N$b;X0p6CQ@7=De zm)K2I1WivUDF_S5?j7PS2!=O-~OD=g1Bs8l+hxp=J-qQF9zCWo-O9JvtpzBHm2c(UOxs z_x{~Lvp#y6p3dNwtd75i!;h~rX8Z@G4~ka5>Fw5CH)>5Pc6^x`?fAo_Ba~B3mm1_r z^kiOKU&EjBsA^~sc0K!Z6lhF#qwanVi17^S8q*&}pkK7H;zgpV&u4L^1xl#YN4Sg{ zsE2>|d(j^@8dOJKEjGYzDMo{<_Sn;>x%cJ|cXmFI7svsPvme&i&$$)bGH^VMIr_5q z#JxO>#Q}3MTiHB!2!UQ+BDhjM9)z}s%roJ&w$H*gTb(8+5Z}TuYbS2jc8#cZq4t4U zg^w_&Dl2YoH*4<3{%ibuBd%ZE2$3rVQlbWARmjMZ!zksX{u3!4)be==kX>Ks%Ov4t1U2p%Kn%@-QH;o5HPM@GKeQ_F#s$`@1Bv&qb|Q*8mFIXO8!wovPz4R3sWeQTXz zg1$R5hII$I^tL0^LU%y=QOGQ9fi|TS%FU2|aqw zgq@L>8$P;(P*KTU_s6CZ)UaaG1>d=9yQ5d%*2npDg;lwa*fI7JGk*y zi;8g#LemA6z(5s*BWcHsDsm3dja%$DxS=INgVa^K0R=^;K>`NJw7o()Ft$#Ot zyN|XeZ14OOthwcwcYed3N}&VNoP6e;rdOt_uTNE?t)=+$a_19ja?5vpXYpo91MV#o z?_<`_ZVn3S3j)v5gAkY!yEb51&N$4%l%ND{6h7iJZ4W=5X zAtL=^HXjyMHzf^sVQN0w^~rzj-CZMe|UKKo;gN%Q+;Q1QySGa*c8}eo|1kjlcA{942kv z&cb$0{S|^2XMD*o6d%kNIv0^-ZA#Y(K0o-D8}Lf@axFx)<5W5qU0@izf7Ix`*)TG8 zv?_ZtD_XsF$=B#v>qq5>{q!@zy)Dk6zKYwc%J0d)m-mDIA#qKO0j~{x^xvhKn<2N9 zcy9BOMouLE(kttknxgLx`xcLqpS_jmAys?nd3H+H{mf@v=Jag$@Ac3c-h|7_<+}Ki zXT3eWN&i*h%%x^N0M#fFB4&Lz^=C6oLEv5-$;q$CcRBfPoCzTcO8g<0=!?!3y) zxVBg|-*DD+{%ur4B}SnTI({3cElgHSLa!q%y-3TngfUQ-ZJ!Y#&T3Kl=Q9sJ?rX34 z+0z17XL^g4zV)mQJn0tSJcQx+iw0YZS)-)Oh(VPI*mpweI@Cpa#O0kK zIp8h-(|kZ1db*A|J?BEd<^As&ALGav)Ed7pevdZcWu|)arnCQ#&oBKO0&}JM%1U-@ zIdZfMHQz6nFTl+(qVozy{pXWV2L)mRylY=fYQopoUw}fLF8IcikCzeC#Kx6u{MIv# zj)$y1@J~J}?lGJv5X&qNSWS1(H+W%Zp6v!|H}WqsXXqD7nxAq`SF1(4KGY^PXoPAY3`r_CMg zb{@3cFr;u?C&zk^WQe#2%Og5YtK~cnv@e&!zmGro=ba{xe6Ger%??DD2d7}4h4+L$ zEu#9x5@=j^&Wa=^v>!t)W^D8~eKKE)nT0YXsXzLd%5CPn)9KxMg!f64Lfu*Ij&X`4 zt3hi5j={v4AUP2}4{d^eE**Zp0)&A69xCZO)Oz%4Zp0UdEhE(P6Xr z+*{LcyrtG*mQmZT6~GU>L(l0u|Gp_(e51aZ?X7NsD)IihBpJea|xc+DJ;*H>b{% zLed{vmOPa4HZLkj@eX!a9Dwtte6XSS)=Tv%7B4Rkcl;!+{DC_#zy~5P)VH3Im$PE&1yHPfbEb!pwi3*N%J9eSQ$ zJ$95!7@*Cb>~#>+ycwOawz zG2#ZQ;HC$r;shlO2sc(T0xqUfuASK*2fkh|9oH$rZMs#3f1GTuMd+lE=kV-VDbo|sM)w9qWi*?Ii0=9a! zwkG3DcitQ^EXvMji%Qc}U;-d-hWkQVTKT#fe3Kd#pE0kd|6mI`-Yz3wmXVd61}(1w z?)?xbGBNhd(SBYd8DeoQ76kaQeY8O)g z$A*P})+h7f=m?A>U6`yI;_ZMh=ng89>J3oaoteNq%@ez#r!fr*!#T z#(SriE;+R{2%q(>DwL@j)G+xH|38`ykVIP-7c%gB>FevC_L$h&;c$8X*;yQ1oN zCNr?X3Z2^>ccpq)w&<<0ewnQP3LRdB9Di79mbcN9uP!h-(n*TT{;JCUz)== z;dljGHtSR;VzT$T;AT#sM0dHR*(Mue=M|_y%I#(#t``nU+mNFm>IVW{otGUuvtlQ? zjm>lM)o!cdHphGI!uL*&4-Y*~c9-kE<;qm+_do_+=1Ur4ofV@W_g4#im+qCuTzXN% zw?ZyxNmpblKj(%Zx96@Y-Iw+L@+H5GkhG34p+ri5a zc@S^F3+5Z~JuHC&x^iZA_IAH7?>e|OYX_%}h%km|5zpRly0q)*yqi8P?0u3Tb*M^# zl0Zp5=`)u;YkgY5+zNHA(>0t>xq!~Bek_hF*2?8+giZe;=gb=S^fgG>c=r^6Q4twH(CBLg2jHM3rte`-Tgm*l0v{US`->a?4i3qGTbq zH#4q3%k$+h%~3&RKL!@Cn?QmNRe;l$kWPkfQ$KaBon`|52vCRI z|9Ce?I}ft$eUC-Z=yP9%U(a)X15w7&$r}d(Tp;wO2|X+|*7U`guJ|YgmW6E@U8@A_ zTAjCwR%50y4)mUZQL9pW@@iD;tt5jcotzZs(fN5T9UYyhRZoyFeX(pkZiC3>lJ-Dk z&^@a|G>zJxH2kk8PBB7AL%-5u;^H`*Pmd$3+4$-H1+K1k^|=yn+7Dqe$~~#o)m5Nm zP*LINP<>;6|B*yiPU%RYHpN3NC_icWv`hMwSh$VAol&tIz10-Uu#icVB%H~~a|;KhCK+GDeWEH3-H+dlJw?PnN_^cC#$+W{ITj1VZO(@w9T zhZnurQf}o}Q?>G^UHKr?gBt&$NENsWk<8ID@M!P<;p@n+ANpj;f`#Q_(f78X=c~)NfsPI$Hg>@ox!CgX|w39^OxBVujOr<_zc7 z)GXINH51zN_g2euLYK!@KvyNn!i(cb=#_L~_sYu+g8-4kne_j#1X3PL*G2+{y&o1q zBbf>ozJFIT-L3d?;5eCB1d-84cos|sS+S)(9tFBC6!JID_FG`En3ME7Vi*CoEzM(3A{c@Rg94#3b~8dq-VWFU?a3WW{%}WN3K@m)b6UC9EWoBCGWDHm4DAwwO*={^hENSqhjLX&`1AC)}*G zpdM6|7S8e$8!g%rS@i|!qPK;~l;84%s@+K&@jgHCOc4d}w)uK%!;XtdY)ezaOR3qG ziUb>$5~}e^wk=;vZ3-x;JlK~Sd@K2zw7KoU;rUeOZFlM^w_tInAomG+b9%)WVI6@c zviU&$B&S}NbIi}J?61sxokI%KqT1v8(waIWR4dBjTIa=atca|b9VNpLT zUq4ge)DuLlj5i6sdZu(U<3E~73g~vOs)W`4lvRD|m0tFCdHFA~E})(EoIS&<-$y~8_c(rViti<*TD08>ab-q6DM+MAz`}7RcY<7rtvLq;^ z>cW-tpHk!j$`llLCl{d=1TLwMe=WCFD){O0_4&(CKo{IdKMwn*cTdFF(t}c{PwZaW z+}ku4=rE=zx6G?vhf?< zP4_2WV()-eyqxLK^8U*Xk$Eux+mUp_tuP#=AZCUP+HmtL$YmsSlHY6B-W%s)aWAg( z#%paQ(^-Kx`{cQ~Ld%b51A_oGTLjmmg{0fwso$1TX!6pRRtZ7hw)#< z_Q!y$)wuuBXM&q0#TyJ&8G*)w5IB4b0Bh=CWm5-h?o-=NlpB6drrp@s;DIULh*H*P zDp)qb=~R3oS4DBtIZ~P6?Ze3Q^z=+OgKptpv%wvn-zo8Kbbl8nBZmChA-+&fe4BiU!}*)>^6(eJ3iXoGLoV+hYiI! zokE*fQ5Euaav_K_o$SHiHB`ghf`?WiVJ=+@PYk}Azio8(3&&WK5TYP{WG~`T z5OuVX_rc#Cd|Z{fM3kjJdJ|lzg6j6@h>L{K&;@Fq=uNpf0@kKM|(Z1pwlISOym zhQ~MiM#p=|$glULbbZE~u-7x80qR{2-0}$JM{pJNIqKU;*vSI+Z*N8=H}#uyFR)7= zuUMnrKOpZIf;wI84{PXNg0;sy1U3qT^#`im5tYyuYsm~&7`dVoJXcgr*Tl5ywt=PP zi5M9^E(k2~z3kwy+TXto_Jq&O=#SzbceP!;+s|jSA45MO$Zp)Q$$TMAVgfs=eZ@dV zaGRA?LzmiUjh_yFvMU^D5|cd)Bs!pguwyUqW229Jjq|G38{ls?JS5Ro`oH1ea(wvk zSCr~9?%Ri81$Q-Shgy7LVuElnPD=dlLW|(N-p>ZC(=H8i8GqTtc~zgQeWZR~F<%H+ zStT|gA5?{k8C6+4`jj78Kn)}vUkW~zJ5ARks2y@}ooY;aBz5T=4V|({wR2YN#eSuR zhDmq$54Ave@`-egvOn9ue`z{R&?f?3RM46HM)O?t`r!pYV87CD%D(YtezYwS-5AIs z`J>KU7e-6n{$(#{vBEm>o1OCxW^yhy+#cfNE)HubInlNz&B9b!?*^9RTZ*jCo@kL_?4M*#R>D}9{1*?C%cw5wf|ond-h+JACf^N*IL^pBLw6~fw$`zl-u%+HvdQ4t*kc4l)p}jq4VZjQ>;(*e{5(dOr zA3_mpFRl>e`ko$5u88t-;6e@5J_hQ9UfUYE3;~jLFVlkJM;&jtvjzYy4~|hfl|-tI zzyF8b$U3j!U?yy-A^dQ!JEqybhd0M_?Wg^mYyGSt;20PfUb?%N6h3_>b$D0f7+!&| z6XhY5I0EOZ=DYc22tJ6MH0ox{8%Z531Mw4lH^}cSfH1 zXC_DL31X`Qsrs~p9xjpFD z8L@f-5`w`y&|jzRBsCKk&Xq+$>|-!mTwuSyVs$vj(EJ8482~`PHLFb^qtKq$H82z= z!!0)T{X|P0^-dK{@}u^dsRhB_kb9{2q#aq}=hL&1(81-fGb-dsD&70WYOB$otP0q7 z`>XB{RtQAT{`iA^SdgOid3E<^Cr#&MmNmtWlWRInihkkJwRu5{M}n89-%C|V{zE6J zLU$urzk05!KQ5w7xj2^mqAljR?jr=`(SUe2sx(sr+|Z31H^d|)^mwQNzVZICOtcN~ zk&0-g1`BG`JXI1(`=fm4+tXN8Iqkblf><$0af)5S@A$p=dFA&N6tv}7xEbPv@5?;K zerMy>$+5M!e-FTG`#&^)G1_ly&-!V-xpV5$Q}tm-`#NO?w!y*K0I&hvr=6W$Vsf$` zf4UT8>n^u;He2cd=p#s>ohvu+{rfe5gn%Z4`%^&p1293s<~2$g85tr16`KBEzPV?? z3g@AU<>kOGrOf`e^b0A1oS?i@5@d_&>gphL;kUQ9CnhGoQLGa2pLSZ=lR708{6w7s zee;stE;IWP*S$2K-Lh{DRgszuuQXT!B0)Ye0-t?JqGzl}9_iF3rPBTokyK~u)my}_j0e)Hta!g zibmX*_oaUqrd+=3jtRTBQuZXi{Bhr&zMf%O2taxwpD!!bUmrJaTcOGAZ@TEnJD>~m z=d?Z@Q{2sjwMAE3jt_HaocZ@xR4otzSUr(S5+AMSFe;#2mqjL zxqx?7Ph*k&EGo{9#f7e%B|2zj;h!~j{XkX#7=l_Vs0%*@5!u+(RBTmBM(<-w*rTF8 zZgnFrTYrEbQjuK0&BXKx;+_1k?4e8!J2@HUF6QcAO!!446q4QE|G9w&6)SFf;_Bq; zH+dH#qZHA__FAco$=jT?qEcX3ucI0vb9H8tl5jlE4jqAM+IjNJJ(z~pT}o<_>tawI z(h^|qH#8g-yI~2tM@uTES{NywwDyzebX1qf;b*Q4v8ySG+3UAmIFC7Ve0ZZ2$v+wJ z7n}u`mOnOu{Nu`^W1h>?T!T>PYG9JPVGPe~#AAdZPnM7VLnUKdNQ1T9B!fG+;SeU#t>FLUFC)-l34{kmAFsF+?vo%4#B9y(e`KkXrtWMGqrz7SVDXPZJrCx zmH2i}x9C(92G6HFKk5Xs3N`HG!98prVnADf3<8l}7}je_a7>1E01i6%uiL^g#&~}|21u&8B4BMt zLIEesF%B%kSZ8Di$}hIliH{q5;MM_=`f;#$Y_;Gss*A+*2c0aWR<@l_qCF3WCC*Q+ zy;0T|bX%knW0-FD-NKRr3(wVAe@s;+b?DhWg_9J;BJ|p$g@Z}d*UK~XE)3>dfP0p@ zxYEtq9HSA~f4U}s7YsSj3f>(eMq&}DxBk6Fa;NpJr>5}P)A1uymh*M=$-siO=-4Ih z<;kQXJUW3+AfRl6(8mXAWdBSG9I;|48VuXztrE0>otHYG>yjp5DM+ zm}QtecM7WmV*N?L`DRI+qy**R=|dWlZ&fvybY#{hY`}e@1rnL^@)h)K5ev0)K3nl4 z=@tp5<9x?YrPudQahoj`C{?tGPA6bUmmb*b>`oIhLEW(C2u~H)}c!RHy_#mH^RwWg__Gr`T=gdhI0;x5B&Fnk|x* z^OedB3JiEf#KbhMt%WKkw<3e3wOQp<2Y-nrQAGI2xW*N|B`S7Y$t!hrqE~P3q`B@= znLj=rNt^5u`0|5h$E*A-)gKQeEdC6)h*wCTRjADQErzsh8%`3tQov}_0e5meNzd|& zRN+U?;($F7M#<7FG+Mby+gZ2z)kabBrv2g>M}X^V*pOU9DREQ$Duj_{I}znN%TV>9 zqRzWJF~oZEMekNvW9J!VXa#DyTVE}`45@=2ZLXt`ub40PrkM}=+Ib0UNRMp+H2HxQ z&zI!wwAj_&2%-`I%R4ws6O{_fQXHwcH^sx+*2O{2h-`+lTyBqCCWZwq-k7`4v0h1* zMJ_dJBzqp!$ppa77ryT_E`}cC42k5P_i3D*Un>5kLIn|`+7GQ3j?bK%P|cE_v$6|a zt*qG2xpO+}7nqdGc+jNHe?P17AdLgHGCb?H>Yk`FcY!oMK<=iT96mQbXmbcna@WZ1 zN1c0*NHhwpdOs(FKcbRVcc=;NK zC1hI!U=c&^d4cbSvLwCNrbLVy>PIJM9=ip9cvY49xCoT;&j@%nImJ5F_4P$T4X*|! zMSmCO-_sRJBO-VV0un!M;ZvSZjOn5Vy3~|fT4LhjX?7kU9_FWWd?@Z(A40^6Gi$&g z5^fe+Y~)J1)S%>V?&En{)e7{Ly6+W$J&(`GL{PUihq(gbQ$#RZi;sH+JujmPiSP+t zIyx3Ry4ppx(kMa2G@<-3r-^U;r<pQ` zL!FWUYo0J?>WhG{*}YBI%lPgQJ&9X5o6k5#r7*sRReDd{({6BwS`cTsg?8#(cz(E` zI%ukN0Pw=>jQGN(l6!M?dl<;5hqn~27dPp+uI#;#aPJ5QucK+ryr~^TVzk-HxmYF& z<|G0e^tXa70^APJD6PIb1$A|G+ih~zYAP71sqE_hWebrUVcs9Ws-t|t&xZq%06IB^ zWm|fJ>Y#bVRC|!5-$DR4$cfrElUhx|n56RZ{U3B4Ux#(g0|sLhe;}%pfBYd5I{!Ih zdT@Dbe`YY8o-Su)tF_}-4Nj_q-?eWwn0D0P30bkFk1t!XNzNV9TKj11t3e6z{O66k z+ZDM_Dpqj=iyWy&7Fu#+(+d&J#x?qQUOITpb0?Q6yXnremF$glA@2tN43Hh~_Vhhz zUV?TmNveeX7HvyQ`&TSLo=ybJ1uBXc_pSkkA1G7->y;w6PXzFDGP0YsolidDt{O>QZ_W zoUg<~uSyytLKXq~8Sqf!euwLeXr=uFNA<%Gs8Y;5lcR0ONur!IE_g}Gb$U^^{s2?+ zC^&0ghK3N^)@pGzVX0r`hF8GGGvR?u@rqGLezYejt3hWBfNF!N2V`so4v)A~2dZ&JR!aQ33`=Ql1B?Cj3SVCC_*wajy^?-ZVg&fNI3(TO*a@ zZ;$O!s2JIoyG$gX=pN(K;Pr|Tzu(`+1V}1gZ0bBJf!2j80%gwSSMt5a3qo(79bY;% z+1Ar7zh^C#c23Q|=cOOdwO zb>$IfjbWI^V9e|ySJu$}$!f|0(yz1id=A!m2@%s;t?6g+7Ac?!D85##s6?)alSgA& zd=l~U^8npY=7lYvQTM=|KC<13mm;DJ6~R#yok@vg>g=G(m}bYVGfbXDrWi`(?{0DT4hF}P}{`I)12JN!qJ z_mg^UY2LOdnU?a?CZtvk#qn6%*|sqyzh8{6}pNc;gab|uVl>ksGotEooxt9)QTM|#$*V-cslG?3)*&>4(YPWbcggW zha(=A3g1)`$e-vE)5+S5IXy?tJ_weNFx$fKipLF6Kdq$Q|4H+5P zr!QlG4q}q?pNn4+P#;aYR-%(9sIlgh8C~pHT5eY50OGu(V7f3_s=XH()z5V=U;qJ@ zJkU@oSV2cHV|91AyR`h*Fr64B8Num*Bo!t za)FODbZLzIe7>H(a}buv>=E{13ECC`C!pr@z;j9b4J1;q9}n&&4XQL?*#u%%VEfuT z4F+v6f}H@MMC{0LBPoeGSlS>j#YaZ1%)}NrwZ*jVez8_TSZ?tAsE zX;@Wre4 z9DZ8zbsC_hmJam`#}js~6sq%m7jDk5U+kas*O(a@i(4_69^0XwRV}K>}+RrAcb5o_AQrCBd(B8HOb+NgZ z3Vw^TBR5d94`Rwceftuv-<~~S|A*)g{f+lQ_iBtJ7;cS9zUO3?9K|*4Ue~xy|L|+* zbG#Q@cQGs{cVfJDYXjz}{>gg*;0FRMm+cD`a1q=$6upkAx-EBzTdH2J^eZYDz?mo> z7x8m&aL`Aq3uaWzI-YKC2WsaqEdLonIAgQt0+SVOa^AFyEp~0DwjZK3kPXra8H-H0Dhhday5Z|KdUiH&96SqidmLOnG&Qvw zNj2n^0$775RYoL0a41j?jATMm3%P;=jcQ{_>p2JTdYJ0rTGYb0;@= z{}BNpA)P-E>=PX=OC5axXO$Bjn36k>h42M|whRw1Zz;`H%x4PLF>cYr9;*l|=@PdMqjpU<7guV}C$v|hC; zlpEZ(4|)Qn3N^BCo z9A|vNz1l9II?HU+3KCy3VW(|O2Pq>-{%;|X*=XFYlM^ZTKxmdf7PC0=8jsMV*^ATI z5<*jBlE|Tv{AL6$9eBu-Vc|s#mb6QltifgaN11*JxJEsPxaEYJ-&vDKO%RU^IVQ#C z4Kozjg`9R-nV%W0xXXU&be_dtrUiRNUB)$cw#jFx%+xFW`zf@-@s*AXL8 zi99~)L2LK>?6~@shajj81khzP=+?6Q?~*!AvW;Sl=(4&z%Y&n5otTl~>2d3NjB&zu z2P*s4*49lBy%SOzBD{g@`N?C|`FiIJ)#I!E8O%MfQVM~~E)sv&P&^yGH*(R%dX96g z*s*};@u}~yE~Q2AY7&p<(Y7lbKlL&M?EyE|uH9T^T|-X_jkkrfWed41c3fBpT}3aG z=-)+O!Qm5gup|D_tUQM)#fdBT-UNHf0JZ7Z(@QW1_hv0?<#L&%MV zJ;S_<4qY^LSxj@jc7_{s87z<`DG8JrLWoT72Bbcs13gnz-=iZbRT$=4b65xSF;G1n zR;_1*l*N|*yQNZjQmE_WfnU|20Teno%2~~u$+GJX+nJ?b+Amk<{4Q{{|C4nR{m2&0 zIx*{Fwu<`L`^z@v1?^nj#$qA!Knq8(L!HnONtX7Vaji<-AlIYNW21y(t4LU&$>{=D zhZn{^*u6aj$n2_SW`iBEw*v#!9TgOM_C~rrQfM}3r`AuIj`p8f-P-}%Tzykom`CvSmjO8;gkFb- za=Mq&7?_Lk;rU5H*1H~22^SPP96qSD5x{)l!F!DTen zN2>@>FDV~%Y{gxC6cYOAb*)(sL~?k$APB&u&~fQp;|IPq38kQbD<{`MBj*P}6Z+xh zD>@P1#)ceNz5b25!`|uM_}k5~-?B%f)t*t~=d;j`9a*5^dKzOBO;#3FZi-<$^{tz5 zNOIM@R#l|2WFESKbUb;rvax!{2*NRrL}vQ*wRjH5V1hjJaJ?Dk5tH{w(jYoJmvuBc zJDzlfu`|GvQQ5d)ri=0c*C0W{*5vBHUT64U3+DqVZvNv^<5`@$L{=t;M?4N)wiol3 z$#nGmedy6IljB*X6(6CyE&n?sK>wOAAJ-&m|BKJNN$AM!0rOiE1!b`MA-R5g`|4RK zD-UCbiQ6FvwcwD=Ck}9hdf3u)vR0H!&+th5=fVQ4L-pndL+Y>IbHEa=##sPtaloQb zwQm=Z?Np07NQHSaD^e&EB4EOtBxEr&$Na znn9t?;9R4-R}2BJiE^ZIzvrwGD#W1x`^?BGlH`Z9eX|9>Eh;8!CT|k1b8*o|^xkSK z@83e**SyiQ&23gTN>gaGlW%dhC$Du|-?DnV0yCaG(|)#4Vu7w~zgcm!ocS*z&52^t z*Kg)+^YM;yi$Y0--#jezMvt7sc~`smk=nb!apu%CxL&71S+zVWvK z#FTPg@WVea>~-M-QSd3?Dqyx7!21TgcHpN5XU;giaFyHzJ-^MQ6)vm#)7oMRx4>L? zTmYQ#gZ2GN-{_X4iAujb*E`U5*~y%U@y+wY6@?>Oy6g|&uPwHmgqD(qlP!yk44!9M zBUVr#6LgI)o&8t%GmX>ohTW;&zr_z__1_Acr)R%1YRv4 zk5b_zw3A9xQ`6&MT?@1K4tZL+lP2w#t#4%66^XF?- zO&SkX?E`rD`7O2tK%27Ip88DqrJ%+D!Tcnq#CzLII_2o{t#sNzy|LDzMNYrQrW{LI z^pl1muiA;^^|ql@jX)|)X!%x*UHzZ8Q&|#R zy$m){8L*Fl*>|Saw9uS@ptFNdB({tML)Xd$)`7OjvjaB!t>;HcFS6y z)D#^VG9+e)eZ=~@;VB;3$qwkai%`5(^E}!z1T6=yeP;x%oUh)r&&fJ}=_%f7I=Q*6 zcVLj+!ikY#(=HO3Sy|JaVc2&&t;NM$NI2pa-Dp6tSR6?@yEe;ack8UY>1pazLipyK z;`FZqdz5uQDlfk{e z{CH3V~n97cky^F}l-@(4EqIkSc{ z>dLSOO7_;o_&+CCDNkiyZAeopxar(nu-;f%bC8EBSeu(OqA!CSS1C~RVPo|)#|_IN z_K8)B(=w=lV%nG8h|151v{N)KI{P~+K*%HUsBMfUENR;6)xs0TAV)akT;55jKxmww zl)6B_2`hS}Oc;HbGWUouaJA;AnJ{e8o#c;ddNqx)HP8Zl_&~H*-xyAoWQx^gdUX4S z`s*?*K4Ubq$3X@bjw-z;wA8D3T603msFHntR=qE}INfWEU8ZE6f3LE%t+=0;>#`=9 zUA=og;?gG$>r2$Fx~#6=&0%I;U9@LYx{-|)v<|rt2|e%keU~?Bb~OX5mX;IBe(Mwb z2sgL`x9Ns_HPxvU#pWE=cTJzT^TnIBiy$jPy6bN-i`px4p98S=$@Rfn18x3#Fmmjw zeTtl$zP4{Eu)!}i09nh85578Q~un+Ys^wcgUNjXxHaXW zJeRLl3S_58KPYXaVQ-#7>c>N9f4alJ7h`Ooa{UHJDwl+7=tUh%_FMhj96{9>nA+P_ zFVttG5^m7!ECHS=laz-8E;kOVjkd_C{MnSDRD*Og3f5osL&QO^U#`zEnL>KRYDTK} zg?5cXS!Y(ohJ(-!6GwgCUfxoKqs^w(%*H2Sj^#}eCz{;&FL%x)lYjpDR*JKgAk^^_ ze9@yDfW9*ud<8Fvb8&HjK7(Y*x6h{?urv(=pS@-L{8)k{HJ333giH|-SHq83A0`h~(irubY)hwak2Lp^sGIxkRGFIEdXhfpDNF~v<+ zL-HPeF(?lP{dy{9QTXx#Ck9ty*jca&j99NcHerH>mp=UP6Lcl4kbgOXLz1YaBF z$MmG%3TQ>YSzNl@glmp3H2iFSC)LMbU^F^XwZxf=D*qI*#`_+d)|imd;=Sx{T9x}`qu?( z$N2l7>MurYI=j1DZwdV5tu4hVzx}2!x->4jL|7b;28_y*@+?yHig2BAhuTZKxE!vl zbx->D2{Nx@R&VXYWl8y+r+C^Au3_9mlBits9CSXV(RCsU_D0wn8MS0To1P`B%|1q5jj>k+6iN1>r}=Okh{*&oqw&a!QJC6o7@^!4@7m5cU;h#_4WYwc|&OLt$c zfJFq;S)7G-Xi>&+Mm3%{maJ6KLN&x#MCg32^&l5-X*nk0#Dm}C7(_y8+%SDe+F7?++a%5+_Od2&#Ib7Cm*xPKRdo%UeOSY2*?YcS z!JNGzLwj*xtbOdYX77cGwLIW+{H^T@n!bV72WRb1&CQ?a5K`s;&)*#+a7zHGDSA9FO z8F!88>_#X`H05j8&Azjd-F53r+G;@jv`P-Q&|hanu2c#1Hfi{JqApmAEjG)pp5Wi? zR1<_B3$WYO@`1x@_WAYSzG-6WK)=J|aG!D<;9o7Q5g9|l&P`w3NV^Ede#`T`RNP;^ zsLB$=p4X-Nz1Q|QtXAK}VEkXg)z4Aa_b{z+d1QXdbI-#8C1tq(hMnn23O;c<0TDrk z)S2-?wfkfHg^IG3gI*@tu>{z9@ui1|kemnSvK`041l27aEe$S}KClUo@~GHt{w@!Y zOPIE{BR6WeThvP~q$id{shmG#W@Z-LDG#_&LRlaI7)$4@%3T8^$^&@&2;BVZGoOa1 zJ~NA?2f-ts@3a4aA8ZEc+TS*Pce`}*yV%EFYIf19W$qIGI_n|@Cwj`QOklTaqiloM zIxnF?Q<9Wja6i6Jc7s`rEoduO{Zodv#MdFa2=hm-6BdD6-EFqNyv{bZnSXo`SNdmE z;3JD|(n0VBRG7Ma{rK>^%wodUB;BfmY{}_LfMxe@`JVE*)nY`?!_T&SYv3vTR)cD;3;t-;Di!V>sKzwIv zN|D>S5tehzP~3g=7Jl(C^G^8>eN!aueYSclL|J43du;>%qgNyYgeApKd3t(OKjT8g z=zrXdOnPX-aG&glO~h9lVFij)W_E$#{_tgK-ltvlpu^&>+yGW#VX&K(@8fUzZl4aU zj6g?NuX~l>GZf?*x9SwXdXlI!Bw5BVQAv`S2d?kmJC@mK z3Qf%)z5n$uE_qvEVwkkwn=y#p`K~)QGo#_c+-hd?N4jBe-!Eq-?58v)_6WSCvfi%WnS=Llg}n!GvmN2JhO zeye_+nVVy>MAw&4k`nWxoAgN}D*K1H8_vehrAF;iD_Q3CHv?cH6n}+c(u}5l~O4sNe|* z2#EfG`cIUxmjO=rk#PnuKh4{;7roa@{kEt3!xZ(e(OWp9v`?BSQ?jfvdl*_bJI^(P z#laF}r8-4v>=*GMG}7|l;xaatzs$dD%firXQsN7_;!}C>)NdZQ4@6cj%p+f3-?TNz z({`UXr@lCQryJJvf#Y8NdD6FOafkPPm(poRW3CsBt=jC%W#Ds<;RB15$Fmvn;$4HW z=dJ@4-wjkJ<7xg6Yi}8qRn&D2OCuf9C8(evA>Ak-Akrx*-6`GDA>CYbcXy|BcXxM4 z*SFF8`R-?o_x<^vG57pExev-e(WuDRyKOL0A9b4?tgJ*ULd%05k9S|1`+-gWu+ z8Uq849~wS+dT(ckhoAMUr8+LRxNqOd4Z>6mgIsOp84gx4l6d833+hWgRkG&>1CxzC zKE+{HS-5qbRc+$c2WAb!OtO2gWhZ9G$2-O(`A}29cSnmDvxS|G#;20lZ!) z=l2vNQv_%59R}Y$5mjd`0A}4&kX|#on#T!3aun0t%I`EI3WJD zxfp!hE*Ba&PSguuDq$~f?=AHY0$x*$49mIa`W3+a*QrS`+IFVRod1VkEDVCk*Ta|vE#VKqSteIiiRppv*EYiqN?!A-E2NrAnRJ5$HT`p3uw zbll~B`4rPn9p;dwXOOoiA~=clAJd_y_oz>*;UkNBtWlw8rBCkS0*7@X{+Dgl$=xv> zYOV;>j{_yg?s!ER#9olDjM2JF`>pMYP{zb#tJXBLI*N-oFci&*I}6NOAjR8E=gfI_Cp z->(gT9>&)G&CdRDL6tj50l5LAy8(5%Ovprg7~YKxMAL{g!sNHne!|!^1B;UH-mC9+c`L^I zNsRIiMlMBmP75O;icWsJCy|1DXt0ja7F2yh&Z)Tsk<`pMm~mgA@&Gqxb%1Rt;rya{ z(eW3sw2@B>@auntfmi~}vNM8f?N3&r4}|{iLptY-`7-3!xXl>NH_Rs=nQIx!L3}1G zgJ`5Z6yv^;BH32viKN zrMIlgB|}#9?^h@|LqaGQ>eyzqH8vAunL2pl`1jO|8RA5*jMQGSa>IqANe*m*-Ejy} za==LCCxA~tDL8weQS}RX9t#8Q`}c8{^=)JC%Hgv0jMdMymF$7gw^h~G;Owd@+s`iM z0R^`C6!A_czwsRIPP)dFwG9mXnDhsacl^!)O;?|D0)hruTRJ#(I=_mPM27?++txiTUo_leYm<%;Xe( zL7MmtU?>3B1dW6w7Fgma^w~5q7%0 zov?bdvfr+(as8s)>@lRP;YR1wN)jx1bY7Jx8ARhE93ru-av>9Yh#1%Mw5WDD?UAZ{ z0buWp*f#g^2%g)E0%$Jj&P7kdXkuw8{W$V!Vk;#M%+<~}7AWda1;3j?uA>sSN7qHy zThqhFOZB|`{94O3cyO!q03%XThc6_7(}%Q%K`quf4pz@1ywkm6D-y_vmQl&rUjWP5Fjt6Kf-q#Am_L za%yNf5k5hiTGhyyn6rsu*QmXz;D9A_rbiSQ)}e}Z z!MpRkv-h4}R2~VulRSBkc{=TsWWQ%v5zl{I%TX1Hq6?5r z?erC8&DQ+>c%on{x1j|S7$z~8e3Wf}tI%*5DWiso`BKKk@nTyO~mGpGwUePAP*k1Jm3 z!D3sOi6&V{YfmmCuT0p`vxQ{>W#VJBNf;Cq1n7daj@_Flkz(=RApw=dNrO{aiogO( zM6Uqy3}+Nsn#^&V`~je-9zdS`>sMs5>uzEDRevh`twcNfjVQ&d(U>M6f=f%^a18xa zSKm?^_@w^j-8I`SB95GtY}nV}IiVW;pNmyyLcMGyni0OvPGpKs2QP}}`Z?#GJs@w@ z#BQw&QsbqLe7ZsSfe6)kY$K6qKxKTdU~A^pRCVTT(et~>^o>{DkR@o7{!GMHO3Nm= zbnu~@CjIphu6r1N150MjnJR;GkZe~mR?%#Kv<;e%S;c8P_NT)JW2VnlmOi(fhUkG( zjfOBbaHR7*B&rv7vMROi&hf3=g+$gNF(q^=k29EI9YMjtKUO=Qi+=q&15~6K8gIrA zB&vSb{vG!B!WY1WrE^@_m=HSQBL)Mmiy~vZwa2)1o}{elLcGbuwv}(zW|FcBJe6!K zQrPi$odPu@P7?IUuC$+5c6(u${h<_27nd-$dY`j;A(Q0*^`v*We+%=ZGKwTlLV(}< zB6*yYtaiO}P5dyoULv1Xwx$!*!{$d+fD|QS3(YFsEz~0FoD2)zo#+7e)Obcw z%?r6(O>yv?iS4uS1AqR-pHm1hs_@Q zVs1{)X1t2IbHtZ; zq*=G8pXuySSGs9hFqskS+dmw2Cur!fi{xBFA2qpX?v4c`@vmU|2*0eRj;WzAV8q?(OT7clozga5O%nB}~eiQ2@46-m|mHpr_&AQSLR%mfdz_KJe|QEr35x%xPoZI-#Ve0=3iVC)~^Ml0@ zrkT*B275Pq*!3$fPuQ;3ogafg5`K;5{h&)cN}J!2Lut%pQ`vq5EYPR;va~08Y{d=skfc)cGzU5JQ&%2;G zDOYNW+>#lSd55jUhWm@TXTYi~_Xg-s2@2}qAk7@00FyZXihULn)=twZ5vT7;(pb-B z0K!+G8EhkAbjl?AOU7hDgCL>o;K=u z+`0eWm5)QeIl1&07>oVORs@rlYLlj{GgQ2HFTX3FuNdxM61`;yBPE(o`B8kLqXQO5 z8EAv1-)B1d`c}&=P{hHt@vDPFpLgnv?y_CG(K$&X52uH+46Emk<;+w5c>Zd*y?9f0 z+WT&3AXo);_w8(V;#_+|{W0kgEUHN`u_)U?Mor33k6ATmgVpzV!POQcB`bgAN;9WZ zYTAT<2bB}MZ4nOUan+bR=>(PI1)q9aTC7Kwt^}LP>0vu?8F1U8M@5+xRq9GhN2gyj zQiPWQMlq||d^b4u|7TS}W)1@B&q-fv7ktW_Im7|Sqdk+1X5K1u6h~HW#bIUDTqS&o zze0mVBG>scPL^->Qk|Cm)}V`XldFeHHRl+TBouFyTij^RMF&+~_-)`_>R%ZRAl zOHOo_F?Y3>!=6iS&y(q|r(o|MzFyrI5-be;z@le|!(Dg40LMpRz%v#S5Ul~1y_3WG zBj8&qU~EjIKa`{k#u3mor4$r!3nO%1RHZbk5htDi z-KT^rk-dLzpCi(I@#}S#r3X0zT{eeoh6l;**IZ;D%bEoCpQ=X+hj}^L&hsz(qI8v- zJk-z?Ims#Z>0Kx6K`7a*9XMv5S)Q2pB}i&olwdr;s`3eTXHRt~E{2x&unRK$<5mHZ}$5Z0_zFfkP6sr-B!J zcy6xmV6J)#MGC5ftH*Z0vYr-ss-iXP6TB0`_H)?Mt@Tiz!u_$}FD;<>j~SwSkcr93$#vWwH7EZEPAOByPf=IM4`vznpPH@C z%zQ(r3UOaYMt?nt#1=K#I5~{9yj(7C=$)M_SEzh>Qb@zP7(d-6Y`cEu$2MwqQ9FtC z^5oetXGleWD=D$b3c^A4_3FCGly#gF&msqBA@!um!rs|609OFp>Ai?wj2O+*1Yy!3 zZo&@e^btnA( znP=%oHnnQg$fFw1*)$fnI6skaAZ}Tdx#;mPs)3594IDEJje=WY@Zx9f>@s~Trlz(! zAQGe)R2N$4G(au7H$Mhy&gxFowFG~{B+5ZZy>SS6DLHv=VL8k~kmNC> z*tIj}KXAmH|1llt&mCmUJq}hY?xD!$HO=K*`N&Tl6>9qR$N5T9VBtTNNLsd?=1qL1_`V4fYm~xiD=%;SL!WemVxv9 zhpn(O#<)+04c9pjQ`qQBXuK+)w@yYfp!;vye-k@o+RcJPLqA4Yzaon;>0xw{QT^!M z#(5G&)%p;Mq`Mal-N3Omy{QQace|TmEiNkO*g3#(FXZa7E1{|s(jmzz1qw}8Je2t# zxP#cX}l4MJ@3D3R8Jv^lQ`^{nK;-vArUoID%Qe2x>T@?0vHqnr^l9xp&^AJ zB>#aQ%rwFg&-p-l_Zi_B@`hVH^Zqb(OUC#bIqdjk%ueytQSx2!Vtq)!XR0fde*!m4)<^)9NUmQd-I`O=!y<4iPf@Y15p|FbKZ zp9Rh-sMte#mdEc%z2cU9DJa4n{tFPj77y!{_01d}N0C0b$PLleJ+bEoJt0WQ$nGM? zOez);1}fiajNuH@R`gAlAx3b9)bhny-)B`ivyU!LcLylccOZP+-nDaAkdPVm*=d}H z4n@WnPXjB%>tY9ohfscXa}NEMX5-V4IIluDTRP!H9#|U6@(ogj&i4z1$dW*a zMZaQCd|ez)Ve|53=UU=tfa@TQ&`8u z7mOMlUid7ikd^1k#0Vz?#758}j_TAcPxnW2OP#K1_z?Y4a&wR*Y4A6SBws6n+{jSO zQbU4*y%D@wkjjE{!;ioiu5yP=8ls=H*VuP?L!C~p02C2_O0N}~{^dcs+=4tdyKh0R z43pB_tUuwEy}1Vd2OCv_>4fL)*FI-7S%(KL7&}ZQ<^SSW2I{{5c~M2UQ$vF+ru`J+ zA+3gQVX?8l*0aSWcCDqBlrY>lQNET5+Fdw+7h%5(OjI;dNTVe3fOIt;w?wTsy-_K+*HEc;1l`*hd%!Tu{zFPcHwH|V! zYD|ZR@QVJCca>yqElT@tVuZKpfqvnv$k=oP8JP*41!Ft4neWs-f!BpO-IyK@M9|=o z{VVp={Ej{;sg_2yC52=4($K`%D^i5h!R36QQ>*K+1O6j5)jWVzYXT_0VRo-6%1()a zefW+oBQX90iV(EJ!GG6*PO7-rG(HhbJZ*Raq0nn?RCv>$o5^%kC$k=OK%N8l&eg2~ z=RJn$^FGsXh?BBg4g2hmsRBXq&8u$0ToQz^xa^Rr;4?e@l?4r5X6^%Lj^rZj9>pZ+ zyFHltX)b~!*CvOTE63JVTjpOMU?nF}tt^K>&~m$!nfcLPry5S=_?J|js^vK3xVr5n zlxr#mOxre|!DW{ollvQxZaE}UwoKUF_%_U%odfy z408azn1F#BKK=oZUR^b1;qOFtuaFCB2=n0)~D%W%!+~ZNCNf2|i*kZL}<+CDZD;{5f zdni!B<=`GQKk|Yu_436-cDwvPns=W(|=~mWyXqWjrUz3FO$`^DneY7QUg@wfqb0!6?`s+i#zYOtI7KQCM zj4!CO4Uyyp_+*2c*Wvw|i9{pA$DuvCa0dfq-*olVBVey=41_

8@{~Q>|%vxW6r(*>t+hXw}fCsVgAW#Y8o6%$(Ro z{o_t*N|(+yCQPL%F3o|o__u=z7zv%s_@gB!)_Bx*;zP)tECeKxzJq|*!9dy z(b*pEwCd+ab93|jNw7hWnW?q<&WtbKF-Ep9NPj@PieE{r%|lB&BxwHi;yNB;N7yUU zw>a}&h-N8DrzlSr;KzUj8*^}(+)p27$xcoh zxfv%^fS5XeccMPI&Mbv8VcbNQd6tAuU%$r{;qXxv%{xNwk4~aWjP&FB^)T~46?L3RXUJ!UhgV4_kwN+ zhxIVwtHsNvuFZjXLqMiWayncA;OvVRFOJWP-4f}YSCFj=aMw38nN$yunOH5N*IejC z*%m%sA3M+mzmV0f|LkNJdTOfDgQ}W+roiW^9jek4Rv6#gQ%V$QowVg_jyYGQ7^dy% z--qZF!BglcQ( zQntZ`M!gy}Hf5{V!3>2c5Mjtts|G?#me;}! zY7VTg61O<;wn|5saltA2?*01=U`N=_kOq}|ZQ1aB^8g%gUu#W4m0S1CKB9I_V6I{U zKL#nfHkqPdU1&c;pYw^^8?RhoQmvolpf?!}%H3gfx_b6tvyN3v7USlITZK>Z7h&d3 zyirz$+C-6lnsNJsw^SrH#M<{23dLb8cOy$%PNZALGq*DlaU{8C`>oyDnu)%%)6?Bd zL)=V5Vfn%oAAW7lCGx_X9b%ti!&nc-gln@j8Rs+bWX_L8eoiP zs-)B!3t2&tv$xy3m9h|3MgQL`!tAx$Ml+?Ef&5sqSh* zD zxVJv)O=q$}l#~B1o!u@W{=v)#<(cP*3fng65GDOwAmPFKiePru~`a7vi{CXys-`%7Xp`g2@B*oux~&+9VM$88%!Sm z*%;if*i7u4J+L{u7&6t7%;c)0-?P&7$<0>-jnWl2xD+7*va(|dLz*u!{CIsgFVnAy zdwW5{XUm3%2Q>8B+8=Z@MqCuS^D03d%t8p#xV4i0H-i7iIOxLr|MxhkNXm9z=a_3y zk-PFKa%YW;Rp@+x>H6m}Auf*3nd|y${?0+V4zP5IkaJ?V;5}6$x{Sj?R5=}(H??Aa z?#YVO$y%ye9<+7))Viu@S=Q%%-dUR2eNU@r6IA-L?}`d<-o=|r%Ia!Bv-iUUzg9qX zujco1>?cFlcfV^VyZ)601qB(~5+bzqcWG}mDaswoo;4me37Yc*?ob|*6q(!INyTQ0>#l6_>UvKE zD5U|q_SGg^GeP6Qbg4FbqD0f5O!~}9;rKD}D(zGB70o*O@9RINFoGMPi9dOkaP|N3 zSH=!RL3n%Y~Hh}hH6((%%u_@Eb!9Yfncebuo}rFFsONfK{* zs!&hDr78FNA4Eb?_R}PyS!?E%m9*|oEO~+N$ ztU8CHd`9gv2~b8RE~3{1tLo-kM;Qov3(ussAT|)X${V#N?l*6)c6T>Tr;Ooq-BZcE zb1CwtLBKJFDhbuw+iMThTCPE3Inm{XfG?V~x_Z(iM;1QHjigmkb}ZLXZ3IPjYa!E- zg=6O<6>&`&343p~)e@cgpMiw1H_)&N82Ch8Ej+@p_)4BDFV_S)w=vMLh!L{;IQlH< zMDu%Vt($(CT_Soq;Ft`><e5?`})hJ5{8ACYN8G+NrcB$ z*G>aopHMoGBH$&Y9f_OH7x_Oxa zSc+9qtHz&FvVF&RWX;Wv#o%+jfBznPG*XDp$8Q&y1+0i?A9${_=y)Ms#dk$)q5{A|Lmu9S@ZM}!NIl^n6ei?EogM2-VQ3m2B0o8y0_hi;bj&6haH55O zVi#wco0=XZ;QY)T6b%A|gS`x_BuJMXDcQ#Uqsy;OA@e`1&CN77rCqZ8FB$A`cFPg+ z_2fJ{Z;3M$brVD;3=1Z}>0701PMI%(9o3`I9NyHT6KnJ!VZ2u{rwyZUX660nO(2}7 zJ#8{xSd{(*Y)&pDHg zj7IKKsWF(gaLk*QF_BVTNnh<$3U0PS)t?}lujVQ1oIw`8Ze?fx(K~I?#Y$c7-ypzD zTJPH{$~HAymh-kRF1^j>hIcK=^GDSp!Ft<_Y{ML>M}c!g{80)WBMK|n^8<$+HXnyM z^_IJ7_0NhpMawp)&G}8%2klKnw+!8%Vszt?ko)NnO?)9{LBJ%WpkQPpVl{ciijs{P z=WFzgyhMDuB%O`E_(k8F7T|2%dUPqQ^83cQNlE11n{Wd$35{?($Xk^ids%?Zfa#^RJs1plNAmy5&$cq z{UEr1d;kA}b{}GUbrHmutN}YkgwRgd*5^bL+2^*Nt@*+Zk9u%+3ytn~+o&rdb1K=` z!uwh)|Dfy*zSly28VrH$y0y)iT7MyI7W0=#XS^RnN?+qAd0xP3nvI764M zx}k=3^$re4r8l_cd(X%lY>$eXc{KX%WFq*QR?lk+zw9l?q-r;9U#bj0{KKLf+I)TakVs8zGt#-mK z-k8KT?=VM%n>+E6n3Y&U|1Lf)WI{*Y7ixO*3NnUyREilE_>P)-^&a%G+<*qCjqUFgP{jKcGXb(%`KQv=wbnO#66l5t{=>2CiX5_cyb?-Bb2)=_6MgHjRIUec z27mc=&sJ^1$d%t*_){gtTFwFT)w8q-xXmMEBj=xkeT9Ff`(|Vm2j5GtK{MeaTaVey z30((s<u{Fidd$q6xw`N$kE9MZDN0~O-5rs$JezbG-E4Id3?_NT9R!8OK7=| zrK=mw{e2_YEzCPPOUuQXnjQ#VE<)UGdhpH)>+yo~* zSjbW++fc;uKrUnvU3OhG>diNlV6r~7uX7o0<5?aiTN}hh6SI5wpMZd(Y`$O7pEKDT zN%Ff(nP(Ap81*2aTWvpOVobr$VI2(&9ikGsE?3SbRvK7{?G|^eeDfG($c>bNrFB2G zoF6xRUoD(j!(<-FqVpLmW^2vKvO@+m)7 zf}8PP+M)3WK%QH^yiJGtmPT$w*)D5Et0831sj|2DEnAXo;|XL8S(2|@K9j&pLoJyw zD~<;+9VpHMwT+SQeIG(qzn)3B*x0;?j(jVKgZU-wA2u7tzPZP%6>N_IGR!ZE6z&G8 z8*73EoyX%kKI;BHImnnvwqT2|%+7+AFlN}gyxl^z21N1``-7_rDWo99oHt*3>$$T^}E8}5)w%)K1js+sd{2P4_zi$3+X#4XC#TZ92@Q`hA z&`^WPe9hx?7?@xB`0mH}XwPwAkr=t*#PsRjaGe z*!p%bkzHEg9!ro0={FkjMv=shb8@U{dP|tZd#?Q2n)}K`-g=?=`o|3z0<><`H+!mk z@!z|^RO_QFoPa9F6DkWmwRI+r9D}DKAkbdXD_d^lz~Y z2hN}^1?B)-cKfVky3m=3kPu*yiB&NZ+(+Y){X?N@w-@igB8c<-Z-FB0O?1yo8(Loq zJtkI*;BcBiSJcPyz!zTbyUd-w^NBxYo3HYvffr6XQdHnKdP!? z<&2-)I-?bpS2NkzQGPC|c{tf}8 z8Z%q;BPHbMy8ZOWO21@)_e3sjT3eFXqOFm$Ww_J+~T-)$6fbW%~E;S``(mDfKCT`SlA!fp_iS)y)`b zUHF^H3-JXM~g-Q(nS%-)lYr8iEFf2;%qU!(o6kEZ!Z z@hMOFYH%Eg$^y`sxr2#Dn!NUSeCuo=hgYpTx)E$SFU#|^SMnsZ=gt9$N^Z4fVq~-m za8-B;DBCRP@k-JpP@)*k<2^XqX!4F_*+?Ch9WS%qF=e9K7m&lp@gS+=bQ46)=h*SaFz%wZPVeCf2Q zN-(@6i*#kgl~q+(Xui2QIet#{MaD{o*5Z9e%u6wHf>*#+u;kFa*5#|s}4(J7qg8Afy?rM9-AK8M&GH6#?b{HqCigHXmZX*txq)FSXm+cy2u#pFJZrRe6k?g?9D(<7*LSi zb8B<_y>Lca%*=_dSz-vd(Lhri+>x0bGq*U~afL!j6DZ?FPWj^$tC^cvKz49jPda!n za^+H~xq|?BDsMqe5ngBT)A9Dgw9(=n&8RAEHUc~l{Ok*0W?*30GJTq{5inyTs{dw8 zOLoIh>uIA-q!;wy23w0h;?(dk#-x~KIckqlc4 z9dYv7#{6oPFQ1s~Jp~2VNBC-sSxoyV73F_!VM%onV)q9Q7_mmZ0sZEv5ZbP0Rbj+|!pjP;_rYk5$ zQKZ3cyMG&n#IAtcHOW+Q@VGI&l2-xFc{LkO6$`^eHzU)vc*9(|YUO+>cP0H)We{@N z9w_UYF61wRHV4bM9|ycFLPuV*m#eYs(Fh^lI$Vc523ql*`rd7N>WVeTw|1XwIoz24 zxITZpi!iZ!e-}L!UTLpJw1S}t)8ezBNoB>t_{pp?DSNIljD+QSx)Wi$iAUno=jR+3 zfr)}xCAh_VJ1G3A$Ln2jO@q4cwjr#DzHPA~KL-w5ihli_Tpek^@Ew_+W-ly!|8phpVNC}!+q+Z3FJT>kLC)aeO zC)t=U?6K%Md|jO50hzUl+{lU_BoYfm`JjUgg+aKTaj=UhpQJUpk##KURuZzu*7>&J zJiPdsLbwLX_pR|BTOUd{z1e-bQ_=iy%}o&g7#S)h_duvwiG(z5lhYwqgc&&9@q+J? zy6z9PPgOjMvf%=9Bj%dDXBSl?v$MTDuNvR^CV@U1&}uBUbs`NYEcc?rg0tsz;|XJ8 z1F}Jh-bRJ|i5J8v$1j%ujHG{Ugaf^R!Zj=;W`5h!{}(}ac1x0M<)8m zW9g&^(Kp}kJ=r+UXwLWJ-t(iLC$45T-+YC*4u9!UbLu`!bPPn*4m3V$XqkGrA!8?5 z?DUwa-?;w-g|5I+?qG$=O47zrDV#XzULCvgDiXMWEqw2$`kO{KKf$^`hTjs zpV~eoBHyP@F;SzPAmwVW=GtkP=xRA;4{rG3Ol16)_-K7~BR zQ^Z=RuCLqW ziJM9-4jl0)*jaw(^H=g-fP@uflRE3FU~Tot{Ded^JVYN^?hCs@9xJjVJyRclu}Qi> z7MvC^8akHvuFbFFdzaSGAJ<59)UJh_P9Ndkv7n&5>OZJ%?gxt76nr-u^v7iRHyn=Z zA^3Wdf8gYL62K}TVo0Bz3Cd=OH*SRTX@?UFL}O%75Ss?aVk|z9mPWUDHvUOqLh7bt4B^i8Ny>_Scih&~K$ z+JEK=De`jyP@~}Qr;3MXlll^yoJEmT|DX}sQ#ZV*`B55T{o}y|L1}_$x&aNEt;nK@ z_7@i`ZYqjR-QOkZx-r6*=;gDsNA^2f#rv1#O;OUus1)WNn^`AL!{^)IzozXDTev=S zYDnV2e4^jWb6#ICTARH_-ySSZshbs+n3A8JJ$*N;?oPwqU0JSQyOWn?tIdmIJ#2eH zjLpUC#YXjOWpCk+0-o$4toAZ%;=NSkV(j^Rl%c#^v8(Ytgq7Z?eP2{ljA5AQ>T#z2 z@+xchHe{_B_|jgo!i~y|LYrc)PkQ{UNJ~@gm}?L#JYzgzjY3U`aA@uqPi!CXm(3nq zx!Y0L(vkRFyDe9dsF!K08r8B~Uj^ro|}Ng={y(VMDG9M`Nt z4qIo}qdF*5%!q^`xFuH25i99kjH6PLN+Wbgs1XEsbAm4C(rA-2{$wmz#&R6Le>-u! z;EBpWq^j%+9>K>FUM^CO&!r({zAgHUaZT^ zXg=jc;VDaNij!x)k?WPsk4SzK@jhD5_+P_$c_XR=s)u-V=m z_w5D;_uX}r4(eEI2g9J-Jaih?7VScUY$ZLKne5;-8JG$!RqY(V@K%rOc zB3X^7DLw57y!1u1&gC?lt&jmMeH zGF4p3+MIa7lnAk__&kGRQe)DhA=Dk2Z?uAkVVKvfITAi~-&gH%Xr*6iz+I#; z@LQ&^CmtFpe&)I)VIF5&$$PKWH}#pees6$X6)B+LaZ7i5z}Wn-mQYY^72n6otMS&@ zPh5hM4px=roVkXO#YT35MTFUxF)TmF+Q{ z?(hpnKBbJyEG?%Uw%9gt443_)>-CqlY>ph;8J{9LJW`{h3ed{Pt&3b;#mY+{_wuc= zc(-g#&3rUjMpn1EmJCI<&_dTYdMBkE2pg354M*I-ky;RXk zMMIM>U$Xlq6)Wq&?$J&bD;lOpED^o`Xz@C$G}-V4Oo`9C$Zu(JZW3?KCafX_+p~0V zQGV&Qo*pKqr=OWo_=~@0GJ(>uD_QbiuE#CJ5b&NIR7M%?yaS|w=LW8_WB17nX;>@YKo;<3vau*54PF{6<)SK; zt$2bX!*FFUFSVgfLQ3of`CI1Nr4Q!MrBtw{HaTWbc>)rJ>iMOtF=!)XPa33)nX6G) z@dLLLZ1;ns**2k6ClKCFfA2be9`OZ{Y1mo^PX*m*4mqEUcvurW{QP-rpim$u_H%5?57hJZtP;7WNlOp{@iToj z?k+a`pyi6ObvY@NXJ`UN;epMc=wZ%m)+X>!=jR%@6b9R{xg$`7onokNALn8vrP z&oVkOup|WK-cN>g%~%e1hSgZ2pfh5<$e^OI#9E`}#YrCgQCykJlI-`%kXrvSNuWkZ zT%*?lyY2=H2$sceUVpDozJQ^%e<*y5BpTYk_mRq+?)lR`{3qS;R#Ul@Yh0D-_x+NY zXiB)@K9#$u%Y#wf3zS-ppF9X&vvFD9WXl__Juie)UZ{K-gK*tYEE(zd= z2mJbV|Ii?hyhMJ#sjJ9-dDeW%`eDmAgvrSW+VPn#O4L@-a#M(%MPG>I7WBR6-P*z# zK|Mp#Y~kM3@hxQ=4%}yR-OjWVZpaz^sh-+UBnA;D0`Jrl_KhITjvcTydLS}-q^E|z z+Bkn3J8xb`D|g;|m9<+-8xx)U~?SwVI!@Fk_QLE%s8vpVg?iM~%A zl$};r^;jmt0~x=6W8hi(2_W?Ok@6&1czVv}!F!~oBVJsW1Wfs&j-$geKh9y`2p4FQ zW%>qVt7qtRD7Rj=4V~NY>saS{v z(cONp>e=m6JYqkLbaZ;lDA@i?$NUm2V8c8iH>MLn&VQuDJt5ikixQ&hDE0|HGK-Ts zgfv@vgnP>AAR8_H%}03{1rHtd+p!r3S}%;W%Wfi3&pH2`sxS_wnu_yHJ#%RqF;mv~ zsoL=H@P(M*_*!-!d05@dTc0gzx*oj_R~`S)-ly9-pJ3mm<#j20D-I zE|#SFKH)pJ6AAjFB^nj|bG=dYBF#xbZ24zi3@g1<*X^m_f9(C~dMBCC&Vm>GN=Z2~ zKphywE#HzLj1UPRhLC>hwMQOlea6YZD#UpAjr_JsQG?+#69uKmu5xi>F8y44)jb-6 z*N68U-d+|w7=reZ&!jawh5yudrqzSYFr7V!ImFFucme4+{WV#6F- zn|;#&+sE;euI^Z~Lzpz(zDp0yr^9MALvU1x=EcEM>n1;3BDvRg*gHXQU-D+sG#<_| zM4=$|-Xc!~4pJr`O>G&=LwYT{CR995k2c>3V%*O$kRU?sFQTSeZX@bdF`TU!0W**Q zmO75%DQ_)SUn$4o;2A=1sE>G~o3#QNW4YT%F0d#5mc%sHd`rOrlH|YTJ06azrPiTc zEMA{zQ}`nqZ{fF=z7AyPUrC}R9znn)!1Mp2xO86H-GFA#!NGCQ1BMNnv9Se^s zSENBos=AlyOG_~N5iq|oyhg0jk%c4j6Rl9pz~|rHIa5j`Y+u^OO(kZt$6IK;?jDZt zUpJSyoTx=Wh#PAZu^e50rX6}|W#^?<(}r@) z%Pxgl@6~F2k|)y?9H7E3B)%eIHr&2JE{3@;rHvPUs5z;zTz=Q-TU|CFyP6*gxtO> zKQj*5MG-=2Ja?u(n-wT>2hrdN-#FWt3k|G%6O^%xO!!pu{YjzyMABCm>?Na0(a-ZQ zGYff5e+}rp0(LV61@9$eXCvrd@-=a}6QR`#^k)vpXUpPsG1!#WQ!~5C!(HbG+udF@ zIeW^UCs4_#wC+Tg!80;3l`0p$mg;$ZODcx>d0km-eRI>%V;6kdP6eY#PO71>d{)!M z61bP8|BtG-0E+5;|3DEe8fghZ5kXQKX(^HJh9v|fmTp);T0lZdx@+m~C8c2{mhSHE zya)V!@4bI!m;q+k^S;k{^7GVNAp(^6hWB$<_>ku>B3!-gMc5iJ9f{=&~*3>UST^afinxk)sP{YC(4O{YT%QoJe`V zpJs;&E1lRx|5bkeqASy;0H-yW$>Oo0;-wot;6mR=ORq)ujxYrv`D&HX`M0y@XP7E> zc6M6ipE1ai@&pivh2h&4;k#4uPB&$^PS%(9Qr2~rreBIHw=jL@mBCU4jW;G58QhG2 z#89s$L|Nrl+`al&$%&;1Hk(Ivt?AP8a12r-(3DwHzo0T1^H z%8QC*_+Q~mR%H{v;1{N9vL53*JdK(Ny3Wl zMWh(wrYjx0@-xK-kB^UYR-ian>N zf~gG2SFZe&Pm(QZWHvvfngV?!XJTI!U0k)PtTU{vy5!hB8Ll~b{g%VhI$~me$iM&*uNg}dV9UX}eckP= zSR8Uie7_`KCtO@yVKX!692ls%v*spy`}S>D10jlcI&D-`lpZ@tsXBv4bp&u~+_+(b z51W1ee_1z>Q1aoP+fIW8@fn`wvDD&0lZA*VomBPpNyGO7`i-}gwRBGoHnvaGt#T>I_RrjDRL+G1 zTRQMkk+&zx1E5ek;Oo*(TG(FF!h&INa1iXD1FS|=Bzeex?qo!u4nh_d7JU8v9nbw6 z0Lse$qwJakC;~|Z;JW8zNvKNH+UuT^Ld6+oT~*&ilsT5m|8e=eZ`Ib$-u%eiW%jMN z(mJ<=r4*oMa>`1}uLALMGUk<`GJZHd5o%s^56tUJtPThp@WPOlOj?!mBzGt#t&8#z zIbd=cK+;?5Wcqhp!mhvzQ%aMD!h1z2oAfgVZ>VO;Lxk5Rk1uDj3X2s?)*70;G>@@& zo?%tI9b&8mV5Uul5_T^(t*&{WT zl08O#Bo&nvex9o0-Kvd~oSZRDsQi_h7F_Evk=mD-?%xT0aSV_mAMQ`gJ!$UqK23D) zufH&Vp1_F{U!|h$<|45q7uT_*LvGcR63uS2%51&L>|e3fMV*~$C&t!j;DBD8*DAR; zB9KtUHuGq{cNen%)h5jeTz<~qPgmmuMnVE}K9MphLVW3MLS20ltMi9~Xnwc4H zC(S_#2O*9mzj(HoDo4frz%#)i2X`3LuOEC&-P%fE(oq|-w1y7(=gc&YZtexU>J+Nx zE2kw3;U)s);L3X-^TQ?3lmYS>=tXkIL2|0|A)WS^F@?{`Nxt!gHyfy|E1c{P}VjP3q$cK;lPYYds0m@31Gfy9Zx0Yw2 z0xBosS(#SWP#s$#h zd(N`Fapi^teBw0hVwKd}$H(ou@m`qkN%NhCnK_JrUbO=4tgNgIa5=Vf6fj@GUMpA) z3s~OL1x*=z;VK1CqHLznEPFeYt(X|#GCyeelDKXB)tu4fRS=a(95V)s8&6ORw13YN zgfeOEVM$b0qv%#UM4!T(XmV9M%MK=47?Md)DtvRzxEWoU*w`Y0io)WpJk`Y2+^~n;`)c>fDZj(*>r9X`VkQ!^oylnBvb#2q3-BWVbm+o+^?jb^fw6*j!Wx zpsPYU*))e<-NJ#YJ+KvI7?|>Xl2c#k#tRKWR2@WH7n@wGBuW0s!x28GVRZMyc_Z|# z4W8`I{7*=54CZ@#dygvoR7BpJZcXt+R9X@Me+%^zAjP$SIILx(E{j^X<$Zq#}5J|nPz)S+8S*)rg3m^l__NkM34i# z<>ZvPV_j?Lrp1=7XLNDzs1qO74oP{sdFG}v@Zq1Ufqa%KT&bsXUafIztl>aB{|KuGhH|;avJ>?@6|K5r#BX3JPx4Lu!k@S8h4_I~W83o<0g{Ap!!kF5IHL|4tY5{QWwK2}kJ7#9=g#Oh$`^RVT z2}8-{VxGz=P+$nUmP(qLLzNM;kfv{vSPY4HcAb}cvEESiYrA;o@KU!tkfn9y@_pjm+2P`KD zOY5FYt;`&62mNyat%G9Q*fxu%a8-V(oCOR-m6Ut~=v*KxO*OQwPKdyXFwSwsYq;}x zOfOKTprSHc+>+<0qZDg|k7WM4l{_D`9eLzaad6T(=bAHA1`x-!2#!4RuAV%Jg*Zd^ zNF)}e9t9(mwQ8^6504SqYATE*;z6>AH%HKvKSTI=lRcBecc!{aG;KykywdeP#Bon4N)Ky5?2#j2OERvVO|f%b=yS?LLvLjk)MtmM&%2%m1syrBOgK&0 zOd|$f{8JI@{6Xo?FwVPOC*r2t_?mgWP4UpoG@xq~N*AxF_#wbQ{p#G1Q}DodOyEJI zd>03Ax~c*Bk5G<(_UMQ*D-lzB{I8+%r4zgGOw8iQUkrtoVG`w$Wfh5e@Tgy9 z6=Ytm(Z*iFw%gSbv$do%wWRqPDZfXf;~|~ZW#=^2g&A#0 zJ(r4Gov0FQa{*g(<6rpa)YjH2x&S)6F<0furrTa)r-n(An7aD!H4_8^VKH9veQ|M7 zwQv9la4P|(=t~hy>FSbbqKRka4VqgaQsgxxdBG!;m#){#iEDBfKDZRAevpoyQ3^lQ z{-87InD1f z>^HflMcgtPn!9%!b%zLp^%4PuzlIUEB zJOUKs7?w|PUu~DaJNCR?toe>5Z;I;B>A2nRaOtgKv)|c{~ zL%UVufq;Xp`M*Y1S~awSZO=dSY$AMT9Z6rmeyz-Z$9FR4DJL)bn4ROx3UDF7oyPzq z0p-0YAO^0;$|@#4K(;ayB}^Fy7%R2 zS1ub5P*f%m-CmVotxsq zUp?o_q9nX!D*yE--2+t?3RQS@#U4fenEw*_oRj$Z;MR|>u4V$VkehvdZ3JSd70@`o zI4D7Y@YB$A9_@V}8c-_~KFOgkgrHC}jHTg=mFz?Z>4xx7A@0|yg zO!SsKb+IyLz79cLty%Yim52#2+LOCOs#VLE_O)f>qGT_gxqZC$d28kbHtg{`nrJEv zH(XQC9gmcg?$A)T|5>B$NV3f&{5g}wTwgP%gXux__yd!~R#1hbJH&H~KbvskCB}%a z^h7IvBnzpzb$yQBR_eqYq`RjvAeMmEh=H@hhVjTJb#OBT3$^5Xl>OW^3u$N-*w|U-7i!0 z)BpLE`(`v+DCT2R+dGb>8-#c-58e$irhRQsKpNMcoag%B7bE0KTX}F&J!_ikE(Cb@ zPxBp7MrH}bB`@YcIzyen#{q{CbY8X`tp8Zy3O>S`q`&zJwZ&y}us8QZUT^ zkmihc6`F119vt^2*aY`xd2PFpSi}VuxuHg50BkyZ=5!laeS7-28W!Dmp{CvKm-ExH zxc+|;l|M;pM_{b$fI-f|}V z1l(%pQ5oeaucx+woArcH!9nBlu^rXmKSz+%ianJ|tQ*^l+a-e@0q)u)2%4+AE(f=Y z$S@F!7Jx=iVwwTv$^R-i#>#xQKWmqzk|5r!8Was;$(%fwymy&zGG>q*rfX~x9Y!^- zSC~CFlnJ0Mdf(1YOQP&$3)TBWix(2Im1^HjoGGdB2vZq6PqIdb7uE!p!ZPf#e+g`I z!0z5fXY_n6i~Nkoa`2?elPxBQ>SbayKJxl=x#YG=?7l_s#@dF`L)6(oXYVbx^ziE1 ze}+nOD#+*9 z!vJiFKRWr(A0uT|&WN~Lz`8f>DhBKCxaQ9nvCb%}!lBnes%fTme;R-8oo-f5wkn-y zVu|02lIYz5X)4ehV0$`Y!e%+m-F)*tIXyic3wu<**SAEO)%ex?8S^gnWy6&O)`8vb zh?0h$dpt*q?8@ZFFTT8?W!0ka@u&r2Ov0h;Kl@>cTtB$?1aLzXe!qKnblvOOY131v zO;Ob5;QlPdVvx;cl-r*=NmSCEYHBNPOHACCumf8rXAVDWtlu5*=$uPrLs(bLR&ZHVw}kWUn1wr{wiC zhv25sav+r69#;rO#Cs#+H_IVwQ)id{*+@V{X3xX^GsyN?&EQ~Z{NBu6e@}e+OQpEA zHFCckuwN>mkCDzXWq7rsdGP;ZoqQE9sA`hGpP!2dr{}FZuzE+x#-`L{hK8|G7fAmC zD+S+?egoHXacFp}p$ z0*wDV$k;fW21lt)kwbJx`bro44b6F!V@LAaq{2x)0tyb+9$jFm$MvpKGpeI&a%kQ( z|4@Apy$?iAmnoJzla-Gycf*90bjU;JKM4QS2@{OY<}o90@eLrM=DP<@d~tMvR-ey~ zj+{J61AEUNPi2g40b7+56UjP4UZOM?Xq3ygf8eENVJQWIE(Hj5#S zD9YdyU_wK$Ltz1fNoQ#Bqq{Gbr~;+Cv{LNJvW}C zq0{8nyFK%JF*uX-FSto1Bq8bfOaW;JdiMr5>P~HVbB4Qtoiy8sQnC9>8BiV;iXv1+ zpWejKgofmZCo17 zpvyqu2vx61)e}=7^pVU-N+5b`KOSG510cNV@oPdVE*Gg5OIxJLKv<6f?a>5eUjmu? ze*np1dtg{tPDMqO=j~AnF!iQF>I#dLGX$96!w}E4`Jh>z(t!h^Pr1I6q*oE7I-1>i zdwV^XYpFl6aNCKzxmOG8j+J?WfE)ncM>U#4Mn>BgNi&y5b7)B^d)8CyXSt4URG^7T z%l@eePMD67%$I{c6s=E>{umkU_z$A|cp%;Xa4}yT5k+@*KCc|i;(HlvmtP@W|1|HH z`_F~E!c>T4r?4o$$P>b>AcVo9BPZwKT}eIOyoSAJfHkcr0#zF3sT{ zSHi<+?h$6Yo6!jAUoGO^*`XUA0CXKL`K#RvC(7cLsTZhn0Q#^m@gF|-@KBuWB8ogr z1w=S=_<6qYPAG)pxt`4{n{X6yn?X?8W_k__!mIxT!J z8lfk|q?+&~bX>35V%D9Yo=HtQ^XcePh0@ZmOxhAgF17W4tdInDZy(T=@Bf9F00RJ* z_2&k19F~?vG+o^T16VbbIgND6UeHxa8G_t}_Z3CLm;->D1Ep##D>7Bf-EqY9$2ATM zMVVLM|1cUZj5>%v7Nwv6o{F(m_Fw!v^k$o#-S?osWfD)MMgX-@C{#3CRv*^l76jr_`dz`SD+K$^%Hl1it3-mf>v?0bGFUEH?4M5&@ z31LQB(^HHfk4j^0@UvWq3@HZul~zE@Hxs$W`lS6H6ywv8XLyAg&p3GarpsShrdICu z_w}`#RU$vQ0IC1?`h)kbJK@YyO@_xAg?-o0l3@q5k)E?KE6CKh^W-C^U{r0IPeiA6I1B=`nQfy@~JtI7r-Ax zbgdkIUKhRqXw)vhSpUk5vf@yM{=8Y|50S)c4JZ4N4mEHsdIgjc0-Qq+tpqq%G5AnT zCA!3!*Az(&bs=v$5*SOqY08~)RH1CZNd;By}GP|WR(j7-JJlM0b()x+!PiL zwM6fFWQ4e0e&fF|8G?0?#&6`xsGbn|C{Fi%g7DYtp zSuTJdB-(VmqzxLnCl3bY%aqa|(5ti8LA72)Rsu~r$Y0ee((%0@mfB> zUygv-&;`A*T0g;ymHJd1%k}ITHW5?ot43H;CqSq-f4jCAA56y}0j$vd3W}yeDoH>@ zbk_ax>Q@sdjOJIBuwtPA;9HGpJqd(=u$d*X9w#Hl5LYFPzc?ehCXuX%G|H&yx`ZqVf`2T)lKWSw#=5Tsyh{ zi_+YBGh%1yxHUFEqNhx;XDexDyxP0LBxb+28qNCHnyd)Qe9;!Bwl7whAAGg55P32u zKQvA{)+RQS9jjipy|-;|Z$Fnme$auU{n1lkqUpxBZD3dXYPQ~kX0e99zDib7@SK{f z=rY-Vw!!MrH8lW*A6@QVO#EnUft%M}cD!l`jcnq0U>690iRU5APS7~7Y%zR*R@~$+ zx*i~5DUs{zD`_@xPJx~*J3sl;@IF!QRmONyprzSLAh*3VdUje~_O~xNe%=dH4(#Vw z=rIdY$-VV91!#*BMk92yJvRJBLgL#A$7v$b#O^x$wHd97`{lf-fuW%mgt`wB3Z5a) zvEwS%{v~Q*fx)8CMjRQ}ufy!#K07JkZYZ6X^Q|qCVSwbbts<*or|eo;z^s9Z1FxZV z^ufv;i25v?#D+JQK^xA+Z<(~P*gQ#ez8vKujkPEF1S;IN>*TzDDj2CX%3E4r?kcz? z$e32-6VR%1Ef6*bYJS<|lKitG#=C(A5U(+WU+g3P+YuNZtKzp zpgE#~HWSWU9X5r!oj(&#*b}yI___bbI+GmapL)x2xVc)RUQfRf-Zxswsh|a7MtU@ zm)FZxW)g=SopLnp=c%`xGPhiZ`qZ8WFT($pH1&+;n(8;?j0k@&O=v~@)kl*jKbV{P zF=ZZ z7+o;9yOPT##s@BZ6Ue7%OfskVaF9X+r*4@uoM%`F7A$=8?J%rM`tSEe*j;i@;4W5Y zX#loePwhSz9%`2P*a$oLB`Ig^bF|SDVI%*`@%-plI~W(%FXlEo?RqmyGyNA~ggOFA z@ROrP*bI!c@u=qbe6pi&xuKk5wGu8F=cdm$)O`acAxE{)riHMv z>6SEVBDRmY3B^kfx<|ALn4WuI4g%e|Okdg7)4fwhB!Jx+H{Kxu`9x}gw&e>KXO%Y= zl20kmKvUhl^c(FpnrhCc)fMu*E1yG4oXs#cV&qvDWf*kS7AwWAK)*&Cf%J2YGqSRh zGTA#J7V#HmA8=pcb(ZKq-K<{Q-xA#Hg6*Nbi?un0*Ic_Fp5X^>ta6u`u^L&8W_v05 zdX!@i5xLJ2%4Dy-3owjM817+yk~-cJ?C0bd&JBshh;d5yu6;f-+->trhy zV25o{GrN?P>XfX~?IORBAzs?^vtnnDJHA~_*QZp+Kex}XM3#SB&bJ(qx*WBfh=P87 znuzx-F}9R^On9vO7&>CeE9jJ=PCUTXEQAwF7z%}m*ura2K=DL zb8fAUTdxHz-8G7fgFeaWe%>cn&o6g&wnI_|76ag7kB(L9&*y8$&c`m39w)g{Io)k* zcld80@n(TwEy4M>ZEBtVY*&k?v4zAg#vXC{M z>{5a^zy}ZCCBu%m>n)wV(A!`OjZULS6GXhZ#5O!*vo@qenPSZc%+3pgCn1`)f@@); zJ`i5dracvmF~J^!C4{xoC)4py1I5Y9pvkSPeDg2ZM}oF%FsJhq`jtf1#?Xd43%wk3 zWTNScsC>31R8{s)6?~Ga#*Uj}5{+whPMT-6XOQJuD((IGlSEw9N;j^O&55QmV=X)? zITA5n-OnS_DF@9X_&9M-I&8; zof{17eoTYqTl-K)h4R6 z6jyz|#2BMPK&Fuvi8|~$Alc5Ib2%SMmjk7%B0bA?%G8=ZGl{76ulT@gn&!9-tU(du zD63`1_sZIm99J9_Qnx9k;oHe~kO#^rDt3XG@Kd(W8+P(+miMA-w{aX74!bzHHbi$f zTREcYc&Jd`_KsMO{v($cef1}wVp2%^nyhMkxK77E`0|}v_X|K4mlMnkRp;Qm@}1Nj}6OS=x3Mxp0}_@nuN~+3~hO| z>`~x%YiR@xhJw+g6b&g9)b1Taq$z7tBzNZSxNLqOb5!;hV%{WzUtN8OplW@8-gMR_ zxF~9ae&o+ zdY)``C>+NIN#wOKza65H)gP!qzOBx9oMVvVKBhHYey$HI(e5J`6pa070@t%wCwqy` zv{Dvq60Y~y`fw*j?Lh3<-ST2ZMV*tu@jr9q$M{DBoS78D72nXKHnX3`7$qahR z3sZ8x(o-bTxd}0sNN*2k9wHsbm$5pIFW96LT&{T8@$a*($;pN!oHv-L$xSOgu~o;jdNu0;!c{}jXe~QHmt3c)p((N#KAmW^=s1Z)xrdU)Nedpk-}b` zZ{(btZ--#BUu>L?vyTw})dGwL?gTKGPxK`@&Hk9M*d2iz>F@y61j#VZP$z}@C5~4b zFMAH%n5d}LKiMG4PO`Mr4-c%1+|S>8I2bWdOrPSIOC|0$mBVKT%G5&HuCjT%lgau{ z9d*x65I6rK^FpnQQ@J6m1hd(t}%0_2T$YG|H- z!Ljm>1xO|BU%nP7tZ5rY#~lX}OR7xLdMmAuhgzr2Jq!5sR!5zJxNi`U`y5o+$?pCL z{{Sq7Vq#(;9H$ELTt&a^LB_>#&$7cJ-SnQQ#6if-7prys0$5hD7Zf$4bas#?~CUVkU25bh13C$ZHI*%&onZ z*?c(~$!C%X8(f(eAw6Ah%+nu5Wq2ijsTKsrbjnf(ibnx{&Zy2an;LupmlKs%%UdqN zIKl6f^O-Ad8dq&&=hyKYiM+y)xA6xv}WQlAtzV@@~Lz{y<2Hu;u;vIB}HlysX?zp{|GimMTE-ZIE1>PSpX%{^;+tLwL zAJ#Zt0v8k! z*r{kWC{lXex+%tO$xpn<03w676+5EE5Ei){Z65a$#G}P((;l;RmoBsJe0|P*WrRh1Frjf(n?) zVJ^HPiosT1i(deY0XRnd7D`}yAH}5|2&_4fH-wW+^ zNJ@%~=BXx3gVpCn?cSjMg4OR#RFM5{d>j$gvvSZ+5W4I8}NMSS+2Rl`X{;5~Vw?*MF zB~1mNUOVSMcG}tqGC{P_V+rm<$W$jVY4H7#usY0?OVIS1Vu}@RlvNp6-!$95xLJJ8 zLlyjN(Vo`v$p<}l;&}QOn2+O9VQHwX=`V`}nC;eez$eYIhC!Bu=um!<}ffJ%_x+ME*VPLV)D+TRYtR_X3N;FN=<} zQ3BdR)5o|d+8V*~tJ#LIFOJDWhy?$1XRq1}vJ%DzxttvY zOgOCsUmJ_tUztbpU@JAee5V~hZ@H9XnMX?-6dB~>M>ctgc7*%Nbb`hVOAb-p_rgIy zc~7$~xXCjH8#?rxKiePrj>zFBT2S|qgj-RZqu`k!2ZDNXYigJ8q;^ge$9z!9J`*

5c|Ysi<=X6Ehx}GCDjq~&Q@@y!}mA^@5f#x*hIh&zC22_Yp_B!#$vwm z*z)=hbM4AAydQ%;>BENBoP*2qoh%=I_Zxd01cUZ_=!>mq9L8Me03crYI22ZxYw`6= zkYedfrurz1zSGd`mUN9zvG44&z;d2O+eNL()PlB$q|cR=p8T7(jFTkS87@u2OTzoG zdtC{rfk{Sdz#~`3jNTNObKonU;eNW0CC!T_b+ZBIEZ4!5y7_`$iKk{4POrF0Nu7pZ z0g~CxHt>@z^r1Q+e0rKA`#4umBDvS7T(ykJ>X9iaK9jpO^1J4Z`ZUGv2p?I+)porQ zc03A~M{v)IpzXmKW|VKdLQlY2%5VDL%C`0T#@m4- zh3)c~A~IE}jd?ol>yhAy1IrIGcmZ32^E)e2DHG{4{HL5dH$m8Eva5+-2<>|gR-4sH zU)5LJnW88cgW1o5B^H0_xI+riVsV3CS*yNU!O7?fYThCV5c~5<1=E4ak5XsL{230< zh6NJ~gUM1%9Ibh4?RgmBN#iG)QU35wXD_`I3_IFF5nN>slR5JB0;5yWy$DqqWe-yz z4H0(k`|!qC;M45n)bH(b%lwNd$pcJ9?VAV+QQ$1~j+nl)aKTYIL>OX2-QN%`G$m`=_ z^qqs*VvpTWhvcpC4+POGqMA8?r;_D@kRz6u7hz*Ww!>9U7dJzs&aB3mVTq>VdHLyY zxZ?wHcpBuscUW-Rb&@+Fp;&DLXzBVTt5D@0B)HR4t-r8X=TEzQznyDloNq3=%R!`C z?NE;INNwBNo&^o)?7oshI1px&4rDzDJVYV@=-*Lq(~S)A11sH)B<6Cr*n{GgiY!Xgsiym>m7~f z+DWnO%HeP)4!gxWqC`-8esMw8d=0sY;S;|(k4}9WT1>#CUE3AB&o!?nQOM}8%=xRl ziH92aJ^S*Ym=GwXypldGY|HBSeNsNYP{IMZ)FON<~Kf!3AT>@~R@N9=L$W!t^f&=NN_ zec5S71{O?qrDr4jX<|6g)K#vc=-~WpORy`W>Y{(Bt!X`$A?1W5Tf4rri{_<1J89%H9uLZj-Ya1CmzHrbb-sSX9@VhsN)lRlecYoTY*Bxc%2zsoIjp8R!%Q`Z4kHQf{#Y-7oOiyL|KPHBx6qmXS|)3r z>ey%Tu5)Y9FVwI@oBy*2d@-s*uc_^%5%yw(>tI`oNa1Xfu`h`|LPPE5d+SR%pjmJD z<>+VzzB?!cNQbhxr|t*=0GV7hiFy~ELPJpV@gl58%V z-S49csPw2LKWXWS-B276Ubzd~0nxx~>aMd>@xwWH@9Hy;UM01!;W07dnv)j08X(E3 z&zSnH(Q=0Y-6=L($L#MI+yj|?IwGd|1ay|)Paj@Wy#?3!X?&r28Er!Vcdv=HO+nc- zFt#~KBGeVMVi=v^id0Gvbye@>s9#U+rS+I+??|cp-9&Hli@*MYWk@WN^N792^X}~( zljB7#Y)1#%i>Ip579}Tyyff}>&uAey%&z-)s%j@kh;CO|0>Q2QfG8`|4OLc-_CV|3 z)z_jw4P7sJVlrtAUb1*EWDIpRY^q(GIIRg-ApQO7q;Ru>r_FluR#6TX&V@&@aOy&M z%&t&z;@J*QY<_MErUhVc3huLlwJZ)X_q!p?L{0}ZrEGT3q$|FJtpJv@-Pjt&bB?0K zuSQ>o7%X*8o>b8ZdOqSks(Z+&2p_+%L?hTY0%Xn1Xo**QfQ12TiQ;)cp2?H z&fWxD`g*fR@{B#L6HZyiEV;SPm5osclf+MC}Mxd$HJJMv=>Jrn)ihTu-H6a1yC_^=WqTB=<*x1Ir znGFE{rLj$LExDLHcxX03hY8zo&~Rn8bR4VL%zgW(@N-IzT-H865@KR?J-am7MD7<7 zn0d)rbb@V1Oo1@=+o|O$3OhE8y`XY^q0zQ|V=`|p<}1M>@9n0LkbJq6%CRgQVLp1> zWE2%oV5ZQ3&2DpS;`WD7n`pKe5<1%4(y}pQm*;HejCCQs1qITU2?`$mU)ah^I|-Lu za4E2EvT14Q&@FZtUorM(^mQ_QqhkQ?bW2_JSyX&m7}PHM$TFs9l{|AA!#4(bPPoKr zlf6W|IY~H8^y{)KpKQh<$}J9-!I5J?WYxoy?V(_nUE21pS3q80KmU*S_8k^s)v1PM zMp;?!;@&rZ@dVhN(iPYDyQGP>VxmY^a;ZYF=o}%EE54XtR#ILQsACCQQc~Glk|gZz z{QR}es;}7A`#lTU#hWed1_P0;Pe!F(J9A_EWQ;q1H4pdq3UFMvX{yFZ`g+PXb3E2t za&9hAUyFXCw`?1N7H-?!OssZ$a>i(KeAUbV!Ey&@!@stIJSA-I*b8=mtEy zW$6m;>F1t2Eo<%GKF|e)_IDnh%&ag_48}z`736AHe@vQH?+yTKEASi7t#5|u{Rkrs zy|_LQ`tk;3hW=V~7QY&)@@@DnU@>3&eqf}eq-3lBR6E_@*G?&wKs)fZ)KW9^>E=d2 z+kW-{b9_q4$Oz2;=Ei3!`J0ic0vpyz)+G=QC+mI`PoV>oKXq5{T;?e+ONu+z|HQTN zMP8}ykCyv*dhV2hcWwbKFt>E1kd_5)`|b(4+U8k`& z!p{%74wgEHTkDMbGC>mb zvMlEv5Blk$HuNO9NMLjx%b|{Ye$z0rs<>r_EpKXr?ctYFYDv`T(k8M#Ql(= zWZgeJLck(Q(c-ZT#k{{;Y%=k{tc$o@gc;C55E>dPHiQ4#m-fZ-k?L%BrTBfi{EeH3 zhsW{O7`Af*-3Sebr_q;R2)^9xRz(z%c^5}9VmEku#@>f_;2EfS@Q`0t_9^;l*wS`T zNx+$uuDY3gc-v=Ei4&k8h>thO!3#RPQDeP;jDV_$WGNCj*!kj6d+8Rh0ZWpAF4T0( zAROVS=Z7xzd&`>lS?=c%jm^!?$oaw?;U#n&@{VQ{(S-5BtDEvm&BF*9hjZP!Y^*s_ zuxEno%(UIK-0yeyS3IzIKl;clOES6!Sk-GXkocN`p&&Pb%9r*L89DjjhP^UWIWITi z4e(@d_t_ra+R^(<3NQE7pm8)MuUyDsvYsx@upLbEM+zLXD`(VQXqrGJfSJtRw3HH^ z6Jpght{m%es8Z+#SQ>^8UKKpXfIJmhxk$S52$;ZcgYinPB|+P~ekm9ARH7*Cq$2mEsid;7`CCL%V0 z(jMni{Huq4&Hs2(;gE0O1B~^~luij^%;#(6D6%i`^L2%d#O9J&q~qLpT)jW+xttrO z08^d-fcKk(J17MU=X-a)pSrdU<)#AS!U%xIgr7$#=8~$)pqW4dJI1enRucwQUMbO2H;+Dg8%C`yC?ts@1h?52aMfz zP6F@!C3UT=_V}==wB%b-0P&&RTs80Css<0m5Fw^Bu4|K>8#{!D7favZ%Vt@yr=6Yi#5gA`gy@CD-YPHc~j@k>Krl zM(z~A1#d_rA|k$3PNrJ|Eq;L(>}Dgm|Kkn?ixnqgP&g8Tve?drq^jR+b|6t$(W~C% z)su9$&Zk*3*r&|1pYlqtVICL=*i)CnOQ1ql;V=%xesd%*cM3Sy8+0zq=~V4nTd^6S zR>yhse*Y0Ccruk1EhrrcIF|!k0en;H{lg6+G%WoOIIxODjX(PRH9bnH`#isD?qgoy zP~<&SPTxAT8=D!pOYA>KFM- zdCLHyn6Xsg0O1d!&_zJanfTm}94kf%K+p$@p_Q{=s|iDITt4lFpt(djI?$H(uUX2pOOuaa;}ByldUgELXMm`QP9j z-U&qElS}T;)K6n#t?H`dqh2CgIC`uvq1HRZ1*`4iB*Qz__qGit>6wpuDs-kjrq?ps ztz9>yMs}KhNqupdjr(?&)i9LKtK{^AuYj z+66XKvhY;36;S9*{=hN-N8&{-43$$zF8Xf%Y?h0WQOH)2o#NC ztR^&?Nd!0zsDoRx}O$)TbL6(fIjRihZ#$!U6Kns#T|->Gp{T64E^ zr}Med5l!5cC!>jSKAN+uN}B5mYgFDPAKuuF)Yqys5G#=f2|OVKwt(G+t@-OsjjbNa zGp2xpniszXoCW6~4xt^5Q}Qiu_O57rXXjgM*{;%B~c zT6Zs76-0zCjXs}MOzjm%ubqwc9I4Pa!8Vr%!g)f^YbKX3$P^y|m0_*(-PjBH?T2$= z8S5OoYKrk#MlGE`|2`!*_!F}wO6$^V6>0b;u>7xq6}x--FMOG==^Q*$BRT1BJ8`4+ zzBd*=dDlcS+KESy-!U+7xZvt{r50Lpa24r{k(6So6rD|2Sm$;$;oX?nfFqT&T9te3 zw10Plk+z$(F`oOrv0gVd%ph!_}N5~;)b!G)71t;-mehcV_whz z=<~NW1?f#K6y9im%>nE=Yej<}AslT3vvk3r?o1pag0R{oM#7C*S_k%*97(Sci|1}z ziiAyr(Mw#_Wk$wZ_TLi(1cJU<3<{i*0?JXE{fp}9w^zD9e-+)d`oat+h=;>JrFcrR z>%2U@WpH&PR;7L0DT-@u88%9n;@R6yIZy;@i}44$2!_?u{TLM8;usek z-I93yo+t5JG&z>(*bUhw@9>&eKrmi)1^%hWZEM2rP zgd_xa2*DEE-QC^Y-QC^YU4y&3dvJGmXK;es0RJTS-tYbI^;*-zFx|ass_N8{+Gn4+ zKxcUR=*#+H#Efre%e4?fa;`f;7~wTaf0r{N73)L339A-zd*#^=ig-)&K4;HuYCN8n z2^V(4CKpA@o6nF#J9yY8x2&%<18yUNMvs4BQlD46Em}e4RX!u&T3$Cfoi1u-^0xY< z7G?uSAud^-yeIfKaT$Gc6H@9t-isX{BK6)2%39nTcTOEfct4PsEd5$&{EU|!8nS=m zIky=BUG3fT^HcRq0l(05H3%4X_N_%3r;o+LqS3VQ92FB_Djkhp zt!&%jL-df=!bg(D1x9SeA&NJjiN4Nas6O*cl|4%8%9MN{?cZ3R0xo^qK0k~$iNcj! za}HAVg7vQVy!vfA>OTjS6Il0hUe=O)Iub5HmebvLsF!qA!kq>Y!(^F@xLaCOSLnW^ z7m3Xl&!S@;7V>F%{;YQ!i2##LA8|q=WT)F1c}nHx*TzJ;I|QH(pbiV2)7_e-Lg6~& zIUgcoG z<=D4T|Cy`UX4kU?_w}yvwt8FqU`GRLR$#VU;%NJTFRC;oRPp;xwHxC-=@8784&jv^ z2dEZiuS!1qZ%s^=j&xX)^PsP&M9Fhl=rvbuI9%w!UnwY`>2!w;lYz7$&dl#MhhtVi z8nqvemmG?BB?E~E7HPMhQXMCf+xbgtbZ0}5zqd8Cs}6-1TpsklvVPxr_U^)-p?+-z z6D2%)q!(_k;x*GUBX9UR8K2)gqUcy2Xn%1eC;zRvcSuTV)oI|7ozeNz7JQknMbKM? z7b|zw+abGl1)i?f5#l*fGeGj?V&P@;}I5GS8v4^+F}vAoBmxQ>QM%FQ+yZ>S+J zJ{@awLI<#>Ff$l6zWeMD)0yDGU}wT8SYc9P3>-{ce0>BeQ_iG^?44@+@tr~p zw;|r?bt@eW?Z<2u7zwGYk1}uH*}QFQ*M$K*t~}b@TjiaA)E5-NOEnZ|pWnu%xC#Q_ zCPte%Ab~Cy$j{( z@)bUxlcID)D7+`=5oZalHCY*eUTMi7A}#@PIgoqzp8g^24t*;!Lca!f26fR3TAIXm{Q) z))9>A&i;(Y6jz^-HP!c59EL5=6#H(Q9FNz-)K6C1k56ln<<2SH_Z#^8#;8MYaK^G} z6d7!uA&EtIC1pv_7(WEP3GJ-<)^6P$INC6_4(r{K&YtXvU!O(loR&ly1ZC{Uses;^ z5p%zHJbzE>Q0g$IvkZDDINe~SL4Q-a?{Yj+hTHIC$l%25Jxy9TOWRBV-x`=R8zv*`@sqUuQhaf%ex%ul z6F*f5g?mn!8tf9tw}$x2RfObpR#ED5hTMGdGT}o&GecF?dHzZNJ{UFd4eUGu&DQ6!om& zf{mBIk#C;LL^%1D@9gIrbiT6S955=)k;*F$PKWE6$TE2;n_z2Cqn%1>6gWiFY%zO& zhhesFEp`+Qmoe*XH0!Syc&0Iop&%kVITWKd!Hb8%|Ah=ez?f*mi5e$De%^8|@EXI$ zzSGl0+h-)?#E7X##D}&)0Z(N34#)G|0&h?{Rr)*==J9G{$*$~?<7U-(HFduPQD4Dz z8J%l{?ngi2sa&FMwAU58O{KH(IzoskPFpw~3X8$R^;(DQ3jD%(qR6WiYxT$!_=_vo zo5$w2Zru9Zo0VnBsS&Fs+WKa`PpYnpgDNQg?@8Zpqed|<`mgea?~Y~yE;icpNyU>{ z{&AXE{t0=|sH|~E+_)V6@p;$4YDfV*6B2hNx$>y?Rk%z}SsfV`11q%3853Hm>kVde znpPyBi)}={HK1qPrT-EB3~yM1CWD;~md_`O;K66)1c_yQkj< z_;&KZAn`_DywafEPkT9N zq(@YEnFZ@>b2gtylLK%Nk=|G(r+2ak!l4Qg9Vh1P5K8$Ch~PX`y?e7#Ezh?A)9g!d zyY?HRJ4#2Q)7eP3hi+17 zp7WLNO?3sQSLU`MLf*xYUm?T&AO>vX=gJ7Q3? zK2+2P3=^v4<0=E;r5|WVHcrJ3#}j89yHf#KQNMXQvcII@I$9q^p2+M~Ey%h2B0M36 ztaH0H&!hTAZ+#)SnlkzPA*cJ51IxQLR4BhXmBj_Nk?Mn8XA4BPSM2#6pqezegFXYJ zi4u@f!+wkVfXlTpPr7hl!*ao`^3FAshJ{wU;u*j74)?uK?Lx<%yprZsq-%Kd;Iu{I zMrcsd4YOKPt55SQ+k-_><2<4UP4H_bp#Ex`N7805{w3k`((W~Tt$)=i{|2Vg)cYOY z$)pOPo(VWsUh@lGD{`j4WBZQWS^t3$2@NSmDk&wkb`_;PM6GF5IV8g90|~BResK+P zG)RO&Lb1CtU7^OXSgDa>oi@&s#Wc5zB{VR!+hqq<(&}_$LLd`EF zI#1v+%hVg@Zz>~&KZ&n%eW(^e^tiG3%<}p?Lu|AsCK)_0QTfdyiiun?Rby3O8u}`1 zWM7pd$2nI!WU{6DEh@p}op^U!spRg56uHqEJ6A4WN>~J((Nbd7*-w4d3rRqrprX;q zbX{=txd@Q$%p)tpXv@GkJJYk}K*sx_bJ9o52y;)N3z4`Gjh{0rvBhJ(4byLM63ayd zO*c5gM2PY!fWn1;h6h%5f^wWz0i4_;W8LyQb?oo23YUQ+oL|}`v6)>HXY)8)CU|Ca z6?y{X&B07KM^|`{y4Rr_b3FRsS&6K+FBw8weZB{6)*I{5`EU=(;N`E*KrT003NmGq zQ}Hs@*AEP0(>C|d!p7^Ph{~VZlG#9}KzxB(3ec;X+^6-o5e|rgENlq=GUjg&XR%|I z)_Q=M#+icLv*AmtZ*{V*r5*r{rc9lsSQB=z9Mv93R`99hNI|sc1B22a%yRxIqVH-x z*+%=xa?8utcgcpGqbiS<+cQZ469tSeLTl@^fr16T`Ly3~D61`oSd+(iAMNPAF(!4A zWxB~vSyuCi532Ddsa65mBW5lscfU@}^i%vajQJ15dsAil=@>;+0z(+rOqTkgJlb~o_7yHiGbq&Ak%65$nJip zWT)E=PJ}_Z^w5!70ruw7SS0uo6gShOTyoRe^jCmD`*||q)+5kYH_=_=B5CoQ)ck=c z*uvz4ZN*+tYau4#KwNBrFS3ZFAhIE_j-|MMnRRccRKS2PG5bL(FKnZard&zc^js-p zQqQL`4ecB9bUJppRFuand_$ea)Z`_){Z5QwR{ClpIXZ6}+nOS4GIb2mq@zYdx{VHX z%3|wbQ*>$?$jVc z=4%4-SuT;we3K#9;X)w*&#tT*+ea&bi_TkiXMhDws8aE*CY)N}xq>mU<7W;Sj5$JO z8Z*!;c|L32>NMhp#;4Y73G=g}jc=#8%yJlxWe4oVhPv#U;a8}V`PB4u2(o?hQ+YGH zyZPKOnC<&l*Tk|W!r;vv;f&83HY(VW()qKdb`9dY+JdlTh7LQ5?Q;bh7>=hd4!V`$ z8xNXCE3H4I$#LO{fug&OQRAt%C=Vyn`U7i~wv)Lwiq6umYrpP%5qs~pixv~&o#94z zo&}!u(r=qx=sa$*foreB$Au7f9Be`C=WsmS^h2}S5J+K!L}aATs(JeLP|6F&sp;S& z&z6VW6XE>(8(8bn)7xj~;mihjsT#Ug@MKqE1*EaqSVD^7dWC2gOeb;+Z`5+{7dxR= zT->Xyp>LJgatFYJ9t0{zoqtUbuIxFZ)M$^gMnMTnx-ht$BeW?tCn5&!KG{QFR zZNQ}s_`!`ca>NNIPX$VLcVm2Ow)<~m51IJtOv08;RAQ%LvP8zdMoq7?<(|##>Z_(S61jbMEE7UIRNtw>u+sw^A{%?|u&5<3_ue zKY+ETD!_}@+4piNN9ugx$_4}3Ex__?ABp4}t^eYQ0p$j|R1$afT&+K*x%u4sP%x8+ z_knVfnWtte@?vFYXlh*$*U!~)Z&kf)uVG`p#?6GUwI@QxQ?5ZN)OY!Qiht z=;PmBII~X1^$5YtF*>s6@}6G5cT?&JiJlMMmS#KYXbCcEAyE!=hNI+ay80l&sJ{OE@fi!qXxvf)^PYw21tuf zWrW>t$ztsZo{Z5G}A;g+qjOjN%lgKFhA8_+#uMQRv(;=qOH#|>G3bIFP8+& zw5skg#wdfePtm(zh9Q=kBYyZG*Vt{ijJ1G@>=_OoBuasq? zP2-UJPi#|X5OI2Kt^JFJ0x%6aY3@^j);stwI`-hD%~9a%$p%A={|IR7VcCN?tCO!Z zrXHFKZpg){d2nKhoywOfgTdg-3+qifI>tZlFKHkcT16?nEfR-i`R^6rLB+EtPs{VH z!6-n|6d<;;T-wnLvYT0GjGaQRB(o026YXAZT;V0kI_g5HJO>jo=P;jemgg@HHpk0 zN~tDW`krFB&`y6G5aVXi2{+}GIeM~UV5TA-bWO`U(BqG#VRAj!E$i@$AKhmj4S`7$ z^1HteOZE2>P?5K0?{uST_*|d0@Z~bFBuFiuw;(0>gtX@cL1*IDS^IJOLuq#;8VBF& zc`FU{i7r{k%2PQtgD9oWrWR9RD_}O-T}i6j#<;-QYyy(Urq}2~Gr3ad*DWiDd9zzW zkiwRMD1_DGLJ+x#I_!Jol1#?{Lc-?m60U@49c}w}si4X!+hiNMy}q#eG;aD2?ayA1 zhGQbI)i&AOV2bT>g3>D_P9!*O#@mV&G(%mw#pQkhwi zmmNPJnkef}2Az(3PVwLlx6^s9UuVB)XI?{H()$&Hk!zGO9s8fAY|*y8 zxR{A7wzvT1bX0D{n*c1y{NY8&aF*x{9!D5~vRTvy$+XQfMB}16gFGUw)?3NXN=)*8 z&yk@K5o5PTVRpPf7rg%QEIq)%!PS&=z9mcCnN7kvxGiGthNf3DH8nLMCbdy7^F)`c z^v!;l(|xb#oB94Q{{q_6H-r{ppoiBDc-{MQA0q*yCn3)IbHPHU*8}uK%+mX_mHax%sGgi8Q`S8knwgn1#9{U4Y^izFh81g zw5w?9#QaoNCJ_xsB3|3qb3fA6eT;%1CfYFAvq}E|5DO#Vq=bjbBxpi!U6&C1PR|KW zp|!XawQo`GRye|_>BBmpq9wuO2dG5Edt@1+<{Z{6EU)V=*On;bC)-c`_7YoP7--OOA?UIQmqU1!vB7v;HyHDZ%;SV`uel{+^`U+6W zW8i{faz^voE)Hf)hi7=5WGGes5VpvEHusu|icElqSh%=rXyOMQw4eG#f1=Se>YWwp zy{5!M1AXy1dSlP4MpEnt@W{jwrz7s$R)+3F=!qMUGdK3@o$uF1bV!Yec|e9^8lH~z zBxN-o+uguTVtm9CL(kMy42W(xhg4jh*Sy8%#8~wb01(L+jtZ~XFd9uHtNTO$0Kym~ zrKDiIKHov;ZnQZa_s)i)kbEf39xH&JZt#A6E>yax(rAWP!LtDE#F>F=qpl)$-5gFx zlw*IARE{=Iq{C*?PF4cbh&MdTj@)kq#TxMQ`Ac}EeAuG|4tqYzY2-SQrati~9e%^k zyly0Dk}j;Fid8PDon=q^dI&5oRp#e<#H1~A%RhRvXn`U=Y zmssQ(u&~8f_B%4^lF(MMr46;aU~J%@GQh{2Y1{T>%MPu|E;PeBpRu-RUK9EwDdwqf zvoXdxeog*pPXOFM=MRdXrXDzx!+6wjMzww(lK*)tQa>v<3VrJrveIPvDJ6m7 zTrlZJ_RQ-J!6!83dwAl>>R$QN$od%r2Mx#u%qDsH-LNq6!=CK!T0knU%njt@K?x(v7=W88|3|w!N8WFN5=c@;lTBa{WBp<-+0wl;Su_BH4dQxhACY6Qb z|2Q-t&?Vwm$P)TMn@QMLC6mw@nT!BOTZO*Opm*>oW7eNZ>s>_!e}GMaet$3#SFo~d z&(jtqGIA{Wf($ODf{l6Bf?>weE6f647mL0}7xHTqq7ZPO^oRPhW{?@*yDrrD$cy~z zzo!{t8)6<_jay^IX%Dg)K19KM$eHZ-0|OodNP5h0F@x`umNG$&GI&aRlm64RzwHB^ zpd&%hBRQ7b{y4pu8RN#4P-5@lfZDOy`bjoOAAH1zKv z=SV+zt`WEY z043&*ngs12K|wiRc6&-daY21)XrqibI}S1LqkMc`3trW>tawBa`RTd5z5tX| zL*GD8xMccqLa2?O+n@gY+mly;A3uI92r9ztQ-G?gGg;>e79Wjg1d%53&a=WY zX=f!dxa`ecy!_qBOR-ivxqggnM*=}7ZvIfW4L8PPZz?Fc2?`b84>xvYy!V9W+9mgww^vG-zLV=ywQYxWoT#w)#I-EcC05XBKvAdtISgkOaH zPmYL1W0UG5lM;hpVibhTz6ijrdsap*uB2*OPv0$x{4kgMoY!hZUX$`i1VbamO?^*B zr}>l~-6q-HfsBzSX~7Lr+tFL!&}r6sx9ARzXkD=h+LQ;S!**9^&Mh~cLJf*-47NKD8q=^nO@0@8iVMX*vJhdcXne)2YMjkj+(;u}Pb&sYw$TT?=W zAQ|+c4R6Xy_T>jw=2vL7#h?3Z7CY`~!{V&O3|gmNsFZ4=~W%mZ48|tHx1#$lQ2`z_Xs1|Mq+@a}D+$ znk^T4vixt!<2(f|GvO164NTt{w}II{hvphI)!`pMqo4DX)t9d`!3)+y3oulT9bKf| z{xGTW!R~ppOIxhGrfH*P00W^$dL-}jzk=j7$?8~$9=FZH>MY2Gg z^gds*oesK7hv4N+!?^~&@y4xz@xdP%%TD0Mi#D`3NrrFF#;69#N_tZsa5dqb1G&}4 zb$6?R#xWU^3uTjE&ACvhGxb$8HP9C(L9{o>BaP>4a(Az=zK`1s6`5^eB`ft`ujCN? zU3^A|`NAr;nBqP+t>8?AlSi%XT&;+`!Ql9+oKeBsbV}Zs#olg_3wJxDfuAN{H$Ag^ zzs;0nl+D$;87Tvk1z);eOV8zTPiq*?-unE5A-0OE2Z$CsI5Iw=Mbj2{LR|Hjs4|$d zu@rmvrb0=zwAsTNbX5gxkyy=qzSJ|18Cmx^SKv-P9Su+*`6BiG)Z6Od`wa=S9O*6R zmkvSGLgp6LB5FDpGJ%039jKP-;#@$V3l&lFnhN#y;ko$9TI4sA80aIPF1{LEYzH2$ z`u|o_x$STZ-9iU@{?mQI{Q$@nYruh0ZLE4C0}TyLi3iF$LCG9Vyg1!K{rV#7E#t>r z(D+~`r&Q1~(!e@ge%pc_1I1td3K=xiiTG_MXDU-Zx?RfxBPA?U)*C!z_dC*5^Zndd zGpzaOOtX!U``LSl7?lRS?&MHT44~)yl(R%T?Nt@%(60&mSN<0FSH19E4K7Eg&2~ zPOs?6*Y^0lAf|P8rhpse#Od_2IVX+DmxKY}7yq><6H8375`8kho<+?1@^_6E9<7Nz z9{EqQd030Sp&J^M#M$`mOr0x6_|5=Um3^l#fvHg{*!_nBX4SdzZ ze*K~dn$H`D<@?TCZ#)6U_3`)%=hy!1wSZZx7e>fDkcR6|P}GM|L`7Q-7D$^dgUALh zXO1i)P*mUcX!4+p|4c$tGiYc9Jo*um)&^ofM!Vg3@3fg1oRB_*!o;|tlB&APuaX&< zB|~FnGTe*h3igw3$Ho*)`!MUZ{)YuH#Yn0oD75Tt#X=A8cWO#XCzC^Hu>xg0cS7Ui zQ8ky)1=?VU-0W!FsqVjhyOi<>0f!Se;pWvx98&R`G~vk*S}LKt_p=Lh8_H*?Xl5Kb z(}Mt^g1?hz5fVjDmt)kF$bq};sfakgLN6Z{@&qD28C#Y2QIaP&_`DJJBL_h=9ec;< zMMY&|?$BM4nxzW`IH+AeaUlL@CGCcdSd*^y<~fPu>`)hzD+=6|DxZEtO>nc5PWhw@ z=ztSikB!e~?KlK=FsjW-1`FBXe4!bOF?|+~=fJZ>a;c1P;Xq*r1wk`pLLMn8f{h;x zhn|le8i9y*&RyN>nL2lj*y{;^{IR}bJ+!K+ec9mzd~iU+y_0*)t1eG47!g$k+Qp>( zETmIOpVh^cMb9c-fx*DEd{(x0j8GYeV`xw>xx(#$tLgK%Mj`NNl$rys&*#;H#U2l} z?mMubo97SLd6UrEaN7dC0L!JBGl1A zj%IH`&v3y3^}%7PWh-3c03^_%yT$!JN!D^zkeAWndTS@Y=10Zr?Hew(;vu%E0lz0m z3VBO_!*2t*jxVwU`1VPj%<7WRyJaVH~-+>+JP@ zWM0HIH_^EB#;URW;^D`&bSO3%ht&}eq2V0^VN7Ey%1*SI7OFo%*iH`@YrC6k%zH16 zI5~;TRL(92+~YTKXry8gt<1C%zHNbhfV-kptBhcVzxXLX(W})(@E{TjntrO7*!i@MQFHGgQYfm|cis}@VW z^@9?AzV-E5@Wk?ijfj&3*Tb9YBw!1NMAb%k1--MR+lFfG4UXWs3NL*rjmT|w5F9X>Ik>lE|13?Z+(pAsKj8iB&Mw~w zPyqog16-=ye}#`iVAR_AQ@oHk7t}SgNC{hl5}iL*t}mpzJLO`>QInlV}-l zlzeV!T{0X-(n+So5w?;#teZ&mF_|fKm-^|5H-(^5#$Yw{(4n@*EKq0;4Mk=LYr^Y!B83oEn z^{FzrlJT+S03RQF(A(@CwR9`xta94ivClS=G~Mxq=2~Kg&2z@IS@p6F*VsZRC@Q8g za9+p1WV-v$1?rz8Ge9fTJJP;#B&F`@{4;GO8cn8f3l)l`g*Ku|_{E}$@P&gqCqLJV zz=VZG_GwzgD0v5GDaD6{g%8bc!o%dh-d)8B7A@!0H_}3L-f8NrWixYl*c#qRunrLG z8Q4U)`N6uC$9_fQ>j1^=lkA`~_$^%t-8CT3C>3LoMGPaMIVznt=j^>c$jOZ?o6a?_ z7EeaGppU{)-_X?B#}dgD3;}<$?T4$2q|#?Wgv*X&pv_(t!v$Y$G>Tm% zGOr-B?Ieni+ESSS5Y%COD;t-mt66r{c=S&e1K0h{&EDhHp3wZy_#P0H`%g4O1O4mQ z;Wnq!@Dd?VH-w+YVg0u#k@so%aG2c>@)J$up zq>fwvXB>ovuhoLg(SPIpM-S@vm+K34Xhv+U7yJ479S7%9S^G7RVFt(yvjN9jxH(KN22Iot z@vu`4KnyjA_#DVN+;ZmYs~r;=%t9ORe>H=g>f7@v%}-`4aeaM#IhMba(0PJn(LZ#f z+Tg^#L=gO7t}02FFR+K^ky7$P7ko_90z1J2KIWR*c}{@x)k$&xbFlNkn5aQ!6KQo)F{m&QD+dQp?mvk!iLe87 z!*xy4a9b6YRyDKBsO9AIAk@C2z#}MhDe43;{O-m2Gqc@RUsh|6F@$S?%E8aBy%&JH0`kz^kF4Y5KoC z7pI|KiK46=)61C|kuX9&pBGPO3l9qm0?_)uD)dc7f}7R&T=Y)We^sh%<59mjw2;E7 ztI|Awwm9**L2>1u?0Yosj2gEAWpd?h|1a?Xiad#Y=q^0ZP(5qyhbP?5aRB6i&+=cy zPbf)liz0-%6zo>{T%nFKcDZa+rWR7xo@}Re*J2v~ROH&e(4a5#FwS~_?!Zco<5+~n zks5Y+7RYKs#UrBRRT34G{7y%7gP}y8#Fo5>UJ{X`1olr5AyPwm-U^wYQv$j5W$6d? zGE1(L64i>&0jMfgZ{o|trNj0w@bU3+`^L^ZQeuet4#lj$JjS5hC-U##b4t=e_>$Iv@mW*XC{}ZC} zlpsW+IPQ<#HiPul*XHoj=ApvKprTsC3>+LBqbW2oQBsFG2k9VIQ~!UGwvLkl#$UD; z%2g!((8_{DO7aLBXO3qv4PG|F0qq2oV026_>%gITSx>yTUJDX0L1l4ey8>~E8?$04 zD5xKgv+ltj&%bASI06F$Z4EAI&G)NRzi-{2M&0cS2$6tLWH-%N2RejM}u&msR7*K7TwiGH&p`I99~#2!Vqb+xjfv_ z=JHk6de5VR>`hQ6fVvG;SnbgY;atm?LkZ=J*2p$ZB~D9_D!elsEr@Or(lH!rj!^4- z|J-z^qrbll&KSBfF|J1O#6cSVWFVlblh4C2*z{|KwWOw@Z)V^V#-6qm>rh##hwaf5 z_L8?+k6g7KrR$Gq2#p8Z{!45zK46G0F9I?} z+4GnC3zFx0GdcRR#@Ul2HHmq5->vlltwihKB4&i!^ov38<0_)d9vB5Wl?lM-w`Q|m zq)#WDwlY!%@Q`3q@hoWUIH}^P7##1FHBwz!XoC$jO+5FFzv!5lm~48#Sb@^Y{tV4- z?k+7}q4H^>(Os#Z9h$lMvOCkpb8ne-BKhc$3bwYxA1zXijGkjmKo*M9PQ5+<3}@UG zKd!SCsXtyve&$vUu3X#9db=Rmq@6x|7MD<}F0?aE5};=MP8Z=*C4AIG)=^jaSqI(+ zUh7)P8~2rd&0@;vdDp%lSErw2Z@%KW3<@V*#dyF*tl@GkdzJcN#?VqgpHc7O!fpzi zHz;Wlvl8TKQ(ayS?C6cZ9a#}8UGKj6(Lh~a^d3=HBRRRk_mNZ;uNJYC6baf}jZva! z<&nM0qN4Uj zPw4$hwB1a7U=y&ksWV&sezfT`#h1`%{>V=-`@ovzCUA4O&b4homA;KJUwcis2*TM11*azsG^2nr+U#u(P0HuP4 zr>w*7z#I$wQ)Mr16r|`uiLnPBTfN)os%+=pDb$rP2N^4I-$6PhkknO1#@Ada2;71D zvll0VwGM#qZuBEA=M;_?#3+QRI;arXM|WlBkOBqE4Rq;qzcRb#jOpqm%m=R*1cZ=7{V)N&1v$gNhG0RI&f$6!KNQb-jTJmb6w z#aTR|%gZHkt7JWAzv*5TNXlr>*|RzT1*^srJD4<{E06cgWHoT#eKFUlag5B&T#tzF zGG4meh5%=BzPrDXb!!i^yI(D0wsB)HTC$U&$MA{+@BL1YWpiGfVuLxKm~XQce!Kim zg96#y`>_xB6Ek2fCt=4QRMj8>Gzb>DU;e?F_Y=r#fzo$DUiXKS#e0f+RvoE=5ibzY;Hc?1M_tr_dpIRclk+mndNhe zb?#TL37jHO@z5$JiQOd0;_=~e6L_D;sQhS5UuXsx2hoo;MUrMAA-P5T`$1NePiGR& z!iu?S1El!KXuHU;B60@S*1^!S<5V^M*f90;TuO(@swe{d@&0exU>KL@M%p+W!i9}F zjIUTD*pU336Z4x?#|uCK=gba?2Vs(@g=!owZaV>~qx`7_EiJS1eFvMIQwJ{qNFlxbjgmhS22ljolY%)F6@DVZt!Av@+vtK+635?eM~s70{z!NY(>sM-yK zg*#kcz&l&z=DwdzDvtsNajZ?o6J>-)D+~8MoY~x1I+_JWt-BEfdy}cS;Lzs^)mI1$ zm9*oPvLE-vBppCttNx<6e5FaW%)1HtIpb1ksAw9fl#Opdz#t0-5)u+wL~s@w5>njB zN&Lv_wKOilBo&ws0z+Du#-q_O`>e$3ihHP%4rOuQhRxML@28HNX;Ss46>#Epd`SAq zH;B#5?x1`%xBVjESa2$ObAO|3a8P#ld2pD85G7k+8R;edk^XwCTgxgr0)m5Yxm z*AZtWO=rt1d+WY9K0QTjx9RRolo<@N%5o{a!6kdwYK|!oas>r@1+BfcKCQkT^86<& z_&wt>Q`VqPSD%OlLPA`M#B=Uf<_j^Jt4k3XPRMxxIo5jT&ZB#VVopM;JuRR{hOKl+U;WTFE zUP(DPoO9ANdR8)iZuG8Q00Rh3;j*V?EE77UgiA$I-kk@o>V z2uMpU{#K#K6mC=&JmnZ*Ks5DpVh8V{7_f!}yj{c5G=kJ6;$RBW6p>lS4$q>@ zjzl3-)#|jZueOvmi%s~+UzGq^mBcL)7fvq|Z|*cOw@{V(T}aTp&FB3!WqNvA9LHkc z$d-O1u)UZ84d@Z0Kr&2pZb*EOi_5A_Z-5>eih8-E<3mJA32OqF?M@_1%+8KkFgJR+ zKX0&FyT5&g!(yJ!6$ptyFZlfFlUCwsDCkgZ+}_p|js(?@0Y2S?MMQ8|WG2cuIx?24 zR8!lv`v^WABEW=Fdhxu6&c0`_+oRkvkkhHCkueXYa69Tq@*4+5%h>?#QXkmDpGMkYVeOugHG@L2CSE3d!>320Tvj+q%_VD+CiYf9SL z**%J|&b&1KBImLJ9@YVHBtl0hud(x3Ii@K&z$*LKjou7)!Fy-85wPdY*a!)Ngra-;pBbPJQ!6*Z>lQFohCppl4vYlN ziY5oO&n2lDrAt=OQ!eSfH%(Q4?)c}}=MfDZY5SgA5*j*uaB>YR`}eEKxa8!)EG~~p zb(62cX;c4QzCW7>2AV&Df*)-i9P$N1;J*gjv45xX)LzfG^>B1-pc+F5txA86ICA4A zC-A>BazV~)r&RB&YNfJ93hCeffKC{`?m6LqI^)kF+9(%?#0@H{Nv%tyR9ton3lDGH zABv>pE)9ATTmIqak|#AnJTAY5xfJ!u`&vV4ymWv>C%ui3TWu0`1U*dg?M|a zMGTD=t@p)LiYU>Pe3u-ksw~VZ=DML_R1e6DZszd$o2m>ouefEfd zenLPn1>!%Aj=-m;t{M!?12xe8xXf=W3@c;(8S{Oqn$8IV0t(7{()Weic(1l&G?R)V zi%H_%7QZ`u3>B#rEOI{6lgk2eCrW*~&d#e%>OIn`G|0|`IYhaue;D1#Y`%j#_q_Nw z-&q)g-Vs?V)*+(y*e8q>g_yRbo2v`Y?=hKpu!O%3#+z1Ex_b{ty*k1}=S{bK-nmeS zC3ScE!z43UD;ajiDk0J^MoQSwX*){JkWgN1(md!2;T`z|M2V`K#x(Jk|AD@8aDa!;SYoTBddHzWa#H2SEe{ zzW(Z|ePF}4iVn)9tB1yk)O z={J0QrbVYEts&6MW%C)d`q0~M^I|Cy{%@!yqOf|GhDG;(d8_baE%vRAfG5l;!M=5u zOWQOTo$sU|Y#q*JH^(EbMq!c2=pQM;V?TQR*a9~A^DyJ|cAihHdt8d*cSMZD+{7<; zY*TGM?;=D$JL~V`G&58Lv5X=J_TNj+Uoa*taiCGNRpidHc-(p2t z%E5S`%%4w(v;i{vz7sHEI&@0U-`or|9}VTiNv)1>p0L38Of9Kod*IuzU@@8^2J8KP zeb|Edv~%nW4nYh1y7RZIhg2Ak!o&uDEo(~mvXmzduFGrMVT&I!NX zX4If>t=Vp9okEo}pD9{M#<~FI4Sw1V15hmqQ+eBA);qmT;<{~akrUP_$Ce~(*a?sDnrxpB!n)OF8MH>(Bb_5?; zFU4`N5Y^muF7d+`5wv z`DRbN1jL;8l=Xv6Jp{(!G_Q*RB15TZ+Pt5Qd z8Ys&9^MfNyp7+AcdtEJQ&T!{BJ8+Rl(?LO4(K9|dI&j#Rs)E!;Y#tcbJt``6)?z4U zmF=vUJ{fK@9l{$V#M8Mu(%jv5#2}t-j|&@s93dFf-r6&IR%bV}mB#1TdM{jrsBa=C zy+P}kJJL6~GPGk|L{=whE8V}zh@(WeI}2mx1~ib$LN&Xf1r&pd|IA)_6rz5^x8idN zW|P`|(S>>B1lgF$;H{oj%L*7<9=P^V5ka1HDMpRICv%p|3*WKvoCi8FN>2BPR600M6Y=`9K}^g zWxl4e)_g~}y&E9o&f2$xIGYSCXP&wB>-#f7UrsxNXpcyj&Vhv)AT*^`Ybttb|U&?8W%2_T;UZD0!JgH-3`~ykCAN zFxe8HGIp}%tj#hiuQOw51NWxN{HkREYvaS{`#Hb5m(7l=9G+!cz1^U{_0#sH9x;O* zOgE*L2>Tt3v{{p`4ENL1XXCAVSe)yxGLu?@YiX~h+wp^4%L1;NUTANl3PJ_nXyuz3 zY!1I(Y;yUQu*KP$(s)S0yDpUqjPbF6NCg#=AG~9&aXHkw9BH(K8HW-QEMIrIlo!7Z z7KHkw-Av;JZaGmbExH``A3k|r8xUB73PwgsRWmsF;U!$0$tc7~I#WKTe(GYmvSu*R z*lPNBsYgY^#`fH7TQ1p$&L;78ScvLKK};AJQgUvB5fFF`4;6J=r~z9D^oU4z(+6sF zuz8R&ES}@f)uZH_c=bl~_13t+9$due92TZEPv3Sy$ToA#WqBrBLs%Q$GwprVe)xpl zD`Gpe{e@rJsl4u^$ZYW@0dPx$W#+Xu`qp!wVfK*o*LIB@_V68{{XRhlklz8w^qw8M ztjWy**ciBNW{&Ou{M_tXq1(6x=XnkAw6^x*xZJ!#b#W{o`)%m+Jn5Oj1`$B3@lbP+ z&Jt$s$dup4SgZpu;&f6lu#Oz*?|R}j?qWz0+o@tLyw6D)Vvw|A%W5Ra)q7}nBR3W0ndq&V{*KZqj&ze))ZgG5qEG6I8Uv6&kme?e7T92yrF zw~1N+Wbw{4S!tweagdS@8!!E_QJ!f00|GGV^gn`uDuI$vQ%??}EnwrYJLZ52Wcg~h zhfhy|Os~Y0Osej)zox2%=p)m`sWeU6g@pXP1JmXf@O5=c`)rRm&8m=Nd*Oj8VdyYL?ue)=vi4=^VK@t z^RM&KLS-zCMsYu@JI+=AYlnH!9QX++ot7?5((!zCA^0Fv)C|N<)DJS@Os8}BYS$K` zh0H(yy{p2R@=qJ>>7GPbSK2;;eTZ3Z^N$}OGz5J>LMr8xhAb&9EpC=Jpj($d`^x%5hRE?rAEyT2Qs z$Ith9|9I!%I8b2cp1JO8X0G$R&YAK3ccA?HOJ{x81GFm-_Mc`?R_fKm* zt~LDoehS@(Njg+@C%=wc0X<0sjP&<6I5=~kd^MniYk9OW-&Q1T>sRsbcko@cWz6G~F zFP3t^I+`njZfmvSWKmLb9PoWfOgNwxT`CJxLZ1{}V&6xzZEk5fIzG-mP;N=Oy{)t2 z*ROFlr&7?lYPz&Dd$PE==;n#MtctKeSvcd9cFE7yt-CkepOT1rCQ|aYxQo?2#XOAo z@H!94>1RA-1#{_eqV4q>QE=;c{MdM;HTVq%M*d=RXv1xRCb4X@J=3wBIxBB%b ziTMdbEd~+m8F37x!_^IJ#PZc*O)o^!V9q}z*{&%F)|&d!Q9_g8e}Oy|LCT|X;?Djf z(WYLkEfL^s)pPuUsU!S@{U<=U!qau#y>xW))r{-bQlhGTtlrZ}Q^3WmXAi<0?rudR zOZKpG`uxgjgLl4zy0b%4gFVVsNUb;T^jTw6Ys43C;?=z9d~rqo+I0V^1#$vzY=IUg zHxKubCRNLf8!zmqS7dhVv7vV+EHIy%6vG<+H(s+!!5kO<-stYDaiktPsqL&3-UB`J zPkI))BWl3}M{U>y6+C>?FwgZC3V(EPI{MW)MpBi}O?Gpd z)2Ep_oth@kju41^anZzn!72nYdYvIkEp=&6E^ITLcU3?%&)!UwktY!AT52@Xk$Vf@ z1l%RDS0uXxB>XB`bl-Un zF~S|itkwSx{+yjO&OqCh#2ODJa7gmCApMx-jiF5H5tpzPpO^o+>m zRzu_TnR*Iclp7c~!mU>X{yXkfS0zDK0_NRsFdSSFJt0f)7oJUPjMiAgQ?y&LYu1U6 zd*zKG*EM^kQ-K~CcFj3U=~u7!v@c)any_?i@njGwrc^plc6v4OV|S+XwJNvS(bRL- z30=Ra<6Pnf;q~$N8bv(|)f03| zEzq5pjaF-fC!b4~a?7U=4D_zdWwJyaiCEh-w^d=clNX1_($@C!SLv*aLnfzSYV)yQ zSUcG3!7eRV_G527CXoa}PJUCzZLOQq%{ehgc_sI?M1|*u@#h%1tQUe^9lK_6r%INN zdS+V(;ZT%W&(!bkWC!X?UkH3IQy<1PI(jdwCD^tmvS@41GdrMhntv7Y_R%_+yr&K9y;lYAPmS`t`7Wp!2vyFgx z!foH05q-XvN?$=RhK6S;^U+_2Upw9a!a$Lnu@6l;1F{7B3h}kPLc7h*Z=Y_K;Q~}( zWbk2${@$I21C%=Rjhz98aLdW7I{At>h}0(Y_2^%jnQi@H6t>+}&Ls0#CJsMr@UQBB z{{VkFK0rjY(d&MxaG-P%)yXRqeN<%dJPBd$xIw@R`fW|!%Y~t3)k(X)y7F*`X;J2va_L?ar=;EOZsdmqRwRgkKDNZYfZG4cvuOAt{V>|Dl3)XZ@ zShtlPAsv$omK|Fhsija~$a(CGaeuypAW;<0&-twsA?IY2-K8YjA(O`AWvLDMqA!aG z$c&cLneF+{tzS=ZafCQ<=GIzKqxb^Ko?!!%CYshHAK^2YTXY4EPSP=aed#&Kweb=D z9#ew9zAq;Fxmf5AXo)**o>B4S~}VJwEo*v zIq$q_s3Zz6ugY;$!a47c+JAxsULax2Ynu)VJo(V%)0GwGQus0KQ26F7RH|3$KIU1^ zdr*T?VPX=yyB40^7wD)*BTBc_5sREzes;KjX`S4?hDVl+xQpYkA297i*R341&?8)) zZ{`Nxyw9-$@lBjuLo6(erIJl=4vl5 zBGh}W%kBUGfT{>y2oZ^TH+Z*iC?1?HsHqRi`qOhx^=fEfP z77e26)Uezj9o8Ctl-UnPzaCq@Mj>o!UF)>%AiVp`PKt@7*b<4+daSJD{u942fP9m| z^bK#km$k6;mpW>K=vfC&lNa#z_wTUn5C@74mWv`8h)cfGR`wrjOX+eS5YIYzZUkoN zc|FGCeruGfjbY(5Ss`myeK(DXo?n*Hvv^TwMVMq!$gE1gZvAhN+1X9rQODsYfkr+t zv~kIFCUOr{$4Cn}gL1JJ@|NW1`6<|15N-xhb7S?J9ONE1T(ch2`uiYOYEW}JJ|!>5 z4tETWEcMss1}v=^=O;Q4p~y}sWb7CDulK#q^2hHs&;{n}9_~iYK$mP@U<*$LitDg! zF}{mI3@hXl)Gcvlz60(TTb^_swchZ|X*nmPPL+SjG8K17Vsbo)D_fxK=a@3D`F6b| z-+g!FOLeQQFvk`|o3&;55ogf>uaD(GbS)LSOg8IOhT*P7;P&0X`v?1zu*zkMlP zWsTtliC48tH{q|hT}{pU^53}EtZyJRe~rV>+z0bH4f9-RJJw-erwmm7dKR)6pY}MV zm-N`hvt`>|hOhbe^lbmYx3n~?2TYo^;X>ZmdNmr>+Hv37du8cq2e4dS!BrvHgAgiO zr1|;uVWQZ&@RN1p=ve)pq0XnydWDOFChP!$%9Ds9@3v9pFC{vzQjn}_TwXD_pn$8j ze^jyHt8auV`Jw1?P9-2dS~qMIUBcu7(yEml(&z1KZeS(y)-&e-CLmD!^eMVT`kq)V z{Pr(LFY*sDUu*w?6C8>|{R9gOWjTmIr`(>CbHMvz0d?!1hX0t)`^l1upFm)q2h_@5 zMSaj+!W!01gnjXml%7D_eKvpA{>;?H35*0cOl4o$+7SP+$yAzRIRMJ7^?F*+1(Wks zb=@mW$x5C`u$JFf{CB}#8_j*7oP+Xti^{?L4{RA1`b%oFXyXxW|6#TNF79G$v3cYL zRGgt6C113N|G<+P`F~MCjP%s@gNeC0lA?*PeMTJ?HM5m;IIn|eta>bJR`>U{SA_r+ zF_Af2DLJH?@ekCx56wC6KQ%TM2b|zOR&Q?zpjT$g=P?EVDPC*46q%oI`sJp8EKCVx zF+jzs>polY7srfikT1%{jRE_!6b$5{TBxZJ0{0IA z$i2UPaWTXD=6pL$@^6b`96}@b9;TH$6W!MnK0qf@qsBxStiQ{aL&}67_K(Z`?~ez* zk@*6z$%t(RXw#3wR+e?o=J74>=YRj;{=4SexyA?o{Q;1#dH?X|e~bgUFXBMM zbe1;fg(sUz@LK}Em~&Q8>Fh^?$P&i?H6bRYs}qchO+n#L!tq^wce0iR$a>}|xdh4g zbB~wA&+m~Io1l{JhZ&WL3-Qi0EbGznn&9y-%-P9OV_R%2H>f;M5bFBQ-%7bXFRLTy z4o~H7XwArdzBxqgj9@Te&W32Voq<}2t_?_+0~JeNYB=o;VM2S@3O?+!+y4Gw8eMb2 z-8!e4_-=t@#el7MvFRIc)V|4WK4i2k@;{!z+X*!CfxIn@9U_0HIo<~avs!55z~vrv z(HLou?*eSpkaC6Buq5SmAIm)K7HfdQENZtfkOPq^Px$syzK6;C$(ZNGkwqussB@vj zt}y25PogE8Dz#?#!}6Z0(-EoL(R1qzvQGr)CTRi;xETq|dL5o#j+)Y>4hp=@2a4n^ zyR`Egf>Nv?P2_kKb5GEEfUw8!B2Q|qH!I@?R3`~)6?Lj^|08A`c+qWse;<#2@jb>7 z%MNbm0w!at5C*i{C_M2V=>VV4X8C%TG$@aiSE2L{@I(gu?$io6MRfi_biRvG=8n_eTib%8|oP9^AAWR5E2r4A(oG#9x{1& zmakiN3uD@;rRbHV_H@WKZCA0J)$zGmRcyWUX59$ZCUiKlYYc2mm?4>3-TK-TLeD}c z-|Tsww;SeKWewt*GC>R%>25m6HoZuI=zdu^led#c^>ksmOM?)Ute0!Ddti|aMRWP_ zq`XA@0w{vx$1BWiGv!8j2*QXh_c6Cp+w~AZJ=wX=V|R*^eTon}^O3~QhNw87=USKR z$EL0#((+_`HJT#3s3qJEM(`f%@&{?|+OAJTMUFyCQ$y{z-|4V{5Vu5`@cIm>Pze!_ z35Pear$Ha@V5Y9v(M%=T8ggCMX7tLb?RJzQCOr9{JR0E0g|Ba^`>|diQAsa>g@2qb zkAfk1FuI@>v)k=6+$F}7(Y4Esn7Nnb)7Gibfdg9NxM=lN2Xio(#%SbZ+;NB+Nbl!X z1RP^6q3d<k?( zC&P{?A=pD82X(K{ zWVaOZ3b^pO4V(WRiBWIP)Hyp@`01G{+>?>QauqEj^_cI98?v17POgjDJD`wV{_tRc zd$iZVHz-QR#1G+g&+PY*n z7C$RKDT4J5LtrblTTe{nynVl)%6h>EmEbKGf+kvuBy3RilWh{KW_=Xb@Ec(dipwvF z2VRd)=*!pzE}w*vrw&*4us0aGJX22M0^^ zF?ICo8#yGiZ7+Lb-#4Z&(w*J?5LPPS2D9>t1#PCI>U3-`gqT;_U}2X=84d4^)YJEr z^9o{DbtwLwf@07+fJuL`439!GK@~_)2Mh!zvA;8ZgjxV9pV?kNZNYlbtn!f_0%Aiy zzp}jZQ241wxYUv59;TR~QwUI*z|Dzwn|wfSXjF0KHJ7YVj1!CuLb7{qXX%E!7i*wi zL+3BVzH302yp|po%GL7-rLRcW=+=i@~l{XAp7gdZ?t~XrQ;}d zkM76#^S?9rOw5Sc;?p}#jyeCD;2-6FCGiFrQcNI}Q8*ZuS~+^$EAI*(Md zv%tO0Q89$_@k6&$)8p!0bC|V%-eS0xkKhS>9^zZA`(<__F@(Ze+FRn6>oe^oP-a93 z>gU9&GNh||tCOy`Cumd}zyYw2ulOP3mN_=7H}aK4=d*fLJL=zcgi*8vV|DAu^J6$E zEKN{&&ua>nOrAxsjL%X2U5Xrt01}kH2-WzWJIzZ>)1vFrN@@^3(b!Dm^eWT5BaM9g zUhiq{>6sMLa=#wqW6yLQ-Pt!S>tq>qOh7iTf1(Kpe;za7d^b4GGQJ?+3)6tWk0J_N z&RkWv_B+WaHwQ5-1Uvepgs9C%sZc&V)~5{265Vx#ezl$#%%+{1bdNvdAKhNCW3*JT zU7eI0DPBmH+H9OtJArXx*sKP}L`QK_r(1dImTvK+(J4EP#hVz}bJ(z+>%SWp;>0ZI zo5_qW$M6Z0-^dwzDEF9)_Scbsh!=PJ)MOXs0k5!g}o~MX~kcS%#S8*%M7&E zeIu~C&OWy=ckFgvxcQ+}5r6lnb5HI%z2PqPWNW*ohVVsG^AGDuuT}Ew7}}rKCwl>vFQZq)9sJ4hh3(iRhk?P}w~EZZArjDYDY+rk zLErdlT=2_+*9YC*E8=KitWDh6MRZq)M!h(2t-3qZ%m8$5^T9JQ!_hx>*A6z6W~*!3 z+pxm>+hj1#i*4<}?xyg7H})LP*>D6$ftwcV|IBH87-dK0mFAj!l9Hfm-g!mWWt74B z&30eJQ=l2$BP)ZvC-DSnyko^vo?Lji_Uz_o&M<<3h9(fuzt1&d01Hhp1D<)ZcUhk4 zChFx?lyM+)k?2x`ei}hm@_ZrQ4x~#$_0U0Bc+k|E!)!i}zRLx{ZaQaIW;^ z$&td(q+6@73{=qNwe}m?=Uq|I@y}?iL|*k|eDJz5e8SzlNGMVHR`aE>Fh$YBgpV7I z8yd{p3m3{dT8HRluq||+GF6j#VN0vD~sTHTz}7! z1B@zAsJn3WW~onv9fY?dk_SB^6(!>Y{vgTj1j{#2EYj3?#Z2wh^%859JWY#dOFzj; z0`A*fM#|ysE^GN;CF+85@N;VWtf|pfAMKPHv%pRHLL&`E*S7x|U!gHDsrbZysB(j& z?yk2s&F#k8hwqfarejSMJf~|=c`_xlHT{)K zG}BNwk-**P(<@WHc$4Fc+or9VM!|s01^GJOD#A~Y((kRCFnY5I?^E*`|ImXmH`@uH z*f3^rxNa&5VayHP6sIkCC=<3^+|Dytv*iXJ2zR{vs@Wv=o2rtPeZzLmPJ`=;H$_Wv-JHjOYbKZFh6$2ST} zw84kS<&IHWL(Bcjxi{V1;L^%qC_s^|vgmP=N?WQlo}qlro46p=_^^VL>}1iB$e@5 zQdD`0UeDjL22Rx%ff!nX@o-bdOK-ez^+v8UE0h;)r;rct6Li? zgC6`^0v`nm{AH$jn-ULEhzSApALF)$38|LgE7kl@06~!vnR{Sh?*N82AMe?fR(jrN zrT>(eouB0d7Ve?|N(2;u4x*PT(SR}#@?*uk8>^>#tjZ%OeS^5ok57^|S>tAgK z05-dyKX-uNX4gKeGnH>R2k0%Jhqy^udP#HASN6OWk6lf#@3==h?v5L6|2_++BK>$U zNP}$iWitsH@xrB=B!$!vh-FZNlS`rx&{F@XQ! z77N$SC&iJ1pEqh)5;~@&$!r0e^0@du691nKVu+c%(g;?d&C(0`IWMa(t>a-hDGs+h z^idSxs@_w3`Xb;CbAW)ugaV_;w4&-?Rpy^H;CQK9oL1HR*|l!h{*0rFZ;ApY()iYv z86cCT5A9Q`yw`N45qEPw6G0Q>-7#**30GG*0*#hLf@dEe4 z_WM$Zh31)sFH{!!BRl(#20%%axC78Sr}Xyq6~=DJq!^Z%_nO#yl~#VLsu&C&U=N-+y4qNdXYa@6Idv}!Vq7%wX5E0{J{k_ zP4{VKVF_AZel|&)^8kc|+<9s7L>Fjczs>$^O>HS4(E#isZaG(5@-Nj?So?K2NF!ym zV`SC;GY>y$gj6pL16M=uak6#L=D{R$n%?&^5Led9;(WvDlaY~;aKg8bUL~P(mP(cZ zU2hO5ypIe27Ogk0!BJ2Od%6dhp-w;6^S%aUf3E1;49rzG-S@P))KDl>vW1DozUj?+ zX(yN%d;|>df5j(>g@J*OD=RA{Wn_wf+XH8*1N%v#o13nF3_w~8ux8TEn^P-&5#ndt zP8Ks)#p@^MbtdgG{+q@@*>*l6d@S=f#p^%NAj*W%_~##iJ{WX`)*`pa;I1Z7cs_bX z*rEEze4o+&2!z)vsKz**yc-&ofS69yKEQ9x4& z6qexPVy5f!{V;vPc)nKKrPgKy{6<+T{@zl(-50tYBY{aW2HCM;Oo^m=_$WDd9W8Rq ziL5VyrZZJ)UHMiseLzzDcAG3P|GuMeWVPQ3>_l@Y(FZka~UFx5~@0D#s4T zzlI++N#`OJafVdKnFA{NL%aH4-0_*xaz5|mpT>2!`j>el6Pa7xz>$7fVj8Y;I@c>L zvHV&zIK?v^K&i zu>-LsV4`QAi{=Rih0Bv9U=bbm$3=rX>aCwxHkbJly06Acyam$+7VoIoB$qBoG7+p_ zDY$6;J>RUf*czQ4+Hg3?>)#w>u1PrMyO)f@MkVJuDT?Gq%T=Wx0YDgI)F3G|P${BVWaXxNHO@jdi^UE&xW}isZCj{1;A&79)KqT2E4^Q;U zZkTf?${P&Q6wXdlgimCNTKh&dhlb#FK}6A?tlMi%_f0b9pOp{I)mxMd8C4o(KS)Th z8+1LyBo-7788j`?RYfE-iOIffXj-qHLog*5-!xx28+UhbOk9?i|m{*GgU~cnG%V zMFSI7K3Nt3lOy(UFj3HV`FM()`2$JU-=T!j|S}39jDcF+-zQEiE|Z( za34+-v6laWs@ptu&F5&fuF#cwqrid7KLNeRD z04SDOHW z(tc`-8>o0L6-mdlLa`On6hOukIHIpcxOO}6wSZOK`4xGSyRH4NO|oso|Z?LGs<7gw@YvV9|B3AX666c!vWw)yYf>ECw!Uv|v%fi5bxR z63~irHAN-R>nB0(9vDLI5lY|VN?B0Lk2E(4&Bo5I_m*UA{4k!~S{DyoYm>NZ;Er1N zJbm=5iK#8Y^BjC|EE%EM?dd3FlB#Km zvM`Pdi-5fWi9Sa`DWsjxY$bmIOwZEl`o11~FE}ym8~{Gl5lBgq4w=kTQCHkgB}t*2 zoM*R&f0mw~F}{-Y9borN9l6jx8ZL%p+Oeo|qiY_37LDRhUJW_FRN) zW-;mp)|MF_jv;itMGc%W($lOyg>%;KDR8q_wKrdrI?N1Qr?|r$PR3tLn%ECrPB4?J zZAtz_PjIYJy}Ep%$va9N`duN?;oMfNlh207Xe!(OWWz1x_{)ts<;Yp^u|t`i*U;}b zhvM*-8%~vjy`G`7vLEe;+9Oz><?Ra(6x|A!?H5<+)@rdcA+ds7!m8! z-mHC&9DmvlOHC)0*_SP6^u^W|k1!Fjq>vGR4jM!R%_3!FDR#~#9p*c3ikR3gf)9&I zfAnEixwXO-TCb1YZEjwM3T1=YE5Y&OmZTr8QBA!_xU${V-a$reaC`h?M0YCO6aoSy z!+AxH%QHA^p7~~rVx6UO<|iYq?cK)Op6hmgGiNT?ecq5t zjfAKRfj8s=Ss65ghU5=m%Gf--O75f4@PA^j(UH-quBC|nOJ=(KDEwgY0l!1mdPwsN z*KjW+gT!xkpdr!z8^`<2FA7k#lF6}m1u^NE$;n9om@yj1MtacxU zJ^A+hI~_f}n6$Tv@I5v1zAF4#T_6deI3^NjVE)4Hwr@kYX3}_WdA!ez#SE7h=BI=tFa- z#s+FH4_x$QXFB^~8z)c|Tz%OVss5VP)O62A`oi?|^>NZd6DAjYhpLlaRw(>_#IYC$ zJ^ZN}MNU(u88V;?!Vz|1Qb)y(#U{PGGL`A;Q?r=rp=CQhh5r-b<~06;D<*1Lpg$Ne zK2js4g&w*JF}_+L)qNJ;Lu2$DFV$-^2WU??QGT8G-Psfm56>IdgLwz-SF9`vThN92s|=mMStN0~p*E1;R!PX# zL|=H2z;TJ`IV*2d6?kZjWH&~M4damG;nj8yP4dyXUAxiI%GaU=^+rQx9nDAP9@bCJ z#vWa{+-L~E*>Kz)$(Ypn)h<`P*d&B|PEF-~Ee0UZQmW^3?iud6Ih1kNl#OLa-LJCCJ zp}v)rR3Z3Bze^2CLY)jTv-fMctf$WE=^zx_>AB{ki`yO=7v60;&6BikH?1J4#JtnF z-NyP;q^0$?;bFbYsD6~K-MW}(w#b?c^my9+#+!mYQ@WmU8RZYo?4X%fix&dLjhiIJ zPBYs-@18;gUmW?<sM0$tUmPoK@U@;s zv`IWxqy?;Qh ze>C&0+j`@Rsq5H?aPP_izK-QIWMw2n55$Vv(voAE6SusZ=MHY0p5)lUF%%Li*Q@FH zZu{xv9y}TW2Pm0ZIP$1D?3OqsCLG%q#dDKl5tCsphK50x8#Wzw(p_Vhoh(rPz~WvS zc9VFUR|6)Z>MnM2+daxN?T1d5(%6>V+!esvVWgNJYGjrzo_lTv_N-npuOA&9eJYq4 z8cIqcULt~Af6%!5BRGdqwUom<%bJyRdGJ^u*1t}zm!}~~kp$6In}@D`)q3K-Jy&2jVhy9CJ?@6?I*cOR&>LoX!PdH z&qLXvCqqBx4M0HGf5i1w`t1iQzLMKp9=i3yr}6KOl~=#gZGc5OFpMSG9VvfE+jFDt zAGWUlXuHAgjeRtBw(eEf8O+`mj_qai@ZbY%Ew~cwzNf0Y;s=7|3cK?Xv~FSvHB+H$ z&XayDV_eHZR!MwBT_*sn5KN`pB z2o+`GlDh+?BR2u41vE7wM!b(IOfrn@0-c0?_C7{GI;TnjO7vkN^7e+!tvYM-n z7?T$kbemgVe#w<;-PMjeG_@p~NgE^P8JMil>eJYSZ745Cudlc3u~rAcS}qp()91eSD{sAQddh&7CbD+kq=@&87?KW#X8rtWG3fk2 zSy?%6_LBJFPj&AWZ#4A}VkQMRcm?vpcO1#d$pR;X>`ZFqzN)(3@z>WLK$>@ZZ?9|J zAts6NGU9vPq6d205+v2OwXY)x{pjXS%jaqxx){zW^rdUdHTK(c6_9yF+_x9*SJO;g zv~*G0{v`dt#cU2;LpYf)je!!tHuT;0fI;1?sO~-1iw;a+VJ^2^oED0mmMM?I(pfL^M__meiIQ9!ES=` zv*^vUa1%UUJ3P8rWha_ff-Ctgzd5{>b1Tr&12i-=_$;RRbe={&eop!{yYzD}0~MQ~ z_*%%q!h)99QTOdCLEHDNEI%M>l@mNu0s@-pCRbL#VfGf964TO1`S|z_Z|<11>Z2zo zRe0p4m0vIo~7qc3ZX0rS-;pNresh+WjqkYt@J^!S; zO?K_J5t930rn)MNiG)zd)7es5zPzNoJt>H91hOyor|(AwJ9?IH-YfpI=ky-+Q&EA1 z*p+j^2A?e6Fvuh}YN-7pIc>VWlAeo6=+M;kc0~*T&F)!dchM?@-|Q?F^&_}neM(B z4r24_rsEpZyGfs9fML|&u(dbF& zvYpDRs){-~Sfu9LP2QX5UzUnPLuJta>)y|mbADAfusq`uN0W&#q^ddOoD{Biwh&d! z9(5`#3PNsfCx0Hr&3>nOj$ zozg2ORP)fhlbhzelp3DFXxl zkKp>B{)w#-x>U1&29qTHGxdoJnD9MP6y4GqYuwQJ$1f)nbovJ%#?26=E%%5WWyAAA zoF9z~Huqht^8Js+W7Glng&w(yYqKx@a;i4WV}BDAll59=-fKeA&+3C;T)zjb{F(EW z`GAzXyy?~Py46ytJ5UL@G6_iuu_9VsdmhW-iX~OsH?6>QZC>b^F{J=mBMTcV55Ex* zLb<*ss_p`q8my)}J6+)riFuoiZ?=_J88?>~{rp##UwI`exbK7EKPBcUwcyt{56kRZ zMP`oa#|4%L>E*vUZg0iyG`2qG{P;zLVUEek$(h4HhJ?t?PerQ)Jbr_X;yV_{$tr7W z-vSA!Qw4k45wg*ec}-Q9NWfwEYq z6qsAW*%F^#H_gDq7=eQcl@P;!o_38acR@4*Y+-hXTt!sOq81RD$T)qs%w^4=59N)lDN(O+F&6JANd(=l*N5Q{k!Vf-R4GM-#P_!m9CK&%BiE@OLq4Iz}pr(S3UYuXd z50o6JUO}Pqig%-Ov)Zs_Z%f;i=XD`VKGsNxsdChtmfb5?6&#BC6NhW^Yr51b+m)(B zmM(E&W`tWHD!ErUsCF1y%qZL&Qp#eIL58yAmgWh+ctfB)4X#oKE$2=mYqcII&f8s+ zK0?mle!*(BhRwRSl7bvoeuZ@yMPHQM=JgacQULeVEd!c`>N6C_dJ$W7Ol)(zoV#ZF z_@f=_oa^y4lCX)QEP8S`a#vl5P}m(u+bN09@d>zacX;LY!Y7bq;8;?{{Qq)lGSSx` zStBB1I^|Wf0*a|nOFO!V$dZVuYJQg#o4zlSrLK8ME^lYCwY8-O95uwG+e&&rW2C1$ zIXTHpX8_)OoJ_noQ&*IckDchSG5Rf9r5c|tF@0#e1ae#nMg@-6nn!Xy=}dXSa=S&K z4w4c;Tx88%4uP(b@QQ^ItU^b70;P8yb(gC(a$IG14DvM?WUh$)dH4Xt+^rym9TtcK3&eBvPnx+nMtjc~@jUQY^FpY=ALx(n52Ses8@QH#$OC_O~@ zOvh*5g{#iz>ZG~tm-tC4lBmSBIq0Zq{&ro}eJ(I9dzd4c&sET|;?mF@?@^Lm_H zvqSe_?#Wwv27#fxbYM}n(ux;k`i@McR3-1c+sRJ zGRoi2ot=MMJI4}p8I1!_l{95*>--&6G~7nWXUcya~$(a1L z8w^sqKKQ{t+7oXo&G|Lxr{%go>C0_WA$YQ8gVV@w7n@s#AdJz4#zb!X7R(F8__4<3 zP5oN9mz<>JN{+uH5B(Afe3Cl#i1TQk6_MDLO1_bYo~VZ^*RYRS+q_9>QOdeO<$GFm zwMSsPqJ2_wDc79D4!V3{TYUwrGjcef9e1sx`9$}F8i!c;oy5783p=dN%A}k`FFKeW zGzgWpH9omfv5Uo%)4r5)`L@slvrs+h3j|-T2=~{YB=5dTHuSrtVR7F|Y<|3KxzV5t zPr(&B^(=kG^N`VI@$Nut@n(vwnDO;zy#I`aQ1&vOpxk^?6q5teF+1SJWTpx?qdEQ9 zOd+l`-&ANGwBHAlz`j>5N^3i^;vo;)E2jmkl*3)3SlyaNYNyPgyDkG(6DWVR08LTA z$;6K(9s$s0tOXM%#-1JTJKrd~6opw<_5gOW#HbMB9qWzSufEqRgc$QCZx3p7mYrs% z9lyuFGH*OI?q; z`Q99;$BJBh~y_r5QF{k64_yu{FfVZLY=nqU-BVOJ~2Pdfux7n)+MqC)2R7&rdM;R zC&OeYU$Y?1`METrJkXpr|5IZo3C!!OCu@djsqMcMU-gq_okcTu#N*Lf6ncbpI<%4iAnBLN-*u?N!^`d*&HeJN&ndf zGtsqVFKheMx3F}JN>JJotcV-(lf@Gus=Z({i|t&#S=P1zLilh^l@4|bUF>W5%#a9N zp3u9uv}Cpmv0@@-`&!$d5bVO1f5DwLhGcs{Tg*G~W7S%0yq_AR=7X{)qs?Uji=`|c zqH#)dj}|MgwOnptq5@UQYqHBL7=eG11=r!y~Nv|x)kZJ={d}r?Z%T!C#m#0xiv-UJ&Co4iK?jY&s91c z^czW+|_x-`|& zJTL*ywL&sTwYPY)kw@HKgp(26@2YX7VE+gvJTuHa?6f@Rne+7(Jw0mOocFgVV5c2j zY9X4Eq~1}@(i%Ym%zlY1@vv};FRAHPp|lOU>2*4a`=xVhd2XmycYbhg34s<6#ci4(Yt-f4P}(q`i#s=(Dt=sN2$^MD-u4_6mq%h^Xhg-fgySu zUeL8ZuV)v^9I(-Bm!(h}zI$ENfGA{*ekL#)d~@7%b(DqJ2uozrubJxmitXcf18Yv& zqb3Umn+&aLFL_0xuPRimkhrLJ#9r7fMO|OcnnIx8RBw9uF7R7#vunQbF{|-J&2jle zvzE4fQxqnLR5F%s7T*SDb*PdYFdl5sw_F_MO3P>6`ler*wj}by)H_zgX*eGJ->yHp z_W)H7gt22S5&H3&;<*4qy&@_$Pfm8Kt%!6^|nM!$lcVz~1S#83p=?mbK}Jo0F%h<|sD%Hw3` z8#qq$9-RZ#6`tf84_l3F^NGMa7rl%dwF|7PL`L!C-#(^|NqE8i(QYfhZTBToq*5%j zL-mSxexZ*tHanvepnC)Ep61X+xkO|y?`9VbNEm3WhT61TUT^IL=X?tcU2lPRE;zYp zN=Z3}3#i;rUo_(M8E&giw)f&Cqxs1)UF^pizg3i#WlwA($!KY5@1gN0W#u3+G#LkC z>}H1Mm(Wq6lFY(?BJ;rI7E19}mmnB59}ijXYbEJ8=Y@hg%((AL6?twe#XSQ}J5qmB zt&Y~ia}660vXZyjz+?5B{|SF{fLB8;s~e&_pLtDhCkD1uXS*b1DLRg2i<-Wlx3TjD zpp@tsKZ&aC(d5r$&u@dH;seL43qs~d&2uDL{vTg&9TjEtwSfu>C=x2&3W|~60m-!pzlhHwqok6J*%%lPi%yiqvx6l?sr97kc9H?^sDb~+it;ZJAyf2#h7fjc>T&~Wi zJioo!`n%R=YGLtYSQDu9iKtH>fs$598SAGzQi8a%@15MgPr~9MB-f%g_oXIshZ#Kk znKWkR5{)sX$?EW^3C zo|$joC4bAyn+hl!?d!M2QOW$X0TB@y>#^#!o%bK`IUyc z+vIE#AxI1~5ggbv_CNB$hxcHXloBFYI2guFh`?`I5_v8Q#y^Q}&QJdqa=FRN8sBoq zBjoYJ`KK>9uw`pZ>5uNXaTS0Y-kV#@n(pp8wbOkdmBKD%`3aY9LY>?sBPvFY8Q9D< zk|h}*_rdR9`doOJSEwK?lpFWorL?}LzP>&ak7Lu^rvS?(d*SzHrKYSSKjAULH}#BL zl!o&BkF=VWU3S?IMy<8efeoA}1bcrA#sK0MkJ{#%$SdEaO`vWcWnT8({+l|X3n88# zC3tOJLuU4vf@G<%d*#_+CCDg;cx+xp$iNI3!r#=?#A&nmh%Fg2d4Mg^?V;5)QQ6nm z7Z_{F?7XK5Aey;u+z(5lPb{0yHlA7VMgc-h!(r({>tCvMNH4y#;T!+aAQ8^|rh}$E zv=pDTs8XLR{bic^?PT8>YU0ReJx;{SyTCKgAF6-`m^UoQK~3vq#<@kE@5)Zjn|B1DXp& zzS`pCq~Wo}!9G|E96elTxcO&9Cm4nhhaX zX)F(kX})fKLv5iKNyc}l^#(p-e`$+<}3NWh2tOCEb;Gl-nKuZry<8DxuY16|7v%!&QGiqDz z&B$(c`0SxI*{&F1U+Ndqpxasa%AA#^rO%)I08eGHM+u-5hj-$Y>B)*^cv){HbeO7$ z*%1FujW^~J0u{;tIAq6SRr9sxEcIElnf@Xt&!I7|rUH{I#7vWJdKUb&fG<=|&x{Fq zQVci%?Ke$m_4_f(dxg6{8o6BEbh0IC0Id=PxLRPNye%Y9%;3|1p)r)qRh`}4vTi2m zqO=@U!K9A_mCAiQ8jk*|s>kVbaexv^zF?McX_3H+!5qx{)vcqFwhW5jU#1}gW#0hc zrLRjr*=fu-o9|TblIGM;;DcUkMU&*qh2pm}_B|yvFJ>v!%&s}ZykmJqC8Y$w*vu*a zefFoaXvoqyLgPx3^DLi7`hu;Qh8^*^RMkhMl}AXbcaPzJ759ME$R8<`qf$!k`pUDk z39Yo)N^&bG<`-(TH&9J<4oz(ycf!9ldl5(;5vJ^c?t`vK#X7e{Mr!M264BUix+1Lu z456nRPmrs+-|mV_|~%!rS}DPXo``5htic26HZKqs%Pg zL;b9dWM|8r4v-cg+rVtPF)5Tm`psq#t+bi}OeA7rn~k+4?dHib(433Q4k5Z+c&4&5ZGi4kU9WygvA<>=u(24%bTB@-fb53t#w9Y(mpB{A#`<{h-H0>- z5xa@r^ZxH4?J-|1&40uDhPheDH5rtTRrJ0BM7~MDbD?Jb6yWj0dtZZiS)zgSy2nT5 z1Hf+eMKW6cSoZ+M-jEbz%c-g1ZBckI@_R2U$xP!-wV03o)!$jUn!>8U1@B`5!^d&2>~kRTM+^8VmF+b?xq zj&vmnyr$dCRg>rB28(6pFZGC3QYHsiq-`A>C>oS=m`)n@dSZ(+Pchyi*+kWZSfY)3 z_Z&%bb8*!hcv85bMv3%mW2OfrrRy0QH-!Tk-+3;hL1I|BCD-HDk)MaXc06cFV9VyA z6RAtm(9>yloa3;Q8hzT_&m><&o%hQQB>Q?}Tbyk%n>C$G?W&JhIbCWB3^uF4mmDax=)m=j? z(g@RLOvucKZtdS}Nn&|%C@`!2ot>N&-Pf;Eo#nAj^UiFS5jY>x-~%uR z95F^mMm~MrqY;<~IbB}uS^(w1Md{nLIsW$3IcfQ!Ix7n*11B|B2`2G(I>i?uU3C)5N=WIZZozfkb!5HNf+s;k;PB#J5uU0 z7e`Ht&ip99*qZ&sx@{Qmyw1EJE0l>pzAQeV8uFpq=cVj_9ZxS*6kN^wcs;vB6$iv^S>wF73F~5P#lYA|3N)tyq5PDJ%1d1>mEiJ7Sx4nk*o7>I#;2zt| z{QN-UbPu+z8xe?Eg(`>p`2p^p)atoG)l^SUPeu#x>4MZlhYTk^*)Db^5K#bh`y>|D zmY%k=$m;M>lCDvl!8Jt1(=xB^w&x=qNtGNo?2BUE3>n5JC@(?0mG2H#{y=6ue(;nC z1Ls(!t}0|?a+2`6>CjmCGit-33?HjVd#tnc>p%3RDEOh|kag~oY}DdME=9Z7D|_1Q zZ0qV&2B4oKBReJ(2GXT-W9s@XQ;rv#_+axq1^GDN5{8w1Wc+RSxv94Yvx!Avpb62- z$?u2IWuSU|T^oV0_+aHXZqAN2A&Ooq_;`3&?j(+7!~Vz2knbVEcMfZlKV}IVE^az? z+G&cHm)F3^h?WO0krGI`fjI;Ph7Z$odkDYy!o`lH^|rpjhs`k;`pjX|myJh%|47MT z4bp|4`=0J#eVE5NKMI0>urhm(&={)QZkfFcZwqY*5B`P$XgBngm)5lO-&@zDLPb&Q zjUzqA+F2G%4HMyA@#a?|ycFKfdEp=ejxG#2y`A9E>&&g;RBejBU`u^qeElco=&%6! zO`2Cls>q0f^+SkB4^JR_XKxGk{Br?u@njg>@9JX3?WL4z!Go36<7kdVL4*bETK1IJejSw;nttv7z2m z=P1PY>+ zxr|;n(!TQBjf4Va;tS zR%Y4Uq4FIxpk^t2X64YYy0$bk>$PuP6a3t8M!bD8a|>7y1Gr2H_W>#0e@FCpUvECU zLOyWKb(sD+`EthcHEi<(54kLpW>53M>%(_4Njh7GeT~$&P3~_x_ngQr#hG~TMl2vn zb<;9Nt)YAS*yXv99kUUTzG6P{25{kHc~^h&=qJNoV_Kfyq*!Dyg+MoUuoe zW#8Uq549ZutaV&SW;kN9O}?WslRnwG@e=ZlCI1Hw#I~PT32^Q}JvN z`)B{R4V*HotE(7SnHN%+|58vJm+hJbL?Z)!c|?zJ5va71Wgd-gV<$$1vTuf4otbHc^)aOf6x*=cprL!E z30Of>2B>ACa2XY!aw%wq`klygC78w?^!8`acU<*~!beK099fSXQ4dbwGuWqo5DO8X zENkypPl{T5gH+#!RS#BjIKdp zLIFo82RNnxTL#!~1818PSppmi3hWwAxu)04)5EpR`ZtSh7J_VQ!eP2s3jme%sCaJn z7obfEX8mgOgo>x6_$+LSYZNjMoTtS&VQTfWq!eSb>iy6k3S&|qNT$~jQcPU)6U~6) zr^_)#3JayFN-_uiw{ZO0Ffo7l);hbie<5R9Uh$69ZR$03Z*S`AYW>vo-}C~v7cBQ> zP$bQY{{Eduj6L5aY90TH=mh@TCsvlTLc&vU&7=5qn*njbg$S&@#oJ2I&ehh!#lh{& zhlX2~o#*^o>ucAm7qs(j`RVMp*NbHuKvWd^Nz$M`9_hdXOq4$}6bY@v}ZLRMy=_wL^@u|=#OKQ$9G;Nq~ z0M_v8E*ZKWgQ}$yDb1!q4ky#XFR}X!LTL4aVI3Omm&rd*t!FQ_kcQgn_PXhD(&*z3 zQ?RRzCB08U$J1aWK)*%V^o(sT0${4F%Te}U;cNi9D5)V{ly9-6#$z)XlX`{zdkIyt zg41WMWgH!fOlGx(H8dnnV_22c2&=|djrEMeav)yMsfhBCPg8le?NVycOVaM`4MvZtGk1t z@WX(GZ`;dm7b+`=!>fhm3Rz7Ug|edU-4==}16$N61H`;_Kze&itwxV!f#*ud0&VMJ z4#C%fsbh2Sr;hQB#zIrD(CYqvPK~~|U%!QBkn;5nfa8*N$negS7ul3ldv^7{2Ci{|xWaf3$S8V>#PyBFHlbe6UB z>+iOO?`Kd`QbzZ!94_7l5;!}dS;{h(bQH|&V%-k&sbVTMqXpNY@Odt?nn+MwB6)1& zTe^s@&^nX@iiH8k77I0m(7&7r_7hwMq)K6LcrdH?O3ExY(C|W}(Ngtm&iw_hvOWijq6dp0Y!7#Z=e=Vx`$q`i}F+5PAnYi5Tr;U3;gADKRBv8 zob@NUxCtdVh+KO)k0Sg83!6C*)9qSrd)^N><(c4_+T#VvixTDba1dh{2c37i_WtKf zOPc;6G3t5b2my)QXrJ82q&r*hIp-h)YCx$yNzZ0sTkzJ|ab$$un|}&w2K(n7MlqEf zTmPoER70|cI7-TnM>P@LOC6@-;=MiiQB!0ch2WtD?xi4je(5b-UWMI%h#NpA&KJ?D z3W`|?zCjCtV!yNjactY=NQaL6c}sOX&)jZ6DG2cK1GQJ6iBLQTBSx}Y$rgQ-(v=!| zn8d(jU)PUPm+L#_@O9P5sh>|3T0-on6x#gx>wYMBs&Qd5U;-r#N!5up8`)cD=?S{) zKcoX6dHm`cl)Y)~Naek`Qr#hD|< z?2Ub3Hm8(MI=1<@$8LYrC6U9PaEu{_baQm(jxd>+p4LA3ALS$S1u+SUEh5ZfoRB<4 zB+1vcT0%nN8(tpl+sHES@kg&zC;^t7m#Euo0mBV>osT>`pj&OV%^#kmOQwJ%3WzC6 z#Q-HXtceI&3vW>@{+(9N)--tCE^9~Z$t_UP+m6?-;#Ip#iZKXE&Ht_ZlGDkBha8J6 zIJ>ctOEr~Sd3zxy2G^>72{o#)4(;*Oln79P_b48;^h(N(*?C^HaFB_|XwG(Dw(Tv( zEyKkLum0p;^P-uqJdu%kX8z1f{0$7{in~ePfbo_8xQ~5n$hpkN)ZHu2$(OQrBGiKh zZpRVueb~n1q5-b2q2p%$NECceuSdVNg%8#$V_kTV?(OThC-tY`UK#LF{^K-sAvTFh ztGb)JKAibXE*%9Uh3w6C1({88{m-#S`HlHc7SbloNshE&F!&*l$U{6yGTSF|Em@{V ziv?sGP2Hl6EWBHvjEclr;-|j>mNN(%a8{T0&m458n@{BnmL8-7eVYi&Z<;Bfy9KmgfeD}dqiPrYTFbv<7XZO14tjyw0>{F*QiIeLl$ON>T!hlwswybH3g@PkVxgU_+Wypf*C(A+RULVwr)`0&%_t+zSO8zOtrIf z1g0;2-p&|8V>1`)tc&GnO63T_6Sd>Q66IlwO%HwmjTMQ^;@w1CkOQ#D(*7=1H#Q~- zTF;1gILZ)jyB6I2{WYip`U%!=-5$A@o`^E>gw{A(1E?b|huX!W)hP3*2yd4KArOZ_ z$h{TFDop%&tSk#qXJcJ0`Xh+}|Ant%{$T(e00_W1dOi| z7Xq;9l%K0w9KQXL2S>D|-?qXcUX&=XhWR}qN#$)hz9M^KudMU2#Y0zCyd4z-8KBvI zs2*!bqljtE8L0}SIekU z!Lc#lPRS^_gn^gJ$aYW&*p20m1zs@)?N3b21J))=0CnPXdjqc-$bJZ|*^eBFG4_@^ zyUo=qF3AUJddSUo6D7Ofo&CKqu00yb0ypT^_&Z|r{AxHVdpk5DGWU^uG5kWszVD0q zB!(hXB|}{^#p|g1{NhAsIr;hCde>-lIoafIm`+o;$Np6Nj}VK?6j_`Q;ex6D^}Mod z|HmF!qwr|k$&&L+tdWhXs2BXxb)xvM6yP?be@7>bV2N>Jq>mk(A)C}dJ^jz8iyT0B zxL5CXhx$EnS&{muX>V>Hug^V7><; zOKU_Y>nN|ydi^3NiFZQk#B^PO#FG1QX2DdjQq`NhmxHd(ml=~|Z$5o0)a{=6?MyvA zJ<9zK&!%u9RzFtWR2>XvS#Ie#KQG@fjEY`JiMt`gyf5vdEryTS$?p(q%~#}z$ceN# zMHwx%u8xm zl5MJsemt;yUh!2@jM82kHOO_~fm-UpeVS^^6)W;w=4xZdc>K=jv2FAyBZoq)DTHL< zFa@r&xQLTJX?dA2oLFR3B>UzCRQt-|EMfaQ(GMuu?)vmj5~eYxk;d&8ixN*k>8|fE z{Y+--LMdZ&aHN=-nHeQ&ft52BO?8#$jcX%`nU5B@GCljoHS-}e!*7Md8W*|9XFbW7 znvpqHuFK@lu7`DA#oL|4v)QiYac^?%yav7V%vS*A+?1{fmEImYm14D#ahFzEuO=t+ z^{6y99=y+8BE0leP2bY8(IBbyFQ=7p(;sY|-;DSpB>Cy%Xg{S==ZZ_sTI^x=lzQ|O?77CO%;`RGift94W zrtlK{8T~^k!S7hbP*k-Vc_2F4+T@H_@<5E$(HM3UhfKF-+o z?_$x7;23WFd@U2lQn&uB1hAHi8U%QjqA)vY$kyulF}q8J-CYG!YEl zQl`QMY515qrA~Q}VzVYIt%`9>&&l;QsCF;PfVdh}8{=O;NY%aoJz#G$maAR)+`RDn6l=*`}K*05YV? zdGp3gTwVBH1x(JkH5Mw0yxm_r3Di%Zdykzrblg9tdiqkmfVl5Mc=g-{XqVl)S!&S) zSAMsDPEYkykxC4Zh{Gpx`TmF+J%!o-w#&&A_7H;H^- z-L)To%4G1PLubzaU{mQ-)xi5}RGXb;K?G)v_7z?0O)b$6%Q6h)TH7H|s!6wm`CPBn zCsH$JqwZj-ykVCXOiWBt^%Uvx6{QZHiBE(SDk>_E;S2LB{}Wj$|9e$3@pz2X&*NfZ zFs?q=+G0_007>G9CJzJdxgaCI*v!v>n<3wId``;@6i8`YRJkjf{y`n)Ui(l@KyaS> zrBwBsT((D$*_>nHTT?WEL;W{2BF zg{afy0j-)uC~i(%TwK)r0YQf4?^C=>knsKU{oHg|KDsDZr9XFHZ~Ocza#F2C*`1F< zCXZz+34q>#zp^EVc61~jYNS(EB@P(DHjW|_5;*=Bj<*9E3FPTqfJOtL&w04XCtDe?!r%kkhcPc{?I?FDF$^Tl0H%6u@8{3j7v3`U_`fXKFjNCPRhr+w#slPlv-P>P2hJW^30y5yp_R+78fr%x)t*}M3 zVm2{3$t(RY>gvR0&41A)f59`^ZMqiv-Cl1(5g2hd z5|D%x6rUyWISo*9JC7$lPd-wfF@+esCR9&)CLCG=WO6f3#5+NoXU&rSaA&h7c=2J9sM=Z12-Z@SOWE=hxDM{N0u`oXUM zohPAZJ*K+PGRtC-`Qq}0k4=pSTFNOV1V=15KsZm}f_rI#25(g-lkt|_(M1MMeIzRycufDlCVl5LaRSTHGD;%6eey>}Hhl@#t z4Ah06%LvY#{2T)mDKVCWQ^b(0pJ1vdY=cz}1{IcyD0n`>@XOz)2}QF1bOWq-e847$ zUgQ~VL^Jj=@%N1-T4MsRNM@mfTGyC=R?-y>W#;$7u`+EBu1=Rzy|Y-rPyvDr=uXK| z&Y=}Z{eh~ncq+l+MRslW=6EMS=k9r9iOsgkA~iq84m1i)cO`x?1=5Zc=2X9XwdnEw z`o<_>BcP40x;uWmAc{ zs8!}HN0t!h%Ws(`^oT&E;&44$ntVLYT2@xp;i%=D%M-Ijv3G@st*Ft62^FL*dXUYF zTg+J=im2t+G$eeUQ^To(dLCZPswEMT=tofXQEM+GPiJHvXQWlE8|G2rqD7pUCA5xgagtt07J6H;seYAOugxJkju;YW10FxOzZ3T*l-091(fXY%e+78Tg9wMu&Ppq*Wc#?Xp z9^ZZ45B{1T)VkXQIN6oM5+#>NFc%q!_^|Q3VdX_AGTNj|eE-pQCE_oQ=Ryk$3-vk* zUaBKU&zG_vyZ!?uaGU3z+5l>ChI|{W=f?V+_{b%0fI}oKwyCs~h7*dCMebK8VX?tx z&b~El$z|h}C935DRiXO648^L9jE43KaRn{l{SIV=3~GxC3OZH}F}4d|q{O?LZ1`!3 z0$X4x?w!n!Y+VGkz9!|1M%Sswvg!>OnUCV)enV$!@FFP+W5?f$Kj%?3Y>3>Ko?_>g zy*UBBjrQSwlz$7(JeO6ojafGQ%rcXN+(;(QWY^_A6%S~7zsvJFQeVqI$fqUA;wEXo zx)RV6^woIemKiIiBj@@eRMiiS7(@AKYVkuZ|8Jm>HJT_%3G=G#W7$25)Ou(V39yx);+zS z6ZsRYt2v&v^j!|pd;}JpxdrSaLTNRSMs-lrETo{s%H(QZRpW11UdtYHp5^El`F)v% z934ReN|c{g1D(8aMEj;9fy5Nn#vP+SVyaW0kj}XUBacm)y=e4#OEURtiHvT^_v4oV z?fT7MA7ZocIV_*;T)uC5Z2au^CY)L5S5oxYB4RRvn*>@y!}< zZJdhC%nYBl7;U6?DUfaT*P+6snGmN0VT?~fZlT#q2p*Rugh85y5Vef7w6qPIneC>y zz-zgI?aI;NVWz#Kdyk{-f<=4#SVtR0*gn(kBM%&7zlXSGV2>sbhIWgd?t;9>h!Rhs z4MA;9e-xflh~LuPsMX{&GCnSBZoUopNdx6%7Go?^Q&XU?)n?4mRXSLTtg1}%-u@%? zMm-`2+D& zE`<($2GIdZwWhhjTjOQ%KEJ`*T6u&qV-2SH0*R#XCUf3^!(>vTHLM9vkdn+rG@jW7 z>e8qECNZFnmqpQ9syTu6+}`fC30NhXkx+37(qoW6B|atosr4XDA%3;LpF z2#qmBo3JC|Gb4jEN?5aO(ldEM8elt@6_%#yfIo}6*c`7qtcY5vJwNSCGyR?X(4He+T7B&`e$ovdDeaiU`b>jh;w0K;rl5&^7{yL1%s{7lg5X> z7|scx-5UjXEtDd;1k5S%$9*84FPJZeb91|Ki%a%|@Ih%mq9NOUcX!b{`;RLraf z4AeAbgg_q?;DKLy^?m^8z^YUfh3GDA{2&H$h4)VE%%SQU8hB%YQWYcWM_a(U^NulV z+yn4Nz9v;N+5UN5#NpjIDgIoExd5_Mb{y99&h`(_aV1U8K1zNmi!Piu3_@#M+@0;+~{pRlItep5C73Mg^U=?9|9Wm_1`g` zK0}G}78Xlc!t2)HYU5v}qUfzGVNmnrrwHevlr(l{xKIsRxOL~-@ob^^qhA3hcf8Vm z+Rqx3Jh6*GXlgF zE4Rz?*9%kk3;*x)ifICy@tvZF$4%e?tMbG~Q*ABV$UFc10y=bPo~);>+iw`W-4=&G zx5m{Gl3D@HQ~IP*95+Cg0b{{KG`rBJs<+48{+X`p;z}NCm?Sq@kbDgZ6=tiuDk+k0 z(s&t^1`Hl3D4;p7xOgspa&nTrmyNC%DK3I%O}VL8HPyB7R4bZt6L;6~fh>r!Bqk>Q zGQF2n0$CXu8}kFGg4(~*B7s_9m0!L5DZODeEj$;UyKhPyO7PMSfy&EZ>NlUEO|lD*#Opb#tLp{aA6SpGe)iNP5)IH0=JQfCKP5d5)7)5u@?6FU{lxEl{2#xk(NS5sTTh%3x zmUjCr=|BPejXCH;u{gh%*T);_guWifnCC=?=rb0pc({?q$8f~{bC+48 zzU+(-IxP4PR`fRK3o0@ocZU#LpA?*^8ljj`D&_0ftk={YNee^FYUe^{g3rE8q?T@h zpH}Z%5~0h54xK*vIfj`zqo}O%SWZz>%34;INz9S4w#ruDp(B?wx!N*29S5r?+%&Wz zUmN%GsL;adhK>?BvPiz~_wNL5XU1YLykQK0bi^fI9H$toIHty)TY45e0&DVW@{ip^ z=`T$kNZ|}P2qM`thHGy_Z`_BEpO^9(KD!!99%y!#4-uhi4_x^ zHWNp`zBV7=E~aJIQG<9&3g{#T>BsT*JNmICAxV%E8jOH6{ZBJzPL{pc^Hvucz4Z0R-Tb@I? z0L8d+iMp_dM++d(qQ+5b`Y|(X&wJcV5_dJjTW8xlzRh`Y`o7^JP>sW>Y{MtHbg62A zez~kJrAsQHV;;o6RylN&DrnUj@932zxY=3d*~*>+HNHkhU7g{E7+(JAV(cq5?k2FAp6S!c8FNN~{ix6J;m z=&U@yGTu4;ic_cI9R2)g|Kgga$ff4Ojj#)i$9`q}x($u{G5!>z(Fd?>7ro1Oq(KiR;ABZZ(J;&@vzlOY|JCv{w z{KE(HUSu4LFC_s?{?8Cd`>>pwu?gU zcB5b1Xo<>Szr@L=UHg5_{|T~2;EP#_+7VEqgwOVnysC(>@Vg(i5-IOfev0;a_9YL@ zo%0*$E@sqcCDDNMpw+8P?x?6rq+A=kw|~P+QrO)XvF>EFAv-!_^jg0dVeL%UJ03NW z6wMGycAg^|tVAm`S~Yjz`7XEf{x&q-^}e^_^e^c2Zj1j*iRQoNW6uelK!hP({7{rm z{H?g%*5feuK&MDa=-2E>`{(B7>Z+3L(krsO4joIX%PkFz_Tpe!rXMrl*gS2oz`>SX zcz)et#P%YeGL$_g)EH~~JC55oq{0)Y`qngZS2x!`+ndikHOuKKW-k9EOK=g)n39;C zHT~KQzP~>@@Mn_4^Cui4 zsu8BuExmMUU&9*BkWk{TcB|s-#=be9BS>Z%4BF}-hZIVr&KK7ame7ksS8~093W5Xv zzC4?#ef6}N1D7pjTuih)bh)au(q2XMwp;h=wp*`j9R&Jdk`j+YDj*5pk9V<^0I{_z zxAHrN7|WRu5{e*or@672Q@DrKk*qU$)dh&MrS!g+aY;%iL4_`@w44l8Y{25}hH;bE z9O(_00>Xcu{Qxz??U}*BL~BW;>N*Iw=F{cp4&0A4$l=&Lew<24S`YVYGEV_@zh6H{ zT6o;F{(yGuQ1$UB(3+B?7$8z^VTi{PM_@ZNqJhIFGf?1BZlry%Vn~;2ONPME9@xmF zgr2rAc+q8A$mnwPr(ycO(JLTI5c!HJlr0a$)k=?QpFdxXEu!!G)r!_z3yK}2<3V&# zt7~fB4GqL--(RAjnh*Gqzvd9fsPDMZm3(L^qn?QjX{%3#Ul{6Dy|pk@9B(fjw7Q;4 zt-j2w$S{a;!MQ!VXcI-)Xu`}=gx`&&k9HSs%r92r1!R<-Q^K6?F1Fq6q&Zu$K3ZFq zE#a`=M6jIJ;Sj!<9qQ`dU(Yjtj`ShFDP}yx_z7*R&rjd*mEw)oPJ3&Qq)~Q?wHB6- zE0i-h=S@i04$c<71$Z&g)l@c#-$gz9ray{?yq5uh*UKE|?6%lnf<(7$`MB((v5eB` zK;i>J5IL4#R+a}ON^jex){EhXszq|!+uNd;mIE1|6dX;te!?NNyi^o@MEN{(Ox)+T zIrzM^4hE;O74Ph3733KSk>7tRClVY zJg7gRCF8t#s)fiZ6ny#2uofk}PPo2%1;7h{aWaWgio0=E6A~ zj*5^$MVm=dKiUzVYlrc6D|l#?n*`|_wN#}mbQ`2%rsXY8G~L=aRJUixn{oK9aT7Ba z_MGc0YnnIx(YR$Zy+k_dVk7ol!)$E73(o>DOB^mS3wK~w&NaJVGu*lGgnbYkb{f0w zmTtQj?i;0d28nAr2A4?>P*x)8=v*cHD|0-cD|)>nkH^O+7;<*r z=>uoN6mm&QY03K(fu>irp`NN18zXR^1!3pX))lf@7xII%{CI*-lMM8pgao08z{c>iY(&i=2G`X zqWzAc81JEnmh8FU+XrG-&72;YK;1w8Ku-(Y;OM;9aM5n_h}axtdXhESh^JOproEcs zsDC=h66)v#h#<9%Ci3S>dW4u?8jsNeD`^0%BzUpmw9a~Cu0+H4v#E9`Mp(Cq#4KFkx1i!Ls!Nb0|;p)BTA{YZ4K+oQ5k=Qf0E zNimFAbUIW_Wx16)O6UGQI5Hzdy|_y69ap*WIkIj_hkM>o(D$$qx}*wdcS;#4p;F20 zTs3eW{h@T-4mXk^w_t^at5qLsmU3Qbwz|Q{I8;1RI%8WbJl5Y|pWTGiueVa=qhGv3 z7g5gmDqu}FGe0NMaB-)u@d>O2is@vt63O~cg(ESAoAxC`DYJpRZbn*PpNfez4LZc_ zKNgVZWB-nV?vB{gkaU|kmGUK#h*7I*upQ%HB$Fu@g0u?HMV2IcI~~U zOO7}OGOqol^i^zY<9%!5;GC3_7{m0|Fj=-cZwlUu(Dv~cPO0>~apn{r=@ED9Q^q#a zTN@24I9Dvo&K_h{95-$IOKt1T{mw(YG4IgQf5lTUE-x?4{=9gO4yz06xm#y&w`*{@ z{Xx&WYg{~+C#Q99^lw!_KzQ@Z1GqgROj&88@q)fJU>e)ulovUZ736Z2pe~PzhirI;-4-~!$H~!>tNv~PzqNu0{mY0{-(|cW??56G6 zb6Nq-T)GPH28vt^(125G#STfCsBA!9NcJ7kSZaLxX`*eq)z29|d%!(M7C%(ELc3q! z4B>c)(!7=Fr`SYt_P;u3uQvdpjtYT@EsC(Y(+8iHCH}`tb{k_-&pf>pOc(n~>OS&G$at z+L$}0gdD-YX;3j>gP&D+VAJi7eI!OJFH&r8K3+`L%XW_hrW+1NZQ{7U{lhQ+I*WC$Uwi1aXFimdb_|K*wdz!@VhC!P7l{u6B)o`nP zYZvgpj=_PKoKM}!9?5o+yOyaTF>D8Ja|WJlv&C(+)1IHagdv3J%goPP4|j}#9_V|x z;H5YPki|}kB9iZSG$*-l4PDvk%jc}!1D5i5K)3$DF%_~n^*T)q+{K(`RZd9&lu_gPfbVX1&7E-}aG`Fw5Y zZNyALgjmx;(A#PBiKNCXzd|kjlERa2mr~tfeAwyC3P$-?Q~8vE^yrJ}C;WL$`U~u7 z_MMG7k{CX@C%`M1e~jDE9YCLC!~NcU33|D`ZHB2y!AmyL{UU0?Mcm{A4`*xBgV^K# zH3D-+gwSR6>e2C_#+g5DAeUp~y`}}+N%yru?~9-z=KD1FD4lVc3A=WsCK&&`5`BJchKud=Z=K8EZKmw@6NN@vo zLMp(Pm2LE(=AJkOYIMx>Y%}F-#^9p_V6u*WDc|n)cBXq<%Z@6ddob1LorQS+lEKMW zwB-G8OQXV?ub{N8aaFYSfjJ*ihR zc{o5%H9&XoBdmRba-!y}y7$jk9Joa1L=ZV*uEO>Yh_={z!gyGNZWc7}1=n+cqF7Pe z6?cI&{!8@V)$rP!lPYb~j|pSy?-C7&{ln$ZOWO<{O8N3Q5Gsm0ln|ydIJUl#$>FOZ==LBD?rkGnu zBU9GTuBNI@ae!}RTV9;H$+^-6+(7|8sWTK*^E zqRZ-RfH!kyi5)~Q4^VbfFA_}+*|li>SSvBQB^;JOD>h)Cgk(aw>-E0MK)E8Q=NE9D zk3m!dz-T11TN?q_=2X|bJH-}xNt6uV%*o37#%aI)y)m>@Jn}er{U0taF2v}UCm^N^ zv|WPP>c%l-OJcKv3Jd6nU&b+NsKwg2EdqWl^r;+>6CoYAvcso{>O(yuB#aGhk`IEx z=H)~ss*mLWu$d#xzKd?+05rlG-XQlmVNWd{-TxhlRE#}TT2Kx;o z*JqSpGtK{9clDNiRRRL&i_Gq)?%6dcDEphCruHVeq5ClXcI_AQF)KEc*+tG+I~4FX zQ%*(|gnv?{lNkV@Lbcoq)Qm{=+b%A9VBP@&vQg4S1@7n*dgd3cwg{so+gT8%MJu9Z_|$-2!P00WVV+}x;)t|Ae@E6 zW51_c2?85D%7~y{uNu{h1XfbhfghW(5B<;2rnK$pJQy>uoZEJ4Dkv+H{cQ{QQ(|&4c|A^6mkgs3Q87;N5Xp;hL#)fL>oWD2>OZ`fGtZVrQNL?$U^9PX91 zD+$>NQ;x4(?mhVNhu`t)aeN=%t2Eb^`4n{7HwT;mzktFoBNAu^O}fXUv-(JEHDAA_ zm#%i)C$VmpI!sCP3)53h=>m%rdwy5-1Bm;IA66&J=U)(F8-vuFX&_okoM=bty8mv} z{vZuK7+VF!6LPKvaoX6=tfDrHy&m6j$ZfsH@*0fam;>VS2WXWT$B z9W`u4%EZfjdk*qt;DD%bgo#dIz~ifBH;F8YX%+)8CbTQ6_jCpbvk%q6{gmy0^o)L2sb`9iPpSGjS1QcITRm@cU`{6hy1 zqzjbAGgn115Si%ZNDncnJm+_lOHt45@d^}vvU^Ziv{{aOAIN6@LDu1Jjxqv~hvt3t z^V*Q+cjCrblOID#p;4{xG)8#lY9u*=!}>0c(nV=zDd|yInoa5)O$#>mN~YMjXYTGQ ze2b~rANN^u&S$+=RB=pq$FF8V)E&k0OcxS@@4VeTS9fV+ADwEKkE|J2fS` zV=CSPAD@5YASO0e;vz=&`c*enLL`I)r~)KQH)h`oG!i#!HpzbIsW-)%5S`)oLdIB_ zw(~XoCrY`AsXu!t9e>bdAho~+`>vw0^1UE0&3P{#>&PAyAV6_hjQ@JYdA_dP%%Y+e zrl##NXx`XiT-oK8Ht>*pL1v|O{<)H)aN#pskU%kf!1!woVTN(5u=GO(a+w5Vk;FVTrZjh>e2jeUJ1gDh?@Q-h1|1u^hewWG4X0*=#p7Ae? zJ(!H@i9T>(PbiYbGb+@)-18dF`!?4!JG(xun2t{k^Et8pW=#O&`z}Q}Tgd8q!;fc& z&PQ*d@J#0MX${GHL5>raS}AAhFaEVn$-=K4i$Ju*N7hCOyq3b9gA6#bqIqS1`f8W-(~?}9w`e5BbjbzsZu1U1{VeEyQ=Gsv1d@|ybLN%gkj|0@y)TZ#xTuFnUNmM&7(L*m z<09vy@Ka5Ufhic;txekC^SqkRxDaS`%JzlCe4dnlUW4aSCcKCbC@Ql*q}J;3mtFgx z)55@M`zzFEO{}GelyYngTPfM@^P#@q;}CsQ(jVP>YG^jbXy%ipJDWe_nXvjyWZ##YU+)R$ z@g6gTygr%+OA@l%q$NdXxoGORuTd>{DwJ8^U-}lN&l_VGI{`!=%^gM7t4MMr{xvOT zJtproc%Fb4M>`o6)lmJ!w{P7c!6G7B7-xZ2JMFxYj+LP-3BxXaUfxStDtEi$-gu}V z`9h3Y@1jY>;B&g!8Z5+@>#x~vpI~4~EfWL+uCM9z|Yrh?69>jx#xO{6Y^ld6;iu0PQG&h znL^RB_L3EqZJLLmtRS8J!W=o%yh*iLVaaB(J3~jg9t^;+*0*5Ena;}0k^eJRBN(f5 z#@y7@|MiI=MIcN}82&^!CMf91kO_B#N;m)&7p+0M^~QC5AD@iSEai#9%tKz~qiIJ} z;%CCJzCwaLOeZ%V%XQCt*H2rRhG1z-OsS(6RU2hIkQWxHl|pLxS2B$D|Gb-$u*BTR ze93+0cTghQMk+pDPm8Si(#T;E4G+R?*0@8qJHLCX(;K~$uJK`1359djKN&1rwwQoVe4(*OX5J*xOwF@p;IP!W z;I4kHBfHK#spY&uNedOlZ#Ax=Me>?mt!_l&r-03=XST?Xq|Qip|4PV26ZCHGZpv%% z2}D`=D%AZ-02wsIiwx>dTyu2W(*9n_>*RU6Q)ets6+M!Z?&+pH{P0LkcmQb)|F5wy z8)H)dFIS5|HP7;S<{Vf`l8_UUU|st zMdN$Tls8#l%x3w1VbS0T(7U2YIJV~WwWOJNZ0k=z74;BS%B$Pq7Rso{>32A|^F}_08 z^vm@=lr=^wt*ERpa<{h9ul8%+0=-ceYtI>;0@7ZD6Jkq+5K6h}v-#%M$tkCa$hNaQ zr?a;VvPxT860GolWSz3p~n>O8m4(xB_uVSzC2P zF>F6#J(jORs0+iM|i zq3cr;u-Mb;s-u0qsu2Ul3JHL`to~&C$xO_RL%w1R+K+U;eJj!=!kqdPJwH+&~3cBb7j8nOd~)=x#;bTNPZsW?>gKzUMDnA*Jy_xK2baIR9v2RYO}_{!Ata6_0Qn zwLTSH3akhYEF2eJSyELREedH25)EVHhgc%r2!kI~__K0~`jd~%&YaXX(X+Zm6As6< z?h;mN9ClGV>GiN?xNoz-&-RDnc8>$h&BepRJZc*_0)iI~mlxMOFb)}wGS~!*DiPEZ zZSgmaS{BsYwHI{=jPefYs1sj%P1VNxygR`^a@%;?tz81K*N$`B!*e|>7ufGP5i!}7 zGjM;tFuhexe`_v{Grp-bK`ioa9RF+X@GJy0VdBRI02u3^q zBc+}T>A%s1K1sQ@o9T<6L_oWX&thAiauMVB5tea{?n`Xx)H?^XT@Xz~UWPYc5heWP zKFN^d1h!jDpf}=i!i9nHLV;=8Y`;!Km*k(AEGAf;pX`z(b<$pK*EV^zGzt`D^)Dgx z)}~&Ja9H;JS{&#MSQH!kqbsvLvCw0~Ws$x&q{bb7f?A(nCLhmtD+|&iFZ-rGJ=wJr z8T;CO&4OXbfrYbr?8VSHD%xo+?I5I4XHzTqJ&N4DJ3M|{aL)759vRKfUNkG4{?cIP z6O$Yd*3IgYaF?^PIG2YVqnrK;+=`mNRa?o%D_o!K(|<|~TGuj(w|mUPVJ<;zSBQ)= zaYe(4-?X@2SU{mjzoCWOINH+kTrNP8zwK&{6bCGg=+p}hcyT^)mwQO;7=m@ky7aG1 zD08%R`QhLV%SGeVrTBa7Rn44V7*ju2Z9E5$$^`b2*0TO8Vvd}0o)nSu(1r5qGd-v! zUC+1YJP~OnTd?mLvU~pQPu4w9PPg6(MdqFEU%W|mp#{3)@m`4Bh2N$=nv8*DhIq-H zAX(b8FwBv9f{y6`9>eKxe4(((6vT1Hm>mD3~ z!Y!r(o`U2!a;)7RD(O~EDoiN~dS3tMxDcLvIJmG|15#DaJ$14Z3QcHUZQgBVz;y#2 z9UF?+5@}Wv2^=>1Z{6)t!A3bufj-3sd3Lu=jmcoj=g6n#%m^}$O^GCV5_FaTkCA!4xj1YAHrh9Xu zLyXJ#{j6zn=xF^$!mWzE`VXxhpS=>Qe8j7F@ZL=2R2`r#55mtx<+YT&11~N?>_w*> zknMTqGS+DK16Si^8LLS*9`SM42R>b#pH9i_H#7Ce2bI6LLGt&aQKP*A?G21Y2W?Kf z$J@Ect*X+1`g*v1b@}Jg3DW$YnX;F8O->`Eu4kv}P7X%&E-{ED?1)E@7UEBm{xX}Z z;UQvw>Ljno1qrp!tqpd$CFn`4pncuRFw;B7m56Y^bfACyrGvV_-DzhA+#s#!79gKn zv}xBrRsOB^Y&O_jXm*~VJdx4dehV|Zok911rU?gZzWNtU6fj?*bkH#SIPfz7wdlIz zBFDi7`W~Li_d3uNZh8q9HtMZgUE|hsQfg~0$OHk2**g>g9qx4#q_SP4o#MUrnHS8fZf9&Q`g%+lN(L3Ba_^^667JT99e!Fp@+ zS`oK)X|}a`oDe(^P1N#mzd>JX|A2VuA!-0Cq_MkgW+h_b85rj6VD%Blzm@5p#nTEZKsq6IF^w8gvorZ#l(3b+~W6A=^JPV1Rl+W!z_- zA||axI3gn+!|^ibJt@o9CLd}${CP!oI(cHw7@agHJTJYmFG+vqGXBi);W3T)MvW)J zb^eCocs1 zCWc83QaSbRAL5pqY`$8F{AkA9;6@#y8eeHW@enT&w?W*yO%5yPBYo9<|a6Dj4^n$ zv6hzqBkq}w;fcZV{&K*+#~XKl4u6SzA>(naHUnmxq(~*(`yigiR&B9n?Hr#CpS&T)3K`53}sj1Yor#q+PT6a)pSO*_sn^5)&&&VJ}lPe&*HDP?#p<4OLIrH#$D?-5fm9>3OsnkrROagF51 zHc8F1m~0!>qBk8C(>fjc6f|UAAUauCcr~V-kpyt3@MV^!2bmZ6==OeCw@bU_hxlhU zP+-5onq2tlFB?!bZQ1L0aD2BO+#b7spK;yM-oL#=@6ByMw<(J+8*)|^xh1Q~@!a5b$>&O@Fz8&w^_8l zCCDoPRST+#soyQol9@zZ!)QA|kGLx2qs*-G_q@BK*1)`B@u>(K8<3S~fA7@+rW<_a zc`~V{-c|iZ@4SvfOm_3UrC#yD>4%whkQIxU5R3+9p@hf|EF(a!q*u`9Bt=>wjX`;_qV}#P?@dKv50O2R=8ykk$jVVC}G6pgk z_7PlrSf(%~Xd-!HPwQZY3L6{S?;UHLT`|ANgnrYeFm4qQn-f)~5ql+P7Zsgr^ID3> zh(E?cnS~Z_b8;4Wl2pfcim8HIzJirKk-g>$NMd^9*x#Je5GIM+B*55T0`Rc&P9D2E ziumnk*U0lYB&8Ulvdb)SQ&VNq?=3uT* zDtz~H@G{xm0TWbi{Lb!P;GyGB#R7mbX6hMnKPHXr!n5R^eI%(~Py8WCAckmq*P&Ux zo?f9jkG40rHcKoOZFlmjJ}ipvT18By>-xk>zMy&b~~j z@8Y!a2v;9I+{|Uk7)q5l@)8hUG>4@iWtv&`dKoho8Y3Oyh{;>K<*MGXVn4_f|0Cji zkN$)nC*rF=r?i{F9LuL|U9Me!?IG=V713G!s;7VSZ^%8Nw(un^r$8INEF%Wrf~YqD zus15vq$ALe$$^!vZkh&Xz-+Q@Y;z`1?O!JK-EV=*^8^tH@PpcZe)j+h%s^+EWO!vD zHT51W@r8C6ZCDK6QuiAXiFW~?RO(_!G0G1I)}v)y)?0}!T4R#U#8Ua<0*i;NAK1Lt z8s5F+CAYe6tj|3f__vnn?|YzNK*EB)2<5X87T-`S4aoUS(-2agPsZ=wkxg%mPCQL1 z;;x7J>j#^YIflQfjtK-qh^Uu*DzRCWc}Hz>Hk|g|(^@-scH-L9h+H<$`|o0oA`$27 zbhkwPueMl}VIVtwdV6ejH}g>SS()}D0H1etb=~2y&It}?QI-`}d#$Pj3#~JiV!qi& zP}=t{vhB!cxB7lRHpV#GtZRYuk^$2%MmcW71x<N$M;63#b;q(-Vt0c=>Ghd!`eDxuAwKs3Za8 ztBnWx;DT@P^8Y@I)yk^R(N^@3Ft?K=eT*hY`E9fvk5XoyBy*`G5lnagLs)xgIROLu8P*=>`ZAT(yNUoWMrq`i`B)|Fx=s>H6{+AUxdvF{xjkx@`k zpi^h&KDa?mt)i{nxwAabI{B_6;-RgbU4c%!idjqEM382A$&?SBQpjEcmm&Gqh~UF){aeSB)M8<(d-h30 zp%b@SDKmq1MFFfD&Ft*#oSvJj=ExpK08I?8s;c6eFxVU`l9|nrB}hM4f0TWvcr-nk z1ZK%xo?Sm@Jd_bazwX}X?UOlQEc&?@g{z2JK;AfinQ=@0M|oFv4T$HxrRU`3^Ki_= zeUz(DEp17;5|Q;9)mAaJ0gAEydi&{L%*e?homQ*k=eo}eV9zQvQJ3-fi6-i^{LT|9 z>BKZsH?q!u@_XE}uym$nJzPru5)S-$9#U+r|D%+y(++pBg<8Dp?m3&4!z-QI&g6R_ zdj$~K4}~~m4JF|sk@)ZINV3HT`8eJ(AAM5aj_PzuU9$LX;VtDI4gcsX$u@3ZI}1U* zs6<>L{R;9kR7p!;p6c9QgVHO0t>Z!xyu*7(klAo+6~E?+_SFY3XBe1-Iv*c@GScIZ zjo&9ua53l29!zsUmR1pBq0xIyP;%UL zhyLz9^qSD#*R{y?Q?<(kw^)D9Pc@!Muk;9)B#Xux2Dc_(;4>1%k7KY$UagyNLKsaF zi(Yl*Y|tY>3(SbmiI&Lb@*El?Yr-ET?#k0kbw|JAuxWBpboIg~89fe#?2>Xn{v+`| zPPPmWe)5!2W(xgC@fGIOE^f?S$4W%$M7+w= z%!`BC*4NNC8uKz4s~ebT4er*yrBiw7Ge8q7HjP%b4rNyyU_mqV;EF3S-^leWJ%ZIY zE4@3QyZ1_`uy5qk3yNmMHw;cLJKY!!r1&;J51FpJU`~PPsna77ON~4)(v!3f>{$Hq z{rjB-D0uGyY0uAUz^BO2&yn{It$h;CF~xKvZ!zqm4&7bEP*>elT}GXy=Tx1#XCt0C znsbIrr>oa(8n44#{4BacMw84ITk0q12*$X8RVGhzFgQnC;p|QW`S2 zI{zz>cObgESXcwyv$yRXT5W_YzH)-GusBuRFY>!MXnXZiWKaV)dsZf!otn*Id4{n7W`=!tT>DWcrUB|%eyX;h-anJ)smC5(UM@rmbAneR4PqC8gXY-ZLc zVGhAr^K@b-`Cu(FZ{f>NUAAiMEkBKJ>XFm`xP`^`PE9fH4~Pibn$YeO9R4x2Ode5s zCS}03R|D{?i(X$&+>ZY65#7(RoqJ%@J2L$u(x9cFHjf;k>vY?SaZTT073w<6%73^# zS{&>4btX<(&dFWeqEcj8T`dy!MF;ld^yjI<=(a`T?=3yG{FG(8k^>TFt>LZSikr?P zkS=n!aE@5AnM}xWl%<>LBm8)Lot^yML=U~nRsBbmv-fg^|B#-pnt3ecoPMA0YY*?K zl2|Vv!Ni+EpB?pZF4W#~hahH}Xhvcj)J@xdw6y~F+N@~g`c_~iIK*V7;K9bCPX zs!nEskA6O5GGnaj%^n{0AulhW`@{Eu+qH2GKSVpOwpYIp>Tui8j7Ntf#FD8RhzIV>9DK}nsuWe4fjLf@YWWeTa zf4lZeLN1vz0sH;?y;5u!`TaYxbg}RX()-1tbJ!z{!)7w42OaTbqJCfRNeAZvv;)&u zedJcsts%Qkj+o6E?kP;Vp7gmVSF_nk<_6x&`-h#?ahTo!SF4t>J4Wkn>zv1q1473= z7BWRiSJDqIv7Vu2s?eutQ8u2MuDE{8zOwczz&3rqv}Owycgx26ZYzOZK5VQGLURJ+ z+Z3q0M0PEm_e3N==1G+4wRG*`o5rILJbEtJdozxZXS4L)8eNGQjo=J(F<*#ONKO^q zk}@gsp5p&fmx5YNDawg=I|+%jY&G(1ROT}X6t^HFv?o9xT%Cn5G@-FYD6e-N)nx4r zCE=aQQrZw?5(+mj=ujj~-<(P^Q?yX1d<*wiUFAkk*VYULjT3s<7^Ed=7-y~1V++q&c-_1g=p4}@l221iMt`Q2ubhRBh#COt?_eZe~3Bai*r*}Xc?hx^WC{lonv#jGkH z>Yt!T6*c+36_O*rp!_(51kKknYW^wSWKubr?o`IDZIc;Oj||K+=B4w8oNH_3rgyLT z2c_WO$7lD9zjRSG>(&faot#eY3Nd(4ctU6ygpmhzoSrFl4=&m$WAWqOd+;*})zdIs z`GsVBYqJn8ZWt+#pV(6e5Ah*|oJ<}4+4dpJ-os-1MP5I-b7H%(-mJFpvyE%eY2wOp z0rfXUbF<{4qR1-$XAGx!&V=SSs1~!b>?4$nBgiE9(%!g?o_?TqSyh9ZS9xzbz#H;< z;$FfZ@AK9nyJ{gGo(`zE1}! z5A!ne{xushm_N3|sE7;Xm@>~@FP%vEtc^Tgmk60A=Smam;$WB4 zxie@j`dRNU6^Hy1d9Dn09DlHr2Q%FRsH{`_upUhpXFsrH`F0aeQ0mf>oL`)aO!?NO9A?|!()%p z{r&tRgZu7;?YDeL#TG?@UTK+kG z(c$J*SCfCloMXQ^#)vr;K)Qx&6d7^}3PvqaJ=Z3IKpTS^q3u#8`xx31ieP$o$mgyP zyBo6D=PN)Ms=#7`|K=lY8Vm*q;YX;*3tg^7c$pN1amhLu3G5YG`!g&x>-8dwBhOJx zCWPW?&7%so@7cXEpXqiS?D`RkPc=T2CyHBTekj z$H&K`xb&p`)gz+7vPQFiCmbWnk&9=JH(HT(UUsGg{}>Hezo{+y z>B7MN*FZiG?Oa`tz1tR4Qu9}wB6;t-?5qjDD(JV=w(!IT7Y60_6XokpuqueuDrf=;lw)lTb#U6Y9#KiGlfxgLS9vB zKZ3>k`^u{M-S`QJJwN#*0bs!W9K^i?)6?=GN_BFo*pX8Hy@>@sLk&S6C8hdQx!Bib zR(JSg9|mSoM#mkyi^uX?{P^*MY2Y8-6q=|UgV@+uo~p1(Kt_aA<)8sSqww3o=~usN zFgE`-W>8pStEs7JY-yR6mc}~JLGjz9xw#pP$>Vmoqf{FGH-EV}<-HwKc=*5kWqs#= z)Rbwdrf(|Eg1uV5NcN7Yu=@ckAR2FoRjRyyP4Qe2MAE5|x0!C*pt`$uuH&#ZFoOsU zH}>BKqzV8g<}L%>!9xFh@=0GpW{@bYvx)p)PfgjlY&_G7rT9hR;tjB%e(gXb|9B2Z zZFEAseP%@8_Q=QxVWQ0W^=n7?U*lW3FofD> zu|3zv4fT^gBe)4Z^E{_-d|MM=HE$#~caga(jKxPuLqpEU$V|H1GTvon*O>}8=kAyG zzA@D6pFvZIot+&W8iMowY&Wsb&;9Yf_+ygFwcnP6x`iwyY!Y+p?cbZyO6-F zSWZP{;1h8Y81?$>`Q}1$RjC?o*}3ThAVkoLad3FJrQ`)}fzFRm8o8!Ki3)8S9=H=x z;}Cz03%I4>u%Fk83ktYW^(4jc|8E(X89QmyDN~&L7h?iC_&678f`UqZC1O!Bo8oHGp8brFgQ4j%9 zfwTF1-}k)dhw~Sl>s-JE*JjV!Ydvc{ao_i|BegUik`mJq0{}p(rmCa^08lglKvoFx z!7CzP7dF6O5+2HW9#5UEJiJZaEP=sYWqE~_ ztq}=jr(kAh2^wqpRY7>~o>x^~e(>qPcYc03n~gOniLXx+Yu-{HJwtk<6qO-(h3W*m z90>r?`;cE2^Z%}9h7NAN9ICSpg#W(U|E%g|Ep~D+Bz5BZId$DPhd`bJ7yPCa)64WH zAPi;(zaxr5ahdItjtVxXhMX&-AYJL2JYL*{$F({PtLA2jo_Y)pFV!0`=xB{>;eFoDl0S2 z3y)K#o3s285q_G_r%ZpJJUaUQVm{0N1?x!SI9+SY8ncN}ZA+7PC?Pc!n$z^>m+93% z-cw_RPwvCM`*mzs8Hp1?r`F94`}mgqp_jQ=L_hds#}--?fEi<>pyX7(vbn%dP2L=9 z6TYng+MuB!<2-~A0gi;;_GRF&d^5POs4qe!m%n=)ktSRpnvA+|7v!_>X5hgY#gU9l z6+5q>AdFz2La5p`N4Ki0hA87Z$#G$eal2M?GZqZPvcu&%GFPn@l2{rU`k^%R zgmC?-N^+6HXqhPl`WTE1)Xa6d7^h(G4E7A>B??~a7#P{t)I(E$22V~eiE353gsdMv zJ{Hh~!+p*rW{3^6@L0VJ%a_5Cb$?0V9W33Ig-0)&n^Rnr86iL!odDd2xPj9YL)A1= zt&?_Ccl>cZNiWQKZ{uqA&xhe|dGE~I*B#-d6sz2o2ht1 zYNS_TW>Ya8`^uIgdcXWB130~Ks$Sy=#NuhWK!jgcl*@Y1g=;=v|9hxB+{P1|uSun| zV)-wfJCQG~Z*2&EV}cA_6ccp|I`_97!S@Rv>Zz@)N}4j4R=qEfhzf^Z1alA)RUiK_ zFPn59%ceDn_S~udn_23*%5} z|FgdORbQrWAD=w*@)D(@rWW)%&^wr^V%xAD&6T~==6@dcZCB~XQrq$7+m|Z#G}=AL zP;tw3fmJ1{h-C9~8rxOTSiCW#&^&zvz17`ZR%4nf88`=@J{9Zy^y5~_6R69@&&|g3 zCI2d~Lj$BqD-BaT0m8(G<i(>FEi^ z%D2*HkP|&%n2mix;86n!$9Ut@v{Bi1DZKK>>rl~Xj&F`jLIOJHqWjppODJ{Vr&N46 zlOLgV?kmwhXNNF=n~x74sI{NgtaohjI_#dF056dJl@_)dk~1*K{M|P^?6{-F8l^ve zG@OIyFeU0ep6QE>AKp%Gtfu{vnDGID;kKY{K=vE8lW^^o$a?~_p?4uZ%dgH&=j$Cm z@fpOeTYNc@y7SA(d|B9W?tV&YYGiz8XQ#lKj9(w0To@PPgexe$tGTe-F-=G*$<^nT zR1Kq{PY$A7i0RIJIaUcF&~-wGazbE`xZNS3PeoqP$OZlV@#W5PzzL~tnO;zKHpB77 z(2xf3I@&~6H|=+TnwnZd=o57-E31S${t5qVO|EQBYsGL15er%?5^sSB1dMrKmzKlI zR=HS;&ncH&GrBJ0tY~%Ou2Uz|9rBjvfr1RB={-riLatmCzO+K_vBL-5t#}FBz6;*V zukMYmdDNwKKnun(q=aG9r7T5z(VfMtsPZpBV~NV#oh2B(gmmSi%8hFMlO} z_cyx@#@=6~deuLyq9Gf;CQ_PKgDJ@{Z?E_)9Sh982Px2m&7PE%o6Vv|owtrFq=oby zHNoS-ryec&|LAG;Jvlm^e#yqcp}m(Wo$ixS*?92Gzc*}f^0~U$ zPE1J&$#QB|`um0F0^{a7tUQ{@w zxr*Y)t2wpvC3h#4n5Kz878x>YdfrT{FReMA-v!LO2bYCrz76l{tp_Lfmrh$zw>{UW zT?2I9qr-+}d?1EVQupj%wuHNY=iW1*y&zsDDl?Pr-*J4PlCACCF!DQbxv&2afl+1c z3=a*KX!K(y$)6(_~-S2A?+ZcVs)`6Fo|2$L|_qRin%5|AZOqw4^%MO@O6;b%{bD z1X{34cEc7I3!j8tOK#0}zC)rlI=0-R5=`N+m%(vltX3zecUDg4w$J>Jc_ zu02;`FG!6fmue_=DU2&;`?2xH(h$tMMiDxOo8AjGUyJOXFh9xcS}R;|){Rd#fD4qW zF3y%2SS*?_jf+s0PKU#*XB@*u>wH4Mz%B5EQSKy)-M7jDjNAjq829@!5A%~u&JtVz{)5Uj_%Jlspg9AhYNQ+5XPpH6lWDM(A!absthZ69y3W_4VULbsbCS=xSd-PGz>U>TjEkO zOghpXd%hgJ5FCuZRBgiKdy&~zN3WZ*!7YPv_jLShyvh_+J85g0rkQ_u~cvN)-qy;(=0 z*gak6&*-LPxrHK4sNlmh2Q493!8WRVo*^`Em<R~!b?4GYBT)qOY2|XKnW41wJ zMld%>4eVyJ#-3Hp>i9!X!yl7AZ9zXy zk}j<^!8{;4VGrUqZZC`LVo1~AwXj5K+_%Q!+?*Sa$)4&)EjXpfHw#v26)Sh=tX`-M z)uUKnr1ciY;$FE~SSCa$AC`}_7`1){Pz?_k|C*#^q#ijFkds^@~`9SUZC~F zyW0_vTV^9PjNxj;+*!&ArIa3re*=m>xuE{@AxlnpseG@MYe&g@4@g#jGwsBF%GWBQ zbyYXas{%OET7iVQWnCcLQeT{@-zo<3Y{6geOsEpeRdZ1zrA#n~meouap6PvM@bi+~JSM^cG~s2QGiLe?0R8<`nmk55=n zOjQLQwqEU)89n2>Ew=^r%82zvh7O=`C!74u812DwW&u5Twagv<9K(EAdWS0jSxxEm zLl$5e^k?k|w+-^20YZM4Sa2D%5BJnJ8dtXUIvH=hvCN6=9^ykabP~6Jihe{v6P#fA z)s53wuhylSw{MtA(mJg<#*Wb3RgV`lS-CJ=>mnw3Gs1%m4AYz26ljNd#n?R7X)C%c zwYaSDcRg#d2AL9renT160mP-9tO+2NI(;AJayVbcaA3ACe-bl#kN{XP>_*8_w2o{k zmDIA|g(=p=WS9espx?UOh0f`Fe1qu? zg7%?{;cR(!H}2>b9?bz%^s5r>v++(T^QQ(*`nB1RBnPW7EK3CG$KioiWfh8=yD=@A zsTB^o=CqR(agoDziP_E$Odr8C!MxtMk2CF<){fWrY4BmAcGXh1$&C;9fFLB9EM;~G zxm1i-wOUJn6dEGtY6y@)ePx9eTS88X?xrD!%*os!!bH?im!7EGjsJcQCcb+|8n=El z`Ql~2$+o!W>GAj@e%seu3r+6Nm!BFM(rdE zJY|#8XclPE)#s>Yr+_t~^}FDH$y?T)Aw=l{romhL85tSX%U{4UD285)?46|d)TL3} zdhpU9ozpHJcQbl6>*xc|8k(bDiaK(lO;3B@^sJ~XOvrz#XNOd7$f~}E-kq}Uoh~{8XB>}fAln90rXOMl(0G7mz-y7HC66SSv zb@R=!aUfOFVfofLY&c6ytb<7fz6z~11wC%#X$3Jsmb$Q`v=Do#N*WDOgt( z1ld4p4N=t2eFwt?===Byi*BMikaUYqvwkN*q7Z81cB`KY>5Siq+R0`AQGf+ky0~lp zcP|jcb%XnPJS?`n0wNP-1qG-|JX7qezh}0eKUP$bZEkK>KXhl)i1N~h!~GF?E;XCt z%pD`&#cL@z16Z_!pYvqUbxMFXp=HdP`5Ll`T=Dywf~vtEa1-FR@Xa9~fLgiAQ1rID zzAi1JfOh7mKUcIugW%mgT@x6|k)}`PdO}7!C}!48xDaqMytDj8c0^*EA>ges?nI0t|3DfamS2GRD={<-o&`e6{ay@vvr^6a6?+w;;5*i#p;N|IygV`Da?mKg# z+694XdF=rwqiV98UJiL-#Zwmigr3k)%&2D8b+(XUxs+*u=*{5@iDaiJ2sr8>ppo(s z_;dc_&Y8b&4mOR~aIEsB?6BkiAP{pe!8KK0v?vI9zNVsT+D*-;-QI^{bTlpWjEYxN z8>_n?pktWCI-Y0tc`(YQ3JH+p*n2uv{&sJN_N^Qz=m8K_JK<_ExQG&rd41ckwKD`L zD=X{1y8PR-d~$M9WjP2h{P?jzF`NuQ|NQCp@BGVk4^L%l{vXnma6e<d6-$kU(1N+{12SOf?Upv{A>Kir!q`wp2*4oe<BddkgJClox5%L4iAc`tkwGzwC!`9w@F9{%jm#H| zpGHW?Rmz7*mF zfsI{cXZJ;#qYNw#4U()OS@Pm|M(uz=z9zOTdKQkluo^6P z4hy7Dd>mOOx6gIPCzp{rKvo_*kD#vRI>jdU=u+rOp%u?!wg z{wWu`vnDDIn=xWlYjk3W;R@>Exykx=#>5(YVDfaj{isNPZDYcyy{t#bcJ-^ryJ`^` z+iXsXh)J_U1`_oLsM`DS^&H7n>y#;Y4t(V304L$;nVXt1W<61VM6Uv;*o;HCU&+i0 zfe{ehb;X&HB=~?OL>I==8Ln#)lj$NtW$ms2j)iROF~|`ewvaIwL2&T;}jn^d*@F zkSO=aLb;ugi%(+RAby~IIE**6hR0pkp3aZ2rNjG@VmD?nq0WT|X-%eLY&1Y4rwf)Y zRqkbQCf#14YP&>FJdPSn6J|^yd)@(L=_o-Xu*G(mNpxwn-DWUMZi83r5OI1s!^A{E z$ZIA+-xHfzr>qKweUKZPG8e*&M$Rkf!d9EBo-)dD-t4B`cV&3_qoCk?kn@fnUY<;t z8lXmM@YOV-Z&y5>!mZeW!fVj92!Hj^+0l#0hqj_@6d2s< z`(%~zi1Qa2ctdm9%!ha+xJI*OJtKFq9ebzmLy;cXUaJKMsT(KSsCeon8Pv#59Vsx2 zb5Qc0xO3cDN zVs2rtH`Fz>w0yX{5uBx=)V%3PVtt@^lH0m#{1})>(w})(FqxqH9*lYaMVhzluw={g zU>();5_n#%ZqCHxALc{6AH#%T>655emOSEcm^{z=Fc9WXN1#74a|_Wa&Y)XwE>w4< z`T&x_`&j}6YM?Vi2h4Vf!<-DDIy|(1nxyy{m%4trirN>WsWJ;Y)qV8EwdDze2ag%8 zeycXm`W9d-LGRTIv1!mU=lzUq{J@w6*B9~0dCQv}qD*Zc9qSVYT1(X&qvv5rq^eBC zT*qD|t3B|C;Sp{gtrL_l)W!Og;TA$io`vv$f$f70l${UNi`(RNajSlW$I=?Edn1@^ zrz|S)q2T|;ng<&Br=jn&(&R9By;7xWwqYf;-LZF_pv2R6qdSQb;I)=wS^9S~(Q*>> zQx$CGLIP#R!ky%s zCO)wT2+< zRbP`KXuZC~@fHjt)&UYSR_ZBQ@Fvlxk@WK24{pKbrn<{#zB2bg`$h!EJt4y4WZ}cm zxTkt)v{V~)-`mA;4@i22>{xi^@c}rDOIHH58}Q#2#7rY1QbAZ;eVfLfI%XUXsgYUs z{OSc8YSBWh>sj;)5+#Z)dWYLNa`Dk27awEms0)9BKjZQ46R{gL5&H-0uIn1#-v5Fj zO-Wyk+JhkApa+6K;DT9vs!RITEZ;-Gj^nAKxXgf@OPbRJIwvdV-N}>3;#GQS58Dce z-e46uc(Rn=w!#PK@~(1cTd!_t7ZNs4mN{g0V>9kd3((`n${7QhaD!x-ImozoJK@J^ zwO1}nfHkr7TjR^1V~f4J9<0K`-;S(7$q2TNjmOs7 zeglASMUT6FZVn3CPay;T?0$@$TP{)<#C^GcCRhhOx$voSh($q2EC#A&6LC`?34Fb$ zKNm%T66;$mP_;7sszY5YX|1rzZeTH+L5};VND7wTw*Ed;t8iJ94`pTA3AG8a986u`E%&_9!_ z8XRquW#b@oT2*BolosFByCVL}Y$TmZ6Wn=0&g6IYDk5pxW}t}T6&Fc2Fs_Dff;Swa z@8Yh65K$lXbLFmpIzlgqdV){)r`KCgMih;W-);FvMMvLgceCz?b9IWYu2oz9RzvAQ zwYB$;6SK1Ds|4@kS|ae#k6|&tIQJ=xT@GRuVNV-^zuB!~XIx<*z!mfwL3XNPEYy?q zq3`iXVimEeq?p?#d0|2h3V&*7x9WY+L>$HH_g(bxMu|`FEvS~7t}gt6 z*FnS$u6Ih#$e^`2H61d1lun3;1g9rdglo zhtM<-w-E7ltfiH&7u8x}d>D66p;opmA99A)WSNlqX_E#g{mmj50jjty#9FqO1nj4D zk1>t01RASQUAMi7ySLzQRvw;5?pdJfWp=#QQ@#EA&n{OCoyfhp7KC8RD?LaFEd3ol zW{0(|xc0S~P3N@2F0?*FoI2sTD}CRDl~|hg6BmpJV@Zpqz7&(f1y{d#;iVgGi%JUj z-v%59gOPPwP9!=tHFf4o;FsV2uV2g5JIn_E`sD%Q-5aUrhBrz`O$`O1@2Yd)UwRPW zzX3s=LBMEv!&21Q;k-F0egS9#CLaL&t0S8Ka|C!qs9pwMilia+gHw54h+h1ri^?RD zS%F$vyJ;Kr0q#A(JrD@SDyEe^GKkOxqKy`+tso?X`pTlhiqna&FK&6oJ!HmDIQ-*g zw@&eA)9;nkQ>+r{B#j41u;GCbsVj_>M$9SucMC=yPf26R9slgO2?rJ5uUx&nb{WCUCZQ*j?_Gm zcUph~s(*rrL;H9gn8ZGayyirtQY$*ut z^aM%wNR>O|+3YowY zlDubf5gaNsLqpFLbw58el`wa780fhb{lO0km+LidzgOk%P+trCjtj*|z(ppc#SV!eEAbWaGzLDfH-vFHhkX7LzQuvoYg3Z-|MBjEY!61WCzRLX|=CR#}=bSYdi+(M4 ziE4crWh~yoiQqSRMP5#7ly_obcR_?BexbSfI!(_FxvauV_~HQ7KDM!@+qevzbSJ5D z`GVNu!?s>t0I@$D5Mkj7V-{c?mo~{2CwmTKW?KjD8?~RhGmI)8&@=59d)|kDC1O|w zr3kd&zr)i;p9kmm4WOlIL!xw@jL@~Y$oYPx9bs}|S)a%o*GxOra`mY^GCpvg!>Pk_ z3hI7Hi;8c5K=J(GSI+ZctF(VZ1D*wM@klV9vBmG-wqlzbV-Ytd1b3ttg{egmC0DSA z4hfy%<#}b3JaUo{DU766fH=ebwM%<~&xqw}kWQ1Iv_Qc1-^M(;-%$!`P))$8A6?CN&gZ3R&S@GF@lmjdo~$g7Dt0~V zRNfXd#tu8H8keXGxqELv7HzksDmM)?8L4IT269vp%L!PC^3CEf|-%E8=wX*`7d^&@4{SWWIzs;JJ4HvAC%1zM!tz zNH>)L6${U0MyLz1yaPKoH5t-DUkGvt9Vi%KXVoC#8t z0XSBcNx1j-Xw{Xdcq)`cek~N1MH{wlFrpd75+2<`54bTNG}hEck>MP?b2i{ZO-03I zNyGGbi9&j4R&EeZ*G|vdsuWb-izfru4>fz&u7B2POkq9a|{@(v1OdmgFx zkY|YmRY_B8b-U- zvRZqaV<$UB>dfP~btTHasM~Tb$LhxIfZ-GguQyw}t}R*4HV$0Q@*q3*9m%%`{ocdP z98Y0&Oy5CD0CrP48jK+AK%JHo@%9r;k1k~NyG6dJT9hSB7SQY*A@catVX)b@t9X*%+!e0~u5mEhY4MU9l&Z^gHt0~5j41|4YGz7Jl7-?r zDlQ;$GbZTdv6TcYs^8*aLd&nXaJ7oSw*#%i@Nkj{hCe;e8lLPtC#06v=^m6&j$hiBZ@{t9`X5A zq);8$wKP?oEx7RjkDd26FCB~`tXlIq9)TiO(VIc{%#3ytw@JUu!VhdJ%c)r>x|xa{ z#Dd#hTaH(gOdwoKC))WI5|CjstI~si^;)bkFM&WS>^7lFW!8Pccv@J`f$?L3L2;u8 zmc9oh?_T&7KX(?0{$JtIBuh|ttr9pznaK%d2xQ~tZ$r~QkFXl_OO`bSO*mPAYocKA zt9Y6g7yfxO=7Vc@5Nrk^@jATH5#i;$Ks5d7~ z*0@{m4C%;+D!}w^mj1Hmz{v3!kIitBre+9KrOEUiEt8u7aE}%N->%stN z{#{O(r}@X=YS`xZuQL8#MLUTh?aw$aoaK55QZ!FlGTU%7c-~CWOkYTAn%Jd2V$ORO z?2Lreth-IrWeYxAm8%rVrBzCrM(oU(y=c0|wA#dT-6W5P%HmZtFIgLX>WtcvzXT=~ zhVdNgTre(IG;&2{!1Isj0(vyteh}Nf>yOn_pFVxOTbw>~46ml_ZT-m#^xv|Zv%lQ|~Ct=_$qFavw96qL7+wmSspb=CgQ-%9(| zL#wV3Yy-|i(FxfpoDUb(kFx+dzgjM3i9ZpQWr9gY=uMhaTOdbUZy@yH<&TOeE9yuUqjm>EuJ?I$aU8^0pE`8lI60{Pw&jBGzxwZ8sx z7WFONbUyT11@Xv}X%eDD*Ly#CpJuy7gu^C6#za|C(N~edSo(KV$7#}Z~(dC4>XeORRv7*y0?)&Bb zsn|CSk8FrGNXi3A@aM?Sa%E3%G0l?k6W`z8uA*8md>%f|S0~O<_~#C-^qVDq9m6FD zR_!ko_x*V%JVG6i$V`R2x45iE{Ms}|jly%Cop5eBlS^qH;M=JO{kwe? zj-G^A{Q86lJ?+F8-?=8OB%+WMt$+IA6 z=lT3JdN^;k3I^L*b>p3iR7w3Vs|Ci{CJBR?kfd`+p>%E&zj zrwFSc&a)}KX8G`(>o&s8tJ}CQpT|&8{{aoL$#iEqOHw|3nfuYi48X96JCTa#{C1A1 zk5=c$2qUq@DFK6;>E+$`w~auj=#9(rVYEHFAGab%rJS!B*X7AM2(0?udi#o941_~# z;{Q{wAL5tMA33`JasH)$85DFndJ)i`(dG8Y^w{eQed+z>>zUKXE5cOYaLfcszg#a* zEduskPdFNiQe!S@+S_L)jN4DrIM;;)#0?i+dkUDtC3> z{w4S1%NI)m<^r*?`j6MkF*#RS6#iz(B-${meZX(=$|Z~1AD!&)s(kgpXmcjqWIsBn z?s@fNNni(svjTNdT|YsJM$#k`*Qc>48C|-MOsEX^zo)3Ajh%X9a%c2cDRS^(B6=|=C2eiW&;NctGV+{!4gd}FvDiC-49kJn(qv3h5g<8Ycvt=^ zIZM);&#C3GK5yIJ&MqM#ukB|f$HW7{2&bn7PE^r&sy{XYe|=^>3OL(nkNwMws4uJ`HMn}w`z#Wji3j$v`<`UQ`6foFr< zg2{;1HK`1-V9uPmIaUV;H%{J#WrwE1wumCq`BiT0HzoxBOF{g*hkKPRnK~=oCP@7& z81cD7XL=gf*HC`kPwHr4yesUIa?t1o@^xvT3jehtMR<7&RP8P6Eex4Rx44ObPlvJ%J^IEE^+C~!aF@B8Z% zf<3TI0Y~yiu06MBFs5(5Zxn8Q$L)n5F(#(R~mUv<=45A(q>SpW4@-e*cn3ZBGXs zCeLvznacXKU8UBH;~k(drIA#;H+pIO==L?)lf&d_={hCS5n_uoQg+)764H!f%EwZ4 zf@rg!xNQBBc2%{2q4K2XK5(ymxW7DTqb8`e28aH*RhGKd;_dSI%W7)w*~9C_=c|F= zyPZ(mFM`hX80E5k-(?;XqN;@z-^lZ`I)%{~$s8p@-1(JzaM>AsH&PAUQQuz-VA# zpxu?hpx&XR#n{r41LXGzE2pC&IQT0dN7U0EgyXqP&7;aCAFcrmd^;*I3GX*MHvBU# ziPKg|BK6Xfn0tv65z2KAo#YC7^X2!Q)3VLOnZrKi-s(g-Y|zzc^~_k)Pr@*_9vkl> z2JW(>7M&FG=;xOgT9vk+nRamzxA%2UZAs1@+Ar#P#rLT=gE<>d?%U4upm-hTzr7sb>^|i%5Slat=;tgupFijSp5io*bCthr=K}wd;5e^X zyLS<4BKF0b9XE_vUKj()!uy$!nd)q;WDzyGuCDI){>$qquC7X#`kqFhfn&bIs zr*(M5;%!Te8CdnMN!?oifxh13DY>qxR*L;|uuyyUSY!wPJ;8?$)htQfL;$890+be9IuP+nu@rM|)juqL79UN|bX+x+{;2oqFB5SV?TBqoMQcqd`YZivc-XXp_EIV$^N!XGk)o|$OmKeq1UXR-3D+H@~sxEiRt9XFi_e=-x{fY1iVrOdn+T ziJsI=U&_kU6=DGkORh1TE1jC_t@ll`})roqn?@0cUS41-v}-{ z%TXd)7`g_W#zmr)zt%yUj+gLGFxl-rrFqea(~^DRlGYgHYvCr9Cpk-$fMIzY97A`mo17yp-k!Jw8Een~4eYCf38yE9#xyCtgm zky`WP)05Mp?t;XyQC9{BI2qHOQKgv3Ut6C%xRh$in6Veh+?kDHn-5^|U7ziw(#42( zDEdZ78*9w2X>2L01IUF1(SOQU%%sz*bcX=l28+mGw$62mke8P4xPJADK5XCQ=`r4K zSei71O_v)+mNhHxpd=vA-T^NcwK+rfwn69sy_kQkOJ1*AE?$ZzxZaO?O>`>0f zw-IJD7=B*%u?(3_sDg_EgX-CjW&W$2+}wCx!+K_EX~x;v*+$R}s%*b;B8?g;OezsQ zJy&kDySuwC;{Q%do!U-yYn_*w!1tp7KHyS}R+-A@HFtFwB#(ie0En!Pwqhrw> z6pqU-?&@6GDKsJIcDgQ-4Hc*BvZk&-*xY?I6Otw8lDJ>QXlR=XD^H>~`8ZO*Vxb>t zIWY*}v-4pI@5H0=#?Zh-XAWTTZZi=0JwIhBuB9Ey@3bFo%BzXHfK@B6Dz9Mtepy1r zD=fJ_e@#yxM5#pH#!gYCk@S{e^hAi9jAw^4=>C2Ea2vOD3N*c_LwloZkOj1ZR1y>< zG;(DaZ{DB+Q0-_)_4y^Jh|)-UA%VQSJOJJwy9a6%jeozlXd4;DfTbV_gE$3`Zdp6V zv@2gSo$x&(#J<5m3zQ9AA$C1N(1V_&lGUG|uy66yW4b@9PB*LJg(OeSl;aBQx+6oFdnCaMqRJc_yj}N%vuzp|?6v$q z-F$O1#`dBlA6A8#`D)E*A@0ARWD^5Vy_0+W@_upcldY%bo~_9?kSi{q*;Y^2hCD?% ze3f-FjL(Ju4zdPQgb;2$+tlql^i?r_Q=H6xvqPI;W8Y@bD7LisPFQpzaz#&;38b$v zQrhw1ZMFqEtie-jR;-?m}VJD`CUt zQrwTFMtc57&&KQx%2)DJJ@Ud(uRaM;g%<_w48&E%an8r5taiS5yS}}M^=zQ7Mo+E{ zqj&TzaAC}&f0a?}0<773>Et1=o_RtZRUqKK`C&_!;YRHTU|)oGH?vV25{ZvQJLQfj zb*hr2F*%VUFmDp&j;iUtq<%E&8UE-=CTf{huoLDG0>t34l=dbWW2?@6IN(ma^m?P2{px4P(UYJdhdPC^af9-h5l6pwa-h^q1~Sab806jcE%eqG z*U&dp!wA$esP6>inZOJ9Q1ZZl`m2coPqMj87l+`Z=onz4&&sLDoIS#DmBxm04v%4x zMs9PIRQX=^uf6S_KLIOGz8_teiIPQ!QX6_yV^m)#@;E?IflF~Wv{RHJ7TTu{F_dc| z=V6Y7#JGx;z)fDRsN`)z<2>zEmdn_5KG>uiuG99sJt`L0GVsf{q? z6Zfd*SOcBTYMwq1e;8JG|11hl{Nd(RL$#kFDzG|E3eChw$TNOB9(b@*(Y`8;p>OQf zjKU-&CXC~$t!u0jNnY)TcXqx!^z^PZn0VyT$LbaLvrkT_1r861*X79;BQN!LM4dSc~PI~q6628d)_VTa&JvF@9w%qfqeU)O7H9$2E!X>S^L+w zqghveLh8J6Wnx^R9W#CQUCNylN~86JP?Bw-3?L<%qU1JbW1r`@1)xy(OITVE*z8hM z?C5@nZB??;%h&T-UNCoGEar5`XnOyck5(D7P;{0QCiR7rbdv6h+ z@gtxm31ijcqHnV_?Iw}akvO;Fo*Lvg12Me;c~W=i)`Jlg=CmRMv#ON^dY_#XdMuy^ z=QvX>*BGW|>L;KzZ-Gp{0e%?cV1~<69cNqYnNq&tS{MY8@EN$jwiNe$Cgtx$f)a%< zzg?{OuvN9F8usH`Lbsy1YlA^{QV0#+bjkP{!WMy{E4!sdX4#KhsNeo`U3>p*Ev{)_ z(E9o7UtR*x2*Dk@^E)8A#37PXp)@=$wi>LWMjcGKLxh=dieKCd!s97_=F!+HBREBp zVBl1@IR91Vn$@lL0xf81E^MW<4+aUAr&rsfe=`FB6L8+>9TVH z?e!syH`E&A;Z1aPY3~4&lW+XA82G=u8tm$QZ%o+SghZ^aOu0f})RFP=3$dklzq&(e zC~yjEAE-J1^s{8n9B?bT6+jw^lftoQV__$Tz4*wGMF~T3BLpZUD#0!`fh0lnUZu$W0P+t1IcWvnBd>CjIw4FteIzc@TUjeR*}B9;lwkE zhA}moh_FKh0k3a5(sgE~pstuU2IgJ-Nr)Up8hxAmSoq5lwHvrK1X;4fb5Xa|NIqp4 zGQx_-CrzY(7_pKCy`vZPzE?ge%6>!#iU;5F=tKEiDr~Re;$+-7Jq@}eN)I@yb#Vly z;54U}jU?`u{{MK)e?5gyN|=ciXW=|@KXUO=QrrRA8H%*UQ*vsd%%BN$S(GL7U1`W&Y3G#1 zeFg4n3z0OuvWLHBIu-NcYoO|P2$Oaa_fZoMb~23Ox7xzhxROWT@4L*8m0+zO9oPn1 zYXQezcH$n|$GZK<_p8eI9Tlsss_CxQIk59XaZ%0IDj(zj(WgCMuq= z&zf&2wfHrJR4YmNX|%x`ybTiW1t ziu!nQ$~;JX5q?~~37=@b`hxY1;3hPAcYZX5Xw8B*>gzDzf*2D>ne$(e0ZoDg4j<;*JuvvPHjG1bht^*-z3w5 zL8+sE+_8l(+MzKrjNBF!E@nmkXEVrv%-y!k+)k?#*KW8LlA)=}r02u1(@TH}IH^FJ zf^(+GQSz5J@t@U;w7b+ECW_79Lny6ZQCiefzQRQsrW)HPsp%;{%~$`k2a{TR(&ew9 zL|2^Tt@@?(;(*TWk+qCZB;M`kawEL%~zJ*K5Bf}LndVE?p9K$YB3Slc9h$k)pV2XG`#pxN6P&F+?!yT z`!oC^R06178WOVMuE>;$ox_hmr!weW+)bkmNKnD_Nmc|TBrk%$9tNt|LPst2P!h*$ zF8S*LN+D~|LSF8n9}7m+CO&i4;x4p~ItF(;k_uYJdBG-I+HH$EK0&dMz4X=&q9?;& z(xzDp$JLAtrl(P%0vvLtvT9cdfswH}rfvSUjT=7|;|&lDLruNkKN|X)OrFG%H!oD4 z`x(<(X`fKu@Q+SiZKm72{K4~>P%Pb9tU1|Kv(9&^iSJlmzICNy%{8eqrX~qi7sCHa zDeCd@=vtBsPX&2BBVZ9pL|5J3lwx-G$P(Szj!x-s6bP?H#ntJ?I`9iF-2`~tUDa^` z>*|5P?MJBKR}-wDj-Pqo0vptZ+#TKCe#OkW#(pFe10zUmBmbR&vW}}mDynJPVdlIP zuzSkMXgG#tvHx-TgjoPLwn;nq^YM^T>TNs|h+fE~U}aJI=qY|=;Jr8M2CTf=_TxN> zn8k=`78nhHcJo$$34~|3*y6ndv!|mxy`2$TjAMfukasu4=lf zBCEh=4HKvPN>gfzR%<~)n-0%H-Gpw9cjVm8Cq1D>H2G|zK=%{l%{BN*m{urY{V-CD z!Mz{aw1;U~{H*5j_{#AG>lIeXj}`Lrcj1C4Jv#HkUuqfK1Y@~}VJ_N~mS}KT8Baue z58K=Wd80b1Ou#)7QK3R|Sbi7~<4)wkFyNvJCX$Gs(gDzj7p)0u%F+`6W|WTmzf?z+vUY4tYl-6=*%r>Eir+*v6Bo)PiDPr_?or%!_*> z!?iwkdi4Z^VGN5gDnTWT#7n1+1=34p)W+58*vJ3;MX!wK;p+>2l?lYp@2ZIl-gtTi zY-afP~}uQ+s7<(zmz#2Og$d1pNqaU&XVMq613f0 zLf#5KQsPCeR!id@1Tm~7aFW~ZB+o0l&RK~DvLtVbC+##R8&@dOrm6Kn_+JEA1yR*m zn6^_`W#kxXsm|14NP&isH_@JQ#K}+0*^Y058*DPA0ZYVq#lB#D{7sVlU>=r;eOxz> z`4_s7*GQJ0RNnc(+|4!BR+73!qQ{BW82w&^LaJl~aA!B{PS)7muu%m`K|~G<(Y7&> z#u3~SVUGF66t2N?w5EnRfR0T4_F5EG%}8cDhsBWjO<$p6SoDoR7@aZaJFWSYeAijx<++&&lAWj=OE(r}cjB|gej zs=H9Q8*Gffm`MDAMxkaHT2tF_5KhFv9^tVnz_Rn5Axcc-&z?NzD+g;cPWoD?Z*$I= zSL5ffvS7OEyJx}{e$~#fEre;`v-jsA}Ee9H6;VO%Pk7Th-ZgTXBAQ zZ2$6&c{3X+hI3uM#?$)MThYiDp*2uR*oHc_rP4{(&GQekN)RWHcSW(%R+}uLa6vn^ zMYS!KP{+j+dnc!m73sjE@rN~&U=;K3#wZwdj_c`B0dgf&cL0z6ulaCo@E(vZTJn|| zZuRpF{P+8<9^Ktv!?l^c0U4saxq>3web8q8t2gq@Z-f?E5INx>ISPDGH+Yv7TQ@R6 z%UAL~v>B!keXoT`F;iJQK&Gffx~`jt7g@${UQ2Kva}x?5fcqAk{IJDy2(P0GW?Jji zU~!4^9i|lOQR^cck$i2I>Xf>B_kiI4DI?K)w&k9kDO~@1@GbK;xo6t}_C)2Q1R!n` z%dEgeNlE$c|JqYtZlglcKGkgUh*Jx196#O#VT}v&e+TL+oj7HdGvjse5G)Wq1ICmr zqxP7tS)xAq)*D6FaXU!4_dASii6RknrO~FLPCcCGTNKIEM>%U%FxX$9U>cbXsQ@G$ z+dXCPk#tMZf!jVRCV%;NaD>L@e+H^I-2ej!^pH-^7p~($$1@y~zt~p>szOAEtKYks zul8}qPrm^=FKJJOsl|f9>QX9vpe*Ek;f@$0)=nE?FPwB>|I|Nc;P?3B;G!@+ z>Z;e4Or>3U`qd)CN{?-FQ?VFggcfyUd^g;xB^ybfqyY$!2pGWSWm^kS@LYZhD9p9& z=R(GnR^|Ub0ja6aK+1>O(mQeY`R3-Pu9cP0b8+eb2Wyi}OtO)ro*Jy79E9}59LLD3 zZkW`207n;I|D|G4{98VxnKVfF$-@y`hT*~glm!x%)aLGPdCr;cF zx4`DYUU3Yz-YTXVsFAJr5Z>He3pRA2LK5^r;e0SG70F+yNTzQHMVNyK-{2vu7JKM< zw##TyZduv=K+qvB85ltyJlU^|Td(&O?pRHfLtBedu5YgGU+4H3dyN4)J^G?8?p2c1 zwauw1e?|K%^|(m(|9ePFfw8VYWF%DSI!$6{idMpj>%-%&Ot_cwm48-YV~}tIN5C5f zhFY*UY5ROV_cgn-6n}}LlmfZ?{|#=W=B+2R8zXZoUZB9-B^uBrOknUIx}a(=D-$^Q zmz0#mf_VSug{Ir1;uGmC9qFteYP()5iP%J26R_A}qnc#hd9k#3nD{z8z8>Z4a@P#j zS!m=@MQKr23#E8`rXr+Z@yJRwRy?G7Mb*bu&y_M6@Y-sROX8h0Ox@y79EDCw%{~gf z@OY^Xqu524H|^Gu1T>no-M2;Cw?0SZ!A;VM!DjK4SBGAJN{9r*gfWIn5e&aztqP*D zWPFqy9l5B4tpw!Po-|hl{(A!Y=`{~uu-}VMZpVRc8tms!dhl~MMWSfaM1|h@XG{5T zzt&xrOq!=<)36sn4a<4hR<-95+@A`|=_LtW{o-hxZ=r|X=U5+Eep=v#dWDc4M1drKDh`%~k}~+xR|gpvM1ydil?liRCb%G%*MK)gM_g_n2Q$0I7=8 z73S;6kr90YW_bo6_eHL+uitY*K|z6LyKQqXjxOwG+C4$xN;=zr8P9uT1nYg!)oq}P z_0t=}jin3!Ti0EqIgN5Lk4j?Wn3opXPg%1V#K}1^{d{BlF4mXum*7O+PLYCMZXg${ zp|qfwB{goAwIy(8!7H%J0prHfDq5{vb@qm1*!_uxTr*x}WyZz`kh@KJo1(kmis`?G zhOE9RqEj9hWNHg=H{rpDZ0gZ2qwk;YEZ0|7L7D?XUJU5NtI3%n@u2lY6wOQ?yCz7Z zvH#1iZ&K0xmL>x7e>VYCqS3U$-E`CW;h36iYr;b3}T;0G;P>HDeWM(C@j81 zp9n|JBLz@#j1e`6NR%_H2Z%n>LW?Htj;O_LXSr7bsOVUam@sA6SBwr49?9cPwwh4% zIH9+!*7s^8TNk(Q_CTnO(y?#~Zaff=#F}FT^uUzwztAoVA?s`H^1hw0*)2qmhpP!J zk2e!8G@>|y(v6k2ptfH$bIlG2cLi!fFqkM01HFqtPA&}^*8%o$?Bis!+kILZRy+;{ zEyps`@36;SW#Ki(rMk}z0>1aUiaI}x9MOPg4}EWl&$~*^2ODy z^)?GGgY=)V=_75$=O*&!ArXEWfavU0Y zo$_gwiyCK&B-E4j5>A2!=6LDunEs)k

39P#<(cuGVm8uV31ul`GC30}sHAbkDlj*t8qR8rF z>^CRNH@(1Qd`QMfOE1=5^}BjF`Q%Z9{oPxmjY+C}A_^nLrtHu&uBu^a!-o{{8RFQw zEW;jQRZRH(gbV{o(_{VWG#O%Fja^_Ax10!ju3?FYfrN0xX>1;LHdD21C9NQw@bjAN z+sO}n(CFs;Rkblie*x00rnX!sijBMyi(IldY^<)!3t4OZwNRv_+iAdr z(Ztj1$9@<$3B|Of%~+-3okio}3N7JxVwKqxjw`8WM;bCJ7RI#XmM;R|ePChRPOdHu zCwWZ~a$MYs!YcIyq%f9Ve*i8SxOW<{O*(e?WxV!R~8w*d@aS$SMmIM~nQ-X&z;Rk!3 z<+Ici+8uQRo|hmfs(Xj-nv5}oHOG-57b5)bZ^~MUdTH#!nTseve-%;kGqwP#gJ}dCdmJ=rpJ~x9!t`K)$PqUoTcP*7yPabOgLuWlNvFS z748?6udytc+`y?u89-pl0JNxvgg!Bc=~E-OL9aK+KTUE?%(UsMJ^JzxCf_MJS#T@F zqEwac_zJxfvd;baPAOEHZV^u8MTEcNRzh!@Gg%QpkTd%=zi)?fWfcflsK_8puKZGb z*y8m0QcioQm5Nj>0(DDt-zE?vWgbc56{vaV z%33JVz!70Yz{yj2fT{U`MhIin->r7C->s#%a4^gOA+l|v_Qfk&!Yg;2>j6R!G9HKF zUJ(_5a-IFoUz)VpVrmh3kbaWXQt0}g$F^#~8eC!EO~)776?nqRs8L2R7)?vW(@~07 zsk@H~@4}W-LMfch#PZX=<%Lg7Nyn2XXgn*wql-IJwN-a;P^AC05IRPu&BJjKeX*)2l06?WaBLeh#TV%j#^ZPAcE0VGXi?yo4WU7Hya_~WL! zew%uvZSaB#nP#rYDpypyQH?RFGmG^!PYSN$cQPqbSGgj!Filox#TnwMG%VeK$Dwuh zl1AJlan-QkZ?iRYep8~T#PwYBis3>P#i=!<#lBNX>{}G<7b4z7Gkf{jr%s{8H%3Z& zp8w9twvDB?2EUqUVv_DDa0x6>dfptx+h9;tA?SO{OM0v=oIwyd|LRLXs6$~~u2D@k zmM#g)D};$~_w9F5P`UMU*7K2KEX@FU7gI4+sTXf3UsVWWA1>b=~)AID?W?E^da z7ne@gEX9mPO%Y2oP$Ow96`>AJaVlz^dXM-1_W{Qk_H@^&3NMjBhG($5=viV`J9h3WZO_D?3@KS4aO{kMaTE~fqHK@04%vmwJ&VM?) z)WcWoggf7dG*7f|;T1$t>j#MXc8T&z8xf*CqqM5%Gr9^z;|aBkM)+XtL$7_2OI*Pa zSz{o9U?%49S1-jRIq%!_EYf%?Mi5t@mBJ!20QLqU-2jvpSi+61Ns<3l=z+8O{gRx- zD#5|6D5=U-qHlGx$ohs7o}n6!e>Qp@pDqVMoeTBkE>3uzV~ z6*^$a2ss0;0oP2Y*V)9=V0HV!@F!mQUNOIyl7mTYX$j55f~U$vx#Q;R)-9;@L%lLf zMyOCOq9zEDHY;@X)7VJs8(T4HGoFO=+)t`*g_D1s4)uohzcjzYsWvwoPvZ?MJ>sAQ zwPKmBc`8^ZkfY1jt}=hsQ?HB7WdYo}E`E-ShohN;F$#q+p+I5J7op~Q=Z92nR3oh# zgRO>_%pvn|8(6HW7b!9!!s~u04LX3jYUVlC!hMQ3 zAwc6Vj-n15zEWnV3DHH4#_9%5sIzee7th5e=cy%2af~Wa`v~(-G5ix zgXm-%4s6`WZEeL^WdpCo1`@2uyRdZx<13c>Ox0Ebz4BRpGtTiOMa<5JhF0d+tzMcu znEtw*rj-%g{b=<#fn@a}8;54hPO0UBgW$8bq~ zT}#K?F@Neg=J%+Gc4!n?3&a>oX@^di_kWY>z?Yu=6sJNXwa`%KT9(-c=hE{iP$#nT z2g+g7Kz1c0v=$yysG%QK=*6?c?H~Bn_ic zlt7q9_h7km9P~t{7`xt%Ij*PROJpfFP@xgBRwTPKxhSxBCM}gBKdgA_;Lo=yYip}5 zy}Mlm^rn?~0D%3|W>61Jn5)@=(u3kr_^QPmlZ+{+;{f^DjmJ3XbKpSS3g^<`v?X~N zS=P*S1V>64z(q3k@v6OI`3UD;7gELRR%bM*wJ?m6fL^nnTs$g8X5z6XW$F+~wvpf> zw^ACu`1_>>p?Y-upO2P>F9#7mP#hlmmeI@MWambBEum=_ z_Qn|I5v<5BZ8uqLJ&y0k0P`ZHpClYoq^^P?tOdA&ahVYJ2)LSdWR2r%=%jRvnyWtM z)M;Ex-biqfEWyWWGphk-Z_9~s!O1pLC(}6b-`(rn(pPJ z8naVkSEPY32ioJ&}HXJ%o9QChUnc#x(bWDA|<6A_Y4Amwp zh9vF4iRfkfx$eb%0WK(%MWP;YdXn$3Jh(-a?J?5voedZ%M;lvrb*-lHvX}@_FjM+R zXvzyC!a#6gC(gb4S2)=x$ejq_x?FpfMQq6t;weE#SVRpZsZC&AsKac{a@rKS1%?-& zDX)bNWhrhxhtbD&%Ce6^?$!c!0uE`LoZK#~a(iSu#^WaIfZ3-{pJn*|3x0KJq6k&U z`Ir3fvrxvv7Nz0N?4J;sQlGheueXl*($WkB715dQRSF^$+yEm!i(jl}3}?yqU(}sX}LaYc)F1 zfCQ}%$Cs0Y-!cw)k;Qb^;~`PLYZYHi;F4byTwd~^%`oAnbtknYK{8c89U zoFU;~oanmc?|$VwcLWN{O>FGpv2#J0N1{Cv9-eQSH{Ir~w)sC|E-Fx4GBGz$WVN{w8UXg?&5jHhHV%u~^%nOBSr z)jxgYnfd!0kJ52jHl+p~_k`H}B@T`U;=jVTj}BPpGa35B#)(bT;V$Fofbi<%MJm3# zYJ?llKKOh$70C4eR@j^K)os4XZa1Lq-`AJ(9o0e$p8raV4;T9xd&5t(iPG&?TWz#~R2^sJ~W@Y;gPIK-9VXWZ3p!5Ci3@Z&&HjSh2 z|GJge?iSZ)lH=`e3U$Z9#9d*rzi!iLhH~7wOvPa@RF7p~&pAlFl^G>^Fcn}pYXI{Xo_C&bu?0y{C|x{yf9ygtT_^#O zp>jcOhDA-rIZ|kmrUAkZpo{Q@aZi>swYmdWvwu0EMUwyUW*8( z>){GI3j`BvAZt*{t*GEdeGzW{t^Lk{K5nu&zX(H8)Vd5gH_B})Cc(G8h0uTuAuxyJfT#g9R4Y%O z7N$bNzLSKSsu|0!__Of(sEpL68D%tp2E53@X#6tvLYuO~KtpjOM8}80?k$d+{(Vk- zGAYsQ$tyJOq${?%9W6Z@bhJW_)wO{$_gWH(^0pbim?T*2mHEk>%^-;g_jbq1#`!eoJ+^=KvGcGkmns?>QfTBv71ct!WsT7B zcOB)o4PTr`yFT*2#(RT{Zflc8GEo1$+4Er3_^81>ee<~0Z_i^{&XY!I4YwVk>sh}S z7aVJ#s2|>)18ooYq@&+g3ZpHrr%@}v>uowF9}l%VQ?I1In|!C|-$EDT$Akm@{h>KN zrvoOJoo|!>=uG-!W^s7zI(Ip&_Rahu$+7%RUZKflKNN0&D`U_7nyY3coUBn%ktZ|* zM)3J7QCJM=N!?!`cKF48j4fyem^M$nWW*?*O2DOa{Uio_VKALeDtf?me|V-FLdBfb zVdU(rQj`Tb)j#Og?!E&-SB)F$`L@M{QM$RZQck}MU_j>9NM#;>?f9&!^y=x zejAlFZ)gUdE)oSU+#^8L6eq#S-a=Q+tcjN9|4l|ovok5Kc5A>1Fo_N znh+b7PxoC+TYiW5tRMYin>+n!)^>0x?=EXG<6bSUW=mTr?x5AQTw^ACa6}~V^BF_q zprz;MLY`j#S9je_phqTk^g@-y`K=99D^6pt`yo0(j1^@sQ$Y`ZPr>6!oKWFe1F~cJ ziD!X%{=@OG*g!IM1IkyDN$M;nA%Dy2%*53`(`i4!#ui-Dd~PrDtpm28&HE!+eSQixH9>Id+E<<)#@T|+r_BWjbRY@JBl)$1;((JYH)}qeHTzI#%j7& zaTrtG+EUmf7c2*Bc2+(;%ji1G2sSg-e#FOVA;}~kx7R=!yn^Z%-XV-1{pr+MTx z6=tvA@6B=Bz3Fe60EE7lWWaM%C{!=i3^i+d%D`;~YgD~Wq#Jp?m6gTU*B1}&od+p-CTEUaA@vH8t3oj4%@XAt9& z=WxQP$g&jy;KjMl$8mJv`x&3#x0eWW{r#@;mE#WImaIwDKOT=u>#W?A=LN{9F9Ll6 zsOIvdo->^Y9SQj~)0kHVy#Yt5W`Hx0B?4*VUL zgdlVQYx8>H$`w{uErj2H^hoPuY5$`uSl6^Xd;UWWd{&9Y&ni!RTTsnuQm0YUCg`Q|n!4RwygW`CXeM|qC%-={n&C`+L_1ea2`$ca0$JL< z2I}0I@v7cWbrkx=z^5ToU*nSfmX^)MvUtBOesH@((RU2-t4Kq|h7f2hSAIIfclwdp zIrh;&qVWq*^Lf749`WyR&93tm*7|Th&dpJmnN%yC)NcJx$x!9hA2TU=b7uA7Ysasm zmbo?ssK+@kj22&6)-QPCD|9$vd(aM(dM?P)WH2!&JlJK3AH$@Vq|EFTytay{;c}G~ zGMQ4EM_~z25zWu2Di9$jlG;I)Gj`)Am0$KK?RAR{i!{-xy(R3YrPt7q6OFI1nyy8% zaWi-wWPy$4pON3bH_pb}xGm9g+%EH9@7iT;d{AZH`$7_Qw5|oWO=z56>?VHJe$WL* zG5Ci`N(`_`kT6j84}XirpdIsOus?r*Bv|BMNo1=1NE=hSy|=H+6hc@L;3d>+30RR;lM{A4uG-S0d?tj zdl~;{s7V+KyfSA6R=qyPMGLkE=zINEw|aW$y2dxG7e>EN>d^z_Hlat|rt%Q?MRc7QZM)_P`)#Va>kXbp~cn^%b1 zk}lDH?*Kp0)HC=+!OOh%;s;#WO?6V)rcLC+7gh8-=3L8vu4dM#hs1>zM~#F6TaRcY zsgrHBmT1$B>YN<$ty;ZUS|$;W60Y-BZKoj$2O9}?t)X?hxCIm%-uUe~zgejznfOb8IYD>$X(wnOMia0Qu zNGrCnd+dSARRcxpGCGP6tlsKO9C5w*@nt~9V!A`_%KPQy>uh#TrP)sBRupV;Sw4OJ zEqT=wJh*No#{J?wG;323))w<3waO&XkIrws&ks7{?umHm>U@4NXQ&(fILvAB-~iZj z^29@YkVyazPSKYu3-;uPv#IkNe|7o`0`A$B7c zNITdrHLwM?|4u7{{?bHRk{N&L;%KfcAOqO#wRNMlb;RP}&YP_8!Cj`PFW?epss3&{ zkn6y8&scWvSs&x&EA6y9Y=l8qNDrqv&vfV0_F)~&^nasP`+@r^&(Ei`bWP0SZkG}* zT|JOmnGU;?n2{YiXB-9Ym{KVR&X2Jsua*)bP*8TS^wXg6fk~-Y$nH-&UbO5LY&ZXS zoa9y17dPJvbo!4{PG>pWkz1eROQh<9t^-K=2V4`gQc-sXH{4J6qTwPvQ&*nu)b@?{ zd*ZrfKL5y1w7fvPCXDzcRjz9o$^($K07{0c_>zokQdo^*)Py%somqR9 zY~0G;piTzVL-}!>(x^o9Bb6p{u=d}|ah~@3-GM~tfHfqMsIKb`#; z^1{TZds+PvAYRxU1snMP*<$>xee&p#kk^SF*Y|Dzlr&)TCK#l{m|qI_J-8F?Rbth{ z^UUXq)mT%z|MoJIO%xit6-D?Lj*T)tTBGTQ1?ib=ggxN~M_*OHAM1QTMkW{jt3K&* z(Dy}#wif$J6LOIcMoFs+mSBk+Si|;a(@ibRB7;f?9DF2z167yKv}!(h3f`;~V4Yj; z!0)h8$GZTA)=Xjsw;dpPEtnonO*q!t@xi2>elXbE+b@Du2ZZPC8B(5V#;KoFzifDS zZ4gkYd{Rp``ge6=%fMf%nn6WmAyFkaQ-}PIoq#)f<*OlVVx*Ft_=k6(snF>BQpv{I zs>P9Yk|~|{bbFUH?P9Nf>S-H%t)qq@-33qGcV?)|MY*OsT<7r{ui16k?g=(dE9Qg< z`Gx3P;~szA-iLR@?vb8plZC3hmg{F1h8mf9yYm>qqwDQeZ|;U@Jc( z)w$pFw##Ril+a9Ykz9UL^ITih;p_=0paAD{)Ha@%3)kIb9QwM+^m>-;?a83pb*8u| zrkY|ThDB33t{ZW7-~NyCr6i6pg55Ns*-tONs>E)N(3Kv)?|P+uPom!xrdqR>ys}f?gx}cOj=DGIVtl}fXJy$Ki`&b|SSshNZ8S)a z8W?Yfus+*xWhQM*Q-jU|<-r&ojzQ7=;O|__6F`9z`FCCKVol*127LqFP+$Uiee^>@ znz&fdRp7Vx3LSTYp1-(qiDgbJ`gfN5#%TXEaQz)?hd*dw>j*mPPo5WJBgXUP@ALMI zN!9R8HXO6r=`^63H+tDgkzJu?*^aokS5$sqh-AKlRR~={E4bgwe36O<0g9)RaCb%8 z$wYajtK1H0Y*t2$z1pKZc+R zrXj2GaffQTu2TO*ySU@3`6iIy91%{0J=xR^l3bUdnTO%bIQR{OHT(H|ea-R|8|I6p5k zlLj2c4)QRPh-S3>vHIH*q#$L=_;U62<8EqtgsR_8##f@nq9w*|nFPSWr0&TD+dSK_ z#V$(}Vu|Z@7O(^3mwtgwOaO8aY$eA#Rc_L!@@RXTB(CFTX9U<6EmnwTd9}4sDeTC` ze~-}e>aHSMB82B!{-Lb*09*>}n^n5-kD&55j7?P!xP&&|Mv-QjmkMPw8Y8mLJ*XXp ze#US_j8_@SzHS>80dusD!&zTo`;#^}~w58p~cVT}Xkah*d<20x|I}(3SM)xIE681nH-)E(wq9)|2Lau*+}-fK>JS z_f_7@zu2GmTUbic5^@<@xLPP;r%}*-5f)fdL-e-e6IqH7@s-%8JG+e3k)r*aSXRpg(OGNWeT-|~V%{q=7P`^t zF(+^+`%@mVOg&z9rqXarn1T1RZ8@tb*wOfEy~(E&Ot90{cHnb-OSM(U@ArLw+PT49 z_1}kI+D96HA*$2#b#7Vjwo!RIapRkAK7)&BKvaAbXpG~a#J!DW>+Mx4Rf6#SDia5S$w#?EM zev=q9#;#B0oVdk-UAG4dgkk>wKFCR%ZulL>@6OPj#BW6}Wto)*7!=Gs({VCvZA)wR z7rrq;P#K(aw`Pu;P#>d<$UdLMRca<@CDPs3B-owOG-`UVo)LCp{LAj4-fgb-R_wh8 zv}`S!u*F{0*6Jg5+7YrH|I4Dgab!V?IV|3FVqO?{ESqX+z{dY$XKjblV)|srvNEvQ zYitoI${7xPo)u`Ie3xGPbnQpV<<)wA!t(Gv=D4W^tD65zzLxC9CQMRAR%;1g*HL#c z3-*7VJh_MXK)83k*|>b4Avt715MJ?{|J=#$XA2x80W^bF;}0zug}`qLdqTnU155u( zj~@P(jLP_RV)wha_=rWKv*=kOj|NC&jOFz`7^g|W-*sv!>~`)h;{(_rEdS^c%5zV_ zToRiT+*yFHsKACvp*#GDNg^UfRGI4FH;S^kM-g(pzu&=!K#&_)mh(S+i?RIF%tIi1 z?O>TLNUWzIw|RZY?2ZuE$efQ3cVNx22vK%fm(v!4aGpZJ>NyP{Tri%P54>s{Ur$Vb zwRhz$d7NU{)5SamQ2|uW#?%|Y>vCC%_5X)qrJ@W*iD}FL{w;Nz+ zQNJVBZaDI|METU?IVrU0|BR9A`Z?pS%!fBqt0FB_=%Fv<5< zfPPOt*UOkiy0_Ff&(WbS=0(r<^Xb;gUW-E=?$!&<&>QGxIc4UrmIUQ_>}Xb*A571) zBPS#1_h)lQn|zKv{ddA)O--IuRC}^Q$Fwj1wOrWQAj5paW{ zkl|uw^JQH0(@pTQK@Q={^$M(yK3H@z-#^?{Y>c{jHT5A+3}b%0tOZ#elaOlOeDwLC z+sysyWXwBEO*!=07Xdg|_4dLQOjA}5F~?fkPn$kbj_qKt)VLdKeLj1+1PG1>=?~_! zYA@700+MJLJ}n`6f9zCTJrhbGR@f0p?cLpQh&K~pNMe*6cC`faqqPecoT*IBJZ+0F zgG;d;?SeG00DIFljxifUHA)}hgQi#5>tB6!Yf9grt3V>)GIuoXpuJ;txeiZG57|QZ zzKkDz-m%JF{W6g{PCx^uC%wV(00dv2ABL@9u&Y`RuJ8``>1=d6x5)Ot!kS5aGI#&Q z3y&rrd#ezEw_p`%b-vdD zKKTwXl$!+ZUC0MarI&Y6Svcfyw*y!QZELc+?m{B)?oqajO*AivCcyp`_A!%=q5 z&iI>bXi1fhyK`_pEM{NG$=2!suNfgrbo8;? zEQ{R1fAboOC3#;i+{5VPmo#q;0u==?Q|ARS(n^cT1!k#}VKq>q>DhTI1?^A%+A1-D zfnyb7ejVrcmbnK+2^*yjfwn)RR$x)Lveg#H#jxTAfeZR%^RjQgL#^6G+Ty1Iy-o&} zUr-(CwdqruAevECBkRY!vLRs4IXoW2ab6^6Sctei8;zr5xLk4Vj_xD}%>x4dSDP>W zJ$vtN-?j>#4Eh<-FT5o<`>Etd$l8|Yz)9Amk$}-i@|<)T#%h^N=*1f&f6sp~S?^q5 z+i#8L2}|~c2vZllv>~Zlyc4lMHvsl}-XF7+IFo=3^&0?_#tRmC^GA_yQm#(b5jYk@ zrHmB_8##}qzX)`R3^DkZmH5{;z>o$HLc`ippI+n)o4e z7fJ&|Tp_<8kLu)Q4IUt*_|KeHc15!~y%_qAKchk3yX5`C(bW)$WM9e>0(FAJwAM2c z$a>&&o0>3HzN%x%0^jeI%Qck~UtXHAYD#P$XW(5NLmA(eg|0};J~Q>qoNX7>F`QuS zby1GN3}TzRp#(reJpXjX5a^7{KxGH~2BVBI?yINAAwc3l#GLk_!c{&)Nb zWARysG-aFZoz3!~`I$oJK0Tl@l|D&~8}O;EjlqCkl3`Tw_An_+r$^^il4kWOm+t#T zy^eS9WcY|BOR+*^>bknl2m45(W_9?7PD=vbjtsVHRXthI2y9vE2|xF%2)tnelyKt{wp(hn1_BRErO%WP7*q6zzRKh*bMNV#*MqJ z2(Y6h$}UziHiKXJ4f0srlEw*Yt)qq(yCouYbJkh@fc5RtR#p*28yexa7}?|IT|4cl z&s7(|?TI*|3;dDq%9> zeC@HChALxAqgya_1)d4I|HLCgl{h;@^aw6(nAP6Ll5An>w_oR))#LN;Lv?EtJj&NC z1YcWji&rv3H{ScI*_qht%!^p)UA%sFE7w=Qg-ws9W+)M?h4u8uCi=VepJxtRgAEaGBfE%seq8{O8bwg^fai$c&_9iBt{BD06?jEw0kWIBseS6!)ySqj*$&kwKT4FBT}`YvD#$KUgXnZJ zIE%xLls8fnflmM}1tNc$wM5pZdjVbG?QF##_;g{~ma*e$Yh!QP?qjh2 z&h`>o-2cee*3l(gd?C2-u9Et%>I*T^COiHc7N!0rXNCRuV1s4Cv%cIVrw4s>?03!w ze=j7YerXxJcslG+reGLNr9=O-$%V!E`bbvR+lJVlKK35jK+iX`8fy8U!Zk|GPV}1B zbE!9Z#hew>A%_N=zSWrv@x<@VERY1Ub|V@@%Y|AkI5w{=*@}x$!V6(^MI7} zxxzGuZ$wf};eM>N=LbN5o*GKrz?`c;y~fqu_a2d<2w!1ZV>bC#EtoX|d#!$3q5Jc9 zcy6=pa}HR<_gByReR}2Ae1~H-mZfzF1S);bUjrUtVN1|dO&9w#VRJ;r^{5xbOQp4j zFFd7QD=YQE86b1%j%B`>=$Hkv(x=!=(JB#??VBO14-8M|Lm17umjJ)%59%GKzkZP3 z^^yQ28Mi=Y2k~lO_sf{|T7+Nc@1vzmkH>6Odn394Su6-0v|4_e(v58A^C5DYq$cR_ ztqKrece5|z%y~L%f9h{-`6-C)`sMS)G=`%;K2A$DwKd%h-Zxd;>@x3^Jmyw>cnoG-}RxJ#`pf@4@`(=Mw@@W3w5*G5~zlea5WG#ld!^5fAs7&}?UN zwd3R(^}Tf-ibaYWHtWuW0`JxNWQcA4fv_Y)XE3?ZO=3K)EN=1hoh+`f<#Q^k3oi;^ z*%zd#3SvZib7C~0{9!u&V))iABX2jklX)S5h39ZBU&e^R?(OgfinZh$I@)wWZFPQ_fNUE)a>eiGd-YXH0z3s-P~WIlohCD2#T z3Kx0DF;#B6eGDA2|6;A+)XO@8jW0xj{^ug!T5KRt-f`Zs3AB12_Tx~tNN_5=Yg7V| z$vv@APOJbVIaO@OT+iRapP&6lZ6JxD9_DEDf0d-j27%40HYPZ-tw?V9^KvL->){0X znd4@|44$e-09kfhnUv1M=C1fJddDu5%jJ2!DHt`PZW~sBQ|kQCLAea>k-tyW!uP)) z4qLHI@6u~oW!V1;GrhN;doX|SeZp?a0*QU{{jgEG1;D}2v71G|hGU*vf2mkGbr{4W z2=w(D+FCpM7HP8RF90|l`oNkBi2pbn{SMf`g}k)I~jApcJ>T>k!uXz}{T4qNKW zbTP5YXMXXdSKd}qa~GX5fi*vbGlN%sU>NAB-N%W}jd^~)t|oo2ik8bVQ>VPj7)Cp$ zHy#*Po9_P<3>mKW5tC`q=~Jfm?&ps=S&pjo%`tDK*p@bq-)p4q_V~Tu7Z+mxB_!ld z!wmxH1j*kJ-b+A-vJcW_pCX93W!7nM3JD9v#8{xC?X1CB1q1XgXAy-$w&|t6a>jAO3p)$q5^_M zNdtonN*v;lUtfR!-M4S|y{fIPt*x!nDr9T0ce+lWGOjAd*{_e}tmNuH7izFf$0!c+eN##UR1 z6^IxeHETGB*}x{N6D-#*@I5>DxWlMqVdJHvBpfoG?ADG8?~;!&o_3&+pqWF3_6L3n zwp<=OJfit)#YEdcnn_Od2qbWH$C)ewfF!w9pH7RyE|~8Sy4l^^eSRlsn?4yFIH}FP zLrE;?JmkGPuI}<9etESSZ?e&cjat_>Qp}&YEnv1@@1u{_`8ZXJtDZ`iUqHg*Ci-&3 zBDP(4@x5;RfN=?SAkMS02JP`SDhzc#>6~(&8M*MEq;Q7{wxF2JO^v9B*eZHkhDJ&0 zF9Qkz;XyxfWm!9S?laAb@62A4GyOoasc$N6Jnj$*>>EvtUSCEJ*W>iYAb30QH?(~& z=qvoeq0dWxq_4=lEb-})By9h~m`DMmGDnZq>;TRZpQ}!IskgC%+$;%i`=1C8BJg%V zfr{$#nP4EU&M|K^ELgfn4BzEX*!bEsSQ}$Z=)xu5OWmdanq_E$h$4fzPnJu~kr3mL zn=I97w#=hrrgByonn=-uX)ocNnh(pN!DOf+y*@*?wu z{d&c0#MAWxF-KPNq~M_Tc9krW3IGC(o5>@GHGFX*+HxEfT*AMZAC>)i&U)F$8BZ}U zEZm+YMi-wI+G!mCf7HiJ?>TxN*v<=&2i5EMsxf^YzoW}7b*leycABiK4*Qc%s{oiu zp7toJy$2!yKL1Z-8My|O%#N?ZBg7Srjewq#LjZ#+7a7&~x&Mh^Xl5o`U(Kv2WfSh3cE(K86vJ0G;?F z7k8|;ceP$k0@d(PRyw~!SGvEt_T*0Q1=fPxR=j&mOQCw7Pty0$zl9~!;)TTF*YyO7 z{gsJNmEN~3cNZ9N4~|eMsJWkMKf`X{09gn&LncIGb1^YQw}Sa06?4CC&X*l`*(;=l z^ex+zPqKdoOUKYIocev2Dxv8|zoh=JyU#{AD9)BkYHEhAnW>bBXzQ5cCVxOlpl^Cr zut(BlZ-4AW?AXti+4Wn`xT}7vYUc4=qf<6}Y%B89!_rY@#hK2QL8fQxkP;pIQI3aW zOB@t|aK$bTk{ifJhv+S1QRk750>i{_pcwxCU<=E66eaQz#}p)4|NO4g5lY3sAB9N< z9pd=sa>;Ng<^SE~ZgHY=G*W4zac0OF@v%)o!#dU=a@y-xu8>N*FGhjzaZdQgtH1Y? z?pbtclSVm0-gn!m<2l#V(!;z5E+f0UK6=g_T$OYA7^G%u+W+Cf-}8*+b|X`7Z1NvR zjB)*42&>Dt&Y|osKe~~Z+90!36GU@H+6az&qx=nOy+EUv+5=9{tNyc8#$F%`b;KWZ zs5oV0PQy9YCTfXMf4D1adkpBIAqT9B@xs-!XKjZHN$e{gt@^sUy27N^1i8Q8#G&1M zg4B_?JW1?E?+3A?cj=ev59C3>OU$~DH(A>Crt1zI(}t7f>Kl3(w*@T0!*OL=wX$@7^hn*4@id zC+_bo5ug^u0@Bai#U&*K(1FsVJo%52lSVTavxgP_2S4z06mu2XAWunV_w7KZ{IA6y zGG_hX+z+DHSQ53{=hmAR+$1*b=??WM4=uQ9e;Sw>r-tvmeFJr!J_V1=n-sU~y11DS zKhRQYJInwFwyXDA;f=fj%@<8&IyCfw-MD!({WOVE3yExZMs@WmE-o(AyJ0xYO_46e zNpg~_#-M#V6r*!@Lk*Xldz%VH|S8$U;46UlF+F8SMNa-SZ zQ<(;#{*Y1&G*@RFtMa8hE1zbQ$`PgwQ;+_AUmJz|{*hw}<1#yIPa__nQT9A4JWSku zQ4bFD$rl$FJMOIyo>NemShjRz4TT0FelHnSWWk)^49r>n%a1@egAEHyE+ z&vfUxxQzR9HHS(pW9G#rqp!kIark~w`%y{R^}c(=z0HXt^nu?;!+JK5{!>Z1Y#00L zRS2}vF~dI@CXx~o$WfKsfASigK%lGv4l+N59!=OiFd*1o@!GX(_v>j9GY~y}9+gA~ zFJ)on;#LrTt8il#*!VRuwa z_+b_;kGl4Z+Dq{B^NYgN(cSI20&R?&5Hc`TO}I+=gmd6fvbZG;(i=HJf^7&OBmT)N zD0G~>g3Mn1njq2+%7JtPM8v$$j;CGue*4C=k;rk4{h?{JJ6@cbv%`4)j@E+*lM59S zZJ=^5X54fL)v&WvAJZDij6*tuzNcL!K^+j=6&x3<@T92y?ZNsfsQh2EvlC)qUFF za^)(mBlRyXzEEn_L)y{N@wu}z7~1uqc?IhzdFSrkKxC(bf+7-tdwYBD=;(w81_s9N zBqSv8L?}!;s2vFZwaGL9p2weCRhYm!T>3h3DFQ3}kg4dGr@;n%D>IrYWpm4C%7u@Q zZ>aR~aX}`kpJg_o)6-^zviJ9Lrdq;}Ctk8a6ay)8euRUAYWn3IJgV?}f^olmZRu~! zqd&#qf19G+DMY`h^V(p({-mR1q4TesqfdU^M(sLzBlBcofvt!xaP4Zhg%8_53+neH zKx>{VLC={I^{%jx4qVU+JJX60KGQ_R*`>p2a7q?gOw&( z75pnik>8_e`1LgbH}1XE3NN_GgJ9wz%Z3EmTu>(18kh6lc!vm*KA9W%M7fb@brXDu zmZ7h?#|~lzAM)}ee(ukT`EEZsc2blheWy1WM;Qvf0J;l9zA-r&wGv5M67TOS-1w?cF!Gi}L zI|~&-<*t~q!jT2~EzIM`kHrWqq#4(rUD4ExBkqvV%KF2QXXxlqSzq$3H2`2A$+f0i z0^Q0Wu6bk1xeE608*d3P^s^Csg8p|sQreMVUD7Ro8qiSxsIY(l)l%&y+YD&Y9;RY? zrxL>^d9b@$WYT)HbF;6%Kdq)lZzGI+9DU$BJu`C_#%92qx@6In91hcszm#unj5vsS zEE}CafBqe;mj~##P7*v&iltNfzU%!;59N|NLy#%>C6?VxsWQ&f6!2Tf2YgnB<9<7K z$m|K4P%=5MHN@ec_x7Er^F1kUaSXiRcbI=9Xiy_LD;~`z7oi%@od){`W&mBvuUWat zD*fcfrVJ>Ee*X4N+1_5*zWO)!trS_EQmdo(BgoEzdx8JOda{|DnU3_gJy>jctw;yeCZUZZ4yDKQ&5-tF!Hj%?i)Z(7yM5FEXa31+09WGuw{Pm&W_N_ zKM6Xs&AyvsJR^(H4Ge36OpQnI!70!u*c@|bhwu@ip|E$~9m6K)h0Vt-Hoa2{5_O)w zQL{eqsB*1W4QW%gsj~!?(i>`O$Jwi@swNj$yUFrDWTTgX{NXbOTwVziiIyA4XpLad z`bh=98eYjme!B#fQJ6JO{E@o<^sS8h6f|c(z?Z~L6QMVC0;;#fl6tT4j;)HRTZjsx9 zEEaDc}iGzI!xA~!fsHkK2@8382@`8`JK4^$M8TdwOBxC_b zxvu~)Cw5}uU&6fzQfQs&Oe%Wv`!0gpQH4g0q|?*W*w>aR^f+%4BV60F%Khy*r)Fvi zBbbPvDDNu`b6&zZD%RCRYM<8m?wG(&zy~~z__yvR<29ZD?~Ye&O~-3MyYg)VvOtcZ zrxNstjikoMH?zxn6e=yD0jLmDvcuZ5%6*iP1H1L<&-M&p-?}Asa z%g*LrHq+%!L$DhG zmUe0hMTGZ$x4bi1%B7{7Mbrp&0B~+aJ~d{kH;d{3R%I0duM6wB@gXN7|m#qW`2T#o@>@Ek*JD`^v$$g;x+9S1_#~wsB+F@s|DC`r@ zb+5`Q0QB33kbA;VYroEZOuEi>ZeSO_2mY&D0RU^wm_1(Y=FJwnSHk*Va|Lt`%8MeZ9IK4WC6h78aRh@(msYisW z=rb}a$dh-kw$;~z{n+eN|He}yfM=ITz?pZ;0b=oiFk`-i`ST&qY@}~sUiQm&je0vxPmwugCT^*Kb0Rcum4!k+1@+gFKn^Mi z0p6lJhY86&3PsN2_b9xW!TCp5UJ>Evf39;{Pna1&TdZ!PSzur)OA-0?SUk4C5;6hN;x?|k=Q z1XybeX~uaTp1Ej^4!Ah--jX`Ab-rY46&OG^_{mn*W-z~h_nZA#HK&*uJ%Ieyx9;OC zYt^yuKWxg8`AuGQno{;z>EHqVZ-r|2rRc^W@~<0meS~8PUf5XsFd#@v$r%+Z9No5jqIVI&|@@p;>?|LLC{ul4@SaA$9Oy&1y)G7urA z;F~W{A(VzqA`Bn>gnh{yRKxDOrYXBUo1yvh+^XZj-X?OA1l}1pGGKBS9t&6-cC&{s zcv5{B67=0zoLyX;##{#*O^S?wcR|#?Q@j_YQ2XD$WT_>Xz~%&KUhUF6mt3VxtPzR?aw9yse~IKwRP%$pf%abY^V&L*>QeI z%m*H$5}cPPkO;B>Cy-%gA;(w(5s;edvqFhPNC>ofeiq;u*u3Y(kmq-lWQA<@qI$Aq z0GJv!T4qrZs1%0d$BV3b&O$f@qC%;-t|v(}?> z@`4!!q*VmCzggYoC?B+j-1-URkQ9PT!EunuveEhxC&>xbU0=U8M=%OFLQDnJm3}+v zGV!b7ejp?VQ;6zSrfNKb>1zmWr#a&t4lUNKs*ggrHn}bfFE20g?2*_owhWb+HiV{p zEpC|(2@8^C?nB%4SG@q3;z-XVtQQ9KfGK1Hh75nR7 zCMM?c?W3@eBQ+r+QZ<0nkgYQg+yIgTl#i+FiL%kjT!fLL0s*LoBDC=dmt4Tg8|WrGII2tuBpx7G9f_3}-s%eW_= z6Sgaa6H5LH(`k>8uk*ttn!36X0c7M;uO8Vq{)=9+vUix?ISraG`(RX42o&}wA#;S^ zHUH=jv=G@f`5^uE6JWZUKH= z26p*43{*ujQ3LOVvc&RUI$Hu{(UXXc0k4t!=tz!~PMI|$;@{zZap;2`Lzg8QC>dmM zGCQ6N(?ST)w11cYXOepi6n{w><Owg<9tY63LGLN-Oj#X;XmdOXl z)0uCtt%i%aYUD*m4J54P%7_yQ2h9yiWO0yd)u?-V%oExjOXqnb_#_2?rrPi3`SeP}8wfgPfY7sE@SVcGKVrIqd_D2r&!BDC|cyr{X zC#&;7ex80U(s5(hG6T33B;OUr%wJ%YbX2@-pVhhu4f2T>A2aBdSqCGl4)C=Fe304F zYdP=Bfb+c&>=@F}<^Uwu0~B%eXAES*}fuly@I`Yh`G$yZceDWe~-T{ZUP zT=}|ERPcn|Ep`0agvNff5Z9wZ0`dAs0o~Ak6)n@&I7VU?miePp`H>L~+xEudAl~=F zN@bW+eJv3jr^wey?XP&Gs65Nb?l`bd7oulv@7RFTI9QzT^2+!-bZuQj_uRn8W(26U zr}!Pi3A2U1tpC^|-YrMQzSO+<14Dw!^D_vpAKhZUQ}Q^y-Hz z$gik;+i_xRTRRnmH}IyhOm)93_>jt{Mx#9DVI(6{7pZ{dVH9CWZFBgmx2C2}z?R`R zl~DCFMyloSO3UwWNV$$nzrcKPTK=YlYUp?qKZJ1*nen+mE^gWVbj+eXt@x_slPS9F z-H8)xzemW+`pbxTmxC5YE&YK0Ijv^sfrMH8 ziHZy>O%1?i4^V7dZlV%FBqsrxH-C7LheFK_7N|fZ16vJ3D4~aW=ww5`EiN_>ED3Tx z2PqdJ!D7T7Lk%JJq=bF4WPVPH*HIAvYRD_7JDS&j6s$nXWd;jKfT;qpj4sHxAf#o{ zTT;5G=62bA~+*>V~OUVo^RvCd6_?k6%`b3*m0C8_{ohb zP278>XE{g8Qgr*gY&7TIGolL!eeVW~WU6e{z-Ez?-dK^ekn%mD&xlwv zd3)czzH**w=#v}Kha}DN#pbvdtz|0uGWUcy3(9fNZqO9xaJpzJhY^LMVI5CeXIu1J zw!c;F$?!3mu@S z-R{~C4V3>YN}-}6I?T^!j2gFOlC($G+zKc4e2iU#JopH?GPNNP|IYB7`HrvBJ{##g@ z!q>xbc!bK?2kMCw#pX53iPXvEkHwMZ+q{6v_Mfqh7;N z%Sl0SMUu|T6vCL53)7j?Vcn^qbNf-RhM`t>la!nWQ@+>~-6^xY_|3hwd&8?1;ard2 zjeU`L2sJg$XH=#g_xyPvptX(-0WnSaIAk*--VlX_L=2&G9QPg!;sD@Y1$<~e!ac&7fWO*qrn&i(jK?BZZXIec8(&C;Wfpr~~b%5ttL9o~AJ&uQbrU zkW`U@H6qzATjJUAhGcfA-23!TSG&-3(`&PrY7(q`PZT;bX$$#9P7preB(>e{oS>F* zTWnyAFK8J5;eE}i$5j#F=(x&|r*#f5cd?g6IFr_aVt^Q~9b4vZ*nDp+rRn+7t9RAe zr-IsOo51%dwZF0QQZC93dPWt-s)P!!A5_RWam#v%zDw-ajvZ6gyXU^qt=#q^ds=h` zX$BR}>r=OjW2W5r(f5cIMQ2r)Gw)aB-I>f+e3^IiLe=1rPg-lf5r z_a(VU;wN#w>A|<@oB}W1=Ie!6X)N;bRM4{$&Yo9chaLqIZNi7*raEO<6px#w4 zJWScZeIEYLRpL|R7fbf{lB5mw)iZ+0x4v-=KQ}5FGMnnME(#=LcD_*V{P6s6eC*6E zDp@TN3uTG--Jv%TOzxT;2L!;b2(mR(ieSA^T z{B*nkInCgx4|VpQ)2aQ9nEJ`N?z%QEEyKXR7xxL3M-R3R@TIA=MW2@C_$wH@&ipEG zs*Eza82$A#zN5TnShmlSfW6etyDzwvkNRAnw{2%*W7EjxM09Kly>asvLxG$Ug^r}! zXf@ku5MQ`a%){A{^0eG)1lt|{fb)IGm42zA$bT5O9bR&=-KB#4!?i@{=>-3uV2QS z)nk=gD@i1WrcNH-EFH5~5l|7B&Yq44Omi<7AFB6MkRBUT^|3z~*qa^1uveG;;f{z% zW|EriuTDVku9If8Q_C&yW_085-RQOgH9yEj1isfkc+y37*2m`|`$r}il2>{q@E)2| z`J!AW=Xs&z!<6M-1oPXmkr(r>4D~A{7^(SpUa7D?yYgM<+N|?`mG-{+n*#i&X)neq z4XC-lrE0G=E8zB#QmQ|CMNn9nW*Y%1s5Z`LgDP}ED8lI09JCJ zKYvC>LEO>Q41fy8B%mwi`k+e!14g?;gemvsp^TVGpk3MvIh!4U6UD)FlvXW6zhEx4 zR}IFlVQ53gezhXqPe?q-zMT{TJHur9a~$=yJVl_DWE{iuLp^N`VII$vl57Qn;Feidnb?#{7r@$peW8DReWuXvP0e=_O$c5+pNo^TTpb zqH3`N`ux1Sf)CLVsn{RvEuqCA4?ps(!=wlciFq@mAU&|#cDLY_0kwQih=(@HzK_IR2509;Z z01V{}Sp*w5(<)%$Zwt(c?;pi5UIM3xDJ<$j26M5u2u~e1xEqPRl9AV$TvntXR!GK0S%BM(*LvePIgXE<7=Z2ef z1WJ7%BwH?=M;+AH?nJ(?-p5Jqr<1X^%oiFtzI#FQ=rmK=+8v>0+q}u=r?qTmF4*b! zTnH#R+I#t{dFa=f?8;-cMcFpaN}W_12ioe)&suKi44ieOcDpY0u1Ilm?Aj`3f^vJW zZ-VHjf#315#ZURvrHadMPdOU+(BfD1Ii#e}3m@dAq<#}_qC6(QxEy@xCPm%g@u4sa zI7CXqc;bZQ&hRfh-es7lf&AO8`1tsn-0}RpymvV0mc3L_qU47iNrIb=Rc{XWo%B}# zI#yDF48<{a2gQ8n;lo!@Sbw0W_YoL4&stWLFi@G3-`M?2uai7c;-JH}qEM*JXHna9 zpMkVZma9nbnLVhvucM`vklvFEHQxK0nrWbUk14$iKe%Lei$vCIE%(&v(`BaZG;gI` zuIFhL44B5qWv8X3dE#l09fOq1RkzlwtSeb6V_~Gi29OyvBqV+nAV;Abwc7M3r(p*V zet9X-KQJ&8C1hBq2Y_8mmMvAhzN$*+?c2A1mX_Sx{>;s}Zp`bvg(}^LI&PV8GSu=? z^PGFgE;V*-t<=lQtFO2B`30z@{htY^;jfBO~%+x2c6lqxP>xNu>~^!oMd zGjGvbE9TFlqd%0EKIt-@B2*%iK4=Thj2-|fao@loKP`=O!jCK~oz_<703fu3{ zTfJ1C9_`;Q!u6mtp&()Ebri2Zbn6^FMC#JD!4=;jWx1745!$@k)!o(g(AapgCWi7z z(9t77E^SxS=rqPJI{&yW5vOvBGiL27_wQiYn#s-M5-bEh?C7Z8wG2%zhVT~z<+Dib z7gmX!&BLf`7mz}3b@dw?cT$vp)GPYKcb=ORB_grxjI76b4Yyh#&kXjCgIVas(L0c+^@dQNUi&Ii4^>G0 zQ*3MxA3S&&&90CSPEoaYdD-zxihtYb8_0H)VUX{ ze71^#V!CwgEIkxlZUE^7jT#9SmX>d&rb#qT<_|;njUW$CI}NL(5xzUMA|&L@=7fQf5gTx_&>(SP2k4f!QlCD3DmUw306n8bSoL98)Q_d5 zeQoXSa(bRKbBl}Rkhyk3^Mt*Pm6c;#N3(wY{&wEWgoF`@DmIYmW>FtIHUxQ$EmFc0 z54|~B!^xyWe zXDR;yc$WC{V^IHoo*588@+>MUbNcwPBV|AiujnX>)GP;rSkD?9LC=ng58aWLk$Ir6 z{|R`@yREIQx8uC5CRLtj9ExS|tfn6_yBBkmy$&%T(mx`ko zq@_Q+e$Ddo#f!|SgcmQY%*1Kw6n8|Xf^p+=ZmSvV9M-9E*}n3vKy~?eM@g(bo3+moCgmd^3zdR zSy)_$*@y!W@wo`B0q(s1gM0!40>A2Bcd|4${e*Ukx~-YhZ)H85yTn$U+JVLH|Ni|Q z>{4i;U1G<_g?fWsA+hOM1<>06-3CwRgEZ{nDqrU-GxVAM<7M_ob zQ3L1t;ubgKv+FNm_!cnG@CF}ur^tQj>T=uf?r4_F%F3#Sj*q)-uS5(N^{C$B!!QPZ zTjph@rL$1)?*#yn1?7wDK#oVWRdk0(u+_%nq8w zHUKMl!dBdblFuVBXDH#0hJ=Q`9hsia6wd)ezmgW~`s9f=e7D_bWtE&~@ z6|U~?kKEkK7shKx>JIk3!M$t>LVqX?yZrn&&f}X<_P`2W_I{780 z1#z^9KUf^C!tQtAS_DrX(=|8Gs)d3bA8ar=91b_|{X5b?QUZi!UT$t7lyipq`d)~K z%3^~B#l=Os6~RX~=$1HjM!LQ0+B{_sbEwdc`|L#{- ad02|xPT!pI`3kp*QoW|GoPWhA@ZSK7lNuHP literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/debug/drivable_area_visualization.png b/planning/obstacle_avoidance_planner/media/debug/drivable_area_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..7c9ff28b683182e076dbd052eadc44e82626c16b GIT binary patch literal 151456 zcmd3OWmp_Z)GiX-g9nEM32uW!NN|F?I|O%kcL>2ff#B}$GC09q26uP8lif|Sd%y3; z{dwzopnIC0?y5Scj=b+FLS>~zQ4n7tLO?*Eh>HoyLqNdELO?*{!oz~E1Y`nDz=s$1 z@5L42!Oa8SFa-P=-$7W_LBZPC!CBAF2*Sk5+R}*L-oVbt$jbhcwZk!V8$b9aR#Qb) zhYxl}dJd-6R-}rimPX)<5D+X(EUcRi)l4i~X(23}TZuWOEUa6}e#{)3AwlfS+j(C& zdDfL6AV?v^g#;B{(hioKJ(MmVfu}PKv>Y7n@7}*8)$7N?Ko^$n@KuGWeydvSUTvmP z!ddu9N%PZ`PSMmfU*R;Qu#HjzBgX{#Mdz! zY3Gj_qt}{3#MkM^*XCHbxEdkrrL|r+hvfAZry^dH6gr)n?c>eew0im|HWq<#-HCCe|39% zo0QuCtk6}$9(+E-Jrj7sqboX!cbPXObl*orUHT93RA_gyAF`gsX>wUKy}b}zT>lYIZQB(H2ywg_z4DyJUuNN;PYi0hno{A&sY zSQCu&)Np(UB$W9d+4N{tSiYO9!1e%HsrfSuCpmZrF4o+R9zhAgL&dg)d>wH0(W>2i(&Eapd?I{ygb_Gpc6);7@ zJ1iMq3$mV)rGv`R=v$PRkj*sxDU&|01Jn=ngZgt6(W^H{JTEmF-YUqS#3!uL(!cpp zMRf`S;UVFaTWk&S&HvIUF<|w~%T@^KJp1SzS92%@^XNAoS`4@egG$#`T@|CHuR=C1 z7M^;iK2YS-&GvCTyG99E*N5C&afTX-l4pB8%S6?2U1`Prd|aQPq5wSo!vX8KynOz} zeMP1-@f9Sr%`4a=y{;4fJL-y{j%fRB{UuLl9u@ju!nL%_RLdFMEJPAMbmC#i!_1qQ zr%-j|PFIySL4sDaX`~1Vi=yCmqsA-?dPvpTsABJ`ckvOP4lb*Btw)|1ap0#^nQ&{r zygtZ|-A%&o$Gi??c}*5Ps;wSjX@e-d!l>_Bn#xZlqdVT;5>m@iAEPEdQfPg1w}4$d z!0@{HSk=pQndX9Nn(0_)C5Gu#U;03PBH!*XxcN#8YWvBIsblCm`SDcViM!EmD4!M2 zS)Wn=)zx2}7j5P<{*prZEex^v!J~Mt3ZdX|XR}{BtEzpa5 zG;uRbQmXG^O`zn}UijL1Or!asLzz3W_4D8;iBQiXoU5KKq;c2Cho0hFCjvRq%>J^n z){u^z7!#P z7S8(!m z6-`KDw2nxE3Jbu;sx6(8pl>UcnE$Ny-TV|}S%M?qc^e(Ys%6I#eI>c0z>#!5cj-WO zea(y7r0f7t%G)kwYjZF)uZH*QB%SS*N19ykNcSTf=5D8hx+VWY+z3(t)$t`eTT# zKi2@!#1RDhRrLh*)0GAr_6UY9 z#*JyJ!H~49?-axvlQc+1rKKV+8W-)GnMv;(suef2kMb%fo=`{1JI13^77F zom$}0A&BoPDd7bBpSixp|73?Y8RVV@KvvLbwI~ZMD^BXvYOqjy#I}BTbOl7E3>5HP zr}0QIWgZJ?h&jnYsJw^uWO+$bbTW0Mwr4QdXmLhcNWD~>B*Ra;6(IK*%F%9IB}g4$ z>Z=AaQgI=yzyK6V0!|;t9dGumbg7JXRNXvoUov_p4~6H@RK?R{9O8}s0$-=Q|?!ZRY>8u|)g+IN#o)aej zm$edrc9$X{;&oyAkSAlUWCA31KkzEe-|&uJ>7J3Zb=Y@Driy3?Y!bPqSVor7Bc;uwBXo!^J$jbKCf(D6870pWALrw^M!lg6FD!a0e@KLh&X#~= z@cDv)G-w9;xzk@^rDJRzi!$m!Fwc#)1Ruel%XAjWLxb~+uQ-5IsJ+;DfAQY+^y&Ra z6I|)$1Lp{dIg?(xpPd!04-(8@IyCO%yKd*ZW^;RNZN>dZ8Zl8lH#h6ish7K>?#C@a z)=^&Q_G;4!&co`7`D!MJj{@;ZIC>a*?2-?6DyL=U#69(wYPlDP@|FSXw$m%#1LUeo zg6;T%^<5C}Z{9x4@_{%BtQ3rJPNp#H&W2Bt7d_My-+muyI!<-P7Z-cWg`yWP1n(#eCL~vAC3!Wu1HYUs@g#;vjUt)b4P( zH`V<7bZ=;4GDGBkz2tm*3MApWKd9PWYI0ssGO-7R&fb^9%xV$yx~DVS1c*)(#1T0Q zx%ityVHuX`ug{kyDcMlA;ZGNIaQC9z|1`rfQIx#AX}9Owtj0rl$k`z4d3Jg%#0uRG zDBg^gXZGLWlW41meP>u0BLCxs!rkRQ@M3o&G%9L&-NV+FnO3=YwF^za@L;y0e(4Cn zh(qzEI#${*1Ud=dOzCse8BapuHE2K}>RTEA_0JIJc1~Pcnv#Pfv2MjH)z8llr$*}I z$L{sh&v9{+B2#~&DKiIzmAySPeqG>HMnc918_%bAYao}WIb{hGbM|0>qR?Nej(E7AN#(Gn3kZGuP^64pZ3eztVSz; zJ$r+60{O3KFUIrJTizNvqzSf#CZT^c4#N~0QTErJfA_+SYyJ+l%6OQZme#y%T{$)v*N)2fsjKHQup<%XK3 zINl4#$Hg(ZUs+H}r>Q!Z7^%%#0LI71%jej*l!Z3LHZR>Y2!o7`jceuD!NW8@T5Nzw z^Sqin)cpNaLPSgAudx1tejTJuPKV@Jh*N?2P0-`6=UY>Og%CM8ImpDk^}-~wFohlm z)X2Kwh*a#ozAabvYDt6s)|-`Y$dcU|KT`H^CQ&Sq#F7YT^<$drU8q4fG>Z;G>CvKp z{mL6)IvX14_|nN|O3`AmJJK3=;_{+(k!w=nI>PL@x3^5?e6^C)A9%GL^dybCn_WmH zt0Yx1+6jf68W{plg%PzhML5ff9rJ;fk}|jd+`KmN$D8F35kSX~w=XeF8yf7lr(yCF zjA(@Z*j!E_NHZT@rV!H<_ker^1cdq}D_&wWrzWD*VG(I*RB*sPyth!uupN6nbKXAw z)=A9=Qmc{D_80~~Lb_Uzx_v7>o{k;*h1n=a@a|HNLX{m2{ty3M3Uc)Zxnkk?x-UIE zUu9})o(Bo4hi@6etG446jF7gE2%EYt6gf(TXG zf?V2eS3P(Dgo~4?tQGO;vmPMhCk-8s91MiqK)dFW+i@Z!iYfU+sG?(oQ?A{76Bp3lbv``TR*t+FFU7Yn-Bc7 znH(y4wmN2(C~sgE?`Kh4X#k-TAtraiEjPkp(1p!IZXBtim4yXN2ZT$E$pXkH=c{Q@ z0M&NfBD~rkJ;$Z5x_A5zo2$!xqR;&l4NNBcGKTOn#Y}iqTM=0(K;m8Q~1Ja_e)Hr8Im=|;A< z?@0EncNKaKa_6J*pVZb$;+^-W#|pQFB1OQ!B-n)+fL*ax;$-<_kgoIN?T(kj55Rff{2i{D9JlpJry`uN>}sRlfE=f zeukQmuy9Z=(w&W7W9-_oiv5W90O$G!)(|#N(qSa%xbAxWwM@3Rrm)u)U3g>L^M~A? z*mJM$!)p8C`X?z4EDTdBOe$%^&Hx0}gsC0LfARq#?p(^eM>d=<01n>3%&T`WNKGhS zvj>~O!`fbp^5^OeJ%a-!IquEV2h?4ih4$y>q$>B0UDG# z)&->XO+jI1gtQ&z)}%WMhF>C8CC6Z|)?+r>KhrRG-=Jg}P;fH$_@aay z5e}C{MP{44z_Mb{52Q^gk`_0XsO;$!CU61J`WPvl-xe!9=*hu|%m`V%!j~NFvuR{Q zo}eQ+Um0GL8T=6OD!wPvGahu6>$!Ki6aoxeg0${>s0HTu!|dS zUZC1W39WGn34Gk?@I0yS4ri3i>G>{CQN!WAStF|0T9B`vg;qsi(aL~c9)c>)6j}IJ z1l>wo&?~RH^0Y!}TTKq~FWtH=XpoVVy^>Nlpe42TiG96|uhecDUdG?CnoAkoBDaqr_V>CaubmOw4N5%zQZ8W zLJ%PIz5sKubDME{u8dY}2NSphAG;}8$7E83pc?QV$J~3!Ad1m1)N?UFDekoU0Sb}+ z#B#2a5zZ7ZxAZPJ;8Ye+zhJR2u#QWKrN3t_3nU^<%_=qx??5s*jc5j_S z#=HMK({PGtf$#oejoDKyV%nScPxxTxGI#v4waI^ciB(SHWyX6cpI7iNn2@2HhTE-H zp0zW4zlIvA<3&>D z*l;uuk{S>xSoyktlELfRh)MO?P7~qSf`P0+N9Bo=;T4ar6kg}TlNrF0W-}OyDk{ya zbxB#g+@7Y)1g7GR188iJbw{U;-zvoNa*yTQ`E+ZZG-}dtqxr+i#zQ zI76F)&6KJvl(>|lsDm6)vaO9?gJ=hCELx()DGa!beEd~f&%ZQG7=D%;dLH;TBaU$K zcD~18|3iJ_cV+_#j`4!m1%@!rR(+e^4O*Nn{x_DR{HSk;t#dK7<{SMwTNL$wPR`f(8&Db3xhNr{u1MV#&@KT4Et!`|i_fzui zSC4oWIGx8yjS1ID_p?8?KC!g-c0wpywjb_I2DWL(N@oseN)Rvg!8OEhqzYEH4VyIV z8lHU?f_;PkJwAcS*_K(-j;?X$ig1iQ(pz&W{sN!_ud&g$iC|yuVE`FEy>T`e!xs{2 zV|rEaw-fpKn{YY>`*9NO<4?H{6X*NBgP=o7)myb7e}@u8R|ri>HqmL!nldXoNy;)V zTn`y<#oCEpr&h9&=%HeV$AXN_Y2fp+gx$h!`cBWwFn5Rp7>Ts7N$N7Ga z20ni?6)Tm)Jn&1UAi%J6`zkuDzf+JTIuIca=HvSu{^_LEg9EY}&{pAPk`e!O%IZSG z;1oD}B|<|>auj6rQPLjri==!p=(1YyvD2Td5INjh89UbdJt8!0Z_Jq%WTrLswxPsq zKsdpjupZ-}Njk!a3&$w{0=NGZ*5b0N%3)M3L-~h{G`_BV>`Tk`Wu6uQw{{W3UNt6& zrM(^Ki%4R&h=K zdZhJxH+ZT^KW^`r_{vqs1zmbwu!?Xcjpu;87Gp-`CX_r#;~%d-!SvArm`l*DM>M)p z9XIDsVZ8RZ8r<2murtEg`Z2e3=Uss|`;y_V`bUUS`>~33*9FFzznnWbj0WY;oyti1 zPb|Iv86^!PD`pA=pfHuBl(QMCCFKU1s=e@I*MTH-@;7Un>qb_DmkHm*QX#XibUroG zqoRC0U;cnir>ZPn1Jbn^6+4Jyr|tz_k+*NeIy;IJ zD*)`vkD-yMUDE8SXP!4;{JE2j3_yv@;}sOa9|n|($iMgBwrMIqo(k_+mGiva{v;D? z{*gp1U5X{mA&j{kAC)1M#b>bTSy9g=AaV~I&I>6fGxl7%Z*}U{-1YJNvia%OZI~ZB zhC)Q)8E45;+x^=wK{)VQ@_UyWqfMd*fpk?&*?Gb}6yZ{rugCQ`W;ZX{8{i5t()*04 zHcxg3uD%}D@PXR}p8dXKv$IWSFF!|n zuM!d90-Jw#YkD%4+JMH2<*M@FAamTg5ost8NM);SNMr5Q6u3)rh9^)F{OUctuRar~7@3bSnmEkW2x8b5GzD()6a zs#T&0YQxP_iVlRNn|Dp~=&I+z+jYY1u0}?JHOFbI$~~$R_g;PJyP*GaOO{RP;QDb< zQRs0@XY97~Hzdl^8+h*R$k%@ z@N0&w1+8>OS$V}U&u&I<@PUq?S1iZs!;KI`EY6?Ni! z>*){^9vDuI6D{6$I4#c_$*U3PYe-KQ(rpc1Qo87K)(#%k^@@~bFu&G4-7I{GNYCR5 z*FCWWVWF2c#fV7dL!V}gd$r!tAw6B%w;8&r~6Xo!SyboGpZQpafPqFX1dmzTeC$;r)~ZUN`^d)it}PH*1435Ua%ouajA5;$FaoN3QWDMW9h>hwcnfKN;#)A#gJDXZ#_qg2%9Ig)+7IuY5 z1q!b>@F0xi$swgQKbB9Eh8vr|X@W0M)k{8CfHhnV_ z$jSAewb9VJF~5VxQdtOztel}&0-wjdu;><=y{_;$^hHv-r>RQou1}p8tqp1$kZIo} z*Drg2C9s^Url|5F--#=9dA(u!Lc`SgC1&mO-IdX(iQ8AlqiZY0IGB#AGLzTjmzK-T z$rl$65L=^}qXl^x^I2CVrWE9MOv9N1nGq4lon2tR;7N_u$tG1C{yBk9QUmo!pYVQBUZ}eUI7YLju@fYtj-9jE3Aj9d4c{B_E%Wnz!VfjhQXI%U&y2*>$I4yKY4>tAd0@1q?$TdhI42v)E8Z*MU$ z3K&^gG0SEavH;A?%*X_Q;z%&o^1GR4P%ymHYOs5=4vYq}NqwB?uB3yIkdR2?a|eL4 zq~fOON;(SwfvKtKtVN0iExBF3OUp7&@VDgTWJ|@!KYbTFC$fb!W5Rolhg@ks!|?u_ ztX4=P4{17wwYFA1qO7|5z-ov8PslU%XciH4345YP1(+6B)j)j@W@1SH7c}U159it_ z*xsR_Bf~OF*+-+ZlaWEzEkpv>JFMyqs^d>9ia-;(bxvj(aYn%4HzlZFOAbscpV)N68|NA7b^S!BJMPmEtHVkr9GWui}f;J4iQk z)2S23hK`^tmJ|oPIq=gk&4jsrqSt7NR&RKKgGweB3NF7PS#t8=_z$nXjwG`NbJ=el zoG*SCk4<7T9rwD2hxNaC^cpClH-0*Dh?pO$^ok2JI-DB$8?qQKt=YMsN;}VF5h2M8 zu-78CcMc4ZklgB*bYptW(p^`@(r^{bM2T7%+mIC@mEg~u?Pfc=d-__w`+2D?K}Bpe zS>O`n()3r7uYf(qYiICKh@0@M7JwW3xOD9)5=XW(k`))zQxR>sjWe{~c&iLNj#qXghdbc9XJejU8o~Y*z<^ctVE1!b>MRqTrML?sJER#YdOH*H0RXzG z<;tkYb?)jE@r4xKMCT_tKXnRA7wf0n{p=(!bvilK;*oQVd>-?4ztG2q%Y)@bcV)tg zfScEYlCBCwudJd3*dr@qeE9tANB6oSv-Lwi*&2aGEFhEQze#}Pa^_D$^R{UEK;gGS zV{jeR3=-#~Ku;#X2flv+1zApK5#&3u>_YttSxph{o=@n2_G+`v@y|wjDLA=C81T~`fhli1iXM%NjK2a@Oe>axtn>5&W=q^e=C?cm}~bAAt7Hlj1QpINqjIXYwh-z+Ms zzTgYH`_~{QWVj}YqB*sVZ0=bH*(x=z{CkXNh z2VRW*XL>D&&iG`};!IP(i>aKh(td!Nt}J&5_tTk@IyULdzWLP4Rw-67rXrWeK`5M? zB~3dk9ftkgcBW2zdv#oqz+^ftrM}Ai*H(Kb_q%!o4AOY1y^L8Oap>kcbXwo)2j^ym ziNOK>>)L;>h2RFW{1awUzNgh0 z==x5r`YYQJ8_p2RJ%ojWZjpu5`gcMbecl6AS7J7Vcp zc$#}vE%b;sH5@HsqRL|fzC`bJS~CBj&{hx?7J9|~Km8up8q}mI$8vl16$6yNm4BoC z+}FQYnLlq3LZy_-#QLqQKTisBAe8=f1Gu&%;eR+p(M96?U_Sx$#ckU}h3MY^-p{Xn zr%)iDZ3nJctyU(JfK4k>U0M%g)Ujg-Em&{Cai8%Tm_?bSq@)be>k6uo6aFnXa`NG9 zh#F#Vrf$A6I*W^kmNJHo>Tmb~T!+EsZ!uyhqQOLtEnZ4;@|?)jAFmg}21W`?w&z?2 zXVVsLA__`ea~|xMuY=38)Q$10wADwjM-8j;AAYQ83w>wT*Vj++*o;$KMJ~Hn`!mK3 zn;&FQlVDFkXhU+_gFSR-Mqi}eoDy6{tl-Sc&K!m$y{mG4z9_t3LAUR7JQEjonVNL9 zDDl+NQ_Q8CjJ2gw>0-jZX`H&OF0}C({%_X7Wbu*z>FbmJuQCB}7}6ygj3A4~Cgiyj z+4FGfhtd4-FcCqJ*7t+IA7b%l5X5V{RN$~rh|+GUAgv4P>`lB~;s`G+B=z-7M}Va% zVX4^D(umU-c!=DzxIXl3fmHP+-F&J=u@x4Y9}kwS`;xwHv=-u^8HIY=Wg z1A`e3!t77&N}oD|NnAFk-ZURcY|Jfi&p4?M=N*@=h882%sxpkE&PF!{i>_Ksg$N6w z5)DFi<=^rfs`G;L&_!vUnTY+BR&XTuyRrTFmitK9_i@slfneCOZb`(*=uKJk8Dg$8 zfwgpIpClvyD3SAGM*w&XJ9`RA0Lxcsd>68;Zq@LCbO2-ADgcA8Ih?xmwp*Fc7mSIM0ucMX00%N-Y^Eu5IyT>R7R-Ct!!U*r;Fia#7V_g|d09l}z;36CwD zvEHu}(JcY#l)zFH7A%Nf;eC8F>itE@+2ZY5JH~;$6(Uo)!z2lP&(nCiK zgkX}2m1JlL7-VcqOJ+5ZS5@s(Qqh)nbK?f2MphUA0Zlq8c8F-2i;>6!p@a7^_h(_M zUuM!Jqjm=uAqCHz;wrhD{5FcsYAtDij>>4c7H?Pm-*bYxwLkI+bZLlVX;y7rKc zM3!x&KakY()P1qc!2vc!*1A%IS;{^zzH{3Pg;UbMnMmP|jtLt7kEJel%!hCs|1Msl z-HE#zBT5WR8uTcy9BDzPhKS>$f8(-7ivIQaO=p!r}omrQ0h{;54`;Fk(Ic{|Ck-^be;rm-lD= z+o|p`N!}2DazXr@kufsNv9h>xn`+e<3eL=?9f{8>THwnY#G|O!1*)9SVi;4By$MH} zY31?Eo_EKWz7?6Ol{6)S{nAD=CJWvyea4J{&L~NSR{nqAu#e6vizedIxNumv0+zrX z|EN?3Z$r=HEf^Q^koL)bEBO~LVnQYIrd>1_CO316*16KrfI%nFsg7wUZKqclMu%?s zy}A`vwv0oK8yL4f9RA}7f1&}u)wWNsr0Yd~iISGqFs_bA2fj%f7OSfGEHN3U_ ziEserlfJK|aCtZwF-|Q1_&@9EjsFWoMeD$2zmNZ#fqIU%~l$1P3<>T^t+h7c6i)!Gc!TT&EE?y!pCzEC?1uP7jWg8zbfl=*alyir76*L~q0UO30XwZO&j0B>Z|C6h zhbws4EUjD+b%lCZK-In5iGSn^7IYs7So{1R?`vhmVah=T~x+2wb0^Bsm{95EfaSk+#TaY)BmAN=-VvS^EpD@}Pt^ z%F!_~C$bWMD?fN@zJ7S|lN9D!Ny+4n(T{`VA@vx^aoc3z3 zIxfj-R_dzGSHCAYY6j8ZY#j@9)<`6rA5~?Rll@3>|Cjp!(+ZkIl<)X{pkIFDz&QsZ ziJY9B%dlG6kbk&;4Q;c|7<}ICm^WTx&jwK^#pN4_M4+>E?UT&qabCBrrad`+n@xsT zTSEEc`cu@=RBFVCUI|@$mcyZD#*GD%Qi+-MDn5TCqcYzpjMnutaF9;3qb);K=;$eT z=093M2z3?C*m{$p-Qrf`Oax~Lrpk-es$hLuJ@0D^qkD>KS-otawllr?!Q~W-PxrL9 z9=FQG^&YRSTTi*EA~>UT`!*7Rj%)MgWt)3NWmb({dnB%x)7v*=ZL!b%eE#>Dw;_(- zN(qK|Ub*?+d(nR8k@p<*_U&4<{<~{xCwiB(rf2TpHv)!L2Ald` zOt8%3R{}>*gX9B)IA@*E*QYacg9SUhA%aU;MV}jm+pJ#cza#YE58zDwvc@}B4yuj-Rga&w4Jr5d5+k>27p$@?E5E2{yTVK~MRMfHY~2`)3@j6`6d`tyI1{1q|dL~lOu}C{dpLlLavBF&(@t=^++9>E>yjyk}dWRY=Fhu?o zS5$w^=xis^LGf@jm!mivi{~+aYUuJ3&utoup>fqkJ{=aF{JdaWjnJKvW6>3%pJb)) z!}IW*LG;9l6_C|Q%!JoddTS9$=35?XDo1H*JEkke&C*bCgVheeSh_yO835N&sN2Ju zX!o>FX|j9;&+3&fy;Xf)zaOh5bio-K3nx5t!D@tPaupspa7gEJhx&9pNZq?~L+UK$ zaC#-&wpml-Mfy%|df{U#ce-#tuHAk~-WYv(`slWy99FR>>T^T1j!Y^vl}^_M0qkkl zq4(O-rJ#lFBd39)^$GG?H4@`mrvl4K_1@B-_!m5_T%3f5TJ4}tCgk_uQXCDXCN{oE zGJwto8BMl^lCf}b?55%qV>2?MhK&ut6>-A{?4g6l_5S@7OYNkKiEaJ(_N~UihS+58 zb1x=OtixF$xwd7C`<1s&(gf1a>u_JTqOuk$vhn!(Ag3AHN4{zhueIu+b%?W1<4-i` z4?FpNUo9-iIH~SH-o^GG6!^R@O7uZ-tBbc{2bVX=6(f5Mg_Ap8qYZ!L!*Pk>S`N&^ zzBQNT)4bG2LJZ%IcTaJ3KFp&}i7U-~@!wk3ZB$S;ZpN~A4BwrIk~*=}E!yH6V4~oC zX=gu|UY&y>sIQhGhgd3YNEOfl1SKua9Dl>);5}hd$t3i}hyWF9kH*&I5Z+yE-59W( z)O#Wmv!`G#!GR+GlZtUc5WRhu&Sv^DmQu>h@m`eJHQ;*1JF~FxEf}S(zns?C9~n+z zN2*&G-kU1Ym}`pM=~kT87BkKNBK7PZB}(EMEM*F0ot+m}5{H>mUN1?P79AdMnzd~t zR8+Y`cyH-5|5^Mr3I)rF=)JnbpEOj_)?UgQEETZ zI}Zcl18w!05OT7)kzTDg0b(x>Ugy4kIkq$21W1#1m$L8j9Ykr}d$;cY2mAob+?0yQ z7-0n(MFw(wVxr-8E0uuHdqRpMCMITVVEF^qrd809xKOcY{K^v`Tp{Bz0!_yyZXp+$ zBCBIc%CKNq7ae~F-^7Z)=V?Bp_^rg5GsYBGR7lc`#`0Jw>-;OX*zrzHv16f+THlw2 zV3ZMD7v5ipM+vwfJouuh{>kvb*y7in|26arY*8xTYdW6eUj0Pw^pu#WJ#4Uc5##XI z-Pbav|F!T!{=l=ZjKFOIq8o&60C1cp_j9_dw#P2Rm4tF?52;-rmu9jD7h@||48Ovi zZi#E`_R3K|wlzxUL<7}!x;NT{PFk0#bEdF*kG!_~DQi^I296sKGU7{lJyBGc`1pF; zm#DHe2}46DX*T-gZ^E^=a(bxj`XBkq6~VOT>--q5!OM6aUYagWY)iX8;t|>QRLH?#;lOn( zQF^*ETHc2x?Y;%~0HIj^FjsIPC1G?!KbQ8nxBl^H*Fwqia?U-y|2WUkeo2nFQRjk^ z;QhTd#qT%?d@`;a5iRgE`-;O#(|u;lD#QE96&%$1&FmYs`#{pERR+Ky;n>{m<|)X^ zz5^#zV6DOn5_EC`ntMFbPb<$cTu*fR>@>Y~7vzSCtoGHqUuU}x6OCIudL zUlb9~Y@?(3I;0sr61bchbLu1jL`rU4mfa+?783I2iZlYvqCPvDpe@>jqy}Kr)Qm22CWCgB$$DH3=?w?4G%YXdbp*x`j=G3m%Xka_oO(MUbIKxvtDsKKizIa z>#E@d=}mfC;!q@HGc==9Z1w59nG5-7vbbTxO>`61LVm_-dr$%VZ>4a_88{(GHE{kk ze{h0DY5{@E_h3VyZbp$lZy3mC9k1PJ`5L4^CArt){1Bt;U_WuxU|K9QNcXTR7 zFY1o_L;ioM8AeqC^GBXwUgamjQWF{)syAD%XQ>$TC#n@YCj1M#%@0$#kirur$A z2}Y2z^75Srb5+Tlw)#so;H_I#b7GQ`UB(lJ8sOBoXaBO66M1-O$RgY9U-l^FI0Q-7 zzk{?x_cNG(#6S$(dq24Zx!de|zV}|qXM9{97L9ml&Lnfm0jLaL#^EzMe_jsGdYGHP z%#~TJLhHO%d2Ga`pg#Ymlb#v1>BHZg(jsW-;nuU4d;OOE3I{Bo@wP1TY zXbOnKBX!EQI*bHiqYp<>9@8yt&@guUe&S)gZN}~hT5EjWE}Fsl|H6%89(mqFPeOF) zg0sSFcsb0MFKwEZTzH8OoOr;nMOqr++1c6EitX2=yi8SK(GwpU5ScHGal}zJNvD6! zj!I!j8OKWbWQ>R4b~3*EFqV5_4nik68YO2+5epVxkQGWXJblHOd3RmHqej#sC=$~1 zOTF!TXOUi#MYYE*A6iYBV* z^9nH#9`?h-Ba#62)MZ}y^icHA`rT&u|EqpCrPX(77=~hfM?2M+`^(ZS0>G|9Sjh;z zGcABaOknuk=gO~LMD+pf~?^5$p!>zRQjO~w<+(YTxp6S?6 zKHLs`f&1K?TuIHDdEOGBs~%$hyAQmPVe>+Vq;sx-qZ1Z`#9}^y5Y~gf!-P?pR<(35 zRg9SV+nrz{3+aBt@dhodj6W`;4`H(&HXn=w=yv$QY+4b3ZAi9gbg5m$J5ry~Z3>_{ z>oy|=Gb&6_j`4EMAw|?VjD<08UG*M05r!sPC4FAvM{NJ(9H$B-JGBaZxH7NAerGNm zWidQVhQmJkmM(;vmf|P6P<$QZswtLFwh|PS(IJM1_dH3*(B|8y49(WK{v-PxbTTZ7 zPaLt7{!J{;&7TMpG9y>4*JEVHZviWmynrAcpwmX!^a#tu_N#6xw#`mf-XCMD_l^r{ z$s}JPPIB|kJ1Uo&Pwi1PJkX~(6Y$r$ZNw$1;8dOmdX7z4HzHg##S7>bNnTePv1T;Z z617nHyn|fv_|hFwW-rG4erM-2dszX4>y<_7+OswseQF-gW5mMd>Ybd{ejU>va}&c7 zW$vSn^*I4Wu81I`6T~jt(W}=vZyDSvl|7j#pN8sRdkX3ySyu7#BgFA)j<2CywPC#} zR@hNDcIEFvE(dK}6a#EOhF0AiHL+=XdebhwY-II#MmoTz60H;BH2{{sO0`3k&)puvKGky)SZ7n09`92c)kzhpigL{uR=L|F zKI7VaZlsUg6r@VbSWYsARrTdfC`J2Gqr%Eyzj2mnjb^v(9(=ga&87NkMgG$m`ZqBF_a5 zP@|ld&-hZFt=y4YsqC*M2Zl?k*ZBjj=g?~?K{Qyf`QUA>T}(Dfu&AO_keLFydKv%` z$CrvlKDV^jI9|sQSyMg~(2DP~@V)IxdN(&JyxehinPGKuH_pzr!$HBut;4kC@aD^D zyZ*cZsk(uir?-tngc0HEcZ2HV;{nhDad@mrJBm=e|IDq7f}rdc$eg7h`PQMS9$+bGPN< ztfIlHU3n5WERcCg0oTq|5+BPz@BAw6#utC&S~_zwu5 zKn|B1^7kKz0w8K9y7jPNhn{?*<1E@8>?PvlMufvdCex@U`zKc}_2+3^|xR*0*t3;Le1x0)xi}6FX6GAzT({Y1>)*{AeF^S*mC#Zz>QZxsNPEQks;m~F?8jbS}R$wHW_+1rMow5rblZunm4k(9u(ky#%iN62WLBzSQ4qLJ5bOt zKa_$zqV`)k9ea9R!kmNkOd6{MHhxdvL|0N1TQFBynTd6stUO?A{M32r#uG_2ncT9r zWTF2&8P#s0>eePZk~J5@KLvSJKkHX50D-E&ywC8_hG%o#CTUsTg6!4F87DcugF5`E zXL?uLvZTHaZTRNOJ^UvWMT`Q938p0GQbq%CL7LAB+HwBTzo~A$DGfL?OSOc+(QW7j zV|xj}E|+#C(nI`m<=NxGFkQYj)~9>51~UKa8Qf)@;|mZwA2L3k6u|;8I27N7r$&Fi zfWgUne(*z)hr{tp=_E*9OytWS6Ul=}&yvRTGp^MK%VGC$!fWu6dIvC(JNnzFdnQdT zdx@G*Inoy6dY^E$d3jQ9pz$Bf)!s@rOQ$XCHV_px)#aTJ&D`JGFkT$4q^MBUWP`c- z4F3fiqvD=QYvM*`^jOgR%x0rWawz@ohBE;1*_b5%z3=qQ}oV?&1SD!hmAC~VZ*}S%AA|a>H3Q$Cs zp6`IbzeUFf6>EjtFo}t@N*M-JftfAQ>7y=^m+xIHQE_5ciZ?b4U%q?^q1xy`Lm?88 zKXzKfB_g!(Nge#za-sGO9bK{dJ)FNF-Jm`g=SIe3TE$aQslcIEpIm78wI}ISR;(4G z&O+^6f|VZL$wWe&8A)QQ#=E)z5l3$45URK?ilhKh#l;2umpBq)T+yivxRF}%nLr!P z(8zqF7zk82W=Br`*L2?(=Y@p|X#s$Q9LdD#8@zw{w>zhCnEbrUqtT`|5hy^D(?QXd zZDiKsqQhLffl5+H2-f~Yo{VSWzy7C#JS~-$5BFtl|HqPJ@;?&}KKm|M=z^;L=i%V9 zn3bg1Qs}>UpN(RH$=^J=h2G>RUK^kI`Oh5AH00D=)E!unvs(v$M znhtY#7*{)4rTIp{JO0u@Z$UJDd1 z+IPVT=aVE}4N@bi0v774@Ps=aFAgVxx*FEL<-9I=PK(A=IGL*OdoKuR^+e*}%@iy3 zRD|Vav)~r+K0^@5gNt7KN^Zvz78O-GCiQ2QH-vtWLQR5`-AUI7PdNMJ=P8lt77rpc z9ggOkQykkEO|D|e)5ky^>(1K!1Wvb!nbXt8>bL%~=0JU8sgGp%nAoLtbqnd@~70KWaMWKWf+}Hh#3Fre7m(aCt|t)pCaz%eW6b(YE}AYtHPr zH)$4WYGk?UFG^+KlOK-fJzC_Ex+l=g%or+@*_4Wan+{CU$k%<9yaOS9jJ9r*R7DG@`yGmD*cmURiNkX|gG~$oE7p zqQ#sH#IfdH6yI9`7P?-ufU@K?y(TQSo(ZYXp~}T>A8f(Vb6Ol@2B8=DO_hYL*1K}-O5%2W zTV*m@>h|s#XE}p6p)Ml4;ds~E#sDZ})pluFOE@5Vp6K1}j11a>GqF9S8Emk9PBL2PJ&jq#PDB#dwJ8DIHCRX!$q_b$Z0-7-VM^AQw1)0DR#{9azS`whY_fxu_16og zz@eNB0HH|v_)^6@lfDQFLggCUT+bUSacQh2k4J7qwT(X+i0g7YbHVap3t66 z_qrCK6KR)c6i1Nzd-EZ_q4WnDddvIJl`9KxF(|#B>Ya&E58VZ0&1DxV|Ddwv{w+gc z-7!?2v)9j-o&|>9eSVAL)`!gLVqA>*-N5slPnqcC{7 zP$Gpt5uF=G7hrM zQIAj^?ANK(uEH9uuqQDb?_)Fk^>Kc`+pL?sBFYyf=cQ+HzqbQ&`M?sp!{MAsxbCa* z2VJU0i&cNe0M?6v(ym*FvkgUfK9?GZwuI)SF4Ucg`kaLH6{jF{ZmCsY3({%AmF?95 z!+OuVJKpA7Y;{J>k*+{&=G8Sal8oHdZ^_^a`J&>mH7easTZl_p-lZ%&Q0*{P3PYg!4I)3r&%~s+) zy)=9IIPh5!F*k}`WO}Z?l!M-yY$sBfiQp7lz8{v zHI!qPRZn|&ydLv4mly>#HICycqef%wYx2)iySEF30NwsWiF!k{H#9u4rbi||M<CJ;L&>jeRI4`nYPs`Qq&NP7--QXXk4jA){!L6~)`K&hDb6&W%tgUt@ypMD7abja z>e6BcAejsrjgj&30s1O-C(EgTlSP$YZ@39eK2>HEb1VTRK0`-#_#q@8K1yET&)xG{ z&NE?!jb4CJ6I^1ZBj+30XM`rhZML!06oi^Qb6zwZh`bRoY#-FuPx{|hjMvHNvU!q; zP;CHk9X{vKjim&E>4<~r9(O+Xi)ut~q^N24boEJnqW04e8a-LfRGv)w{l6{3fHG0h z;{wve9@9S;NrqN$;yw%B`5^25w@bvouV2?wQ~+z~AD7LK|I9uV`p-RI!Ym-%uU)_o zxbt@96+e)NsvB6AHnTL=zzN$G|P-8G%F7lDEM5OGnskivk(zzs0fDtoob}mRaCe@}@8P&9!u7Zz zP{or_Jf!{$1MygZa~Y^(bMT(IS&3kwTU9cZyGB({RfXVob-Z7ld7rFj<$`7o*JlATc_lk+DniV@7j1hzT8E6F4|z!JzmgGl%RmzuhG&ToG4!s z-TAW1?m3DaOZCSuSR1zXFYui2zNbCf@xZcc8=fsK8V{-0$1Q9EjQW3Ets8(h{qrnKroOxH3!$y}`Me_~Ja7Kt0A$jwx zM}8LJvKG@5KN2dxcuKZxYl1A;1B@p>j~QK1(+wWir2S3s+nc6UKa+ibRhr>i+TPK<>v<@Ik|aQ zHCk%Z>{Iiy)^D$LzA4way9t-1(G43RFcM6pWR3lbeV_ff;mqxgWI1@T4`*~`#ISWy z@CEX?!$p_J>T_AG(<1C8A+I0nl2;3f*Uaon?-NDV&mcCn z^ZMp)X6K}TKhD5c_|GsO zyPDN1Vvg=^UrL^DabfV)Ga&Tfbip0PCftXouV5&6O)R0V4Cjizt-FzXPANgumHI~X zHZ#>{&(!Irf1bB)F=Hojcy6Q0C~k+|9qK=vMhoKMSp6+EI_1281v#$Y2uG@uNo4V_ zH3uu|QTYCt%N0g*i>~1(0Q1`oD))pfg%1@U6}$i1>>Y2m7QU-66tO*BFm}6Mtr-ew zO!b#o+1i7D9%?8d7>f8u=K)B#^``%qbpzH&$$^BX)Ovue@#4hbsAY2(d@9xHr@F|A zY+<%F`2)4<+?^N#^NsL#w)i{=zOKNJ6)_)cV}n6YKN)LpgUaS9|ASFaA1SbvOX$mH z2NSeB`WtrAkUu&(asCz-?G=ON^n_7Y1lo_8p0$hd9$V|$&NMRmOJ=SM!R zFZm{38q=I*=bj&4%#L@;HNH$)?>jHD9HW*VZIW`jF=#Q?|GE?#QcPjJqgqa$3#nIA zWnB*tn9NHL^tCTk|L1+*tSkBilW%`^e^55r>}RBrybA=qx7pIxX)1FixZG7e)x)xC&| zs`dTS)JEQuQ?Y;8rTzWPEOhYqvC`4LM*9Jz$+{)k#FDLXqF`a zrc>iN5;(uDfapSi5~9lW#sVk^zlwROc2Rs_2^c$P#{+V$x&q-z8wQ5j9iCwJ4+iU% zk)`f{;e%Ua-;mOs55}CxOTm3&dqceecC4;xamS7 zh1T8&2GAqGoh2Krc>{m{+lh1|1lucwR|qh3t)2qy+U1lH*GqYr%ze=Q-TfbqQltVaBr-2~@^Sk0*R*2SGC`>B%& zChN;w8feX)R!X=Kn}|qb?;5p<#b~)tsG53{^RLF&H+Ss7j>%VO9MRlu4s*(%kSDnb zLmSnxGc(z95z*l19CWZvlGvS{*(rIxN`ZU&*U$~j+fZ?VF7nsj(MezzZRT@|LCXsO z9u0$);{N$z1ROm_4jX4qR-A-CbH&8PkqQb56wnU^`l@6o&XQKz6_l=YdW`*b^5UWf zhCIzSIx}KgCHF_Aj!dxC?rqLhYQQq;Acec|T9JDYFR0&|xpb&><~UXTVO_HpYpWyR z(;#+O{n{f8gDH;c)2oUsIal}M`BeB}pE>34xvpX(UPKMp?BPhh3yV_V`j-&(`&4k8 zwYg+|d&TtY#g-6(mPo;9_s!bV@FQiGOg!spK5ruJQB6iLI(Fo76=}0W9Fg-d**Ahu zgWK^qN|A{>8%2Sl80%9fF@NUV6z$+|($K*IUR6jZ;7s<-gt=+s4LfZAT>l6>IAukh zA0{gP=^|WoA!9>dak>M@Z2MoDb}g76v9tWn1w>TJ%54`RCgK>W1>$_ zcdJ@AV%@!nvE&T0Qg}iA`bC|t?)pmGVC!`4W^eJuC2|+s$Wr+|CV_~82c35T4n2HxOgF+zpwyH56tcNr5)4{@z>qY!o$htF_e`dB+k!7|jt2a;8%21MMs`IcGDGJ%qui;cgP zoLBq*|4??wicGA@x9SKpmCHYoY*l*$^M%pEA*Yd$k)7lkuFZrrec#6^c}>;w)Py?t z(l4dlFPvzxYKb}ac?P^^q5 z1MjDuv^GuN4C)Idzcz*0+kZ(568K)>A`=NxW4Aebm`~xk#4ILpyjU4BN=sZ0lIE$s z=<{iz>#qz74Ko;sBf^VW?ReXFJ+1b$;$0X?Gu2WuXFq%g1j6~!L(pP5T z8$+M|yrG(tnF1Qv2hJSa&03%W7vZVqh5qwqfo2&cXrsFcti#A_cgUt;{IbPukW+tm zAjOA=VX1ut?hhM1)YW*Xbvq5rg<)5e*CMU@s@D@{f>IkX`t7FbG{YAXdf`0JuLG7E zl-wFj;DKg%KFoqZr|E7(^fDB@*$!^B z{#5+w8RR~cnm#nh1Ff8CQOa9J?uhc^Eee3wpIv8tPm?*1a^Kzguv`_gH#n$i3*ShR zzkBs+v*|7<$JA`$XVk-_%6|Ax9C*Px33Dt^`jRM$GxmM-`1cxW-MGsk;vf(ciVEIQlmLYOz}b(m1c8VGl!oVWHdF$ZjLlD#d@))M-{Tt1=TbFpadf7g zUe-eG#%UslMG4N&PGojEHO4BULb9;#4;MeAc{n4F9@$tO;|I!F4aTdbBcR-Nfo z*#7~l2R>3&EPiQG=;Q_E<~k#c zlcU=53$)Y6L9rpR%H8EEJkPz?pJRG-KA75Uvh{8&UAw%?>(P|LTN?Jh(dHg>gn<+g zudd;M(8jSj5A6L%=`<3Y=A-K)31;GJl6S#S8fJ=D+H7M_S3ssLsduue1eA znny@va3yo$8C=&iMf^qf4eLp-o#IyBg)eQ=fi(T9{|PdA&*hb?GY9ely2U6oPS5H9 z+RkdWn)0O-O)Hwo0Q$;Kl&Q;4_EJ{8bsgUWc+gV^x>t>*fTbnMs@ZsG2>0hVI(RA1 zdT8mzqpKeUWa4VJEWzDJqeqk{+K{cAb6s@;{ugR^k(%{<%?c90Zoxtvfmi`045_i9UeDy~Ce;B94{eDGgiF*@5TGTus?TxgBpn1yE|;Mf@t zGT&3>MGf+A;R{2b)LBi;W2uQjgb5LcM3LTG{K*=>c|P1DiH62>=PX35X-GlN&3Sva z;f^(BILVVqWr>OEg0?plvLm_yY36D9Ji4O~zNYgKw_TGwJ6{^%EoR8+s@r9?xRmYFXAIm=pExg8KG+PgzuR2Y=UXL5m)Gm@mqSsn0COt=F6 z&bLPUGQVBYr7^E6;Y|A5s(({fO1<}Q9@=Y}QK6M60TsH@#+4cjJ;CIM!aAzFt?i-Z z*F$Q}fvtJ4L3=hxPaO`Ygb?iTtj)K~MoaIitx%n1-q8z@%C72rhX0FTF|~Gu9vnEr zpq&j1%X4G1B;guDf_|ZPTO^l^3OShJe4zZ<&S-$rUDtTq3p$XU!xTe=mRkEkjL%4C z{?oE%wRc@eI0qr-t=r*fc{vJv34#AMSIEX+TmbpI6lE1yv+}m-DIsJfES>}%c8ekB z5{F7R@Fx#3jyr>75vPZq%b?S$tgQP-{cVZT=uZ)T2uK?{5NdBYn4di1RU%@-(>g3B z&0766O#Bs+q2ZB%@{uoj@fV*vR|JK$mBqt`*A1UH)%?`ZV{v@-;(D!hB9hC$S?g%%x9Cu%4Bs* zH0RMYrMHC$C*|{r^D$Aoo8F3{J}zd2EZfmweN z82@zg+3gzc?Scv?R;jU%G5$|NkF*Hhx#2y&PQ<0O;d3lFty`%Pe){;&x!KY8CNBvN zimEgbo_3M+dDYtOT{B&li)~ydgmjK8KX+vbZ+H2AVML_kX+DOm+BKcN;08l8g0Hb; zz2MQ=4;l*wSOG z&`Ck3;{(FyE6q0#sw#9Z%c84e$yB0l7(KNzYk|YA&bkG|`37+B)h>*<3NaD_xPq>6 zBjZNTQMpif__Caqrju+Zs1O2jmqxk(pAh4R-aTyC-U3^|EeU$LRX-el zj$ei25@e-!pUr2Ru3qNcBVt8MDV_TRNQQ9qa+9JMg6FBUTx$!#zO6ya+DRKr3ZW4b z`E4WLTWRZ*tuNapCurJ@S$N~5n9wu@jMXzrsO<5mikieLZV8eTH+Y*+YodpSuV%T@ zRz$v^T|0vB>R7{%Ed*K*t*p9#vfCXm#*V*MX?}RZ&Ye%ZBn#Ync1pvY-27omyqFg~ z>x=9`S10Xju(Z*zx) zJ2!1Gz|ExM>y>cuZk2+oybblJP7^O^4Xu9fKVsE7{j9_l;X+gvps zVga6L1FrcYji?dO_SZ`Xd8Wv{wT=pnpYwdNEy>qsyTQJPHaw>|A48VS>ubV%iIT6+ zS0`E?W1YWK7vfF+u*E=;e0x6Ca~YQ32wGqv=(XL5w9=hKXW5ywYc|)TX=Wg=M3j4; z3qMG{zdOOjf5f8+j%#nwDDKX;M8f*vDT%`NU{2Zq2V#&&H#GOnol#b|rIxF$Ll zD;a^U2M)$06IYWVU07VYIP`3*kX$L=jQ90$))Zjw^!G*mL9aiW@;d)(_I^{iNivfT zlrJ3W`ZU|?P~IYVkaqXvC^qvyNI*kh3%h!f4|+-P1%Xc127($i5| z#q8>{r}k4oyo_7{A#+SspD}#phsZd1AkxT9E8ILP>8Zz$_fy~RUPbA11-(~Dma=eI ztLgEZ$z2aVC?X=zN+YrSf)GXN$;aWT7POtRZU-A$2i;GZ=l(DJ0 zwG1eNokBE+EGUS`1$Ic9tX(46HVz19el{P9U}8@D&S{y2)P-lYDMXDBDnxlrUJC|Rqfz$yeFDJk`Dd^F$B&eE{}pxmPd*u&kuesiQyc9& z=&=t@KO|)Sp@s#fEePcbmxofWnCo<;pbsuxPo&~lt>NVn?*#t_lK`#3Z<^8W&)r=k zpsVH>`cH$X0%F*F%3G*U&+L{W{$N8;t&i<}E#=e}XE>l&NOAjbT3^3UMujqvCWwp- zszT?>!92MRzYNYgvZfc$o1S|s3bXr0beEdYSugx8%Revo+D-;eZoVt_F*T$->*i3g zBVLZ!CbcJ#5ylVL-QE2ch9{0td!VpF`IxJ6(ubGJ0D_8OK?|;Jps+=hTBz;^fCL zlC%2&m{QO$g4gz(B{h1?Rk@Z1b38BGDcfO2>V#=<^UrsKZWvcQJ=dm^!_qo2b9(1fN%Q?r0l*zQ1~767JdVgJcwqQzzT z-ZxIuio~u$fOFnum|!zcx%4By^Go~G(WAD5j?Jjt9LGv|pTS0FPRnk;Gu zyyQlaJ$C6U|3B&?8;X~{AcYfvc=k;~#Pinr7X736i)Zg*V=kvUJ*dp;>eo2X9S2r> z(=TTQ{q-Ha$x`E$HJ6Mpf^6n7sYxugUmCq2uH%aPZ^@5}XX>zhgnL&v07{)qEB$nv zhj^|tK|a!@F9kW%6e*Szx_vwuZFaa371mk~(Rgw9_dno8Np|Ci;kH;W+1al6Zi>MG zy3i~YU?tAGG1PoGfdAPkL%CITa|cX?cyf0? zlw>0!O@Z##2#;3rgvzGvq+uhxXcx;=7Z_{<{j%8U&-yZiH{M&s`o}bx%{tQdbWLD) zZr7aUO*VHkuMg)H(2Wc$uAbnXT&~ic50}C9O$Vlu#GVY6sG#7z zx}~1#t5MshBgXNai&mQe@{kf_gA0=hqM=0o)WBjAXZ;1`Tz~fw4EIspUE`CAIo8<0 z9@H$AqMzT0vS15Loi=g}=RRC9=SrT42ljxST+fxUubuoJ(xl&>9OTtMDaOpE;dKCf zET{dDw>zN?(X6Tgg!sKuMU$hsCq6Hc(H@KlXIQO1how9G@mOSAZ}ccMKKb1iT~>=+ zX?XuD`hBTk%ZI38K3>^y1M>A>d3mgRG8kfCz5tT55&nlmlkf#U z0z>|`+o}%Ir?-Xzr>OLXi=%ArLgn1Y+r^?Q`WO7ktVz&atY^nfcszZmDFLqQ;FP9S zQx?W19}tnQ^^W6CD5`~0)bpCjdj_m0ZVVb%lr3^n?sI*1Kyn_1a?MCrX zeL#^5#j3-@9+wl-(xM2?@pf$5(;oiGcEZRL9!otv)vGyJr;+uMhZAkPz>Wm51TIhb zA}{EsI_nGxcn1$qIG>{D!pv6C?=cur++3tk-vAWhJ!KO<5ZY>Ns+&|y&w1r*%JdFY zhv-fBRig>Xc^r?6Pu^_e796?iwopl1hzQ(7Pdd-^wnm79!heH7#~W8$!ug*zzfWgC zP5lNtjftlIceK-#DJy7luMNU1FXUB9J)wWh3I52d#m)6A@D?!+)-04mPK>^Hc5szn z^^ZL3cV7QSM#ZarKcjEV`<#!+O}Eh-FYJ!ZAMw`GKXF9x-xGsX(>}?#3f$o}IGHm4 z!QUk0qwW;=;d|sV4Q`N`vC1HwI}R>#p)OFme~OIJ@DXU4!UQ8eU#j{SiS%MVNn^Ux z-=8Rlc_=kH`W)+dPnedOEGb0k9ej6^p<`3R42VY+kI?_3dR-%r`6J$4y^Jd=psXFh z`T&V9z?A~fRi0Y_r_nsVelM3hR(o`|TZdw!ZOKyI5Q&RX37Ieb&G^-8aBQEq%y}!L zWlmnvrQ%9m9Erv}-s6GRMi0U4Meiv8Mk0IWcQ=-}7uRxp%HPC@KIW?to|7p@M1_H5 zTe&}o$-Q5t1cw@7?)po6a>8FKQ}BbKX0jgQrX4o<#p2Q|n`lcX?n@k6Di*Hz?JRZA zHYk0k*B_9SL^e5cv#hE&_3U$)P`$Ek!q2xVj~}KFcV~Q0`A9AXObgUq zPTnRZ!+qYsF6Z&DZsuLA|AFGDz!dOF_#`B8x6vDC8E<5Ww&~3VxI03P=yF$~|HUp8 zL3e}b*Wt2^#V11C*M4#Hl#z)&BR>qfL=!hp9)bX2ak%;dQAx<3BXy!wS?Ww0$L{4> z5Ml&3TxXl1pRO*M9FFs!;pf_~Tg3fhL}|cM_xg!PHG7(THtC&^rp`-6SpG#hz6$S< zltMfbrfX=(P(K0T-)OoJ3)r!nL#(58S56wSsSHXw`9BD0|3`S3cUeX%5?brYH{?XC z!$3xcYRDxFp1~*_@dL>{b*bl_$-RhV&O^3@3V#h_CRV8K{{$t|(mW=AArF35S`jO< z?hHzDMslQ={;rtlc~I{fp}!p&6l#3;j+C$WEMdIG$eg&P=#M8bfcDZ~ZNJHHg~EN8 zf$S>xCY6o9>uQg--sCj1?x3o31xE@?3sW2poB+~F8)#I@+=evOUn-&;RhX}C6S-2H zsVS6I5SA7e$u#;Z>+)gd7d@E1P+ML&oZ}xS0T))sWA!8sOKAfGD!}kY4;Udxr&b#p zMJ@^qjQI>uLxEU;8_*6=KPu=#e*L0obUX>yS6Ots7`A83(x&u0xQ8F&@Yp(D=06`s zAQKw=6{85LlE^QZo&BzYq8iZ5>tl_~?GilboKQiylQ4Daq;rtp~U@LA!= z?pU6XUALxnl8~I&xI=DrI2MVPe zjlX_u1oR5uZbXEo9a`@oYPf?1C-vR{AiTpyVIT=VyB>*z0Y<X_mX(p8fi^p@5x_?XHkPL#F?p z4(oM6%HM1_uFS5ku2q``t0v@x${@=HOwYGofGI14Iw>jOx+ppMR-hH4lc}5zxs&PL zDfX*V_`bfrwu38O73_HZsPuFhCfwo`}9kIvOkvSE%L04Yeh6r^X^nuPRVet_fR6)=F8TTC)yBnBuR>g#}I`n|0!U za|H+;E$RrswTQ^bom)0*S1xBxyZ{{_CN)(m`*Ro*YW6L2C)1Cxpmrvyww~JdH7m@B zotuXWGlH_&kd+f^Y90cJveA&)gYG@MsH7x-Q6Onuo)i-!Bq@oKYy8IMT`WBkvpc_* z^({UM96%6A9}S$`>taFyrh=_mtpdNu91xv%&qgIAz~f?KZf@K>K#J2N%WFn9*&ir! zI~;z|)FcMjk~;uNhHF~@nyXekpa=`LNY=MhK_>5;_kMZvuWt{;AT4g$r-{jeDUZNe z8Q`{?Jjq7|(B&x0eVx4*BsI|F;ux)CL(a4h)d-tX|xmI`NvVfKmakX+ku3 zfZGQ^y_lGRDI)E;qdULXTt4tt%0OTQtXZHRj2{zkoqPqUF{K7Qa)if>+C8joF%_js!K=BH4_5GXMbzn~Iv3HXt}6+crxbt=w>hlLRi&iAsKD(ltb zLGp14-^zc70Qu<`3=Elw|CcZGm){=_rPCWu4sLpf`1I8rIFb(yE}YN%^ahqnT@CsT zw%tAXmEK`y6%~b~E%UQ*B_F2|qfGk3nTg_zvikOJkS0p%Cc&MB3UM3CsVT|S=fY{A z__8LV+_`}+=lC2unNA;`@^$+T&zukfJC)-_xKnfM>gq73u5WH)B&ozG-ng!6VCmKH zC=_+V77En>!|oJr9A>=>s~@m*xvh#MmmY+o6q^MRDoo#GpphmIqTe;oMkh!hkovt6 z1YU59w3+&{0LkO$?8C*zxaDJu?V+^c@j#;Az6n!x)nhBOq9fM%i2l2W$GJsK1l3fS zNUu@g&YW9>O-!t+sp7;TV+(m`p{LB)C3uOcQ>6iJQiFPU_=q$x&L~LO2QcxA9!(Iq zK}V6%u$bFb41>x!THNVavwANJ3v~C4N`iVfoZR^hhKvN?iySOsSI>N}Qi=VxdErdh z`~HX{wSSd!l}&1UIMvsI5WAWoqpl9VlSv$_T>O1wW1|&e9%dwWc-U42!0{C(f9>WW zF#hEi6IIUXPby-WwFi`5>%J|UE?wp~K`?xLd~@NzFVS^(-@LdJyt3fs&ru_mG3-<* z*&ZoQo1EH$E3^Qw$VFR12#sc|;^m{E=+Y|GKGZy0MabtORiNXV8v)Tv98tpmm2ND> zYeMaA=z&esTBgTj?2&C71Kutl09TH}oZ1iDZT$H3G@H539i%m7C z1FWlr1aeu+HU4l-O^Wlrv6C&@QjmvaNq&Ll+tfjwdp8(&kYLfGZjLck3{^~jtm@VE z^>tP(8F2)(HV+ymv@B|lLzC*kH_BY&B#IcZ`}_OdgM-dmbHKvd*e%ys(f^k$f?%fl z8u!#Wpi`ec$Z2gQDX~}3F9t6wL3^Ypn6U?r?$9gLG}awAjzg9uHfeAYGWgftxurSr zO1r!BeSE)aXGTz^Y;Wqq`!m3s1tk`$lL>ia3||z-=UWbDJmA0!1JSp2k%7r(e>F8T ztz#6HB`cLIp0j&&v<0vd8U3eqZR)2pX7q046$;Q$N2v@^KNmn`+$elKbY5D;H% zlC=uNv2^$6rrmPm6ms7rA(3{?0R%D9BTcb7w5~2$`RK|E;6oJXFhZ~0x>r9W zO1?o0EGiUm=O+Qon-ShgVSsDTl(AJ!B{^`X8c*jwFa@t=j_y#;;E*RuM%S4yfWdnw zCnT5|jlFn5O^fC@i&Im=EQ!MJMYOcE6q*(@YpomNGGr~ zxG)0>Wge~Rjg8!rlYlCCVrfZ=CQi_q9z|a}i7HK3Ican&xGYc%G^aVYah5SY=iKDv z=C6;XsWiEf>1=>(taj0pY|8m~N`CfEiaYUpX{z4dL{4>0P1N9))0#g{&%NGTDrNgP z6E0bz!Y#}9vh>Tx+_Lm_4<*Ht_Ta}xg@WS>|5vV~M%%1$WAX^3RN*lBSfH1-!RjMi zkgmz(2tVkiO~P%zL+^S$-{I5E*}|yhPW%a9pzRE*+ZI%JKv#Q;gB|kn(o$VjBE04O zo3iw0%2NK4peO<9@U&yK&h)f{jf~0gT>U!u_kKSM7rBc6*wkImMIcbx)xqrK*w{xo zJ&dB+(rz3y=B5JKwQa>%2YdUd{_o}H$;-={&u0;y08K2vpa3$bZ=U^5*yjs{AXRdS z$-G))mx?KGcYKR%{+p|Nx9?SW-wH5~j*hyg3)QZVX?Th1!_2`7SidZsR2#xwTWwZU z4+>}6A^N|+c~_0hE``y_WMpB{!vvV^JV=1=o;-li@I#o)&fb3Q;tsGS5hC@Yhb#4H zC5h;j;|>5qZo(jx_B&rQb~U6Vb1(y3J><7N%ssoLv{Gq+0o(>#0@DG>?doEMImZ=f z#njh9DZ%N~|0bT$>8-$Xzl_6OQcz1Ts{B%XYc}wDC#PeT;bLNgnnyK@!ev=leT$`g zf+u0Bc>{VS_#=p!9%}00q&59wRKT+xKs2=aER%JRG)Ih=SJzBnjTtmW*Lz_TcA!qY{jA3WjA{N>v^&8B!c&+CM+%kXYv3216mGzCgep3RCXU&JSm$-d55Fnios;>Br*42iJ7)hjO)D}830)u;$4 zdcK8bSUCEG^sfZ)GuU7>Z5UuADmOXMOQ6&FF)q-Ib|-$J_|dI9R~z;X33y&yT7bku z@ut1j{QS->Q*hz~VqoX5Nn@XOZDTa~d^C=Wy$`ba$96mCL*H2d+Y@{O0z`koZlvi< zfqpa;-axfpjnUM>DO4(W1`?B%PS|?!_fXy+_uQ6D6aa|Fi5HlC2MkFByzC{ZI(=Y~ z#dr3ZrQG;QYHDh_HmuL@2!Y@vNflxDqs&pA}ivl%tATZ9jPa| z(~rhyv|XBSFA{MC9hp4I0b&*;o`q2)w>%<2My~dX!J0mr}S&h9ImdcIHM$_ zStE?Lg5so(+})0&H=MT<4V6J|cfzQiI3L_CAH&N8uF)87cZ3kpl}%0-`?NxR8`gh_ z5aN14m$?Ve5;89HB}(jnF!y}KZ{@m`T;|(`POuvTb9L{KhG3W_!SirlFyc1Mvn4QkN=*Gac2 zHWAH~WjwCUu!j=|bLqhq^dw;Jradu=J()bNjl(KqOUs=g>a@8Qk~bAfu{$#KybjRQ zI>38CLEObJAA;QY9f>&XRzb-WVD_dWY@Sfm??`uDYWzB*<2W!sDkC8wm@VWlE&#cK zYr|#_fipn$ufJ*p-_|t|uQ%)M*q%fjuLUEAZ>{ajT7OLK)K9Mu2FxTqHi-d2ZOJqQXH>P-EO<^oLD?JKnETn)(d2{0@no3 z^`u?QCm>M3qMt9)-(?1q;7ZWfw zDkKEx$O4%X0ii`x&|6!_^`nwmh{IUptBLLN20_!+W+|%V_LG~93zveTBItp*LW?#$ z$vm<9Cm_Jk#L*~tE5a3cfAqS)cd4Gayt$Fn(uy#~#z$;A@`XQl;sv~>CZ2@Jm^Wi_ z3gk0WEm#sM5+x_5r$u;)%UsMC1sc@Rz_tAbRhL&+6&{^%CI|cCWv|88&|$vd^d198 z4VM<6-kh1y1+xRyATSDeBBd%o$4Zz*OpY`3TX491Fc+&qMNL!SvwZOJv4xAP%SYM~ z?gP5${>{=>lGk$5T(b0wXju9Dcd9(alV=;?t2{zrI%9LbX4`PC zN3sgoW`eKK>`4whFGN6B6QT_V0iHYeLdP4yH?3hWTzlV2pKd&NlBQR-I@9k+MW4>N z!&x7cJzvZpjewDI8w;j)!51_)>bA_YFwcFn38_Qx1D~Sdee*J>E|yN#>$$M|4bxVihYf9PH^iEc#w<^-lV1|Dk9h()T0K}jdDacxKn&eQ zD|c^6JnjgO@6YRu_T6H^FGp}bH!svX(`8%KB(CrRMh%IKE7mY+_N^O50>cx^_PQS1 zpewuhr5DdjB6s41G`_%i1K-QSguDLUmk^G!#t_;vKELiT9_RB`B{|Ri!1}F9-XhQi zBLCeJw2JjG^KCTPY5RGa@Wr3GRqD?zcvyAWoC)@prXF!KoTUwVZ=B`Hj~-4Ox`Ti| zF7mZG5#k^v%+D}z@8}?hV@X1(KBRddW^ilw`GzN$?sv3*UaMQ zP4$XXbtX~=*KQvA)tpu3oS_O()UbzX%wwof@#*OB<)MwnjA9>xTGmx{INmxyEAd!v zT-<%x7yOd+g<>q6D(y$MZ{ygTxw1@9xl9TCp^|Slky%6-QSH}wvXxkB4qDOmF_?uS zW5gQF5&DyE={bd+gYe!8qAcOF9QP?Mdw+)k@IrsdvRH9JP-FH`OpH>gn0{($t7CfRYyi%qza3mN zfO9PR)4^7CZLKaYTwc1z{kxlmu3n2fvJ(L=7!AIZ=kA@K7yijkqb!Ug-fCQTBk5JO z8n)`lZ72+_&n^u7?dXI7FXt~?<~ITohdv?7we@J8ChvRc1%h&eM^R`hy|U3QyH7@~ zyTqui^94qWa&kP-8V{-XU0-+_?vilkYM*`G0KWO^fon>-2W{t;zza^e+NQV2$$B(~ z^qON4H%O8Ki;&Pfn z3}u&Y=9)4ZsAQDyyB^=Z;WTcnv&eW@?KXSfFg3Fc*J-a`q5QK}y4JY10USB+1M>wT zhVoO}O$^xrhq+MH$~gcYve}?Zej6nb#ioya;H)y_fG(mir4V5i7O&i z)>Lo@v<-}?+8aKZJhJ6Hft{1f8AC@e6>3IMouG0a63r^kCk~(o%w04*B3ey`=FQ@# z7M2SHZ&^_aDohutMG5aPo1>e)`bvJ}ZWn%k^>Mbt3C(ITZ9IXCW*jQJg|rBG~}4?^vqW z0VPa|F(NYwB@3;4%*dZIQ%hYy9FsgwOmWkZ-O|lx>M7+|3`_9h5kdAJ&DSh~F{j$M z)d^i(jW0PA6%q_sRr)^8^u^aP+R%!!C7H1!f7bCBcjDD7q+^Ty`h+i=&n+TnpE7_X z@93E3Upe4#D^U+J~s1_laOjnf+^1cEww^=!DRsfr^r^~Ay>8=A1MII_7}JG z`|9D5&`Rr(VnGfX(U^Yy-H4lun;OOmb&kO8k9^=to?WpXpt-YG&i#`paoDF6)(pW6 z_woJ&5}NTd-u`;5H)-)gej$_sA~53pRqisYS%}t+Lo>YxZ3KCj9s9SMy!Lz~O%My#|We^MDFi;#H?|tS;dUo?9 zRi}dsEaZLPDx2rMh4wMiv&{3E42k& zklOHb{=%^8n#7c=i^~u7Fcrd{_tH%Rt2&%Y8`hWv1p~aUNj^I6#`*T z)*&}rGpi|KYI+bk$N;)sN95`md((WqE@8%fX(b3IUQ2s$I1eX~&ghoS5122v=Sl6S z@Srmh6uN@P|44m%(86K65`6&7=z-d`HLah<%novK}>Cg>wI{pkr#7X&zMLE8O^6-fC>^qC%QI z(2#{(H`3&V*3;<{_6;EuX<6(a-A3RUNU0f^@mdB}5;PV5EG!p{?H^4hr z-MawAKNE%U=+!BV_;dk(1Uir;!3Ait54!Hc+2bwlCVJS{nEYRxAdAm&iY!8~a>cP0 zu4yz7q?VXeu%fprz44Z1rwhDFzi5a~_HYoQDZ$p{90fM$Hr6y?m9Qn&3pF!-tflp5 ze3Ma85oKhkcTH>Hq5n~12cyUe{UDkr|VbiDeOsE|g%N1i$LixrLEtI6JK zMA=^2nEunv7@70hx)xL~*>_z4aQj^7{Ph|w`8e;z_rgN8ePQ*r+v?22?K&4d?#IFR zF9U%mpwR42rHaduUg!Nn{ac5Mx=VrQ1hp3}RHYKmki<{u2}^F2txcx}9v%}BPA6dk zlpeG8DXpt~W&BtXG{VW-aJaL!y67w zwl!_=qtpz}8sN27JE0ZNTDNp9R6Mv&(rl@h$r;vSc1Zep^*S`^{&nJiB^RrM%NgED zXNrw4H9~VaHcV-IxpfaAPMSp!+xV$aUq!fOyu*DGupVcTHW*_bT6LmsN;K-cF`!Y1 zRzy(K;od7=R>xVuHZ55~{hD9cpiy+K=61Bm-WH1_R}@i`?FwHqTyo3z{As#^JUnro zA3h~1#yTH$7CZcC`olEWrVF8N5N?Peqd{&`e?V!0ns;N916Db{OhW4=Q+gVWK)P#q z!!y>H;fIa0GtOpuIDWLJ{@{Lxpc+4=}{rY=^-o)c7yg)`yj=wTpPi7$T z0MKI@#gO4`S20W#0S?b4B_)2HI2UES&+=({oAH!&HmxQ zW}FS`GTSG$%3q;OY#>PE?3n+LuD6Veb8DgoAqfzi1osdUoZzm(AviSdgy2r&65JsK zcelpf-2w#f#+~5q4)f%`_kJ_8)(k)TC%yWdsyZcm?wwrLBD<*i94>9|t z;>A)DTOgGE8g@gltH`^cU_1F3mpZRv#<~fsBx({Tf zqa2E3#A|73Ne?;^db-(2v+pM~p7-WocumnOrUi&u43PVHHnpwOJkjL;)wUQQ^Ek+h z^Z?*9vCdX3oVVA1g3}5WLUy-m6Q*9fi846hoh2mO8d^IuB2#|8PF<=USlE@jPSBbq zlAz#@q+b71%>(pMkl4w-uUu@L-+PeyHpR?SZk<{`t$FeFm1YZ{%I>sQ8^1%3lmOO+HlSAD9&Ofg8v+cdfNlvyP&kp1cJwvN2Bs znLK@gaZ~cv*0%&EefbY>4FRI@S60Gh&vQ8p!5af!K0bSrU_hp=8W>S=TFqG_fCYvPB>uy=+Okj}nIYIyTct#L0HNp*mpYZOQ~84&Z1@Cz_nrVUY{VIIOQiuZZ{ zEg&tXXa95^^G-Tu{@kDJaA0bw5%IlMp!8Sld=ypQ5b0S=Spr;$*I1evA$ zw#@a^)eb~na=o75)8Ul#2Ah|`_iWU)>-B^_D8hcFGTvGc^9Seq$|(sGpy^q~yCe#W z(R!%YM6cCE_lGFEfMP6|_}@A%(Z9_Lqx~%M_Z9FtxQ5@0SJy-CENfWiHJcO1*L|hf zoKtf)G>V*Wp?P-XlAANtI#4z>vf}ed{;)kPr{lA2!a&-mS}qdeHKim;$}uPUzpxzp zH7dn_?Ci~@xb#;Pb1in9kJ;E?53NApd}WAgU~ydc@o6qU3JG)EXNkmxYqg-rjdH>C z_nPs_DEXkKk>l4JbY7TBdnelE+%PS5PyvS3M(Su`RizXgw=84bKIx__eUGgRU&pQ_ zHT#I%2*D#Fk`oCttji(r!_6AW)vlymQC9ilzSwqnjU9N5QUJXKt#h@i=^mSid2f(DTmoeGdzp8e+nyXKfAP5}6)MNI0$`>$rPB2c;~@KdOz%X5_M=EMZpsHbMwm)rkLlfY`1Ft z6*kK2TO=CTluUTlOPYNPi3^VCq^w846Dj-a&_6^^IQ*56I@_btVIYus#J?&u;*Q$Q zYU=~U1*Qj~MYVL`A6Oy>3m=64Yqn7I1|;ofN-svK7(=rZ^P2?aI;6{)BqdCPN`C|N zZX8!RTUvvQlx2q>&3rJDmz?RpZ&m6*MFcSSkc8IwXpT)c1;byf)9CtjbfYR^RAkX? z#{ChKytE#E3*_pfgOK5YOFAaOj_4n6az@pWn$}z>By1ZkKpVT=_~%{O#YO<@BTdGPPG^2R(5X*OBdlYfE|-EY^d+{4ECI4&;J;7%YZeODQ#2mx z;8^EzcsZFu;m=ZmzkbkywA6xZj~t^me$>_EZ^tQf3!36fE;a;|D$){wpG(j_`#RV` zhNF=Xih$7xm>WoN%|7rNZd6#bp>aov@+MO4ps&|>Y7FJb&&bW5_Kq(y!!(Z$E}1#r zhK|q7G%Vc5yaS&#`ewcQE}FX6wF^81GWz=DRT@?zPx?3;8w40PH0qgZPjpv)qvmnT zTrG&NDTe+ZM}1{%6S#2Xu*CxnuzdaJWq^udM5C__bmvEZDa%BZ#0;*V@?ji3Jub>p z;RLYG_$v3YkLR;jC)zkiGo-C73WH^t#Z!{-LrBk!-<;SdrPrT>*?Pz6dKAkz*0-!^%9uee>S14P{%1Hy#8f#Fu%NBv@vVhp2T3KDi4eWwG^Da&Z1e1x@t3o&f-TsIOn})?{>e8NQ4(b3Ye6o8 zG(Hy_TC}tSMLW8ry)N^7pg)R%(p@-tbA=>R0`VC}%Zq& zNQ|fktc+&dqECfmK$9f<4#(UlMc5JUi}sEikuKZKqEQvWgjrR!gI`A`TJMWL9_N3y zFposFIWTt>FFJ#p@7&PEXd4ncSAQ) zNxs0&c^dTx44!t4%Nq_Nm^NDJl7(T}ggv^RjIpYH;0AZnJOe3{g`7@b2|>#c(BKyZ zzu#7f6nigBAr&c+i;cG~^@Ep(u1A%o)#u*WWCNKxtrKW3bMM^7)2p8WN-y%=ArcBN zPNkKt>M#LD>~)ihcPR<7LSPcc2Vn%k9HH*$n>U*An{Pj@xq9)tl(g`K_)~e90kd=k zEkHaAFtHhWHDGW~;&n0MVJ7zX=}2POK)&jK%N=F%tn%?|+Gwje)6Ed0-bOMvoF-d% zZn{H!uC|<}XLsy5mMlW?>CE`V@@Hlou|SYvDn(M=H*@``0CGxW10t#d^Pe>ifB1Q- zGpZDXrx%xHYbMYrDmgb@jkmu2T>g`E&6X49CPq5Y#f$e1?rNwHZ)jGOOS5MUL}z%13ErOWatY=ceJ$!);>ceINzj9R z0ahw-)Q@2sF}q;E+LY3Hl_*BV5Q~qVdUpJswvfzy=a~w!Ow}%~wyv0l zmH94NObdL&UqLV(%&F@qzKCj#Hk4;uw=^p5NFX4+m_8Eg!%4m4gs+sgCR#}nj~CEQ z-%AOB^oPDy&L;w2qv7_;B{GBc(c}j#a!Pvp41%n2wmi9qvYpaw&+R0fFudM1Z# zBC}27suSI)Bkx2W>^Q@47I8MqQ41m;m=shX{@wlg@!ApCml18bFxNi!u#xT4$-BzB z3LbyfW@ux&>&8^+RrYmABrP*vC~n-%;9q(C&CF!@gzoLSe7eYf?orx&ZM21lEwgkk zDd@Avchhk#)I~hgfosX&53}cdT(f^5CptIBsHz|%Yq253=l3MU6mX$06#K*E`d|Kl zT?oCy)ddFB7Eh{a8#UFDOyAS%S-K^Pm0652Fcgr62nbmvf+mp;baDLqL9M*s%f=m5 zU(nA*xdbPsmm$07^aK|IcGgIzfHWG;TX|VdC+n=`T}JTqMYExM#`>O5(}7pAHxw)4 z6|#vacJKe6*=tpW^Jt1(;5L9h*8@ZP>b9}nsr=Zr^6^W85^y^#Os0 zS~eUGx1T&G!>u!!zvWglE`MAgu*9ftnjy2JwN_pwJ-9IAkuSC0*=~6uYAq7H;C2%O zGB|>qS~J?}&h}S4)n*lcbF;!j=x1i(KP19tl^n8mXV1Y$AxHKp2s}}`)`gBi9Wa1?T_cC zJ7&D0UxeHc@JaQ8lW&Qybvyj#&oK=jnU2?Xn=;ojN}{N**HP3Mo?Y5I9uhqtVmjZZ91Kh~<7w*)S&H1~oy4;R*HbGnwo%?RgsX9GEG8`@R3~W{F&T-2Ewe z-og#oSJF02mZ2yuF^reVB8+2IzRZ`I970W%RBf84IjdZQC|m~&83(2_hl*vlmEAA( zbh;_hmpBEx>r`cVF2|Sspzf5qKec?$+Wtu=ok!7qb>R$Du-X>&c34PqzclF3ar2tB z7PP)J#2Z?CBksA@JZO4M)a)Y1P$>I3UXk&|M1 z+DH@gxJep>`m$e}hz}0$Sw=<^8kyfvPw{wn=)Za{B~n*5n*xpnVTdFvGx#!36o z(wKHDu<>}TrHtd@4%nb)ci8iKkn%D6_8>RsML&=Z!YiX;0!=UjglJ zsE)U0jsHOK`snhUxcKq7sMvuSQuO)X{E3chb8M{o0GT(}f_u)Xj^(^dir6s$+ zs4JIWV+qgAC*$V#O$Hx94^puW{fdS)SbJr{j{dgPVf;TVz^BiCuo&)P(%M}691OYw zs*6hi-jc6q$&fvw_}L;Arida_A`0z-6}^KMwG5+walv&zMt_?YHKyv0dCj3$;XkI{ zXiH$QKr{u-n?ih>gHm;zss_L3y5zJcm*%nB^zfL3Bv8m`lD(Sdr$D#F^DCxHYy+@QY{ z;hdCoQ)1BV;(B8LscYxfqq~h+0;CN zu8^(xS<~v8xMAIu)YdRLNasCL%$fHR77Up;c7Dr+pFQR2>1on9A18=)$gvNvVp2^j z8x7=+K18fozFgMI_(=tgG-r#yX#&G;W_ZbBCX9Z_dZFLaEqRI+$!A{3Ve{lwyJ=k; z+eu;W!$wv|brpCdNpxz0fKDS`5w{3ISKHMZag>h_&&G`RjW2NJklM>7$9`hhW9dX4 zhtOAr#>}`YJzkLm8>^RiekxP1251*w{5ekn0HqI)?|RwU%3eVKBDi$UvtE##rQd5N z=%7JPki{$`Ei5U46@80m00fJs@$m?pSA#*sy`4wpeLZ6A+-7|2oAxyNn%v`n!jGxW zv5O=4?TxWp)zT%a&~v}F=QeHM8|u-o+S7(MtSUMdliVdSim;VBKDX8W=<2O}y=7-L zg3K3%#@Nq0t^s_}ug^m#-A8oXt(sj|#tydT*AWU+M)AqE8u(^T`nOjGdL*Jqwd-r_ z`@(fx`Zb|&uG`}}`T`AsE>~zoVd_&qmPTu?m--G}I%FU;6pr6I?60?4A9UA2{?Gbb69%mjMnCCHR=5tj~- zm9Tabw9SW$tkt!d<%jMIX#1vI74DWDemrFI+*VpxkUgXysjVwFG~Q1UaJQNT7d2CF zp`;Hj&KR$f)QHXzgKTWzcq_}8;!2e0k6VW68e*`(X4r(T3VGP_+`d2)xN46FSw5H( z1l(%8p&42(0kz_5~4PH zcGw@&Vcw-4!(= zGs3Yp_bU0`F8s6NczWx}Ne@HYQRonasi67Jl+zxsIlwYawUW zYas{f;OW`cllW&t@l%M=m|ud__%A|&=~tKeOG}9sNykzfP23dps#;<3<2|6SM2$oz?9n=0*n$ z)rLu^F;2VI(8brC>7~-l2Jf303zEgGT2^*a8OsIV+IrH)89%5DD0^=(P!Z+|IXQ3Y zP%Ty)Wzi<2QILpFRn3);C|;fh7df}RO;Zc+GXfAm@iu*8D%??@5DHg=3O5x&ud8fR z@!3aFl*pejyQ^SvzF=>u0>%LcF>Om#Wz>VqFN=?WPfTVAP-@>|_gk9i51 zqwi7m9PxKv3GlsT2g=2jBjcV-@->Bhhu;MDwly~mV-NJyB&nN0K93y79gm;oAGShu zT)Rd*ckeOn4(hfmnF&mLO0+{6_^ig;owm>UTaA$M`Cajb6L40ZMA`8d?UCvAS~I4; z9qw6?+_lvIuuS>v&-LY+SfSF$gq%cO$EwzD@1yN@P>Ik$P2KTk@Rvu*Be{R4om4}v zqG6{tTnPsDIZ;ha%x8#Qc0XKMKdZEd3iAuUj}gwtY4;}I^=#JhDi+>m|L~n8FOogk z4$*|hYM^}H)Ot?(PcATUT*RdloVG{+riPnLNZA z>YMNLs={`Gb%Soe$^vS0F_nS#GctLkTL3f`Sp1Z>ele%zZ|%P!yW+ErTqTsu30Ok) z-o8@jRXt}$&$}CV7iZMz;okiVefHs)H!}@uv`<3ZPSHByZ5&8H`RC_ zUZ;m!Lo(h~e!;5B^|EX7-_qNXjTdY9O;`Rcyo8uvo^G|4?-wwuDg}pqx4qJ?Kj{X6 zw91PFo?d)nJKCy3RoFIIdEElEOa6NG!Bm7CqPwy930s(=U2FD+69!3PD%p}~tVK65 z%iKhrzmsT+B8?bzx*3pVsX#haWn#uQhv7-XR0YL5QL;$UX=QMWJbvpPR2SAs@HOMG zH-DyTesFIzo`mpILl*XCb$t|J7D~(n3`^IkEk2*mJ8xwllh;WK9|KwL7|54@BtoZg z)JBa=j%7-bO6}VUfc76L8y_MP@^N)e$uaQ8kDFtn9Vqkg*$N&E~xP$35lXx6d#d012GS>?8ReiI6 zR$`gF+&=X>IV(R(--rlCRbo)4MUU&RU-@YG)9_AA1!_MQ+p=yhx70LRS9?a|EipLd& zlv7>ZDS;2`Bl>pN#4e6rM|V~2I{emxV-j`6I1yJQ%SvP_;vTcR7W&Alm@XL9GI0bf zoRCO3SoZEG0tNhb@sv`>QZ!}V_|K3MRw=Mt;=9XnQA~uZwoW;SJnGhH`j-!HW9X)6 zd)Z0Ra&h2lyb3KLTxkDg)OZq_}w8GMk-+Rm*p=zs3^}DHDgQcxEpp~eDf#{pQ&6MLI0h`7JE|4T!qfk%ENSc>P&LDdVXg|g7gofpC*4t?uwP3 zKRj(Trmp4{D}1ew9rG5~W8PuR_5jI{Yl*^uaucsARHYB`X zVds~E0S$x8da%|>&a`WkD-NK5M%F27k z&7Fm%Ii$FaynuT+T^dyx{vc3to#X^B3+r!-gy-WeVp)?2-!5>@W+UL!uXf1RYA>0+ zAWDUF#k}dR6J}m8Ym-Kl!0&aevhjPcDwbNrGJ80*V!F3R%|GBk|K=Y7SlD|_N83ep z7IWs{aVU0I3OR5p*y-3G=Mp~v#{<)o)qVXXPMHS9Fb5l~C^MlkB_-Mj50Dldt=a4q zNZ0|gAHWmzYL0e&9~GAP@&f?CEt!2g>wH2e=(qe1m>J5M7N;wHp~0c6%Pqr%VQV(T z-bL9gm!iiu_~qRxCyh{{$_gzf$(@bk@w-C0HMp{@k?Y_BE7{U3%7eo z39HhAIDCrlTYZ&Kq)F2pO7!y~3r~AtcCZP9xNT)Hf`3;x_kdFNK9R=b9-CL-c9?a@ zx{w>KOTl)J_V@QcA>`-cMoz0+ zvsJo-x?yW>BuEw008!+RRce~y_mm`5odB#@$rq~s)nOvCMX;rkCeO7^{!I4_ciXtd zQEw48%CG4Rm*@ND`ZH0+iQC7jG;!I?%*=Aw`8f3hRLKfCZA7q=6R3yO)=z+#!#aoN zotbGzqk~Iz*V-=fdY}8xA^)6gLc0z*fHf6+?@P#1g`Vnt_XU)$%Sh%NM0t^dn33mS z(Ir_xCF;Q|CkhF+K6S9vq24#RK{1S9IT39)qEZ26P(w#&lLTXnxU>jTr=5CvnZrP| zQ5$h03W0Qi@ml*1jWXcMgHK3O1wTR2ay=h#Fyi|)w@WB9$1qXAlB_B9?X-O2ROwy6 zw5;U7Q{#(b${3N&>Wq!wgQM(z65>$^cdH`$)vYKFV}yU^2%4im+Q zbm6lJj+;V;B2B;sH-KhD+L{uOaf)e-+R>$S9N~4}A!oyIOMhrIivhrK9o%THEC@32u z?{ig?DQ(9q-e1i1ToO?AmmymEBu?*Rhm5Y86$B{$hw z6Tjd<@XXoI(Y#Y$J%$SL94_DKl<$P^ObUmP=f4TP-5D_96#$a{7od4EGBQF? z@Yzz1UWRt^mL0V$5VXB^G*ypkEL%9m9i`$*u1wo~iWX@uzI`B)uLR(HW2AuX1{}-0 z4>1zFQ@T(@;v!VU!Cv=JaIe(;q!mni;M}-cVIEYp7nBrhZIHwZO)HLHE2fuud46HU zS^uJ#nyh@3if6^>p{V*u&s=JCg{x9cTO>tmz1hZ`{b zt~%EI-%wn3K`d7(O7Lz+fc^bH!K`R$(lnX{M7uhK4!n26Vs;t&t%G^W)_SC)! zATRQl0GJT0NTZt6pd#wyBLpxR4(ic(_`-8Z(NN>^2R9vPL}S=V&_v_?Mnpapg@MS) z_=iOGHYcQoSa6Lc75J)TBZ6EhWy}#J^74md8;qQU$+gQkXnw^~?|&WKbmZ0xep>dn zD#Vh2i1m@-7RiH}ZD$cb(@QndMjXzv&u|#u$pRhgiFq0sT7Y=yxIOYQT_(|Q*focs zh&NCe_PD_+n@jhj>=Kr+B@$`6ZtUIxTvGUS9X3XxnXRpA^}ikPfu{6$uHcP6@aFu2vJ) z?DCFFBOQf;PF7D_-=MciX=wpSB=uZBJRN(vS47zBI}d(LRIS@b0Ad;qwk{!E*X~K! zl;4J8xiBowA4JjHF82b8GS@mXaxKVqaHf6a5yY0r*l8;L>;SO*rT;$&)EN;1gPvP# z18F^?wt`V*4kTR1uJe2i_9qA8R^}_AFdb3OjCUod)((!3JXR*LgI|?C0F3=r5VzLG zlZ%VKa_ig5T(RJL%>)0Hw0kCWqs5IRK#9Wfgb|kpQ+ZzqksSdgI6N zW>HB=Zh1KdpLMLd+t0xdQO-MN$HKXQL`G6Us3AeV5K!^#d4lsPk_(VUxn}7A^4HgD zLg%Ad=^`PyuO3L*;)dT+z0>AuPTe0~@hjEmyYI+f8(IeUpPO`TmE7yFtHSnP@_D_&?5HaZd}`&H$3k25W`kO%X;lHzF9X~kMU z4cmTac8n)^-AVLSubL7G&9;g;@eku{T6XJ{#p}m=N;#?di?n+4ri^GwGHJ){_G1Od zmB0_jIx_>?rfz)>^79LL(;1&cKI?nMTkyYvba|O#l1W^pWD^h+ZCXGF`n5w)bjkA& zOO!0P1;b;wFhZ6mxgNYJZAmf^$fdrlP)WheXY5*{#eZwhXI$pX*`CXacNNlT{O+77 zzqq@9{Ep8I+j*`>p>W4QR_x(_o<@|x`JX1* zITr+Ui-gQN@TM;by!yv+-yjXq^z5HZ4y1^uj}0_431v^J3K4%}FgRWo?-hqlBf2FU5|NbfAl79;=#c0!ex@f!vQ0^giz7IPlYadC zxyCGSR%M)oXm@b;=EN5{K?b+Ps4tu9r(SZ9z3_J9B|%tD*2j77BOW}+IC}ja3@n5@ z5S7itZoyxt!C+ywtU|f8YNw1snC!*P%AEcRChy0Ho_PO`<7NU(S_1Q%Dqv}(i*<>z zHUPsc_71@5UMQDDr#M9gpl?A}#oIf+L#i&TZ$Ax?M5UrE%6JCSbWOMGf+8*SUDcrp z?KMk%!tcb=x8`UWy|l;e%2g7F#g&v|RMY$4Aj>cG7eWjO%nAr0!euHr50lO6A$r;B zuZsRI?CXypB%SYH+kmyUJ0of9wMI4w&X2tG(L(6#EX6q+KwGbaEx@_fxZ(>nUOkLA z$na%Kk3{*LCLT8ZZgpoLM0d7Sv-xxR?2=^f_{q3vx}Omk`!PM=4A6{~e(TCl9`PDe z`!5SJYw&OPCsD=lLuai;gMNr_e`+tC>j=so&Gu9}MbK+CO9|>Z7QTcKc)yGu@E_RE zmM@`Xqr~=jd?;2c!L`hh5b5sCCSX81bly20OICq#O1dr;orMA+i$l^P5mijbkRmM_j5uMUR? z_hQXbB+5GQI{JL*#L7C(W^O3Erwo#a$RH3IuaD+GheGGE;at%$p}xCZO6&+DB{5dg z{kj_%uW~pLQ;hPbwT1`7EHFs;;5e~6^d(^+=&O(HcqIkd5W27&gDLh0kT?5OSi}4m z-E>TkZ|^12KZAd!Q<~<*8ht73|6Yxa#H?C*$N1snxABz(@r=nt7mMX}p^WE?p9=BK z3M#%9reoPDD!hKRL%&1rf2Vcg!{ao(h!<1M&oI{eh3`p{NMWI_o-6Y8%gR7?`?ArO zl@qXn`rO={Yz9A1j)|?3(wn}%z9nwRav20-ja&3Ktv*u$bQ*|I#Clwe)h1ctTHIna z$NC*3u;^U>F@)U9@jX-93DURGv_VVCyYsnG|A!M|?8eidH5v_Iq0Qiu#tyr;f5a-rGwqxC%I`wF(rY_~&b;kt$nnZZ61_5DEb-_8*G}Cv43V@CLFZ}}6 zGs*HGs@Z8TeW3bKo&OEhdt|IAPU)*VYjG_IAOVJb#IiC1E*c*2-+P72JQz4Vg$NTM z*Hmeo%-kv|RuXaoW8QD`Qu4A?0z5B2${BhrT?zB8GOyw0a`qs87ocEHE?h!Og|dCL z!z~g+@QKfaLRFPjR4CgG%4kr&c`fLHl#0)xhDxB)6x<53*I&^ORk^=G322(%T6|9X zBh}3=XK^{Na$bcP6c~h?+86X3KrRk?;nZ+JOZ{T*Eo7QnkgQkw5j46&*%K-R|Pri*Y3Nvy928M@E23cn%;jhTkTgP zuQK6sq`R=jtEc^vjg8PadGmQW8l1#phh+Pl zGW9aP1Q~VPkaljicq3dAUHeMre?fc7AZ(6`jJnHQmIfvL9)?dL=CXqePv^uhCI_D7 zcFBtDmLxL-yq*6v_IB~A#OL%fl!w9F{LM;-^ZVn{1yQ}`uHVN?J;0u@l$9(OY$l-_ zrnD7;;dUQ}^$|vl0d%cyE?@3WEPOno-_vc{ryh?`y1GACgXoc6 zHVv^BU-~N2P)uVr6nK5mqE=82Im@R>(|MO(;l}f!+#l+U{KP!6ZsmFvR`5lY5XByD{Fp+@49Kq zMh_aq=#jt2?)?vmiE*C;urCI&$2mrX-)TJ9(E~l}ec?^#qkOmfqBE5{efX|>#f7s~ zj$A6EgIh;@Hil0Rw~V&qr8$2h2W|nb6K03|PB6dg^suMTl}W4nL?r)754poi{qx2Z z`D60=@-s5N7KBEVGc(coDG33SzZ2lLYC5f;FDBjyjzwg4Lu>Snn~dpZ@V2Ie_!uuZ z#pTHROz_c7Cs4=}z4s+XciCPAYf20fU!N|(8cxrtkG7r+=SXyK8ITb52d^tyld((i znXi{S?6>wC9186H+HBiHpUMj7A3Xn^cFs%Cs`FmHTskU9C}tFr>Me8SH?JF>NJ2SDyhKN zq6)AT2;^rf8-ZkwKM)52*@PXv^yU=d8%BD<1EtiFXw$!O*nZNawF=(YTCQbHdUzlx8AZ0tsgP_pk{iSHh1j_^6 z6E71WZywj|QtkcduJZ|hdfGG2$#x++-J}cwWd3j*!oyvCS6#A=5{bVCD?UV5ag>o{ z*Y=u^TXoDxi|tQ3L!CXi%NtqPq0`lkL=g)pvLvBQKKw*AqyDC`FGU zsV^nCuA5==cICZFVbRgBd*ju;JVm$L(`0vmMRKJz+E(;^&^fCfji9rE%sY**{2&^I zd3`2Aa=@{-FT>C@=KMFcRmBa4X~Dn=^1o6l>?QPDrr7IFE@yuR@yM~45drO`UaOU^ zRSumZcTimp9ZDF{>(`8Us5E$rojG)}sjLVfP!YF#KuQV`aHc5*fQSn4QK!X%M#-#h zsY?p%UHtIzV@yUyP)^b8p>vu%b*M967$irt40^lAjLwF&s8x3J$Qx9?aefa-+av{b z0rIw|w~v6pu!W`NOIQ`P!m4u%F!9OF%L_0bXxu&2&=e^%s|;UZ0#+j7+`5&vW)f2Xe|Zp!C{z5~;^d z04HFwx*=8iFJ;ksrsM^bknNk385tB{>8ETCC#tBZ07794jmPcxBExzmEE%sTwMZffk3A#sq^e*OxF@P`X8HyBX6KNVx{FyB!6BW_CZ!&-e1a0HIq&7E=Eh zE5v`vFuX*W#DDSXh&PtVHkAwb&VSPdssN;#$Q@pH>~IH1$H9?7Kwn7UV5K7ySPAJI zO`$Y@pJNzLB7fvF{Ru&Yr-(BBUNp|yCv}8Ef8+~L-wC+ARZz1)^b734W+P9VG+x8^1 zeM$@m2x86~A@a61F7FurG2r>anO8-m=n51k1)BpxPb><8w_l-~fJ!)*Xb{@&xS*Eg z_H38(uck0|TzNQOZ@v*Tqbkj|sONOH%-HD1SWx2i!1|rf;#og&6>0f@q!)_$k8Et% ziNk?o+xv>HD24NnVNzwt8or9Z=2c!!Z*@b5YEh&q2ekGp()oe~ZD+}I{{A_>V3fB|t<-puz69y@=B6R~i z-b>fY+?bzvfz!&$_sqX3KZ4BPqOMSrm?pAAOcL&b1nIuzj%q zPs_Ph-r1QmmD4&0_-hGvm`53fUsU}?q}OGE!RaAZInOMM9uyL9j;mS#QdE0xOuKtm zD{$!L_(gKHd_}JZG6Vd=mYg!%9;`am;XhTS6%CO53a>TYbk>4VyfTxD0Dv`4;qI@8 zomHPWvu^^h{B)e>OoX$RMh@m`az}M1o1CJ`9y#=VE_9vwMmH0v^|nswk+NRAEbvZT z&`%q@9lU1VN~FJC%{cu4tuP_H0&U@bTHA`jxTt6qK3y4&n1%clOy&`Kq;K%dC&&CI z`=`Z4cjzWhPWPeZKZFd{`xKMm1n@PM7-|Z{;E=Wp0>sa0M4NpCcd=PQs~+uymKt4H z@wQD`@3yf}4lCmc!uO1~c_Q19avn_M2@TFiH3V)O-**_jdXBly`jz;u=g9DLzL}b; zXlM}J&22g;sj7ZB2O2v8JGgOxt}#i<_Gom zm?Yel3s;PQuZuYzw_Vq}r2}4e6*it<7yua=NhE?M>_JbkIMVJuuZorex6fDemV?Gq zPxW2STih485a5ZSg}v~t)2hxM2qGTgwcxo*!lW#@ow(M&Q5rtT|okGJayXQHOkHjZ(nNvV@IcG>g_ub{l z(Vj48$n&qS$x|14eV-@l8n0F91{OR|EZ#s>(rXTjR1tj+w_ES(J}u_|pSTwAIus8Q zB=Xy@KzrXgVOljG5d?U7vf5|O$FZ(GXxikP>?{r<<1k;AKH?UTdl$M6Cel479}u5G3t+fBwJ!1-4!`5m}M5Ny|#m+P5#C zEwuZze^_iK-H=^?-M{GX@K8Yh`RaA2kMNNH`^RC~mm3bRlv`ad;C`n2u2r5B2cE>y zvL2sf^jg5qv7pBboZd$PN^%@LJc-2yr(I?9Ilyw(YbpL;|3pC6rS{%>n7`QCM3#j) zB+~-wimK!vy&r~EXXr}zkJodPUN*vA0?L@C3-#8KM>Fh^sQ_B#vp*uZrwDMP0PPNM z0h@*vxqTo*7!`VckSB`y&nWelCXTo~GoVRG#rBiaGc?T1C}^c$N@+H$Dk35W{yh(h z7w$UWo88X8l{c=V`~xeIWjlFaSzY}TkeVXbaU9{u9!Mz&g+S1V*k6M{EtbE4Gn}_? zS+d3uovF}YkCTc>LA60PYhyv(Y?Z`+j zkYy3MZ7}D&DvHs6orGN_%Q*KA-jY5rIBlHA+MAD3Dzd>sbtg@DM!7mBAn;s-!lF1~ z5J;vHgNgvG3WeCr@aX8#5k<(ii*Yzu@XGN3b3_Oh2k^qTEJgLKbsAOu?KEPLtd3`k zmd)4i3Jm%r9ItO@!t8oq;Sl^-iXLd^3GgdbQ>`R|wVrDs(_1~d8c68h^=H*cUY57< zH#eu8Gx3FYlN9IRid~nbM3pHd|01A|q*hCD+1h zWMBKej=uLYINSa4a<89a&%n_xH@IOK(%JW$g(5-M7RgT;&&!|Zn>?BeGy-*>DSdNC zTkccJ)*KpD+)XV4g+y}Q| zimgZSH71uW7OL#Pu3KPsboi>|F8`b|wx8*(TzYIBigc(2y}nQi37Jnvr0;KAJM_pW()3_h) z+wY`_bxr_f0Dyak7x}4(f@QvP7r2g)&$k}_K!hE(jiCy4`BHPMG2meSLWa{Ai zDUH#2Ai4ZA^7n#sQily`ud!GApMpT7SuU&Bw#$o|7nJvn8`qx%kGVoRMruzd$*<0? zd6{)KbuNDio^`lmC~(U(ZAD^75XVX^9U0?*dVailsd+Ne6(N6Cbr(O@=+P3-*Up!* z;D|2h<|W|B)%ja<<2Gd<)ka(83u)!eCb-pTc>NYBnC-LWsrg%xkVd1FfTy-;^w^cQ zI^>pbYgfZ#d&|Da6k<$v$8G8AZdhzK=Fe0>I7v(JBcA}jlVTiUw02mK1LZk?tZO~g zNBP9WWP8feKW_iVF?;)t?tQyi^*qb__0##V`i65-epfrO$|;@rG^{o`{-BgIu37uC z+iOtB^xh;K;GdjmO4`I3-NihLUA;No{cT5`FFvl*`N49S^YoQ>dhX5Sz1{qt_kM7* z`#X|cy3ip<2+$|@mf3_2K~7D5%Trw=SNDa^p<`;qxk0nLHG@4dVn{P-@x37os4{h- zGZi%!=g95udipjzo)L*IM;pt}AI|6NXp@4Z%WN`GzRSgGkvd`jtWj=a9vNQ1wc8q( zr7{5|FaxzjLdgD@ffz9vZv#$6@9h>gbHD%En<`cH;EGoK+rrMdrj2Bc&ci~#j6458 zK+xAL(xf_!HbOn8*OkzjAVAzwDqv^XyZ6$yO*r~ir?@JO95*DqNeT9t&K|UG^nY>o z)=^b=&;KY5(jna--Q6J|h;$r4Iz$>ox;sQd1*BWz97?)dK)OL1qy(h9@8)?vpYQ$t z*8S(+dzNddi^coA_ujK-UNiHW8QU#M@>En$Ebe(DiX)+lUn$hy^_wKK1tJ z-vIJ?2tW!p^?-p)76${8aQ)^fnNFu`vM|lethP1TAk;Xb5Qa`4}t@3 zPYyFW5v0T1<|^&2WLuC;GP4R}5o3+9lt0a^BSW)RIsI5L;i2c%o0Q#P0oye*AW#y-EC>E+8}9a%^Y7K>Z3|hSY66%HiD05 z#97Py`~@g9Zz6@@#25wzmL>mBPU~B%%9V;|0CoM))6mfHz@hyH6}nk!7;!s#DW|*5 z0w0Z=yQM#|vSn!ULT=#X9Hpe875)9L*fXRD4vYt(Qsn{LtL6I7N%DpYX)aTml{|B) z62Sm259nifKR5k7sTT?bNaV#QTVMw25~|OMec+_poptYtD)-rxA$M~-*)y+ z>jQgyT*oX&vHevJhkPUF;_4(joCPGKon66!Nki@r*Va(5%=3i>J zyX3~kGk#-%W87z@c9VX1gJqB=Pu2%xEeiZn^f@P3V{1*$-h*ZO|sdy0EL>05$zF{@o~yB>pq zYy|HT_|vq8DIC^e%KOx}$L15+f}_XL$gzihL*6)v-LadfSq$!=36bMNrW%{PAM^y#rX;y>lSMG;-O*wKzq ztAl}JnD)Tb)PbcUSiUx@oh`y^!LU3XWbUIKMpJbo3;d->JqV$;>K!LAsuPAnHfUVs z3mt659!LEFbEZ3|N(%<)9lIS@JSE!4Xe$vE4YasKo~xzYnF8T@5|~-m>}gU5l=_ z)5n_u?wU!4UB?cq@GzNWb}>QN>k|#q5bOeV?tGlt@jhL&v5=yu&aSYvhShCCxWVgw zG^ix#Y%>wPcF*!JhL_OxtSLA*Ugrf!OBr$6^ySN#b8!M; zDm*ch@`zGFn>%X%*{k7GIFc$^!#xye3z~loNriNeA@CV_nXX1p59AaW(+K{>F z@72&i?O`)oIjbFKc$gW<nBxLV~JMWKM|f;^4eXSMJ<>8E{#D+Qln~D$qMMR>ri?2&ABU))c3T9 z$Jl#BR@I+%D+^EWoBplu?bvhoT_Q#!;pkor&C$SS43v`$jwY`qw`j{d-UgS-L=!(f zqqgT^L2K{p?M|@$TXt!rxS*TcE>%BO zjRn{vYnL2BOudj*TbIP*&jVz22(d)4^GRs|@o&*}wv&er?lt>p8t?_)?&@TMOt$Yb zIy*Zf+h28Rjm^&K8?nMeap|Z4_=Z3rnDnEuGrN56o>kwnF-HX#4#&Z2)f=I6!c8m6 z_lBmLe&Z24-#?R7M1|$V_a2^mQVS5Vv7{oH3~h91k(-WsSsgzNpF20BXlnAS-g`*F ziC9D&%`sq$hbQv;=zUz8WZzFs8uk!p{Gg~)(mq(+*^`;j!|~t(zbvj1G4ht4<2hh2 z%Z;4=P$71`zy%9@TxH?sVKlvv4y)eaDd}G|b36!<#`$yL{3BV%g`x5S1tcU|(bAt@ zPoHHKy6H05UZxkdZo6E%>!>g{zi%*nN=T^4%wS$tI+fqy^1Y~t`L`8t5t#tI7Ep`*7H0Ft_VWcPqnzwkcKRL+!}_@;Qvp4JU)<_3f=RZX*|4wn?Uhy* zhT+f(OwFnHge}s&gEr6$!;{;p+r{be8L5G|M#1x&*vHFWVQ7M^B_XD_M$!kgzMN+x zh*c)X%BHu12|M$KMyzH~+}y%#XZW4jHO9lbQkKBJ*5j^HV=nrs;fxv8o#r5cjwP=6 zCQem4+WBc23^O1&5@4E7Gw@XY<1D$p^lT@iDsz9PhZPPRLWXth79c?AoeWK52ew^) z*YZw*w4Hu|`8vrSwq_zPvR#V6+o_@sXSbS_gXLM;9dj#5kdI%#W>p>fs2>oUXq&=* z_Xc@!VpQ)GWtGE=ftye!ofCj%?-87~5s5{KNWpiQJ0o?dZWqk|IZkkOc?@sPjM$N(I`}nJ_*` zw(!ue#mFGMBksgizf#noUrB|zI5P-{w?ZPROH)SpNm5^#vW5z0y!=1bK>Q?J*8yF7 zx4h8XT@Fhtt@ss|aj(+HmR#klM#vnIZZY<1%_!_ztPorQZJ(DV#&wpk9$|tx=m&VkO!H> zA{yGAZB~+0LBizV&;l7WJXQP-l%=~jICbovVmp;m%RUUcM#3c@6~K@Wi4ic7^wGE0 z@7;EN4|-R4j7R=QK60&u35!t5@{nPxiBNDC$c9qp3_mV=!d~rJ3)sH%dtjG(8#`OZ zlPtn`pI(+lETBVcYi4Hl#~sApsHqL%U9u2WGniDuihu_`+T0@X+SXS7k2_?l!jVGp z)`o>23nl-b4Y9z_4u_uX-r65UsBi}S-N0#Zy~V|^E_2uenv>|zG zc}{w}qkyfT9|ux#So*+w(D=lNH*=@OQvC9Q{+TLicRWG-y6F>I@27|J&azxmTIEev$BF8dk zXX6^z4MgZ>_s!q?5$2rGh|9SxNab6!$uVKzC}#{u%MUP!OXNdW_gS zoo7(s^E_OMY_p`5yVxO2SpcIEl6frTBWj&5Jq60k7dyTZJFS(*xu3LW>A-VyvxVLA zgm^lf3BoP0FLmRTNl?GAu`x!9r=+&uh-;!8WToi5imi?7^T`b_?e+Ucd673U9Ac?` zGHl0C^8IWrh}3U;-fcnzTc0JP$n^&Mw;CbMoibFCzd9N3>I0k-oL(gFC~Y)aj^PCmQFm?_-$8G z(7`T}j4Bi1akAK$1zGrGs;|!tH8>@l))wH<3a;kjjJ&v($w|!g;nVBgo**0Hx|`(C zLVii6;5VwE*PL}5h|wcZqHAomUE@hzZ^{{aui}6ta{P?^=~h(+>eZ?cqPjlRD9?rv4dE2bg4lgfd908Qe>5$zfJ%?K( zuxj(^d?{Bw@jcLUFuAby3a*Jt<|$sD;~qD=$hoiW{OR+4(HsVndp|yR*L|Hkef5}# zqnuzv(Ej5YnY#1cd0(15EKa-=40rJS&2-YRr~B}Gm%v5ucATy?U{7x8bzMZWYe>p+ zQ-s^@v_K0_UaBRR<7yv1LD6~yh9sTa8!9K`&9x4xdSUlr=`vU9-*HVUj`fmpf4^|O zuH1g+vqQtfml1&x;c`a9wjVQJzjKiIOpT&@-bAg-cCx}|&ymWf?TdqCSUT;U*KN4r zuo|TOuwreZMf@%cU9yZv@s-+IW_f!Z}2weT82 zsz2BUgm!*fz4~%;#x@^20{5ZLy`-$E7SKTMU%VGxD#?x2qoSjV4E4TDLm0Es7cjBK zLDy_*$_F!YrOIR`O-+d=Qv(Nq)p>Nw(KU3%^*q?aVMudw$nL9hM`bWypyEb z-ffD^+Q|al$1aJHF+g%&i4fg8l<`nF!klyw~WKFXkKW7Hug) zcvF%}Pwop9F2}Om?zs5?BiAnk`m82mBYiJb3TxL%cHJqgd{hw9rZZQPQ-2T$#cf`H|Deib ztUq*P&@Ymi*u6J{ZT@Nd?W$C*mX{mwd_Q^U|w3Yqx$%9P!82;_?#%AIxqp z->D&IQ5}pVFZRyb*bb7eJ>zkYkVYHB5Wz38XBT;ObRObMFNI_EMFpnzZ`+eUVahL_ zRA<@*+ot}}44QL5ILSu|2B{<6KYEW*09~|Uhn=>*xRi-nW@8quQU9{ltf_Oi5P+78 zsEbN7^Q!Z5!;1Dmc6xME#B5c(85n#z*+~$IDZ(cdWs(E7m8@#zsVQjC$RwU92$D-< ze%_EkQIHD59tycWolvXty?SqJYx}F#f&608!^CQK=Y7vA8O89|kuu+oQr$%bk@nuQBG( zKMfR5boLt@*)KS*BdwNh(=p^v<9Gh6oM{OT@h-C!x3tMk;1J(nPYUCqY1&LK)d@Ve zJ#=2(MXsBLl$7huOK`#56z>}M?6=7c%f)0Sfq$nCnu{OuGwVOHozRSc>nBHHQu788 zpcret3obD4~Fbkep9dQhl!i|j$yjAGHMs9O+v(Z){NI2GR3jp~9ZOQ>( z#UJEIPC!#Tolu>y1l=?_`D~u_6Iyuh zz~}ftf>?<6n8r`%Icrvb70R)=UCr2|ai$Gz?PSab?s$#bX^F>x!Mt01_~CIsWpkxB zae2uS!_;Hm4q(Vr`KVwMjUql3_Q?@H{Qziu|3v)+_o=)oB{)QWLlJvZ=z1uGRs<6bpZ6>2 z0w@%th6e*x`o9Qf?4do%Mlxgw13e; zE5-jg9ao8XUvQiK+R7g!?7u~Cf4JqPBqsj+grw(I6s)V865Y4kd#b3|e3-@RU*$@C zQ+ZdSzt#Qn)mG!!hoTylTS-Btq`111EeMsQmi>Z+C}AJCgrzyG=s3i&Tj7PeaNN6W z^xv)lX$kCHr148#h0!|0OkkNj99D9BLd>%X;@@cW}zP59AVr{)(0 zh-BKPL>Xt-HE=lTMii;?A=Ztzj+RSvt>iu@h7W>s034gWIo0|V9vmDEYKdziT;bN$ z-kL|}ig;;i)la6kSly^>u|-mRXk^3+kdE*!{-NV6K2lG>fIM$7h862^9t<2H5)Ecb zkQdj4sKuCDjCY6B+h%>No7pQY!em?;{caQ!=EBv#n$~o2JlA{kOPnTz?bz0{fqf1I z60RZBGn|f*HO2BpfKE;LK*$;6JMHGYAi3jdYUh_&NUM(H;e zJ(dNy+HQ~csTAtGz?eJ|Zc{kNx->w#s&ZTu)hX5QKHZ)W@jhj4XlMZAgY%ftn>-G{ zs5rnX=mW5x8#4q9H}M%dXdi`&L-QDBU)t^nB$jEtw)pbJ9*a#td&7ts#K2pQrMc4 zFe(VzZ-vh+VmAD>zvt&@@c4Eh6Pe8N|C4kPxddIMfIbKAV_**;oPp*E{$YS@nm@D<=1TBFn> z^ONZygh%;M(`Jzh7(cPhj~<(>pbTN> zU<0R?#0YBtWGr&Q(K;s+fbw6es91t|p`I)B)3CN^w}y83nmi5RlR_ zQfkn|775B0{(4eAN4!LcuAx+;41&_?`A6C#v5^gq9E+pu|D#(TSnIQG%E3(I? zZa}YRgxkFD8XkeOv$;_J^b~fdz);+n zFx_kblGL6NJ{FtG^|C|-6{P5unv!JiqDy84he9Q?4#q_^*ff2V1YkfB`50@TAtusN zr;}>9kqxULn-rDWt=(iFbd2uR?C4MHPs{JyIh?{~&c{!BerMbm{@GgbEs`!u&E zHb8F*Q4&qX*2{x~D4u^#Nu&+letl5aV zO9<_?f>+IbHeVpmQRD*R-j{gM;M2eC%yIY0(>mXl*4tQI#qOxykeFYoG;Ox=2*y< z`U01Od#I{vLjOt!LfN%3r{aG8U4FpZz>{oXrMkfa;A*<_|J7I;xPDKI#A`wcyOCwJ zArfu|r|eKD^o^C(nyYA#^r0365_WD(gM{U@+tkDJMIiQbOz@;l=1-a_A&Kv*R;bVn z(tkGbpE8o4{o|W5lN2t(Cd^~=mqdS%bG+0B5-Q(zP0)b2(KN&KTiMB#BSbRFu5e(< zz>-msVlBVJJX5W#ic)|5B#!_h#UtVfRH!_>trLbCVD^&N>~gTO=GNEOPt98o@BqFn zo&i3P%zy6Eqt(RL96i&56h1E?t&hy4)mtT^N)==x`4%=3Lx%aPYfBz$2|J5ipk7rC zL!+x$HO~f$Uz2kPv<~4eTPancakhmY!|~c;c#emifc?hf5*My@9*drGuGB4N`#nxJ z)c`#e0nYKF!k8cvxETm?p@pSbs`J-E%)iwRNouz)1uz%Fa2J&jCYg79?~5+x`Mnzd z`*vuwxnpjCuq``P(6ORD(?NZgM}&t8YDU1Y=$zf!s22jZK&52}3O%y+(2nPFi%|Pld(!oPgeVk=1~w4YGl0)8HM`1MaUf{!<MW?{o`A_nmwV_Jl31=qBkOmYU(Ta(-yR5c{J~E(KPX2DhlAS#CQpY&`d03tAr52I{jqm9l8GPbv zL#spkc&46PlBjaE$9vIN>OS6{sTmnV>wWPCpc8kgmrv_vYz~-2bgBwspkDW-SP4}2 zjpndhbwZ5gYp#>Bw9!6#o}&c9laAKs%6%gpc)bUFz9wax0n`TVm6gvI&Ib=t1p243 z@`?gl4MUQ7MOw4C0A=ntT>4)eIg!Z9;j<>~fg5`+t(78PVnj2Zg@iqMpc zS57LZKmS|y^>zjeMW5tF<(lXAaEIg}c}3lSDp-!0Jo(o%ZR?>SEZ$++i`-pns4$>4 zEotID;^F2F(U4cqZYx~$*bsS|E8u{5;cC6j;Kec z5-S2DfBI)Eno1&-$D#+=_GCva$Lb5BoKn3|{YqNbWe{rD5mT*c2Q`g-_7_lFiGO*K zD^0Gdh0!b|xwVPlGM8q6Ly(SYK`Neah`7OPQnq9OM?LE(UtEHxJyK*X(_dbGSutf@sWlo_kF0qKuvJur% zF$beA$fg^E2kaI%L#1A=jei;*Id^h#E`LUIg49Jhs>qqv)OAD}S0F{eU2nZQe64yFOHK#EU23A~{oP&+AHec@#*R-b;QfDc@ zfkqqM>)1366hto2xNs?Zk`?lM-;)7WYmT?num-31chIV~DH%i+3agLzSW=5c6Ky9z z(9eRIuuvx5n7!)l&^4gnb~XA?P*#E(!&;|h?DiC^%-J#r-)c*0-So6RKxG`sk&W;) zUGjL{QjwlD(zjJ!-rD)?1M$iXR;%-KYS0F1z@ct&`m|^8)wIL|ZriOLp2^?KFAlp= zN0>M0q~rm8Bh%BLE4N=zd7nB>X1HK8&9HAiWZn>B++R@JpQd*-Y`uxM=Mk>oA*J$b z39q>Fdd9|>Ii4u~@I%e(w644=hc%>Xc(~gJ0!JM&^ANKve$VHB)LS?Eo{n&9Rp@f+ zAgN;i<0_MuS4aLBAqsKdOmfkeRGNJs1` zjt5lS@uzQtENiyDNbw^hb7PnPp26Yh67r{OP()9rl6)ATzqQ?FvR}Mm5K|%$ZZZ|t z_aeA~i-u9MKim?EyWqaZD*wJxVRGEBprAe@_Uftxu8jogdT%IU5yN!kc1J66*_1KdpPrr>0v}->z_X zTq%cexWF%*L5etPPKKb{Y7f`FC6Jj)#YItwZM=C=Pq4dKdpzz9Cbtew5_3* zLiX(P`O2j8I|GX7GnC<~3S-?rm!z`2IbZG3BwB^~hle-&*~;GxCiCRnL`6k;Ze@7L zj948uxHT98%6zl2Q{gR#`}%=8e>v15Ira1Nw@BvMXO2P06rAz z`XRrYt+d>8+`6eUK(Bwezxg)?OwzUYyBx=;E0@@0r300EedmM7V4DNk#exgY$<~OI znVowjSAFu)9pxLfYf+&kPfCj$*d*0l`xh~*lgWLah2!>%hS778gOZ7Q(`mJ<4T~A` zs{up*s!b9`bq`O(0YQpfB5v&Fu8`$hfe4KK)mf_phJa0L#Q=n1sQ$`WFPy^&Bu1HGTR3i)RKSAsZ$o}X0cTf5@bmb%JPdv% zBN$|TwNxLM7I3LnUA{DQH=}B9zl4|haKhS;1sBpq&0)EkbHDy}I*T`|C-8)GqjRDC z;Ifo$nC?uP@1|&esMy1Jh%bWiI0RYEdCQX+qwJoxJW)T*x6Ihmzf)N#xyAtmh*f9_7u+%G6X;`8)jA>yKE2NCdKp4?<1B0~?*7GQ!Z1qLEUKoq^nW zK?>QS8*1AP=-%YDk!S3eaDXK<*h^6C-U?^gAjUGZIJ+*|kdOG2Ljuv-duby3eSSLl z13aKs_10`gCp}_SLU+8|rvTMW8j!?~T&?wCF|#6T3s2IgMus=}nAG2m;c8=^BYZvC z-yB1AH1(xxpA|n>;@(~GeZ6C`o|1UGdcu2~6duqtI8s&@&^u3j7nsY|vx0;|Xxw}9 zP!*oxacVho63}_v5^%g`H`0wAO^KQvFD_2$GepA4ULPqLm9;nWz~vNuh1b1&g+9v~ zJ#_OV?Re|BPR(h(0s{`^urz{tE0*mh524_MvCR8atz-_w?Zb5r`@|0TYQCX zo>EE#@!ib*^4>&3XM9t2awV3!(5r_3FwEDjd-U;4=)Fcb!WQOwYaA2z!_ea3<@3`m z)}v$U;|Z}c8eL?*Eo_~KWgg*;sN9T@K1#^q-5hbE5a_FDr~q6vRdjKqpz#ZXuo3XK5E6F93%Wn3mXr|JK< z<#l_bBo2r-pHtKyWEbJ1OzsKQS}sL~KM;TU4O_ij(Wh&remi}*k?HXFeh+ebvj=UW z?8?lZ_K0jDca>k}jzmf|n|^0{;9iXvvQ5rTqaqs8j5pO>bwIL-4Cjt=u7c6hrg3ff z<80YG^6FsEw4f@~LznQ~P#0nv=W9oIY6X$aU$Wf~RtNWMbBzZ+M{UEOkz{T^eX>XF zK_HFH7>vbIH0$JDv zs;J~$SN6I^5Sl?QhFLkO`1gl9g#``56>86B#3iltxX9K$?eOYLv`?QxpLt49<4CZ7 zqu+jaN%N-V)W0pmO;4BqE?0%Qr_tcmyM`Mw`NXNQ1Fef|)t_8Fux7JUtQh)JO+nuP ztAVgFVL#LYie#QA0j8}Xa{u`}!3!*M$ow&CsQoJI=hv(cD8hZX9C8vivqeL*NHT=6 zN<74nKZK^fJ&`L+A)vmgr54^^qDr=DaD#JVxXDOYBWEGFDyH1FE-r%X+c|m*MmTim z;)`{p?H@_Ri3)l%DYhBcGpIk6ZMKcnkNpW2n}+7e%`~^vB5P{LpOd6LY$~4@v8~+B zf?ZUnXx!fTrkk;j@z&ZSOv-g>!M$rRyu96#ihHbH&?pZ$9aE?PEQ|Vmm;EF|Uhjv! zxQc^I)!WlB*=~2I477r=0?rYe@7vsSr60T%8bdKSSK1ssX}f}E zxf&9_-+XF9;mM`Zb|XFfy-A3dAKUqd!ycJ!=_E(Z{CCBgHHQx|*Pbt&33FQE+DUVq zMySjQS@QKY&$=#L9vm|P$$nc~MY0~Z9nhy}YUFMgX14j3~F_Dpxo97EI zBdZNtnTWWy8^xMWk$o=qy8*(OsIddPo}$z_7*J;!3R6!U^%|BQV!wuC$}od%dlu!o z9=8k8>V~mWWK~XEBpsOR39tr!$A!Sk!nS{X{)Xz-hprLffGFH>!(5v=8#Kq4R8E<8ElKy4aEOsMy+Wu$s?@Z&vh#!m88) za7G+%9mMNc#-zj%qUd5(%vx<$)9~={#-ffpaQt!Ms&OH}S-h|~SZXoLVFf=3L;C{9 zAbck@4o4HI9!Q4NUZzf}L|uTe{p8(X1od;%k$W$L>qZ1bVVhaBx<2>@7`7Jbjwb#j z1DhN&T=^cEp~S&Nt9w(K&6YzKHs%2ZT9Y5$rrlYwHfuXKjVA$y#!v)x(7`SjVscX= z7cP1ORs^-;pNetXN=qkRaHxrcI&BH{pSQUocf>|UW-|&XB|DZnO_W;xQm-U=`U19(E=QZqGubY>0 zLwR`Q)SeVsJDzA$=dYSCl-guEHpTEb`uUu$9d7R~$PPED7sIA>$XS;!7;e}1{EMgz0})OxZ+4~~dK z4M+SCj>>ZdesA~YppE)sIUs=S0$gO~swcQK%4qG+WKLA?;27b}UIo^RF9qx4fyQRT zSyFN5=kA{3nG6_l%Dr*zuJ#222Z{so;sQofXmDliaOYn06$2g`P4+wOb-2H(q_%I& zeS1hex(jlqxOWAcRQJ&{@B;a2D9vUdsw0Yt9{tW?H5EIA-eYX1xe)tqgHD4#&S%do z-QVu7M%0|xnxYSeF2K>~PCbXgR4yyNewoIHL(#v8ewF8*Ah zkw-yY-QF2j-BQbtxxwICS%7M7FG2KC6D z#pSJ0Nygq!R8&;zy-pZGsXoX;(4ZlJ(V(;gyrQC_-$6y(&&ucsDsSth8{OMHlJgYx zH+%{<6&TW~?LX@SgXyaF+wgh4{V$*V6}_fS_iZFi+#!4gXR-7oIV$QC`OyP519$jm zD8*C4^+D}~{&(6#m4qR$xuF5jTpBciB*H{cMBjSG7iQdC8VYlGK>X`@)-;nS! zD)fM-C)2l~?&)o0U!=sXW#&=;=nJ?<``Ze4jDBLK{I)L3x;H!$9|SIH(C+~a0`D;g zwbpoN?kFplpv={JNw?pyMa3M2@2**_KGm;vr-+MGT~lLrbG~OYe*jo&)e?f>8XG2T z$9=|7B>N$|t*fn#1ZP&Itpzr`dosu=%&5R=8-vE4lNByGmQwNBP#ex!Hy1(ruw&H0 zJ>yr{B9jLqoa$du__|#(!-*UgT-%eIw|i`JGX+v=ei8g@6Y^*+A0AY9io>Q%$>A0l z74-f%c-dQZ#??H{9TIb}u~A&38hf7|etabA`bQo8JUo)f;&t_*%8x&Pm>)-f|Hd%6 zL{QC=j1jP#2E&%|0J!?|=TH0O&H$y zcIghii}J&r20`D4J__;MJo!Q0BGG~7INDCbr+57+76Oa=avIr@BFyZsp0`~-ZvB^n z`g#(u&*lqtv~>M);7SD&CFA4aY1osbb4o$6RUzT~eBZ@uT{^zDUJp#|eWA?dtj%!h zYQi#G-R@gts@a{wof7v*7&_3m%?j5+QXq=!=*K7g+9pR$Ntf^HV_*0Z!j7=-P>u#lpz*-oT_+sUho! z(1WQM`o!@A7AYce+^Tgk-i6=A{NW5Q_((?^VWz3@HgOS6!2&!JD+R_iANdh%;2}>u;t@jZZ z*$He3KuJA*tY1V45}$=y7GUi=nkf8Io|K-rPZ*Mmf#gjVWk^-*{wUe~4{!)~K%Aq{ zhQKy+c32Y86QX`lca8cn{T8_mgX}N?N z5;dSH|NU5grfV`16DcmPnJ93Wua2*36kTjed0Mch@X6=WY;QOIYmAwTU=q7rOiqhq z-ejb_$kXgv^ipd=gRO=0p*h{^^A_(N%qeYjNfPD$yFbN#YWjkm4)5X6hF-WK%PglE zLQtVFL6*2AOfU@I%!NgQ3J04~w3?mmK7DHH``jL;#)n8Eo9?C3XYAs-_`L?e%WO2sweiH_bGpmjY54y|6ud) zMXVmuKatYO)fsP|plhNWP9=lO*?L5=mENi}bo%J>aGoG-KHfqtCzr4xFE9V@=y!LR z&@;Mz)81H0r3+46plEmtbfOWCP;-v})KcEQD-5|hq(2ESDr*na$w-CaLhK1?h5Dw+A8ylkD&KiqYa5PLNzKdAa+oRtT_ihDL%8q4 zSXOU%D8+)Ih;DGa<>*t}uDLlmX4B0R8x)SvQXea$Vcf(>X3q4WS8@ro#y)!j>+9>! zd^7)*T;8O@Vm8;Ezsj=~?7cf$5+|z)H11i`t^WP`)Pez8rLT}>Iu_T1oEXoJuu4%P zOLOWVU7MLvrDjuwtT_siHsQA47*Zmx`+jWYkTs52OX1Y@1rdD3f|HTLaFZ-Ggd}~L ztv=D%%76h3vG)3Wm4%xiVc2c)eM+3NT!Jm8`iDqfIX^!?&0&InWLsnN#MLe5E{s@{ z>>H=mX4gMvy^^0-?rwZ2tAmgP4j27E6EC-Mp-jZ!LLT26DUz%AL8oMrnZx$MJiqo> zCE?yGXE+!6tv(wfA7O_Q?fa$es3&R`XbKqu0%j+PA0nAWQHtc`NIMTMx(+Uw{<{s8 z3ar7}2czoa`)u(kvD7Jqxv;4?IFMy6?p0iW?oo)S8} z2fj}*TLS-*h9W8A8V4sZ&S7qTp16MM7}w4d<}jkuDkpbh9{B3Nj%5NZK9*(+8?!j1 z8$Wl)%9)W~F2){*Jg$3KRwZA%?s!T!rvR4d^k#kuylNsrCMO+c&D`FvY6pWy%V+In z`oA7!CT?VO=<41>`K|2Rj#f*UjP@P7DnQCX5+8Anz^ZFb92^`xHx$Z$5JqvjQ`y2~ zC*LfzZC~O=E*8RrYhlp`Q_l-49PnF$vSv=Vd@gYpV*@&5vmGw+UnvAo57Dc!v6?24 zh)7Lr8EDTJz%R;HEq(XY8#%JHqHU`2msip2v3`#a#p=56J<)$GHww+|k>=v#4fXu5 zhlF%bOwWk%S0ni(G!UU{(91S^%1-_SVhwal8Sd0&HP1e-0J;7Z5Y@rgVKArs^p}L+ zZM!21711PHLPFT?y+R_H$sPsdKcCk$UuoR(YY(SB5`o4<&3;QM4aq?TcRY3RZlW0) z#cF52u{5ws!;|YEmM_>$7LNk@MF~U?&fToH2ufv)wpVRFFJ`KrK|S8#ZmDK;UTGCx zHb0kp`a;j;et1|lIyTna)Re~PM)oORL>GMVR1}EYdDZP69P|QE0rb{a>yb#J@}eTN zw^gLYy5*T3Vr6#yM1~X96y1$wAHddWzHrzh7r7Z7z?HKQr9wZP{It(v*D~FyTNKXpC9Qu%uLsz$a)40gUuf%57 z)-T~@R-rU#^=q+W<1K1(JU(kNLU3?XF3qNY4h|xiqg;&D5^B{#p6ugx7XnO9NlD4f z#`e+suDu;j&~bs}Of**+0t!aJF?8D2$hTzfrdDFj@N+0&lY~C&5LHHg1zRDkU!!c*hx)|mkXazu4~BH;(Dv-X81K2$FI3DF)^hz@X2vi z6R=Ne(y1sZHyR5{_<=`p;AS|J;80&+Ba-T5^r(S31avZohyJx}KOt`K(kS%BOlbJy zt9q-^9pe$-Lns+>d~s?M4as(+OlOW83Q zq)xa4oWJ^lu3e+nkMD}B)YHzpaPbUxdBm|&%H6nRwdiu!Um3+c!jykMxtM06f&@{S z)%HK044~{i{@UD?^n^dsdFW;VqoyB>x0=ixTbOu)SJyV-ck7VmQd`aqCWxWIWkYfh za)|nOoOO%U^UOR&>GeH#C@Fq4XcfM@pJWLyl#^5BFMdE^lV(msld0&u#(7wYW1sN-!2rlQ4e`#mpd++dX zomOax%;Mhes6X}?Or11yIMRM`AZlW8>&SD(Rdk|-T(0_MmHy@NkdnS*eVL8O@5X|S zaJzrLDDtZeh>1wWYfwLfdtAZ8(=< znW>0EsyI{*4vr52^siqnHzswk;Ej!&2BuNH`Y5zj|TcVO>I4%$lzm1V8}{`CZ9HTSAq3 z9wf8u%?r?QtKtP0-q@E{i@jfTFiCaq_gsD*i3r_qRb;KLmNtwDX%)OX`O7s{ai*37 zSGDvfN#5shAYRbdo1x7^S&`17=;Y~Ag9s((2gddJ>Fj26N}bpEet4xc!aT9gwEQ;jqePiwdaWZo;#a_IC9`gp=$o4TGFA=$!2`j z8hrlXiAY|%xmL*460d8Fp5#^knt1uE-xXMhj{EWLFFh5Y)Ssk7Pj3s4v3sBMQj4Tv zF0AaM1osT2qaP;)fO9-N2BSBTu<|JFjPLe=&9?Li!2ZlL(Sh6-Cxmc^$#vDnz+gTq z!waCD?QS@M=f{bh%lE92f6OEbDEr)PhHbp zmKlfkwxI}ciYcpe&n|~~D3t1%)Q~l->5e%w1m@C_E~RxPs~?+kd30=Z%W5NPyHUm& zy@=?In-bvsr4oowA=|dadmX_c0S@bmm_j-A_i=RkIkfh;G zYY>ZK_|~4wpQ?oHMq9$@wYxuidtHamOgTAa^IZh+In#~8ACITd{{STqk1-xDIjW+^ zvFGgGS-BsZgePp3t)<@A1@pNDyp9-K#dIoSw9$)R2r_n4XpkM^Aq!Cn)HO$V6m_KL zxiZ=d=3@Ogd?n^mO@zGq{iBse5A@*KD10mASLkxlMlDEj0cWQNxNw%3Gn`&4CVm*K z4w{p_n^s7hb>lPq1rPTaxp?yNPlEf9dTq(Yg%o%s8S;LXn3}KfdY5B&GHqoSeM3mh zN9OJ~_T*d&g#L(vlKYVyv-~tL`T%p&NzQJU@<#NVL0zFt3w*;aqnM9j876Of?cO60 zmfY-2*+oEyK4AEcD0&UH1xj$Dnca1A#?7!xjTo*Ep3Vq7N{FS{#1Z``m|YF*C-67S z2#c6Fa=5wv@$+pQB(3NkH5^pCvKAfUkcAoAIU#2?0)inNI(iaa%Jsck_DoMQ&+|Mj zF3Q(p8}~f3PPNj7h4303ckul$4?%YmM6tuenbyeVGD7E}wJiS-?Vk35fH1YY4#krD zU&Kc>Qr=P&^eu;B{%E9!ewH&fwA)K<)f5DNHC4INL8LFH4Uy#KSKgmwlET=Yb)YNf1_$7i3+D7*1=I zTsRD6XL?pbG%HEjKM6>hMX>WqG0Rw)qJn2er^G_DE8xyMDWreC7)!-3sW6~XJzf1B z#)hVsQ3Q3)weAo3C?SjXww-6AarnE|x-;4}_uq_A(+V0?c+4iQ?Ej0YzmBTv`@YBF zOSgb@gGhtYNFyno7o=xGa zg>c^Pdb)sPKUCP8aB{s$@?lt+#e+_`>raekg$l~MUSp1!+FTC`8z5?N%l5}3G}`Ja ztJtkJ#~dOx2}4>bjCB~8_&)pe1+ae=E*T#{x_d`Acj)2@um3mBAVs@XVR+uD&=$WN zyh&Rlwc|PM+vWu=may$ef7rv+MDyb2HAn%F-+RWLXV3oL4yV90$CR~`r%(lmQ_u?( zH3mL(i53gX`t8ohP?ZuYz>H|n!l23nIpX6d6$Z>R!^S%@%aznE5n4`7h36+aVm@n9 zgri!lc1^*qsM2OK-KXKmEd3bJ&vLzEw&flM5V>wwa9*1D(zb`sa*HLKO@`j1Wojqa zAGXL;TKcR}#4n#aFWzb}cFtYO6%E1Z4YqBpsB4iC2Uai}4<&tB61b4v$a0ew+j02Y zF5tdcA5H`k^YLsC6w-N<{hLK5G5IfE!sz11tdS$Hj&!}s>v!E}{eN?^5vf7WR9!pA zgzfSD@C^OQw0~Ir_em_j3H`!Eg@vksDM53Hhvph}RQ6tvwV6Q?1sQ&IKWBswc>EfL zAjBx@EK4P21NWt!ydlSVhVt)ONFp;#7hD%NGh34n+#m zulQbOWv)seU)lrBu$m9?Z@S&2y%zq(yRVEO3`H$#6nZrRsIH*jW+ErIK0@9|)qR@! zzR*AV0X*GfY%G_m5@-r@_btXcPh zGgO;RaUeR^#jY#g_jRN&^Trd(B9#>t%TC1mJEiV))IxIZ7B%R9t|ozI&yhVGzM&qK z`Q8jf!pS%VSX-aL4n68HO=-L1!Qj*wq?p%FW@iozL`2_>x)RnNa`o#eVVgtVzk?{y zas$>|bpm=~6|Rvug?= z5V=si&an?Us2tVVMYcb{ZG&)VrYecXlL3981$=qf_5~A4K_f!{3au^fS zL>cGhjGq<55W}uAYOV>zv$Zz1`+ngF{lS)5{<-CVk?Tp8+kz{K_=}<+dE=k6M_z3S zTf5CIdY{d$04>MO7BZ$G){|`iH$VYrT2pF3{k2#VZh}N+$pHS_!Vx0IbsnDbrEZZ8 zXfSx`AM8p>L;Hnt1X4QpDgs3xk6d1qr$i7dEX;&h)abkic4^Bs%fq9HV+IHW?WzFu z2JDvJ_P}dV*7J4h2vux>?n2eOlN}rp#Kn$*fmvedm9jP|$M=OA$ z139Dmig?8T6zlc(5!xX+PXO6dTc_w`v2ADEuxzU7l_xS+e8M>lzZtDaXhVj;I$f45YhInPx*`4^NW>G$=ZeTq;*)S1uo1h(sE<8B+hEQ%wHf$)tVDpMyIhYGzB^oRa&5^>2=y=0 zD_e*KB!uDZh1zD~myg){vASb|#Vxa^olqVRbk!DqFxRBs|o^g)z@c$5EaiKk76#((#L1#D~&#bB8+S>%Om69E< zkLwhdD=}G?>8F&Q!6cgf!X4jZE>ApGFrF@Q&TpFBd98s7s1G~Fu8Q`SbluA?P(8~? zdHo8j;0Gkjcn6M_FWkPFC?>eC?+G& zwvD(muznZwPIvWPRQMhUwp*Wz`TTVXw~d)2tc?zZSQzxV4K@lBQO?EMzzQ09AcJcW zjXIt=q@aM@hnjr($ZL0uLyMp?eIXXc&=lK13F_x<*&v+yhuRW6T%D$$!q(1ocgxN2 z!?L^<)-x-#wIPLSB^`Sj;cg-r>y%N<>Y=}|PW5B{q7&tlA;v$=DQpOpt!iIrlLX|j zli@c6G-FbR6rxbjBkR$LTgwTSxO7wCfzx}_L2H2jZSc8Iwvp{27ZO>b{XZ_ife4k* z5yYmb&Kgtg1A1HaQph(6(h}X4up~H~zuQQNVd3xesxyQp0`kOnoiK%jaP>I}(qY|B zmWaEfGhIv28&c|tfPQ3zf7^jnP4+d9{S#spXEQ$Q%gEC@-siWz zK;SG>|||?@cUB>om~uS%s(|F!TV<9m$jp(xd^PV@n>pTV@iItiQ$Byii%i5 zkqt!Kckf$&Av9FL%k5uy3i$KQ9Mud!aKJca}@pVE+$MQ0d;J7qv zt7(Lr&W5Kt4z)7De3PS)n#Rj)WgT|kz|Q(Ph-RnF<4cr@O|_L@{s|;h%d1jV_y9JMp=Byq9%%Z*piZE=B`@BIP7Oc+e-L6=^Qd zTi+KR0TDQ_l{-BdHaUYuIjWF%sKo_Hiee()u8S>4$+!_NvkeV)SQrK3 z=hL(vpiDW*DYk_#2tAlv<_$3-ELkv z7295~ojcTbP;l9DwP3bH|4O#FY#nU9XS{fSpYHnD!g+MpaZqJCyn5?%A@YMF!I@ zeuCkc^dsKbHW(t%hnI#r`?PF5`c1u5YuXl5j~TIIYD)%1S%?{*TvR;`KI`*5HQ^}p zz00Uc{Q0#IJ0WE?9ZO zoKOL1V@$-IP5U{wp3n&hQ&p?l&6~YA%GbcpU-y!3(9@;D--huQ6fFHB%&9F@ z049@m(09sDEusUQv%SPO5J!N6RZP0he;=i~D=jULCW{AQH8(Re(327+@Q0!|0%Hxy8`?EEkOltj5fErzGX>GNT70ZM7KK#rHER3j^f15v_U z-e0@Bb2*HM$*{)Gv=78pDJ*uIjCwJm+9>0v-;cR-#)LBp?jHV)LW7661d0J{Yr;8S$R_e5)%43Ue8v*^_*Suc^r;*mJ&VK|BKm;TBbovQ6zhXB5!GV> z3O3(1Cm@{xux;>!J;0|D+~x$nmwmyxLkwSV?$I+$f+C2w>Gv3jfC;!mMK#yxgZpIx z;mLrQAi6!B#w~JFnSa)-ia()qvJdl@MI}gW%!^~>jemh zaeRI~$iKs+N@DD&||NcpaMMi!cO~qu=@$e7;ST_nvO035Y!0Ir)u8zI-#~9$ZcE`{F#3CDt zo4Z$lqmGIzwW z=uxWgC$V&K^-Vb5*PAI4q;U>Ggn@FIiG{^fv&D}e3AT^&q&L(X5QQ&I!}BFoC+>Y3 zrBzph{14293gdbiE76m=qLsw{?u~_L-YP zXlpN7gVO4V%?oyYb#Q0rT6mk3wUJAk~@@CRn-C%TCDzd{tE?0^37u;sTr@@>fgS_Po^_zL$OAQH{EeUW0y8!sSvHcoTrJem&` zamQ$o7pdPDKqX=XrTe=9e6}Ta-YWAbMLIesxL(bTzy0*lntv5%L*AS+nG@vz(Pi0U zo>DM+wOqUvep4H2Ui9K2o>O?yP~w~zj(m)lV-#|+7Y z$(-!$t)^9`acrNcGGplBJgHuapRbpRz~SNHC%YYtxw*Oa50)k-tpI(diU1N#7+g)x zL6VeUeHU%NWn2Xi0eQ(x=F&zC@&POS6^FN)*0Cc*foNW5RcVHEk8$GbKi+i|&GoYN zb>7PJ&>zNqN?*4?CwJDJC+1(Ix~OSkWE3;%iVV4+HSc0y)#hfvT9s9W}#Fp@QjO!ySu5vybqZ z$I8j(&RK)1vMMiJojS#P7nW7cjWTdS56%~zPfdRY@sg`6E7NmwsKQ+(M58@kNfVuB zrA-0J$;p1h|07OZC4Bs17?k+QT_~E-7A!?wfou=3gRFSW+9A?`_JHA7D-ePM6(~xX zEN6}e<^{t}-Wd=vCFgcdOivFJC6{Y|#KbfPUbP`=Tt6J>*L%8*b5YUCaw~Y?u}06{ znv2tKXHl2b)e*F=Y4i<=rC8FdO%EncBZ2sV2?`wE1IBE%uo9H591v zwNASKBwNA8j!;$0NXKTRMrc2@yET|p)eo>fJx)V))0>(|02}vXf%jeJKsz!(t3X}7 zz6ZXr1myqohO?!>M}PvBKG^N&e#55%KAqh4(Lx2sd!EYkQ`HQflu3Z2H(%86PYT74 zSs_o^HQ&vp4$l8w?5eBtY$JTlrAD-@G7zs#mkCY*9BCO)xioq6vh4r6Sbu4R_fcMWc61LA7y)?Akxm-7)MjrW0(=0M zN90=j_l*1SWOv+J))3F+Gim;zi}LBckZ7eAzOK9dQ!M)HQ?R!j&e!CYmY+0>ZtoaZ6`>W1A*8}jWBG9BaVZBd!Z=92 z^ti|%=?@do3m9Wyb_D=~4FB&^7b+H?teOALvG<^)?G71JlNK;cxpnRwvvDYiZTiiZ zDu>vFf{-E{iJ?ZG_=QNcbWa4ZCT`vF5AKtVg2>i{Te+Fa^62R1EfV2bP7D=x}W73ymeH;fD zR|S9GkP@)S7y4<2A5LyJ*b ziW!=T?=@RatAVj|M*xLPmb3aaT>E?fQgt=wOMx2cf99P*4tU7#>Th^&dwNa_OWoik z91mJY8;-k259h5f_>bE>AOEGb3JM6A-8*SMzxc?U5FR4%>f9Ue^mgDRSz`?T+Xa_SP;-ppA^h}#%GL$nOslwUqd)zRc~ zp3?6bMwLf5b$41>ioHhV$75dOl((2v7XP3pyp|*Nz8fQPBen=4{&R%0Y+mwiYgIZ# zd$q5XA!A;{fws#}oHoNLA}Qm+^M?)#7B#?3L}F*lCVyMcYe&Qzx4EmA&6<$g)Wlyj zCxZqqFCd&8pY#X#f|u7zNeaIbBLH3y$BAtc@hAOR5IOeE;d%3$qyq#HZC8%<;&yNE zN>M+q={Um$qIK0-3}H@ub?DEyGsH{vPHN!~T>i7e zNyVp!L_9W2E;@XZXKI1_mWZ~+`G{k|Tef7f)D}mkT8b){e&TDPe3aO7x0+>6&1rbDBc%Gk&9p6+^*q`H%`C27ZhbpN62c(oh4`G1u+4!AHa|TR1re7 zU+kwQTE}M#{0mVOTXZ9PqNVpRsreTzNu%UzmLaNIiot>SXNgN5U1FA(0uc;FQ<3GI9>1DwH#{eIp z5#P9$Ym&whZh|?Z3%=C*d(Td3{*309zLg&jHz)Ge7NXrV4IkG7J@2Xbo{X1U1)na! zPTlIWuS~wxc8H`Q!Pw2G=pzeS!CRz(28Xt>3BR&fT$#r6H@R*Cx#9f7PA`E2CL{glOet^;c&1%IBjoDzX>BdVHHASnOj zbV9xjoH{1&e5#izkuOb-B1rj>(}wZRX{xs7hYsdKNCI?MwT7`ldSmWyN@pGQZ0j)l zHe?$okJ|EK$(_(>QXfzn{TfdH1$yAQPTQ}XILfUg>PcYAt@>A}VZbu)dXPLnJ$$r& za3gz9i|^PHuwA;5G2?_O@!aCs)#)k_F8HwE*%RA{BtswiZ1)<@Fv(Z6D~Lf27;XGq z3M2M~s>=-WspskC=03T;79k}ueB~ypi=_nS_r+p>i-p6fQ>U7D-^5&0C;)yB)Jh%M zP8|;Ir3yT&Nrn97w}QPe<2UrojzRVDd&=NUTLr)e87&oroXZ6VDVZ&$)|qlZ-gjLg zSS%f$O&RRJK`Ko>_9yeWNPWfu`r>!|KwchLo(xI5U|;jSHgBuvpvo^<4mWQqU2$t6 zC>gB6cdHgY(169WC{v(C8ggZSghnQj;?riSfZq<30b(nn2)DhS`pb za(fCM^IO56_6A{a&@X2m+h0T0biM*X1Y~tYe0O!&5l)lV zS=A9}{gg%4H9=%4L`UzFQ}%lj@K2)AG5@)}Y=0&okX{#=0McKuY6CwzWmP@l(B59y zkLAKKHCgch59kN0B;<7LxIt&v$UL^{9(5niW}wJ7P?L74MOK1@o#ddW#kKjvDE%+D3+_<2mYf+?h^`XGliOGt~qI4j5Mp#J48_l`qk+j+U z!WlpjFLr5`TbHC@L?zHnr<=kZb$CN<`wsI9>{hE~x2>P5&YkYXNh}I`;mFBb$}ykU zQI^}IBA3E{d*1S-^0PrV4~o4!zssFNV~yYyKJ{@O0wonyFAi*cXsCX*hCU%#;9nPx z?!-hZUJ@Mxed@|E#n&%rivWs+alz+B*AH2nWFBD|hnflrM4M%1N8R^fA6EqBno&x1g-0Ao zNVK^yU_l~C7Ihr~Q?buz!?BtQMvOjY%2XQ9w}GE3eqd?cLT{`B6MtzwtaN8XRfmM< ze@JN$`iL?9^m3#}`!di)(2UqD+;=E$2nnqeu~#{hM$I@o%-O%$O@CN;GWHBuSo`)$ zy^X#Ex`viDU)M~$>Zrnsk;fC$(9J&QGac2T;3?HJA`+t;N=L`Wo%B15+7Mm zb~@^^zwt@lylVwXd|8b*l zuH#Z$HBG8l!C$MX*I;Iro>g=*kUfEVihd$<_XHaha^Ntr?0Q^uo4=b`Dhw78)XTL| zDuMXUtKj2icF#4dRmF2QSL-9Z$W^szuD#!^{T+GJ>nO+iAlij-J@CZUV5jjJ<5#WS;a;WZk~py~Av*z(;_fgc%sP`XMnX zi2@P&yL!ZabtbK_B6ekErQYM+CCKX~arwq&pacNi)ja@MlX;L^DsbtUdXU%0#fJokTQ${1bPxc9bhzDM zg1p8FkUb2Fg#bmu_mj32pLw_^_D1DpKnJ8pL%Se)W&nTui8Oy*oX(?B<;qr z^{9-*4;?m)zuugZ>caSf$DRiWi@hS~83eU}Qb>=-<9l;MugMGTgSDfPO<`Qx>))T2 zd|+{5qu}6PehsjCLmC_T8gJG@e`VinGfV#Qd(pSyhEl<~iUY^G((WCDA^0b2b@qQKalFCxFw2X;>H=i(C8_jAp^g^7quvzAaG*w6}ZE*~>@q z6GBjL4B>jw{BUS<*Y!JM9_{x11BkEqxrGXNm-xl-ungO!!r==>Gn`)f^Q}enD)Uwp zT1QoL(@o!;ym*MWAC&oXguO=^YRmDA?KwgqDTst6ZA^HrDJ{4qs|rqg$fz&5nSSL{ zys@vzYQY^8K)Tg%`7eJq5u;~98?;rLKY2+eid6vN0Dz{zdxfDXN&uos65=qzOw}EM znXOg8rIDpxkbDB~I1@H&Q1XcGrWjAxxOFE21??kzPl94jvA-V}U&bCPH z0J9nTH|Y=VWU~8DUB0Vyn2JXKj|QW%-I!f$Fv_^z5 zfxNi*E(s{@Ai%tu5{SF&+HHOhR^g^%{;8~~$;!-x2C!1# z)c^y-=iDajMr*Jv`rA*i;}^T9H&aM*CBaqt^Ii7OFV@DF#j>u&o5kb$fx6 zfK4GvRuEUy4EoY#%BR@Gl!(-uq8aFR;)8+={hJ(%$ED&G>K|ed#?sLB40EniKnirQk zaDNJuraL_0E82!2VG78gAaar?wgopknc7RU2&Z=RD2&Sv1p1fdo2AIoyord2$Sf&& z6OwrXNJaR%+<@Ec=7|G@TVsSv0}|DyamuZU_B!Lw;rQ4XD=Ey%EpOd{mH=kSz4^Qo27GK*UEEKz{o*_ zQo#Ni1$rCB8!Bm#7c-#K(M~k<8GjGxIC4InIpt|R#TiW8Au3if{qxO3aFA+Z*c%0? z6Eyyp$N+nNpXuf7g!nhdSmq9h3_9#utcN;3F^sJ5c^wW!B*+#c2SiOYt2GRNVo=D! z3@8B-d6Xnyh+x2OW}55Xsne@ViY5@AIi@ebc#IR|2~`?6BT7p>{d&M zE(#&fya9w6Yy!aEfY-I``rkImQ7V+1RBe{avz07VNRi8{ChPwUnZN0NA3;A6&FAL- zRj`=&*Z<^u+GtexWjqz zpTuLrRwjU;ZMkT?(~oQ{a~Tx1k{0hZ%;g)1Acd>gVj#xE#+A}{XD#KjWR zy8r2^m;%@r8m4!%c|c0XIHT3){`G?ru*DO_e^9>wN7d_cdAsdzO8Juy|f6kJ|juAT?Eeuf!>8?OuH=|hzB zu*M1r4K+^bJG$i@`rsg#^TzGD1BdoQb(?A>^8S9(>C7tLD1Wn`Wf&cn71_Pnf#r-> zUx<_ncriHAV^`N&-!9etSLymB*%QcIZ8C@#(Q^9Z>D=W%SV!^h&29AcPHk5!R}a2J zHf$M(2j1qJz~$SPgGEOt8huehBbFMtrjJ z))b1(_ey_dM;&K0QeBD@$%T3)#VsfsCwg;q1!PS*Ys-aWfVB6PJ(_e z4fWAlyFZH7jU}CLliB%DeT7!7l{Z!kTBgQP45^e>tnQtGe8sgn zBp=|X)rY$_m2q4u-_``YX2GFLGvgTnPecI(nsMWHOIRFfYC{h$|NN%3)4qL#d=>+? z?RHCBmJ=c#-RGdVT#F5Hi`lsDq=S1Sx}J9f6{4XOq3;i&HPyt%DwJh^(hb;V*!fP+ z+BlIm^_zvTG*CX9qw1@D$}Sc!)__tuv;J&5-NTk77<#UWdf(K)jc0FRZ6RFq##O!I zeo7=^Q~72Xm?Z_EPR7f_gqALD&a{tOAKv@@QZ~b%ZcWQub_tlPzi)Bq)p+SEil}I% zR;tsqo#RGU^^~_IRUT&PFk2x{ajewxE7jkWRFp|h45?SA$q5rwDDCJovZdZg-5o-e z=1rgD>W{HD`px_f7?nYk12s8^smWk=ki1B%+#Qk~Rp|7Lg7&!V9FdsAA%twK=GjU= zC`8S{H=Ng>X);3o+kL;9eqxcd{EP5_0Eff-)K&Ge#{eZE9wocM`b z|5@}D?ZVx*tw4)HutR;;L)j_fsRxPkZB>TdNrfzWH58|dM6y=@+S=T2MKTDiV{+e_ zZ;Dex9Sot!`ySha24W;{+glSyL!Gn<|1%93JkPYYhm{B!mtr)-D!SymA3TLp=!P2C z*d8fYTyjnOSoQi;L=o8vW-FRu`)XJ;9DcIP9ufsCX87|NtehZ+L8sdk>w~=;98c8U z*4{)(;;%Op5-_RVk2}b!r03Z`>duQA@coXmxIV4V{%Sks_eVA{7(ShD+$?&!N3EyP z(LXDc$4s9F6)em>v!TS5Yzq1D4yF?H{cR4XO*&*!C?PX)Rnc5R{VNU*e|hZY+R@iyR&J$F5_j%AT>?8=+v{;qI>U+ubyb1H!9sGdoZ0 zQuAHgx|SOb-wAc)g0>b$3N9v|d(!rwjINuNMPtkdrPsyBvJj}6+2TId9~wCnH9 zC@$X%Hl0(diWr@0Rb322<>&v)`^sVPrf_iEv0Hj#T$8kp#f0S8lT0!zAoxJL!Jkda z-UZb)952yTNs42>6!ORI8~5>($>0k5ow7*W(?Y^|`!0()VmLAR>KShA&|?G|&Dcqa z2B~W?e2+sZYt<2*k>P+j*1YmV^!&DD7KXbG+WB_Lw`*CNJ%_!H{*QJ!kSHdOq#C2= zfT&Kp>()Bve_hv-qN1=B#>3RCtgJl-B_$;?$)7N}xVTV;f!5rL_}3rEP5g^1h^j%R z&^?|yt%+X$iVjJ<($^5g z<7~MStoEa)&2Uve*-9Fiw`W^^f;d0zE%O!12XEiBt2ueZ2=`c5#B;XBi74N(*_zRc zgQ>VL5DRmMjkNc$8d(puQ?KU+%}NKh6&g1Wgp>D2AcokQkveVh`^_Czv}QeBhMqQz z3qhuc`pb|Uw-zfbns3-DA{h6o7VvT9UkMEA8ZB@|Xi6o_S^R3mr&c-}ly4t1p{Vv4 zpAV~Yz#a6vZPj5()mkJP;JV(HJd1BC%E5fsM9T0jJpz%&_}5#?m3t%jo=rrTyw@4W zY~iQn@XR(l^En5$d!4;C@M~p;?<#5*I`ip8j}it^3~JWL?#%__AJ`p|#81xR5P}p3 zbQ^@-MkM7X3&Lu^;;kPq5E*pIx|5|Ro%J6OH73tHjP`{&)1;(4<<=xQKhA{v$~zZf zm6Vw+a=#l_sXV&enXLH;G|$Sk-lcr7o{NzZ;QY1k3c)Dbr_>>Cz`EYfJ#Depwhl$3 zV0rZQN_0ukU2^gUC+5YU%_5){+Qmy^d92#(f;6fi5jwh24nWJe8R^x&5~hWV-S(i} z3Vh{#Y)kpunDYX9Q&U*uDL5NSigkCcZX4&0G_8L-mx-qt!c{hT4h_lYN&DL@fV34) zW_w@Al_xx*ZR3bX72PEqXIrWKNDa)=sb#bnz|cwOnA%{r=$tvG5mvK!wp03LhbOA8qGzP$E z;=sMOuD+gCza3UfTN}l$uDDyLB(PU z)Uo?e7}SRc4i}yz3&Qc~**eRUyX#SQB2Mq8Drsxh$n$2`OP<&MmZC#S&DZT&@!pA= z1j}nj>$`=yai6c0A6YBpq1fAEr5_X7j{P+juv^+|idf;~DfS=W_WQmrG{3)32Zm(` zo?Fr_0-;D`fE%xv>A~LFcTbw9n|tOm`s`$s?;=w2b5mn^#+W?(9fj+udG<{j>_^;w zZN(AgF7g-wGrkY?wEo)?7g^Rq&h+eiVrjVzxA$LQqxXkscpXn>*_v0=N&bXhIT}B>es(65l$rpR1uBY?^vb2QU52HXZxczr>tv< zK-l0d^G4Y*(7k-D%@rMCh*}SocW9~BJM1S;ueYrvzGcccO9kn~slUU$wTvCT1Z)Hg z1$44Jj(O6p>O=mW8SlF=gSkFj%}N=X99Um@oy>%-aIEldm@j!`@XHcSF`0Ed;(_0!=Jj~Md^|x4+fhlIL#t;tT~mk_ z>z~E4@bJleOJ+~hHHhR|VM|?jXW;DmP*G{26lG&bG?JtCcHbeDg5V2JQ|RTKfL&4X z@E>)EeW7p#E|bX`UPp7WOLwE-9~!N*PngOUe+_PJeoDxGyNE(7&@Lr;ysK=ZTVLH+ zZ#f@KSPCOuNThFmnmC+|`(XV1T{jH<((GQbz7oAEi6bi@knK|U_E$|RFj?&*%>oQ$ z)pbp9NCJ0FbO3@nnfNtvneP*Se-f5%y7}WA`z}XVMseiHen~$*iib+{e$OoF8SJ5k zT33Uc>|CX#&`%$JkLC#6at9{QR2A@N#Xpi?l>S~9^hEjIDG5?8s;sYsNNB;9(V-8E z=>pz@S|50;Xf?s!h)Xb4bT0T9acYUj*asoj)Ugj35igEeVhW^pTjJtxaB?Ry#)54QXj_cs28hl;$_hVQ3SzvJ0sR^yn!&rc6%ANA< zuT1Toz(54j)R{ddFkCw^E3cD1;x=%^`7N{+Kb(K;#u8FL~Rkd-Y&^;v>iLuR0gcV^>O;{Gyqkdvt zS>H>BjqX*~f|}6;O5XgMZsx%GF)wIfX(x`R78o9r<8M5S-Y?Khb%QdoF z#OmT@S~jH~_2*AW8@|+uV*Z*YZef^tasQoS%($PQ@nAa#zLH|q9Iv}5REnCqmQ=!1 zah_by68_ZDiru$&d5$F=cL~)Kv?(4Bj0RF@MvsBVnCyDg9YnmFzuh63gdK?7(31>K zIdP|Kh7S4k5YzX2cT^U{DUuQ&@wBwGtWFPl2Y!8d`{(GVS)XYze?uyFNByY50I}-P zCyAdL#KCmC>-|o772hM{hsm6WEG=q&mJ+#Y@l|ReMYjDiXqk=3SR#n*Zon;Wx~{N2 zHna##p|RRVf=r{ddMEevUY>uS_ESWmUOl_-XEzrNLZ424-xqBS8U1D`L&;RrT#vpp zI5`;us0);Hq;R?;$~O7>FW|0UCQipcSVZgC(cE zyzaL4`gN zr-}h$i$(S~b>kuuty8<5wg<|Z;E<5M+7x5Ov@`!comn&-BIlOb8%N}8@}1(e4z#noMiXjVpss+ zp!Q&en<`XUFidFQ&pa%XK4?z2NgE)0B#`+IG{=8Z$@($RUVX^_*+-pwaiSk##-)yP z(9HS!)erFGL7RZWz&6!AXRg7TS5jJgc+kwiVK_@o-Dl^8gNh^N;~n_2)A#i1kp|7- z=EZL=s_&w-B_jWt`H~D*7RRc4e0l^IJ_W(x^Jp9 zioSH{A=A>Ex~PVB-BvKS+-iw}WlI%<-(4gMQ=uDI&R!KxnwGT(vDl&_JL-I=O02G2 z9l2I^a=wuuE_kA-NGpt{N-r{kSAMZsIK+_4wGPI-@2%VLqmwzU@^%sDo8Ze z73X!9mcgh65bcH$ag_+QDc9vQ`C$N)&sv6+KRk8^rggIHEqYH>a_qP4t%SrG$m5bm zHdhSwXd6kUotcyuSKOvuFD50uhO}SQ#?-2<@0?79*%LNhy%{%M zj|0lUr*R&1Cb*^+ZOV(WIowBV=t6OR2QOxdf|LX<)Xz`q>{95;&bcS(1(#6t~_3NZs{FD$Dsu1ZwIV>Ysj$78Gtzm~_+`VZMKFXyo>db7{b{kRH(C*-{@03!?Ah9H<*!vq%2NCExFFTf zR{VOnuZHmdm|IMY*MpJ_-gAj$Nrr?|NtXQ$r<+&Ymo98J=dSw+H}CW9OHkcFEDl5M zL;;?>li9!)4sjnib0LAjk8rRjkqK)&m*+6GOn*><>^y0Gyt1IEfvr1iI^O2i(P)rQ zwnkrmH3g%uSTjSklZde;4iW;n%s7pjoT)P9a4qe|AaV$4d7hIN7FSTv-ImlDVKVr) zhvi2@^d%f=>*Uld`+M4OG=6(W3hlm8;9Jj>4$T_dcL`yj90ZTlX>NzLx4%cHXRg=Z zc_4APce9&R>9ON8)7A}IT5yry@&&%pre+mLOh4>bZ+=F)tGW_NGH+2m5}1(T?JgT% z?ertv-tOw>PAapc+7o=zS|9EwWBfiDQrCF?jjd7ow}Ax^J`!|XmG4bIYK7P2%EZ7= zT*<#@<%AOhOEy_2RM<1D6*M{G#U1y^0=?~57o(1MCdi*|c3|Y}4&+e+nM+{dFtM>k zM`ASJ*RtnITr)5}T2O9hDKWp7usLl}_9L_@@rL6*j;a!Wv2|-p^=g2vGriU6Z9<3C zH5{%NpiOOQHgmO*=A%PP=eRPlq_wOe3TcitI@|secuAkWLPdS%_{4D}M|KD%cB#yT zgx?wj6F=+Y%hIdmJy!PHJvrbGtNevGCzxxl3i@4-gIcs7Deu1(cB?Nqy{0lT6Z-S{ z6rnmLluiLur6vjx-fOhZ;AoJ7TW<{P_;xW?d#1>b#Ri#{Eb)l}mYu(--noef#whq@$IK7dkuFjRQI94hkydYjqB>AY? zQ~D44sX1o)r^f2|xqIwI=tcz%!@Bw{U9+6i@2>IGPTu*aVz>Pf`YVue``I3WMhL__ zt?jlKlh3s}^IODIIvw%-rNL9JThMS?q5NiFOo3J%f$~$c*pX{h#+?_po2n~U7NKgc zOWf`O&_m^;fg53zY3TNt~&KRl;+1;)Vp1?tut++Vnsc80+&UwQO=We(I-Xa+ytY=p};2h zM~3x`55Jah?6|MYHkbXU0}I{8tEeyU-P(%9A9ubbvB37wvlrDQuw3@7DpoTdZ8D6z zt)Nb&ew>L!1C1%+tX+A^9M^*jRI+GVVw3(6k?@cF>5f@{UYpJ4F$^ud{riHbA$Fs9 zRycLw41FM#>aVxYSEgCNnsAGFACs}T(G~WgDjBNE?c~b5FF)tLme5QejgW=wqXsZLfaDM zz_87=(Ja7`(vL{xiCY+JT;Hl_)%(O1=1TO3<>8%uf9`LrGQcgiL&|rNkkX`$v6P9R z(ivUPuj#IYB~n&WF#p+Gh_*LXthqZ^#SrpGcZI(H3(NcN-#-t%-08+gv3)!Vgll9M zXKGJ=Xknp6JB%1;?~sAj=Nzq-zXV50R8{fC#r9xJLp!K%aSa=1Q(?rJ`ub{H%;#CT z=?HE)4;ktlx5sD=UC#v9)LL;TM-!*KU(wtNvO4GBKlX8TB|x@FhsHbFS_8MWD>NCLz_syXkMX9=IGlTyALl zyW`KSmWOv>NHsM}JyF<@^L>+@5L5a%CsCv!4dk+r5ylOY^##(kD%4D}P`Cw93Y15lrDA zgr&t4%NR!K?TFaLP+PWs((I~StvZ`)SH%CpI4hN&&rd=w>9&&)a98ux5XCeos%XJ#2D$)-y?unh&b))%+c(kS7Zq&cP7oi#XH$9c?9tkh;=Y{c(1B z*IuVIng9PI>o23?Y=W*)n1tXEg1fuB4@?pyI0ScsyStO%I>9YS65QQkaEHO&-QD#Y zazD@c-gDkRtYNLW=IXAlt}fYKdrDDUJR&NyI#l5XmGArTt(;hbZ;e^5nf4!dg zqMdyc;9a}jD6_lt3~zdt0(a^qtmL}$yw9AZz>1bRb-lbZ0;5?~PGVn{PXb0pC}wQ9 zd9NFqL2A1sRU>})kGb~8eYCv4^xA|KJK&N(6nUy9^6w9fzH&N*~o7Vmi|#;n+(o1TI?bC1;^@4faf zPghVk*THLaVBFG%7}?ua`FzJTQCRYV<~963%VIZy76IV*H^yHk#p+BL7^uc!{nedq zZ}Y^lWym1w$1*5cw~QKacq^bwRUpokx;T~+V1`oeLLF1OQnm(~NJkKDeWSwj4F9Fp zhARKDh#7yB)k;89NMG=hHA;KT7eD^yEMn_NhO`Al;?j2Wdz7c!_le%9=^_+mAgHI* z`Am;|GTx?V6=~RUCF|#>4zE0HRnOLbZDAImC93=%A3GwQlJM(0M~gc`Cp#8{{=U-4 zMg!3;c$U5M0rcjX5m-5lot}a*$?d6&t}RwSz$tr7#5~l>@S|(NTp5u6H%$XgNl8i5 z@{!)&JPny+5nD~)?KdC)%NQOvg7Q4t*y;|I>2=6drWAq}-CXoFbOlp)hzXdcMeAzJ zd)d+VWv-zFu7JjKG#^Xi1J2WyMqIM0^Mirxn{Y2lnolxwYJWY-RG+oOQ3;6#;&19# z{<@oEFZiJdq7$OIr%Avrvj(S|m~1IVpLe&aLr>CwyWw-F5EQJJMo?@u_D4Ks@K(e& z#dq5W5a43sfAP_i48kPHN8SQ5vwad_;ed!Nl?(&d3y`L<^T8GlHy?wb%P!8ak+v-A z%C6W<(7ZhajKhQyjfT4a)gSy{EWj6ar0r;2^#0HfpRp6Y&0bxAzB{$Ges84LF>H=B zN7{X@R2+u&`~LlVH%~J{#`QTyy#Ia58)Zqz$0d)X2d1#|7TUs0tzsWV8R@TF?sAo8 znNZS2cW2?zH!65|c-Z2f{*GnQ3#6JtNkZRimEekhwRdo6_-6}3e*Ch-$tdReH&+i7 zRMhO(tv?2h%{fnR$hp`=tr#LWOD4V*<2LK9KBbt+9yin?Je~_Y+cKg026vz}CS#ka z6?wqhIm8@7nYi7(0nm5S(a}L^ZA5DRU-_N3QRU_3Z@lQC8m;*A zqNL-0JQhkjXhwjgmRTjPmqEisFL?SFLqsLCICiF`%e1_jzh3kW$6D3;fvNCEJTI#? zk}=jlucdbomgHlJN&zMwtIld)43(I;_|nN5)bD=F%F4(7Dd#~L8#*TXf8zYF zQWOKcV4iHcs=osAaG)O_O{#YTX`#&X>?YWCH zndJ90f5Hv_86v%$P%LlDrqxi+a%}9@bgZMs$q8YW{HL(d)i+)+|0&zQU^Vm$h#}OH zaYGv)Wc4y}=s1|lEC~%UKJ9iGC*z7aAbiCE=FDE3SUe-gwOdjC8`o_NOyU3N>+4Va znZ;4hUEaViAGgs=y{ltD+|9&|@yM(&Z1KK{(f-g#zU2@h)Tf1CXgBt@QY{I2Wrdq9 z)`taT${U4V#jY%vx|ToYT(xcSvbHY6)iWZyZBGnUrK zvGuGLZ|Yv3AT*J*xPN*8kb+VDH<|zbe5D*3yv29P3$p3S^zfVbrkgSZ zej2wmd$vKP*B~#?-Z}kr9FVGwwD}|UKYjYYekVXa2{DfRzJ6&py;0bOCf2Pd*GYDtdpZ--&? zJv!et?8-X zhJ8>X8GVt}DAe4ZypOi1=-*tOG$Is&KnjWEmr#P06HjKS8j;FR!{|0TH>_;DzAS=C zy>#{D#19+-l?ABTW}$YhR98p^%E&gshMn?U>&zvr7ayVYPyIk?xGY-bmQ#g*Iu3N5 zuwRc8l;^0ZxY;iSwA3%F`MhEgKa{dK7+R6l+TF-bhf3*bysNn2GM^?WXEob)l5bXr zPcEQJv_3{n;~n%*9m~nfRtpLX>80CQY5$osz%g=~xFxcV@W@==&zdB&@>1F8UX*dz zE4|^h0JV-8r8^_1yW#YLo4u(bb+QM@Z|EA7{(sisE8J0l<+D5Vun3FZGcZ{moQQqA z&wOhhZ~>j`hT`IrF7f)3;7zrFF5+|rPHtN?wQ%~D)SNisZ|LVVfr zKm7;~@*rm{Be(Q@Gu}RKMyye*Zk>H z_q{|zMN9z%*n6SO=h%{8_C;>>v<@=zhKwsj`1l&ky?9VlZ{NuGMn#k#A*od&M0$%} zKZo$mb1S#U9*V1uOaomABu%=*4+Wp=P&F}qz%xcgPI#nw1P95SJ?bbX7jB{LZVNVl zPc_r+rC}t>iH_g#5U>Wlp@s1oFh6PT3b77MN>U%up31vhdt3^x#x5-(kt1PaYX%52 z9PEeLb&AMpVfI~lW%!z{Ui-=5Ptf|Gi>T)7H4twViu8A>(uECk?V7C)DcG@l4|!jw z`Hsfoc6Qr<%a1-|i=%yK_^qvZIfaz5I}r_|yOx=W=@7(47j1v8Wz7LciYBH%-@&%P ziWzqjA+x?aK7%iG!Y=}O|3|qBIlf`=MS-^`sC**{%?JA3CD49aG~u?7pL;AijP)fTdexur+r&lEJQiJK4U z?KFYzU9+nT4ulum!$!xG&nja9+6x@eQZVU-2;nE6y2uk1BgzT~hRtUjV`>K0@72Wm z@$%e67Yrz1-!!wu_ou^5OS?cTy1FWxJnCKyZDxIYMhhed>g79Rx})>5$denwmCUk% zEP<7($0qc>lZH$WQ3Ot#iIQJsQgRef^YWKa=JflDM)mRAu{kPJLNr2@-o`2rH>M%W za7b9k6bbOc%aZTD`m9~BccQ9PRKUXi;1uYpFEDJ^X{E#nV!6osiHY|`y7cQOlmigv zNQ0@Tk}&vRe2+f>3m0$hD9Vi zpZUO7+gQikUmG88PTos)790YY{celc$jm^ag_QT zj23Dd7mm!D2m=%lNoS>j@8CjNxw`Cnn`KyGesAboY9vn z+fIBQOYF`}tEjs7)>gvZgH&HQEH}xu5~J34!=(V4!$fQf`h=~gNNKEeS#PCJAUa}LQ z%+h&=dqSC1nFZK^QR@?uR=Yn8IwR;dAPqS?{nr;dGCRxGmUImqrRTI^tmS8CeecA{ zNQY`aFH-%eJ+Uaqj9Xr!_HZtwd`rp@zq`n(PuGB_IX7_ePzV-y{VU~7kj#00cr=ym9C{Q;*c;y1Mk-YQ&d5s~a_ROa@w8z;frnegVE4x% zxN=BXRfWnz?#jW>!C^w1yI3oL^+MiIu|oq`%SlQ~YFd}-?M!~6qGYs*(dt)&mH-ew zvk?e{Ls%b1NEy7x8rkmmNxn4$bUhA@-cJ$KF@#nT?QoW=!+H-2Zft$c!~>&JPr~58 zKX;Hr2Uxa3mW?@Q3_yi;ro~R%6O};>HV<4oT9jv25{fHK{-1y$n;7+wc}k}u1~zNlc6@20~-4jC)Xep7Cat4C4<*l*NUL%r;pQY zN3Izlng7|B@QPkn`{GdS8M3#ZJR?%x&AFL5<*{(%L}jsR&(kzN|LzzJJ{A(!V7yWS zbw@`md*L2LeS95J>zS4cH*oCRsX3IIK14!_^6-&Q7XN~%r?wM+s)P~As^@IzRKLRG z8VlF=30b5mm;G@fU95oMq4}2NWcUvKhBRPLnJE>mYQ^Y^f$F-|#zG&GC}wT3XvbUz z){pm0ShlJPSn>QeNabbJj;98I+5f{b+HKt@%nfhgh^n3jGF7kV-p^H*xBbY zSbm%97H;}{id5X3^;i0DqQ+8l*Rt{q2W|QW7+i*d>+LU0C;By()zP>YEmDq9Y3gi^ zIf5dver3G=aWL(YwAEi*Ze{cD3tE>K1oa;M_GdbDhkui-msq`F;@<)$yY*hR9j|CM zpZ7S9Xi1Vx@=xX|gDm;Qi49f?*s-^8{p1dM+d%S)cM0gX-^6TKz3(w0tu4_+dM@V2 zaUD@4Aq~mKn>}Ys#9-GrChhl*B2#@e6A$(H8=nUSpEb-PjUJLFZW(ep*ibD)p7yq6 zpIqtcqSOT{xI)G1Or1SC@RW0O(imBGl_tVMu@Lx4a{Udd&$gvRJZ*@D(!JQPr+6oQ z{*a(8z0vjYME6Ulh-%^FLN}5xHnKCEDDG8K#Z+K6o#nEtl=g@%(3i^#IYy@y;R?L_ zf>~)wNBEh)iV3q<>y5ifajNCDOTHIVBVg+757%?Znl?RsAnEcz?WmIT@hqa*l%$~s zu|+sCGy%cm6*Qyom;SZIQq&utVXJAZZ6#cXfp3og$fL*GEr_seXf-{2K^HiQe93hW<*R zQh^iI!4H$*Bvodo4vhJxs5oVQ?adK5HW&$bS#srt97kz;BX2dK<$0NSafi=&$IW{bH6sM4rq`yY0KFQ4*nP-IW$Lic&4sB5&^GK<_CEiIkK z*`yvgERT^*-KuxuA6TcOTKev+&Td8S7z3Ukf<6317m{etuCX*Do-B0sCt8cJ^q*Vf z{_-Kj+Mn8ewjttZEdZ+h8a~&edaKTP0<_YSJ(6ph&sbf|m!)vj zIqw|Um<8TZIhnRd`seaxPzde447yo+7{Q?l#RovH?bpw3Fy9|i=#_+Z^w5AfVAi0@}_Gr%^su;lMP#2dKPxO8pC0Gsgw+Zc6IHgGc zB~Zb0;O6dECN5CnBSV{F$mrBc1#bfqBr5GQ9v+(XX#pTQL2@Xy!5Va9_K1+lS&$$s z6@~V=V1VnSPWDam$u-#*@`tt?69eJcHadQwGCHM1lu)tsD%)y~=dtC2KBgtr(YaU6 za4|F23X6{$VK{F(3?7zltj#`w$0!M-%&OxcQ#RXZZV?Y=>z>v3?uxlFSD)h{PQBo7 zQ+V&()w^djk5b@EH^=QAhVzRL5?Ep?2XbIHHmDq-WrLL#XX~`Li4?6<5PFpAb0|pg zqe8qL=t$UmkBWbVnwC_&E>U9U?lRzXi*1hPWHw3XlrpcSVA%Pt*7YfV>V?=$OX%hY znGO=&?yU>vk=JOA7m?O->!$z$pi{$f+-3fT?2wC$LZvh5hlusuw-#O9)JED{nz?LD zARh^4ZKIt)uLA7nsK_sCdOXq4zzOR3t)Gql5l2xg(Ms47*#oA;d9Xpg=@P60pr~d~ z@twpRY#W1rfo~0c$@xn|{%dyWaD08_BMZ{A1;!zBo2yc*IyC(NP5qL~v{kRRE5o3< zjvUYKVTGYZk?X-FH6i^GoXj(D*|FASiRLcWCuo76%(gFu@BWDoNJ>hBv{Z%Za~8mt z!+nehXyqp4)<~-CB&6yu2wwEcNi|=xm@Qz^8>}rqnWZp%Zg^L-@>etGP&w~|!^K;v zFbwNo<55w{vNug*JTy3R4UN^MdtHs`U*^8PV4FQH8>+1UJx*={4hzY;_PBw1CF;Mw z*+EmF#(!ypoLKnbTUyxkSP9#ZZ_aTTx_w!fLqGQ4zA!MQL(Os053-=kUsf4nFu#Hwg$g2~^yd2@_|U4<1LY)!*z(WAVwL=o7YsA;#mCX_F+t z%(J7#3)B&Y7(M|a^!tI<_^B;-ZphUangy&$F;?5;{#gh8st`i%i?H60gk$|4Ngr56 zw2Dhg#&;IS(C~CADPlON3xg1|wC+Z;y{wvDOHKOu5(LPeP+qcCj5Kuh9U&Vv-lX3a z%-==eim`jl3pr~)kzQpy{S3+kWmOd6R%=yf$K*;rL-Xjb`q$kK$Twrq(3*wG>RbBD z?$=H5v*nM|pwj&;Cc_F8P}rgKJ&pl6$;0x`C;b+hrIstP(z}FVbxzOF0wf&~?_m0F z!h=_Vib*j+FBkkyMms28LQAFx;DxjD6LC#g z^r8gEdPHJ@cs?VkPwNe^geJWnE)xv>))Vi*HBA&*Vd=1-3S6CA<|^EWox*S2 zZVvO-Z*lPvdZ~NcQ1DPkn!|l;PoCrB&b*>qXpKK0O5wRSimpxVT~mIzJ!&E4Hxsdx zV?Yq5FUZa*$S(-%qS>xswJIsEeTzDv8(*&)*5VR$z~Q+F9m|ji!nB~Yb^wO}&R^u< zF8+1S6&RvsOWy3l09Xe)z6!2Fij%VEASoN2b7l(bn4akUClQ0Ac2R4O7pXsL3I>Y` zdF(KjhQwn9weA87IKJS2>h&2h0-12u3;V5qcefIm%7tD=u2OZ-k)PI2%vQyEC?+sH zNGqPRRV^uc8~hdipTFMe{K@^I9^+m3wxt{`%0>fU>f&w4^ty@pNeGQdV}5ftJ_ zb*Ks1&ct2!s^GQBw2R1`!!fhDqjk117%W_wvH!Z_kFKpox1(26U$@&kN((%jn;|=w zEAXAHidfzK>XqT=_kmU8YmEclVw{Lc=XT{KfdkPa4^b=p3G@(vlP_1exME zwiI3=$~}CJDv84=maiSnaQ1PF6%|b{$Iptb8fh=B+wLV%ldM;f$q_5_MC#8#1Z1q| zi_ASlTZ#YdfKGN1r{_6}2od$>TbugEo|b%s+EH7UFVF2k6MFKa9;!`^*R87!K=uCp zZzq2ot^Lu;43+u-_HHl!K4;^phSXHPY#JwS_^V7KiySL-bn1 z=^f1lapfoKF+W#Y*NaODxbC@WWrQrP>@<)AIme{eH-|C z>1%gtU^MgVdtJQDqo5Bm82-CmfW|fRW8lZ)vlGEcUl$S<`2Aw5~(of$PK0#(*DYyMdN(*ej)>7!+jQDrM`-wvXHx7*H? z^|`=_>GqWId+ySch4zX!HRiiY83THr>n~5~WWJI)wgGv2ntWc}p@*L}d3J<<2?;tL zhUDltS@zu8x>QUBuWuT_=EzdL zheLEv_lgbGID$T?b(BiwY|8%C##If73%u!XGHEY{vTAQN<_rUP~ z!8Us{vQMOvipR5+Z{`hVt)GI?q?4$-)s{=_`d`TbumsyyQ}m7>+nvLC(+vL8HDh$J zSyPwYRxg$UPdC~q0zj@PHHYO`YGXdQA6R1Sxj~K#7V!7&G^^sH$k;W98(mfTOJI`@ zL+6(|!w4Fwq8+vpdLut+t0(kw$V?H~mk=!t+qwzz2ymD^2TCYt4F%oXRas97Inx{A z!q`tcY=H=xh3$Z(ut2lBhb2y?tRF$>fS3Nt3&ASWNx4d$*YyXVPL{t1tFrjnndZ6J z4K^|PZA2u&*4J)x<@!{7?`!P5^IlTYv$7VbNA&LrQlk z5;&P^*WuYYUy)zlcvv_7e0vYy%zl8TMaakQ(|6!~tMK7&CZ@c5!v2Q`mf4w;yHzfm ze%q<1C%2aVd@JB*ZtxTH!yWnB`(ga^=fTPFh3<7bKBJ`@Sla4g_ijR=LLM(<5K{#H zLKTy)pxYmxh~UYh2~ZiRYfC=^7>Dt<6*J1ljor$e%@f=bAYC@H5!aef-XYm{w)9S* zI`6A$i*c3+ZES4pYqOh|=La?@&GcaN(F!;d7U8}9YTKLlq<}uZm!~8TA?MxEC(_#g zfXLCD6x0$o zpCgmx<;)KoHs+9jJu<7A#xf#}Tu}jkIpQiVAEt^HCe}+hDkNm6oLr;J^Ya6aoTY`C z&ZRg>&}V6D?y%`-{)3XOKSdw@NWL;ggTa2^>(nRK!{p0*`Wu|L%Z%e!6Hu+s0Wa11 z?cd2f*W$C=$NH~JeZ`F=BWdMpdgn@w!7K6c8iqUwzI{$j|N(kIi!F znv+j@PMu&qeR5(+*}D)%XmyX}tV{;tLMxdT)5QdZg{G#7ssAdAr1$tPXm^QAs!uAYZ20GkJz`BV5mU#9!^X!Mt~X03 z5PU^YJcj<8QQ9+N8!QMc`(IhmrH{VI=RLSG*z-9oXi-!-Ea`OEm%qhn#PEl?jlDB# z#&ag2l`w0m+m+a%&fqt7=D(wc8@rajhsr*Djt4}IkmBv=kgBMvSP75FHvsftrajG2 zObjA2r+YAxI(%ca=GLLEpgm-4b~PFDy_gBmecJAXUvDpLB!r%087(p^p5$(U5&;&L zw7f>BKE6zuirp_&%NjE{`8Csy()es%;o#iwA`~_9T?gH$q&Fv0XNa;1&L3tbWY((e6-XKso2#kG!n*nj>tr8kR7h6(OxmQtw9@ zkPa!&2WwzL5X$dZw=sDj_kB;K-Zj_Aps&%vc~Exat#ZlPLUH<1+B8o1#*Pf(AtA`* z3J6(K?38De`d2webU;r=P|OLmdv;_J*VdT-#v)w=@LI*rA1Vvm&+9n;6J6+@e8Yz} zo$zL4=YjYYGlFP9`8ry6RCAsEF)#C$2jR$&)EY0E!ljc>fXU)BE52ldqi`dALgFH4 zgUttBd`;q}s;+@InW^t-YTW*-6_aXjw||A+a*TMxgp{>?96mB^cshygKT_0N+$W8c zkN#8hUPHtUDw-kTUnFh+Rl)xYra-8#hq`beLZSz4j({@x6gDC@+(we?!uk`Y_iOo1 z{_TJDzSot2LbkkmlyWl}0+cFYE)w;^d6_OECu38=KN8P;M(+!9Z$LCM5M`(F7ZqrL zZ~OnQkk{`FJ!GUx;%1rTe$1k2Fj2t`q|IJ^k|V>}eq)xio_?si=LfCRcl>&%__+fZ0?SHKnpY8GQQ4PBfeyMCx@WI;c59>dM* zX}?%dFqWCC_ePLD0dQUBTB7J%SDDnpM6&n)vyCF!z_*yvsz%d$oFClVhkfjBifi6yLDhdygS73*ftf zIP+o!nygWM@N&)`K_Lyeei2S!aJZfIJBB&HQ zpWBC`k-S&j$TN>4B*X(+&)&IaXvyklF0OFWtm6*?R|ZQuXu!~UP+G1V;I`J{gXTi& z-OuQqn4Y_eR!FHu7Tmth2dT>bis>Tq8gaP0B%D7X=%jlQ%l0!PRFk>4f^h46}um> z_zK1#(=RUGV{B}f7<6{H5zJpm-M3uBrIk@@zJJtOSYKTa_qr?OJ^`jHtW+8toB274 zzuCyCk@d5}cra8^#HuehcyHwC_Gi$k?EH-FOTCLP376?}+wU}@+sm4<$IO<8_n<$A z_x#W4OWflqzjI?gy!n*+c~`uUTwL)T5pH2VD4d=$T!ZXTcTKe-%b#9}*wLF(Y}Bv;jP)8MZL$WvQdk<`#UO8$&yEf9Pg*}nu12hlEzf=Qq7MfQ}Z$wq`8TySEL z5!Mlg}^JU)a;^*KJVT4hhA(9A)s*W2JfsSWKIrXly zjA90@A!wPUP+*_?e>%hX|5?t1wyKSO59=Syq80DCG&-6ef#07ZorV~H!6g3?PajC5 zATE|oEuZ?aM!5)rcw7bUU|Q+URI8n#-b!Lv6!c|6`vUF|in~|5T~pN4N(k4q4|M@r zQ7yV*ffW4jXuHd-gn+U?2U!%T`zi>a_~FO;_JqVb z;r78eySDo~Nj>e9NDt;x0;Axw6+cP>e%H58%$fEtP2iuFKb}r0X)l{H6WU=@ZpW1u z@nb(Jk(z-^x7-oLvjKt`rJR2v5w%bZ=CJ~FGliqxz z$XBDjF7Xmj@*sVS^V+)xBW6&=L{8%l4t|{o-+lRtQP9Ja6(>QAWe^|Q`*?9YVr#R@ z;_Myai;9?-^!EBL%m5QaDe2S3iE&SIo#xn?luiV=^9VundW|k{u_^w|u%!{jk52)A zcIz(LNDoH8Yv%zFu61J34=EZxai0y=I*u;?5QNDf!RNDJe)_A>%1qlp&~MzJ)}1GP z2QO1LzVRso--iSPm%Z~#)p|gP<~_xr*&6tFL4h} zL(nshjq@AO+T8M2z`5B#_o?@A|7>|pVAA`q4XBtH@!sZgUIIl0At6rp^ya2h8J1Sk z?X4~j_E^ewBRq-1vu>yZAd3I*IIZxTA$BYy{X1I`Ew>kk=LD$MORr`NE54a%tJ@L= zEIV+pd7smHkoL-V`vwZ9f!H?^=>fuk)6@LVlOEiw67v|>+ zdVvB>I!t6+3Kf*<3|I01M&D1j*witu%X)v!9L8^&)^I*fF%}R@^$XfTtGTB)nM_4Vbn4Xu4UNBGp z<*6ZE*5EiwO(hDOq_Z<3C8biofZbc1Hl--m8xY;*MqP4CXUVQHs{W4y6|>79RI{>J z7qi$ep6K4scadX%>&7hRm3(h^O-PBnp@}g5NNs1-mKNV{V`cq$)WS#Cl`|dO6IlH5 z$_c5TmUmbYtW7ISxr z`-LrNsM9K0Na#C}7jI`Td%uEEM|(gBe`+F#g)2rB0X_Do-s-OMzrNH^1E^@S>w~QtFq;_wcoT)w-yi*5q~1D%L=B?;tii z>D8cUp3|EmsUigMw~2P^#k8fN&1)F~Y|M`>&vq4cTFM>LE^v!stw%Pkq}u5@8;w{b zxDp3nS5`e1=mn>%zoFSkKu+fX=gWeXGV{&f=&E|Evm}Nk7HcXAPJGyZ^<u6A z5O{K%iygG0pP!Y&0~$_6CAhBzOY#b%0NU^Uz)n=^)1^{J+sgFb=N`6^wT2}NaR~4y z>&u=Qf#`S0Ne8`7578WAaKRHM<7MuAjf68wzibkUf;o;ZMy!3PgSFauEM9IQT{%0L zu89YQ*oBgC=jL6yb_#7rORST{W6?>-q?_q$a%bGg{I?6t%Xf~j2+G?V4D62F7=af<0o zV-qq0BFfN@w-|)2aAOlt46n^1_xxDiNnlreMJ|HtXvsw?eJkH>wd%` zW7A=k?AMNajO2D)@;-9`3ZPh13Gt9LB>|U9;b$EsA)KezSM*-Biy2=eBq&t96`~rt z4j3u%hN1XpXs0)Rm)w*urnv5&O_}BkrXme@rS88j*GzGZ<18-PdOPnjlQ1wEW}(y; zq6gC@Aaqs5)P8o<*MDVYBRkijBvG}U(XajUl=N)otA9h$(s@H^JXVRFp0L3Z;uu;t zlcc$4O|BSZL?|EAc+Hl9x=pSQL0xLhZkuVdRB3P6864Ia2G!j4+V3GNEK?c_*6lR?k=D#Wc_T&NGu^VSO#)Wv-S(PBwx_q?IQAh{cb*{_fUk zo3zCJ9^u!e8IHFM$E8IW^YQI16eYPCTUr#V!rV!6G64)nSjBD%s!t zASRX_tE8pys+F5>EhloL{))byO9hvV+Le=KftanWt>16&;MVcHw=37T62e#tEgEX8 zx)P3Y&w>ais*8u%Fa8{Pm0A7tJcb&Gu=tPv{HX^2^NWjq2!!qGUP?*|kAv{l$J$Yx z!z_d$B^4J|SZXO$NqtrIhuL(~+in@p#HoH^H>L*{ER2`|Q6!buug9R|Gt+oOJ2tpK zUCppLioME3New!j`ld|D)Ql3m!oR=tJk`S5&zbCAH%vn{!*|AiUwYfgJ|dvWO!E@Y zYJ;@0zG>m;cpikR4V_|_g-W7c9&}|-t}cXJ^h|bxESH`_L_vN9U&l4Y#74Ti$KJ$8 zg|PrZ-U}%-u4^@j4{OLTKwA0l~nH5#HJYeS2~w2L$=YBfO8E z_ghz9BcWW3svgUJ|E4W~w8v^3 zr7%Zf6QqJc+R^%6E9j{7XKplaHs}fYXH;=9%#0Pj4L_itI$rKDdll1U3_vY+dL=K2z%$dJD1 z(bV(9$^dF=>TF>+1lBOSoyg?Z8j2Z)NClUdhfK1qx(aEyWhfXyh&#Db=T58eUC`XKMQwAaHw|$=j5j`!j|@a70Zdp zsQ3ME3x7E6!#co~g~*an-uY5BnM2D3Y(|)r;q!yt`QD#&4a)tmgM&YKs(~QjbUI}kI` zj~z;;oJOGE3)7sinP8FVOQ+S$&gn(7c(G1ZP&{FJgV*BIWzkMROkEI!_R)W(E%z`} zC>>5)c+Yv|U9fIN9NWrEym(W<9+xd8)w~*;=LT}zEMP}?IqeDMOTYrh=JP{+g#!$p z0En3~+7Q^c&cJqNHh2aY&w@bY)+2Vm21RR#AG^37DdLTV%s`LE9pF-nLU;q>1Br z{XBG82V8FguMLQFdYm4Q1UBYXJU^Mu5%c)3%4KqHl;Hv%`t3^{-7dSK<^v$D+`&gr z9~wgHDQV*Us#MVhs2jiU@8L6QpsN_?^&6K)+ekr^l#tL9gDSAusD-W*1(R*xffd1_ zRF#C}M`);up?u;;;gBDq#SaEV-_wIR?h-%qwgQ76@^st(e9>Obc#T@+OqY)x06KXSLD5^U=!FU*o`-8Js}L8b8P@pZ)fh-YRwmThAz_gcR}P^ zS0~w+_uNMH`Or3`z>Uk$iA~SrndApn(&@??*4eKcULQ+A^d&%b}XZ zX%CnhX4m&6Pq773!u2%yKUo&GD+YYgX=xe2vTM`5$^_TvOp9AMy?hGqw`ej?@Ckm7 z{319Y;3y|`!Q|sOS*p9M)%FU$iO!n-y>jR3D)@AK)dskv!m{-w0@Gz|49CE0i+IGZ zDZ?gv`62c%w64eG@p7DR(YaTfVXxUnx3W`GCdgPw-*yy8{j86%Hy=*jAyB>#5m3E4LNoOsqrN~Anw6Mn3VZDHV(7s@`2 zyX&{b?21c}>-Qh}DSW_$>r7Y5#zdi*89kX6zH5vRBtNbo49yi+w9D>ISXTglLebr; zd8^|7`ULH?|9@n=G4#RuB~2_zD=z%`wD|{~y0yupDhv<74kbp&d1OHn}mXI@Nbf4a)uzQOwBKSadGummVAfm#95t#RdWg7FtN&` z*_Qh^O6Tgv3QJKYTf*9H1S`K8QMNp&I91LMQ7Q?tin%m~B|;wC?mM3d6gNH`fT4iZ zXUNxux7y+ARb<9Pn6)fi=u)M;nBkXtc<^K9FIhEdu`&?61PMZ`ju^g(nw84 z!}VulIX{%y9BBHfdSw*an(bWH-L)<~6*rV(_p6sZ z*L^62BW1F+iptWovs>1vh`!yur!Lj&Z@+#DJ1viM{Dz0X>mw=jLZ@)JP=we^ zt=YroExtpSD~5qrQ^)H=IL&h9c`=fbi@UVB@Hhe6o$JoyR7VYvv#e0lmASLw>gW{X z`|quX6S3B7MbvWZES{1_G{41q81s2_a^_&;J2M?RLoDQ=rmcINQ50homeD|ful7nM znXP`d8v+pte;uBAJpg#8J z;K6yMCC)`V4so{r$Gq+_^-ydlTgAfcm4sa(*ul^X(g=yQf-P67QB!S>2jE~Ze1$4- z1~a{+Fg#RLVqF6G4n5*zan*k`UF}@|#nVW-oFq6XwLU$&V+*_7HVi=TOHL44D|}g1 zi8az6hhE<7mq*;c29MR+9}AQxa|sh9q|3b15~sP)}U!N@M$m+}-kk->HSlTTSz zx>~O2-|m8giggLZ7kbpkt8K6cXMB5uRdE}2mGRU&VP7n#8VuK^IS=V-A@c$;YJ>+W zVw=spwu_-@Y5QrfG4?M76Z{*MaC`^6XNEnL6my>=nG^$Avm4KVP_!}s>k=t?&I3h#>(3WMazU=MJ;9|3jc+x|SdJwHQ8 zaiq2N77{mGLf|{ULiLNDp+!g!jm%vYak>OcdkKMkr|q-d{O8)dP37dIp%MK$`)r+0 zVWAi0iht#RjU|u%ba|z}XRb=}J@3H|#Td?n?O(m$I0btY#oxy4M`aW%WMDJsDH9k&%2i^+v9uz}B zP!}1=gkg>8)o-N4p&O|w{OAADIrLL23a9>GVeE*jYvMk)HQoqai`Dwko>am|pk?o3 zM?}O%-%Zro_dR9A7YF*NACIRX(!Qby*BE02tECJ8yF1>^^aZtdpRD0vOfmP{dB+(n zp4)6Em$!r~?U6%>r6N}9b57+de;1VXPqP-B?`M$O*vc{70`SG8^k z8}Ep_r%TY#S|YBu$4=#!U-DV}M7+`3eV+r}GP@SRSoHb3aX1(bpP{tEQ09eyf>6@) z(&eER^Vo%k8GQ}-5x6XzUYEOTyZo%ERX>X_iFLev?15jVkhu2fNRI?UlFRh-)U(n* zdyyi5y&`Q-__jiDZk!TO{L`Bwosk!xPF;mO%y=u6Cn~(|HjcEG$8l-z2==huZ`W0i zeSTqol_w-{WqWMak(SI34Xs*$;u@gd|JM98^AIh|U|Vk)^0ebomj6&Sv5t?A1K60f z0qX9}L4Yr^>4Gl#N;%R6({=yr&`QY44xQZ*@!4j}rSak!EH&i+ z#R6=8MnOX}IbCgs8A|1exV^nq-j>=ch8`vf8CNi;-o>H~*I(VO3<{)==jRv7-O7_J zGg-NGST!uZK_g83hXHWeAwv;ND7~bi`Meg4$dy&6-V8Z&6W<2M6%dbF9vX@`>uA+= zqTw|^j-&(N*sJ28T}?zSEqUGRH%GJ&~_4}3oe{_9ySd`t?w}6VYfPl1ufJ%2WDkYNA-QC?VBGM%y-Jorl!{U_yfvB2&Z-07AU9GsjX5fQ>BX%pBq-9;moBYVN+l7>E_( zmL+VM*;#vh2Q0rX#uCl}Dt#}mh<7K8+%+ekt5

Rz&2QM#6DHJCCm-w+QuF*0YdI z3oF)c5fml|;;rqYPZ>Zqc7$xkl%o`XQs@k8LdNTrQm`GIKS)xKzq|Dn-k&Z#x|aZJ zcw$QTEkP-u;H_?L%JHBHvGKQr?@?}5ZwkIEo3-k`vGsip2|{vWYflT=SAA-F7JvCJ zW(gKdraCP=tz7cvwxfXNBQgLufo=WDZd(vA}6?8T;J3hksRVY%@3 zg>6Cc&N=%%jb_y15=e=^Nnft5OU;~MIV2ZR_R9EK`gS==fb~r+9=DJ@Q=#V(xi!li zq%b&GDH#M7Ihl6C1FnKHn)qdaO)ZjwPb1}5`?!GX4crteas)vTItVR1@UVDPcMi0CAY^eE3^CtwGprt_sKy3Ll12|$@8-kf& z{FCa(0B0XxftUF^l}dc93Vo$DV? zlO{2?!VYM%Z23^AY@br84c3!r1r7o7pkoKJ9vF( zCc`M+hPFmq6VJJDUOoqFCv>dxBll*v^!Ui8BcGqlK_Vj16t3ThQNS`R8}=G!N=}h4 zH7i4m_s94+`t1!#WR`Zfk!(L49+y1)Qn@bGO?tuBGw{BRU^a5svh9BQCA;}*bfW5e z<14m;2k4tl@?tDrfX?5^CA$hs$9qC2U)pl*DWin90{}Mw?~NiYnS%m5urZ|sy#W7l zd&bA--dv_nVFT)I$IG7yv9Me@FPe2_u5(e`L@o%TTuK46kkHRHknvr? z5TI-BxEl6l*gQnqbB2L(XQ9FAg%0oo4#!?}N?f`vcR#MTajqeA9cuwrkK&UiABe1@4Zrt^M@0+)$|Y_KNioVzc{x1UkTHur34 zaQfg7oXA&6*9`7os3OuyJcQ3UWAJ2n5E|ag8z@#vL-S(kK|lUF{VeI!M2p|t?rmy} zt4&VvQkdI*t<|wjWx*z@i=Cl;awOA4!h591XbLNwi6*}Cat7=4bhEJ5$^lJ#TkySL zN`JrE9L@5im${Ogpk8ESKq?Z3C{t}_h~2AtJiRD)eW9*mm^A(j43|l(J!0V?W|{}d z`j~UgYtYy8j^rQi5cU6qE*8>7{?1eQ}CdGt{+RgeELG72e9q zsB#~~ejN7qGs~p!3TYU%Eaudg=)1MIL(-qKwm@UhtPFmVkDmCnM_}=C(&x~MKtRMe z-sFc1kq;r)*bPAjO}Tq>qh-_MTdy~qo32j%>F`gm5v#m`WtT|E`ovhpqP*hW)(40d zq+fdO{%>P8&wcq%r~>o zeIYL_+p1wtg+0mLSao_E7IuEHczh{M138WVE8hl|*3y2+z6p81Vr+_BOvY$WAihM^ z!?XGvkD_k*cyuJlBfpc*joID(?2Q~t0Aec9KwmwxHmty7kxu_3%|}i3mSBbk+EzOO}JDS*j%sZ*MQOxPw~uxdGxsTuE=XO3cdwZe-{7TfN=u z+!jYR+T`yOvHf~Y>C=^Bi%nJvGvn{%e(POUE~}M?x>=MhhTsQ6$U&?< zIb-0gCJOKG9i6vy0-WVJq*`=5IT^uE%h%rBz~@+Xm-i z=t!KECe|-vo0EFk?}X>uuVo8Q-bfmb*P(f;cn4Q+cP$*Km5{8E3!}VN!>cZ+$3BOK=G|*w7$IziXedvzdlYG)6CCJ+$Bb5b^#_wf7WTOeXxY+Bm z!$W6pA0JA}KwzZq3=ENgpl1_Ad5iHb&prA-(w#fHr1F`GyvBn!kgaX!-dU8^Twj}s zO|tu+5Jr@}O~~I`Skfx5Yjmr7PHTTF#_symr(tRN+|2k-0vp_?d0BJE=ZRiT@aGqS zImHiHrf(r?>6kEDyW?9*{x@~Em`yg-y^CCm);ecbxGMB-p)9J->S4sv#tfq`-0s-? zmNOg=EB;ym*xFt#0#e#PI}dp4C=+sQ<8E3u&Xs;%JJG87NbP5wh~L!BGp?#nM?YQ^ zj6P&}0P&2A%j7Xk2Z@3;N;*~n<%5r zu@K;(!sib%g(j6buJl&0s0k7~;9B<43?RL?)o+LDN7j}LPQk8G7wN-=b6!9=(*6x( z2P_QE*{U5FDTOJyKph8nb-XUSlV=@m7jk+mCDBpTUG2K4Ci@2sfTj}in_w%?6cIW2 zT0&^zA6A+CGb~tr_)RY2fF!9wLHX&QP62P-bzk7ycjLlB%aRLIh$4yZ?PCj9EY5Xh zQmo5o4&!SXsy6y}a2-Uef9t6dNRTH7`SFZ1 z%!q{$9>gq7`^yUR zPVQ_d|1%EY2|#)u&4*(FT#*#dcl5@E%oUf_*UyVYV(&P|rxL5&!G1}*c{W)t(_$m1 zgd*2$BG^u4xaU&E8-O^AGHiILZz#6tL~ZGKua6 z{ugG!kYcB_<+O{U{$$|FrJYDzg}aS$`(WXrQ%DU=T}Bh^E*uOL7;Unzdgl%oB!v^V zcBJ`ynj?lTK~}6LYR3ZtuaGO5aHHKT1QtEmVkI&+$o{9`8y2mWlzy2SL640tffvQe zJ?PY|`bw%#b!@5If2FzXseXgx=Ti#G4Z65>4#P=6U`F5T>%+C#&#&~l96QDy+Hr<} z5OPKv<5p5dQ-NYpg2H)`#uRnlfIALT038_TOD2V*;#QtYB*p z$RF;amrh2oiMFiu;e zUBBO1`rb_SYv-p&FWtl;99~n{zEeuEn^a`5Ut^=8Q&t8&>9oMMyGtu(Vb-B8C)AO+ z!2O=DqXD`=JXbWTOv->2JtOhQ2R=M~v3B8Ivwlybny}BN2mI@lm!yR1@+GUxR@hPB zg@=_2rmaC{Eo*AmVllt?rs+*or;^$dp=NS8cd0!h2CM|0z-r`K5WvjALsaQ0{t~>@ z=1#Q|pq7NVdB{^FhhA4Bwh$*r;DxzbT$P^1Qanj^Qx7)LG~d)7QPk7DSt%v~<95L5 zulHofXu988b51xiGqccRH)m&Ba4utMw+wqXsjnSb@?y}|aCO^o42^eR^&OT3=!B^~ znQA_koZ4VVH;pm$zujzb6G7L~CW zQ7{9^<`56-hL16Ei<3UsQM2;{YVGItGfP&FHe9IjT%pU`kemwk;YbS*1QDEFI&30v zr)AvIo}W@i83On0z8S5m)$`f$MXQFiGI^YpsRSPFxdy_3mYv0~l#Vt1OQ|^H?8ghq<~}M$Q@Fkf zL4wSP8RT_WZ8;X2)pct*bUooox!3l)MbDFE%f3>CNOf=ueOM=K?(I$UxPwg}y|Why zm8Zia938x}{gk;>6;kdq(wz-r(Y~GWVcLD_YGhw4SEB{bmN->Y9U6}1IX;C(`Y&ek z$!P6q)IyHS9)`LqCF!Z-9a%|MJzG+cU$S6j#??`idHg9!SqQ!9l!wSItOTUjnfAio zF98brp3XZp+^TAI`f>zuNP3J8@@5OUkkClvK6zf^Ao%;7b#8eSRy{wSMK^ol^d6_D zGms&o0XJi}jObE0i)yv^LGARefLcAJ!6>z40(Ulkh1?W)o87;MQ&x!5HE`b!AT*H{ zN%}V35lgxm@nyjf$+O{;kip7A)6Qxu>Kh83-c9y4A!qL}{f9a+VHTf5uvDc7MVMG@ zYZX3?8X6`&R3+hk-}ijZmUgAp_M0VdPMo|$k3QH^Ty?26P4q{DbI$Om$F^4j&wp?hL+Okw(d6qIKUCwOk()W?-_5GH^7j5L8gRhj(8vuvO-RBo=g!(~cU3 zv3@NYRuRXd@D$g2zLB#<$+2KCx;T;XI@0l#iOO+Fl^Md?GDZ-!Kvau}r3YPESZWtP zj~Y^3$T)PSTJIlhPei6|I*Hi;c6dODb0qlqb@|T{vO>MJM3P@zYl&R_tXj!v#l0W zukE>lEzj;N4%e^_t9o~R708WLHHTYL&CPO!5oUMN(L`;>XYIG@UaL3=JAVJJEtr#w zV#<>*8MBLVoQ(+>i=Mt2LGL?jvb#S=y$%tDHnNou_*#E=&ab>07KOt zA)KgbWwq=@kw-5ArTJfa3lLqRg>ZuANGjv)6A8|Oo9VI!Y@=in*hbUMtQnKI|80d3*{ozYOPDlu-c!x?F;=+2+)+_eN@@@L& z3CGnE^+fbHNdsGs1|Hj$_XdNm36+ zz}!tI3J^yuD`o-E?o)Pj5W;UZ0>kcc`!03i!Rduj@Se-_`V;lQEi&n)UySPqza<(= ztvwY_40$(P>QQc>$@zmd!XHcSss26}hCr^O_Iq7EeieyqOQ2=l8d7YFCm)J`J(ZBxllS(V)J$1$!pWZX^6UQDZjMhX)yH0F zaXJN`o|zy-YbBFt@Rgk?&-~Opt{aexqW+n+yG)!#+V`5vHU35(!vEEo9Pv%j(s zD3Q*M_qs92>9Gk2_^HX;h`l*r@9=!!^yJ1-!=~)llxA~7d>!pv2h}9@C#euD6!is< z2aLj-DDxsmC`ApU{%T@ka(|xY4Rm)B>e&rYAo~|1<)sc_5X}dA>5kS6L?v9?O53&j z6}1=hSU2TR(poPsr7`v}*8Z}UIYq7J``?!uhDZC*)jphDr$?X4R0x6tmN^wYL(w^m7-*si_%mVi9%+CbUP_G`0G@yAe^IuqcugNlke zP#-x}_I@SzwyF=qk^k1!;Xx^%aej7IW&`Kh7%z>=B*3PLjhwMH15Ea(XJ@G{l($-! z{GHa7^H=M7A8kKuT$Sw)IDEazUcwjwPNXb%Ldfyh&B_3ag%)siBDjD5{yYL9IaBWf z`~Ov&%JIldHEy*pjz?hzgO1R(H# z5pt#f(PnSQY58e95PUk6Es3|~+K_Ej_Y%1OJ&c5v{@JtE!OYvy@21<>C@j4*;NDjA zt@jd`6i!F}o7eGy0xla03JUXUY(Jg=_k~SXm_^x&-A&nT#z*%Yh>4V*00@%PI=u+@{K1R=V9}22 zk9cJlDcoT&vJ3R%Zc|*rX2580o#Rq1gH=rLXZ(GmC)@n^JXZ!xFx_D76~z&y0xRKAJ-!QzQtcG%G~+H-%rW=7SwEL()cBxvpcD*F?&_?^H zgIsw*#?h@*e|G2bxob$*Fk272>5E$0Z08K;wREXwZ_|Hp0OcorJJ430NZh3qMgPx{ zHz&*E4uO6a{Oi7kiYps$t)i?0|Eo}xuORxJ$AreCAqC#8eHZfjS#u;8MJ{&UH!lz`joaxzKE|PSwWjWk#`XMdOKfU73h1hq^g~AiVwrlJEI{4kq zqvIFZef2&ai!cOpTkdHswdFIs7SAfrAk++?yJc6uC-=FZa`sTFkm(?VrD zYdezK?7^8D&oj67(iap09p9z;Fq&MS(9+iIuI5UvpU*RM9kFMy1+;)KKa!2rr)j!}k{%bRh0y}b-H(&nQn8EK&Ov5ZgH-|!nSI-D? zW5uPK+~lbw$MDB*F)d!KC$UK88RO>}lU0W@8XbYD55y1pX)ntb@idRk-`YqEw8(YLp81vLXt}@iSOH zI4Q!ANva9^eTi0-cFZSwakLP3a~aRdOF@%9)a7Yd|8)zaFOg%zq*`*iyL~BWP{0m1 z8v-*hE5Uf+z~pXupPG)xWX&kbQ7gM$hH{Syw8P3Y%#ImF^^B#IXB1VN-4VB9XE@j0 zQcgf^P9XGJt-j)_Px2|}oZLlp)PeoYG9E6 z0j`lr_GN;Vp4fG&byHES8 z{?{E@%lZG#LpNRfL|w%td3^R4WHXj`I*FWY7C>TCiuy&Z$^4*eLrZMPOR~OhdK`PH z^B9%Qq#-BoN5qQnC!4==uPU^@Fxf7gzH%mW6FEVx@z^%HuAp_FF=JUOym&0QW2m&va63({s}#LNM3fvZrPGoMgeP9NT(J zGmEiwcSR4t%px-*W9Ob?x$sSAl(Tj-G6-n zkT;e7wr*p5h_njdbjVFp3%=EW!L@ch=0SCQ9ZT;6S5y^Ej!QqUHR6TOiOqqp(qGsw z6`uSlwjjdJB8{z$)G{ksjpN}}AaAYVrQM-?zj+U>1Y5tm+^=7o8gi5f;`D*I2=TuP zeDC%QKruwlgXi#$>AomMq45aSoG+v~J&@JX7R^AZ-ey?j=Hy|&IS{h-E(FQ87eAg2 z+bpH}4b%D-QVsuwFpfczi5d4bi|G~B08q-`w9MhK|1=fwZGSDk&&teC+S1y}VW&1o z=MCd+&KEA%cpwfCrh%+2e+@D}F62V&L`d%<#Y5gW1GnxL~?P@jgOBfx#P+SCurzJd`O>iYY z-eTI<_OHv@ezvnl76^YJu;<9`#81{jJ}yv|@43}Ws!~9x%8=X?r1V~}F=`}fVPuy- zZiV|Y4W&Xy$%isO#&1-%SGb)7l zRuB4QY-N&E6FJd#;almQ#Iz5la?hU&QzL#J?=|xOz;lzm{)`i}{}TQP^NxPsJ`~9! zWqwF(O?)gky6oj^wiL%;eJ^x9MLap;7YzWJCQ4ld%?|?&er|BjtToz@CgU3KpG=vI zY>$RMieFs0_b|}oyAPPkU`$61pW^9zeSMXZdM{!N4gM#!lEdZ6=zYA%7kkK~%hK&5 zY)iGU*cK#>$AyHi)of%}TZ!28E{#&d&dM2;%^GM&)R+G&o(a>O*IVgRGTYOK4-7y_ zo;1%j6Xf>svD&U@-OnB@IC6zlUK(LRwTEJqb}{#V_Imu@4Ym}I+VmVMHeyT?dzj|Z zsL(F>Y2(G$Zw7)q5IIvzni1TN+#lB+rUD`8He$+05D4p|Qd7dSopg0WqbOOhcTe#k z;zLs0|( z$lg}`rk7VS-*#E8_-7rzBby$FcD)r=FKdyVwye0 z!lxut>O-v^&6>%pIa?Ti5RRoWuzS;QoGVJ`P$E`EE#|+X$8I-lQ0}NWS+~r%I(acv zTt=;n)4=xf)N7S#T0+s4Cj__(NNq02K`HmV)~L9k%1jAA;YLg>T5W!%m z&!PHq99kitG=p&zKF0<~jM(S=pxoCa4RAR5@N@#Frqi6G}Z5pBslumw_hWI#aK=Z(i_zdH$M_52ZaX z*lXb>k!EOib=4@#_Aii?m5o*LO!4THChw?Rm2KghHba%i3ix!UZ13K8Kf72>JGh{& zi%)ilN%r8Jg+XYerl-BSPUu@PPJBS=u*5m{2&3i;v=Y7ne}fm_V!SY8-R7X2UKhJB z!nugO7jnJ34%A9C?P(ZTTl}MlXF8cljF&KNm0=B5Eghr`(4{PDqVi>ixmBUk3KJjD zwE*GRT(^dk89U+-<}`Qy?zMnUWY0tlt5E=wSDSB1Syi|`CWi+vw_-jFWF*_KSL-@R zVY-qAm9?5P){~{Z&hZgCi@-_*Z{#ywT~o1~9d}ZYkIw!Bc>`3WUC&JA`=GU`mibeB zwM>bIh|AM;3&=nFE?e=65V za`P3PY-fIzv!d=WBdp&eeOb_r3Q{@3*B?H)%xpbh8jF>{J?m#7hggo{uiXsznZgB) zFi>8ydkuJ-fFcSHHXXwCdSyX3_!TpLPU1Q8%-+y!K4i&J%J}NQQx17uC?)vfe$9wx z2Ypwd@*J6aIq|`n9_w;Jl0dL@D`j{dC56u{o`<7>aO9Ui(^EZLu$JC)Hfei`gICu> zJ8wB1UL(A>MdEbSM6)^l+|?QoPX+ynYUcW3IxZ7{n~*;i*RG6qcNIu5g1d^F3-W@1 zWTGbK;AuX??xdHV@rnWUPRD)2{zRKh9%I5pOIS=`XEy8O5QTa$MLuCk=7}Wzb6VpWW z5xwO$q34QBv@|qBXiZiNaM3`{$mKt~m1cs3@hL);zlSrKY*DdbsdAd7*$)3LgykLl zkA#w2g#sG0cQ!ZLXmm?eA7u150CBua{4=!b`T`tI9~qMCbTtkdDC!tIYW&Z*NeDo8 z{IF1(d{RD=4Kj_qtU+#D2X1B6pZM3Hdj%E+2V?8_1Ho$lVS_ZHY6hSuS_RN z{Ly((3h>Q0_KK_T?Oe2gbEYQBj2r~GDV$$cFog{bDL(kGB^v+fYfc5Ua<}a){i#Y{ zP|0}tOGmzQXKYR|)^gh5YV#jtIx?J_Z>KI(9`P7II=U?}E{=Gc8@sl$l1qpRkB*LR zWNb{ri+?BpFl{a_EhX|f82(QSX@o~sC`Mkw-rz96)#Usbo8&o-#l?(`9q1Vt4vyh= zoLaGqjq9Y8{j+tHV7J=NuZRag3{Z)6EIMypw!zpIUICge3T`?qd3{Tum1=zU!&?vc%l4ff@p?7m;6qi zReG6|4e_C2zqjI>tkjZAft)?%MY^d*8AV}&Iqg2Ga<-){LBK|GeEDAxBKobGwl>8! zUHDU7J&nrvKW{TIxs`!4=W&1h2^|)9K}tH%0Xar)bCA-^x-a1v8XBH^-#TO5CJ7c! zur!cMLXA^av`_&alrJj2#x&9@q&!Dzl~wlwAD-lyHrfA`b}*S{ zK$4=a$ntB2=icOi%PZ;3-+#)=%5rgYAD#W{FB8t<*DJN=bE-BXPG_N4nI15ug+|mI zXth*$OK`K3QUB{Uioae}GId&=9zeGJdSt*98CboCqX3j0JqWGyI9N3=1w0tU#EjJi zSH3G{H31fPpjJAHhMIStkm`y-W#c4$4FhUq>FW`{a+aN^<%K*b%+D?T7h6b;^<-9|=6_L7-- zd(hVi64|-5$L6{OyrTONh`I^-3MwJcE;l7YY^-O7nrVi_@ z{8CljliHzI_CEodi2Tzv?f}ENauosEE^<3!0A`lw1k^AzG{lEU0hYlHCrn7x!Xp3O z-&jk0n#UQxqi@$3ho|_+@0v+Fmvg{k4}7HH=HjwHo-{LpyOxR!h+J52Y;I;>{XL~5 zF#LU?LQ}PHD`SYZIr-c>HHqEpH{^PZ3~G0Sk#EbWF!!3TpH+8aeBDS-Xz8U~%J&Im z*c})}`u^w7pX%GDtlZ<{6-Nx9%)>fFYqdW$sdPNY$!fBLrx0c2!jUJs)8yTHFnCZv zUz{?nOP$@#_K+S21iE3l$4ZMn@@y|$9D%nzCBIk$L!yHwQnmz@e5Vd z)1egfz0jH#bp0ymK*Kpal#m$Lm4ZRIYYp#;)Vm?m)6ucN^G=I4cUZQII3^INYFh|) zhcj8NHBPO0?p@=aRHX+1)HGW@9%bVIj{8w_8|&h<&5{~s2O7yHJP%7-5@b}{_m8K= zTS+=@9N;V^;y6tDF*)LUhzYpbj22yX5P3VUR82e1NqZ}7qc?m$(e;g{T$uq$H<CLAG@Hph3|CVF-q2#t5U_jw!` z-_6Cy_1)U3)6n2>IRmtjf_l^Ht)smG>e2e6Q)86;fd_%9uKNN*K5!K@0Z}*NASecoxz$->cGN@bED^$ivt=#KU>H0`WF~N=8A8EH^ zTg_7GCpY_yq}4rd$Ko4k4xJ>rna|9vQPOq&3c5T8hYKD#s-|!~obxMgJUqm@baNw2 zbRu?|Fp4SOg+aUD+?I%Ev5f5v3we^T24ryO}n+lw4)g%0I79B&9Mf-YIf^}xw) zB1{m@D}h3wo&8+a21=S2xencjL-kmaMEN%VM%}_ENleOi~2hnAlyJk-}Gx zsO8kfO!qu>&-CyImS8KPE4duAIP=+!F$l!^h8f@rNyE`!h4GFV3v9#eYVqoL?m7^0 zkPg{)Rq{ER89`2mFg{1|7I~0+yQ4W?@a@<9?g+8jIXLf~y8mfV;pqbQXj?+X6k!Po zGIwt(ZnDgeKQEKnn;Tt4%=i%FA}$LfalJq7aXWL(^lvEdT)&MPi{U#78btcyiXUhO zM#3TzP3P3O{6o|Gq+u>%%^2!cT~T%}7Macyk;t%RG#p8Ac@G-&YO2zIziSLDS4Xl3 zte5?RN@&T9!%C5&jL@`9e~(5kATO6(z8*>Y9Kd!;El|MeVkaP=PrxH zDc$)og4(bls_V6pez^&1;4}7jSrg?cE~I--^r5<`Ewev{?`BxdY3~Q>&c&5LXtEZp zXmHx{jL$A+wQ_B-+41F?`|lG^Ma!N_W_6d4lf814Yo6a zEsRk$Mk+fx=5n&|guG&4Hk6um<_O1h1w7Cfiz-f+xzqJsj|iu)w$Qog<(9uJF}&G& z;RsCaLXktq`N_eCoo_2+N^kEb5Ev|pTuhs5>b)L#?dr3#HHRgc+cm6yNDL=yVp8`d zQe%-`D%KO}Smhu$U$x)!+_~uSZ;Y`gAklVsm~VF-S!MU#$jFJW|A1VxrR$dM9hTyb z{;0+&E9>Y_cpKjC2j`ONhIWRAWad{s+1xewhuI#+%znv3BWesBh{ds4B7gJ|U=%3) zfZU0#0}w3ve)7KYmTQ-djScsCKlEP(p&nas62}{A^zbZfFYx>HW-_;pTGHk*`WpX7AoY&U+! zIH>7|fwC0W9?025Gx*oe)k8%mQx5(cO3VVL4a_+cw^~NOlsPj-j5pLS8G1U6u8=-hSe+gV^Z9P_9&c`IpJyG= zS6E+N4My$CB%(Sva8V0yxT4W)ELXcG6d1BCK>e7w_?dDV5xeqWQk z=#1~i9HSw;nKR+*L<}9T!`d76fo#Y(f?)8>dU*1mR&tY3`)TFXNO1TGCZp73U8+T$ zo^dsjWtLG$X0gP^c$vkh$U;f&QZMcNU~W>|iwhD}np-`YGf47C!RWobTTnndA#w28S!bF%=CDGZJwNH3=}}v))^nq!(@I+jVHk7L z?=M@PP~jToapo8w&B^hmUZEC&sIhwNcF#CeoW9dvN-*w{OK9bDqu`ViNiJlFU>L+u zJ+d9UGGe}&vSnMZRqpj6HX`$B`=FRRJh-32=D~3`32$1 zgU_zhHg5$^!xknu)mN8-2w-!4!6eT>)%H0WwVrKE%*mmj^+F2U*01Nx8-cGj^+G~I z7JzRe*2JKlb`^Vn2vmJcNGDlZOU$}JNaLmBCMH2>$6La;fEoWHcTg($HiBGHgee^Kc(Ru;k_{OWJ)*5hl_{b9+EKsetB)$iQjHd=~923 zY6Jct4=T>OSExtiw2BAr_$@=iZFiM+6y@UiP6*?bd*l^UOVa_3#Y)kRG)B*V7zf*^r7vCz};66lkFD-ns^%dLW)<6C!K(&~3wdjpr};~vQI zmYlOXL@>zyo}$v87O{j4^EJCso<{w5!j?1W{ITWV$Wu}AXItc$m_d8wIPjW1Xo;mq z6W^VV`d6t){Kf2z0tDODEq{~#E#kY^Ny2G6T^lT?TxmlavO=otYErpQfz1C`-l&S}f*u!#6Ln>Y#J@t|B4sLWtuM zQJb66%Yit!w3?Ar=03A15o|4)LATi1Ah+hVug&sX{%$<2N=b)o?5V!e*%{nEKtmh8 z-?B0;bgS5qI=n+93K$wC`p&qFFsrv-W)d$ed%~AWp<5Z8ICssnGolQ=Q+1>9 zOG}@d|F}4DP0M$?r*-pi>NHUCPBF~y!&Lqh1-@J|5FHA@B9ZXUvblM+^n)lS1Z&pl zD~AgUXIPpE{Q4)8cGVXss0r{lOX**aPw!cWfS*pY*sLa|99%}7E{dOg^EsltTpr>) zU5pT+I-Ma=|2QIco)T8OVHMB8S+=rBu_+u$cqRyU%H1sBG(u6VfXw)cj74pq&wbn2A; z=Zol+BpD-7+Iu)hIBgKrlLsPU!QFpMg@7nWn-V^e^eEtPDTm(}4EK=-7gv0qZ1);# zigE`O&@x@@Ia4TxF8*bB}Z$LBBq7|<-UQ zT%h}-AMNTw>{`C+f6T7{2V?l62cDSS3W~@Y~ z?}t>(Jw5JDJKlcP>QFLrVBS!ak`(nXP&R>GcjosAs^&JwZ0&di8|M?xM&De17Fyy z7aT+TRd1=ZdvX3|-y2hVea2T04aM>Y895nIIe@=>q%7eAZo=fSu&`*{?`3pv(skXL z?t$C2K&R`R@=HqSIXMZVAZV@4J{P}il7+pFzow=}*uYc3*Jn+-;iQB?443{Lbd`lI zT-qI-F3lb%*ePkJJJR-|{L>u}w|YLqMFF3ClGdmglFc+cBGa5)4iJXQ23RW*NmL=a zG?$KpbMv=H&gYjD9bG5q$v`M7AiH}A0f#A`nZz+^d>(9fYrMGf)%92*TJ*dDL>VBx zZ&^o@<^|+T=H7G3II2Ff`vHI}>il&!s~Ic>Ug@8g&wvlW0bZ4f@lzx_>byJZZt?J! z#zgo)q{^9rjt-?+stYlm(C)nkHzYkBT|gqI8373i1UT|+@63B^rXjwlh^e5U0O;=4 zmUVAm-zxx~QTlWTlyW@niXfMilER1rUGtfkm#FdvjpZp5B>#jB81GZ7JUT z!U1?Jux#v=*Lv@{qI~^}bjQZPH)aiTO4l$dh`1>oaho@NvujNHG?f?=mJ#@yEV zHytL8t4RQ*!XWEb4=m*2r^ny#5LwSgy&v!3rw{M1W}u$Nm9!lVU7@*Nn}6(nP2>3G z;JcDs$T8Wi5b-w|-(Qz{1Rv(l(?FY`s%-*9xj!0t&75QUt9EVCEiQk?*peh#}xJr`1Exx$6Yh`b>19EDv9BI&3^0)y5lTtdo+k5&UuHq75D~ zeqAmHb})s}Kle%0ElB|jc@ z>q;tSYe4_k7vQZ{5I~knGJWWt+{vJ~kLchp)rk?+@7jZFnM=p3y(mI)oyqma!z4{p zi0e5%*NBQLGcv>nT7lU!HUUt2?SHGMd3!bZ+pQK0&`C4{FaebCSy8p4;~ujLT|sd7 z`|NxF;~F>>TUlm_P3- zli|5FFg2dcg}l-m>?gwG=yo-DAK@_3DtZKNZxVoG&cFIEj*Cy4^BXE$<#(6y5~d7PqbjGpvT;g)y*z?HFT<8ohI0=lWmPS_?NQ)TvQzsKuG>cFAB=b z%d?uk82rr3GjD}`G(Uz(Lxe4s;4zpZ-)EU};wjFw9Gcw0yPN3W5H%PdMHxR{6}$t0 zVf?>1e z3k8%RO*qdAh`hVb{Xe6&1|x0;>P{Xf3$MnLF`MM+dBdSFdd{wH7oKHmp{5GW{6)<9H|KFuhpn_VEKdtr({=B?!*>Ik47||7Um}ivpo*UdV@_6wGK#Px?7-JZuqs$B@ML zYsG}eTU~aJC5E`U>mgZE5$*}Enfad^6MLv=(wBei`4n;6Mzd z_7<&k@*n?L@ji$y{*Gt*)iQR!1qAA~y3j(CEes#OImKx{IYb{hS@GPs`4pr^(O$%Q z9n(nqmqIa`)aYV-OUJ_o} zb~<<-59}3D9`2!io@iA&fBNL5dlI$ChLMym5e&3TQzAdz<3i}R-#^S+;c(EPY?{_p zuvxm264H5jbgZ{~G80g{(-?gMSt&nUM{l3p2;cbHKsv!yuKrDevjPi>O1~(e&E~$7g`6`-n(n1lX0^D49HMgT0Y{ zGlk%EhLSIAjWEG?TpAXx=RNbe-v}GvqbJGg=DDCFG6o`TRzJtGCCv=wTk`5M%PxiRSH6HzszC$)%7wzMWH!zyOVfi+vv)t#^EIAew^q9CFuv7>CLV2V-XAcHy0Q++G)K9yviLn*!by`s7i|CN_?HSgpl~n z8801SyaV*cCkjS+LUnTj1}}+vVRI6v2lKMTPWHt)t&20Ti*(6%mVnDF^eFX}_NHL! zPVE9iESCZ`GwxIvtlEMu^RTe?LMkS>X(yIWiuq`P4ymhOCS@OggU=e_?}KmMV6?z3mEnYreg zId;AYHmCuRbyFZORJqvjbmb0IyEe%1xDa5{OO#vjQC9CmUT8Y@YGL=lS-xMw)0{YD zDQ-J_#ZP2ye*Fd9?g@WE%J*%z&5J!V4Vq=Fm^IQWziA~5NjccxNTzQeNjDIV+(Hxv zGjpjGwLZlpPbPq(mHjObDtw`uZ5Y)6KvP-LKKN>@`Wdk~mq+ueG<2-$Qj#s5v3fm4 zQGkfwMOSs|EwI&*3?ijPIm2>Pm3o=F6ingH=O5Ij`FJ?4KDAwbqu1myL!i;Kr?NV( zJ5GA=7I!*(a9_KK)^&hxrX@IW#4EIf$tuitAnWv3K3m&5>ao)WH=ZbNBo7*I>0bG? zxz1Y1k!8wB4ztR6Ll|Av3LFN*!43)h0W#GP)`NuYsF$Ugwdd9M*;0qPcP3@}e4zx5 z1DAsuQy(9WSh>EzPt~W{EjcopWqQJTK+<|-s1B6u|MZTICx4G@?C_2_YbKnzm}AGz zs83jMCu2-95N^(FPAZ6PjbSeDH=2ry=Q%(&*gC%Tx}4Xkov`zZXnv@VV)i*(AI#(p zj2~$Xax$%{v#NNn`7jF17@XwPWtkuNNsHWYxh5lUx5Ga{`|jU?8W?fDYiHkF+Lh5& zUE5`1Pivy>YIIJ|gVv+X0w;gW6YANBPR!aG9M<_cE*A%e^0}4p&&j^R*p3f_otW9+ z`08V#I$6`IIU7p<7MQKt71#ZIS;Uy~OUiauMG2vS7Hf0={ZMp){A+gh_(6vcjko(q zXw!8ytR0*Ith52h1w*TP4{K(b&0(9<4^iOhgSCqCkdR-txE3UN=0tJ>ghYF?d;No- z2oEX?7%KMh(}t(u`HbwxMdFz^@XPubT3*NbwO*6&X3($S_KY7r&$Je#k|0}2VT)re zRh$kZQan%4KE5Eysmk*|4j)fW9_!;TEKxzK|8{&i*%&o4NXhOb&^Rripk{NoG8FrN zdxEi@o$)*)?vD&Sow&N*j!in451VH`xDYW#M_+E(S-Z2Y4ZwZiv;kM-0Sfs1bUU<&~hf-1r(585!8F{>*m*bRlhGt5~YYkDbKtMMMEU32ccJH=E}%M zo#yQQ1gaxO`>o;pbR$N;Ym&dLH_Hs;2dZhmW0A5g%lB^Yo0)jNhN)topr*3EyHO!Y zPOwy|do{zx(H>lcrN6ZQRGvI~~t zwS=J0RBckwSrxzaK2s+3xKm{^;CZR>t1rz@9|rw?n^&mBx@%dpbDw+pM@=<1I;Wbl zE6aCQf}@$*o0;PSjoIJYK9)bJ2s6lD>OS}90(lamt(7c(73~3 z7QV*6l4UktQpOM*O6(@C^*_OD`tI~w)G;j^&k+yoy%#^|e*fPqlq1FwFkYnfXu~f1L6@f~&ow-R)X*iYxQ%Lind&gq69i?aIn<{biP;yWZvh zMWe=-e`5X13PYV_DSnTGrqqUp7H!$Fx3UoMaj1Bf-MKE$kZYyrf=t0&h+?W%j%AOr z%Nx2bYXDa--m;?AxFDS-xf}w)%au{zDQd@ zh0sW_y_qBRJjvnWRMCF=;Mn~lHS#+bRTBOE*Z%1C8%$&s)TpQ)@6Dvl{Cy1wo70>? znP)}R5g48+3XNLdo~XUOFsgYtT~d9DHSK7K#=SYO?Zi_1f9Z^V@A4-mX_h@ zUMTY#1FO{B;YWJux#%U5mX-_xG8t%Z=+!AWU0x-v>~o~orS2A%vCBwDKpURij5NA@ zGRvDsV8Z}38$@<382*2$45H0R6f!_7V%GT?{+YlRflMIIU#9g!GPi)-0K~>KAZCpP z@|pIu6P>nU)1AG(9MB8+3bbsFR)~T)gdA%~G*sF?h8D;Lyy}!K5n*Z&0+4nN! zyqt|gKKE(7n(eq~QOW8+<4T$V%kwE-dY=uL{1zr7y+bKr<1t8(w6MvFq9Gsyhm!%DY>UZ< ztOyqy{8AAH#f-QQ>1pcnQ#fvnzkR^f797&)S-oCdr~?_wWfK&9ojOT8J8t4_NCQJ#oR+OY#SiA1K}poo_rPqNKYu*@2^G9?3z&s7oXsv$AGIHU zAL$1`9pcumOm^x4sO&73cej5P*o9j56o{>=vnWiST1+bh!5zKbE7)$yZfvpaFvuAI2Ko6)* zP7UBe|1KCv#t8sDQafpR`}`$r2^o97*rr9{FbI&GEFSFQqYQIr^c22@(WXtPuG880`j!2mxUR0yZH+byv++shncL$2pEFHxdtDWX4GH@jZ@Fl72uZ7!`p@3;^MA{o2U) zK+Y@a=FP2BT>JAo^lD_amZ|TG;~6km2spHy_<69MES#@mY^|JG2cWyJ@(_gD7gwyYfIm~4>p#}jA*0z4 z0gT^bB#(#-U;59Uo>f9>Jd&r~Xk$SMY-(yUXMXB?$WsJlY}d7ftboRei2Bc7grE!E z`9u*Q$pRta@P!lxsJE?}R+m}ZZpE>{>?&bj@&=c`w|S`o=4E6{S3j&A1x<*2L6QQg zh{1nWT_3$)@j=p(5a)}y+{vzc8jHv__s8wy;};V!&5elYar;Ad)P3sCB{=E9dKH{ts+%&||cXHD$v^1{X=8-6oZGpD!QK+{q>$U7q zss;j#<**XY7ZFjk4UJ|ji!;loa4sQ5EO6Dr1FgARLnQS|r%7)>WUNFJ{j9e6{kTB8pJweb zRL*YhrtV=O$7a+1wH#EwmynLb9M#+A$L2F<_DDDR*kN`|33l;)x&=}Oq~9imgi9Kz zPbc%~JXdvNO+L*sP{P>FwC@YTM5=WOdgA z(ftz%it@;`?BXoGe$q-G7Gq52icUCoROz3uqt~BY7=)I^I0>&x(=TU#+)J*su}van zfI2tZUmyaeAesdA(WyfY$%~;VjRU(7rnxdzi@hRxXK&jIXL8`&&S zL%2)(?cFx!B#2tzg=dQHeMxK~J+Jp{VbLMvQ$z887nzLYqufL_VWIP#_Y00`tIhg+ z#!)9C{%AH~?I=s~qy)}R+O+s@_w{mmIQ2kD-DL$kl@ zYgpa?$acvo zNBuU2sr63(;@)iHA=^R2?}FmWExTFCjpg2k;L9`4yQ|KF2S#$n{t*42+1gOAN`gIE3IgNbyWttC8wD8Su>yf6i8+pm7Y|HGF>?mG`Bo z7=k%_vZqrxPX<#)rz9a6etYXJH*S2i*7I9GqPOsHO2_W8Sj1{EmZw059#lX}OPlxO z2kP;TxFp#?RbffVMn?dgv8gE_c7B5CyZ%Zqs|p{(0D2$s))(kXcdMb+p$cLX_G*RC zkV_N4XYA@c*zJ!Dbf0?$Bvv^0MBoT&OF1~OK9i7;uxUf{R`?tENP&sXTVEPSM_@i9 zF3p7blk>T;T4{1}G^}|wfa?PFr-1&$2JfBkpgn>kkVbJ&bRUT%r$gz{5y~TXo6sKs z%>dvN0wHwHCWj*EnO2Gqr3dnp&WgjV31xzJ7%OxlI0RIdmX?||<`}NR^?>6U-rU-% zvemo1fJ5l|(9L2_n&q|=(Tjl=8kmrPO-E0k+xkSr$N8FV*=65(*N@_bJxY5lR*~VR zf7Q3{pbP)>e(8vt$`RoGW_`1F}Q#{u%y^^_U!Bo_+@AXa0n=U+sO*XixQvYs%&&u zG$RC~Sr)GW;}aeMp$mOHD$~Q3OT|S|LC%+_FnRDrYSBlkuBQECoEHN_B0A9;E7XrL zt|~$&HYU=#{bmk=gm1CxW)^U9KNb5BvXI2hgys)esKR_mXb33a{nV(E%lI#Ol99zw z7SD>Vli{v;`vBX#Y?~V;PL3~7d8^G1PoTgD=nL59{wL%n@DS~e9mQ=6z>R||1$4Bx z#4w!|bw%NOB>b1)<4sj+YD`=BS$Ozo4BGWEIXUF|R}%#lKxwZ_vTgRcw=Q&M3%fNEGkBGT1b(*D8toL6o$()Rx6*?rMv>CcPj z)Agg}{8pt4dWD3ZP*r3=`TWllhmkk>?Ohg*amPnhd{m&a!cULvzv$tyuya=TQf@x9 z09Xx!B}p;X3niGU0Pp$y*T(Y#139A{h@8)HF=;|(* z3Y~~(Ou6CVyIr^&(0`#owZEwIeHJveuP~T0L(KwZXi)d3W9u(OQZu&4zm84%8*ZYI z11j~LujBXB^#~lar|?ktN|aV4Agu7hnu#vxzeY3J%|sx?xCD}!#Y)f;28MDxe)?jukA(ei8J>R}yFT-#6K>alAfYM)0d>am z2tw^K4v@jV@;}czvorfv5}@S50#Xgl9X*JIRgF^?huL}ck@NTHb0#;Gm=3$0#Mocd z$f5Jm?3eS+!R6U6=Qn?uaR2^O{pT>A9VLymvSDzl97+vBS6@*i6tgUu^|iuy2|gd+ zt7j!q7@TSktefmx=6%-Pfl|a&cQ6^EY2 zZIn*oMl6f5T$s6hpaWZ5^aD5qm9ZYqhA!YNzfW{v=cuu@Zpbn-7Wf-NXrRCV`AF5w z=yh#auhNv>?sA4IsP20KNQqM#2B>yrRnFX8jIbU!!Fxk{%o=>_nm3nnXf&($Oqi}N z4jMQ9Os$MRpj|LDM~xk{51XO+24B&W<=5P;jtxUDh^CJF(x{R2uThuphRd(OI#gd= z8Dz_^xR!6`9Ao5FEh#WFB*s_85;P{qt>Hr8+`N&B`Vb~>`U`g{-*F095P!o!kDesv zb56cCMP^~qBmFwAA`@nD#lKh1Xyhj$X7$4ABcJY1YRdSp*pc@{f3JI@P;;~Kz9CEw z;inlbe#PnB-r;aO2h7E0(?yx~0EvBj`h9Q;l}({08)=H?j`a1nIan`Z*6WJ*uxf;;Fz2tnW}40VG_Kfq9a7H=^mjXfi?Hky zT8EZxA22ho+cod6;+^ozmoFsvOt{rP=x=tXb7jcIhA*m0xyZ9~h37>PDYAX!R<+N< z{0h!rV}JvXWJYB(C-94g0jsjGNX+*cd{uT-8x%FI8Tw0)^=Lo^;Q*MwL>C>`apq98{hNRj&^Vu)^Sr2U41b^0!v zIZX(MTjW+i$mc{uv;8#bcD;Z6YA-6eP{1JWP5Epr8Dd%T)Ku&KbCt!?*zb((Da&noatZ|lNRg=Q{Bp-V#osdlW67a~ZReR%k6XS0Zro-#@%yIX<{iT8WE6X= zI|pCLm^l{;dPC+9+zQ0a<t6-@SK?cEz(uiZ>P_c{Uzi#pQ1-|FmT@`czw|0%%98CoY-4RCBLa@eu|YmjVCx zJJ9_k9tHu*6e-ukE@NUzL;S=H&sOGSZ*+NEcde6R$Ku_R;p|x`?@whpdGiYeX^MaZ zIUY^DP;#d@mO)JwuqoyTy>~8~@6a@QUS)ojv}~dG?zPa-#7#!4?&iw3_&n0}Igy)j zCR&w@u3)Op+}84^*{}GF6~bP#zjIh%MIN)_$t@uOendui9oEEg88k<;9s3q4V5%$Z zMPSE=QN+W5Zke{tlOjSjamna1(aBK}P7Z0*MOR9oTF(|y2+QeNvNr9$Ga^U1`>z&Y zk`T$#b^`=P-HD_J0&q1~Z&xNKc|;~c^V8s4?^}6}sm}w3b*dSn^CJQC4t-Iq7xoqX zp*Eot-?b+b4uX%0j-<}9;$r0Rj%ba-Wvz4W?Wu5ZOz?*t@|wEE3q!)YVG@^P<>#{| z?X*@{#OT`O)0prSx+%GYzR%3y6VnMl(cW<|##?sVuM#|;vTek@wAIh!z=d6FGZooG z0u!BM25)vm2Q0_OxXbk_=*Zbp0LKH&*=O~;zeRgzxpE?1^j_`p1>cH9<3{GlE1qm^ z8$kAV6)0gk>JwgOJ}{Q=H6$)r81c?krmh8|&gi2*b2WJx>=K_Gx3x1mg(nI-@pC(^ zY6e`+Wdpg6S9o2cs&elJ-;$4$pj_bxY`e!mLD+eEIk9|+tF7xA5gfe(-d8bWNp{7}5b+D7Y#(kWb5Jmd-Zjz<>2FK3dJpFaYmryt5>u>{m+ZZw7 zleerWKTO3^<&7p``U#C>6k=$mOg?c=jhTOMFlxF!>+MKS7Pq#64@KjZmOozkDW#_d z@A9)q;&0td{F~8*dIC3?<+O4FEN=?+G^3z2R2eRE8uu zJ08>eA!B*P`Uy?dN{Cm(m07+0X83Z}GxSEh#omMcTb>U_P5e#oy3(vJhkPn;Ps>KC zHs)f@)9hjKO7CC#T@H$}4ep=g5tO2Q!u%j}s-di>FBS}+%(SM$CcR%~Jb|G&ho9OX zVcGwl4xl?5)}@K!KTG*Ro_ImyS3$*FtS9x)tPu8E1Yat^MW6(t<`aBVZ-cq}J%*=k znvDRmn6Ez@s%Dtd!L2hZyZP$jvTUV z;O+ar&d*k5pCOM_GCT}p>0X{$TBaDu$c0&ys-jx7TgiRAYUS5ly7$#J&hVsi6F9PH z)A$ewl_9S?laIajkcw@)5X)Q*qoNf|q_k#ek6vZ5AWJ87*d`{Kb}(S44yYM?uEHo> zx7uM{pG#qgB1MBTGxoQ{(4@BV{;^#Yh}GOP0r6EaZrkeI8E~5=SI$%vQO-<1w=?P; zjE8*q^_;Ew%~cn|^?^UC$IioR*C{z+>Wp%ESMr zP@q{pzVfV5^rPoMNx5MiM8V60rJM(}FDnu$T~j9@KH#`SO3&S(Z9bin+%Uj6I&<5t zp0J*rZRRi7w_*VQU74Pp8>uUw7S0ck!fflT*Zj@PF?cUj$f|6nLT9O!e0I-naDc0c z3b8EIEFByi%F9{r3J5A)w>x?}MIJ+FyifSALRcM=XF5GbFY2mw!NPs%AiD zh!pL95t5hw67|F6j)u5oJaCMG|LAat4<=w<>_=<)KT#2Rpp@VAUvil;1xb&fgXvjI z8ynzU^=y~hTFFlh>d&rR@bW%u-$nHP!7k(=>4*9NOh^=F zQBjd*Vz42;rr3&}FFD2cr-o%9^_;N*8if;00J8P)<}R>-FYb5Ws{KbTT+&#YIoZEH z-5K!dQ?*OykU@*_9k;cg;U$`tIo(25(`6(TToFXXXf0w{-|R#_`WDq^1}=`i#`(h~ zhq?#HI9Vi8L08LWoVu!1x)b9f<@J)BO-_7niMs;&QQ4obOH1f&aqy*hm|eQj(gvI# zO*mK#~o-M;wM3uyUKv3gG=x zKq|4Qo)(ho#D_mABnI$t9YE}jI(jf!_zE*ZQu7-jU8BqL#wh=Ma7zGJN47zzFD?cF z8timNw#qkUg^W8F)2Qh`gCxu#YcfgOP^RUq{*DlaGdIT;?MKpKk}3+@KG#{VS)U`)2`V5Wk6 zyt~$rHNB5dVN#t4i?S#Bxd9vvL`4JpKQ9`sqvK?`sVV<#;}6I8Qq%BKtr9pOINIOl z+FEZv!z1_h_vZlWHIYC7L@5#;o_RxkH67su(ooM3SATP74+rhGA!^L8+`QOYzIfPM z^zznmxdR_f%cSU!-OMc}L*Ij$7BoZx5-S6UUccydauS?b9z-z?gJ@jWsn+g4WwhFk*QJW3uZfs+Pq^QT6f=Buu&j@?+lGwzjFJE2 zq#z*7xjgdqqSK^08vM>qvn2K^?)7+qV(i7Mf2=87ORdl(!?a&uh{4q^ucQz;;ykFJ z5=|lSj+HU`z*B%#*p}lHW*%%*4xLM0PSK~}QI>j}FD^)W5|oJuRtGvNDwvm2S>Z^^ zI9b%RBTO?dba_zIELPH98a!A(ybpblwd0zxR{Dbc;YMey{fbzi22bF|Vy3x0#d-F~ zelyh`Vr8Fzb2|Te`sIf`7Ai!Ad9t>8c;ALhebv8s1biN03bb$YLA-~pF8nI2eQJNQ z^PrxG)^H5VXI&|EYn|jOh=*Ac4CxkOy%Bz^I)rY(EB)h8DZ3a$!o?vMRtqD%>m$@B z5F$--@LEkv<7@xh0K389;{6aCa3}3e7YCTd?YNUD_2a#-66Qk0G)(3K-u(rfc_~Ud zI*z|k;WCWVMR)};L+qbt?NeO=?b`7&w^?OtKJ~BMa0U#B7%KPg$->0LMwK_dhL$xU zNP2jRN-RPtVB?Z^P+XnUOmBK@-0zw|EvG@Z?2AWBsfde!7;w5|`g{G6nM1B>58E#~ z>z!7wnY$wHUOR=|xHxy9KssJ?&=Aca*jK)z6;O!^Iq;Ol8%?M!tgl%#FUS};Tlr|5_oLo?Wc4np~yud+7k{$ zCe#>m?@b){0X%9soE>BHO(G^9X?Q>6`TY_Gwq}Ho>2)d|Ie6^C{ygrv4!69E$mx;9 zxQtYamzJT(!5^qjON)ymdALEfwl&yU)J1L?!J7x2=rN%YpX}{|&FZ?9*+Xor`45zM z>=?aoSR1mD@>35N*bgI7+z&-+|D^8$J@eapdwGqG9+%M)#uGqEy?0|BO{fAc`m0lF6SKppp_S0ihiv;(L z_j50JHn;avE}I%TS%Kq1AUOdoR{{?h&H~d4C(5=D+#0am(P2}-9lIk z0!08~c4duRIuUslC-lH#zLh$IPER~zDC#mFS(`TB>0Oj=!#-QX37P#bw^cDB20mC{ zKMdkToYcyJpM~Y+VAJYKG9;1+zTF$t-0iE1i>2V z2!2Y|I)@g(rgQK_nA>Bc7K)xR=)@Qe?YN_ODf!9CuBWxN$>8OD7LGFKM$u2@`{q5K zmsJ?{d21{Ac@c}dizU%$nUb1#7s`bbS4w90y7DYP={wtx2DP=fKk5=e{qKbwCX_oe zF8a`|tfXp$0b8SE#2daPPV+$8+xa}mU?0>qNliI4Ci0U%WgN{N~2a&Vmq@{&X(i`fXmi|3&3;KFM84=^BU zI%Q3YubRL~e2VLOr4teolz@X+W!=!Y7y=U2gQUflw~)UnRw6!uJ>lIT8Vf6964=3bbgS?XnUQA+{cj zRyY6sn#b>w`*Ii|L!fJ7vgv=wL8y*HClZ+ZwnCrL<1;E~BgIsv$AnWFtv4P%g9aXn7nC6jTntQ;uB7^ui%|`MM7MzaGLqTzc zuxgY&g=_MZTv2Zy#6Cdsr1!+V^q*Eh3AFcEzJLE7wqB1(qZhjRTqC>8W!Na(>jMzr z0qZaXwssfl`r6#KnR3h)zXlJl8ormA$yD+K7CWZ>PTZIC_Gfp~^Vie$h_$e2ZH&N= zy?1w#8KRM^z1syym}TDNThNtY$h_vG`I}4_zYVP2b7|D207;@|AiDtQB)gFM%#Ua} z?7t9o1=5d!o>LDi3j}1mgom;emj%z~VGT3BlgJbuZPxx2C2rn!76p?m*2sgTj924cd7XWv8=zQ^sk4?IM7jH~F-^uaQm1pzzQHp}=R|Y@594fk2cT#v*RDn52`Rpn!tT*WB z@Yn{K_Yc^mq1&&Wv)SBz$23u6$jEgYXxBmCM5cfE#ozpydv7y$uDM|?=#F;YjO%9a zg!X}pWQt3u?*0yQ>zi)~zrn$*6ZZl2K0owznWr~R-yI~VSLqgFU}*RzI2c|ovk_e? z*38J^&LdU;=yybN_bj$JZ84tb}1tClI0I2+x%43aXh=0`}~0Wb&`jU{^rFp z-}gY%5kps*m&h@#LHwCFVfxR%3P>gp0xQc_rl2#6Lk+|r$VSFS%@{OWMAyXsOt5LO2q?7|;=%8i!7tpwWj z_74T|j6FRZgP9{uMIR7VofTYHok~feCl0m-WRUYShjcJjgXRFPN9&s;7?@I^pCo7` zdPk?`#fV#bq}y+DpqV}oQ?0p2`@v}Op&|9%!2FKw=4X2S^~?E(A$h66uBB5#^t;RV zZQefA4-Hr1rgQSHt;e$J-eHD3nr*RNtReRX9x_-JUpJ~*Vi^oR-EKq>l8ovZG8ZZ5Yp%6b~Ne23{+19XSm z%ov4v%Np867hVf;;|-wOz_qE2{ z=--pvY`KkBoKJi2-pa0&`)%Z4sUJD6M<;Jd2{>+U-#RIyx}~!cr5b|2+jW0HKff!7 z7{u!L-rx0Xh6qM_r-tj}J_R>L78QxDKs2{rgBh*B?$-*~P zRpxJLJ1-B#>hKY+@?~J2w^6gxQwCtBI2ciPZTAD>4A7WHoAsAEPC z_l0i=KkO0kZftJG+iZMjIDIaZe&V%cSqSrjo)3_9PhwY7qR82Sj4l~*f<}EZ;8GS>pZ%xxC9Q>fu*B0&2@C8PJ>|W zseN?Q(nckpr)VrhwV1l<%#|O&SwGHCRq#c&+|DkB4U2$8PY;gEf*WNH<~mS>URN$y z#DympRTr@tHG6gU<9t}}hA{`%*K@FNNX;oga()%Xp8A<0+`-!YS+4p_Paib!>9@&= zG`hBJs>`d$t=5t2`Z|YB{Zw~DJs7aA0Jm|fpm)O#>E<^o$l-VddCZA#e65}S&n_{x zi{}MMN>~}d7GnF}dsuj_KU}sCi(TH9l-!@>C6N#rYy{`f;`_(x{OY$Lr!zBpC+d8g~R-vvV)=3ywJEl$vXw21imKTRFW1KiWj7Y})G^$tf`>Ae~dNx^}X z7~_kOCcnOTw^KNOfdHQ;>1WQT9UxNvU`3}^7^CJsN?6HgpHN;Z-MOP=Xywkrzi>{@ z=1_8_s0N6OF%eCtnY3pj8+p%1aU{{;#|_Owi87l5ahFxMc%gA_Yd2pWy!LQniu5H6 z^W*!mJR3}*z$YNIr?XwzOGG`akzDCr`bBHh0e(tB)ylq{z>=VUUP_jb*3+r;>na~1MCz~gB?@PM{ zN?Id4Pm}haJ=Ql?e}vt=8EXX&i%B+!{7e1g%ZjsFK7KjTe{vmP6--R1fQeCWR<|`F zd?YdJMU$r`g}@Ev*=0_{na*m3oxh4p%MY@;S%E8gSqPVjP8wjZyH#=!VNf0zTukv&k0Q7(_eX`s*Jz(RPauAv2kesyx1#U5s7;By-pEPsoB|fwHO6GLTjr*l>YH#`1YqR$REwiGbBY7Qlko)vf{-X^A z3g+<#Vkz5VXuB=FU?f@DJs%?Con-#>)3|JD%P@(7CF#90B69U?CI`F6REUKa2x!(- zqEiflz8gIE=k;Q$;YKGb#Kj3-iphbuD}jeq3zI2qqM(o8)>~X}kP7JRo_QlSXWut< ztc|Hs(tTD*%seKH1IP(v-T(+zDjfFG?ni2~e|M65L+(B*)5AtK&y8Q1*UrO0$~7GC zs{i(kqYZJJFGdz)23k~zSs~Bv8Gvp^KV)?!6Q0bU3(Jr z5tq^GsixTIuYs{9Q=kG5kNNF{y~zjJ#Mxg~Bc)WkL8))u_O1vj%;bO>KiR?`CkLKx z>!th=6k32aTgCl#g-(@T1pe&_$N0+IE)9K*>Poo;R`??5&=)f7un-A$0SheZ`!}*Mo=T`% z53Q8hn4Sm6ro~}hqgm#6#Ps2B;LPDz^(FaL&P=2BTU#z+9~$Ay`8M6F6%6d4TP%1u zdL`EE=HOD))V|uLb3!fbBsm(hTfS}SFXkgp6lz>J_Q4^xXtB~XFQocs>&wIXBb(mx z=N;9~yfK``Mto)AA8XHoE9=iuP2r2)1XybGB`-PfOA4TBloD>&g-Nq110B3S`RZJe-BD{2I%FbKZh72wqIa_+H`ZwSL7+R8UIE7SXaxs+m{lue zCG2~;;iT(Z;kzdr!B)k4xmV14!mMEr#*)37H8bq+_>`V$hPXJw6^NxF2p+4^-3z+Q zw#n>~5xyj82RcH^GcIEkAe;TRl{V=3DGVq$P&CPCWFe3GW;ca6CSYNX*M;G4b zDYED*Y--}mKS@WUQo#YaSlDB)rdPiLr!=70EWn2rN-2!84$eBU+UU!9JuJuA+=KLU z!KjPz1>`Po-(=IF6l%hYg4FA0tmR^7|A>qKO8PxFN2s~S7%UNBg9h3djWv7W`F!`_L0pu?j2<#w z52wjkNj8cJZ_tMrJF?y^?Cm&wNrj61Hd`ayZ$X)!o|dw*qGvZ9OkRnL9xBnQUK4yA zju@w04J(l}AOTEdYzbx0{>3i9NK2dD)I^A{18;Q^F@N+;Lut!mtHt#}h>%!fVc8%! z#bJ7LW|uq4aygvt(!+ki-RLLK9#29#*TwzbhKm_`{_cMG;2g2254#Y}?3WaO?_MU{ zq-CiV;VExeEyI)zaJ@=SwhCn&cFq+pR@^&JS0=A5v8ch-!5-E@uCJOoywlDK)EHj4 zjSA<3nRG8@AgPb3=1(y|0H~&>7BD)z>8PxuLsZ{C{!tyr@+qzZnaw)xx#?jX7%C*6 zam_c>osp>IW3i$x97?F@dfn6X-Z&UQE&HpADwG43lwEXIZ=js_%` zx`J>7DU7z`2zOM*{Lg_C0;$n(V50&gd8`nehOUlL90YWI#%}nE)p_wIM)LSaWf8Wr zre@d(q?-lByE0||9i_yqHJ7&#S#WT0plz;`3T0gmFZ1J~DSb<>-oWcP{R23%3Em31443qe2lOt2_*E^5>9^;`lv}` z6h#4WT6#npBdtOY z*c&r*EU=7s^}l&(F?D{Y{T+vE#H!W(A@V6=yKhut1Q>$ffpbdk(lE`7x{KEg|y!&~}x=BmmCk%WabN)9lmM2H@Sd}^$ z1i8FUTR**CkYkEN@*Yogn6zW^-YV@SFqxs`aKx=?iZ_;OUp~Pj1x~H7?HFl+TTu3w zUJ_6TPqCbv*RgLD%F4|(84(Q)l+b6+ACk1V4WT9{$A~&5Ltp?-%wwqj^bq`bj5~RC ztt>6=8+9FsfBylD^*QKYIQKu9+tu7n!%If5HR~C15UAz*p?xihBHvw7Ki^k9JM*bN z-Y#V$l^R~;p3+hS-~+w>r#}QV^})t36&X9#3NIiUj`|O}h3d(c!G%-aMSX-huFf^$ zI4NlPi!1;kNO)tXb0VdX-}oRdu9E)W{(6kJ0KR}gbgwd+beSxztY}=^k+RhaQDbsM z=nbS>U!9fK>l4@eaL!rZmuKw&DpMKJ|5Plc69C4iu&fMi!L?C$Vq)T_gZMgq1JWdt zY@pZ#Kw$&xg1vt=$#3@NJAen7oeH9XY6Y;^r+#XH!UEH;&K>apYL+o21 z@Gdx4{RYIL=+ERh$3v9TEoF2Dt+Od2n^c&xYv=7y1BXUaWtV|y*t&?ax4UG2hg3f>$<(A?wpdzyTN1yeT{IvN= zz@P~#E(Wy7FBcT1`p2c&4w_&`#x?`&ImTKFI|p!bfP35gaS%dEIzPir9@?vQ7Ki11 zEre4opXQHSf9gz-;khPxx-0+yr4L*JwVH;1l-^hZbqyAcM+9zh!u{$ojpKk{8YN*r zO1OmNp4Yhx<{}cT6Rdub7{lV6Uiw8{eC_Sdv)c0V*s?Mvx$&RC{Y+=dc)-Dpqcl#T z&bJtwoRlyyFlY&VDpNS9YH7&;pugfOFOSNUL?1&DktzLV2Um*qZ(ZQSmW8RwIK@Jy zflOfTi@(1Y)q2@L<+NQGWK@iUi!0>$8k-O~d^y>?_2~?hl>{s;rafSt$!rRS4eln7 ze>VZMGg0)x!qTz}V5?$}&;=iDC{FX(vlSShldq6Yc<^*%m2?^qY}VG+zQoG-Wkn3c zK@KHaB*}OH_a!bi(^3ejovxhXWmftzSG@+|$6h&Nm{p;Dgum{{fb`1PwhsdBDRzV@i@;-F^W;)<^VI zytDh;_kguXT5s>tmuCUoJ>Zjye*kCsx%hk?FRo#kO;_yWjdXvXuN}a-6zduXC^w#1 zb4SM#t?2b4!GJ$NWpauS0&mL<92oq9`I+v2PM(sARv;Z8I2C;jyT=_+ zm*J~`4(zPK@xlIlDIhIDOuXu+KLm;=H~D6FrT%K)ft_^7LwX!=_VW$< zs*siz+JN1wtKc{F{CwH~=!aPfpI@W$lne5)FayEPBal4qbim4K%XyPXq(QL?&bey2 zC$PGs2}?g0%exR(KfA~G0u(F%>AICt`Ztrl2GwgnP@%-O=$m9a=VJ}F~ zH4cZygWsF}#izc$9%#223bj8c341hxbyR-m^ z-6Z)c>-^~5qEXF$z5g{>|D&wxYK9E>=3!04O3yjgH3;jM@pQ49eb@ zu78JJt=RC@j%hxUbh`TXDnt0_C(&X8sSh8-Z=TCEaE{<{18Whna59TLs?NP62 z7_(Mag^zDb1}=N1@z(AS3;?ZM>@lc0!DzTG`6M<~tgbP-z|V<$%fxSMC;prU?zP>U z0)sY|L&h7|R&acKb5gs&9qIX%?A02)!6%?uFJyK&@}g|5_IUg)FplrmWk`}Zlo^sD ztC)4VPSdbm;Ah%>uCRZ3u0WdNhcKOyITFu}LaZ?@i|#mbK)U*4tBCl%vHWmy9L*49 zben1Xui?k3YG`Q@H0T5A3^*=IIB7RfdBlNme~8CirP2roEd#fjR2xioPGyMb;PSyVD8!?rm!&UcxFgIy?%E2SABVKbZlz} zmz&>Yz8xOwgJ&9JI`yo{H&tj-pi^e<<=%EdrL(@!);Z19J+JUaDKF%>mCQG~XVGtE zq5Lkx&5P~3dPQU?nRhsP>xz|UH29!3b@IVIm_+ChI@6Jh4kh;kbtXbGOuhOXblvaJ z8;#rD8t$({-IvGx_M|i%kAN#rDo<6)cr4JC@O*y-3%e&>K_0@?rZYsA513ZZn_Rs~ z4vv>0NSeoejrWHfxlw?JcyR#Ay)W^ZF&n+X-$-CGHuQiY&_ll5h?7z= zcK0}FYxZzn9=N<{jJym&MPs-@up@E9L2q?Lm?qWic{knOp)+L0wz>Fl{0maHax&7| zF>h0_vT%vX40WTNRv7rPcS~0Jig|yllp|rJU?Zu#qUcO_YYS#@Wx}eh`)VNH=)`6{ zv;H=`we6avfVc&Z>pjoeL@TcsRL8ruBoNn*)hYcvEcd|oB=h#T9egA_k~WMHjIbvh zPp>bKs6*xzip9KyTv7cnt#O>rOd9n6s`~1%sJia$0fdoOco4~v5D=B_Mp~sox}>DL z87Tn?36V~vQ*wq*De3N^L3-$h-x+2^t+yr3tCPmSc!bT{>98ubXEm`>!tn?5ZaPfv$NXk2{K<-w@~$?X zDPFdh+_$@v!E`6PCh?tFb)5pTSe#+FSJ_pKky8g3okGZU9O}E|9s2PpA&i3QZ!cZ7 z1slZNKW=71XUw$CsJeQEGJP@vx79^rBVpSaBeS@mV7lU_4-*R7wE@&{Fl#{UF;=7% zf$X`s#{m9>2~2v7c<|CHiPgdRH`=bKi>W)cg}Z)l!9Rc+DPB~%W!+{cv& z&TkPfXorqeSndPWw(d)jWSlhKQbum`rP|#tQJ%;F6@z`&}RPJ$+G1ZimvO| zSf4kO85du-dUQ$-KE%0^1>S&4vw_(bX9;TR?b+5XSx^po*}QH8aQ1LkIHv5!^)5EbSEy^|R%; zF+iNU>)%|kr{MdF_kU?v$lT#_afvp{VZWVZb!bj(T4pt; zY>p@FU1{^VPHQ^rU+9p)Ve_p?7kY3Ss#EQ@t3JBDxkFVht$;vIW{$!L+i`iF; zv$0oME5W+<&H$Nn@9+ne+rf~9=yEbRwK+aVuLE-9N_&~Y1D^LHJg5skS(_cZj1ixR zij0re`GIJRpBx(gBsd@=eU@pR-luH-Y;FAVrk69=;AeDTpU`QpsA|*E+lbj7tU7Bx z}lPS@egN3;pNstek+*eLKLc` z)Do*5GVUctEa^=rc;p%^W=%g2&ns#YHt9IfXZrF4;=jAwt|e&Up3U0L`(v6r^n54X zKXHp=vrEV6e_tA9^&a|IJrK)qLD!zIb6BBeDXe$%3_R4u zFR;?JszrmnZ!U!lE=&ua9+a(8{|puM`GL6AYFTtzcU+lBGrmo>Gd~yaH=>ijM7+{+ z@D$d7@Wfy=UGVaF(S>iVP*h*y7GG`u!0gpVYQ0|+39f5&L+7+HOm<;QXE_&~n7^dm zeV6v=zjZC=0oc-&aKibYr@$Sa@@3J2&nIkt3}w9!hEDvC(k99zl33O6;m5BW@cfS< z=vOfI4&a5M?|dkJH4vH(W*IMUY!i`~H%e~-zz2JFTyw(*{SV{!^Z)}k4nT|rSYm81 zYTXuj%DcNiMs;6!{`&RnF&%4sv!wxHYN|;2K{-~hn1E0WqF>LQ!>L;#tmMVWw$sQW zEIKBhY|)*eq0Vh6J~7y-`6Xno&Q-#dB~iJ(?*XgcP8|}cT;Yl*B0W-(tk*!cVwM|t zr=l@UZ~MS3di}L3egVp5#j_kQ(%Pp6DzF1ZY1B0|REG^XYAnYJ9Om50HPZE+`nW;W z0J39giQaQ~kYnGBmLBe&esb~v;knhG5YDPk+ZRs`z#z3oZ7PLhcJ@8<&m)%5dRj?f zqpFkSP?Cb7+PT{*Qys&^KJD>a7Y-{so7_zK!?BRAm4DQ6=if~NBO-G)#qz);!-!j5 z`E>FQYlGh-D{_U}Lg4@`oF?vhVt82*otP{*jE3%7et;VUiKj~zlKGHnw(?mtH1j|9 z(p^8~KeDw*XC?qeet+{NYBm2}S}XD}n};tH9c@#4y*}ze(*rB$yFmf_I%EcSk9D?i zAGkT9aS?F-Ek_p$)C@lCFjx&HCC26hN&*bU4!Hl%Ba|c(2P9<|JOLz#Qice^G6AMR z+cZhtb1rIKe|6lib(b^6?-;;TwboN039Ms8{9;s0ORiHG@QT*a9r3T51mA^C=9IqS zYd>H7YH5!o?|smyhaOx;OIw!nmukW1mj!Rqwf%wmQQSiK>*=f{l(Dh*jxInxm=^X{ z2p6N%D)ix@4@IDn%R-gn@9&`)FbbqYF#|#0@hZG_3I`F`aR}STV zzZTy%bQ@y*(Q+Pkp^-V=uMe5Kk(5NSq5fUt(OJ=(z$G6M@j$nP@Yk<*A*V`2ZvdQ< zkl&!-@o-AsBF$5=_6XAMZClgYISNf4y0`A+T3q5*0OVd;B5I94?^+4KF#&;P(MP5v zOH*5e_o+sJnB8iegs6GueR(Ddn`Vlg8!?*ivfuvpVCCq>3KgFh2vF%Gz4H-{J}xHq zzUJz$r71SK`9hhttqHMN4ED&X=Z?4xWV>*Nz{SxLZ+e;w#tj$!ET6rY?50mz=fChJ z?GRk~BoL+E^^}9cah-Q!KV_W&!XARsaqH%TPa(K!IO*jze?vNXT--c(*mx-}T= zoK%E#<4dA4ym@ZO+}JaTHH((ZzQJ6vRDiBP$=SPo>0!&aM01`bo0Cbdix$ZYUpK` zVC?ibnJ$8$lkuI`$pZMk7OJ`I&+EXR@H;S0T=O47;o;d-P@dXy9Izhb$(?YXyHr|+ z0%b(}3!ix2$;bMV5;3k&F?Ufh*Haz5$Fc5IA4Rj&)+SfTB@S+5k6!-0aOCa=87;Wh zEeqqJ{tS6xYMNc3_?QL7-kVtOPo}80!OWEivvC)g_0EZ2lMM7b{3cyDP*U^)whAGi zTev8u7#eR2W2jEqu^y$7QbofEy)pv=q9`RGv*uF6X1=7XUN_w`OXecn;%BgZ^4gu=tC z=YbNoGE@5Q9AtYZwcYoS3@@v3iSHvB^u5-;zL?X*stE`zZ_}8LXb5yvJDilB;^5zW z(7SwZSDGpV-Es!7+W@ddqUjQK$h;d;i-g>RIM8tjsTGpCo3iu0FOw2;f-(q~vs>*Txhd;1>Xh%m!6u)D@1mR;9Sxe|A z`tOhI@G@g1iRA5*@fK~lT6SemNM9`r`)q2q&T%L@J<8KtqV{qp8(^Lt3WmjX3(MFd z8~@sxU0MH7`f~H|bU4s|W-1ySt);%={u~{YMZ3?Fwz%t#Rd?^wo>$p_4ogP)k-N@% z3Q$q1z%*?wZw8H*FBFJ#fX^_R7R2mIp?Ggh1y9(x8kdA+O8y?h7ym*Wb!bv8ZD7u# zzl5??vU=eg`Ktv<71?h=bwhXR*xoOe0OVONwH*U$`8@L4S;!gY-cup9s&N^P;eu(| zWwHXy1H0I!TC*fQ0meKG{zj8_MAis}N*GfVth zzDJE<1_HhJ0TlIhB8SvszAPRPasZ+OLDum=9i1Yi8a=@%2dW4oJ%1iB1f_QXt)kIC zpuMF))##&ZQ_PvUjXUtEdW`QvDS|s<6)Rn;3=9>5%kuwgDJ4n*#|Op)NvS*ms{2c<^)EP+T$@@BgA`80NN9r# zVq;@zBK=(SP~kXP%6uGkdRM%*kAD)COv3%2$}o5pwwUA&s!7t9Nsa9CooudtBf9uvUM0#1M85w3srj>5%|!L@Is!s*kHmegU~>G>{tpLL|or0atp(JF_+ z=IqXPOe{`uzxp`>HwOA>))3geHI7Vd?cvEewLPajvC=(Q3AmcF`X4@byv}=aZ*w;2 zgeW-iC^A`n50-2#-nwbiw0mrP*y|XXl6>XHpc?9AAAWL=NEJuPxN~AgK62s*+cqD^ za9MDQ7=zv?*3z4{2ENU%DLxs`2%xUt^?W_Wo7tZp;GAGcVr1GCHgDt6lak954zuZw z6DZ0S{+Ly}KxiAY*fwoKoWH3CtoW`K;(P&;Alp+N9i3#Zy*?oBf}<4EG19zm)Dwq( z`}WACW3IW$kAkj<(=XTeP`bu0+Qj^15Vm71(9nX5&w*>s!QCk`ow~GhxWMimJ>hwY zJn~ScWF+cu>w!Nv8TyI!D6FVFFh%8>DkM=p$s+bGf;>QB%!OgY=LnK3zt- zHUYa+jwB1nFJS-dZ<3>N5phIgbfAdehydjBY%3+={`p-sVzsj9Sa6@3!yDE@x@HmOBo+0aa+0p2h4mS*BZUuzre(#ab z*8dCSYOOie{a$B2yGUVcH?}tu&mJ?u$^&8j(H$$7veJ}kO7Ic~y zeF-%Qg$U}0o3@k1jBcR~&7%7n$ z1SAUr5m3lUimSy8ht*XDQp*rnG^B3tZnVh`d@W^*ccw^y&N=UHW)*fyq+2j@!lV2t z!Ee?TE53)F&sU%Ob!tr{^f4+nedy`e z?fU03ZEzGv30lXqe1+C9_~CF&V}dA{;$7n7)Xw^Aq&-@?}K}+YiptJ6o5BQfm79 zG>$M_(c~R_+^{Tsy4ev0r(jx#+i$P?+F`_lo?b>CZ}YvkqmB9U9gYj1*=ce^bsqT7+T@0X)mP4U5yl3JgotompM~iO zan&B%`b990m&N?l58IS~9>~*7485{a1vmWMBnlHn3Gw>1xMPw?le0K)SxLf%KhfUo%gCtJA$-q(14cy4(t{B+7^S6C5*Bf0`F>szZd zM4Q14#ODoLMBcw|w{E!|FXC4KpB2b?qd`Uci?vTeKW3Ez#IQHT+9U@edg|)!+!MOQ z2O=U`fI3AY*D~SDPd7cMe*QNun9Yj58)DeV3gBC!&3ZKj%AP{gU*F&p;A>1v*fx63irHJxh8f}R171CZHNb1#-a<&_ z^2W4YS#wzX(gm0FyVeSMWaVyU{eu=zH2Y+*5*Lm=C2j@qgG5ekJtbK%r|^{)*tNcnEo-H=zo23g*ARcC+1hkoP~02QjqBGetog=98OQXuMRmK=%r zS0OFw>Q*&lj|T&qhL1#>nXilrLYf@8tHs*xUI<`JlEDlhNamZ9=9Uu5DWufrNIyC^ z<`E~l^e;j8UFW#2bJO6-5#v0rr!SJ)f+p^GDUGSwUs+7is_WifYw z2C=D*%;xl|Hh1?3t1f=^9rO26`bsbHw7HwbJ3`P<1$qzAAu1!zFJ^sRa_WScm%mGO zW#cxnKxmkL=etcB8mzTpOcRIk zG(g?UVjhe~&6!mMJWtN|lBZF{%*B3%W?6KmbM_VsGq2%z^!gJ2#K4no1V1LyfBlI| zZ`S6w8IMX&PM5-_PAQF?eWdW^eq@+N*=21L@+>#kc>dxZspvsh+DWtTeRq+|cXLB` zvpZvgLl{f#x>%SP)>V0xPk&@nKIGZS*T?;RzDEOQmp5=F0@drRI0hmMK-`JW7|Aq) zkkMvHC_y$=7utbusR})@@n$&{a~6~GPH(HI;-vW%NrIt|?AZUzEmN5f@>6m%6)uf2TM zZAN^`Oa;0*v^ReJVtCGqQ8yp~?|j5L^0j0dTl%Zkv!jU=SDuO;I#O6%U%iqOr|3qt z?|d3ZaHSX$kge(K@DY}jILCgLrtwpp1efUwIP>*(wr3L+wUl`p`-|&gYh;LDL8g9} zyK6h~2H6ht7+r|Qp!w?!V}+~n#n-&AVbj)w>n&TD>*DE)x}7AmmkYEdf-VLJUa*6; z2ZEOnzNcCE@Yi^4gNkA(les$&D1&aV=ci{KIN*fyE)BIO%3AzKC2h9~fp1rj--}x- zOyO>vaH$3gL&EojAD#()m6Lyh-35{-hic5_w0F78{=tjQ5a{Z6TC$yL87By+e9ah9DLg`iF^NyOBM4jCC!6Fv zWMb*h1HB@%-TN zE6rctUITN(Cz)r<^M_+?0EA1~#Xnz{yhp{0LBZzI#7uCui$8mwzO3nTWu$vm2yvXi zCv`d_*&9majEre?rQ_Wd4I?v(UHQG_IHLUPCQ)uEa1fhleS6;w)ZvN=J{BQDjPu?P zP|K{U;w~7D-q@*N~9)?5`41<16I4-5F;R=t!fXp8d;%4<+yywDq z&ZvhzCn+hJmc{3E&MlGK>H!oAWv7k~58Y_Dnl7Ee;(sC!(I0tOia7FM#}{k~qkA3` z5+4`W0i>a7l^TlwI35r>#A5`+Swzwqa^z*rAiD&-uoPX6o$+qt;h7p-MKhKui)ckA z14TyLlogXZxnCI?QmKw|)}v!==LXj2H9V=OHU#*M+s!KWe-JC$_p*0NRzVF6AON7> zo4{`DFT=xAVb&M=#|W2xUft?2R-leC4hDOKoU~ZhYelC1$sN}{NyORl3@A*eZCLA| z{r)KO>IIaIytj&xMP>_*DHBuE z#l!Q`nH~2Aggc=Oeg4#rD{%j5X=w%60?Xxp)L9V&KwRc?k~I$nP^PZ6wG~LDMgdIp zG@6jt@n62=p^iJEmsyXhP#kfZg5Uht*jOnbypM^AnU%dUN}4DO{3qZ+(qN3%*9)O| zuz=o`uhBzx%2Zj)gLCit!+t>^>#N-hsI~zN0R4^C6o9DkMbg&*;viThPlW)&p`>Yp zXgi&xdMLo`1N`xh2r9vMR#usXg-;P}_vI{sJ_Dm+x0$XKhd*IuT@N4>Ss2qW$Oe{w zP$sdQJiz${T2R*4r~cz1fBd2Dt|N((68qdm8<{alyP9vKA5Vf|2)GXP_(kLTIK@^!bku55S%wY5rU^|Lku%V-EF_0Xk{D%C1dV+ zt#Z{ZeE@+g0=TI!ZuWBl=W_*WQ~x)v{2>SAvhA;P3a~;^ec{;n!6ErKpz?WTv=$Zr z6EAx4TRZ9ZmPdu90IwBIJ)M9tspf5)&gmw5tY&vtFUl>Y$8M+n|6YO3m}ICFL^@lm zahMkRQMNqc*FE*WxTW+(z^8U6G#X|GIFc4~g-BpFKX*$8<^AhWqvo1HOds*3n%V&M zhASU0H=r=@KOfNCpTWL`R1#%dlvBBoSKpOcp>wVvLDb*iy_LS$3(cCH3`k z{dBL&!B;zORVok!%CHl{zyRq^Xl!|Gp;^A%c(dc3+`aNRE$w}$+2OR@^+iqYlgEos zKyG_=5~Bw4qSfzQGf4(DA)A z*X~Vy5cQB_P52j;-u1(ed~<{Y=XA=;AQvw3cF%^09aoBgmJAmfpub_|&oZC&Jp3fB z2S*2qMUJ+Oe7SKQmVi#@Fohy82SN5BUsRqw2qUDie3^fIUFzT~KuKUML=E2}0s&7( zw#W@Z;`%_UVw!YHj!lXePIKnPGfBN?4~iQz_sQ~5zX8GR`7o+jM`Ao~C_Qf0+q~@T zZfy}V(2Gje2?9{bR}q(_b&st>CCuNyZjP+fF0Qp*Y!bm$q@(3Yo*<~@zn_7Q{I#i? zTQRkL1}Mv1bXV2hwdMPE5w0L7fr|7R2?`1dRZ3D+2?`2c0SXEh4*?ExB{&;o4mrGV z5|L6tfHZFe6CmU>fwP!~v$CC;vzwu#DU`XbosB7zld+?zsjbsTJLhBAHbKZu>=r5- z&hH&f4V^9QY{^tCY)l~+p`hNfzGdHRsAhe;l>vOqy_Ni(>@E9NY9Jf;CNPwhb36ZY z4irZ&6cibhl&G+Zd&a?%o44xaBj|Ldfq{$5>z&9eGQ)msObjuFjsT69)$|(0Ue%V` zCESG{Rdqg2=@(5+3lvU6i`lDw=f)5X@`o`D7I@p&n9Ajraehxp9t!zBLcoo$Ajx&y zM#lML*66j4D9Lr^@wF8;9-cPvKMf(quJtyr#R>!S-;IY69|s2~Er6cl-wlSl^=_}| zs#I7M(l&qqqi*08^B*66T|j%K?S)77@B1kn>+P%Ep#QjZNY287o;@nz>+2gi?{c)5 zdU9gV>vps#o*4dDe{Qr2L5TA#KM>h!MG_7e~Q}`H0>MQB%+bW{+R|n(JK9)gU zZl&9qO%{*|zb_`|kocl+<`gMbaj9_-`={m?*Q>|z|mQ*MUPtP4prcU*{UtvKl zFq5i9YNusCl>Hjp!3JIathE=Vx65FAgSrI=J0b*aPvg3U{TTUd!HZA0EWf@t{`&Uz zHYKkCRAHcsGx&UlcP8|N&scPn=ss^jy2$?z>NX2=o>5Z6oy~>t1f#C;j$uNlDGRY!TG3RZctPo!Qn>krxnaHR#HZM2E(ffUSbCf3^eYG{hED9`?fxB z?!RZxeT5>iAM(9PAGJ#*d2s3?Q)J=xI6I%!u=53Vh7*ahA6Jn1wvT*F*%d5pRqzxk z|FBGCE!b{Kff44rcHg3sv_iJUFPZfD9-zHv8Z?@tj9tAs;(MjTOs}kTl9;r{z(n=4 zislpy#z)32x852OnE$O&lA!9DSFKQT`A)IlJ*;4qtzxOXb(!&!234=Cx++FXUjsKT z7M^;i-cuGZ&h~LVd&CIY)dTNsxx-B)C~|$DlF{DV2ItWy)OuBVi zULWMd=_ch2WLpQleM25Ls;3oYV~-@Z!eZo6nl4BqZ!q590<7h#kJFSIDYUz}TfiwE zV1Cnltl{giOn1RL&3dfA632RKBzK@RQQ&wO)_kQ4v;Abr+A(yU`gp43%G>BTRKSk! zX2fFj`s$C)OEe3ZeNLnP5`k3w;9Wddh1hn)+u7Mk>$62rI9=R9K!6y~Zpd@a!O2E&CM`6y@)0QWk^B$6wf-;D({6s~P~(km{WLgAD%!IM?_uZwZPqpNzNh%sl~7S4yT7cg z71;6p_+&_8|3{1@We7`Zaziv3RHBI=d-5=wRJV2dsPglo)XI;x?NB-zjO}Yf0w$8A zU(zFjzS4@Bscb*&<+LYbZpvg$kM1LX&#KG(09i<;rdplqf2yqLhI!5ymG}NAV+o?v zoUx{Uevuhm;gW4xdg{E9I6fFtK?iJw;jfiKj@&jHiH<%7kTC6YvpB`Z*+SI2`+!*>A5k#0Xt`su6$TT^1pZxVk%UvFT`VfO;b*5H;a zJnBhV{a`CLg`9M%gZ0%N3iyJAiS+Xy{U-P@QH(57vS(RP*a?gUO*L^Xw>?IW8+;m3 z*MTNM?}#R>um*gn+R`rx{jySt_19|OEl5LAAUq0~x7SyxT6QThQdK+(8Oapzk_+K9 z;=WR^Q#hMuSadmDK;d;miXY{TNoaYiMVPfCN_(PYAv{a6UD&UCg?Ze3PUVq#H`aBw zR(1leYoFMDAy@MpJ%nl=_e!UCO)j^deJZBQ7tXJ~HDV^KG2nVlemzh>6EvG^G=|jr zYYh-j96@njRZq}9U1{?(sDJj_{eDwxNAu#~Zig~z&FCOJ+&vWKN0T0O;jh6$nk1-Z zl*;?M!NiVI=C+oX|K-rv8b;l?_7lN=uaJbR6u}JNVU(<=wjv(OL8k}PWv#;Nqkzga ze#r>R$_~juZK3sknmV={baba@S#<|6U5mpEDr@F?Z*LW=6HbxeL(+y~P{AA;XB2Z6 z%f>Y5x#Qv#?TPFBCGO$8m4m^r+1rKMV*&B))GnMv6TG)jdSw_Iz{iZ{_5o!i0x3!^ zlUC@_IaJ^(CFum`uerV@_~?i}8S0e*KvC9iwJr-UD^BUuZLrpS#IbvL^Z>-94g3(e z&ft?~%{~^=mULBwQWt^qdHag4=w#|hbI*9N(fW*`kanpyMP86$D_HR{oU7feN|-j- zB0v*ts_sryfe9#-0h~ULyWH&A8qk>TXn1Gyr|2xR(*sj(g9e`0Z*} zHf{I&_(~^v1Y|DzFu(ZXTe>yvdOcpMWVusV*#H1dOV%z;a|iYcu4nxyX@Z&M_1rHD zep@RcST9*pVt#kl_xbX6s^%aPuLIxGf(^gemF^iu2j_h+6q=}pkS6hK%4M|4XB2w; zH!7d|ohF_JlBD@CAF1shU0{I*Oc-CSHyNKEEUEdH1h^l^wd+mX`Qb3q1%XlK`ddOW zVdo3Ra^M-*=guJIm5#A>Z0eW;;e1bq5(2~^9*bFIZ*A_+0a5@m(e`4q{l$Ba(XA1Yk1bZFKmaNRC&&Efgj+KTs=G~!}${*tZs;Fo1;E^dw#ufsCsSB;XTv9{i{484p2`kZcPD)O?ion(zg!*fSJ`v` zo9O^HN>@9FcCBg9uvu3n}EswD7j#}c}^y5qzZ!$ z82+r5XU@OFCy7>Zr_P87B*DiE<-5y$(8caVcudUly0?P^8-rT$Y8SeY$-!(z{n8PD z1())3b-Y|45H^LtQuR~Q8DCQJHF!WM=1ZC2^{)`;c1}u8j+%=rxo*WbJuom3w?_8E zhwk;$PYDT=;#2=bQsEWipU!1REg;a+GKhg`QS;YqF%EWCGWs_jUtiAqJnfgY*^XBJ ze)b001j--LUYyTIdj1+lFsPTBJlve7KVH!nT4i9*fH%xV=mA;UB~T5N#I z@VS~h)cO0VL`XIyIdDP3fgNN`u7?!ZNK+vNO|au0=UY=Dg;3wWe@7wVuNNa#cvR zK~=V5v=as;JsOBWgBi0lMKsHf6Zf8hnmVul+^RPDC)M)%D3A+~{uQQ0Lxa=y^vi-I zQ##RqY%aGbw57iRE6^g%E4Tm=5wU*BmY)ROwTU==SX@pH4HB>q?=2KEZ^vKHoVSnD zyK4GF>o!t59KR%plB*V`ZQsgFWaNZ>VL8ebw!74$T;)hd@H1$al0vINu~;mz?sE@c zj(knc^B`gM@GWy>)pnw?Df0FaVGQ^yGd!-v-GH|>ZAso&)^`Z6Ulgpelo|EMK!vMr zK`(8$YaBcPBBe;x*NOy;*bh($QihI44hDcXupW67j@*c;xNUx}h5YRxaQRDmkN+{l+KV zp^M*rLK>9&W_5f{?&mL^Yp5N$S4gIog5`z;=d#?kpkP*)9_X(>HEEeluRv^8WnlEHJ&&t)2_yPq4cxQ%Cx1gpiNK>AP8>iYfE+vqDR+>P_Iw?d-SCp(D}4uSCHpLb5nHXj5T zvbogr9rP`2P^n%n-p``7(gDJyf#!E&EjMBju!YS-o?Ph?m4!c84~UjnQiV`X&Q~*F z02=LhMfkNpdyY$AckcuqHdmMX$DRkO7@JS_WewqHOPcd(v?Aep*9NpP(wQswk>yIf zy_P?!RUcMUB_M6i9_|_}q^;$_=V8qB8a?_T9pu)*NVnyu&E$z9zxAzH=c%O7k-=*_q96FWbwiJBM^wSXJ=tm=elX6=ew!W?*Y!5VL5{`<>D1I?Mg+% zVhyG4&(cA;VOJYv+pZK927GOg_kgoIY6mk_%rcYvA5p-y7@0c-D$*cfO~xddkBXw}D!+O4pO6OV)J%a-!-@Tfr4`{nO3-8N)^atFMPJIwMy?UK4j#dW{)>EG1g0-pj z?S7EeH-$!67Jh!!;9CywW{Bz5T9fG_9C?Xcl^Tb$T94J}^i0RreS`Ydn39{VCjb?A zL^NC$6P;`R0^63^D1;%cNKVR3y0WKJjL;px;BTsWep{^iV5s;~d`8svHG#}%pM4_- z$^;|n`O5H`{NVej*NMHEU5nOtu9WEJYGd|ei=77)tw?hOOI#sXUh^m0*r&Q*#N0jk z^FuT@N*K&aND&fFhv&%xcDQ5YPtSMxiW&~@EgR7!*Fpmft#vCxidF^;^AR<0r^q97 z5Dh9Fz^{Gl$}2qS2nOE17)cV&$3Nej!o<}i<1sIF zrt1Ygb@8z`YU8^XO6se32OiKf%h}ZPSMHf-Lo zYjXBU6po7ETVfKcn**DSBV*&t710=Hw4csW;srn-L3^Wb6Va*M+ZZ}>dgE*`P5>Bg zZ*leGPbc#0H_>z&&f_HdhhK6ZCMgJb2gQh-Zn$bq@eVbVu@IJ;e4^8gJ#AKElI-oc zSUq&2sqX+2kQ0ir`8)K(JI8NW>W9mPfOJKyp9FGi6akA+dfCF+V?OTf>BC(zT<81W zwFv~9Y1nC;=Ruz{hh+3u_1^FFF%NU7o1L6Jvbn*0dEyvrkDy&r>!m| z4NgI_S7LPZ6c=F@e^tGqz-a0hgYK(8K6D0=7otSkso})?i6Ftk^~Rm)LTB62ZktHY z21gR!i5apCnr9-8xO1HXpz!)n;jAyKs+>nPv($dd%Mlnj#lNy?U*>B8@ah#Y?^R=g z-?o>79bu9}ggz>&98ek%Tu7sB=S$T$#cDsC9E#`p-cQ_f(;6JPxItk>ej4t`X_e9u ztVdqI_e7wX4CM8DMW9x7{G-dT3r+>Tr12b(-(tq1)`Xf5ZT9oc$CrH!0JahgyAkcK zbeGNf)0e(`JPlqPx;R-89Q{~Z2J;>u`+b>652GWbnEiN_y6Yci*}t7TB#Z_Z%$>^1 z1Whc7{ECu>QB<;pf>BvZ(#knZG*j|IEHqyPa_U19xdvIb&2^)wAjn56`LTdpEvin`Q74bPkf)OD3sDk^TZTqJ3sy_=weom8zifWG^&A$& ziK7%(e#Tw$(ewK9TM*9tHiCYoX6Ta`pZa%JCdW%vREggTH4 z*GZ{}Kjzx9zqb+|kwU68$qlk9JJ4*(u>VA=jvMD^OGAAA}8KQ!pyC0o0USbtlQ(9H1gwxqOno%bD)t5QXbf*`N z{v}Sb&nqP>{Vm5Y@GTNf@6;l1qTcjU6MoV@2G8Z<^YrzwM-JRB@a^{{FjfSa_TRc}9 z*S5zavxW84t&GKa-fK|Ds$u5N{d*ES-^%cmbtB-pYB^&{-=TTPVOs<6pu-G*k<*km zp7a*`omX~5pJ7pRbB0(X?x91m@4NZg>)+07yn=(X<2Z*^7OQOqJxR<}jv!=nD&ZDJ zwpF?aX2a7*mJy6>kbh10=way1-*v*~rAbbTJ;&{!!8@v-AfmPOO*m+|<*R+^;QDb< zQTTCOXZ*I?7i8+v8wB3%`Rr_1obc zgf*nd)LRSkDS`@=xuv$@E*9$R_2mG=jndKWv5+2Xw*|zToY7Av;!RAg&xUwKMV$nG zhWaE#2PRYF#EZ8buFJEgN}41E+H%u{j9Y`3)b2*ywSz}>z2aqAY;O!sHw#}OG4c7p zcTX%qSsP|du^`d-Gi5m7U9ER?$W52_ZH8~EI=`MxG|!*(!xa)}>d3zYFF!F$*WsL* znBgpWc>sU-tkwp<@m-j8zwQDa4Uw{puAVVd>zi(!bdS?_F5#+zGwXLFNOUH6+7CwS z96+F3le_os3|eR4+zJr8?z*i{<~`OJdnS!v;!uBp($n3T+R<%cf{`DF-O1_&%b62< zvzvKd)_8hW|5%z2Jw;eaU!SCslG2s?_q@F67D#Ttr>EQGN<~E#5)~D7#jO216h(Wx zz8))7+Z#7JY-)|u`*tH_xIR)$%mXSN zB<5}$S5EMC5(`;!U02M_MfS=|bya0EUSM>&F{o3YAZLD)qA<>*>5HY% z_q?E4du`ntt2mT~$VRefqpaZD`woeETMa zQJKh<&~l!piu#KJSDx_Y^@iySZ40+oShdf0SEi%po;fZ@*S0DNFFUHr%->L4+AKGx zUR*dsZH;D+{>aao|9VwoK}q4rI-D((9TkPr*#+?nKD5}K9I};_mH2E%qJ-)*^^=p6 zu1$4+d1pz9$t{^1t)!kj5v(qMQosgBldf1uEcEW_aPvGF#rV_(6@YInOMG7Z&`VQI z-5nqCved~#hraOPO6GUE4USanpjZ%x?1zc&N=7JYY3URJF90M< zDsGytWV8klT3A@jTBlhvP&gL2w=Cm^eMwDCwNZ)wr|**I#17DwtoU#6Q7Wxwm_@!Q z=mH!0$TGR?^mGf56tuJkRy%@zL7wSHvq<1exD!Jfz_gTxHkt^8i6Q%6(4fD2IM+tW z@eUOO1&&SDDHem1oE*AtAsV#aVOwWhHP_eQ521JMo{8ZjJnq6>nx!eqJ{)&BjMNf^ z^vtuUpMR(gi_AA+9hyjjAecN4!5<=5gqkqyzGs(_WCag?QHA-v@9wi9JVn<+kHC<8F8w~GYRAYA<|=<|%!A$Cs&JazS2DXyw2IT0A`DzQkbgKRS| zlQwy5=m^GoNoBx~iy#BbQjF&pdX1iJOT`BoR5ia)cK;iarJx8)eE&LUB$Yjk$7$=} zeDRx9dnUwE?s+y##QKyX2-+wQ9)mB;|{Mk+bV;M_qf#mDD!wbIjVvi{5RD1lUt$rCle$E28MMVXR^y_SiL0r zSF7cOCU3+hecV?Vlf+zDyS?SEzQnuxc-cQm`Rm`9DqjyAC zieUur90e+*K&$D6WWptqn#Dy007(6 za%EcNF?V%}^g@<#qVuC-pcbW#yWP|6er}4d7Nep@@yI!50iV@+VEALh<-zizml{z; z@Xeb+84qRR*S0Z2oY56={sMtcqkCP^xklk19ZVr27Lrd1+9X7FKMNwIqc561Q2tw? zF?kMZ21yD~VJDLiLPTD`K$kOGhXzb6yVJf#(Nux|Ad(j{Yfe4*OY)>h?O>Zy*8O-|vd+ z(rTjeVM3L2Lx#L6h?8Bx=LrMQUTxVq{>juZ4L8pe6JgprB#p|u=+UgmEC--&Q4tG+ z{B^w(2td(6BQt>1bC`zEmSs0ik7T_>t{R5e4j%ptHxan95&gma?6U34(HX1%W>GQq zKR$DM<%F`Lz&A-3&1r7r^3FP=?3NQAoZV^F!dq6QG(Y$Aeyy9;Y?+h^0k1_E8`&?w zILiadZO+aX4=%mIOj{*L?RpDC2)S0~u-b+^$HOZkzIE;+LV$?!Al)orpJDqyL6CnW z=wj?Y(`!w9CZK?xV37t{Oy!J~P6M=zWqCt*AJ0^^aL8u%t)^bJ%Cbwc7P&tT!rF6mvOE`zm?u7EbnWC zBs}21uKn+|5LQEJ3s(pshB&N})=SV*+&iy?UUab*T)0J^+ei&+pc4pQ*`=t|qf;cI+Z8f zH)@#|6-hb?z!Yo1NCPgz1t^fmAQ^m{yOFq0Ns%k9-y%rHT=L5)sx zIe)M+|GYsIjaoJv`)_6ab@JmolG{SSvIu}D%77ASrl zD3vK@+d(U~tCgvw5YviWm(jx#bL;|SfaonG?lW71uqcz%)YPGdU7nxf?_xq zs)odmwOgQ!(fZ<{rHpx_`U^oY&tX_OJ!TwbEQH8$z)wp}ofDt>$Lj$(AV^`!_MFGy zY{tS()Q=L6?+;GP*J0&fwaf^r^t48BMop>;9)7OqiGJfWGBQf@-b~P3MJc=2{AY|C z_CLvCCLx}H$e#4J2WRNclBr0qIW4S=MA?m>lPv;SZdd*Kd{Jz_f^pyfcqSp@GCk#L zQTnN+r>jemqR3?sMk4=^D^kCkE}bjp84P?vn8i zkw7@8NvU}1nnIsyP|vCgp7K#^I;0SaZCxJS;Zk34BLj2EV{j9x@~o(oxtyN160<&KNd7H+Iu9>MAM?i~5i7kMODQV&ON{THWghj5heVq*(u z?Dy-$j7uO!RfrVDgnz`Y@IO+G`h8Y)v%Wrn75pHm|-Uq$`IC7SAXrj19j~=p- z=(3H>2hw`Jy3aP>aY0SdwH~w(ma-3m@7(sn;Fk1nCR2K0V1dW~W2uW>3ZPuZze$zo zb>gkYNsxdauUGO53nPk)8EsoGryHFh+-m2cYnA8a9`2<@6#?gjH!6)o+&f#SGW2Hc zI`;JyzT1MK9IuQ_qjr>(`$d{d8dnM(IDCMPTzlmSyf&{iX54$w|G=0;|KgP9^8Z=? zjv9NcGB+e2-H|?JWsMATtt{@`rrS1#Lo%~z7m~Az7KHK!sTkUIp(?ktIF__jKcbOl z1|@vU=iTw8FGUubB~8f?zqHYe^%j4YDQiYZf0Q&!x8T2T*vDX3Ko@s!TsW*-fk@y^ za8x#nzoF;x7J`d-%lYTh%lv_hnA3<;wM*o^%*&o)aI17NX4VgJtz+HE*y$B}sn579 zqGgMnEAL$63Bj!ohyQVeztDic)wa*Dr0YdNiK?#dFrL152Z4D8^gB_}7s+~_bZ8)9 zPY$%8Lro8FHE0U~CHI{NW@m>^9&?v9KfB|#M0rlq_P(hRAOSfGEHT<=L z$?yQRlfIl%_S34_2n=!f8rn$@5-+r8sc0 zqIP@zGhO}oLq3NI4fSFuG=FoGq9|kX;}$nF?Kzfx0}z#cwKh&idB%zxt4tsu+~yQA z(D}ZoAE2856b9U1R-r2l4h+=q6&BU+mo{nCS`%dQxtU$;jEPD}RM{@^78Vt0w)qM? z-d*PA`#~6qbgLiSI&h)>NFCDH{aBbg~DMf8p3n)V#Zxz{;$6C z@c?!bqCbfK1ng!9E=LdNqwwvOj3`|N_wz*J?$}szQs8eu+OO#|5U16}{Xf0u?Hqi; za0MTSjjcP9foRWLaCPr?@;~y02)Yjps(t>C_Y)QMCBe@5&rQI|ziM0m)^sHqubiWx z|F69#MLRuszfEs&_}C0tF5zLM!MHQ@<1ViE;Ub3-=s^ zEPir!F3)ajPx1c#4Xph-OW1k0Oa6F?69-hCEKfiPGNJy~wSOv)_j%p6rrzZEZ7w-d zZ3*?y>yI%OD_;k;3 z>wT+6Qt$o7uJx3cCW<@8pl>4?(iOJ!5=&PK;fmY<=Rx<=R=u83=t-SeAiB(iG~Zp^5}e$ zr_VsF&^WW=jj07aGpi4r`uskme!dq>YOf{OtQB63$T~G#xB8tKZb{c#>yFG2=JMEz zy77x+jjD>GX+to*?%rOQa*GLSPl$o}jdpa`aa1f^BYP z@1KX~jAJKGY(eaLW3Um zWXGp{YV+kQ1a{v{xvlE+`u%ua(F^YIczCgy3wBc^^Q*{^fkQ_3JG7_cLE7Gx8!|Up z=hG{(w#}LvU$S?K(+eNcc{9cO@f`O{^2eCUGe@^g6tRna(4HG&_2tuHY4p1;2;ok< z4*k}aE`_Zf9=VNG>`qYDs*zdNI+fp^RPQbQ6aPY{m4}0wQ*KsN_IX){ZX4uRaQV}A zXxKII+iKyDtdr^vlwF*lL7`9U62$LSwz~K$cJTO9JTP?Q}Rl)K;oB{b$fNxjhnID9g}w_5@fD#>lPgdjImJh zKeuz9%dO76B&@HNr+`{2ZAcf=2ZW|9%^ZKh;^IGHRnI00z>ESH>y5_Od?&iQ*t#)( zds6R%Lc*DbwFD22{!c2#14T^#E|bIJRXnwSE6(d3F6DDf`VxOHCQKmSSUGzJyhl~_c}`OvdooXDajezuhj-p&`z3f8B-K*n7+TWTpL&@{at z`JK11*nytb43L6+ZlqV2Dp>Nx!JE7{uf}%9n*bSdUb0SI0fVTmd+*kR{sBKAGPj^1 zHbY#2MU{shpO|R4-AX4E@SBk3ii?XI8(4miy=fbIBqdtxleqE(h*Zvcj6&CUPgux9 zq5Rr0C2R6y*Z_lIhQQobu;*z$tC(K;%nfsjCkB}EqOm+4#;)MXGk&~NNAg(ogYLIw z(U)q79t$EDQZYjAhz|j%8vkT?5Nt7L=YI|TLRwVI_nMC9cvnACxIQH(>kS*PUBo%l zdj;6U^}i8YC>VGSkQcg5Lh^(%2nLPQ<$cQZ(DUA9zLHi;?;&&SQU13I%SV(+Q9YXLqU3_WGI35GBL5< z;T4)fP14X1YKFZL1y!Wp*7qJ7$Noowa^>+f7{5Y}My!@0yFRAkuN1wV#G4(y?*#ti zRjT#EQUW~5z!okpoY~%IQcI(d8Q1aL{jTG&ndsF53GuXNy?|fKNY*osq@4LK*$T@% z61_(E0?qqOj))%#@bY>bCcm{+G@P?JFFeZC!#ONx_p&}e*uJ@F3rBa-;^LeDl5`yF zc}M9zx1>B}^0BW*yhORXchcc|1JkwBz3cWEsm;%F9$A_xMdHA)KjIzT_EgBlZ0*c* zD_wfJGFsk;E$6ib{{W>@{xJ9BLRQ-JhG{P2ac}*@(XO?s&E=d|X8&=%iPMrINu&M+ zHKEA89p&F~669oDEh<*%Y4$ajt&Z2sm~EEdlLsWI4V>9GZTE*})T|7CiHvK1x0|o5 zpzscoP(ic`KUCP&6_9692?;0R(1;*ai#mRfm-k1r*PPcE&z!Y>C0jA%zJ=Ctq9Id* zMI~f7-&MK4<{~Uu9Vt958gCS*uCGuG5eFqn+OtSq-lehmnux+050x3164C2Wf|C#`{=T@(d1 zKqJ5y7#iArErT@#VG+*2Jw`}+g-1pjKRw(s+5Sr^Bep! z=MPS>$*iI91Rm@ORh>W1v5$a9*%z9S{&K~C9O7!-HsoXfV<0hkB>x|R?Z0LgQW1tq1{K8pzhIsyRs+nJ%*l6KzQ9+p~XJ%Z)NTG-RD?`7e8vb__&T z2`WnBKF^XKJ|tcR`n z^IVzrDy;q+^~Xj$N=oz*4SIm>T5nzCuBWH|5z$`9augt-&@#dY7uNtE&?z8Cp$pgB zLHC0sGFrcEtHV?nF7|K~^)b`N9vySH?-w4%-)828sJkZ6?XDA6@Gsmb?vYOfb`q+? z0Fo76BPe3MdS&0Vj_rOy1L|Rmk^zwH@LzmF; ze~lD^0Qdgk5m^Xl>M}oadMNf+{cbbD|5d-6)*7%h{E~8gM=#xs_w&*$BEYdiOw|;l zGb5NwQfTpJ#^$myyi5coZ|JxjymGKne<5hrs!4>7rU&MbSc4E1RMMRqYZrt4viZCTTII z7$C)a?3ZF!NQfBXSFQUQE2QM)h*FXW7{KHF*!%i^fo<>6Z5`Va$CX>}wh_2zf6oh> z(Hen_4f6x=E@@@MtgwZg~yde`&l@oUO(l5p77=^}?<1kSP9+XZwrHEQ#fy67=;l+}(Clo7xDPp&kV zrdI@P+{IA)t#h4}q}ykz4YHy-jBavA{XLnPE_tJzl5#R@2XWw^6RYW}+L|gP-(XHQ zx6W2>7jCx)UIA{&8OdY3@-J4KW8}`-w1*pxaoNpG-j-fAx!cJD3u5T_T}-*)Bw#v_ zlDwO47-lb&I!I2oF78MvUlgPu=cu}*324Z z4Jy{vjGCf~vk1r4_si@WJhsi#*YfK?jT zn#lY%nXO~vu0Dl*NxGl!@Xw>edRHUT9M@|L zqw2auhJRVzABRABur`;djhs7D;$IXVQC>io!>T_EMs+z8VJ;nFp=!s07#~BMtN4UP z_Y*Yz5q@c-1A?;jfJRjfa8VsNqLi-@ z#f)pfOrz-|Gl_=&ZOyK;@ePd1DiwbNto(@N z_c!@KRZU!7{vPWQIx}TNlqD}~5Lm$dDA0X~bN^;zN=NOukPHKf?K%Ce^sv3zhuz`t z{pHh_O!__~+$T=d6yyH(vGF+RP8!XwG(BRTAj$R;X7fFE))cxnoK3dM@Xu$KjJ;Qug$1r z<;pB)vw_wB*}Kq$?3aeW+A-?turK5qH_wv@DwQ<;2`y)J?`_TUa)Ll^<_1>PlGStV zl;6h)zhg~g`C*&)>7m06&Xu(Nw$xkC!wJi87zq<^y%Xz2`ANu?ZZK%Q9d%X?D@>7q z6+Y0nG7@@1=Kf=DRwOQ_MJr@zyLf0uy)rWHYc0n-U(72T|JYFVry1QSFsq#oPharR zqQXYPL{W3iQM-Ach-dJgRf8ZY>0Ts3?FAhzqJj!;J01cwK(KA98cn53_(N1!H$Hke zn{DTwM<|l-&}x<)!wzdB*ZDC)=i?(WXN=qUeRpfKuY_L~0S=^|8gT8SDf*Mc{R=Sln;gaPEMD8y1 z9vEvaluusE(VXhFU&SkHdHBj8=S1|8+k*>AFOG>u_p|L*r?>G6?^S;L2FUg!%aZYc z`B#Znzqn8uuL$phzM^(KYyMp)UX&|rH4Yny9LY!9D$;nou3f09*la}b*}!nviB$$R zh(U`Ooq6u^(4>B~>FBNKhK4WzFSX+JdFM!Wd0=jk;aVrzfbkj-CASEE>v&)@`WEom z^!;t6THM$NZt^I+aha6M`PZ&j=bu_i6S5#RQRc)%E)mspmGqHqIJ~sOOj|)NfRR~u z@%+~sD+~U^S5aL-X4}7O0hXFu=(1-VZ3?{HeTWpJ1eb@aB4us{7xw3t`i(lcd;_&$ zRYkS>I8cr<-zN0Odc(Aj_Fk%7|GSp9Mymw&(m*pQWaSus!OYl|t$|7~f&nIaIbs0z zfU)?a7WPMYjp|x|w;7e?<HbN%~ zRQe~HjDQiPtb2VpcHHE#3O|}7QsR&*a zzsJi5(FP?mAb#}v>Ws%n>9dh`*&Fn1t6Vc>`XmDARAu?->TYfds+jSl( zKZnP@VcJTEmOl)y~S;s#BTtQeM~d=k`_dEiIc)cStI} zMnY1seQ49kWW2)NpijbUW}_CflGSOX7kw;Y1+;iaaGg?o*xz!9zEWhu&rlE{DJs}v z;p|!~o$o%?+(WiQi4qNUP@Kgl#>EM1X}yNp-QA5M6>8N4kq)sz$`F(wdC9LDGe*W@ zsrxVya>hX;NY)OC_Saa|XUfrtd8_9ee(yz^|7vWDq`y!*_u0x2!W`!vP?M@_X$iMg z-{5905FZ(?AW&n*p&!Qibs058Hy}U+}a7j!RJ4bzt{Q?mmTCd z^s->Wt|@%CL^t>!9|<|DmO>pBX83ouMsbF<{sR9YpQ=PxBHcjSH?T(xKW}XQI|PDd ztF>7NMp5@OlY_=CYJP}`#sK7FFDi{eF+G0Ww7@zHvr6iu?Iwe(o6#%JuSSczuk?|u;(At~$|E~vG{5{j?0 zlMtrln7zQfMO1R8r?62p23t%GvtDrJ{B^gaHiU0R^K(F?T5z3gVyZNzKPo5?kEvA* zq^A&)1#lWq?)p4@a}OMTZJ0mWZ)~*~R?qxTLK3&7=&u!Iqn&WLJh6H;zT{;uCJtD( z$hj;R6_q@FK>)DUsEW~qFdRAmrqi{OVJ2VGJDyiO1i;lTJdxpecmz|usovq&y?5Pw zf;POVHFF&N{K`A}@ZiL8H-%YeoQcS;Jb`8AW@mx@b8}+)?IrqVH0gq9oG#z_B#^dm zd89-iTfrHjx7aNBG?Kl^!OR)auC*<3jw;O29+M}nr@Nb@(dV!hMrpk(98vw_ziOZ) zVgZ;rxKH)|DNn}Q9HBTUuLufP$FynAF6XWF9(UlO)^fXcCaB`X7^9fiogboLiNFcpdcP{20m%SE;gs{;W8bQXQ^2mD zFg8O)V5>$_ehBcMxBIgKn6yWWOW+*>}SjQ1*px#h?b+da$=%+7Tps-FomV}2tQB$v=mt7t>Cmv)b(a`f0S1df* zZNFGMoR^s1;A0Af9K<7(mXHuaYd4-q;0$E#XDBiEn-Hd{6N^)A%1Z;eN&&yU&q$|` z_nCn+)Wbvk0<{2>cwZN3Z;^f5Ra94!xcxbLYeff&t zOYIe6Pm{;S5-~RMOnADSWKIx>Ohs=X8JX)mKMIPRD2ikbRPgv4*vx!jh^0 z4hwX(*-K)Jl5?CA;LY0jDS4&u%Q4jw!Pe;ZU^A<@>*?A;b#$yqMbt5_RN#VtPVCfR z-ANdZ=|=k4BHwpDN&!=ER&#;T4alz3Te?b{|HIi?Ma8u(;Tl2$NpN>ha1HJR0tAQP z?(XiA;10nZ65QS0p>cO;G+5(qcV)}j`^D+G z(SqMmw}OtHtLlVJAb9DYzlfm1t87Q3zTJ(B<+jg&``+ZdHJe@8qk&nnq9~YQr9XWr zxZ*)eN2O=d7@@Zmw}n;7T^!Dr@HONs3wMSBH}~L@((oDK$4Tx$y)CQ?M=$7RdSov+ zmyN21AqzIYfT%e|0p%I5yJ|Z=@$f5l&x*h8AwYSc zHDw_zps%H_Pt#HhfSOMjL6_z2G~4WF0ot5H!@}J58GR_Ys6*lxa&s>D%D&29y??{! z@osX?LOv00&wlRn1v}A;iK61llZ>6{>eySYeayOzfrP*amVj>Aj#-OBo)PKvnXNKKjOz z(dq?UEb;o9&w)AIwpZb#LlpyedgLzNyW~GqIJAlJC6C_q>=Ylf{7S;>X6zz$n4y4Z zn)u;%b6QsTm8dl(;1)mn`zD2x{rK61yF&WCAkOsr&lZBjml&+%W~ea+s*eIoU?NId z_T38CBN+y~m58L*_5U6C&gQ+C{%!wikj%R(s;S4+{V)+K=xM_eb-Wwhm%jIgF%!yg zYrF13i&jGWUCA>bkkmPNlpVF$XbkAdVZK|e6M3B~mz;^V)W<~liOcHsG+}v+Mwb6Y z>2^35KSI#a?mh8!1vH~c06tEjc+^+3ivl8Af6!izR>Rki!OKF#*)VnA7uX;c%ZG1g zZLXEdmiFIn{;*p~njZASef_1aesFe=l__FRabI7_4Z zk%H5|B?l7)BQFc+fn0l<{OPA_V#&_X3-@}lYy2=4nl>=B`IcX^#KU}D?1MBe@0k|v zQ)@E-Uf{fwqm{k*QMo6(tD_H(kgpbYfcqIg$yNP3QiD?vxh#LJC1+@TY2;SyNbrp<3n6{Fo?vG`USTY8@bCsgPUA0h zA$cO!qDWyv≷|mCsV61ThjeF1|`(ECc&15iDO6ZjH)cWT+;NxfPyX;Ejh!{tTsd z4wx889xJ)vO|Ycj*|?f;#GQ^1ptuVbkLc>5P~?N~CyVgYwKzhiVw%w;ZXXT=)A2gk zX^yofCNy33U-&KJM<_D@Ax5{rQl6geaa^{P_ZB)->HpjpdKM8K55^DuIf|~u>z5t2 zO(FZt2;EG`_8mjba(YPB{LZ!q;?x9d$&iMZt>rtK=cHGJBmW7A}SVebDLya+in60;2WKgr#`^ z-6{<{q5AdhawYZ6mEo6+)|iSbzBfv7>!G3jw(cFig7PxkRX;_V?fUbeP*zMFFIB&G zt#JNCKS=8&q39CPr|L*}i(fpd90U?E5sRkB45C$I{e^PWMROiYSkl_N={&J&In;>w z<>!k3{e$HhTTS`LAS%l3_t0nNkd5%|D1n1M-D-cIXAeHc_?q=EpSB7x>4r$zCdDIv zR{1?wel+?cLO00C&u8%xxdBtje##NgATnb%pQf^0vOXJOLcpR|?*Vus>ZOqX4bj;r zfFq^zxR`4`|CSdAvJb>r%I4kbmUWUf@>AE!ymGMa1d(Rtpg+w}N1bhd9ts^Jh2nQO zwinYwNT5fJ&+w9-80@xB(Q9J~-HujDyKCCNie19S=B6E%46&67Zg@qW)T2JR9Cw`q zr%U_Amk#i^bv?>(MV~d4c1=87I;7p*9}mPi3|%_BUc>*ZkARC);1-H4PiOn0{Zx2# z-bUloqVEu+B|d_|S}Uu#6qVpk#+NkAUeAY125&i6nzPu`0UF9Xo$!Br1wq)wp0k2t zKpq@|Z0&%Fv>NVGa?He{5`eeSn@i8q{ErI;;_w`(OBDN0{b+Qj}bkp(Za z8ft0(iI7pvm?=BXctmTR34zcp95gWSyU<<>fIzrR!?5VhkI?@9z%44>I_E!GasSu> zcxkW(vJZ*s@uqcR#=in@KuK9A6{1Uc-nQB^Q_WxCvLpcE4XYL-a`FEyF}XH1xvxVjiAB#1>1hboiehF)O#)XG5tz|)#ICOKjO-6bFf^*SpRO}>$T(NI-)rG^vuHOHj2(ugeC+TseSI76J)R|FY$P;b~|*Zo6;T&G2wN z*`=H!We#-^a|FjH>TKk}2QpjBVK?=vNoDf4iW{hlSlk}}?PngY>(-Dx4=A^VR1P*6bri< z6P{zjnti+TbOdeP_#j20>4+}tT^0Wpzas4BE&!MJWYrjn!sowM$*mWSse) zR1WDK#7#|z$DOR^ngeeA+MV&GW6L%?|CU9c?ItnN*3cDv!&6bds&W&f5ZmUR?VUIu z$%Cs*^Th`SzFb=H%K?pZn>?LUe5`!Up>W*IkhL4;bI_gL1YxzSt2s^P!Wtou^>-@L`iPouL8>!x}*u-S4(<#|SGzYDrj>D=*Z)y6TYsUWuYBncqbkY{GU zUzks1+Y*ZT3?5WUJlRsn9|ytbX!fZ^35<3PgK*&erCTCA$^>Fr(GMBs&TrSOcc+ML z^lo0;81dQh;cykuf>+sa@cxL6v-7}LUVQHH>;XB9UM%~T;iL4n>+7n<~jHUF60P3WWHH} z%7x2@?-pf@feFV||1Hl0R{D@YH0NH3lLLZ<6o>;#!o64K0wV0y_ zH$=fr{4`xasRpjEJZi1~cB{E&^E|xBuqf^9MppPH=CVHnair5?_hgT_Y%BiPk{jbA zea6#DIcKXw>Mi+yJxp91i=W{3vtP>=1IWqPnwlE-`rq2oke@i8koXe|%XH3`+xt#C z-g|{y+HBsBAi*LOrD@D%o)Us)Gh~Fsh-sg1k)M_h%%7IVv^?T|ITM(8^^PvvOBh(T z#5l02G@UVqDO5q)TQpNCx6?`2D}V_M}q?X z>9?BFmRsX$8fSvMVLMli_cFEk*K_e@+^4IZ7PF|+8{Z))wxU!&BbUq`w#-8^w++XP z+of8B*X1id`*O=pvO`Q6(`9(N31mZdoTdZf^{NLWD3OtpnmUBppbv$Ra0IyM(_2r=`HHXnUU$*4 zv3^Es7sqRvM@#jwK&QcHU-jM|bj+~)HtE2yVADD1NEZ|${J9%k-ie;+n^lIDzQu^* z8@HIs=7s+CpCUy@L|85ALXk4z?};-@<5w^vybeI1 zK`ye9!=I|NgTg}jFtZC>hdnFT&WmYcpNAL#8ix+5s-S~ks)Gi^3+w4Ft6)H=TfRD1 zXC*b21EdF&+|hwI^Z@EGb{+(+I?DyUqQ4TFTkEPw@Jm*He)~`}Z&j1NJ_=Yka?`i0 z4vo_YI9+#($9b+iT=*-IQ8*DkG3 z9>anC=6Qmmu=OoEP_2_U=l-TuSY;bmu_LEyIs@tAdnYFxav?*}jtLfRO^t95Skm!KU&50w6ddz4%Vi~E1``1eE{@m$F zM=XzS1&(_>aY9`l%aZ5-vmEe80g{yx@DFw|1nu#ogrUdeEtF=dh266eBoX9=P! zba&MWkNS;U3J?_%p!J*j;*sDW=&LE0{?YbXJ}2qw%83*NGsQYMI%+&urUggD89l}# zTe3Uj>jz@M?`rK=2~1b+WFWek!s36;)p(l%ULG%XtITcBNy}Y=d6%FOacruw1z|7{ z4+*1oa;~j2vD-f9S@;qUj}J@8({m1DnQF*N&EF%{7tX)BRcmWS_#!l~im`JyK;=99 z1s-3_@1xaTApP>Q8+EtLF({6Kf^~B~@3qxhA7ci{xV81UE;wT)$;Ihyh&10CK0JrqX>IU7ch4NZMGNsb=sy(cbGH2#q zytx6vyj)@EIuK`~_wlu_2Ai?~OfZ0r>&W(q7{kLHsSy-tfE9nz$U$M&V^vEa@(iap%imq;f*v#cYyZ@7Mw+ zbePnZbdekz2Fl!xj(+xnn7i--QwAPfi8qx`L3}NVHcaNaXq0_;oEzP5itS$T;N)=r zB3ab9)vX{CZ0r_SoH;)T-Z0@n+9YTfw^S`H?ouJ@xoS9>ja~D9fF24jvfFRo@xt@q zn^yTbAiMB?$$Um?J0&ug9+E=Q%!#rUJPg04>HeaUzHlH_eP(>bmse!-qfItQYJRTi zcSfLeKlndfu}kaJKZTIo>o|ZWrF~5{WXyPW1iffYcG~<)&9#l%1)LSci@jCc3Cn7} zd$P-LG??0CFcfXbVyx=pZJE}C!KkwKGTyuOGuu__l_Yld$WL%6CAx$C2aPUvZx#Ym zGk^pMd)(r7ujk2=D3P|dOxvE}MFlGnCuPW$w5!gRId=am%6t?P|6lkwfrV>Wrz?>t z!W^ZW%PwJDk6Tx&Yc{*-T{utN)!3~c>dyw!06lY6NNAYe;(NYE){%gZ!KG_f8>@|6 zo(C*@Yop>^D6oRT$n=u!0adXfWK7WIZ@;?(P>H<>AV>))|bdbt|I2{S94bOnZn?MbvhxkfH5{H;Pz+=j>t~>X>mz zZ?%kspCFC3i3d3&`7@eG%flAUlO{$lvGqZ}njP$Rv&(tcA%gbsTYa|{O?y#U2o9<^ z&N^rWJkp5!VAYzr(dr|k5@2Jn^Q~!a+3(2>v6V>3lg~r#2rm{bse&@m(dGl=%521@ zR`mT5&1kB^a5M|t$?gRB{_!gNvxeOHnhz;xr?8Rsw245IqtfQ!?+)il6pQ1L5(gXT zk5_^DPe#gEeR+d zqU8sWaRW-0)!pvxEJy{6v1Xb|SF|;6@%5x#pTXhw6V$51K^CAlhlAUGR^u$IA~SEj zoXwDA+Z#em>bW?*4Bx8c1-c%`)-GR)FniOnGiriH;3cVSu=^3o$;1(6T@wveqMtI^ z9^6HOV`cUS__|vxZ{1mt8EJQ+&>v>8&SKI{48TB5{F~vlq@hn@sO>%$w6vabZAP>%!=rkQxSeA%QaSm!?^GQ;m-5IA(W{`B`gf~U z><%`*gv*3T;S)+;4=^?5h_ZZ`?dZxfxqexOgCX9cwyE01neBsf1G=?$c!kB@%&~he z-LanIZRc;ouBj8dz>e8QMwF@IJ42m7-7ltZGqUO7!aA4sy(1hq%*Tc#q5nkyuI)h+%P`Ovigpf5L69^5@-5JZZzUrm|Ek^H7@EEWV42`M_;_+NQh&DRQ;BD_QpA~j#3ga7vNHSD$5h5;@t zboac?0LeNB!XG(Mg7=X(7;Q=)&6Ft39l8_>5aeLKLIvurGa(X0!n7B@eo1c$>ND-a zM^S0!91UOSrd`{us^Lwv(PGy0(0n!KrGU%4Q?@XuAu|4$19^ZPs%rM4ZV5DnG)g*G zx;vt+c`Jw(;*N$>w>Glk&Nj7e7mvX}sWxAq>@<;#B2lMJv4nmGt@|HK-ndFbyLERV zt7_aPSS>#t$_$;+-cs`ez5&+x;U1WmN_WWSOlSL%&Fo zS1tALGIJL`ev^DuR{2{C0J^T|16bF?tHT64q!ptZv55}*eEGE|9OdP2^eJ-AeodEM zlx76>bgiaz!!&wW-PW)5CzOgjL~nK_A8j6#d??|s?H|@?j^%(yyhD=J zmoh>2PmHbOkGjPNanXKAojc3k9Eb3_$-ju15ffoDl032)Rl73iE)QbXIw+mUjQKof z#B-~wgeqV|tbZyBFT49mCU_3t(98qSCMsKw>YXm8YqB=sGoxDnoyZB#9m8-FUe%ute~LAwjv{}1yQedzIs#91Q`IS=fK+3;;?O;u?6G&T5U9@=?ZL)AH$ zW4CO3q-YZn4%1t}<1HOs_s3n=Yv@e$;(~9rSPkF1_SU&OMxB!0yh)p&4tu3>cFR0x zIEWP%40(ePf>2SBefPp?N0Oh!585n7v2W}nJN;6}@bh*xEG1tzZL@S343={#rZUjM zPy2eFUBI(7nYL|}WA^kbO5-i&OH04aFI}d*v-}+g*)R03icy!-zc)}BVI!9gZQn!K zGj9=Oh)`s!&J@i2fSt+H;S9!Qqz8vwx9$3849-|&{zq05=?n`S=?lZ7JLg`)pB*hu z_41w{-SVb8!`DpNo2Y>8x2z~qq7*Gl=-h9L<~Pivq6((Ai?~RWvZD+^Qn)U{XhF43 znncwNdEF7`=0Q1@TdtENSC)rjcxl)pSEdXXM@&)F__D462bsasaQprZT43>VKN4}0 zHgZUe%totVV`kbH{H`l{6lC2`uD^^0)e<9Hn7NXBitN*5HX^>mC}Yi*lKb4YV{9Nf z;s%B}GsEVAxAv(YlNOD1Tye0#>-XERc~+IhRKXGOON%}u^C@gDZ0kXM+lL53;nnsu zno}>QSeX{Cd5?W6647Br*B8`>zXiZ%!b!>S@khE&O?>u(droy$9%UeUX3CU4;$bo| zH~BtSx?SV5J=bhw84d^M4I8!ByGbdk_)Nmt%J5>%!*<;O1bIvInvwt?^kKizxcYR? zFY(ULPVD7opxDX$GH=H1ux=E2=#+;Wt5*F~hKm>#R=ev;~Qi?m{ z!QrJ6@LQWE_EQ;N4q15{uYeSxdoY8HnCFb<4ah%kpxfptT^24A#JO#!#7uWn;ZPwTUs+#(&?}~ zHz^ygrDMq(31gd0&X4-id1I_un0rY)9B>IKuQnc-DF36D%1=X4YlWDfbK!E95Vrcv z_ofotknZ^7Y|u!k5lI>DsJ*#3!k0X|c5C6Vp+8;FJJgI9V@6RL`y9FTiQ%Zp@0i_$ z<-C?;mjX_$Xac44FBD=gkcG}A4l70w_`6;TM!%! zUg4O-xC$bB0-~}Su4LP&?jy&mxEHARM<&tpJjw9nVXo%~r4K8~pM7k6iCG9WJCJPuIR$^E155+J;#sP7T86Umy;kazP<55Sau zUSXUX`6Ui>dveDbSsts87jx8bxx3Q9&egFjvhct+wLYxiaXL>u;cCltQj@_uJ|``& z%pglon-8)BE1DP>%NQ zokl>lG4>4Fs@K7aIY$11<3I1c;`%U6^+h7oO;3-ZS>Y${p{XtjOIkJMHTdfjk+b#u z$WQq5g&il90$(J*W?KtvxMY0iv!ILg2e}3x$|79+u{|?b3KS>J7sBMonrodO(7!i& zOTDyfydA!KhpjU=4_gijHt(;=blGgmfjaig=v_H?t{x`-Q8C>YEVFS{sFj>ze!5*{ znQ>E>##An?Ha>rxq7sOP@5aYE94xUu%ukW0XTRUUi58bBfzQz*hNhA>=?9^n_#>+O zE5{M@Glkh^mDgjVCj<}}#cFw7&V&>3r6eYbeb76EddLpU&n(sd&E-1X{$5Mxx<4tb z7!py=D%i0}QI)~3?bDd)yCnSy20CLKSq_CMB*b=FJ$*`N=Vy;CDz-7Zg?@CPS{xP} zspqpgosX|RNIbmW%;fFu1BRN6zQv5Og1V+#X=R3AVFUOMNOZK*`Hme?6zyb67Wn29 zYmex7Rq}eM=*WZ=wE84>i-hMx4C&&1`uOX^OcUh~P9Mt~Pv?Y7<>~Q3Is;*2W#GZ@ zt{LsE*p!ep3R?T&!9R*4h`;-?`=W@~N;Z*qaDeUsGeF)Hj>q!%1;Gzs%rOIl zca)2pg@cevovr^~m%3j`sa-(Eq;5+c2lk zgZouEfFsixLxR{M2USThg#;J1qfH%=<>8WZ@mg$-VAx2*h}Y3DV!d~={joJy}#vc4fZMBU%Xwd=C+G9Z5vwzs!8 zCL?3@(BNO0DD@>~>?|SyS5BMK$QPD%MiA>WyVD76>jvFvFs)RiI{(zjz@|P90bzGe ztiosOnLT^@k^$2)0!&HuC_{=Xr2d(d?O*~5;Xnklf2u~n=OYaPpDWXTM3GnTjA}0x zB5^QqWLByrf(h4;csy!VsulQ8bt^b{8f1C&FWl7c>x;ztU$)oP|8{Fv%`w-*?#HYn zzdZ0-KAN0*57^!Rye1Q7_U6nxdY&m9tDE33hgg~M7Ryd2j&){V9|s3rR-Rbi@^v)#NW%V;HUu1^n# z?P_>l7OyXg9Nc<}qqYL)m6?^Z(@!~8!66}kEo4rhT>ZyVtuEP=87o_h#PPhO)WpsC zmLGqn7Gv0pr2pvR)&md`^mqm?-qh9Yn*BxC1KHM46j>#8#g?5uuLh zS35?qfs%GO*4zp!`}P6p5Os0*zm)@us=n`j%jl&Q7=RY&*qe);eS z2-?=*GJM=B$jwAXy`|n?Zahcjl1+Urm%UAD?%0s}m2g?A@t9w^RK3@)-88c$Kjm_3DfzOSu{A^^AEB##-45d8485>aXEzr? zJb9Vc+^}0BqbM4WwUEi*Ww0c>PUgTrHnKXh5GByv8-fpjJ*HZ&%wSQw8Fub8%GUim zJc&H)89dHj@OoQ7A9&x2dGoWr=w{H}JHI~dfmpHGOXWKAYw(B=S2xY0P8{T&DS?ydveh7_W7As=;BaOe6 zPf8!XwD|sE%jwNljq@9OoIR7n0n?dXEuNai91)qo%Gs63Y5q z(-Pf}SS_zyD_J+~JFar>eK1~i#%Gy*h&Zr*h7;z$XCo&RvCKF}VJvU=Q)4kX6FczG zPGL^Q)yq8X8Lv$9d{}BB_Wpn^g)1$QKd(;s1G72dd<_3-C~z-|*~(bQ{hcLvB$eWP z)mNna6`IxZS65N4nrNw(zF< z1=;4`2C!y4j#>e4#ar<~*?n|*w(RfzshmNee7A`9C#9x>E{wLkttq0eUi5FK-%;d`sY!ufVYAeT5v-m)g%dcS9qpT)I3gtXJ+e@;up-d3CHKY_ zGk^#4WwH~oKR1R~6Zxcxyi&1U@MUdTg@Tdg4)IG>iF3MuG{LjW2<; z*|n0KR6$LtwOnJ}U$2}jwZAr+xk*ZX?|w&1TU;v{-Myu|hJL_iXIXsbP|lTZV)1Za zuya7g!cx83uK}8n^Bbrvl73b2yB&LiyC919?DcW`GynGXHh^*n1SlhlHmLx#QM){G zrdWl;;1e)|>?`!V47PPz13`T3F`f*Ew#4bHL-(jKnM0^0d+MqVJKyRCo_De9&=mt~ zZ81k{tsUZ(Y>OX(sXfV|ccTtjUwOV`v|k@O<7!MkkN%8m8%c;H$2C39Zpp$}`-t#| zbqpG@JGl??RJ8Wy2PHG+_j0mVxFijPu?D=LqC zvn84FPpw(chFMpO#p*6fTPNIDtLT#FN&(qUev{p}-)Ft(m0taDBA&C5$vLuMfi{=y zR`3O?d60%pB=6_@wYg@m#Tql9XZ+nAz3|r2urGrNx`hxkl(aYvBH8BmV7$wB&-WY3 zuubMRmp(H$6A|g86+230?cRt2&ld_$i@m~~{ZqHs#3^!rj^0v!zME@TZ}x|wNp%vo zNCfJ;VsZ{b!wD~Mam)PG`+ekP5tX1VX09V<>Yn)z@cGu1RrG&eYOKH-IN`TkHy6%C z%^@fkx2rS&%57%EfS+u{7SsXRWRqw>jgk)oY!(l2mw>4-%Extsv6RH$9j43Ul-4}O zjN73<9o_^dYOnO(w&O|{nd!cB^gUYGii-#LiYWRQe`Q7>gUbXd&M~?{bT(brzqj?= z)t^2Z!@*b#$HS@ht>PCSJXLjEa*ee5f0Q}e0&M_`3poj8{3;!a&)E_yqQ*t?~kh) zbxX@VYO`%?oh#ldfz4;es+yEVa_E0e7ow+gI|1`_%EX<3r!%WIVu^d7Rn@ipbVDM`T75> zB+Ibg@WhC+b~Coe$|&@qJ_>q3+W`zTTc5Du;nX* z*RCD~hJDI*Af4VrBcFfpI!%fffBPXMkdb7%Z(WobP~H&iOBwjNej?|Cr4REfBZeOa zt(WD^=5W;XH2t`Q0r`E=o$<0PkmZQw^A+?o)U_Iikk3oNSStCI&P;%3b#uCz>h#b_ z0AP2i=+$e2<$sFmEjh>91nO0oPLPR)<4l-4x%?W>o*4xM?_V-`jxD`?@5+514=TJk ziT0J7H7*5Lis9^;reNms8x>y6jn316am08k`S#_WO{|eo1rZ1*j zEjw_rq!qpJr5PveR*l1rH$ptx;mpL2M$F z^gS(EkoJsX3&4M}wpRu4;!1q2WnJ>9T*{AIFw=m31Nvm$4;fN_v=PP#TL57wXcE{8 zS9RBNrxqP%W~VHR?~giu2+2>V--L)U=KBasR)-GAj{eiV5@QfJcaZCHyjr4~y?*ey z7*G>JECP$=e6DF&z1-JRz~(Eu!1Za>cF$ba3N78enCb8@+Vi%6D=L%KF|Uw8jcG#4 zYp$Uo(W)_(FFgkORh<5=z;~l%yl}m^YcN|aby1R@RgwghyS}cxpyRNtRKga!LNfSEnRt)r~O{MAQMp( z+o)(eywJ0muM>+g8lxTghC^ zauj`+_s~TsLVsM@Yf@+K_O+v|qEg2-)Q+qcn=c|n1FE1~*b=hJ*%jxJu>EXCa zW|!dW@7Oom-HQQZ+HwovhW$Y1 zv&F-i>i7ji4~0U*yfaF9OK+u%cj=vU;7NNRQZE#LZ^7@o)lX4xoEx$$eZH}XI?jrb zij<@3S#ER~+_ndXDRJ}g6c!f)@z{?EDyU?sJOcZsPGg2dU;>`~EiX|NTsM=i1l8WD z>$p0Mt{bmvf(R49*F}`-euwi`UIh^KmeCussHtmcSoCdMYdkKNdOIa-AqzN#?dsl^& z+#>BIOb%}1cBDoaHLk{Z8*pZEy$rP39bf;HAg%7-BqcyHP{T@=3RI<2Mly$kh5elS zZ>Ef3-%g>TTl4k~GdKMctFHi@r*!u(mn1T zz*uAkxZ`@_6^**_`Pn`}9|5=iYzB-U&Gm^HtJ>o!a#Wv~aC&wx(F%*ZCsG`_5#`Dt zB}j4(jRYZ|zDZF4VxX;aw>oE+&Fgz{irC={zEq*?vqm3V*M0kL(Ryh-)CgQ7+1BbjnM`Gp`v#g)4D{v2(%z)Z1P zZaG4N9_3=|Ym3KQ<3cG+eQc)L@ryyq%(x20*Q9-)(K7A5{vF;~TR6=HpXkWB#i}0|V{rR2NSN z&HGh(r5}SjQe*pFk5@}kb#?68ZrhmZ2M1i>`OT9ZLibphBz5_@`A-y?{TH{d?>u{z z8*?S5EZK$GQ|asXBYO3zazDRAgPMD4CTS+f;fc8sto75Tv^aUc*96d+k& zYY1IqK?-AdRm1( zDnE$8ju5Z_C{g|Wgn|6e59d6ltiVF|K)_WBjI;u4F(2O@HZa*Yy^PU614t@FhqZIs zEe~g)7K2PL&W-WzU#iWKWuIQyaDIk<9Y}T~(P>5#Pey<=r|5I%$xj!Rk0X~t0W@J& z($&l+Su+(loz|M^#&rp2j>)zN$k4?9&|PwLa$;s;VtOa&6vcw)(zwLXkeeF-eA&MM zOaGMO+}LfkX;1qxd-5Ac>ImA~0KiP*h@N`Vhv_oCRxHwf^cFxwL`=#PXTr&;uTKQr z!kIeG5P+lM&8?`39!o3>63?F2p5HvpnwWpp?C2R_gjrs^cRJ4991&jX_82j9*#7+0 zHI5=yf_ZJU+Vj?)o11%J_na3X)^9$tp~RNdNz|ehAkCfC6BHy6)e{ydF9JolvuGB(=-CD=OWyzM2-69j|tx1_Pg+&;0s~rje@$5*XKh= zb9R@q8GT%*_H9ln`daojkvt8E$5)W0g$^whZ$Fi&XIN~)xvpQtl>IW-t`7!7xi-n>Mzw>W?? z_vDB3%|@_q)Z{X)vuegzhy83aY4`#6&b^6QIyN_K@r^%>Fzg{>3ovJuPcoteRtV>yKQllc0P8GM&zh!@~EZhFo+lVc;DMa3cd!OAxa2AOB&_6XK6N`T%}dCY&Vp=>XHrolUV2BEn9-gBPke`KVtGvx z@Tc#UD_M<0QIw)|*c~-|G>#DPA(Pm6ALJj#; zVFkDYxsqsB=`Ju6;N^6gR5M^O&AUg0C}1#(c~%;Es~3Lz%bgu#;O`2BoNi>R{9wjn zX6@!2c0V}z4R(TpmaacTmwgEpB$4CSsaKz=q60>20{W(?eqkyMvec0((}^GQe4k+d z)&iV0x=W#Fj){4B@c~9mh*UOPjwE$NcL^!*OA-+R=h4w(7toW# zq@J<|2?JNZ*gA7t+^GSpYRmB68Ug_WFhcgeVopq|wexEckI(+PpwkI&LAO%A@>uHK zXWPP>8%%x5=v%1(6n*z3W@wrUEzLK4HJQ_G>1_zhos5*+>Fh+&9Q)g z^;#|RSW8pLrPib8c1gF}MhK;9qrE468HLQ$^BwUm1m<|N#%DG0BrEqSLFUQ)aO4*5 zaBvceu62u9+pfjc#gL(p#gX@d(7XNmji>E0bP<{3uU_7#P`_GXIO@OSBbrjx%5M;e zwed(wfKgJ8UDou@tQ~>7yZaFII}Df}OLoaW0wQ3G0EYm$pQ;7AYLl_N^73-td=n=U zF3n35?({w;1R#h6T*~KnLKLxjnO;|d9Ppux0HFab*EmjX_+qpSF zD0^P09wRBz`RC<&^t6@$4no2;c7!O%poarNRKPodYS101;BxZx!3hdswer7D`*E5w&CIJNU19DvH<%h}Rg zCKm>e(bTcKh}24YVjHLH$wVpU=)se+>z1IhG6o{=8}QNndsH3~qo?T&3l2F#yQk?d zN$PyEG!1&@Ms12_r?fp=fc)B9+LoK(jWn=xyD6y9G?qTWcyHXfbjuQ}%No7`0LuUi zhSmh1)>CU4E=SV(hYjOVfg?GH+m7^=sV(QO1NPZ4%UF0@_u*ROWmR)X+p{416U6xG zMk3l^tUX+o&dcxlX@Y*axh_C~p(#z4hznl!>Ui0GkC-WPDRu<;AtPuufOE@l_q?|n z>D~3bOT(F1RHfUdXxmw1vzp_X%FVv`IWv^W=Hv2BE6>7W>MoB?_~~7K8TePE&1q(< z$;qX{)bc}Vv)R+lc3QPg@G^e;Hom}ej|YQ5=FcBqEjOveXWdJgx)vb$w8z_XE`w)S zsSe0JPy0RC=cKrQHE(a-@8lARn~`ucIa9mS<+&zV<;nh4rk6QZzYkbl+4{!Cdig?T z)rNOi)_bYf!=@#}kK-|9ZRL?kwxuGZNm!sKvE7p$jva^d0J3%P3{*8dF7vtQnyP8s z{xTIphf?(P^gu2lCeW5JvTz{R0SKAVLSDAEwgOQwDVS2un)v`W+DH{w74DeC$QU zl#KrT&b%z*UWY%kzs}0Ok>K(1u|%sr@-8s&j7^C8;VV?~hJT zQB>(~!$BG^VF#kGKUo;_PIzv7@LKkq8fyUHcCKERc#*3<{Mep52AUp6wM(nn5R;?h z_EBW*8&(eOCmYSWvC_2X377LVvGkGm&sR2@E&KhRXOaTDSwRfjOx2mSE}9@lWuN2& z#zub|E=Gs*UK4w}b<(!x4b#YlV~%A^-oU9*?r#g{2O!K$nks*T$d$xr*Pb1JWN+W@ z9krYc*CZbHv<{^au~Udwd%s8d9WheV<-64zh|{QAS>hZuT9Uh-q?oIRDrDA zd+)OQInbNcQ{uGAhQKBMbAInxXUw&hCn#QhG{^tpw6Y8|b z47ZwEJi`p1m?i%E%oaOvgr@BvKb_fX*U#tL&^`l!&Y4{d*C(;e&2s^*p;m0-Z;Y2% zvdfjB-R^IV<8`r* z_l+)&HoS1I!4TZuRK%0KDREcpBvqeqRSHqrhM;dWfJwsrMNEQ27nt2CcWNhW4ilz< zg(FD5wo`cp zK1%b~Vyz0G|02hc`JFUHtf^S+XNvKUT9$7P=f+i+^Jo38iaRHe>iYYTmZ&7Ofp#XiK^_tHd zruv0LCXz;N;mFH$0Np$6Rxv@3!#V=ZGz$nwWUgl(!|tq zmz;e;HlHpxVf9CTJk2^Sdhc_}-|-AAJ~e0jA71e;NgjIt%63=d>xNbl@$G;Z=W)w< z1HexQA}%ocvpvz#(GgByCopGTps%&=B)PbKR4fYVqbza1&!gFn*OA1i7PwcfDdeY3 zLpqyQO7|j^vE8asqTLRvx30j$?j!PX+a~o!etKu?tCE|s%wp4BlWYypslg}~@_TPt$g6Wr|#a#fnkeGsRmEb`$k z^eFcR&eM%2$8pLfPuq3k_1VZS|L_F;+bj69HVvQAST^jTu{0PYy-YRlr^-3f5?*su zSfm4}^DOv=v+pcws8nU{kjphFO5x)?rwd4{KO%B#m&Pb5UCN29_@7xMt;E(zQO0Fv z=-qBOf#Jmy^|x@?&I3=qWng6|+H=`dSreCCMdSdr%WBo_68(0rdvFPe*~je^enU|< zl&BdF^Gm_Eu6)lMX@r7P;B$I=S&L7zF8Wo# zX>wc2Y$LR6)&p-Ut&+C8mtd}RIq3LwE}Sb76qC{JD>A|Kb+o=SP*4GCWiASOIC<&A z7Vl9B;w%$(mLjf(XVHY)$ZVG~ds}S`aNf_ui7P6~QF^76+f`Fj+pJkUxmxt}TK@8F zmv8<}x~Os1d?crV$pFR&;ZYk6Pk!RY#_IW;mf<&SlT-WMkiCz%q5ko@+8{K~MMI0C zAjnq+yoWHHlOELqY$523E8f;4zwjEp=V(@ z=4$Q;HRJdBBMJV9o<*xl%@qn+0SmfkB>Ji#Kf`_BdBpGT$i^qN8PXKy$URb|RNQd0 z5e5Qz-!H9gT;IC^2h;vaF_@@+x>b_>%9D-G4`D9yG*Q?B;#IfcHbLfK*0F#Hz6%~* znG;V%Tdw?c7uGf2O$M2#$2m7KRd7pX#$4TMKO&s}t)|!{31b~CRMFH-wzn1KrWfXGN4kO&c01^tnjMd&X%)41)WP@<3cO1PKn3t>LN;*PP{UK&UKe8kX%;kg&0i?JQLQh< z$y?>s57W7}`$6wr97WzE#jakv2eh9pROtD=%m>l}h$Bf*PC(0!@70xa+ru{Fd4!Fp z!TdJ1rY$ruTQdAkJax66M;Gi-$e{~W&^Y24e$fH{Fb42!x5kKif7Y)I9z0*XNf1df z4NDuPAA4XVR?{RLG2cLD)phRujDa&{(`QOPRNfRn=4p&c?6VI29ozD96O z{a32hfBqHQs}wmR5r-^PVQiaskfQ?;o|La$g3Ow9uY!u$sXtMR2xmbH-m1I#KWu#kP+VQJEg=Ddlc2!~5S-xdB#@v3%;4_s?!glRgy8Nr zFt|Ixf(0Gi-QD$_{QvjecVE@3q6(%87&v?H?%u0=trbTJ*=Nn21pqHsAK)UI_WgLm zrH?jYWN}eszY?IKIVnf7H`9~}T_NsWEo6*nT{)b=wA`0Aq(@BY!QWCEEIyN2vBfKygYED z@$W`G+fPzWy@T~0AHkPG9#~%qk2YJ?oG@z-rR zZ=WTnq=r_=oSuwNth8D{J&wY^Qbt)QF*C4wQ z;>6c}(<-6c?VRSjg(GB2JhYS1DBo&R-Pp9w{Hqhctyrcb6ZvBV5!WG@_d_lZM&?1H z-%1Q`T4%=!x`uCOppfedn)lqa)@IGqO7fFhZ}3(6@BPeBr_x4$(R5$@I*JQ)5%2D@ zPxI~!1*`%I7dP}re0ONAUY(AnHL2}+qE9r0euqQ^zP|>1kDmCX54Y$<+_xBiQEh2= z-B(3YJ6@2sI!;x2JB~0ux~2BPnTFQ_&urVh+BLi%C!TBQ%guJb{tr$s0gheafCu28fFXHMJ@s`f(xneVR`gUw%-CXRK0A0xM};Ql@aqP zMcSV=X|02I@|#?pbgZ>XYFv3gWLa*y!e;DtW*cn$83^+y$@dNx>n!YSdXG-9iz3Nf z24gSzw=^E#-Owr~`CG&tN)tKim?7jjEz69+Xgf4F<|X8o(L<(duHUi$evLw-OhncSjr6XT>sB_TA|97SBHv=!zMQaJw7no zv-uv+8sGUjc{4bqxM?7@xU=TkrDn@ZJ@JSf=$h~6g$}9ZB zIU{|2e?{+AT<-%by|r#az1*6bxHu-Y*Iz%Vw|M?-nei^V2ew=-rT~jh+G_xGx2yrX zjElV~MFoG&>}QIU5)1a|n4-}kqgqGb6W)X=i~g$E4I%r$vH{EK5S&FLml)k8n>la3 zLEF>4MIqTdlGj=od|IaLI)r9reF3@$_VaW9)QK5VxR)VHCx-YIW1oJ0D=4>VBJE

(O}MGN+Hee^&U))z4a5t`{WbV+1StY&3Ou<(yJ3 zaHv*=z_=uQRP)|dUEWz;UJ|NY2Z^?PFM@M6ltA+de>~tXP+xI3eeiq&owXjp->S61 z^miraAHL_A-qL0lX=yPs@T&bliVq*n+@rJ#68!EDmu{j6wd(gnoYX}^inN1qn(_m& z1k9nKl>aG-@_!3)V`pqo?}q;zBp9zYrzipv-j&G%H=wC71TU>gd*Jcu(+8H6 zRv*EzNa(bE1mr6j^YCPfWm1-udLWPF+4C!P$_~()(jqys`5s=C-}(m82Ih&Hwo`&V zC#s=KhpxWkQ3{rtTAJ+07?;zHy@{7~f+Vcq;3UG5$h_{OPvVwdtp%jjhKK#y6^Xe>zIZkLZv7=Kgj^R|z97>_lim&<%)e3{Zo!+0;!$z{Iqn$4E zmBet{mBb?Q(ElbRi7>Jry{%p#4I%CRPS%KpP0!Zg7ee`9kB$|Lo#F1(>#5ovH&}P1 zB1+VlW~6aN8%~bTjdf6IrJjnX%oxl|C&m>a6sq9f#tM{L4f>Q=itN`*81_F3W}#Gg-XP2-Euv= zyLlASNF%G|=&ZE?EpxYQ_>Wq7GKueAf}JpCof)?j;i?se;5`G)Q`NRf@TPFEL7*0| zHyp~P$dLTuZ3h4s_wVH%e75z|7N#pMC7mj6zP=ZckP1WAd%iBc7);a@4TVJXhU*Qc zM5U;3lpZKqp9t1c;(vn_z0Uns#HMV|m{nwNAxSun&uhT&AY4j@*}y=Wh+{bR$sY*V z|IIpKpQGiC`vg5wzXxKOj|pI+Nicqhw{94#6!3Ohav}{)O=AMu;lED!=lE7jX^n&X zI|}dGc5(0uUlcT+dVcbUS{18EzmDqtDwQ3>^O!t2;J?OaeEKF}ky2zJG>@6sxignc z5n~urB`xlc0=5cu^h*FcnropzRW67mc`1Xy*StfXdf0T-dVY0<8`Vp<@f2=oNZR>~ zB5rqlx9wX?<{5FG+feBV=SV9Aui1^I0Eei!MGI`JNg8>oj7D*Ub0_uU-2?#Swev07!QYeTg6-H zBZN)rQuyUi$c@Y>PZLwDNI+^%$ZTvUC=$ zge?D8WSK&QR1ULVYcuJhwOtss`0k%AZ`Y&T|2y(N#rjfiJtqPw~46B81nQl)IOH>a3Q_V^TI~(s z#lbaFbX@KXQA)IUk!$*vRo=~o+#dL4hWF6t5H~D%U#ckg>#qpil-$G-3YveP&_p4Y zO4jw+92pZy6yNI0NTJi;R7avfY8C=IKPqh56)|Go-(ocno-c#$@8*k|RU?B6BnDr+ z&P2=@%UC764@m8I00y4xMN(5HIxTU8BOs)4l=%wv z@5}^Lj>er-ahWguK~Xg?k0^E#Ket7EagT5y0RG|ke;M;*X7#<%s@t#!pYkZvQ(5dnx z7DU8^>3wnDOX-!|XXOK}K`t+|E2%rnCzGWHBwq)LR7bx3Iuvz5Gf&`&O>Y2?(IGTz zSoG;0i#P&^E$nBoBi-Tt7S&U}s3XA5mdPeH$83@`&hYNTprK20Emtn1xTVX$l%s6Z zm{Ua0DMK@gwFK1 zb?`fy!%mP}a*m9G#=l={svnlo{ZTc%&;mJh-#%U-l&I~|@t7(ZNvjn!zRQ6+a0Gyh zq!vUvgB>_&?86DVT4M@8AmoRnYG)O^6!3Ia$Z9jr>1P5#>GD~k}i22aY zvmj?>&9IR=t7}7(7Cq6Dn*m09((d<%ftMP|PKuyGOCpP5tQ$G3x#QI; z!i44!?P;d+im30jXA0Iz{5Q=u3whU&jG!7*#5cq9O?rx0@OdUz{pPSs3vv|!Lxy5sh z@#4IFiKmR@Ik&f?@;Q_3&?myO9>L+*EAWh2IK%Z`$0Bh9EqeSffbd`}n{Dp0v%nuG zftg(RQKZ2%@^t2zCR8Cf@rx;7BH2skW)J8~DVWbSv^F%mURfQ#v&TAS+V}6jO6ZD ziSUHqPBR0$EDY{eA@&|Y|BJ3ziHH>N;r+x{ajWh@@(-TVYs&~#=^Zz8ek%@bny0n# zp&KqG=o!io&7h7FsuZ%FI>brElGc1s5J6Q8PE0Zdm_l+WZm30qCV|y{b=;mZnY(ImUT0Afdd+q2G;)I{ ziH|-?3yb69X_Y7ahkRJ->7k_i!_d&Y)6$u~ZSjeX@R9a>haH8+ zKvH=8vP13ZxlRToNvj`i&CuWpV!rZ@ZxqZGJ$lttIWA0hW^U(yo2* zF-_}zQ^KvvmBE3X?dHji-s&bgHr>;F%Y4)6()CXN((%mQV}ExqsWkY@!{$-LYCP$Y z2y2gyXbZ}ok?6Y9Cd}JxT+pNKgiZ9uhLFx@kAtAq6U9yVm~Ys{UETMVuztI_^J}vw zliI!VNwk&7;NvqSV~>rtwjNlIhqlw?;&%@8Z~v~W3Yoj$zq0^umReQ>D~tK+~IlWfO|W%^ufXH5>dur&JJDFqc-cm<8Zcl|{Z(|uWc=!PA*B@Qbc zBRh0~2lRWW)k&nk$T{dOdyrg|Ey9b=f0@FWa^fyzT{8Ducb}WVsE9}V$FAj(`Fl~- z&?5M}KHP_tv{a^CfWs^=uxhNseO_#Me5B#P=G`w$dti)(gvXkQ+n%MzbgP6x7r>)x)?hhUKtcW;?qs*atm261A`;~uB4=%b=naH6fhKc~Ndj%J5knwL+6zqdLn&A+Q> z;*nYLIt`RjOY=bXdpPK9KFOkGp1XbFcRgp3`mlI+^9&)mtN7~7 z-coPzX=D7QU26=Jhzso*dDBJXs_juws-q} zr#->Ejvcgj<)K$5ww^t!X%x4N6xFIubHN#_f?h)XE}<-0kE6p*z32s1OVI}4OUU8V zXyAm7-^R5jJ}_|epFJ~8>mfv*%puPw5(;47Yb8?1Lci+Z0zz`54#Ct+>%{(+# zX2tEEDF4eE-?g<~Lxi0R(;Qd;m>!+q+2Yl_TVhv<(+4ZzQ(|k_Tm$n*x0)8QsvEAY z@cY>)o4In>U0aRDr52$oVndSnQ zhOJJ_c*u+S<5hHCp}v2@?eg89=2tJ#MLdwyd`r~HWb%nJce@yUJx+p~9WG(_tLq-_ ztJufI6vq5Vm)H)|>EzRA&r@Bx*zZqnY!|)Wijh#<&raP8ey(CiSn$EVny&)bFWn99 zTVy?-&uo_$x8ASR<>}nwalOarh*dI+FT$H)lRtFmMkWqhF8kzgNVU6(p!y2C-@@1erWY z$?hq2Oz;T6z_=T&U%6>1D6W0aJ$!&`J;oypd<8r%pug+VTZKpvw4*UIr0FJhWs91K#^P@vt|h|Mb3sHpP*q zx1`<5-`2bUpWuc~62nKuSNfS6ZhJ+0K=uprc0c?0&6jg?G_TjLuxBnKTV(kkA6|)^ zwJ*HT+g_~>zoI<`nN%#Cy{+>*()2w~T=l0mJ5&8*;LE6`X*niTkOUgasL`rF`=(fR z8%%U0!v0SLaNK0iD^c{_$#kbG!%w1TardUmTO`b$_U zy^hy5|7>xq{#=Jn8D%+5+REr)o?x+|%A9dQUecCRalw;%YT=w?R1!PKRx-I2=?$s( zzSCH!hU;mX(Ah?3(#7;qUxqI=%8QNn|8s!Jx(wM@7x{cQ3IG7#$%zv|gHy|T1t^tY zszF6uo>Ur7ZbX9mvQO5_pO+%`0oc#@zhh4LnSxiS`54Ws4*R6wm3 zW0sxW$1lw4i#aeN3}RPbd=qEH3j}vgcORaEcM{cbIxfq9v#rs*#W{R>Q#IFcALC_6Y;@ynSh-z4p5(HBqunwL zpKnS?C?Uz*wI#pal&;S^XuDnu3>|G}^u3=?D+Z4M=;!mKF1tG6tVdl2;J8hp;W;}g2){Ow!!;OXkh2?9T^r+6;CA~pu3ch5) z!=^7jd)Da>lYUNiJEexh*|_{yzwMl+jOZ%%Z9}j8tV9uw>Sg{pid3~WT5-DQDTHG) z3;ab8ho0MtD?c)Q|J!)a*NZPyfBo{Dlfb0^b;DK>Nn~93A}p^<5g(5+iwzBVW|LW@ zH#9E8<6hiU)b6QwWj?Df%Cb31rx8f4P|`*Tlp69Q6YVE=WuZ8PO+a8UbD=I< za>=c8d6yrwAfpncbZ^NpmyoA+Rq5I>8(ju}Q7>-cVlI$+8JSn@#=Kx5ZdsEIy4W@> zv=makf0);Sf{V8jVOX&R+5PfRCAwZ`yFCHzCS6notL`-iU|M@1%CM4wR5~G0#lCY~ zrjRjcx@IWsKV41)MOpMG_kH%-QoUiSg4AD|Q+iuBUWY|V?~J=elo~079p>+Nw#bHd zdhb4$38f3OxOeMh#+ z9M-R**3ZXFS4l)$VkF=5f9>vgv8TKE!MNL3@-nX}VFD~<=-qAS{GG8Vsj8-RwZp!~(Z*?b>o1iHip{Nohnz$C ze{L!720loB`)bRZuJ2G8$)6lNgsuTJ8*IH+Ydhpbi8<(3mB0>3zGD$9b z3~k9jN{&jUs1*zVWl(8;t!=i1a&fsM1Adm{lPd?$E-gjn zq&b@Js%EN|@ft^tLmTvzGFKrmAK9o79yTFls2+ajm@<+Lp98GB2e4|mO#O& zI+QVZ;2>BFuOD0}<{&swVIM0=rP*%e^$sR54dZahhu4sYwQK z*eK+LxGe>jKsBR-@I))U`ivEvT@?S5-SM9}LyNuyvdIimMH`eL|Mjvtr|u4J@5y*{egJqBGo z8%Z2S-SUfHN_C?g(o=7561lLz65#u^v@Hk_V?Zt?*9m1OU#@)9Ngll^o_zoRtw4CJ zpMdqlfbe`vFN3!&AillW#w(phyt40=zVSxEOOx@6by@h5!i9+)YkC8%Y~gjJdwdNIewWr)opf7+f#JxD`?r;2Peg zQi)vk->SwKP>RaWhLvV-RrjG^Qow1dpW=4TqlZcI{KmnIN@UW%RH#hRZgRCM&v%PE z*xb(=_v|^|j3md$D6IYveRK$=m^=O$BFE05WJ)RXKyzS4g7WtDoAdPX?j;JJ=!C;SKId-23?wVM%5GPs7g8P@qZh26Psh?@1(qP@eCH*$b!W^^fZk1U0}eVKBR_ z@BO41wvfEL43%9!!r|_4{6bA5IvWhr5yI#^1V{Ug?ZQ2^;KB|2IKvBQpvt16PQC5x z5MDEo$}XB# z%v(Z!kA?`VCnC3ZUT)_-^ylVu6<=2DMI+Sok1>@QPxjHB?Rzas-ff8vrzhw| zauf`UDi;W*P5(Z-TI@|hf4`nU!5=;O=KPJ?OLh?yGUpL6w)lS%fL!$VXezlxbyg|K z>_`{85~IuJnV_wpuVvwDLtZ;F&MW398B?KaeABfNQ+pp7J~HDQDY#>Kq|upey)=Gq z{xqULXm{H;y;fG9YJRcf&ZriO{x+t_n4dsVME1WR~DnHpNRCUaXsVPnYGuLGO9fn)SRK>c5Za4NW_L-JK zJlt_9fi{ZnnnS{EMdn9L@WLjnB7wBTPr1?N)zQ$wB==^b+{Q1KLW^o=ngH(z1oV+# z>r@2bHibUGpkgN0cZ zZ!_p4trA`O2ZXv!`aZCWv8er2PF(`4$;enqK(2h;9vsy*p%M^!Ynz1UYJNI-5))R0 zo#1hnLxFMz#>w7SA)x4AUm8Yur7UL=L7mZjX%SR7RRXH?;4 z6sEvENfN^&dXCr<#3$SZ|AVapox3~Sr^Ij9^``toeuVH%+_C^Z$X+yMF-$o3nIc6~ z9tfboZ1i?{vVW3Fgn-Ux_|AH`6p0miaVLZxxdaXj-jqc~WpSHFJlFpOiN@g!eo^>u z;TV(%R=g6CZ-ERGSTV8qyebJcKnq43^-xlNU;w_*J?Nh3F8{y~oK5sjKnW!eZ^&hc zD>&uYv!!~n?&mR$m?Xf0IJz1yyZcOoTlj%iOc^P-R)*z^4NAre^)}`zA6A20oP>=S`#!1A zl6hcR7SZ&sp}nB-pK)cP-BvsOSV?7+g0Wq-qS@Lu$XS7S7?kB$QAHI#e$OV6USM}9wN?35k=s->qswTT)=>p$%#)b^QQ@YD`>GA|z zvUCxdR~%ffj4>P}^51@9QO!|SiI_Fu9(^U84df}|B}wVll;E4gWJ|Cch2iNZ_|E0t z(Gd$uo)LZo&!jbHy(a_!B0We^$|i~YpRe1bG#mIQr;=y`sY?3)GHxa0ppcegKD!eS zp%~u~DZAMF_-7JTK;N1)0-a>XvkJYpba1H%L@#Neub=!*hQT^Y9{NMVi<>e3n9K9i zh6-SbUD?3wn~`BpuZ{cewz<{tlISM>%qEJ&6!L14 zrc7E#*mcuG^7tZEu!QlUq^g!MrWMATj>;xd$~XmhGY@7Ah!0F|7FhO0B8!b?f^0~A z_BQ{3YetTM+N^?MK~}{IU0m^JoA4EHqnTT0dm=XP!2}oI6XNwinMKlw3@pP-PsV#f<9^oZ@VkG)Ut<51MhySoeQoOh=TJdp;y$a092r5Y zQtP@m-tPxJjeEtN9VxyyolZ)ld73B*lQFwnTZ8q%yiDs4l+0zOWd|Xm{>=9?(rIOp zx}Kjsl!G8dQ3oB{JTE^WVqk!O4R?_CKFhPWZX(SjKtrl*APs>Xn`4U%NH6vQ{A2R* zK#p&B73e&Su=3d87-x`f_pJcBo*U`GD8Skfaz7^c_QkUDM=l6XF|~H`1Kf9N6{orZ zRf2JcZ?TwC3iwYZx59ijcEPalFJ)3{j6zxSV{Y{xAYR+~u%*3%WjvsBI8aFhOwqId z$mE}p8~mz7kLT{>lb2`9M@s&>OQ1HepAjt`F$?sv*TLM zrt*7nkh?uQ5v*drJw3}Fx%5M)*S=%d84J=&lFvFKD+4e1sFa-lF$}Gn5?;d@2rdLC zNYFCF(n(zGWta8~THl{#+lH<{6#%gaJz0AJ`R=tA>*?csaF%6+w3QHE(_RyP;Wy;rQZJE#t^Np+bpP{2N)lr?DpDL#w>10x%`p&w zVFxgP5;&H`1yH7(YxzWrdQU*V36J?jn&T7Xcmk(R3_VzWR?ui#A)5MErul)LyaY8i= z1jl4Am|bRbspnTI?o?5WeMhiOTcT#SAL|fl3YC~xfhrYmN!bivjgb3&12hiu@{U{+ z0WS=*G#Aw&F8~x@o@#r%z>E0w-Lx}=+j^Q!c(XAbYkp(`CXjbd+>Sh=IeU#(5gzlw z{)bnFPfV1~Q-MLk!+my)`;mdy;X2Uj?ke57*~*|JkBYKN0Z0@bC=|_sQUFOCSVPxZ z-f=sQVZo?}l&h_oA-_CYdqf*dSo6bEmD|>d68!41S8pqopEIV9V`e(&2M*2$kT{rz zOAJz76K+nZlJ^$Y53{MMwXJa}W^z5*ZLxVjNl;~8gCSpEq-1G>EJ|<74OFaO#8Jji zeU(13Kb|%a62a#0byC6$kAG#6%fYG5KARl{GttNt`$6eDu1HDLUY#;AHEEQX#inc# zCXkH?aD;EPxxw0v;nh?YMEM;fC0XWJm?=Xcg5wd{^n9dPr&3#^6VrI8tWmsNC{R;+ z5T;*HQ8F>^Z&Lvd>MBswU8LKNcOKalyX}#|*cdUt_ca@2hJh~?YixY%O?upLbcg_! zhgCT^7-L+%y-=LLblJ6W23&=js?*pYPA34yMDdYw*sh4ifIv5y0Sl@;2~?O%Ai;QJ zU7me;G6ognxt^9@=E6+j%D^@boJbI9>u1WHal~_t&!0cbHR=915WH;-aG9=wgZe=|n#8gpFg>zW8rplbZ|V2 z*-$0oKI(gFakH}u`R-g+kn}=<3j(Qt`^%3? zznzT@W$O&o4lw%20(Ll2UmzNrm_*0L1&3N{f;rZc}4*K>-qC3`w zOy=Hf5{1auy!wP{UvfzF2aisFMb2Thoc~irf&RFJU!7)r@W9G1yBBQo&&S!=Qntd9 zLr`VR381nLqq#RD`ye(;j8J7P4#Vr0#CyaQ)&#)OtMVq&rOtn_%f03DHV6(-LJt=+ zLKvuIOU7_ch_ozJhvHi_km!(E1}npH@nI~d9OE4Pv+j7wVh{+{Bq_~%I&8Pdl;mXM z)MVW5tV}C`oj=ab2@0y31kVulzo-@)s#w=g;8j|3vSSmGR*`*F!aK(k>}{5&#&29v zZ3%gmySc3de1A?Is=Nxdlj0C_OlQ%K@fOC)@88U%P~1@A7{+07VpKrWl_w=+u9UNp zHFPS<*1%>#^IpNvPBaKP!Wa$AY31~`&SIS;s~@bmO|9AL!bom;Oy7r}9i(-43E_r1 z^$j^_-Lf8AzmTBXB|T!b*qQqhU!_nCh0?RI#6ibt-ga0_y#V9O;Vx9Z#V_>zNJS6x z3MRrs{^;N6xFG|$icjSjk%~;Vhm*KgK44Fs^$U8{pSf8f5GAE3jIJv+mtPto=q}c$ z9O?Ngtn1{p3}-uRE#0g|B9`8s(u`@&mq4202%nY=@>!b`D?ACKy!S*M6~|t)!}5%VIgBVg7{y${+_H-Qh|gZhgRA?3G_7fo{A5lTpwrc36y4{!wU?N z<^K|#GYH!b>F5Me%+Bt?K!juY*t=35ia3NS_?iqg zbebh%H+=E^C5%A`10}wh8eBn`W^DH8?O6p=Br`ahXhPzO6-IlBr6BmO`5#%Zg2a^@!??45*%i;i z(sIP1brM9_pbTu+ma1{KD6%u6kk+)DK9799Q754kM5dT&Ka2 zRxCc(M7#4aUDQ(ca6N73U?u+w%IND-M;+*lDfq)+OYvul%g zaB#?uUwRhanD+kcIwis3CV?(`5|{@%6B(d*3VJo=EG!0b+&bO%I{LD}x>EGt4*zrQ zk1j|z4L4x0+WD1okolC-2K{uq(blm$ zW5KgF{L**pA4aZnrm>};v?pT9JWpnqY{-mAq_Qk;P>y}6M5B{z6HSNYt?fz```~HV29(qDVId;3#qAihP}WtLYc-Kd&~eXi$% zhEM+G$1Jy{+qXg6*nxm0cY0{y8&*NHh-wwbVPWf~)-)8~`CxjPOWZ)QxQu;XKgw?BqoyA zV>Y52AxWL(H?=4GQBNVaGY+KgXS9pAG;vOCkHWUBNdbNjW%XBed;H~g6mH&EN8fK& z$?n(3guw0eUP*U;wcoF>Ce8*@u+FwVFD);AOlrQ2;r*TJCSdZO*+g=2=zcdmqD1!w zc~7R!!TQ?lX3_@mw?N&Y|8h`L|KOIm zE;DO|&&%@iXMB2(bcXkb5yITh7TNlr#Emf(3Suz4ki|DX@TKg^AW`ZgYu0Skl!N9E z>+L>ZMF>MsQ_SBw)X3M2X8dVOqeKEl5|83Ptx2@%Wp(v?b?3M zsVuIZSX3qY^q@EICJ$}Ue#96a_2@@U|dZ5(W}%{kiRep3kg*a@wu4SjJ0{vY;gIQg*t_FwST*zMGwP59_aFis4u27d9AaTG?!qPCxpihR&INp~lmp94D&c`4 zd6a%!rFeu95xRf%;=GX`dqCGSBO?en8U;&7y#hqH4O}|iBbXRXuPnW^?J_NR5HH1m zs>u{PIG11od&XR7G3X7KLtb7qbmpaZp#u#_k`2fBy4+wp0@)NqyM47{&qsf? zZ+Nyj1cpEi_6B7?*SS2*Taa*p^Df$`C%30}2U^qdlbN%NRhmfhHxr`l>Tau9R_=sY zL}U8mwoVM-O*$e{dOJX-qI~y3XDhiKaaalskvj`}xF^Py)$;S_uhshp(l$srf0=Y2 zwlJXxHFS6%zYdB5B0T^%B?J(&u5>>!1g={3hjZu*^z=Z5##+A|pg`{Oa;f3Tj5#q5 zjk~vg+3bjI_t2}sGnvfk-q-Zuet4hX+Trn~zX5ae9&0JHBcj=|_B9==Zo{kL4Ly_D zA`LzgIw#)~GosfQys)1x01M(x;J{3mMh1gvKCU?wLF)LT$*;$al`ImC?J+^Fv)wEA zTg#dP-P4KNjM5p4!hp;&8U24Fj=7p$+YdprO;Q=&*zAMt2Y&mv9{BF)i5tn?A!H=C zUJMVbfJP>nE?pyL`P82Lv`uK>lzH?n1ResVr?;f1oZ!O5!^9f_2lH2%WT z*11q9n$8rvJg&}E#f)`g{+nd@?o~{3vJ9|eG&GXvzkM6u={j(YS#{1XWNaJ?5nb-( zfPw6-s$O9bCx(av_s6{p!=!hAw@`riye+T1ynNQ~^x6f0>fQT_nwXf73eWPsuLSrA znvko62lXe18c8Q<|v&zoHISiXz%2jh1f?&r0~B*hC~>RTP1QqAEiK| zO*b3c>@*kz5)=0&_qsYXd3t;R+*{qeFjr(WAeh0>FJcH`X%}c&ypf^LHO9G$N=m*5 z^{x0Izs^$@FSfpe$8?aEyYk2ll?;8Jwjqd(3PmiWpN3nK_4P3GR7h!M^?rH}Q(~I? zwil_9X1UWesDr1ewgUDJ&&O(vZv_ISDg;tt*!|5{d$ez84K+CLKl}R%BN?HlV1*&* z(fkJBhjs;Gix9cpvDD4~N@O?kbS6nNvOm}7U-$bWhrjy;)RyL2T`^-h-Sx!k9kh1! z6v3T$<1p8{?Qb4mukyKTyYoT?hU+sizaenHTCtc0+$}$g zi;K_O{B2H2*iyG5*FN2ef)xZ}CKR7K#>}uCW)#DTvKZ<4sSTch4IEBAzEuXz4casUa0f?MuwEQ188}xXG|P^~LpWCG>m!&qcyq(GDs4$2A*= zrdnX%h2W&yt)~uu?Tg$%SzTT7IY7lKKR>@M!Ep?27{QjwIHFX)MoR1XTXmZ^`5}^B zvxCHzoK}VAt-8KWIJ0S&twQ&&U9 zE_|v|4d_4y;RJSMqJo+Rw$3VS7X$!*IYY{cL(`4`BnPvEbJoBd65qarL!Ut5(yIE) zFJ?D0dDNgUud3RHF#YPkIgQzxoDQp1Jx*HiC0~v8_(Z12#5)bWAnY;AFkQ<~4Cjab ztnxtMy`1SN{D1J$lbPMQY+m* zq7B2UhI9yk0w6Yl$U{#PZ@Q)Arr+3hYAKZ$Yr%`mY|=XJR2H*%IM0#&zr4e#PnXG{Dj9n-~5~E`4`BGvjT$? za%0Z4e=yar_x4`$aej(eT&#}HNE4yhXoza?3ZeevEAevF0}v;VMtcPG$emV#30*Co z4)>{paK3^yH33g*&T{7Baf)x*AmG*c&iI|p0=0DHe%%~F-$tp2n+xOlzBSPdTwf{R z6V-=lo4SR`4IkAKb#{7*gfFk5wY=}SOPJtAqg0k$EzlauPiJLSZF6y!gpO>Re~fXfS5O$|VwfhS`Mge9=5>brMhHm1*NV=>0oY`|&8#{6^BDxGmj@ITS` z`#ZM#N_Fdk^(kacb*IrDJbFZvl}BYb66bQNsszPqWrwFCe}S>>)=)K(!A_z1r2&A0 z6*DVVq-ry>%B%Z>SSJnb00nxpu~w9Js!)7H=k(FCKCjHCfn}_Re{^-|BaoGGP?gaU zx$)e2DhG8wG^7V=@Zle=Uhu`w2dUQ9s7=Pcq@|@Dt5o~D7u?2B3hU+_(GjqPj>U>? z^d5HAp1p-5tqcUIa3mdHl;zZG#l>H~4wp3v*$IvI%H`wWQ}T&U?>Q;KD_LG_vRYT= z9R(EP;J4Rp_vK|gDKZq1KK1zF=p^}NHj+NMK! z{}osRp3&RYU}!W>RsF$aV@n<m9?_d>V)%zcY3j=N zZoYK;prKH6Mzxxjx3~H{f-t+(B_hgObVg#royF_F@89viByNFs_$lTb_C_b`uZg2s zv2y1uy8PPb9!mIsGRAcJUQ2@PTFrSdE|ujq$IL$)XVsYIe<=b7;e3AAD8VfNIv8+m zW9b}<445dDsilPX*S(y_-@b@%WwZaEpZniR!obg!nhY$pT3^i(iZl9a7G;Ca$6mr% zw-4f57f_WhAhOhV7s1WVLNYQkhOKpm-DnmwOhGuSxm5qpn?INHtG+wvPn{^`FiT3L zQRKF)3@%*RyZ9J3%OMo!0f>1}DM&qM74rdnp8uwEEg!upm(tc-OQ{HAICe20A@Iru zs1@CX(peAIT$}i}Qk^_4KK|XFK(bA zcPi+h;NNzd1hTgOEkJ!gy&3i+ALjx}paC>t)DjqM0}u^oO3-oDSZ|Cs$$~QGNJU6M z;E$S>I1;JOfa+sH=g3eB@70(k@Md9O2Iy1AmSl0B|Ipy8X-lAd-A*LnTf zsJObNO(cXsa1SmC5Zv9}wQ&!@9fEsshv06(8h3Yx;1;xl6A11;hd1}mcfXMzGyUtZ z7OT(h+Iv?$RrOR=E{%|$9ubfu!2$dnTwZSi{{hOYg;z>5s(8N}rk)jN0G;v6p>_4p z7E)cAguckI!r)0#F7<{?%=eT*9|9~L&~nM(R^ptrAXVngSH;zKZ#400<>{Bnp{=OI zLoz0LZG1c_q~secL3^1(8UPeA9+r(C*tg-+7bGCg z3|Xao?)YoH99TwCL9X6KZBw~1Ron*Ai-e4Zhi|1HKNU}TH8(hi@+{%6?(eVGP+k~q z>%I;Br^{kXi*dkvH zJkJB-@1Bv!6dZxG$&M6YIQeVg;DPNX&x|WDOGt|iT0ZVrI|-5Nwo`tB*-?szmL%Mp z#d{;%hoij(sCB+~$o@8VXx8%PsC4Ig8P#Ei1pCR&m@J-%h>qcBUkJ%Ut*IuCV4eBn z`zaQ#wePWMc`j$S`TbJ?&SeZ%pWRdk7jS?Bw{d)|R)%n@m8Km2mn zffm3Ss*H^Vh5DB$!p;J%3~C&=N1B#_nC&3Y`jUrF0_g61eC@PiR(*5tq@0!=+RtZK zqb(S522X$VbhytEW2H{AlS=O+HM+hF$?8JFHAK$0zg4%ryJ7OZGsn6{y-g@hCNzXJ zF}Hb*+1Et>+2rl4*myL`zd2WP$+{h*dgwhnILlOs*K1bSZJnz->#)oG@k;$|>RysN>=k34$&xd#ic>V4P>gM~m6&8t6@ zS+%=ovwB626>ICOKw?k2zb5p-(SeIhp{%9J0t8D}OKWl6`A4;?v1u;uE6Y!7<~8%|0y}qi z;EKj`B7ToAa#b_>i5X}C@+`q=XS_e1GH^-W40>mQ-D0 zDw+piIHC6zevEvVgztVTkhPgTe@+6cGGOXdSbCct9`LcKDDEsSWIFuy*JeXJ90Asc zhY6n3`mymoW`$tubI14n{U$|4ECL#$7F8#3$n##B6T9QYBlRIMXMZZZSFR@5^qcsI zM(fO3$}pj;fOw*xk+8Py>s_-uxANBt1nIqz8EiELO0sX5{Xh%sr!(8fEH;18Dmp)t zqv?33rLX_l#YTKlp-2MT4m(naQ`1838G*3*Vj9%R2i$S)-&V105y}o%m&^|Rc`1|` zy9j_*ie?3rjsi5XShdP?kL`8AQ3Mv+7h<1LPIwIc&5VB>_p!JtZ|%2Oi6oom;b3F; zzmj_K;7%lv5T{}ePImJpW1?I6(Y2q}0%6;d?3DH*r>9kJ`LW2uF5KTjlE^FpO#B9} z7;vJ*l_x=P@&`AWrv5o$Cfd|Cl*Ksm9i+mfV-^%Gs+F|jy|3N8g<%d?f;UDsN^#jw z=C5R;w|5+SxAXA|dZw;Lmd^`gHm4X(Kb1N=>?LQP++F4Wc~bH4lzeYzN%kQdbgqs3 zBZWI!hf2zWCJ;|k7llA)6uj89Now$srZ3Ync^?4hQdQH_(@**$VmiKm?s51R2Wip0 zO>$l_0oT$>FQO8_Hq7)Btprs#uPmv}k7CiD8tLvJb%^|po4%Wrx>!!{>~_HF4eV=K zuwNU5MVE7outHuJQIg9=37C?91vw>!agY94c(LQm5%SifHq?n><)O|D&D=mpV}~I; zuo%uCAIFVDLSz=OEqKO7zjPg)LI&w+Xu?zNXx2;cq+9=R!sXipXiFK|?w!u+hg$yi9u9+x zF|xuxFQh|TTo||W<`$!EY)vyl(|qCQLIy_s88U(Vm$o>Spl1++3W80H(r^k*(BA|z zkj?fi>~b!b2n7KZIzOrxsvIZK=NFLHN1JJqI{n#oqBm8ob(uJj<vvz4V)zDAeE7eNG~!78!T7xJZwYczy)eCULIq~eKX8&I%7S8ABofwpS1ub;E2 zpTgkc&_oV0Tz5~@vuI93!q7{^N8!W7&eOidY1n?eax|+10MelJmr$PN)_CqUy*M=I zOe>ge4~14Ta9|O6Y9Q>?iE#}Tw8f1B9Uv0&xVz(b;+#RIIr!A!Q54Ps0{lyXj6a{^ z>Cy}B`(|d3kU$?OlC8{$4Cm6FSK7B=pZEoWx{B)CTqenPXO$B&EJdwkjM`9iXi-mY z3=U3@xJTeA<3>R2^g+xhnoh;Ry9=6f420dcW6Ly8s^iArjT4A+XF*)Y8Dx<&Y!_rM zf7CGLm0Zxp;)s@X`+Y6kre5N(^Vazl571lPU7t0*PKUHRYz(&-fYw4TyfX z*+h(U0Q7VC=CI0K3ScP!x%h=w%+Eq1S52`Lq|LkVQKWg7$(u~7cm|hwG;KZmTIPJse~=bOO?yLBDxe|9+##YD@A7Q4M|Xx-=@(j_mWxu$_rwSp+Zm;_Z=M_ zjQ}OOu+!Plk|qvTq2+NRH$ly@$pi5!O?*$3SyiW%1=D)7ltLQ9i@Jp#T%pZb?xJ(g z_Q+>_gHeMgxBA9n0$|nI6Bk^X?5foQn|mDLY@U;~feVdYV&TH@#nMsXWz642a<)vgOA`@_m&Wclu z*S%kWIt(o!7rO&X=aN_7MM6Kb{el6au*_phy!r-RecO9Cl1f-`m4cyQ7p0bxCGPwi zHXj4)DSJM@{hD};+K7RlsqyYM+I|va5-k;7yNFE(eb9K$R~8SQtT2RDffrvgH=h?# zg`N@|+U#@RR$5TZyqnA8q)1M;8`;p&k4OL!aQp%@ik0)T$6Gxg@O7vkQyDhK|BgKY zy}+AZ-25_Ysik}QtliDzoAirQYXY-7|tdQRvy!$+@WK| z`mBEOcwq6U7KYD{$4p{gv8O*6G~Djh3{UmIToSH$NJ`b^Xb)gF8vXy=Z) zm_?b7KQcc?1ik}QQ&R(UfO1a0{!1Pa3GJ9p^s8^TuW#+PY_hB}$-%cvviy<*PO=eR zZe{=2J1h3O#Ihh<+1ha1b=I@OyZg4=$Lcph28q~e?9FmCZeB2nF`(>CJzZSI69XE764Yqvw&ViYFe)J%G+-A48d;Q;VV6N} zX#`{w5Uid1X(xRZMI{jtPA7=oXs&qO`Lh0G0W(fh~$)kH`nRBTVW3LizS z*MHyoSRv;TaSl*!)kfB!9DKc0aHVz{NEobAlB32k!7l%`q2qCJx{*PU?D~lpj2w1adZB`F@OERIBOn6_01sgI#XS~5c}N$@B)WY zRahrnN|OkPSi>cphi=r80ll{;t5}qeb>aaxb4=!maUWfV%uF7Yy-X<0($wN42u78x zZ&>I*Xs>U`Jfyiakwd`#5h8P6^$1fG$@*e3u(8DD1)bV= zSL&hrx{j>9ozAHJy?W&|skr}+f?#^+>eexRBt|87|6-bD!Nr!?1$yJa689gymPA4Y zFi#`?TLe?923(BWeHS=_BNK0MPkAQpz%N$y;Te>~} zdLUKrm@8-3yv6B$=*W&pD@Ln-i7L8VSbTiuX+p%|N62u?sKd?!o9K``dBWF3M*bPv zb#|7#cla<|lt0NvnDEcIi*ji{SSU{Je{%uw`$^cE>=u`8Y&)M98=K9S@CZF14OcJT z{=nwx7jC50Hg_k+a-e_SKeBsWu_sht&cyCvYN?^~fD%kP*RaAts&jY6CiVi&UKs-c z&X=ia$delMQG62f&6Hv=S3sz{ww;$E1{%n8IM6j)bOGkQi;dBa4$9V*Lru-I7`(Kc zJt{+U2v>xW_L8xZ^26UQ(P&WesX7cV84-1+bKe$R`O@F)U6U0I^shf)l$1(kkAp8N z8W{%4L#b^W0hgcmYL10`IcVABIRC#yI?p0!!_8SwOYalUE){fCe<=@=h3pw$1|0<# zi;IiLy-NaAC9q!R8hVxX6~a6QC*10;+PJSm@>>pQM0qVoDRZ?XdCB7Ng|@CPrH2?< zS(EDa__kvNPr4T!z{F6OnVxZmJH*Gt7Z@H;uB%RRdTq>SJAx93(ou83*n_4<3 z4ZJBxh~CD!(}fCiDklB+H~}Qe3D_QvcZL1(itSN@2WGwb=T*zIPx{~fo^EnztWl9h zI;_zi5Ecv+m=AJ{e3vde1$mXvgq7E@uz{-`QZkJH-I9Q97BTVHgJI)U6sX39RSJ1R zyq^BJHCetDKTjg02nujs%$+ln$o6>_ULo@38Wx&_F4gTJWXRec?d)SRQcw^y@|ND# zI2+=RZF1ABe=H}#G-8stPM`ch@K>6ky`ZXe(M?mpM9u&AL zr2TfBaS(yWIeX0nUzEn+YbHIO=so@@(m_}n3xz~=_hJ*r6{`)o`XB|{sxVZ+3bU~) zIv;c4A1H;w?TTdV;vb%}S?K41^diF9^)=0+Q&+Duu3`dUcmDwt!ab>y$@-C!u<4 zCZV$}K1qcxS=H5)o15q?+nf?~SOZ~StpE^^$MV%Yp0Wn*`LF|79rPP%U^FLzj5wr? zdVUeDo^{%E1T3K77 z`rnB!S$_{xrB}t1=VvskZnT+xiW{a${w`wXfK=qNhh7(Ax>`SNpQ;-o7D}wMvwrBKJ9%u$3BuumEYSy-nEpfq z`uCN8RFmv@$MprjZ+&)f9WL>5Pe7iSkGbtJu#`?0h+F7L2phYowdo~3@-0n@fknJE z4nD7?eal593eDOz?(5rQ{9Lwf5QS5smAZ1*Pbc6}@)h^dP+jdT$n#41qM7yf5-AE* zcGS)OlDPpMD>!Oodr%{CJ#U?(toQzAywZ5#ruid}o%K2M{iv#@R|O{f-umz7r%=c% z$J_;?yIWO!4fOoSoefEEIo7r<*MxANLrVLY+^oZ3o_@#0?n zq}t`Cpx`z2v2e}!v2G!0smu-+qaZc6Y}(fT0uZuE}b z7Z1s8eyg44hO7?NlE8C&kJvLT;NOgPMmtPIWIGOAOUB!1-5|YfHG#&#CUCWX6l}v% z5D4-NzP%X?hF!U`r15fUQvGUP&-JneU7_>4gwH>=e$Vgw0t-W%Fw6PQoXa`8-ogj&ldC1Pp3A z|M)c2%$@PVBg-S2bC!Sja@#6Lz#DkLnEIwqJ$uKL>)t)+Ur1X_NuG6jm8NBW7V1kE zs-|}bI9_Lz2>{t8{K(34BS-bHD6)nB(-K(}nSIzVP1?}GN=qaVs9Zl60I;{CE4n?o zwc-W0f|%jb^e|qQj6IOt@wQTeE9TFoMhr&ZueVC0T+nqwev8ZS`E;Xyc6Qc&wGmfE zNy!fk*0t}3BO?4Ue2W{sk$-LFUdfO+%1AU3^xKfQ0$xbo;k*mE$Voa0CMCoB{!O&T zLUsGddx)~4mNUO+jOdRUg#2jV1mYt7iC+7lBGvmg8%)eCGi1JI$fry(- zF$|*czwkWf0f{pG;p!D#+a@opd^%Lwr+Gig(O+w&lqa`x@mg2(31$2P1`V9d`LXj> zbzZYE%Y)0FRyWtx>vC&Ok$OqvJ;Syt7_NvwS~GUk$k>cbK@GE3K9)i?F-E_BTZfI;>DiB?al^rCIn5R}i)1}N#c;BHQO z#_q@gtXv>F#Iree_IXx91&RLCbkb{K4cI-8J@wP4VX;)>L=>6kxk?9o$gD zfooi|{A}EJc6(C?4N4C%`VEEHtcAknm9TI}e*8L0pCUZq-R@_W&kM}zhsFJ!wPA*L zN~SSK=~Phw#u)uSM^s*9#r#G~$Zztk{A;SE8<-SQR;73`YN-M>Pslg`HV?#)aRp2b zs`}mXFJ}li_@HK2EKvCKw2#hs=RdFLbL53$=s$KuD)~f0TNz-GRHit1*sj% zYrbSdo(n6E%tfLTfAn-)0OSohH*GaFap0km7#7&67E{28@gpljBO)T+{BOJh9#Y2y}b}LxbouDw6Mh zWpN&2K%*G1FgjVwDr{M|ms4H|u$*^wXMrgNf~@&yuPIU!fQ%!^*da?I(psfQ;WLH;LACY>cak~v);CLreN%7Q2RIC&j-w^cq(JhUF^2gfn0Xse=JG}=F zzKk2xdu~NXiHl-<6bZ_DG9&8Lu1@!M7oN91Gb%K7=>Lv2Tgc%<+?p<1$bI{W&v^XN z#Wpp;f2&9&bX*BLs8zPmVcWPAD&=|c^gpgQD2B%E!vnNA8QVh^MU;@YOE`Yef#jEiToYyxTxw~q`0Pub7?WPR^_5Da?HSVD52J#yh*}|AP zF3Ep~ujzW7_CtLyEUYo?hOurSUSki>e1{vk@%A3Lu+`KNWVO1o^hG#)zPqv zseiK|AV3&5w)>XAy@7lUT5VuVAgU;Vg;?7u1^)W$*!IQ&1q|Ez*6bpt`^eHL?181b zBl7p%&yFnK# z+R$OEp8zW-$`mZqd)Fi5TNcOwxj~)A)zlYJ#@l5gcEOJnGC(A%mF23n2ya{J>gq-Z z&1Kuroc*ali}+a~0HwqbN8yA0R8L^WL`zFPaHq)_?R1l`%fU-P8OR!OC7D+LTLox< zfk5_;Tq(8z5@i)b^VYW~eaTLDU{c6CfZPs@Ta%8bthSh;oG;Vr1xBZqR8$n^QdQFmI&ALiz+V8c{*Rs# zs23-f%(6MF_a(dG5&ePlLs^a6^mnILP#8~2?@ZF6M{f)7uKN4rhOehr?*Wqkn>aiw z@7L=8f2<7`!W=Mu>N}#ki%B+?nY@mMG`GhXl9Qn$(kO7i+kt|CR~g}^6s-JDxmaTo z>e>g#r7a54Yj-WFC5Md2U6y4#>w_-mR3ty0LL6q?F|rWJmXZ?_`}gNcTiXE1y-4O$ zRTY%QDz8#dfMUJ1Y%wA;n4FzX-wLvKxbA&NE{5EAai}0(V$)o{OlCPMGiyIrlAggp zLTg>e&O^z!nq!-zQWE%}q?9pqTMAreNs(Dc{t!Svs95kVx3Zefm(Qb?d%;_|Evehn ztfvB-l^ovzQ_tG-Lg&yo^U!*hz_#L}*&HVv)}U&(zj!KdXeU%e_SN=GxQqOl+hlIE5oz_=Q^xpaPN!8uMwnH!Hn+=E*FVYUgot-a2;!ICeM97}$B1 zCOT6d)Quj){{3&|5xK{z@?(obq8DI zp3Jg|X7dsn;!zfsxOkz()v>U!_E};i0MgMvs>;tYRIvJ0cs8;uf$s=YDt64 z(&yFCZaA}x%=g4&?FF|TH`hyTTF8GXrc#>#dOrEj_DgHrK)csCH;n&?*@Y4#s%2R! zi#x2Nsi`S?F}zNSj6^y+JF{u9r*M8Q)YZ7nPYQkai_cbml5Bpl%N+TFhbd;IOLI4&R7F*+)-mgWx)R43x^$rrB z8#_ux0bHn<-Mt(HMOhgcs82mJak*s`Mc z@8cPWc8VAL)j~VYa>m}?5)Uo%StUXW1{k#7w0bmTqVXXQf3A9~P(M8iY%{4u3;KHA zdPN$Eo9BX+72N+;d3CGKa&wu5PtR6ot$-a!PnBpC<+bO1cyDi2n#kBUE_zAtfw4eT z>+wYg&2szTH1H_q#kt?yyliZ1Ym;)rpHFpZ=LZ)0SZPvVFX6%=8jO0ptA;@4A@hHT z5q3J;`2gar=CE6f9NhdpEnwT2?ljI_l&t=@Y&USvraR~B1bjG#i~>C^R@U7kBI&te zymVVb4*#5btak41HurMJ3(ci>rHP^nU4sAGHJ5UQ<=cK5D@Ag=+7 zD9cufQ>g^xVyS04N|c(sKkk(8B`jRB_rN!M#g)7g>3Zrx+K^~B>Rv1#k=2#z=l+6L zN=mIfIsOPu)#%wtc3Zg828o}Ax}vbw)H;}%U2lScgYh2P63ch;SBHsRWAo#a8DuBV z!q|RKJADDj6hITl6pb3~0c;CT3--U;6WWoB_J;Zu3}wTPMh22-cMS&SpU|w|rCo(4 zIuJmmVkAgtumb62Z6KF(oNXS4q|Beno>A{C5poaE4f1z$a0sdaC*Dc1H@75xe)pxI z%Ysaq3=D8~Zh&xTU&Gm9lzTBOKOexrG~W4=P^w>3{oe{NlQllA zm;W5P^UhCEONgNjdmew|)spnw?#oO|E8+0C*=hPD<|$Z~cl!j!?=MRo_Vz^pLfC?D z{zjL%v`VIHI1w()3}+G>I@WE_5S62Q&7oJJ;d$MIxc#X%?l|U${H~P~r9_7h5NRwsL5p#D z2Wq?IRkyClWnHkXKNckZH30uC9W=F_2^}$zS$R4OX>e*g;9LtzxA+C=>-tBd~4-FYk zf0vd^V+$LOr($(K+wwuSz2HpFtJDtHZuoH44&3oF=S*{d-oe%gxGc;$57Tu}Tf_n; zV9qMbJ^~G>69IUw=eu!hz$I2bR`%Q8fELn2NQ7uG!B#ZTa1;dyDk+_Hj8&9GeJ>vf zxm_G;9`&{TD(H0IXe)P;4+Wuz=-dVe!JfrSyUkmCanlC$7m!anapQYgQ(j))&~bKP z5v=SDWa?_%2)LE*n*-8rG<~F;)HF)H(E9)xsKq<-|Gj_@h+U>p`yObtv7M54_$Z+0 zc^)T6g)MaUL+MMappDHIpt*BJY!TOFXs)}n;j!Gf!LxJ>3dOP4n+Uc#{;fzT^zLM?Xt}nHc&9@}`NYel1oTlAI=X(ub{oMr`@h_t zeNaw2oZeVI}CC<*{QV@2mtCcFMZ9`u0*twik5oB@bf8oASj$7H(6J2cz4 zZ=FxgoBJ`q6*}1M(!E`S@1HrB0eR1<0DOCxsvmlNf2&H`r$=0K%q#anV0ris;MjpO z5FH$+b|$iYAx#dOcb-K20F6q<<*Xp4^BT)e29g6w`g~fji&O%b$uT%ZAgBAO=eUDw|9MMwgWP=&rS=Y+y=dq z{*(*ub|CvqH$M7juicwHm}L#0I*;CTQu%goJU`Ovv=`X}RZ!n8DB&0Q#@iV=SPF_` z+4_5QI?{@WZxF7Zt|P2VMt3e)5$%_;NW0d@e0MYiTVq0e@9~!pSnWxC!VDffKBNo$ z?0rIotix_2g)5HbRBzB{`P}Fq-S?kcuT(O7Ouq^)DE_rPQ0vMk8&sOK;OmYn2-)eY zKH@C1=84Fw{!Q)Y?uOj?@LL9ErcgB&?6Q!z8N#`zzb4!xtexgt8Zi>0~)k2Oav8TJyr=MT3uFY;`^^Hvs z8vWe-{I}Fpgf6OVFA*anqvWgOae&SoCzb7U_p#P=?9*(qGBXLl-j4Lja2)vvJW537 zfWhI)`4X4QExwnf2A9h=FL#+fH7#trstaLHY^|j-wx_jYz zQZrQ64$W-z((Mi>ikaKFGea~v{dBCWF`n!3 zhtz(9&y5XN)hl;!5z9br>mk*+2mpd%y1q<6j(BrgmeJ&FYdG#WF)8Wn?x0fgXyU|M zM@=ngaI<^&{Bq>@lcEo*`27-3$h*ZwBqDAMGZ~qp7?T;c=@$FPswBI8>=)nr5~mBG z1-i6m9(ym~H~|gqe_eWLHCVqZED9HVykJRsTDJh^&N6iH@n=g`WcQXgu8jZ<+^4&z zGPW{Zp=W|yhtf|!beu-frm%nteox{gL7My|ujO`@csmDguddy_6S!tGn? zID$>FVNdu8%>6$EC}0m?Lg}Z|WZ$m0+YKDYrMpKSfrzSNo`xlmFjjl%Heu>1b(cGOG(KXfkQg2CWoF!&Qtc^x+qAEw@b z4Ir*bjm%>8$c5=flL$?KRgV{>iqVlJR(}o$6cqJ8n;oxhrh|_K{CpLrFTUwdzjZ9N z5RJ&m7b+#6)DD*s$C`964`*pZvO{%qSK4hGFHz;lwB>P7?fYG38>5lIWv|pa|B-q~ zJg4D6wZ9%aI5+er|65M|S$#t^3C`d2H{s!Oz6- z@$P(n9lKd0mOXuU(b41Mh9o%X z$hlSK>j$V`NxN)aktVUk(HHbR>4EBqVBpeYI6FHxt>2jdW9BE#*|_fi)WZMNVjED* z_Ro$C8#szLBYpmXFe%gr4Yj0t+$DOg??3Yi%8-Uw3t1{t{lT!o=xjL3Z9N_T%b03s zYuQ_f_XWJym!0PvYhfHDCrh}pxbYxOqc&I<2ydM#! zY_w7meJK^tTB?o<1UFX8c$IxtwU{jZ{zMuWY8*MX)nCf+IlhL9?A=CvK;+C8#KDIG zLZiATliAhH`-pU-WxdHH&jhuMEhG}#cA`WQimCqbl9C(Cz`}il(XkmqDd?&i6Oh4bpk#o~>9{a6VHKPA(VBjlBY_;poZpubawZ;oL!u67e*m;zq>kw(1n_Npq8ed=NfrpM=)5ku^DO=vJu*-)jj{RYwB7)yJ2zjbdTcj=U z=y78Qq9q5u<9I!I^M7ZBBE>Js$4q>NyrIenlV$8AQM6u)DMgz5S;b9)D-gTnI_%gP zG4*$^MhbHHnP~h60}jQb(mgpy}^d*Y}`DZ>l~@Baj>g3TIu{X;Inv=@m{; zXy_5q9yxlH%a^4)UTLwvpDj#i`{fUZt8+#B?!^r~CX*mLRH@PJ+<8cuszI}-lW6fc6R`!xw|Ju;KM3u| zO9;Pn)Ymb|eLyre!pynD&w}wA{@kPIx*BBge79gL=nL2!!=69{{lnU0!Dg}94o}V` z+q8gd0j;Qyr!HQ%H;}6CqncE-sJB6d=Bnw9u2?QFIXW<5=LG!8QI!LXM(nXTxT1vA-*KX zozDVLlC%b?@1-@H?8$H#bn(hWDagqY^;|9j*6z{vVcl|0=;Lpu!M&R;65iL;hdT$A?9L&1&*xn30BAts(*m|g@ zF;ojFQI3lXo&JqR^e(J;XegJ*njA5<>W$JPde+EM`?Y?G9A#s6>qa;&A0!SfmG|~FH?93*3>+_c{E}tUzUC8l$?xOmF-x~DHL`S1M z92h*S2t-Fk^-mYbIy_!3T(|VOs|GW^HyltaHPrRQ!BA1?H{O%1G!lKq!r+VVt26CaG|ob9 z`=>&*@t}#3mNbgK+o^=y%>7-ontY|x%=#vASZF9UAH9AXUIZ?qx`2M2IXbX+ zSbe~yBuBJ?dG*EyW)fwvZAJm=&~K7V2$PsmIO+{f1f1v9A7OWQZaSRN*dWOkd8^#z zpEGHVVuJ4uT1xSuyFQops#tLYw~DsWna&rb!F}|>hYrw~ZhF-v^mA7&io(+Vo8eG@ zhAQmubUm&!Kn~G+YMKWn+POIOBJ?us1wTLj5sNArV60`$pD$CY81?@+iRlRIml6l- zDbX+y!=4Z+k*~UK!PKLwaW-K9ti^g1#UR@ePGC?5>mUi~xwvL|cpT}vQnhM;} zf({EHgOj8@-H%kB<7%$0n9^UrhlzQKK;8AXzDS-E=&yHkF{9Ytfr_q7t=;BUjgf+Z zjvi-*ml2#T1Yg8rbBVHdoXTn_YjAmZ=JJH148J_ic`THr>ZZ-oD0bUMm`BM`$hCAs z$phwSP5MH%aoN=YTCV^8wq?*8)$%?qWT`aqxXlC_q2Y0uoez1dO_iJ+UthxOpD}7s zP{iIBQ~KGh7t^xPLM05b&&cn8yJ2(iUBBm$)Qd8+OAourdGHk#TYZYsG{EVs2}!cH8?6&75is>sj&Geqbw4C+lGY(s8DQ!7SiYIJ1S!kw92w}>i% z`3rVh7aqTVK>&cN!A|Z~5dee4+Sc!7ds?EbrmFei{Wd*wo;qgtB)ZFF{mbp&vCS<% z3KY#7%+h;82Nz-CM@mpEvttIm;b6S{Wr&uV+5i`+*10O+Te4}RRrnD}bmu|)uHV||YWCAi#P ztIIUcg9egSsS8o5Dp=Shz&uc5aplLyJV@X!t`Qm&Rg0hgAZ5`Z7~J3yGIK5Q=B z6^IX@Wwlau?x2^$X!I^iA(ffpMHXz<%vt}u>7Tbr0LUycf|*sdSuT}Xv>A_;HNZQ? zCwI9HN7+i9nk0FTig#?0um)`|;Hu^J%4;hk8mb;dEnZSsH(}E`{G@9EDW#lHLjGRy zLCS+w!`^XMnSH+BK7AnLy-S9~AJx8V;w4rw3^505yDs(ia&R$JgVDgmE8c8LV?;nsWK z){d-~)$`E24#~@`RH7x_xC|BOm2`H~rkKqE=^)ya%qyQRN|I_DgY7+A`61Dv zX;2fQm&UXP&gmwq*Vo^3oCSZZ3O53KSqIqG2h9$A>2n240HtPdq5Ew%_ok%2Q=dQ( z6B8waff4{_aT=1qqoX4`0S!-ncKSYd5n!MPRYehSzP?8T)=C{YjGgay?O)soC~H_i zONHv!)X=m>^YUCO% z=>McHj$HSZ$tu$*$v5z%IDeGEwq!EPjjnSqs=(fJOc_CQ-U~EVW1W)1e2Ik{lED7U zMMGEqX$7v7RCNuqAcX~4;RP45ETCP+DMwVzYFE5+kuBebMpoWdQYFd*?`9=g$|%#$ z0tQQ?#nr~CpPQVm9{&w{2VBPEZ|!Ng)lHu4>-^;=9HLPts6c&e@RYgOOO2U((K?~+ zaJi@F>Nr|r=n!p&zl<0bd4tVz@X(M{b|vOND^cF70jY5_Bql<8M%tGNs72`4Vx;XK zjtm|kH7lHRZi7Kx=qvS%zVnqamGpBWs{3wQa~4M>g|j7hAj;V{#A8a%?C;N&DzChW z0nZ}j?2+j}rAk~70l0l+6Ghmpjxa3g4T5KFs@#0_nsi1aSup&<76#dGlW&K_#QX=K z5<{uQwsv;zwt4;vCP+Y54I8kR?{kDLxn36262+fbP(ijYIw%l0tPbCWz6M7w#-1wg z-EidmVfM|W*UqDC^_ACsPV|JTBdvi!Nhj_Zopw%9JMe<|47G63a=2{EH1 zBT9hfJ{d&jFg7*qoGY@_Vl`zF`#_El1q=H3Mb0BVH;ctTqW7B96`jR++#*9zp2Lo2 z7mik|U8;p#V2R3sE2lT`k zfmdj9dU~lYBQ0(3uAR@38a2;P_hNq(<;QB@)xvtfvxJ8Nu7#+2&^`kn^0j*ri=Fm$ z3(I?|T8zZdVpJrhzv2fjq)2Q5SO!7G!f>tbydIl@;7ceNWq%7%GFRQNaP~Y|8y-lf zYu23+ZP3id5oW=xH6A&;`UV$^iM2Be{aX=}BO0yMUDk83A$6k%Rrrg57SJY^fuDT` zlGg!W(uhU5@%J2{Idj#W&8Z*n)gr2`$}A?+7%qmQDn6olX&)R&KAgWskK_H1Wd%b6 zWU9EO9*r?QU_qxz+MYX~mJpNOR}|*W*;>j4)Xq7?=8`P=*VH-av~R)V&pe`vdwh-c zBF#ru*!xnbihzRh1`E{BFBo6Xm;VINU^XY9H0>?N4Yahvc6Ll>=jPxJ+(P-1zI}rU z==KBp5&AT4wiK=h9;EdkFR%qsC@!!ATdJHhRPL>3Mxy=hEA^LjLg*~Q>2e@yL+`aM zBh}n)J$SZ@R&NSdH^+OoS~O)2s%TZu1`p>Jr!bIK^8cF3 zTU`weM{F>FW}$xOWq%JW0+fzSv1NLr+^xR5@%NCTu3uoq^24j;A{-C?Qi4UnYCK8T&qG`SoC{w4N!U0}twg!oq*4 z+o3JeITfv8!@eM!HI^b7$xFgn`a5X_RvrL>{dN-E@2V&(`(blgQd&{k%9o|JRNr@Q zW70DCMc?MQJamDAboLHsxBG^!|$BI3;Xzy|-%wMxrR8>6>TD7KdxAviJthOs$AP~rKrOCloaKc%>7kz;}h@ip( zQ4+TNAol`*PVj$i!%$kwF0M8K{^Zm=&Q?AGy(1HqDGv=Bde{a-fGy{1Yd>P)%i`TH6^yv zC=tbFNP=5hc%;7B!S;lG&FyrF(OqEEbAu7X+`1|=Q_&wo z{#wa-b?0z|tlU;#@(usGwD)Ib= zvL)(tYv&R7MzhbTnn5Ecv)%FY?PXja$j>ro>;ya9q}M}%qxmn<{iDnfzXKlhRL6tX zhao4>~w)mxzvl?%QgsHAPF(i#8( z$34xXViEc&#o!X&HU{%m)LOo`^?;3M=&r}_RSkL4zGh(qUS8RC=|=i*-ARs!4j6`9 z^DrNlhCQl}B)D})8Wqck$=w_i%$##TC3tEB=)j?iJ0+s~@rUB$u%`@QEc13^W+?2+i2Z zd-;Ft^OTZ3E}&}xX@c^n-uxtVI`&3T^zUjstKVHlS7yD@Dj+_DglH85zvX}q1m!(0 zq83sFc*X#H?C>S)O=xju3{WM{%k74mBk5D9bA@RsmNLKhphzt}}UxNhlojA~Fy6s$|h#**qUi>!?r&_&)ixaXz8&`8ZIr zjV0dv=~S0v;6gU0c)Y;dii>Ni$duCC+p7{zfD#TB`dk;y|2w1^y|a+4XMQb=K^o>2 zGC6sE&Su_=2+0xOym%uV6+z{bQ-!XXWVkQdCzPf!F%h<-yW!~YvZ+8@$|4IcKTExA z`)iwiX zHP=~nD8&nfaEMLvt9#i%Y!Q88d8Al63i2y6nKO53=iGnl4F$0mNu!+1zW#2$!^W)B z>3Pvwf7U>Exp-bqt;Vmph?!X6+rRf!<7GPF<3OI^y;K%ALUwKcIlGPp%XRY>l>0oQ z6)fpawpMUE4eHd{_t&$u4_8fDuQLD$V;AZqRtZ*b#~uRqRg>Oyi?rU5xmOi8!%jww z?LyOkpZ1h=MDPwjzHo4(eGIZOV6hnL(wO;*OQC#|P?jP4OUD0T>#w8YdV(!bcz^)G z9fCt3I01sY26uOd;O;Jg;1DFZ2lwFa5D4yWg9Mks^*iKu?|S!J@0~wpF>5h%ru$TP zSJmFT>gHtpTxUar!d{QJV{RttG-vySHOI2NTjS-H@rOYTn!*csK817O+l`z{m4auc zcy|5RB)M~bixq4Qqc(TvqgQtT2uo^#QEbNPW z1henCD_?pMZs(aG=;M=Ld&eXVreh4A!!<7s{Lf|{u@`g>tM^XPHtv_}JWkuwzvJK> z!BGBt@PaLJF(9={F*S|P!@%MdCSu12QZtFizAPC!cc^MO2Wnqr)f)hZg0O~FAv}zx z>0QpfB;PIfbF($MIzK<|IA0y?`p4{;j1xTWW&;)_YxQv_IC&j zr~FZPv3gOmG(ys&@E(`5UKxJc^uz1xVeMPAnl4~Oh9Tle z$q$e28Pk<8q+64CsNkRn`#yX)sI7A=pZoi4rN<$=xucvw2|@o+}U~j+(;~4$ek-nT$pShaGKHKYr}o zF@I#E$KX1HB6+f=MjW^6A8)e9;I4WRxSNS+v zYj5m-R$00Tc8c#~#TiNl4a9wIgCIH%BN^nkbjQ$|v^e~QaGr0`lWrXTV9RhGt!Ub8 z3lFP39#|)N#6!m0+xRVEzmP^V6QI3zi!5aYBO#CQZj4)zN8<-Yyuq1%* z@U^I8EDP`{2^fl$>#`hT@y0*8X%5eW51YSi&19r<%|DYg9N9VhRDyXQZTojTa_uv|G`Iw|FCYy+vmF5Z)TZNGIREJFcWX{{3)S&yL-@Kko(-iqFVSD@c0ddP*2zyuIFY=rZGToQ-SVa4Z&~up7b?dSH~%? zXS6F9$@UX;a1TDHPa%h1IY=!`F|qv(r{}Z&?(ZF!-b9HYxjpYtt+d>|(Y-rk_1GS! z^zr#4y5R8pM01^KB~;D6!T8#>ta?T>Vws5-ud$6OXJeq%0qD%o1i8Z`!ulXdoJ6DV zNSnpW1H<`pue6fli{9CO>3<%BFDa+cbB!m^rJ;@yPuZ>B3|rNKl#v2=bZ}S`>^BzV zy_t4>VQeoxJIAD$>W4UmBILVhe_jjU(Lcn=7gKbq16p1pJiqiOAX`dTeCjr7dR{{# z-_iTlYJZR5w)z5Et2hdxY}oAjLg@ILi}Vkv7jmQdakp>hEiWC<2g%i&*8N<$iEMBB zlV?lpwGJZ;+{Zj*+P(GA-2w{29q6yFxd)ItP_|?|v??im zuU4sg^-ZYZ;;Meu&VQRu)u331`VSO4$PAUS3ve#Nf@0-ZeaZb|nFQ_$zTi}dE7y@U z@3|Vz{@~a2JFrA|>-e_U$%TgYvM0SAjTu1e#oz;0^Fak|p)CLmk+9}F;+0=yNJ??c zoAH=@JK3I>Vs>xC!WH0R*u6Qv%sbGYXx6`RR(WIS^{Mh@Ps`)3)=JlTs#xH3ssp0O zr{RQq@-VJELi_==sKNpRVkXewyGJK;%h~(}W0As#@gu&StIY|)T$Yubs)bnP%bt;2 z9WhSTT12d~eNRz{N*oQSBv~&kStD_)b!VC-dR%>b_!>5=b-&1i_ZO^0M_GXHK&Hp; zerlLKUB8YskHe_7##YqGTQab*E{C;%!2SI@#A&E^9|xI8+c5TG=5j>22+=xLLt9C7 zBZ53~N^C!pJg9v@4G#%hy&`$O?T6;O$o|93D+T&B03NIOVtjRPUvoC#>@d_+aC>vz zs>sZVJG(=gw;S}*ZJEY&-YP)y&<2rkKI1~kfz9S~WBlkP)pbrvr%0?8_VD8Iq3|#2 zX0U4&#ns-Sqmdh3on-HaWNdJR|7mw-ktHaqM=tge@y}RPh+*vDW0dQH!7{R?@p~sb z4`}Y{{HuiXMg#8hK3XSL3y^0Q0K+hFJio41Y^j_!J($MI zK9P8TCJ3cNZ1cb=JmOGykyNHQTdI%+PoZ<89PloBAkH@fP?ZF7B4SbOTNBfU9(=Jb zt`4a}6Z^Aw>+r`hCAO;P${xw0md)7z0r#kbmXP|{0px0_;%IE_UM3}VVCicm7_oHR zMVlNIEFVwi4=4Ru6uq;U`Spz7o-vzRaPI3&-*zO#`(Eg z^YKr*OCe#wQ$*YGAZafIXP&C z|K$Q;d=IEc$;^BGVM@t7C}8joduG@AkV9+B-N;&3pek8>{!;YzA@=D>)=}?Uki#9CbdwJ;_B$WPkg!m!XL-T_-5!<2 zmAQy4L-sG&akaz#v6c{r)_PFes3^?Upch@hdjt0=IL(Jj=60$A6q<`W;jmER{K?}M z$Z?8mNxsp15Dw0QjDcoffTwbzFB(rLbX+ceN8QS7wg!GjA!#us4t@P`p%q3|$)#;s z$+wcyQ_vVD#)rw+Sol5L>O;cMEKWGC2H49`Y%yYipimABWt(w>%LZS2!=2%$rrln& za~Eyw^6Y2K({gpeA8*1iDaCr2t=Op6p1wTpJ@fVPJQW29;#K~$31Miqns>=8_=2g- zsAZK;phkfkg^`!u&+kaHqZ|<;&!>LOJM6sK+g|M$^z{8>J+VIuyUczvxe$0BhVnY>m#zX7>2pm>?0X7;}48jMVxdZRgR5N%+$7M%WL zto!|Fum_|!NLA9`bbs`aw$o9eteG`LLYArTzSiTZlw~QFL4}M3J6ipFn)=Mz*_CGP1 zcQeu*AJQYwfF_z-bxDg{kY9X{*GaCoHp5QaF|k4>J0xsT{5T1Dv-XH_88_2L{jq`s zhSK379*<-li*@*|OMyN5_CNMLd*!NPKOl%8&e!v1Ra(D)e?i)jgS`f=WZTP*rGM|` zIBfukWk6hW(OSvS-r^h}2_yqo??oUZHtc%EpkUxRHH;T@1CguGhCPXO%U-(enKbHI z9q$1CyY?e2D5qi#N-pW)u5L46Tm|)l=dZO~Q~bD&!8j6M)$^dUGzCTxB5M5Vg+cj? z6_ww8UrLrVIys5TUPk0DJg3Pxqx(kXo_{F(DIc0(Gdrdho_=tuO5WrfP*@MG#xt(M zivy>fz%jy1(JnZxKOt_6+<038-at2K#g&@O^?)Ix{Vxx8rw>#i6$0o@RF*T$^G*Aq z03_F}yC&CO^Bz6|vX$#)f|{)-Uc2)nT!TZ-~* z+MhCJ5Oifba()hz>z6qjf#`W`;W;xKCF8K{f7xu2@C&BJk_`iTD@pXmyFE5H9bX$W zJg*u!PDUkh9j)}#@ZZsPIMeW^e5Sf?I0np-0?w@%)aW7HuTi+>@`2uh$=t0)2x?I zmF;Kq9tF1SB${#IOtJgS=5whCb;4Uh0^b#+z9^hIe=oY3(=Ogiz2rIXfpE0vtL3Uzzys z3Yfr~E&viy6)?yrEcoip^JLmNA_^N&iJ(U^%5~+!n<}0k*uch2UMhaL+%d~|ueX=; z1Hc7IMAsw!UhKj9$6@~h$O{((A%`GBk>Yn49=Uhs5a__8%gIJKi+Gud>~((a9Rm1_Gq8xr9JYV z+i0UNb-V#+f-#k_@d8kj^8QHfx&2EKVYhF@no*uU*KrcV8>`(Uv`j3m#Dv{)iCueD ztj2Iyvx>Dt)$ru*Eu<}BV34j4ntbJ~w0@~+WW$%&t{MC6 zd34srek`c0L7%409wrkO`h`hF@-N>SvW^R%F@=voxb8eZoc6pZEj#;vh%%e$Hs0bB zM)fcQZX{;qMgQG*%UQZX+38=uJ|!me?m8{)G6nz}i@pSd*=c@#uc?zmIO2gR^$G6D%KL@13-CikM4D+EwkGETWHvdT3o4?Dz! zNbx4EZF%IA-b!JjsTE4V7)skU24uJx&;~In=8E?+JW;3 z_S>Uz%l&6p?lWjF_;RNZ9e=1Y>;AI)nr*!EXz~1Mu;Q(vMt12wM@0xfE1|JC>PQQ= z&7?vPKo|WWn#H_YnsT&6g%5kSCE3{dBMQJB<$Z4jtlN16_$>B8V`m1ar4} zZ7)(a;u*e<*zxrgtZm4!Kw8wUsgRZks8)%A5kfT|Fw1^2uSssNb>cpPW za<5wWKPafnH}6%*Dr6$7Nt+!q75Y9-^8w(@1nx@(k}S*I$*e{ZT>uVJfOE(; zFo9+y07c**BVlTob1VAo!UO5rCpw-k>lCkmJ49Dv4Ipu$&O}!wTHe@zDU2Eq8;C=G9 z&;Hby-#f$e!T?@yk0JAAGs-+W%4-V!pRIWQssyHj#%Cz7ln6A`9oNz#kE#N>xLDZb z6!TQ}EuGUyUlgjpxS}K?mc_Bkxzq?LwOcKFUQ|-at_9%O0FAq;jpFQO-5SK~u%76N ziHV%Y-A90ZJTWr^pkSefBv{`ifbknLzhidX>id6zc2|m0a&jow?eXUk=}TTbE>0DNN75Am+0@`Ql-GI6Q^YWbkH&OXu)6W~5Vah0k)O%7{F zLl}sTwLdvblooo+?)@>kk}AgVQp+tJzY?-u`;U$V^_Ms2dcOI?c*(j$&cH@uSP$`k zm~oy_)GH3H^!JcH0QBxBYJInQ_V7L89cTj}I3yn4d+*+ET0B&WuuB4QbeSUQFF?u7 zJ)fnTdw;m1{BrNLw&jeA5skg%eG0_XhNN#^oo5V`v1tWC;v-Q21ImN??M%vui&U;o z{|dK{1LfPeN5B2-`a}>teCK~y(b(3}S-8mzFn){#eW3{Iy+Dd00tpqU>tcjSwoj8* z>eYzoMd9*|1ya;Tzu1Uz(lUoRlw00VdNnA}>LF?d(BV^BxLE?&jN|j&9(|*?S7k_O zZ*_JD2xK^W@O^djHdPW^C&{_2WDQlW*GQ0*duaPqPhI`T^f7QidjR*p<@+o~0r&qm z8Ixy|Gc!NGmb}gf%Y4M|?yN7sXMw~d`G;uHXgh2G2LORE`#Au@Qm#_jx0F1~9|El^P(Eqm$!GM4h$V{MU zNWG};@=9YOnM$s&E>vrHP<^IZkcw&fq9wiJpv=cx;G*AW2i*PDzH(2UDqEw=fAdmu z&cH!iS2qgqvdBn?F_g|;DFcWYK%W>O--5wvPKI+Z`1rXXE-t;;~nF7#9pcX)y%| z*Pwt^yPJK0))LL|%De%v^OaG_9Us+ofHMg7PFH5J<2OXEeep*xr_+ol&`^7`3^PiQRqp-gC6%D zUN#`Hf~1!nKY!NzA0ySg0nDA)SutVY&TQaFl46{Dba+_Vu2z%b7UsPbgv$#w}3bTiErIK!^?Ws1=QvZiLEe_dM@DRKtP zu1o0cmv8UO5NGRMPrqOZKrH=z>(5d8q87jR=*?PcY2nk$hlkyF{hufNW@xt9=J1fP z*$eO8itJe6?_=}Pe=dfyoq^S{XZiKcxK|xhvso1{0HsfGoe8vA?i^Ne7ayF}sj3_- zxTo1aoRmc~c}irtmOgXGEnmTH?FEL>=!yY7rCu0G{~1!TKkJt<3e&YepT26Y^!`*%nPMhj`8_IT>z45nx%LJ?8Z*zt6BWdjsdA9sTB;(z ziH_m<%BcdbXfBBuB4H<|Ph)~FkHV`j*)NaOF(mxM0RIfgd>6L05dqjVP{MN97I?84 zFZrbUI_!laJ8qqc7Si35(*N};o6M@x`juh3Fk(=#bG!&cmmtSs#pfpl#`AOS^&%Ay zPrss1;~Y^Gc3!98f<))`HNi3&HVup(7714<{->}WE`w%3Lqmh1KR%FsW$V#mz%AEr zUn*&F;%dBPH#fhxH4xSErE|9BrfON3ou*Kb(kuk&&r7Znu4sc})h>T-c~;0iCLVnBkQI;Gr4}u0nS$E>kd@v{t8^ zm$^(xI&@lI+&^~Za`f`6dO+#3vURxE)F~xC6G+oO)xW=@5+g2lt@6rNPP4C7oQ0Up z=CX1BhRDwfo@Tg8i*2`(BPrTuX8v_LW*~RVt*u46o(sO+Ekm4H4n45=w={B86PL7g zY92!H(CfW9oub5L<>UuuwoOfo3g4UW$sav~NsX*+)f%XQ0|Jp9XdWUzYwlG1DWg=0 zQB6%!QeOPz@lF7?q`O!^EdfRlaFzjh4a5cASuj@>N8<(!0(K)n5L8mqF>eb~zmEeL zvGyJC7)fmRmRjZw9jJoc`#K@d7N5)i~JV)5;bo>jte!h*QGX zmWwZry;U4Nx;il$*)Qnc1P`aH3a|O}ZKi`CZOhqSh!{GJ?>~IPtN;(@x0fIs%gI%n znZM_zg6r8GU3lJ3kiQ}SH-OEFsd?p{6o_R8*W?}owXDrwxWn@H+jL5gZ;8lT%xvaKhW=7~N6X2p6N*KMK!UO~dWOa5x@Xh7Nr_IZo+kR_oQ6w8EkB;tpzh7Oc zA1x-_Rf#4LaJdmIEMNtEATMyJf_KN^^Rqiw-K7n{(yH$u0Td;m7_wO|$M+0LNzzR` z=y!(z?@|~k;oq`trl4d$R8F)S67yyys6UU39}t!%K+4@b3wZdYx#GVnQjy$P-?Sf8cQ+Y&!s#HTZ7T1Get%!$tRkEA4&$ZY%fd7D2q zjJ1@M0$mU1a`W;;nr#8;D|7m&9l)PO|BPW?i%-aDcLWKPop#2kb;U!i;}-a#U0P%P z@NOh49&uBV`}saOwx+88JW|)Hegopq7i+M7L+1BzAbw>17rKSv_Gkz1T*|D~Bz>3P z<3+)LV3$B*-JryecTFEc;>H=y<+s85c%1sp;q*yibNtj7N(PBu=apReJ5`0fgr;Y0 z3c93)V2byYtR)9@-y=fA^ih1d!}qU+EvyZP`m0|&S-rV5<<6y+*McO?Um>aHA6;Kx z?Ch_!q?&vE1z4-A_(Qfn(c%>9725rtMF8)(%Xa9Cjt=2m zl|k&);e395{Vdqs>Z(z%&XUL6y0h;j4HYER>dD#gVO(6@>dnt23_C7@tU(f#BxtZBvgbU$u4!DUx#EZpt|(V9(cm%5IJwuUQ`6eUE2i*W;iK~ zhnnY`mv0TMmA%KDFWA$@OA{Yao>%|D-q=}QA-VBy#3U#_(Ib7=X3S$F=-b&Aii#53 zo6JW~Psjgn#P7#N6H$`U)hb0?2h-;|x>1v6Y88P~7$lUp5Cs?sh(@jW$&vFxbu^(= z-hMX++V@*=aEUF`-dus|piokLV)AdXq zR%Y=kFx}{hXFsguB&+<7SX0m*eF-)7`QDsHO3mJqtEjt;OP(LIR1;gdOXh zNYl7@dA1rj2V#V%em5wX&Q!)xWWw0IlWVl^%`c@=xcxuMN055g^##YJZB?s7Km8;E#*3akJlSsQ3&ii94GO>X_ z3N1O*{iBb1_CJF*t4>!&0Y%fp5{P9b-El3K%dU|qVY?zmXIr3?2 z2r|hZL(~r!nHB;YroWh*sP}RlEw&IY+tf0%^G}%}L9sZ7hjH&vwN?AUaM=9qXoFzm z7Fy>@rG_10b@q4IwpQz;MTGBD0iFliwas#{z5hrzt)&v^O<&<2cnLnM7ver5GA)?Z zr^B1pmE8O~dP%v}821DIo1CZe+6gvu0XjcpJ_D z_C}tOoL&tFk;qJ7siN6HIM%C7Kx?{)zA;3)i&8@ldMwufkSWjn-8z?3MI;a}fPduj zu>_~vk4v;{a}5w|GM9@`U-Uza;^NzvsF!cOVmE1l$e{^E(Ztxe+F?_KLAMFrt9{Lq z#?>EgMP3kt`-@NPR`Qy7?}(*jtP^Ab>&xa!n8KOT5R@kG@n0+cpomh^Nm$Sl3)lXP zSR(EV@efOCBV93QS(PcJ`}t0z!9-f-enfP_n~imy>#adIM$Bm{3TGSmG;LcFV!?mz z7105+Dj{)nf_*zqg{S92)npeDarDw(ixi6Y6S|54B{%D_#Xl+G08+FV+fg%;62I@U zeKGs&e6RAp7EU2K2QJVmT4!a|`v&f!x^2n;hYrMMMN#9sg55YjqYO>e}Bpf^f`Y#kr_Xl)*dx_w{c5QF7krYQ@JoO5AY|$!-C2*0_Zd{ z0gI4ot^ky4R0#+K(GNjt(c&-(LtlG(dY(z;!utC%w8AW6dXFrz(2wm1pN5+Ljvca? zFWc8V{)%)Qa*f@}tnw2|cniXiOiCj{SICPlYYOEIxoI%X%FxI$kyw>4Mv(kvhn&n5( za(k=4{7R`r(WoRZ<@t%go~52k-gn#Kyk0SKh z>Ff4i-F4@3HnQE9#I;J*X5@vZDbf49=Dns_Ux7&~Xkn8hDzh=5Ai6$CSur9s7-!}K zLQ4Uo-cS_s`-9jwI@a_p@2|qb&jg+mZ7MAGBgAZE-}C}rE1*Pp?Y9Pm!NTZo!t(yk z`mz(CP)dn7I0BrC2KJNNf!zvo={@0|-gnx4MBLaUV%e6Rmpw%#JKsmQbTwDEF%OlO-N3`g=Tok@P#+{qo2Qi=Js|@hS?R1ZM@z~7=&-}f892Xx>-AL9nq_u#6*>8=5_UNl$P0K(EcqsOiFFP0gWdd-lxmMOwty(`dmDY!8RIcSkHF(w8yU_c^`iesSH zl%&c>x6Bb$k+40(zm%##3f&4`pyBt}-6jVplsBr|tbtSYFvnb#Af#Z54@k-;WWF*V}rX;#* z!r`4rFL_G*0J+j%RXdGulf5Ya9y34ceCw$#wM6mvk8Uw~_vjLf(jId0bQe{OaD zuqrLBPf~v12_;83w)g8!jYZV_X7MV|zTcoj}myg}l+%v=Afcji8mX_9pD~rB{ zW|e9>A9ygbH(O1QN7|}uZX4e z6(@k%p#D3R0P_T{ZL!rBP9`R%pS!ukYQ>>VT%dq@?`umMIJ1-DWeBi}T2}|MzVqKc zwIWF9HJ1r7E+~Us))_Riq1*RzIPMoZG#0C3)rtu?af-t;N89a?>e;&iZk>gP;eTG? zznio-g%;=ba6Qt>4b$`2REa|M%-O8GgiNek(Rck6Y-q0v#bxr%;cBM(4-xAi{A7X$u>%E+;!;!bk3`Ae zBYHl1TRYsgh62AxJRV3Ao7tHtDPcrJMg|k)g--FQ8vrN~pg7r|9hkRqP`wBAQNpde zFN>|Gw^Rq50pM&(lmc(4f)Lc+Hi~yvthCbNO~<0iQhETD!5c%-ZD8nJ> zoYb_UK(pex?}rt?5}c!f89I0>VT?X=g5WTqWw71_+k+jp7%)L!M9cH1-u zcUS~PQHsYn{YVAtgOD&@F1=^}dyB2A-6!JRZJERJ>5w_vaiSj@-QX*A)LSHSF*Rou zctxn@TE8B|`PWrMv$rkrbaV>sN?l{o%!hW@AGQZ(e8aD4`buq871KtwgVR2} zU__{149g#OwwKy~R29Nq&amsNKtVzA;olUd08==k`lRsJSsi5FKl zH{%ZvZf_;k%<_HH!k$ zy^o!-I{Z4?z(nMw3&7w|(gTyvLlEuCF97^_UFvzA0*XBX;8r54YK7%0DzpZIf}Ml_ zn|p6BnKNct_;d1ky)^AFMS9bl=Tg_jU!Ny31;6HIqHP{rA*-r@T7F?Ota`T+RRQ0c zv~r0L6z&>UmWrG#R=s~`TC-!^XHkB{veNV!7|a#j1Mh>n-s_Z+m(oFOS_o4^tVj|g z!or%29x5!BkiLNslg`;`72pc&G$x-u%PkfOG?D3 z>RhH+QD~ApS>=Z)Sq|tN_Xj?;ab)pl%Ww9x?=dGj6G=}A2zb~Ccqho^?L;d z-p`?o>&tR&z>urgq96P?;**RvwLkLL63sh0RsQRt)-*Zdoqd0Iw}WJ}_M2tpBV9{W z)dxVi5M0z+*BZfiMM&a7b$WWMK5rv{Yr<*LtnYu`b>g#FLT)d15RtUloL?SPp+FHqFo)Kl;*1Mmfx3{&Z zsLwAE`@(2?QjF`7MBCWX^@x+U{_9u&p7L7rta4fJ>WqF(l%AtgFVGZS?1R#KEr?jY z$h>0*vEc4{`7lYwzlA^(4H!V-R13~f+spnjwh*J{z z?`sB$c|P%kJbHfBCZEpB!BlysV<7qs3d{fFnI})bYlHgwj+Jm=LQE$M8QPuX`TlM4 z$E@wD5R-G>Gt6ECP0?bxPqZ@H*jqO~U0CBsdolBk4m`UAdm;khN*Q~|-*P$Kk8}@H z9wF`7jNnd92!j%#>37p?v*l8*&`ax3m;z5mReK1s&Wm1GbqfKZxqD(;3^`9!@Ddf9 zJ&72MAR3$5TK3|jR)ztgO=DCQ)9K3AT412>b+z04tj?!DMVEuGdz|%Z_34*rreHyV z6lX>}4B@`>dRc3%-|b9m5=g!~*}VU==Nh&D{{5R!fB44j(BG=^{hwQ0Rptlm2&O9} zZmr^7VO1SE1tE@$6>gBrUKM=qXsw4_)D^t|jGFWfB6;6&|JbF3s|HgkOlc-PDi3eQ zN_(-AsKkAZTHE>e(C<}zlC=i}WC!wNOY^+OJn@^`(03Ry4{qSWYap|k~fc$1I zZ+i)xVHo&#O96x41LwSz%hodj7=LPnIFme0R0lPut~Ih@?cNwZBhcN3@lv5JHEFvIAn zS@F_d@XyeaEk0z4zc_$npRJQobL?PUA+HmHpzn1+5=6uXGzPJJ?j-c@jL}j(bt=V|Yn(lQCc%8(tuIa0UAbb+W?JoX zEMU=tsf_>ZaN-D(zQE^T)cSqnFTOG3Mgz_!l4?E5^ts)qs_Zv|oFgG*kZ?wl$Gn^! z-mfp#-*BDRw?O{ZQRA;n;A39@vRFHv$-JNohOUoujXE{B!(CnQh3P z6$nDU0&RJ2@95n09P`yWH~F5=Km@Ja6XnkC*S37(TV(btG6}l6QpP4Gse=9j04*dW z3vzjBdVjg^;pwU6Q2-RViw-eX#gi-GOB3T)s*jQqTN^P9t1@g z=@9{TDTmm8M$Q1MBlEtGE0te05@Qak^1^9W`+c^XoyD>Q(Ndr%xP{H9AE7u>1+8!I z?xgnh$-g#@CMy0_6}|Ghazwfdihe2Bc@y|a0kWsT>u_BbEO7jZH@U65hkxuclP`V$ zMisp0IDNZmgIjD#^x#D|eo{OXrgh5V{S{s(>zPz1A3L#_pTX;d8~3P9+1P*9*#F8t zYqsd8gXuXIU!8RBX`SZ?${8=`@w-yGQ>FVn)#Gq^rjWvE&k z#@im6YNBsab>l1ReL~W5WvP&pkJs&vvKRQU1U7*;+}^UE5#Hu;C<+_Yu_HE zq!zZ!pZ%@qIb^Up*%MOW?YPAEeNb>sAl+5< zZD$mCrSOv#Ix0lO>66wA%u5e6UyoOYaXO!6GgxD3M`IxuBiURD1$pNEPENjWlU1Ar z-Ayp@IG&|7?W*Qif)Uj;5^&oQ$L+rlnjCy~V@T^QA|JaRI zJ($n%WKz{pftFtXHH^&{@(97JtTJ+ZiZ}}9aoYaf)>+^J_}?oe(nr`Oj#mAv6sxy8 zH~vz}@;AIMGcr;nM-+`k!1@^mQ}m|slvVbr0O z%Cx(Q;;%X4b&^Je@C19f54s67jdyNCX-dhh43@%bcy5Ojy_@NPt?-WC451Ayzq2CT zZ1(+Kc9S_A2|mrUjch=E#~J8Np?K7NDfwI9xtfizFcdk8i-8sXlLudTyDhlEg0yG$+5rUmUj@SJn!C&!G7MN0SZSPq<@3|70l52Sf9-%*f`0z{+kxV#dJ}=v{ zQPTGK_~ddr5yex#G~sW-bLgHy2_q?3lYp|cd1 zlDnj6`V5*adzj2qp*}ftqrMGq^f>Q6VY_n7H&?`ZjD7A+ZBo_^+qatd8C-D37`pt# z$N6OB1=pCR$=ogmlrr%}pq_6amc(W>ucYn5>rNcFSGT)srUO5xt%)LIY-uli1 zNUVMyB4gL2vm`Dw`x!T=(d3v7rATe#5rQtp{0_TQKY?@z$ zn!QiJb%=&XwWBNBw(g&&YMKOzETYff?)~1>lMcYRpO`{A=bii<_7+0E7n%+$ zJg;L`J^YK3`l2y_=nrp#%`8{_4P@i!_?-~!A2T1@$-!y9T2>(h8t~sr6&Tg@8)3C4 znMQtyiY|Evf!ntXx?fu-a}-yAtyo%fGMNTUH=yw;CAO=KyH zY6;ObmlHRO3(Qx=&kWuvEpi{`vHW@G;L`htJn-)=c48Z(cCjJJ6tglgy9f!p(N@lP z>8gHj+?$bC!^Dr zBKs)K_x$~(F>8{$2777kJM{&!xYA;$8ERR+K(*^9FTMPk>(A5i_BV8-C)383e=w!o8LE5Fg~F6R@?DXPfc;vnDD#ZTy4i3 z009AKVYvfG+Z91>{_dyTb{&?*BDzwRv@p?$x-12Gd_fiSZ>4#q;#*9adl#F{msjUq zy}dB8OTMXu7!p?ZSFUnej8a7$XKS~C$XOR8^o`k6w7jWxBN^vAep7e9Bu4gPjrSUh z3%VX&r<>7;CHx(tZDW_f%prL4mZPZkRKV@1xvTy!>(?VL>FGJ)CPfd@&m;=+#3^kS za3q3)@`G!!=W|OYed(X%*|l8;Y<@)^lzAt7%*x8*dwGPgSAQKjZFPZf)G}hlV(NE^tUsyu<1)NwMXduQ4COtY>LipXNr4poUy9$-Iq^pv0xRu_PGdl_~yq9eEs_*Dl%*RmPQ&NTENn| z{?1PQ8enZ*o2o$_1i6H4G`bQw|O(AU!UxZxw%g?sd3I^dM{p#+d;QB z_DPr^`lX%*w{@g6vE`bK+dMBgC#u#uwP@j8*B*-?@o?UZ9Zr{)!Up^1q>RgSyUITF z!B&An{?tf$9ui_zIi|LFaPO@b=9l477Q_{9ugBi;ppHH;%ihrQqLCW!iBq2(E>c!K zI*hd{E6p zI2XgR?Eni)Espm{L8J(3qU7iWck5|kEOq(aAGH~IezBxLM?|D0%o;mBGmO|Ha4M-y zd#i4Rw-irwEfd=Y9$VFGyS!uBjTYX#Pqz^oth^?A^rDJY@JJVxTQ`0VM!A4ZoNY5K z-2qFfbr%dN>TA_x#*LqnpX58XHB#VyR#Tda53AY@t@Slav}Rb}+TS0lvz#tR%o>)n z1rFm(!aLtAPd^m<_Vkf$4Th#3#Ja^2ugDd97V#bK3}<-s_Un{7{D=4^=9W`_OST0 z?%x_X?N~yox6(Uo-#G22st{DieP}8{w6#9XLP@P}ygqDyTfb>>&o;TY22zoXZXMo< z%*|M7{o$VFpOi1Ezt#N%)gp40gNyT6@`fV&lfNwm51XqfDYop*1eyoLn%4^se%s8) zm}9NYzl^SQAYC7v-Dh@Aw05_HzB$RF%U6@6u-B$=Sxk$JJhcNm#N285s)rN8rl&gFwh8Y{F zb)c;5L*Zr1cviiAXD`9L_x_}!zi(9YDGQ`$d?ejFC=h(w&B-27rjZ{e$D;YnpoXJ% zDDlvmUhO<FNIP_gh%`udNJxWp4@!4;cX!7ya~^zu|8t$| zJRj!6TuP}19jFiLt8$dn?r&+*y{b^05Bl$Wo z|-d2c$fX!X4RhM9Zi(C6-=N!Q-`L?iVWogX2`Ve<1QkYRvLDYu&-(S+1)b;ghtHU;f> zyh|m|I+9Cg5li8LDY=M&&F{;Ere+db?W43%nq7w9)fv+2PR-Q?Yx{W9pZ z!3)v*;+LrxvwKM`CZi`5W;mQa4!T0haD} zO`DUAwPq6?O?Qr&;!^%b2Z%8{llJ&@a|`O5E3qL)XO`W6-a+^jj5SJx%SkIo=f_ep zFh7x+L^~nqP;%Y5urqS3HOFz=aX`x@m^ zQJ5NzoK8{w-ez&w*jqgyOd!Y@RD?T@G@Vv9vmtw%hLkgmU~bd`j$uR0k$eBVXM!Hb zyLx-|Tz{!;LQQXSf~Sn?zxEREiVsH8;yK^;p|m#ok}Y2q7e!a7Hz+f#ro@VeZ-kcS zk^WNq{gEAKdL?UPA;)2{KI#QLVh$ZOLd8YYTQOZWLN^v3E%sv!3ZMD^!vZK!KzgfC zmjr$&M4WcB4~w|sOC8BR+7|)v9s* z6+7W-vDrasHHxnI8B9K7vXX4pM6?;lC}4j0;xOyErpCC-1Z%(2ysnH*Q`L1dmAu=I z)!%{Zl&ohPBi#EA=k38?7d851Wh6i@KfP8k)m1V4xna82sH1cT--UEJf&E3!Y#@2=em1~B|!tSV?X`A_0Pj=tOoARTd z0QHqZrQNI^?%+gSo(1>D!ccYkzP?(aV&(wZ*XNV!S3hugNO_&8e&Fos*V!a0)bsm3 zxV)p4c5Sh`w~&YMu&OzY)S-ze3XeK2Imve0u#)6H8LxQ< z#)X9}9owxuewqAL7sJJ6zG115a1hm6#%=f-Gry>(-;h(CAT!C^xR&s^(E2e=cG2dF zr)jTJSW`B*!QPgrgttjK?R=j^9~6AprY~o@8yaB%I@H>XrZ5{5uK6zJE+|1vyJ+y5 zUS@Z`&Kmz?@X7ds3XIJErGS$|!U0Jph|UR}V=q>n)0DkrRjFp{-E;S3e z%w}&-%@C?hjVi20v6nksh{alld#kP?#%U#&ZS?opW{jT~Ut5Wqk|J%-g?~fs?Sbcf ztSfVZ+Ahi7y|#!V`PBPWdy_Pqkw#6*TW8I%IJ%JJK7YmEvtF>b&^c!Z!j6;2O zt*$qIX{9{_^m$&a!T)R$2fSZQ>Ux$rnu*XtnuqeizKj$cIMhjRtQ1n)c%iKN6FHQe zJI1{Z`&&w1P7#S~t#R?W9m9NUD1)d(QZcZyLC$m^14@4B?~IZAW9r`0<3$}Lwr7;Z z3;TZ8=q>dTMrH7WaW(xcRBdzP|6X_5W5}$xR$DUuaAh?Ug3P1QaEvCZP_7v1`BQD2 zF@a6mV-qMv_hZ)s6uNB{wZ4BvW*Jjh;nSNeHCuQOIZ#bfB>J;8c*9{gnFv+#>9lQY z9Zzs}SXxjp{dBnCk#OD%-+B{J-5G!Y<6xFXByeHf}Y<~`{! zHCRi0U5&<-ls!^_?rIO#c;3_gDb~=#o1^)7{IWx!2!GSyoo1c9@TE}J`UBA)!gqx+ zRw*keefyg_>g`H$Lp4h7)^gDvHXWRr*W7ik80vldLAqINU|vDYo{wgMFz-bCJ@)fA>C!w2S1-(erXfK^MMdp6Thp^{Iw%ry z)>;FeL%b(+n>P%(K9ylaISaKIHWKuXh?O#bkJNw`H&mwc1stre2jbVhhK5{OU-%N>i)%oZw^ zx5PmXZIJRaMQ!XQSr1& z0CgS?M_M{8Sza`Bppfnjtx{Ik@Nju`2w>neylPru5d5F9@|Km2ZNgHgh(?26+rses zOa^^KHOCvv^8=OzE}oKSId441K5#!=@gQMjg!hlZ1tWZhWw=I%YEm;jfwBu9zCg z%69e4a+g|ZsD?QG06%qTiPTGgUibeM(AViT8ovxRP__3PSOy;#-@ZZ}iXQeJ(r$MR zTcl%nZLi>|uZN@~Cw9$hB%a{z_~^J^Wwn2;oc|l7_*cq6X!8Gk6K+RqWMv(& zhC?GGso2=62P`3}x7=v6vwe^J?;dqmR(swZz6`__4B>VrpURberzcmf6pWdB5C`|n z7W{wR$`wsP%9JG*FF){AR!B{-Kz<15*mfyN~c&iiwI+ zJ+tp>ME?Ie@r%jA2L)WuFpSTITWTlMG0675LC~7_e z$N;qF&49M6MCRvH=^Gd@dJ_OG2_LUA>;0cX?NVT*qWT78X1$z!OxG=CKvH&=y^DU~ z#HNgbs1$Xrm$zzpU-!${)$_p(5Sm0h0*#k%U9g(j+6}$eF=ds%qufZt4pWdS#7zR{tGW>p%lG|D!svK;N}|ScbF?{Wx{W^J8{Pz1 zecGm9*ZV<#N0LH1h|Xwawi48kzX^y<*RhQ3-J5^2W%3F1S4~4hfucDwx|pwuWKz3E9-!Gu~klz zyZ0~8pxoUGx}DyftAFe4@H?V%;?OIWOhJXu@u z1*m|7z#xWF)W%<_6*G5H&ynK#6vxD=r_23WFE-)eqz8EXhMz!^N(}&19w7Vvy!^VD zhXqos?0=}s7V27N$>{v3n~zU>y=axZAP{PkCseev9TSnxkE3?K^5X|)`jHXvMEQQt zD`m8gB-%F|zC=?$9r9>iAv{d3kH^gUeZ2gB1omJkhB28A+!fxPctF$hZDz3WmNc?+ zxN7bhM_f9%zF6MVrQN@}JjhON^m(8Qf%1zD4WDTODubId(7<_d9RP!PSo^T9X3*P8 z%dKxT(^~Iu1}PmcOkI>k`7f>yX%lr65NG*Wtt|-4rA|X*3v=Acrv)9#t!t9?1x!_eFZMKZyz zst6gbHv&Y`Jnf0(Fdiw>Fh`cm&cQ6pgRhi#%P@i`zUe$kLYVM;3d!Faa{tYCTf!nZ zSsr3bCG&|ze@u;&cdj(E(U6{)MM`OgU8+QXFegu4V+7Jyzuit;BM>*AV7Blq7!f6Rho3pc}lKF6!!wKmOAn`;EQaC zXu(+>zl-H~m(5AYecCdpYrb!M;Y$#&b7|qur-{?g@ySig6g4ebe`rUurYf*h+iFv! z4%$j!s@c`3$Xxt;KusJ*_a#JqbM7md7=*$B#arpu_6ietXgxC|^m@P7fRvy8BqaXZ zsb@%wO`4HBojDC{tjav0zG&!Tq#)GSs>b;5OQCGeILYX>Y3DbmEZTp*Hqc@pB|c`_ z$Wzku#^<(wjm)Plj5FAan21tTTd_JXWOdG-^%L?oeMh-_yrvs?oe*grXLo^67?+tQ zzi?gorJ5DebxE1EbI2a$dDK>^1D)23ENhEF*py`VzMSqjl^Leu{YaXZCVmIy^l5@J zAtO*)5}^^HJT`-)>{R2KhC{+cw{FPqcx~SS4!()j-uC^dSg zpSgW7|Ebnok}^Qu*ng=j8OvnVdxvR<6EGvG?GMvDZ+CV0j)y9cE`1NgvoUG9vtIb$ zZ{w5sLqHLOtnCofY4j=E#ruunsIGe@f6l4J2+xN2 zR6|Xn?}S^^+qwY41&yor&uFvWBY| za^lFqQ2+s6jK4kk0ar`1&f!SxuY7DaZUUp#5uYMz!FsipzEHxv%GM6_w>B%@pX@u_FV?mpLRV-Pa3Y>w3ac(Od(au4*%l)uXgKIg^9 zN{b<@7MH>5>LSRnK&h{gJ-%&DOLW^XqhnnT@UDg*Z?YwxbT#eo!>7pfhc_txhJ%N` z#3JVi8_JIUN9g&NBXcT@H~WAnB=Svfi1DvZ^CaHG*eJ8%)IW0-TYvss4? zp%GNLY_QbPOmHBou2Xo~66ng$^F_A&elMx3&E~50dq%}yxh2++$4#U%bl05~4DiP0 zF1guNO0xFZH2)Qdr{f}K7POFq-C{u$<*WC>dH;>&(lSZA=ICY5oKPf;4}Amg+&F%L z!_NfeSI3LgpNn@Ms@agom+vANz46%VtT5}AY_O*6-=nx0Ff3iFMs4p^7!aHu0X~)P z#R%ih?$5&Hs=cartwEAi?;C_Fu)*O{Uwy3kj=4wd{bK8*PIF*i%?J`cbIIF>HZ(NM zPeeA{;%Cd+MDlmdDqZJ%I$pSQCmqavqTdN(+JNA6CMADof0}(O4G9GORY7O5G#kF}ZOC38 z)a!2u%rGv7o!!UB7I8*(Ig9s?qZ-^XH)q7LYr5^g5pC#j3EJpBys;FQfA{!LYjRs zB?0>aKfv)Z4o5H<$~Bmvn&^_7H~F!Iw^FM*9@zj&f`czHX*m=hX{Ux16{mQWI_hCE zKolw1%kF7xraG&*2}Tw+@rSiAL9dV@ZX@O$kNlxp&JCU?jE3H)=-wF@u5DE(3$3ml*D73AA25P*B>JGzC20U*_+P{5#;($T?V)xFT zj)d@n@$#`k-cc>Dab2BnOGcG~z=lrSD7;RznEUU?yIWi3YJFzkzmI2iZ$ zFg*wgr}ygVZ-wCZT#RH_1v5$&z4^ZNc_MO4sL)tCie@?|rv&*3`k6_|&uZ&uCDe2f zV&YL?uIj$_3X#)AGB0JAyW0TCJl^jMvXamv{CA{Pt81;w3BBa6Bi%31a&GOVf17cH zj2h6>d|-0W0vI<~fuvB2{y1tTo$7CZGK=euz_0N*H$}uC)1U9edGV9lVn_`v(ekt+ z7S>kM@m5)k2Lt56_!8P#0`tt?`yUH_^4Y9`kmeP-?(R&1KN?sE zV>SSQeLMZyEalPhGMF(}kS*b!!4r>Q79mnb>2^m@^oJ!u9i`ici{8q)hod(OH^uPe zM>~7Lw)rQk3gLN_-=N*=C}wB;t=U&;l%E&J$l{!O#}5^fd^rPY`qM-8T4EicXw(C1 zau;DMR{P*XDYJ2>C9T4~I+yWu&Q#In(_oU&1Fi8ARN(c?x-fjWp?P~b?Xlvit zg6;hW8_Uh~zE%Zc8)IZcjC*qQg{KQvWK5o^GkA=lq{rE~<`Z(ClI| zU7~SM77vXN27F%B*;%*|H~`UX;#KKW@L6sW_Ev z*}O@&mn!%fdmi>e{hiUDsfRWC07Tl`G#=hxv2StZ!rzctAm=u}nyfGO4lKjdT0rFP zQh~SeLXG_ymLKdtvY9E|4we-`)It0LClV21=F0K;cj?YIQc1RIREb+z&heRi`}P-i zJ`IU&FjA`X(aW(7PCiaL9@jTjS|f2;c!R%E;paIfuNv{;*=ok7tR-$O9m-ZgDaU_% zd2!F)Uy|J=0_Ojpku_ySbEGr%L$4X%cYxaykVe+oeI`zl`E-6h2FGVJQ?A5$13GbH zl0AVb?O*Y^5Q%JlwX#Q&j-jHMp5Xo&*vM!l)B9qTsGQ;8%gX8ni;XAj$fnMrc`nU&cj7xUG`+fYms%CO~sHqg6?1AI`2DXfv9G1xR{kVy;yN_F$ z*}fGTZ~Pghza^K652Jth$Yz}n>DrjXdn1 z`uF$GxCOuqo%`ykJgWM;w)TaHO6{Tv)Q<26+NAe3qpw|9!YOdRW-@YM9zJ1_mG=3I z-9q9gaCBGsQy8;JlVI1BIt#=*&Z8T>#fGm>k(ON#firWeYhv}!G>^x+-Yi-#;-t1a zML58bnX#R%wYQ<_)TLQk(~G67E=Oy@EOh)Z-pLzn)DHPk_lUamv5`IM&GMg_HI-7b z=`+)_!p9~%BC#tOFu4YKrUB+(U-)+ytYE!+{^qP>g1MjgC+q%a!vmyLGe=^Jk~al@ zr=qW4@U8~A9yG@$ImPaM%ZO{M(h}|Oh<&INeB(b)oEs*Pj6O1acFlBGCM$U-ndI;O z!slVUrht}Di9C&0%|zTntjZEh5%8>DzUaNo{yJXUO~4pRnEAnl@$^} z6~jycsJo?tIC>vTzd0%Jjd`~r4bw6ft-s^auv;F;rMpuoJ*7)MvO9V;L^0^}@9~8r zq{@`Iy?e@hF96*`m%wQzczP)HT=1j)uk#aU!7~OE2ab`fJAM&OaSr4+0bf5>I(|mp z&3?J4%3^Q2GUd**Wd8z2wmO(Li@2F}TShvqPx7h%J-?pBuq-8SdCFzAW=JOb2RaKn zP-&bCXQW(Mw8y>ortTN?qbv0Wcr!^nNnBLxeyUwxxSKl;TRAg){J0o($Imb)sm`fE>P%;2VK&9SRV&Oq)APj3G^9>&ulo@*g} z8BlLpj8Wprs-#B0FmWSX_v;&LLPca{d5!X*T91}H^h-bEcHBi9AeC=Q&b~=0M3Kp7 zaYnkvC$m{gqk4a@>!iP6_0uNq7F@Nrw0YX`C^)v<4ylaa_Ki!FV|jTk+koS%c0#tA zeVYaO?!J0qA-dX3z;Z-gax8Co#Yj(A+{yo&bi~eh@HXOHc=l@+#x>QSqv)D?2P8xn zkn!}WE${B!_l9P!f-}v!sUxh677Uf2i!@7^45HGD&HDT4FREgBsDB}5*tq6cGN6i@rd& z)Ox&r_Yt~;BYWx)xU|0AS3ev9ly!tjFV_dOoBkyfQCM#`YBz5`G-%~FR~DI;vLqT(PtSd_n>m_qEeu;{a8Y~$dnJ+g2nVyRCED|4g7rLlW1R1@|`c6_iVZI zoKd*{MB!!XC1hk$f5ViRm^7a1g;X1(vgpBj9&)U2suQ2MFJZ471e=+7UX1}o*Y3~|LZYj_oVRW=@S~aeVrdUo}eYNXO z7+0S(A8%x#(P7Yff64Z%-nqY>+}>W-#XcBxYpB?T@2@&ObI_GTk;StSdi(oDZNm@0 zk}h(KUh?()*q&m}Q})Y(WRLxVm^s{3ovZKHXax7r*`d9>-}jrTtu=!|E#Dgkk-bzW z?hF4A9A51<%}Q<79Fk^bol_DnOHNiM?aPoq2wn4azGSVwzhs@)@@8{XviW9qlEGU` zG*AQI8ukFtI*eL=H6td=x@9tmB2Hz$AzXQ2Pl!8|=22e!l7KL|doCvLzQbhH^=&5l zb1n4B$A^Oy?eXp;1iq`$#q@|cW>UbDRt`M(bs66ALUeS=y$qBqQ|Nt${uoy*hByYR z@Vh#hNSa}mI@|xb6*qXf`_a_JPQ*Lpc!-!g!GzVZ@UI$*$88|u-Un=uIsQ+UHtX3r z6*lG4(5ovKAb#Gt>JJ-UY4g5J0uU%w{xH9r)78;Hc%(Z3?|YFHgoL4a^ZTEYaG>u- zxRs~&p?>554)YUswm&E4tg%@s>&6?DL^X0c>gofy{zQIiP0sw-ALf6?mvJ8_G8Q%9i_ekGHQakUt6KAv z`{ZTc4UgcuOYt}DGkl{<{{8#IOL+KlL!)6u3W{lT?%M;;_BfReEw<)PG040(!ecvO zxLz}&7Iz5SQ+UshB$4Wa$QHG3zjpdm87fPS-sOU{>&K73;xV(MSBBwf+Y&2P*=1z= zx>m~fF2ApLxC=~K{PKQ$6K0A z9YL5gS^jU?;<5WnPNL=NI&6#Q`>8DFHZ84B(5$;?&DYoV6|a}>RoQUDUe4eo{5;)*rEV*NLhoEwPxz7p`iQ9M_T$dDZg7;Eoin_t#IN7h+F{1 zzOJ92-!s%80O04`MoCi479#CyVu@$^b6EWtP0_MS07oXbBxdZ!Wa7mN1`Q&o9W=1y zNiFQRVuLStM;p8rzmI>%9y}>|!SFoJ9WtEY zgyJOoF)Cc;EI~%iF-k}gc#lvdS`e^sgEc&mSHHG6yRhoZW0nh6oYe2bimRNvI&0)v zyZUPo6}bq5@w~N^P%Qj_c=U$#)rdzU{&{{$?gH<|iDuWO=5J@024%dNo7$TSkA#~D z_1yq(w2+B5NwXMRWd7<>cMP1K*518t;uNo09wPjMAOk<^-G=I|2zYZ`A5p#d^~>go zDK#V_!I6{hc?POi{qb% z7E$}3lEV?b@!e4#XO)MiQCMsI7kQgDb&Z*)Q$E>L2R6d%&A00PtS}%6;r{kR(-9Nn z_6Y9$F1 z-qZxMaGw?Jc1~#6zQ}%!JCK>2e#=}}aB(HV98M2s|NaRG)r)F71;IZf5Ez1b>gX|A zn^M4J?pvp)^ksSHxx1IPb3dmFR1jV%eG0M~O)Wdn!CC}^YW;#dcYFUz2-v<`^2Ce4 z7lU8DF!1|KvUs`WF1!X^CaPyPl24L)r?AjI)O_E$XE=%{Y&5Yp<;PG8^TAB!&&ZGa zA0UT2z!OeG_AaTcNVT@00Bttcg|QwfTEoImVG0h{Ezw=Q-ehH!L*EFVM{UFQA9Cbd z*mHC^_sy6`t>s+fOrl_un#t*bF)c-%XccGcl zPmU&hqSp!N9;BB@&-RqGkr>Xdv+!}O_bcIjGV7ncoXWTo2HY`~x5zor?6yaA#}XeH z4^(lY4avf7{A(ZPr{L-k`A^^9y=GCbe`oaellWUuP$O+4E&@s47r5%!0;cVdK04(A zri7E_EeMn@_$7jDFiqg-Ve^PZdIl(4Et@KX|Mm$e^6}p#oyy2}YE7Z>0$}kHDo*AyFzns+h$P>uMsQH;$*NidSCLsw%tCaqIM0 z*{>~kw100lI@^P-@nGT~fgzlcX88AYOed~J*06K97&X@N3HPTqYr+@Jg-;e)gxU-W^Yp@*jz zHl}(+J-ng$PS2|gMWO7vO{pv*C`&tShOmqsmE-!Obwud!Wd+@j==xY6Wa7CX^u!iNiCp?&iitbuPtg#7)lu(Khlnv#iX^N`2s4_>|r zy~{=p8zK)_Zjigz>&0PP8Mp!TMQE%~O|i*~h|a~UgVj^Mfw;(FN005i0<&B}qu$G% zwuf;aKdeu$fi&$NQw&XZVe#|WFw+NOTOKFt?#lNY;*moN^2FyKaSfOIPL}mNSRaVV z?$4AaM!lE^7CGa`acT(eAJK0h?CE;`f*?g#Y_-N%$Jfs*IlPRY`jT+l>(#7XdTE`HwB`Z6#_S(kxCk~eD}(I1T9fl?S>KT zNDLuwV%mh$vkRjN{bv{V1UD4$P6io-&JQ=j9E~w4esX@EuzFb;1=?+!^*7B%E30x& z{jfthQ$S#B{`+v39`$fM8r@y6Bj1tR*?d=kM(7rS7y~wBOG#$grB}+61qyIoZSTIL zaG&^TMlPwK*BL9I*v)xxiEDRff=%h=p1=5mTifeh!&zj%(C;{Nj^bxdy#Y2vN<&?z51HK+io}GR14tXJRjEE-N>Y%NCg&Vo0Pp$B3 zpc|Ja2cpECTAW{Ym!MgLiuc~zmCUhVNX+9$ zPYX856_Xigb!LtxdZ= zr(vSC;PF9md4Ea!5GX#WL5UjhcT16 z-#Zp@sizX#>5CJmJzqnD4mG+5DbtD5ISY%CMCfpg5Gc8W#U3w;K)!6JFkC6W#ejHF zl-0zXp|~FE0ae{j@T?nXZsBX5aNDr^v}BEwHf>2W9QO)peGufsI%IZwQRuQSLf_e` zX5#N6PD2OMlE4{FX4w+^%zIiCAHiiM-~Gm zhnA&PQJZsP(>+;5e0O1&$cN$HopQSdMBtS0is%W$S5qi&UC-)I6HTLci8& zGR^I4P|}-M_gVKZ{?^?D$@?~-my&~15tn-}y0ek3G}f~cyi+*IV{-LMvm&32$%r>= zqz8tCrqc+x@tJ7dj}H#et>?E0bx6XOqiv7r7;uLvjrN)iC%Q3XVI7@|GD|BSHE!6wlp8|PZtQ+|A zGTM|AH8NffLQH!0bSw8AeOa*-s6@0KujQFL%IuN6_Q7G=Z13m^1qI3jlAM^dY`HQ_ zk+gXkQZt}JKeyX)91w+C&jL%#*GpHST`S{MFcf$9`pW9RI&cfWoZ@#&u+xQazlv;Z z28%J}TMdO^R#lG>gtj31!G)VaWQ2A<> z@-lq_7WOdYdmtmEQx`857Dh4$VOF{!>Q)M|Gp=6?$1Sb9!$4|!X3(@? zzb65_(_-<#OMNXYdj1MdhXTjo`5_2r(o`*v-=iBB*mqHRa=54JI{U+R9w$j1Q1*2t zNDt3MWClW^-7$@bXKP7=BP?lixQ&Jgt2A8A&nYX6Auv0`n1 zP^xFYyhB3Fg5C>g6h;3K5X|nl7u?q05lm;jYsD^lRyBo6Ii?pI-@SX;1b+QqEknT) zEId=Fd}U~(6AK5EoaFodzta2d&;j)~Z~_^11BA7UBiGOj6Jd#|oPs^Dr1 zGz(65c3KN;A+?^6iVn(JGMQZO6MT&5T{V)k1f}mDo9_HZR4-ExLDHJqeZoLeojqKt zRyc$SN`<7keqM5=%08*+pS%>dR5m!RVbCbw(yqDNUFI*=D8SZmNE3%nvN~D0q9oan z5{_GOW6Ykt&pmBuToOupbVH})qx;H*1N~DtGTaD^wV)%xpV~^@n&Wc}!#mOHpkJJmEt6lk(Crd#j=RXBDtcJdM ze8MX_iEp@tdMXSj38n?$aJX)K7Gs(KoH!;3{AKhIGVE^*OLeOubH^V<%u*>v+SU)@s z+rA1i&$nFP*p2YE)*U6fH_x}&+&K)gjXk!XFV5E$Jim2gjytQZx;+HfLW_wR!OihG zLjnT6ZJ;J5W=AxqN!32L%g)iZ&vWa+%lzm`j0 zbmrzEm%3R7TSHEkyLx+Gj^+0^-73wN>1fkb;SP{N@al^m;N*FPV3E5?-UhwRl`D+n z`o&f?Tn(nSe&>}Mdg*#qb#(Kyl?K0B^y_)mhD(REf#e+)^L5vVA-Q~`fi(84#a*JI zp;UG`*JU8>0+nJ2Z`wr_1*d7(W^XPk}(MNl4 zIr7&I;1?M!QYeNm0ww&eyDDF)W#bJVMOU^zHc7FZ0OsC2ThpfVja+O$T1?INvi@n5 z)wqPLi2tTJfkMhQUDs}K#b!D*CdxJRKuyYc#j$6n>!~!{*12q^7qB~o7-X6|1Q@wD zDkKxnf4c*8OaHr^WIA&5NG(s)0C$O@zXr!2RI#n7Q8*e`ZxbaZDQCdVxlup^0l02=f$CV4_wA(u%~zS@HmSH-Ppz}xT_CzZhW}b)Ad9lv)g`{- zu^Gik68o<=48ra2mX?)h6-Kp!ZCI@uvNTM8U&-n{FBdKD|9v~$ge{e&F=e>hKY_&> zWwm2#KMXKKtmd9ys@SPgqWBbUy?S`+zhf4y9BeaR(_PWqzCgDR_@Ve4rl)W$QGk~m zqJP-L{7#+*e@Q_9I0=gj@Q3?rR5;kYd#T>f#_31fY4^CT_SBZFhxl4jV_|_DdSl3~ z01ysPvJ|`AkpS^K=wx>yuJ%;pLLKP&mi*)GX#=3%GaMb%U_ahrZ=h#EmxX^!P1zn^ zX3&ppDIa^nP@bE=C7Qt)Xp{fjZV9c{`}hy9lIQXjQG2C-MT@jl3+-=77e5ar3Hit11vO1+n*!UTUyr`t{UanR0H5jDiO;_mP6 zlz}t^0YN!U9pgIPs(CxRRq#_}FSp&CNIZ=KON#WvxaCXB0GX`0VJ>MNaIe+6es?U5aGGFS*tc)5qE9lq*T%dA z+OIH?k&%z|cz!HUGvd*4>TMXw`xIfjp)-onZYs9hpoTlszbr$soJB|WJ=imuwAr7Py083Gg|7|3 zx~&+edMD<4q28Z=oHOENKYoo0ne?z1e_3O5Yta$9^9ujTXMIP^So$@EM5WD$CYYol zAmF5K?sD0x?9C&2X&&%wQOR2$u&YZ%GdeLJTsyH7gp&P@4)zT|`>nXd3n9iHY`Rrre( zc#3I5Mrgek9_isJFBaFkTluURqk04b9&d3{jXYnCy2f;fqK9ZI?JipjSAV38bHjkd zP-HUHT-KZqU66L5wArrN@c;RmOj}cbVkR(2jUC~N;Y`yy7?#C)X6&m}eZ#z7<1Vyb z=%1sR92n_S#A$LuU-r1>$t89B&U_MI9@g?=)L-Za@zSv`NL-vmN=Ek%5eeyXFE6Gf zsuEbZeKOG>$V;+~#ym@vP;kpdnWgJ{vd(?9wdZgnF`X1Ol_a-F+jD!H@Vc6k05ce{ z=Kf?b1$w>k4AFTUbo;7{X1uX{Z+B-*5F_6bjbKK!mi6qfDw&UDjkof+FmYC}Yu`-3 z%U}8ix?AZhZ7k6?c{|vz5b2}9AljCw?Gc`?w3kCIvE~(?A-zzmoxuj;NwAKq&?9q9 zecPidcRqumRqu~<#fd6266Y5m)=%&wvttLc$a~LrE&^NcAbA2R%#oXND;r-tXurER zXV-4W69{&w)MLp07 zD(U6^xZCD_S7qRg=oX!Su^t8CVN7(u@HQraCW6{l{=$m!J#2r6m1oD8tWAkn3S$q1 z9j{*8v8NM24%8y|2^7Aix3NZshMLjKpcwJ6hyB}&5rCAZ&kMEI#SP3T>w(isPfNvW zrEI)A^z^nPp3=^qKrvQ*KP{z~(@%USsaG%Os(C?QSZQrEY5n%O(C3MiasQMe zdHM;VB*nyb-KJiQ>FLf{l-y80=0W2Fj?C%GxQiadKhiIU`kEY;S>Ah6uq13dH(`s~ zmJA!2$#xAZ`)z4#`dz>^N9FSo?ptdJCwiy6=4)ML?uP1f-P|>F!WT zDW$tZy1S*Nq#Hz1y1ToPZiW~dhK3o2_+5Bk-|y%DKWn*WExGrexclzCpJ(s050?MM zPJ7iGx>?wf0D?c3TOcY{RgccWH&Kz1FVT1{0ncIp9~>~$>S|OU?(OWz)~@7F!lZqz z6YSEKD-!pQM7CMBVMSncyJs5U#sGQ2Z9{tvDavy`I3UT@T`H~V>xIfT`L5370v41c zi^J_QWE1o&I}`8=>u&fQ{$aKCZ?2H@!n@vZJOms(75qM=qo1E(J~5Iqev=3Gu6J>@ zP}&XNWU;)cX!9R&3U&BwjEs2FKC5fri5TnDpVhF}*R8%s=5a-?F@VD^XFq5+j|J)F zrSmFP{LKX*e=7${+#lEZh;8e#d4zZN^@6^&i0{KpqT_W_1ICheL2y#n1l?Rjh4bl` zTyN~*GxCMNh^B<5qZCu38}hwd9#kmZd33A#SA%e9lo-J|1?UR;s{*zSJY*nKO%k!Z4NS$4= z{5gL)T~`mH*8X@+#7^#dN+yG^2jumer=DWWjVrsG5si&}5QtUXOMA!gu=6JP%3$`g zfS-|l?#W3XWRgBN`CMPxt6lMAuN}YfRIb;Qcq2t{Rb`Y+No2&RY%`?55x(zJ+&AiYcVZ~tGz-VdJYNq^kD3gB|C&5qEZUqqMz3*- zv!{}5>MRB1)R8`kEp2mLSNUPg*X-F-a?C!i3GjvZ)xb&8i;I&W&3oTOpIC2MfmZi> z<25L{B{f8u;(GTJaBy_+dZU@0C5*N=#*bKXh@64}$K3Ss zuq5@HH$KlcJekL_%JjzcZ{LZI<@02-2tZ~##V0l^DQFX}Q*rjM4CutAaASkHvDk1^ z9I}?aW4XHRn(;0z2iuw45%s>1ENo#=Wj)7<@6Cxy$Pn$Q5rT2`BP`~RTVaXVEQ+2SWi#;xa$JK%L%q_ZULD{b)seP zcyL~`_y03PlqJbe3dC<36K6eGnm;1`9=ox;h$|I`!bV0kedmYCp-uKw9!*V0=qGuf zhL)O|m?Jb>Ux|5eh6L-tztGHP`0NU}TDDugu+;rM9fj@bbZUdaM1D2$y5?p7Ck0&v zQjY@ijM@@m-6eQZI%)s#7DHS!g1zg!z$pjCl39R?$Jus)V`dO+efgO$um>w zgpu;1MNs$%i*G8NU<%9}NWu8orRuBGVto4vFh<7LrzqO*q%~ zOG64!d}n4x`p+elbEpxFVsYiME(Hxk9KW--$KrR$(0`CqYGJJc$3;%w ztx;i!3dFd9+K`nZdm6>c7Mw&2wbnG$)SHv*M4T2sC1a?K;zf$(b3P>zi{Fd89U2;1 zmRyD)!cZzt3=|4wBaMkxgE*4VHJKr-oQs6YA5h$-U%#kctiDH=dURug51?|ojd4PY z`GD!Bg_WlG$!k`oC@)%b1ZYPqDqPc#vv;eXG zjUq&ilE&m)5Fev!$o`cHQFHa`lb3Da?{Yo>({Fe1*7W4;!(@jFFcXmhd9|7xj>8#@$H3d+tefRS zaAyv3+6a(~b~%h&?y``0{nH7@>fn}`?TVf1vzi3ptz*NmCR-kEP7OD0{Vf8-t2*$k zI$x;lmO21{b#{s)Nw^yd2H{SB{aua^z zS3RQM_plxS|ATmXofSG$MF0?Viv8!pM;;y?U&pgi1NBlr{lL4`T$G1i?@kpS5Y*i3 zVTmM`Zqr+~`|*FBwtjeszUEt3vscKRDZ|Te04)UQ>Y_n`yaM1_HF+f9=ikO1Cbe^f zO-AO8L{aa-sFIo#qx|@JQi4QlEJuP-2ErycTg~Rxx1YdmZ?^?NvtFX8qE&ZgUjfQJfEk?otA`vEgGKwN4 zPRJqNH+^=k*wtgkmr)1gi@FyWEb30Fht-I$dzeQyM*{yNdpZ-su82{m}% zC#jz4U6NbwRN)UF9-}U_u9XzvwY{c*JqJ!I9?10nwsleb>OHKkMKiL*d1+4MX)qDDo7|m1+ zBpzsQvLqZU^c)+`_N8P_b=g!I>dualEW%=|L2N4ar2I737Tn^zqrvq`1;?LrM`D`? z&fF(0)j>QK7JTx?|D`7ZyB(mHXm+n`27>&z9pywyT(ugVx|z{8N7B$H6B$8rox=0CbN z?5Vn>*bx!TZR#w#G2(k)jLd91pisptm?WNSNx8m%X+z=Hnk(4#lWL>>vfJ5pXZf`k zDR;UKrukz>z^f7C4Z7&U!BfK~TW99uB+XKmpf)#Y=>@9@tpo{S#@Iu|41sOTHMZ~W z8nf60t|GT$;*Jf8e4-@P?J)UT3B*fBmg>CE8tKDigz}Keg8Qno&1XvT@RR_b>Yt`b zlv?r_R{~D3BEA$fyxOjIIi8=4rno1XLCugY> zSX7Uy;2jX=1FVIa(Y(%y_hn;GGP4qU8^VkSGl6b}@7!DHoCO~&@ln4Dv+=#+>xaF_ zM=;hYaK0u}SXdl2plbo=h{KuZtqGXwA)6Aa0_3ADW7dWh&i&#|SG&&p7?xe(J@>Jy zKAt_&#DiI{TY;J%D%NLuv%kd$C%C8^(Pcl0WP`)biaj_XqO4+`Ql(}ky7rx&Ts|$O zEu9krbOxCuxEFVAX{TIl^tn_mdD?g~(5d~78xFZ!!sU!dX?e#31*(BFt-b}8hkWPV z(S5gw^?SpQ=;2$E>YTul8Zj^bQCiqRI6of0cOR9GO+PfbXP~;&cyu05^}S(RKw^?Z zt3#I0I(SYBfeSj{)T3FUwXgSKN86#>@T7?hFWgdn46@qF><)Eh>PQ2NMxGvoZb9b3 z_|jCZq#otB8j#58eQ)x$#IT{IYi28ii4WRq@JC#0mXC*ULrS&=Q^6hajmG>cJ6csL^mgB%CPQ(k0Z2 zgluDCVOHasbDf^28m=ncq>(RhD?LUta^(lG&t2b+tQ?G zy9Iq=EMyC1Cdkiyw(=4|vVM7S@?3koHGO0paSohwOD2VXkZDxO3ytZRRx3S*tZ~~# zl&*BQGo4IatQ&3`+I+o{Zn>)Gb>@g9x1Zoccele!iOi0PaSdy2g-0KLfNW0Br(XzK z{`*pB$;l7vmLf=g$o~*#=zn3Ryrv)`k{T03^;rfw-JGyRc49EsMLHRY{>yA|E9CGB zw{%GjSLH63|7wG1QuP|4`d#4X>Iw5Aq3G{l4*&m=7_XBdhW`t<XFYv3R!1j=a1bE>~Ss zbqP<(<*>$PkQ2QYAe+ zn$jrjJnr3tKdkmB#jMVcj{>}LF6xmHAH2Ooz6Wn_pg78unUk?qgux@Dc(sGG_3onE zqVfPNNYfbaMiwx`@Q=giGwA#fJ^<^FrU?8iq4!;ak}fS6W7b^^6Fe{{eV#qnMGURh zJsv?wxc=6yFK}aTJ2*Ew${14#=zrQ3fMfpGp8|fmTKFs4IjW(Cc~XLPs_oHOT$Bm? zzVkQFC)xaRBwkGEBPBG&#N{OXA!1qV)@_xXKo1F)nEU)#>Ay#S31{q4CkNRiDsd_K zhdG%w4L($Vc2sqnX z797U&*|Ac&3ua0js!76rUrFu0F*3O;?g4huo^^o_;qM3m^MDpoHn&gm4dBQ=YL0jb z<1&#)3>vb=eH8%a(VJTiZ2$kn`=6)X1xuaiP~kEcO-<=3@0)sWp!UzhzgLJ&Jy4_M zGw4*G(<0t$yOD<^L7oIb*9z89ctU&1NeEzIFj$YR&CsrWxKqh*AoV*h*=AM>Zwa z96x6852zF}K8g^3J6O>qZDIV;)+YS;@c@q7M|WhI+bGNa<$umSQfnQS#JpKU>u+i9h)E(7$Z^cP?}nglC5eOsk982LW<( z?M&_bv?n>KujVj4_s#~*eiJ<>qOlqAuWH18;dQQ0uN;QX~5wT3$`^Q?7dL1S<*T_Iqno{`{pf-Kr+vzJI+;3T+P|u zD*-N@n@GI6A&f{c|8N)-WG9}6Fv}OY)jE)~RGf5u(H&_qR4Cp$hJ|CVFG%Jom|O_>fn8lJ3P2yti#Jx9jD&i)6tT%+ef7yeErS>>hmu9R zz$f@Wa|N}A^3-&fs7N!47|hAadeQbT4Ppu12@l=+vLDPwBp+Jq%SFe{7!1CZS6dvc@i)wxsy&fd=v3*K1I`Y>(9_ zOVhb*AWnr-30YodcmH7FR~3j?o5(#~Shicd*j7bmXVhWVJ`MFI8B=}0gxItK=86LJ z?lrS~=zxs9HmN#dXi_We#>Qv+a)3PM1+V1i-$eA9cld$6x3g7DQ&V;%hi?U83ry&7 z?mii&XliCftvzC1#FsNztttBE$aWVQprEo!q#RH+rQou%<6Y;~Cef39j z(W`{lo7MlZW4VYpoY&^Ae|c>+$lKQA=#BHa_T5I`%3)*>vxVAI&kRq$5Klzd`6?NAT~EK>TohbnbtC;u>Gm@psnPuJT@-{noLe--RZck*qH5{*zCK~n$rIG zWHRxOwz;7s*=?;4Eu$!rKc2h3<>$p(N8R;!EDtF$nCdS-rTR~-F zEgIqM5rC2K*<*yoEMO#+y(+!vd}SZR2f_rZPs){0*G<@n)yQn6(FhuRY{2Mr@}0qU z*U2+?_^W)P3S%~f9m%bt1YA6CXBM{_qeIfHa+O;9uL(7nX;O0RXnI2a~Eb zl~szmBexc?#;W%NsvZ5wx57yeKO6@8vOsf7Or|G^A?|fd7+IacW`F#&!<8#^Cu}Vc zZkt_qlYFbJCleR=K;JXYox}ttA~g(>ZQQq%!FS~;ot%Bkyg|-0pq~6*w=rm71N*`0 ztH^5g9(SP|zu(G4Zpv2yIVlP(eI}#Hur5bP-|(goqlX1Hj}$VRPE!U%%X)n}kZT+w z;BvOnGU+5R^c}6mIo_bJYs;lf3msztBpa0PJy$M-(Fy)|^N5LUvjlIl2rMTtdG2q$ z)HZ?>Kv71FnBkS|uFjEdx;0XDcCijAU#}|^MN9@QhZy(XQD4;gM%hKp{JY91FEg3Q z0JV=JkETPju6|1maoeP8K%ebkB9qmHK1X9S5gK5y5?8w%)@ZueP`)N&@7fZ^>(881 zJ^p32KnfNrPxVHgYExywO5j`m8NcvF*@|aiXvZ;8&G1es@cd0L^HIeD!GL#;t%Xpa zo=*;^bA(rjY%UT%52a6u97c|sE86tZJ>9Oq9E`d;rl8^f2M$yfMnu;vOGLZSbF%FW z;HNi6>}1xnwe^dox3g4^#)P~n|D^Q}j#q<@`O{9(6%!<_9zye*SbLohrq(NRn!L zNJu#0ZpnZ2n2gEB;-mdrzPI54=qIMz^qkrIfvx;;ufxhy|yI!s&k zLBbEs`H4}c*FJ?$zJDYZe$!rsn?)>im#rJNgC%_S(x!geBdh~cl+Ly znf0DW-zeTOuk7SBP1Ayl&@l|lST0$S zvr3ijAT((rUCAp4(ii?|@^~YrtLBIG*;T0~{gEci+Y8%w^Kus71v)~y5U-mpc)a7R z+Z;FEFdQSew!eAO0JhWLV)fEUaJ$+pbeB;Ft&Z%gP#^p0aH%UhcQXe~6sai0dtV{Z zt&jH&50dM_k)0^#_PtBgM;c>eo7bD1626H9>%DsQoP~I3iTO6=V7k^8J1BEiE(98tJm-R*7fxcftwe!66@K^V07$FqdC}PYkmRDt z!H!Z;S*DnK9!wL=bB0U7J45x$7#-2OxGjbZouX$nU^h*C%=z-|Zs5$XK`El6-%6zt zuH{4=>Pzq2His4W=TpC`AfT--X|GH`dK2w5*fW(1#x_H&VS5ts?^Hz?ailgb(8&n; zFH1eUbBFAzNZ~A4jWT)GY0U3}dYR8E9lP?h=Y!c`%N;*1b;!+*5eP*@$82WbnYG?x zVojZQJkdqXQ>!JKYY>bqsa^I-KxGcnj5i3?j9L6uZvg&0qySp!)q>@?9kL^J*&MFp zLL2N~>V>1Quu-JClOG`>hBDbw|hwjXlQ*fS_IJ<~xBmbUbgkCjdBt5D% zj!8xpY#~jECEx-Q&4$_6*SCB()(S&Ol7@}(=v9RmYAo+v@L3+!N(ISU*VU~J`5$NW zxI}ZN1SBdaK&tlh_C#DwgRX$x@w!R8Cf=@snoJ-myo0RZ6d1^tx_um%< zcH_|e$_{;S*8x=E@gF(X3`p3&L>cfCJG=3<9~jVDpQ7)(H4(*XYCFe2s(7|ugc2LH*v~v50Jihe0eE!$P0j*2)TQ36K6>L00Sg^pLXiTHTwZfb-f4x zq=0%T1~VmE7RyaZKyg*~9!m0VpwMX-2$W$qRgmUPa*tO4O#|Q+*8jsRu4ybNW;v(3TnpJ5cYC8F=X>Pb-@d|J`A7|7TjMDA$k+%=ZA{miWJT z^nN91>glzc5`kEgZY6-6266Q`Q`G8g-T;%ozvGFAGA zf&7EC07_xRP~P!3fLE$D5r7;<>X`oJa!u@jEk}-w^(irLntu&Hc2uFbzut3`UU#qf zS%%qPy9)dv9@BdG>!B`#oS4e;m2c5Y2`$mujG7$981LQ;# zyWpSb$wNoBU?)rUw@w@0-#xt>R;Y|u28P! zJh8JYPg=5ZW{7s@C<1SSeN&RM8R+I#7k+F`-Pnw5)^kQMx_vK+9NJ7hv_+~iIN874 zCeWkp_Bxde)#%rWhmW{=?1__XAFK1P_=?-$?s6Uom!iPOs;%lLynnKq{AiYA6QTT@ z3t+-yf8jq~E#ufEjm+bY$FecE#Ls?%%d4ae(fT{u?4ra=3uICta}ht5nAl^tRn$9z zEs1$Z6hcGItBh34P#_pDps`N^9F)!dLuzo8;CGQ%CY79vSKl}d(Yhz=N3*4KT+fEm z^;=Ony(<@XYbAJa25B=AQ{K?eWK>gubR=&<)EWxu zvv&r@SdFN)i|m*;ENQ3|I=v=6XjP@Ur6M`+uhOYJuG}@|Ykx=JQ}gd)>h^pfDk-^7 zHTbt_%5-3?M^A&CmmDpQFHvM^WJhTbW_7^M6CpSWuhM|P)LcW=lY;&XA`M4s_cg*A zq4`7&{zn#F*6JOt;f?lE8_XX-+Hy3NL?yCG{0zFsXEc2{Wk&1kdhNqBK0klHekPxX zJclxK(s@RvdL_r18Qy5)404)0Vse>|ZwcC{%spK%5J)Vn21mHNPq2=|e@)flIa_<& zTpzQ-aAr$@t=I0cmbN^L$(7%0z523TvlQcjn6}jDmTOT69Uq=&C)eqWeP15u0i-FC zk5IW|>B;m>sLSbsp;b{zcVGbBoRMPQ(h}C#Y5YmuX9C`jH=jd@yA!h)p4~g++qt+&I+S5PhgVQr+YKfcQ85G zCmcTqZ!X7<-Ms1RgH*Zp*jlu&nP7Strq1HlydcF#&NR2)AO4C)SCm@T-fBagMWkza z*YB*iC2qCb{1q2%>=he-{rwAfy z>0Hg*B%TOVd#9KT_a90V>DfB9jEgs|Dp2DaJv&;{qP&E`{`j&m$&cDb;@~uXPA7zL z`xb-k*~8g5OJQx|({zF^n%=#!!w{B5jjg8&C<3FUC?`xiuVB5HFA@|2PJBxeD8*H^Bm^b&B+h@G~}ov2=Zu4&dey1L+0)@MHtQASl62o{EW`Me)bo^jcpdr9iDN(DJz9$nl*ISxFu=utkR za=IG5UTS5?e1BYYcVXW$n=H5G#qjl@G4h-ZuOpv^o8S9o=L|bIiwk+(87y}zJ-YR* zNlyDQoqK{;|F6BPQ?1e-Mb3}KN16L|_WVLOO97drttUIV(_!fo0UD2`Z9GMhEg>T) ztq0jlh`3C3TVdh$&}}~q)ryFtnYFlAmn{R9V~k~JM;3i;*f*y5JKv%jk|i@}Y_`mA zOjSm4aHa_CJQyyARJ)gCAU~h^=$If2EXMTsQs?7JfN}(q${8aTCK8V3MiyM$KA?Yr z2urA_d!C>YVL4L8vPB{)H`Tz_(;Z392^T;7KrP~v?KRJ~)Q70>EW(_ecSTiS|H7#S zEhbQD$bDWi?v9U>EHP*Pg3%~{^XZ1???)g~f-SnWy|_iV|Gd977Ki2t>sbT%V4xx3 zuzQoMT6Bsj3sC%BYMNJu@wu<9%qHTSLvJZZ%zjij;?kKpQc_z$iMxORBE|O_XX&+Xu^b*ILrdUvIEahS0@MN}7 zwn!oX*9F>WO)M{hIEiZq9oBO64ejZ@uu7B)KSRKAY_7_$o6M-;5tLDOhC=;uc5ljknM(gx*j(2M$-9=lXAMMczq@uW>gVV7Sc`N)9J;{8p>wvL=?MrrTOv z*9<%8dgDY>qW@uw7YSZ4_v1E$DkeQn?rSei(jtF)?UmDNdx%cutqo=Zr(efir88*N za>|6Lw{=URf`2_}RxN%V{jniW5qj#E52|_rW3hj7^ucP>=Q8TClu6X4&5xhH__-~^|2D?M;mOC14+a!>2hnj;SKS5c{9 zj`{mvU(bJTU-hG=z|jv0k?V2I_dmJHr8`i6hnesqhW}eWW;`~JEv8ATBXu5AYUj{U z_K(vK;j<$0w7<@ROHD&Xjnr7eWXMa3-Siv3t=$N+%D)H>m7}KKL*cJB$8rY>m|NbU z(9zW5C)eBzhGVBlm@N`4R$E<;c^M#)b5k&R$>p)Sl1aG)XNGd~!?hbA38m7Dd zix`MBye3wPMWv#mbf_k==9<5}2<+j>AI9*1r;UwGkl3K@`z(<{ZsiQ=upCmI;Bt_| zlFDK7xR{)qA_5$ySmL&?5TU5_W$LUN9x)-wPM+j;vP0~8z>w~`?zoxiz^`D!;Dcd( zbj?>9Rj!L{ApKe&Jh%SBB3NhK-PNn zHd15D_A1OpKSC&6N?dT*K+a1-(vhQ^F9ST5H&Jgmrns1xhvy_Hyb19eZ@Vev z4%Teaunwb|_n|8Y%bbyh&r=eSQ9`*jHKddrPc@Px)l$o=e5xaxI`THOJZsFow($d&H+%8Fq8FUtWn3C#mIqb{ZAn zuPjBu>X6XCRq^gm_;ouRcPa-4Z#W-+PG3O#yM~+I2P#Do zQ2ZJC)b6mN$~x17#{JTwPL+M8@iXFdsyKr9l@NuX-gQc z6X>hQeXI#(o1R>5A2uyST!He@W3maSj=^I+@XCYwPO;za5|e}=8i zC7Kks>35>e{5BPxHlbF#cPbl`E3caUQ@n2MjT>%ycT-8Lk2reE_8}Pb<~1zeCSz1= zd%XpF8Iy38Ds#{E zQ6mgm+FI2$O?zZE_pL#r<9qLZ+xNU!H#>eskypNUkpinOB;&)H3$pV4H}Dp>Y3fb4s!OmJ_5$&uo?GQ(&#XrV49INTp5l zOUTr{1|6H89Fk?})f&<{VYF%)lUNFgAtket#D>i!FkY{dy$qH8mqRuFk+R zaAy7gByyM7{fhC)*_n-)X`XRrV7;fc2Ad(iviHlnMG%{zsEFapZo)IgzbF?F;kpyI z%;z~-?XJ^}#W{y%( zQDNiait6dTQBqP`)sCp5pr#H?OnlW7Nk#_A`3uj2CGe~HP&kIzK7Z^#ivO|q2{MKb zq`wlVrvgcQ7QhL2No*#MKjyudvLbYAv0UI>TVKcR`?t6W@C^SS)~{TWmlY1aH{o4M zy`_DVneATz1{>Fg)*h6N3Oj-=kYuf^J@wAT!9AmhZ3#SuI{++UP357HP3=n;aG$L* z#R&?UeSQe=EWo3axNY_868_2uIr%t6=C@{F<@ZVD?pzvMBbL=m1`EZTxq(t8g)A$U zbC1>T6Lg;>8~=Q#``?;lN0peV`98B$$)t{rEvrT8l{^%4v@kJpk$U_F$fkJeLjXbg zZ}!0whet*uyVEx(Ly%^rRI)WMf<|X9I1exlhr!)xmaBoQZ3A`7O4iDT8{+T5eSb0$ z{x9R;O6&dm_jL)(hAvIrtJ)vvZr@GnE+v)ECw!xmy_ceYyq7HC4nrT8tu$w#*X`qf zDIsivhM`mj;4Zde!9Ze>DRmY1jE?Z#C z4$sW_TnS1D>_yuA`8^oj`q@956d!!(?1g#r^#$OPy28&3$<0KIJu`Cm&kp3;O0jMs zfN(sl8M;|ss@ksy+ttY7tE8@E>}3 zfr)}enq5;9|LfN;#wF{?{4XM+qAX^U`GV?6_v4ZHYCM9+UGIuyX0tbEv;FC4x7?D` z>6Ck?W~s1JU5iOjc!@&|+z{RGNENfnU^>+^1AHgVPW*s?^S=a^0MLzP_D3u4qobp_ z;ro@1j&~;Mu7SUPkq7*f81m6yNH`$tVTqx;ifAC@jH%6p`;Pl`6*V*l)lAX?EEkrp zc=w7b^MC(Fz3hD8^$3`GH3D|a4+OO(w~%U&hwXEo)W8>@>Pc#5>vZI-(vGUWSK1J4 zuhWiO&QkdNjsdsr2hCEZPxtR3n+X>eSFbv;dGfPD=X4|F*LM9@TMeQPtyDZSd^5#X zOtgAFsCRv5)aXGV{K2KkRe*3dM|yN_C-_VlEO>HSS2uoJfFdgp>0n2#{$6@Ei9EO& z#f2Hrn9XS-;tD*miweXJzFkf2^tvz-H}>5I<8zi zNZ#sN-y9)?s>(F0b8KfJR|9ctNo*z*t7?AQ4zB>vQ9=jE`J>iC(q96&z~@2ln)qAS zZ4xlI2fZW6N;LcBbRZsYRa!3r2UH-^cZPB}cXz_^8it}$eqx_+42zqw8N6XSwhh4A zmlyPai8{qQT)#aS5U}vr6u@M6@Ms#a#Iosj-LhQ<{vDshdBEIT!BOG$iWmKd#DWDE zt(}l@w=>R6;4Pwav@^KYUa#SEgS=9}!A}c%!!m1reVhOOtO@N%YYo_Naad>XuHY}Pc>zC?ixQ*N4Z7dWhu-^d zuh9*9c+2R7R{DdM^}t98Y+S=n4)dDM67X$O9jVx)$hO+^oIcBY1h-z_T8?jO4t$Rh zTN9{@OGtO~<+_-R;Wft|97z`!vk=JOuMIpO+dAq-TDMW{ZaN+9h1zu3DUV2YS7DaH z+G%)L@9Z|~oy%P(_y9Pd5J5Qt4wD)&S+2|PF%UXpEI%FRDLY1TiqIUXWlWbIhL;|7 zRi;4eIOFE>blP}mBB?4$Qa_?lNRkMAuX{=(BCWgJjq_75!4ZppAkZ^_n+!$)lT_d~ zSK?&JXll=`tvSA>p%Rg~LC0qR3SAD=x@@l|K` z4qrzpRH!-K>gQ5(R=3;Kg+zoho)lqaWy|?InuV?6=R?~YZ zDb0$C&fdYWzUaW7S=FX|cZXye&oFA1m#>_^{CSL)?e74a~2A9U}I+j*iNKYum8E*~oEBA-n z&9vA_jx_EAvu7Zev<|{xLV+{_oL?cte15P{Ji9gMtNmy$*j^;rYm$%m7^@2I*F5`FlvO%HMbDF!}iPD43GK}d}x!IQ^ho=rQ%B1iWkd7CX3cbu)Gf1#6rJM6lThup=$5tJnb~^eb^7k`57sE-w!>u_!L!CDvgH;i%uSs!rEc{M>BBP?PcqzYn}^q zZYmUdQQJCPpj60fn~!{91rmYLPV@(dQQP-~>@QVi9eie%P~0`74iBLspX;17ok)z{ zG`>rbE9WBkc_ez5YFCShi23B zB`DD3u$V16;L*Pt-eky-H|et5rxIGhS0R<^w{Kl(Ft^@J-xB&2=EASQCJ_>>f0n(T z_I<+=9=0s=f=2tFhYf$acwb0B-U#ItmicnKH%`c{nUoqm?LhCPDs`yjZd#RrD z+0pMr@y%AYavsUc)j^*Lde75G2v{-No1}Pr{v0+cI8^gFvJ|HjFoS>-VWg(KGFVdR zmrNLzO-W8ImwR2?nzOwnL}NBi861%dgbMZp1C1~5UpscxCMPd(T8rfs0z7SA2!%tD zNar3m6KH>^IbvX7FaouB3a_U~=|DU1Rh!*7oEL3T00^MzxM9Z1%F6Aq{k+oHaSc3H zmT*w&`62EQbnOIE`0VMEjCDHKa_7*~<7m`>PAsVEW54+J#r1J1Us6?hb(4bTqh1-~ zi*0czb7`2r7GGlYIft>^;bvzOMc2Wy?5AmYu_VqZBPX4|_ZiS%`RR(`=E#nn@Yq5})V%N}8K7>P2aHAFuV#=*b-ic0p=sVp){s24oKse!=^- z%pB5@OfEA-&9QD4JsU}TS)wj_u-pvw`8X;V`bGUa1y#UyQBm7LxL4vKP>l-!BDe(0 zFQ&P)YFI0im6V*6y@YPl_wIeobuYlzq}c;r27ov5ScQ@5b_)t!PKUXEmzHjIVhMqB zQ>>n8ULJbi0aYlULK+WSWJ&Tfb%|0inKnd#EG4^BAkkrcE84pL<$HQ{N+Pk|XbrjMz zT`Y`y#PJMn(HW3sDVb1&>Nj^(UYCuJN1$_~YCm>=oiqzou10ZUNhn%8{?hA}B(&`M zC}~*xP0GNF*PJm$3YAH(u6-FBzcH8}g1fVcpsS;iR1qHO%Qw`pHyORM{DO^5S?>3a zD!O`mu}hx!7M}+c4w^VxwC^J3e;N`3rANyucn0c=Qe;%?2m!&hS1!y}feJjhf@(x7Hr5+?^U9O6VRSUtrP?29HPb3JUexzd}D~d#?uIN5{uc|3=)f z26e60pC-ERQv$_xy0ZHx68Wq-kxCDAGx$O#v-K}L+7r6^iK2K@+dtM4r7Q z%WW!&*j0b!-9cd30wZSf{wytHiR7A+zGdXjVxQNgzoNf5iIeZTiJi`x%fd3(pD)SA zoZ%YmeULF+zJoox{BB@CUm`5hKUrVU%NdR5JTpC0(U?AcWZER%V4i+Vb8RL5-)fB!`JrYE~( zUt!tZnd^45LG0{lk7{?U@}z=>R*?HRaXfFv*3Nl`y!K&M=GE)QOX6Rd%`~$m8xp1r z$Ee43#ejA7PB=iBZx#=V#6p+G@rai@y+?b7eW>XsyTM_GyN)wo1iS^wlBnyWqQK%} z(R&VdhN~ZP?^aOiaBw&fA7E}^Q+nXfv}SMTtt7Xrvh&i`aBJp!ghr4)50s~a?wbe^ zu~KT4>Augys=BGxmsMwp+HS-1^Y5=rO24CDz@pb{-w1U*O_;HT>Co8C=a|^cA7?zV zN?^Z1AMv`~@;LYg@2lIzgfu`MTAZ>HIJ~dk(Vgr`raL}T@q+8;_Hv}BQV8_glHVDL zPaBRCue@RlnESG^F96}@|DyYb!E84=AeLas&6KKbHp36xlnf;wOJU=q2Cwg?LE1_b-hC3$dZcgobzh?Bb zbz5}NVJ64JYkuk4VZ(r%4d3>*Nm`8ahEXqqCj_Oi0c@9@6sS&`JLBK_s7Mmbic4KB4>=VqOo9%t~||;gL??-;@X{mFA0N;taIy z9r?MI?p>ib;tZ2!c2#irn+u@c=-PO18h(zmK6Mlki+0>Aw%IFwV-1>qAP%B@d$?@z zN)kGnzel)QG!FV&x{=*7Laf(Q0Om%S2!xGF5iA#$S5kxNGoL))=6Gv)dkF9?Wdx%F zmztGq5i@&6@QZ^~n+{Z8OTi2*aeQPS=L97knKW$C*uwCbTqQY2N5qoEua8w0vxs&rwB#5MXKH|Rp*zMv^({#Sd}yBSW!)8dl!6FwW&BSR z0F6vQE_idMpj@QttM^J(>-tHfY4U8%@O-s-60_c8gnQCKhrUvwCxV2i#^7F|oK1#v zEkA9`l}VW;HtUM7s?hI#1~6M#>_9!+tXO;Bo=*dPRwH{u7qC9a`?$Q`n);?poV4Sw zMarIib9&)&g>e4GZupZ^A!j5cq#~`xnyK?CXA1;fCD>-$X#=$vX?+P8GegDOXI{;* z+VPp1s0ebtvPp7+j@Nxk&~&i|0K)a|bA$kjY_8Ho;meozz-F8;U%nvhgIdWJYUUc9 znFt67fH~A}r7s+GCt{C@1hhnN&*GgY1cq*J*H|yJAetyj_fplh6Iv;Ot^2*BR(*Sg_fM_O9%9ypU00w=B)ZnfLI(BsXZdp?uJ)5b10y?85pV7_E|v!Dj>B}GF;#`d29f=a~d zn!jj>-Xp0pd06TI)j6BUIlFOb;jJMqHfp3YOwZAg1E52w&8Lg>M$-iVSjX&n1spY) zHCJm*rd^r?A%)d>Rv0{E}CvtHukJMXm6 z($b2Ei^n7<&x;p6Yyc%_Y8a26F<4kKTVF_+H(Mu?yj%?7K*v_N03SRIxO6{7&yu4P zov>_FnVwU-Rm;DBn_E8v{XQsTM=j438z0~PQCtNwoBp;Z3)?m;J7D5Ti;T!7(joQ( z%ZSus%bMf!JxOkohha4sucRhD&;b8%0So-g`gU6V0?Tr8bP|p8J++1W@uDrAV;gWs zWg8+Lp*vzlgv02mI&HU~qY-3`_cM#IOSc=KUDfvc+bduf-)N!gHS(fxG-E9w)`Bzq z2>H>b+^@_4Zjjrq=3;>t`TIy<(MHb3GbK^O&upE||FfTFN2_H>ZK=iDdI*1MHsINq zMMi0F@1D#pXA8n!RwSy0j_S>q6}u&l)`Ky7{#eJCWdP-e{J)eR^6%xZa|`n6JY^tG zh@|^!$$%r(soB{}1U#ifE4*KBaym=ad(W|>ZaK>F9IZPOjsQjH^7emnxT1WPzpnDl0<0Loc?R_S zKd!zqAgZown-EYClon}3knT?D7LabFd*}uMDJem^o1up8?goJYq)WQH;XB~-Joo*6 z`v*UOIkV5+Yp=N0wbp(;L9C*gpzaa}#sEN4u);sEHyPQGL$zBapPwrlwcwv7j%V~G z5&XI8LG=Y5_9P-_sm&Us1wp;9AHmiC4#U?wAza|53>s2P)!9oo+Cm=bZRU%nDJ1%u zmkOH0!c`Q;X9I}G-A^cN1hM}^xwY99%o*tE!wz$#L%i_LKyb7s2+LJ;s z7jniKmjz_0R>yVJ@j(mOMp?N zl{)RtMnXO$j>r@z6B5Bs0diG1+ZPNnr_3D%t*GDCvjgFv=fAf!J7K|cc{YZvbjku)t?afXLI9k z)M{W>U}XYw_T}G`LS%a29bTA>=^tH~ix6N$MUx&t^*h$l`1DD1!Cja{M4Q-CrsB0@ z?ks+-rR-q4oXpO}8BpCf@_)983~_}3>N2~p7{uLC&W#=GX4$YfdwKo%ge5yrP~vu_ z+S|{#wQ`SM4q_fX64*%?y9-Ggy#KKO+zPz06dN~vDT%34`SMIT2&(evOaKdnw%RN%cKmKQPOR=zp}~67VuLl45|U}7#)FM zSf(0Xjb~E_$E$h#xw(`ZpBH<0D_7nad+d4dqV!Acm50qanN!$%)%XWM_QxT4mv?bj z*@K1ul5@nAM!A60HXk#$U%O+x9nUM5=B*R83xxJ|J;p(UAJ6RnSX$v^@-IuT>Itvf zv$K?wzRsKpHcJcyk_o*I`!7vZE9{3jYS;V7o6DV08qU3Xfp!}{RqM#j7Y78}H!hK| zDuBOnDz$;QNw zwW#jgc)j%!7f$DG8qA_>-u&ShqOqC|aDGIB4IHZB*ydsi{&yUzxm6$c&Rlj-F$kDk z5GRlQyPHD_qU%*ymHTD>VJ>#-%;WS42=-c8lCT&FSx82 zIZc1&y7|6SYbi&K4ucvvec#e@828X9XWOque?K;n?Cb&ehres&e%Z*@iEE_96@6-B z|4;oQglvg|Jsyp$Mh=7<;7mha*O*hXx{Z5agI^hHqwUTMK2+*!1dc^ zXE{W)ZLZ7nmfDAdPseh75^`J*AzF1F?C-Rf20Xu~@y)evNpGvQoWEG0Jp%2cF0P>Z)cY;676g*wdcJ2fmXEV<=V3G(TaBH_#EfbEdh z(}zPXm(oYt+7K}AGHaoex6?`pjx`5j$oea>eBG5jc*nZEJ_}Kg5f|$QdoY`tL*d-G)q0WH| zR~Lkl_0A)D-z#zGrVuu1Y|6W98-Mbr!@YCuUbj(aGl)?2ZkdqU@@<6uBI?}bl76oD zd6JgE!|RsjD`Lx%GXWxw5PIIUZA$jiJlLX44wrR5BdtbOqKA#lqITR`$F&Go@0GRN zr5;@){XJo=`w66JWeeduO5W?@f!c#Z0tkRKczEUdwKv`KU$7gMJR}x+SB4lsE?+o% zZOFX6_o8c=)`FY^`2T+fvmSzKRQ2tGvTFd-pP9?+IvqEdjfN38P-&Z?=HBQ`P7aeJ zpd(Fs*pgjvoW5wNO@07Yda4elsyx}8C9)RB(=Kcio!tKG@pf)o#u4sum5olfulhLW zRwIpCN>hw?(>WC?w#~`!w4K`BL}@N6djd?k#;+lA)4eE~Ql&7N8^=`#Iz3z`a)08X zF2>qNn9ZJj`7(rrpQP5ALcJgOoK(qe2ZMWend^kALW)mxi(~+4Ogu4mdm~`RkE_G!lc(dEX8!&k6FVl&yRZ^& z14S?*T+EiPpXuh9qjPI$KN_y^*&f?-gcy@<%hYgyra8(sCfeXrc*Y3#-vd@!A`cGQ zdr7|1)D^ADE}%XwE=AQYY_~f)|BPSIurn%to1~-`&c+tDAw+k%`*TlJVxpA!j3Iqf zUi3TVFsqlKFe5|XhfXtl!;A6T?HLp`ue%Z#hYss-7n=Oy9lgj&(&L(r=u-us=1vII zA@`8fJ>+gDymiY`Bb^0~qYCQocfOq1>wB`|ay@~o{-DLQL7yn4wA3~!AOFAvkzB=_ zJ_UtsjvC4okeNK__aoa=;R*O3y|D7|?WZQQaYv8PiRs#eDk**z|LJ&^6|FjPx_GPh z-y@G6Nxv<%G>xa7FX%t49Oss}UWWE;7>9JbEufp@=jRla^x~3~c(IOP6Mw5P0KqDg zLja>ERB#z|y0PznKr!dCum$b7Ef6%sCu~{mcGGYC;wQ!wf4>weO-8q`wLh&W1Jsj` zPg&o4jMl24lol>5H}7~!uD$nO?hEwpqMJ(Xh{hpSF*{K*?TlPGvRyiiY&}!y(nn(q z&#oO#jZSeXA2Isl$zdx#&5R=#{CuV*=`uP}O*H43-JbwtDYW=dsnGY_?6Bgtcrgp? zP8PsJ@Vc-gc5}%OFQr`{^710Vc>mgec))`PF=R;BV`QRLQ!Byrq|*5eFeud}`GZ*! zsTKA*S%EO7y&M4dw$$?Al-}v1(UhchKX@H~o@_p&5`FLQaXbS*=hQPxTX#>EE6$d3 zXf9wp5c`R$kec#f!u#-0)4tZB?U@!8rTu=n*8P3W#$|R9k*+qC`@-GV%xZpKC0)6r z3>UH7PCeB zbGRAymA)m!UYaMXP`NmcgVn($$%heXV&nr|=M`{T(saSx8lEZA4r@LWTHvZO)e6s{iDcd@HGX?(H0cKi9$Yz)Z$f)! z(*0nZ_NxjzW5iX;!PR;;oAL{Z9hgyx_>O*?oZ|?4%AZUR1H2k+sp|Lq_2@liyGheU zx@=*CpPNTQ{8fJO5rzs}uY+}6s#p%Q)vk8?90DK9Cj*X2$Qq(OOl*JosS2JJG|2p*q5t|hE zF6XM+P|hm*6Y}}?vJV$F&mdD5n~I6>yzu;9nP0-|%fTG}#$-TqnpH_vUR0*n6MzlF zp$)+yW(RNh^d=P4&CuD%3Y2@lD~mr8&gy4n^7aDEsS9Mkh>KJ=KQ@mAs5)VUJnVDQ zk0gVwYJ8hU^sm0YaFY;i{Pl^KL?`P*20$|_n4;h`aR^NUF^<3s*6I^&Oo3N0KoGRr zJ3T|wbK6`~JZ&_;QMUIZCI=wYAm~l*lyJ;?H4IGb^Ap=~_Z^VLYnOdNSnY{8_$grj z4nyp9+M7koBnEq&$xd1ryd3{Gfv-+yc5vu{@Kh;U`I|c)8QJ_~ z%*>!zKuA3LP{(+drKQZAtyN$iOn5JPXAOQT+#8Y3aMO3ZR*l1Wgp2$9FI8W@yQT&@ zzRh=5W2au1pr8Z)GHkkn{ZIKwFUi=fmB-0TKUCu#XN8*K6lrxkyCoVmab+-kepm?* zq|q3U%Ru)W>8mG*_BLu+bHnkhZPIfXSck<>AyPmF`*73k>su)q?mRkyR6~;4fkQrm|cO7dKS_{Q&w=FEF ziWo9(HvNk`gO0}t_<1_>x;8aO2)`Na3=8|m^{kXLfM959YLqznfEUPKJZDwOv@Wqf z5{hY1*VIi{7c~bd7YIlwD;ESwEIty2{yUff;!uQ&#Wlsbb?+pw1bf-!yIl6a7rJSc zS|GzhO^q3(e;na`3`SxFgODHH826MAq=BrNmx>d>)X4wCp!o}CytHd$k@pjZE=1eB zX;Sgue)S2q9|-cC&S%S!Ck$ry0>Cs#fTtggv*NL#4$KqZv~LHOAp6=R``VF0q6%~T z+T#w$GmGY#q^qc^e%8_o?O1LdMS}163;H0ZjRcNtyn7GiWi~fK438ZQMY4rmAy|6O zX~ZU39X@%1utp%4?KqP+gU?43YiPL==BPgR{`NdQqAR66maP~PbS4=QI%APSu?6M; zu#KKXI%_W$fA$9BxwP<*?ZjdiM9A(5UvI3LCd;&5Q6m^${Xu(PjQYziIOQ55eMhxjxZlV%W* zYEW^|Bf}lJ1s%Cl0OV}-EjcCO(sJ;(+OMt9m=S*gb_wwrLr` z=gNHkr;oJ6rUV&VBM^MA(wt#j0kJe)T7C_?BlyQVMMyP=9WmcbE<`C0yOzF|dV)B+ zeY60ocTY0G=|NH|OIjEtVUfb`4z_yIJ1;q|37^R3h#|2o@>3VfW%c9TQ*u(~9K8Pf z${9}3{+gz*jwC1$sXa6IMZJ5j{I(NC&48lxbY+ojY2p@z*(b0LkN&jb@AD8JSzE?0 ze!a;wc9Fimjh|1TGbi8=JsM;oRLQXBkS+IY{xRiT6=PFv6lszO??zG^r2)rLP!pSnMzU6H)fY>+<%}p z36^j^O?cP>T|f+tjL#$`p!4j_-95wx9=Em)AGe*x4Fe{ew5C+P&M4%VRgZ9hHLj|2 zc=kLsy=pohS`aaR@4}y{n^`VY%bG8tSEc@V>X>k=5W@U*P(0GRvdxR{#{u z|Bi2ek~mSOq?=k6_bZQ3Cv|>kEVLz0ECZ`W*QT8BG`1<|GF{$eGoYStwPo2m!>osz zQ`lDMfW`P~-hh~mRrnNw*fIa2qQT>(f0uUVzW@Nk=g+N|lK?&&J8o6YnToX5>S}~f zH(owDv9?XKS(Ki-)v)kT3bX&WC=3j##2T9B#tffX?cxou_ED8)_%?84R-!gNw-R)H zPsr*5KnwhxW^dRR=wC;1hgXZqS+H-~}y1{tY30q`s8h>Xy%QH8R#!iFd3CvypyW zZNWlwC~t?J7>_czLdUyl;(P%At;+`}uTomXuW@DfPXk|}5B7)Wspc$N#UrbNbMa^g zNjO*mh^nDZ6f%4H3(2Fi#3x?Dv-3x?0YM;ynq_Wln}Ahe($oE2uI$y>Guquf#;<#R zFsiVRDfYjkm&AD8((G)#sz-Bf!)D>45||6!>~-~2|D&P+_^K+(V4_(xyi7OCB*cNt zyvT#gqtzsBxlf;Ls+vmtkqyKhbGenWQQEPU0vSkNd2=qzdp9(=x9orGz9U3)#`<+G z`t{!kjbRYLr7dmVDhI%|v`X>813eWpX9T4DtDlrLv;8&2)X;Mw=vt6yy7L0tIJ7b<3i&V z7`M+qHSZnfCctWaaNuQfuf6#Jx)(%^l;~gTA6~!WyR%>r(2QDhg&K9BM ziENHeP96+Gf7jdFYkJ`X!1K_F35Cy}#|2O@@wx$$WzhHUU!dRxi-h-&MuPd*w=8W# z8`TWNlgG(ZFnO+Ys!RnIJR-Mjvl|9kS$kh!y@emWe=fn3Xf!j)?-nAUwb$=;_ptyQ z3p^v4m83ltnb>cK78(!TGB{V_yx$G1;M=(lw_!GXc?#m~&>Smft3KN>`QQ)TuEE+2$aIZ$3!CkM93WO#d!eFO)w4<4_h@dL_BbTRFYqVZ_Is zVP^96tZ9@SCnlF6+T)g*x`V4{vdI%WH!pJ-HeN`Z!t)Va1Ww~ELoh8J-do zT%aOeRb-3$OSOh;8&Btg+y=W)ABX*|utzEFWmHgC?`!u*DRZyO`5shBM?({Gwj=CK z^ouz4ZNNuiVoya?Aa%e=03=}KRa9{P!`(jRW-&pb+h{;&`Dpp5&QNqW8`zuals%4L ztcw#z@|$7Qea?MW4Q$rXP_N!yyFbh&Gcz~a1(f)kkb%SuGf7M}UfV|t%!+EX9-sAP zE8SZ>hbHJw0|BE)f-nyOk@>PS=uJKU^_wMA@Y@2Zs;l#P(u?s0riS`%$ab;$Mm3Q) zSdas1Kd}f9X~wp z$$*<54ydLRo>&sB<|&T3+X0Bch5jYIpnviPhMOc) zv(x^cqqPC5kdSv!WM(^iShZR&zN@RNqMLTyQa+;4Mqc2TRE)C7GYLPb$;R+fP%}6- zSUnf#-h8_@VG^bko+!eCVYixj#;Veb+juG%F}XlUs4U@(HRyzO?L_h0%GC?yzOHz( zpU}UcZ9}f=@E^YvPYA$KFEu}2pNab`=++!njgQ0r{+TjVO!TRuwbIBXF*0eOJ-3Ye z9tN8PzPHTE&d)l@O8rlQaZ3Quy4DLwX!=lJRtrsBoov*&w#3e&AR{LZne6ZMUx&l3 zhC>d_5bR9g=R9R~VcM!1R>yldP-JG2A=tn+vJ?nmZxILFuRa}rGT_pz!RayT4`(hR zH#u$3B;fQ&7b#*Rw_I;)W)K(E6cUl3Zu&ST8K#d#elTj@1 zxX|b-xJf;+^oz|!;9h>BB`qT}57t_L9GBImjNq1cyNHB2^mldf|4bWj=nrF`&Ahp0 zHaXi$?f`bf7P|oW#b~=<-(ZzyfG2+i z{|i!iZ&esIL0oVy9=+{jyfSKCCU0rp+TKS?01$^pKZZdi$Rg(Vu^G%bYvO7`QLi5=XL~7pF01l zp1I^f(t8vCaiXib1eO>rIUFZVx7w;G*V_iQLj`glA)5pKK00G#QZ|C zeh6>kAs<$LVg!eo-tz1gQm+e|S$%$Pp~tNy(%t=&kqqOGA{b-zJISeUmC{Zb;9dBh!>LO zg8xu=x8t$=Kz6mLZNj3_au8D42PsLVM?-6>Uls~x1kn{F(>Tem1x&oOLKL;H>q_AX3O39L7py+yH=j6O6 zaLQ(47W1Zh3RSW%61X(KPQW}?9RLM2%XBZaYyc@RL(w(0Tx}R-g(oGi6zE}%Z=owO zSnYO#AFnHI~2Wagf0K?jw*@>go+&<}#B3>J$!ycGs` z9QVv&x_5`l{I$ju>eg^2k|!_|)-P48@L8x+|9ogIcuzm(!$TkZCpx;Dnw=)i`+loL zMC*dM*=@#f4u;A8YGr8Aup$9PXw3{=-?fnpUdQhhF`5>-Y_a=%8F_sYgazMQ zv|JXmlqp3nnc}Og)fW0TVOgkD5NSIM2s0@<=t7W5oO&lX_ySl75GMiWOC&TC0;ZUl z=qXp==9tZv#lI&&m$~shunb4C$^JVz%>oNzfqo9N#&h|3)jR{0ls;zQRiO)Er3fo~ zdwFTyuYey29a9wvNKPI8?B8A8a)0wm`AH-Yz{`dTrB_r7nw3$yhVLt&7j!!FSMQC7 z!g;UjE1%2bw^Y4U_G^Y|aKJsV3@5v(rxIbcf@ka*CUNhlwDfp@Q6)|br^x(XX)MzH zdX+Z!_7|y#t!-zw2;vYaT8>XWH_A9+FwJFkK#~N9(!|7SR@f^#HJwI&Q0;$k2#Lk# z5c)IK^ni{=*ONCa-uyV?!ip`!)oXi@)BteX1*-K{lJzX_E>v@ijG5Ij@9g0A>LfwH z`~C--;#o;^kc4;X`SJSrL77We3b~jV%fTSGwa1w!B*7DIKm33&O56ThN2tD?WymL? zw`Jtn?HS+Au@XYQ>4`;gQpW^+SETMov(4u9jsHfDVW5>EEH~R;-s%uvY;BN8;X+4i zdi%>)TfA!-qrfsG;F`P9_+?)iq}fB{X%EO?{?sXcogb=J2k5_UgGZ}9EZ+CGDlyXQ z-C^;ruAUh2)j148z#g10z|kS*$`?9`3#@@QKCUP0RmebS9Vn$-0H+kGF9K^`tM$~%( z8?*~8XR&yg~>xFXK~y`EBI?NBNVUMpU7)rtWiO`PE#z zelmuZ*+##ePuxD6xuEW(6C8#$nT4v=oF6tV!eHWx;`WKhck6xzJ_Z&CUT`w{&_Hrjv z0%^$0w*ovUd~egl!0i_uHwyTKXveZYf#c#7%M%%haqAr%`IX##JhVgAuCD4T`v80m#5BkUJf#pIBbTCKL>hvM@!(y zkNNIZh0)L*ul<}Iq>oW^P%y_8p&+t2$4H=?>gz4$vh4zJh0GlK-kqD_QaJucLuIPKS3D8~=>C`t z6Kgq2n8i3vPXdae0z~Cy%oW#_D_Ew=uFt~S@*jqd^?-Ne<$KB0Kr_NvJHJLYyRoCd zM$L+tPc%z0!l;3epI)E@kPvTUa`%*TaImldpIuM^PyU% z&|(k2sb89H#+oMzu*PaQM%7_G8(DLVAK(Ez(9SU*BT_%RV$bugh7kN1IJ`raN8%qR z?0L@dFtX6pQ=>fPP2io9z4gASWIk*fg|GpHPeT$HTjsM$_Pk$|7PpI(ksdjS1o>DP zLE#St8TE5Cc?U89kvcG=zCq>T&w=g~)JaDa1N5@h15VtbXeM;t9}S7yL*q2w*R-)NIBqw|Pnm zK8unoi;ORDL>4|uW%g@8la^&!06d$=@rACo9$Fws80_Oao-uQVwiaP#mW-KqCGVFY zDC~L_PdI|C_@I~A$l1!Sa%Pny}q*Y)?t>`9r zYyk*CC6E;m3M6(nHJ(HkJg+>^23~&GY3wZ2eu|alK&R@;alR`iGc- zeh4}Y;^F#W&B==^RP1bDjl1s>=H=9~m~~AhfPTeNP*V#U+2~+=>G9%F*Nd!g(70mx zQQ|A0s`cq${zd(lXRe1Cb28?SBC`uqGwdo@=@eXPNN=4#I?)?m3>hq}!rFXWgnx-|nC){mHd}=< zgZjZq=*{bve26sI0CA&MWX5k=dUW6)`XzW;lwvR28@kyS4;RlDji! zC?hqlG*o8yiUOEQ#Qf9cS^EL#^~&>R9f{#3ifb`@Yg>e$!1o}TXOkA6GL>?+31`XA zNAVBm1v(b_eQv2h=fR*oIG0Oz&|cnM4Z{stqdVedb?XSR|6(J8Y^x7ahpcYEYTjkX z#H6$S!pM?AYXTZ}MaH^m?P-O4`Y^_e!puxx;BM4XpzudSLt}-HATnD;O-({ahX^P= zg|}ug>c^_KS(LM|ph-zdVIoM8Fz@g0Cj;J;>T_XKzpe9Q0h@hGiP!m@If#g8EkL0>vot4&~s46A?)ktXFMC_G{A~0>@j8I6P3Y4#R z19E_2xDCxeA_97kKMr!HLgcEsagn;bVE=u`Xk163(fvc#$u_gnzXv<`$~6o9CkeLR zGv)jaY*}oYZvl11@I{|DsmaP%<=q#7a^Y41xG>eAr>Q%&b1(T)Ey=)dI9yKRUaN55 z61$bR8T{PB>a_s_-o#!ETYe~LRXfc5MH&tE3U02LMd>fcWln_EcUOs_?BIFBkoy!H|8}y~ zLI?ycZUCD(q6QlrZuGQbczB>TQN}zRuX7R)23*JkGVMGPGtzWP6Jajb4N?ZzbSn-h z=?DBT(ySF?(usnj zXz)o!K#1}WWK0&Bu$V}Xw9s>Rnn~CP)6|{OXSE$KzKgrlM~;H(v}kpk8+F;t&CIsq z9aZJOCU%B8sJUPf*uH7J^#)Dw{cxny;xtGn)Kes_eKWHFd+yO&=0%h%yrl$| z2tZ9pyTp^|xvKDjf9zmwIiRKkHBj80KNz)eh1JCxnwXf#WVTfZ!=~=q zhRV68H{$y){98%OOGnM6TReEB?{67x=%Fo$#Du8!H*g9SNIGsP;rv9$sHX6s_7&lD z#f<+koF(QERF~D>5{MSr4eMvP6RxG^widT3d@ISsu<5$}mM@g@yx5}yfT)*j^k-vY zM2$@z4&92L1?GQ+Q%*P(dwYrI+~RU)iMLYGBDV=H#{*jUAd%{2FF5=8HVLT+X9 zGSrKWX;3w>)dyba$ahn?-y+Di9fb;og@ySL2$3yY0UVT^ZAY)RoN)gZwaDq?Wa{Dk z$r65!-+{@WcE`AOKJUQs68{LR(j~^r4u23x#j=}zHLJOq2mf+>Z#R6uLzco2(Wqim0FyuA)xNQ(h5xGidOV< zzQ|@==;DO;Vo@Jx;_7g(#Ao)amiXp%`(1|q!x4T%Xauk+IP_XUT(I6(SP4PYG&Jf} z<`ZB4zqhFY2>M#|s!L_7bw&;h#n1F6V3fhZ(C#Vb$aP`VWe3Fl>NEfR;;t?r9{KV) z#{9*z0+?JpjO+p_Wf6=nVA8RI={GAOF0z=5z6gT4K^od&R%hnBg{rSylVt-kVA!_s ze(VsqRY>e^{otw2isS@l18L7{ulYPhE`rNE)}HYjz5nn)n#0aKCq^ zz7*D^VWNUBEGXE}X5JE5oVIjl@ z0_{u+0PCb?B@L-5oAq6n(&jNiL+$FS#KA^wGI)u#^h&vSHjY#izCnI2=~m-RuvP@WDj@Fb?z4di3SZz{2ID_-<6&>L$Qyc@>=ZAbn% zZ-Mc=(7c(fL8yX5^P(k-`mpPHk`|x}sEKxf&MirrYerp!E=f{P@t3k>$OvDx>sY7N zQ6PqzisBe!j}|hw1M7{y7;sBX!n7fT%1$Z-RZxkn#zVCFNm-F!8=o&LixqD?r+JH( z(|Y}e00I|Jp?l`?+wcvk)mM&LOLG)jGFv168~_`(X@j%$ge??(@^95J-J4VC-9SGg zttnSZ0*qhn@n{^b%jPoLe|2Kb#dWrSm!jT<#kIFgnO=xQfVcGbGxYgbHRtrI6$`GqlHcLJy zlK7(8;DU8MAOAI9N5Dr7HwrW3SMz)eKh6Ro#oTg*?P(viThMc$IS){UjYQO-1rc=N zPTu}34K#NFmRjEDt(Je{CWS~4H)8!uKUq)Zd_$AZ>rMu&Y_jondVcCw-tg_IJTx+> zuhcu@f`dYHObZmw?vsOhYmW}EQ%({tesa$(w=5>6u<|?fU3(74Wcj zm(qrReki%uq~&$n9DShNt>aF(vY0zR)7=x>qCL1fHex@bIp5%X0@-N$ykWb>!XvRS zKq-Q_+H#MKf$T%+h)x!RrThw zxN2O8$zrKvP9A@+n+*bTp!)7{j;tvx7? z7g$;C={IjkNg@pYmW(@*%xbp#YTKb45Saijdo?y!yO!_6!So)GiFcm-!&`f6$qPD= z6BjrRi)pwLjz5zO=>WSc;IK{sIGjs$=NgSDIFAP<20TMIdEGqesq4&Q>S{4hnCyL( zMBqHtQnyx$_Zxrl&rzCI+Z1Hv&p}N}t3yNIFo)OBn9XgVpS5drm3Kag`;^;#(=D5Z zn@4;us)r`n{TkJn_{R_?Lt_uZ$@$DUVPHAefywR zn(Y3Gp~LvM?fUE?)X#Hq=W63KZmEr~ZJquI*`jf#4a$>e17(#TSO9E36IU~!^j*T$ zg#ao2f^D7&)bhjv4g5*V%S}H}wOw8su;U?KYG|MLWC|FR=8VpD2!; z3}-z**N}eWz{^-Uc6xTOuCw~@&0t36LB&$GDHSXasz7i znvZF$y^Q0vUD&8KO(W#JNYY(x*kyunnF&0wyPj~}&7Q#boLIRgm@M4GsV*{w@z|*K zxl6xFXNLFILqYe|lw_@^==u3@U19R)M_k;e>c~&aE2~#p!^D?*75IxLGBUe{YqFW( zTF&hEfm>`$R7*?WWpAw}#N-%~g6A)&7z8R3^H0u=1I@l9@;fy*C-dlX1>mPXAS20^ z!Cvj!uf%9woNrup`!O7^&4%Z3q8vI#CYe#boARc2U%b>{YKxTpsKC_K))Ki@|CHvF zl=Q3GC8P<*22yyp%3#2m(VI*}nNU>-uKD66QDsi1X;o7(V|}6ejzaUtwv(_4Wx(v7 z_uTZf%}@4@bkuZ)=aubUO3#%7na5fk(|caOZAPmM3zCuPULVTlJC=};)&=keDiM9z zqAPd;7TR7`P5z~-dRiPU?xfT7wQ9T*HO8BFDlH8$Cl_iXG=<2V+nMU5v%BjZ$`@ER zwA@K)syMbq7d%BC8$#>E@pU|$%3l)?9c07v4tGYRcV-`Y9vlgJg|Lg(z(4_Lxpj(4(-t2@k46}f(SPdur_SXdUGx4@OaK-}WHm`IVkWi*~dW5)dl z?wp3%H?_xdov0kBVf^`0_j_VCl|xeoUSj~}`veJ~`R_XuDrR+F-2;YbuZK}lB)b+3L=Q3$m&OpR3tZr_04g6Bc4zFi< z4}z{DZ=y(tAqtWqjoa&Ph$ciegre$XP6+k8t^Nl4}26lDqc zV+OiS8h`<%R;bb}LQqXaQ1<0MNwB<$C$u7Z(8|Tp<&o9YbJJ%JU`ZpJRY`O{53n|{ z+ICBzRCW6G%a(1?1)4rS(O(aVX|x~pAxI{2@KR2vVAcM)+V{|u=6#AV=W;}_&~hQP z&$&z8?7mG<4!>7bq3&=sf4kC2^^wlQPs4`Cxco4rPV4@*rBCCAiqg}aK7nSa+3KYo zMN9|JQ00vbvSq`?f$6jlr8BZ?!uPJe!0n*j6Q&B&@5JDo>JtFV(1^?q>Sa^PvaiN)?t0SoI?U;A8 zv7a`1)joY;KmYkbR|R@7a&#lx6>G8jOO&T>$G?iU_;z<6nIjE1ZKxGEcO~BYZ@uid z+Wx?};IOPl>7KOnNOP4c+NaB5{Z(G}GSo(s$$q~#G#8f_Dd&be@(BB}kv6`(WLE|0 zrKF4@P_kToqp5SUg*jt(5N_%Nf!P-+P)3*Xyx zK~`RQgizUg61LZ1b~gQZozTJ4Z_lN(u&I;~lncN2ZlcmaBQCDU8s&ftgd`KP#h1Q^ zs`D!A9R1a9LHWd3jxbSNt#&_?#a22a4m+JQlTr@I+GyI`aGuFRS1`7di~+T{_N6Ql z|BjnAbzLwDuF8+uGt!5~9aT%NHR}FUH$Q~Dhv<%1@%tsoEEm~(-!$v?{hezszw)+< z-<%JzTF&`DRI=OUM$7LiNr$O1W!^?m0upC*F*U&|ORz?1f0g6CGRSiuhw0@_UokFo ztxNeMmLmo4$|neOmS`f`!;nH-SzIv^@gSigB7y6G6~ejCYF)p~k6dz3cJs%%?C8q< za`a(;2s?sM>|?Kh!mk!MY|Q$^>9NvCtwM{ENKxB9CA)6O&+uo#=k-s03GqH1p?xB) zME<`HE(~u-+>%-uZSLyZS1OviZ#*p)^;CYm#Q^8#_-zqZ*w4skQ~s9=&^azYQ4mQK z5=4#(sCKed%YnNM+uwJSS&|<2sSk&FB|5Eq7bbQ+d$_jHu`q`b&LD;qcl=jcF63S8 zFn-DK!yBrvjP0lP;_P=h1UmWd1m*Y-%pnQ4^a3t-@^V*O(0MEIFs*ZeV>PGy5tPP? zQ$sz<2yHK{2=$$c^W|I<-Ia3qQv+Sa=*S^h6YVZM@4DoMhpKp857=vM%E>cVm0w=f zX33x(XtGv|28msx>F^C$M!+B_X{>CIDpUFa5O&EX)M{2ki%?OVaGk}ufL^EKuTE11}fvoO)|G{vN)rIm6RfLmL# zN=tuKR%R@EFkCwyfsrW4-i?#O9T+3()YsW3Sxw`}PGWs)> zW~;pAqX|p~VvT{1Jq($@sHAV&)u}amxHbl|K)RWE{{q^GZ?q9Crp6ioG(d6RY-Nu9 zfeCJbv$OTxz!H-ADZwhmffdGiHdl6F+f zqMqVs5MPKEWy8j&m~YuTPg#kT3?RYS*^aM2u!Rme$b z)A2%+lvN(}m3GGzjR!V5&`dK*QE86?gQwtMQ&A}>C;$TxB`?tsZ_X-^mtn0%t{NPd z00d80)Tl84=QEHBPaW#MH?WoW&wbH>td-%ti42ca5}N_{`_PJv4<|DCF~a-~B_o41vkp^gcZ@|2&)?`+-A(3i51Z z$4Ga+!eo1xLs}hQgRXMU2xfKwC;YQ#nbT#Aug;_9pDSqwhQSFy)7M`*$ng=H&NvTo zY6^Op_LymjjEn2JIcOP~tFveF)j1S3-2HcgLJWxREk*7BLTRCsA}>F|642bjQh!s) zK&&~Eje%iPOP94=?16=!sHO-7uHciQZY^~+;1)|zV@EwC`X!iA^ga>f#2J8Ji-vs| zj*ZaPXG6x<^9Yatoj4Kj*)8>eUh|cem7VUKWRk_e83RB(YHDi4x&Qmk-6E);=&G;T zE~#(rGc<7i;&y_7`1i`J)X8U|6M)}Z4FTPN{ge2!i>lCDiBsjMgEn4^W-`nF;8{8s ze%5GUROI&s{f(~tr|LB&VS*3k*Vw_8!urOzqw3xIeY2Ea5myxKgN|L zx_=h!o(QK5ZvHMcSJNob-4y3Pn3QNfGm~gr$NpLrYc9{D`r z<`q1SGLTFD?+BHbm6h!!fB+e&o;ABJTakALCA#=vp+|fka3o-ctqKit?49)Zq5C;4 zokw%!(dJwDOsuGY3r{&>Z18hl4oD5!Bx1o_VS=>*Ja9Mnf0Q?X7x^seJ#Q6YaQUNk zyXriF<J6zvnJ~Ckoh+4c$?aMQ#6WU;1~3FNJ~L z8xs=~K8Js?FrJK#&(Dj6tN`Fh<4S1TAAHb!vmH-pQ8Bds@Vr0{8$E&K-yavr{|j!l z8pI8B9j^_na%PrcYx$c$qA2Eo3lMl*2;&{Jox+ti2taBhdX(ut1)pJ&ulcFfu+f7B zG#ingnzcT85X|W0?k>pp)Ji?}4TVywTpQ2eK7R$$c^s_#l6846V01;_?`!IGYBC9| z8^|IiSyi|06*teCH}HYn2Y{8*e`c)$12lkImHr3q50b$0?EnJ*nQW9#bm730Bm;STr9i~RCzJ8O3Dy4*rp<0vSoQ$bl7`%zeW{wK~ym{cP3e?AyLB?c&f zq{`f{OY&E1s*j0pASS(u#qF!TVBS5mSmio>oy1{-_M+3sQUv+$JZ25J!@28A4JRHKFgYT^zZ=0D)e~i7Ts-nQGfk&)oT-|*vCSBmN#bgkRj$59 zM40bCAo_PP+lmsVbEn8jNlW+G|I>+p%odl5x45t{WHksQWL-4I)X>oQ*Zc(Gfj;?r zgf2gPNqOGb4J3q~K9cQ!oka3!AbInFH%y52@7__9b;KZlv}GmT1Hmu1h3D&Wxc%Gm z90uk+rY3rjKOu4adYtZ6i!p#+0)&CGey%`3KL53Sv+<%L7?P}{wncEu8SQhXzH_7z zOg?a0kG|Z0M|%G_Iuxcy2O658QjaJK??DoRl~zdx=<74xcQ5}tDKfGbMFj=axZ`33qXF zf+9>*Q^T=pXBD)~`SmA1hX;_5ltxko5lN*R zgH%dVNNq21sOu58DW4Kq(yS1V+QFQdSHOzcgFj9p6~sB-t!M14u?5= zcC5YDwXSvTU`q>&$5vKWoEnmWWaZpkg4eh-EwbV3{(SSLH-Vm8%HubY4;oCOJfJcJ zLU+JHDd?{R8hE`MK$Wh#wNvTqh$+o-d)udZ@<8Z2W7axnXH-p1=+kp{FFKkJ^}O3> zr)AgT9?MCh;<4WUaiCOH)6{|QfsPP=2|3*g0=-ob?e=tYTb>QF=1RAdGdZ@{4HP@S z38G29@xT0`mF8PYSh-;gw6>%ZDCtU+nf8|6wz?o6m^at^Bwmrfhk6UeKvc)tm+3(}l$BxBf+a#Pz!53hYJc|N2~;s=R;_|M3T+SH@f z)}H@OK!#X!h+g`2MJ_$jaSc0`JoB$1Pbw%4`hW~fgi#m+V5Uf?j?Dq1CG1OTum(-j@)}B6bzI3(W6zcJ-*KzE@2Umq{nlLp}J9;*uXq=|?H}UN4iT zRrWQC?xfxUDeP{4!iCoSh|1nia-RLR$MEIf&5l!{8mtAlkEr=!)LF(B<-PwopbY9e z&5&M(yap(AXiR$Vs44ZkCC|LC2OH9k%nz_k=LNsaaI*Ya*($|@jlB4Q;SPHvwQZ0rzj0$g zA&`G^*(C2`Has%}pH;3qlR+KTe3BD5d4_;&PM=&KR6YYmhTtD=`myZ4--rMF^M;eU zHp!Id`+FH7-7g32@ZE9d4R6k-m*rw|c_Vrkogyk15^m4{Z!9)&=Qs!1xZE6;*HV4) zUEUg;c*+xzHvW;{Z~4nr z@)+D}uZ{c#lNg*QSHbgB!SFqDs525Ce<$%THn;Q?kJx#@ZR5xMgNoifeRw?CbU1n% zkS^s$Y2oc-fK@!$kY?A2#_{;=Dr5Z44^#G2A($DxS%exYlC1mBI(iY;{3zpMg0j;B=6a53hp)!N##d6(~bq1>kfW@n+@ZNlfnbSGVBddHnv zs1-~$IQp6S*hSJs8MA`bhH3T4Vtu@*8r=as+O@5^uo@S-f?q!?D(Kj;t# zS&62Ji=lQoNyb&**rW|ce8efQeeQ+8idbF(NoKeM$za}z)B1q&Tf0|S;IN7RTs_y) z8gakHKMMYCXjs0RkMS@1`shiy_$a_g1b{gN&UipBy3D9b@X6&ycu$M+mAY4^#i27B z*PMZZGd%J6#)-%botsbA#`ywwUNn#u!f70cnxHx0){$BI(QqwhSZ7+YEcNHSN5% zLktA?DGe1IE_u}|$o<6DXqFm{PJ89ax?Ea6IuK`aT`R*g1(!A2rdjT0YNIg@#cy2h z5mb)(@;7%b$rgVQ&%Sm1{mIS$^AzlEXO-)T@K$hgVNP^4+O4xF=O`oN<)0>4vnguR z&>DyUA%{@{pwRnTpbS*MQkW6!d+HK~F?Fg9lDFCZygru@T;oaNl<(f1Ozw3JD{=J> zv7~s9SYD!+9TgY9J=;Am0Ot14zWu9BGy6xh2J=pj+r{VafqJw`cC@F^?OreZsTY5X zyWKEWunH5JbSm0Hg2i6^O4rb9YhAi58nRwWG?4MwXOd~)w9RiO^lWj+1_^!tkR{L? zTL%4JwP#a9hqNst9{kW=S%o5fVo5t^Zy`28Foae|*DLwR#asB)lH^CG#$Kz~|xBLy?z54 z+4|eNZU4*E`uOo6)Yii$+{WyDD&iE_828=?-m`+^v>NigrSesdL3=bH9%QRGQ;@QL z->XVa?aAMI!5g`u=1%st_)5B+alLtA5CFh$5#_rVR@bIeOC-r@M7}>C2+oA(wDMR_ ztE8t~oRH)HDCB0-2_ry`;YZFhkG)o+%}i^;=*aW4f-W89&;FQgK%Q)UrCxO@^wCgu z=$y=iDckn%3xzNFofR1D$AH)v7qWC|X#JAV#8 zBAk)`6AelIZ3IM6CCU{Q6*^OZy|b{Ox_NWhL*dB}r1!i?#HYy2Cd!MM5`Z!Hw(K`r zpVyxuLi6#|U1 z?$~S*l-sC&@D0DkY{beQ745hEiBpGzlxoG$F|O{-BbFt}KMLztjt1`Dp`=~d#Aq++ z-Rl3`jJv@-Yy9KvYqYv2WO0$>WHy7n@w{X5-G_nsOw7f58EC-s=Wiu2VcQV}WZW0h z`T1}$@`$y#W=ouutKfe15_iW4*z@_|h49jlS*`3@wpcaBBdFRw&#y-l*}C%lL!QZ? zF}a@8h1Z!FM+<#dz(~>zc8Mjz=ZB@^uXAF!Z+?G^ifrDRbXC7>)ZqKGqz#^6<{(ME zxBoSN@kPx?M~+iduRNDd2NWuGdv+vq;GG!poN>;p&Yf;9-b{pOi{QUMTG>S8l(exl zj{7}aNRKWXbv_mpB-wgdVSyd7Ci5JtnTt`;!?fjh1K@+V1Qo=VMVBLe5QvkzGKNP+ z#QD=baZQ1Lq-%P6&2O6>USBzi|?^b64WkfB30A@c@Zif5cQgWTOI_yjGpwf;(6*uOve( z`BsOW>>>7=o3%EfC@0=+{P1n_EI~n^hmVnqEIuSvPgj6JFVW z$nu0C1K3T`08T@0XZ&e-MUT=fk8=JtwURY~(Q>5#;1bcg?7CHt#gSERF)2|qryQfz9*1t9rv{$!%wcM#isq3SV55PPJeAPOrOgC8Ive3d@A6c&0 zD1(dc@13{I1-_@{_JQ?xMuGF{vRUpbCJBEmkTU3De>%?E@XAZUAoayK;jN*yl)IZg zLsbK7&CH@e^8r)gN~4BqmLHa1|VaHQ$;_uZ}uaM?<^@y(wm z@x6@2e_BT@ti9~g`^-6ucp((2QJdtDUKp&M!YVZU3R=pxCy0K(dnF)hJrG8Kl{}$# z(CN52;LLOYKYj5JuJk4$!ACy#KOmQ?)+j`Lj*QA&f^yHBX_(X?}oHLlbKMyBKMox>lQWs!;kAJh3;aC zsfhvLS$m3L#+x&-yTFf1rG1-Ep29IRgp7uehX(3_Tv>>Fp?el*0M+tciXh-^MD<&L zD=FT6LWL8eJN{Sbbpi#j4AyAS`I^`ttiiobdoZK-ZfK05KY;bTUM|q@ z4=r;St$}f2%h@N-pbukSGo_jH@b(JzaCAD~OjTu^ z;eYs@L#Ik1XQ6ZC>0rM6M{np1l8M5VwNZoTSywG((Bh{Ghv$Q-9AU!$GI8S9Ny%-1 z<|i*`@;!O_sWd?4*p9EAMoaCFhj9CBHFepYQE70MvR48sk1CohMKd zPhhtlk>l7Qk7$dYyVuQD@-y(j);X*bocwPj6Zm{n<}#dQfEuMvJ89hKF=^;r=*BUf zE?+F4E1|tqcC6btLBWR)M_ZSMUzUC9JCC;Bss8cM*e#r|y`n5hGOx}28l5D5mtlj_ z>fa5Y|JMe04rp=a59ODqJu@Z;Q`)z&Zrr|t^krUqkkM{IsFWFC}Q#)@oZ@gg| z85_lhQ?D0YQS1&XlFNx9=~fH5x6mCO$#xmjbLT1PwtkzNb%o4_jP*GDoVVKwcg zLrIRFzuOwFW`OFyJFmWes%9T1DNS?6!$?R(!(iD10|RWyntX@$4i2gB-*>*dZAdoz zKSDfzS2M{CMzbeR=tDw6-T~=7Ld}hR8bdh<#NeQ%dfy00Dy#o)m5~yV1gg0feH)2Y zkYC5YqxGc>>dOvmYnqzafr5+7=}9R~hb?_$sNLuzxhd(N7J`D4BSEN82S6+%jxxQ_ z1I$SSB)N(xgcL;t1Z+l%v;f)Dg z?PSGMf13ajDP_j(S)cyqOjMt%0i_K+J7)K7f~(k`m0q>XrQD@6(&%Fk+BuG+G;V+B zKyfbrG7kDTPYGl{()o1&JrV{IK(!t)Qun7FWTd2SD>A<(ssBZ=Vp_DWsBBKAk8k1= zE6_GR1?xs^MYEVocry;}GTPBSwg+%pAWd-{ZU`i?fgtiP1A}06+aX6SjMMs`N)MM? z9vIT64!>@Yml~crPkui?z-wV;#YJIo|6h45?Q4KBi9V&A;3oq*>c%eXvrkubU?_CR z!&{*Rl&KF#2{3tObim(A7fsGmN@Ko2>h^f-6@taJfA>O2gFm#q%^osjq{>&VhTN7p z4v_gSFOl^uW@CN5q`Z8CRp77fdd-NGB$UDuF6xIn*-a*DiF|oGuG|Sy`K1BYX%^~^ zf5{0?-Zad59WU6sV5vSu`x+a+C;nYDOcng&!_|As0?8-Wy*a$8^sh90Yf{gSK= z)5;aC=f!KhiX0Nu9K2#tdw)DV?M=mEm{ zLB~7pY|4s{RL5D~IrREBgZi0x0#-2 zwtXxl7xs$*T~-KqbT;o-iRhImKaF7bRC}jDWYeLcd~+KWjW`uVLatkRB<9c7A^L7u z>Ub!4_aO8M=PibT_Klzcr#2dzdn{&4`*MxT8^SGUAx>ppMiQRv3qPt1r3eN+#a)_Z zS}cQ9(7bsy@j!Bz$B|@9cP(acaeX*~oiHbE+#V=<6+O!=mL_|{I9JrV)soQWORUOX zC5NG$bKB6SCi&7AMx-UZ_9|$zK$UXo1L}m1_tCsw;+>N)BwM@m$c|B3s-V7I=Y>?B z&&k49-1hYebD3S79klvDh{wCzPNq7zENOB@`DeBhB-K;m)Hs!e852k z68X0@;zn=re`^**GZL2iGP+#=O#tz{7v+YZE>wp29z!WQ-Fo@BGPN(90!VhQ?S!DO z7tkMzdJCXQOh^VnUI!wlwE7d!O4eg?ysIIHH@$ZUXr+>Ln|W*7$Cln&G;!Kb7CZ>>>K8_l@&L!ViBYek{%~q&!fZ&ZZ zd4M@X48WTr;W6WSsvlnqW%+}|NCLv4W35Y`Xiszmx*YM~?7GV>e28H_5zBl&rj9<6 z!nGwI&KL~yIu#>!BHp->b9xgEMsy-*!dF6ls8wWAFaI1zzMkGXLN$e+ii$8+Lb8*` zSeiC<_x5V51E9kr^Z7j!<1GoI61kga4=DXM{h`uGddcqUN*ITi`ZpEtEe}X_2c;A)FV(r+4gr@tsf})~OXHzcl~51)_f&L6tw$aW!8%P1mGeAq zP^3%fdKFInKg!R(|+HNdQ*0BdWl-7K&3;)&`vpF8C~>g(9ADVa7&w%snX9^dAnyb z0aUF7a&J#Z(NW9mFJ)zK2pr!Xpo-Q+1gxfN@DwnkfcxOqv*8b%M`CIn9?-LKton)a zxBbXV6#*%nr^+Qt+!!-Rg|wLXCPEC?a6#=&g@5#01TlBKVt7cp6(pihZA7d`EQYSU zQ-8ceUYv2@LE=qTMJ&r;{OJ*;#BN~F(DoXPg0s=yzSx#IVJatGU|_HVaVbclKku0~ z=R|EnW)4kpC2Pw3wf@y2NH=*nscXX~G5?a|bI_Wj%(kOU?wtEb%)sWxlvbQf`j0br zarY?RxPfG8d8Lpd$i`MgAV z0f!7}+pK5EZD$1S?{!;$dahT0OxV!qQ#*>w41t{B8)F}KMU8dU93EpLSMl2<_zuKi zS^dm9!)lwg3yueEa%Nlh8tyCg{a!l-PL^hZKG2e9CG z&)0(3%_3)lPLMG*R`jT>@0fmOl9 zmS)mJT4ACltGSy`+}QhL6;nai8+fdkqkhzsq24SU<%sH(kr=&m!WW!p(CuF))|>!w zl{SEGl3NC=vFpvi=_28)CV^I1*1VG$qfHC$mCv{GXJ)zC?hp?;iHS_hJY4fxwEc6L zlcR>}O|RS{%Q`;b@@bq7xC}%3cUXG>zpvE@usAn(rBYWk09w9wQ&iHGRXSHRofYYZjb;*?KFq=Pmg!zzj;~~=rDEBPg znnaeVX_#hTA7XodXz6axFaMJAz!y)PS*XILAY3}`=N+*XA-t8s@TB~P{6UOfo|gHw zW68D^$5|B~$frNSECZqr&z3AHFUHh0oH!H$7Y(1iORBV^^7u5K$0SYZZbULhl8mw?lrX-yu^bk z@4n+Z)aRE7&S_RWKnx+lGEa1x94kVimgN9FU|S9WO`XMtR={cK1tT^Kx*ZVH4>t`j z3nNgiSP=U0OMa;@2nj?f;u)eHp?#*+fBSev!|HO*D;0!QJiOD386RT8T=3|T#IC<& zO^Y2it#0PFwh)`}{eZW*D;=}VxguL+E?K&qE-=VVvMLVlsRpmM1&J!BET_&cp3mK2bXD`-Ea)EpRdRUIR}r{UTv;5ygxy8EEUsw(DIW29 z)7tsU6tp#N&XYAIVqa5qW+FBmH*6Vj+W#v%O>4?Ha_JAF(D8iH;9h+K>s{2z-1h9q z(Whgi%1%TE89N4V)kry zUeOD53|;13JA(gzmpe5vey!7Os%o0-yMPYQGvq3C?jYnYjY3-juSoiC#)l7GA4DuN z6@olF4*$p5&F3%H(R38s4wPxgu@v7L>$Dp|Rx|23icY$uiV0W;k$dJW+Fycv;#cC@ zIw)F6-M`qHg?X}vFp;Ar-u5wI7;4jUHR+j-SW*oj)#c5x)_i)Ytn>7H#6!jYwZo6J znR{W5hA+upiQLGkX6-%}XGNc~TUa_Ks~6ng&-TOXv0(aIy*9KI0`rc2KYST>?&wb8 zSpe$hgjyoxbGuGXLYl))YS2HoS4PWCjWa+XZ>JO5ZaN<2Gt5cYTT>_%ASuKNlhi3h zVN`mgp|+M@t)~DrVOx0$wiP_*V=F0k?k1rugJ_3&dTdGRxcLkW$9G_d4vP12m5;gI zL_<)8%nhV7!Y=CjPFasep5nqrobedtc!!iHbYu4_Y8~sQ;A$O9cl%O;A`-fN&R3Tf zdv!O3L-4!0r$0~AZl*ku>}ChqoLkcD2@C|V*2Ip1nC6`}3diQpc<+%$y`j+mWZCKk z0&VC-nJ0Rz%99qfzG}BEatZZOepAx@)S5^T1Y8IfbC$fZPaEV>TWLJgF!%7^aomlq zl)xX2RLKS3^52(szPg1uxW69Np ztQ&wp1uQJA#jx3L-wZ*n4rXsdeSHmF;|1@X+sAd9|2(TH@g;mwE5HjHq^EL^Qdbl9*?iDl#`W>AIw+jhUn%0IXi16 zd^n)s>u+qtl6^Bs}u_Bj^ynR|p28!aU-tz@OAlNJ|L!K^z0C&p^`m&90Y$ zmvH0 z6HIDx|GnR!Uif76=GO{ODA>ina)&8O$G{#K15(023EYF7gTDZ|(%YcyZzWd_O^DXR zl;K!fB9IN&@fH19Yu>a~$mxo(kNLHGlT> zUcTl15I!vit+bgC2+;ke`zMOP9bo7(bs@$XB%rFpF_C*#FM;f06Kj-*BquGe4pLT5 z?sYuRN;_;uv(7iF2?}L(a&p?;nua<{XG7=cL7=Y*lkP0Flfp+wM`eU5Bb7#{hdda3 z8x%H`(av7RZY zCoE3jLU38K=9xHfY4DKTOC^hG>%2&~i!DE#}fr|7R2?`1dRZ3D+2?`2c0SXEh4*?ExB{&;k4mrGV zdM~Ad0BPO`CgG6Z1kPd_&dPRX&TfW|rcma#b~dJrPR5R=rnXL>?3_U|bUnBnNkEEB9{~zBI=J)XM=mP+p<}}UgOCG~Wd?kH-JKn4O)xmhQPnA%Y zJLz_2vn8tK`_`vx-J==2VE?FBzizOQ5z3A`+XNVEs+BIqkqBqu>AA0ys#E>$S6EOx z%#3QO+F50>vR_NrxFK@R&-1!I4y&>LEk)iJ)-hRCi}rk( zO*$2V9ml>$2kz4!1AT>kJ4yUV`&K#+NWOmpDXCdk0s+lCRkWktnVs#`i9K^Je~3_+ zJ;~Hi6E|R3T21JY!|<&-+jlE+uV86wgJ($u z#$=)z*6n5$7+~_X2Z2h`3fUIF=483uMMHqqc;gEewNvY`K zzB=2D_zD`<{x#gOVehHX9c^`JcbwC%5y;1lU!C#yeR9|o${B;7i# zY>sf^^pS7|vTg#{D9OSm^t7UF?2*J)nT+=E}MW2oM9h40*vEoSgOT zGQXGVp2Agg@JUC~F34(8uh6Q}M?rfye7}2ABDvc612I`(qK$UnaG)haY2vn>@BrTN z^vxJag^{-%p{j3J38mYlcH2X@8edGu=aC5#(S9JjhoJ+sS?~CV{<2$FLPd$}p~}jR z@b3JR(@}|o;#f(F5a!h6<``0_uO@!%$z!Zieb(s{%FjTl)#A?GP&yin-D^VvM&hJj zvquDdr4>70({(h!X-~@3n#qzLGf4J` zV@>_SQZu*`kZomp>XMN-{yL_D&bk$bzg7wva_2-GX6E}&MO`bjd*}@w<6&&M;}aM* zp8M#R4;GV_ND{G@Ea55xIv#WyzQah4bO&kDPv_;>ni7+KGx)>$dc!*odlyKy2DjW1 z(ND_ihdXg8WF)iQEU)fR)-Q+|NxuBiZ-S50WytT#_brP`dcxxXv#s1KosTh72A{{( zb)bpSyJHBet+_td?&z0?ep{`<`fIiC6{Vpl5FQ6C+3Ty+uDFyNsVW|ajAsgZ$%Swl z@m#4lDxA-~1-cw9qwu*QB~0+eCbqL_5oY}qr9D-$5LqDJEg90i!aQjMQ+Z_GP4=E| zRGzLkc1`cTkgI==8AUaZf2A|9A(z+0J{#NX3+LC=5jmgL5^%jCzZs~X30TN8nnddO zwFcfyA473o)lJhrU1NAu$F?k7d`hS6a}gnKATajPD5$*;jenk1lp zg39~4*~E@Q=C*-P;N@s;J%et1*QwBuS4iSjicp5{7)sVtXDP4ch|`1VidM<>aX`(6 zfMg^^O}AvAw(#Zp zvT1wyQ>#5>kq}u9Vt(_*w{&aW^Lo5g$#N&Rvf<)t1zEeaE*{z|xSkK8qzPqKHSxSG z`n_8T!+Ob*yb*9``A{ftr)mx$_B!;fDBALiTkV@ybZ|cKLZOLn4rvv?rdUCnc}Ahf zr&ReeoFvVU`ABX5=mHyVz=)A+z0L6SU`fpn66ATD(rz+w7l6Y^7YdIy*WVGA z2?H-1%dOADKKBGEuXayvVpGQ+iWGXjEhj(>;n_SWY45+KDzD%w?Mb^yHhID2~k z(Hu{%?a(b+deMA<;a6uRnnFd2Ku2bSg4bPw*BqXY9UXXo%|?7||IN*2T>9nSgx5(s zfPF#$wyVx!n&+r)dZ~^D>Z9;iRa`?%Lr$58JN2_lE8_m9OU;4{Bqf{RO^3NvzhQC> zRgo?Nk)~d#_c!zp3xexBgtp42xTmvNjpt*hsX%X~LQiD}tGiQv0rw0f`Cq1vFIP65 zi`8@(8>P34L%YE=Xw0m)hT-Y)#4jN}9=aJKds4|f*52X#4L z?$5S8Ki!*{o6o=Tx(2!3o&iXB?+OP-v8Q$<724>1Tt>HyX4@0al}&F42iCW0Woy0Y!X}3c)lHyd zE@oVcFLeoWf#I+z1eU6wThIBElCRf?g=4=}3SIwlac&o-2L?O{|4g|DcHEE`d1leuZP?4p2F@L1)=SiVhCP^R>)*ZsKGQ7})ZElkofiZlG zk&`13Y_Sj#iL!ac(_VP+- z6jWuaCwgE|(qqCAXfR_zvqTH*IPo9eQd1WUfvp;ne^9M_hz7WX)4#&BXl{1eoqJi7 zWJ)Lc&z{R83T^3cz!Gke<`rCoh=|w(vK1gkcWr%>J|-?FhX!%j$M%;?n06Dc=fPc5 z^sbuz(7G+u4ks@OqUGvDXuEbYzcO&bzObC&4%-9uE7v;G5&Q_+qafF6RxA_y+W4iP zKS#d4{&|G3ZtRvRs&@CQvMKWJF=6a_E)zVi#oe&CHEnr8F3UTF*Ds3Jm@AEjVxb~b zcc4MLT^ffETv1Xa>KmnkM(l?u1Sz8@Uuskohfu4F6H!uo;&h{+#1 zG04cnvhUXE9xkH%kQ9IG5nlrry26KV7~KZpoqp?uMsYt%sWIwKMRaxGl1yQN55_|W z-(4e(#$mCpK-JskL-$rGNqaQZR9V__R~SIOF67eln@20SO5OROr%PK?14T`Oo;`;( z>mRCJcwOdh7~5s##owcE7ftbt$zBgQi|G58c+MXyD$z=&u8ONPl@FD1ZJ{fe@`M8= zNI2izYP6ID(nC!H3J>U0f%&&06?^Ck0YS9$@{cqq$0Kc7WIFL)v8xyGMKzq!%6?Nb z?$BlLJ|m6DeYZLRlll2e=NW28?U#_MrC_;X!4CgS=&PK5lemR_b~pS+N8e~uxKql) zB{PL=xD=KAwTB%{2b4%*!f9w+4_k3jjlI{QSI9W$?uSIxK$_fmFnNtU2@^=#H8#0) z{Ab~*iYS`QN&7W1Q)I~1c^NO z3UANivirI5iQ9PAOR!iR38w!bscSk&y^XoD!rcO&vk8k*pZ@$R;SdO4_2uVT<@STn z+iY(2LI-_I8&s;7!21QX4mz#~>2UKqvGyCWNZ69LQBUr4iJFpPmO~;CbE+`PDR?ad zhD)OhuN1%GNB>F1>%O0XM{RXg{&C?6KaF650k{d|rl3uZiQ2(m`(B40Jnw+Kiqk@;l$lbe`I4!r$ak zNNRLufuB_UpMS25wvxsp1bXuyc=^@>$1l}U*CXX{yiX0e{4~}2nGR8S`C|AdQZx|pF{<;3-8mu*&vZExW--MPcej0x7mls)?{cL1W2@rd=uoQ_{q zNP*9eueYtMbuzfCN!-xmx)4?Ha8GyI#vY6_v)R&v;(OUr9OP(>kiZ_kb7p!#+&&a1 zr|wjrCJ#}{buU4>pcy^g6oI86M(il3dwSv#I;v8EkOe{FPgpKXAH4bBCRq6)?A9n6 zmT4&UeUT2z3%lB?+;t_dHsJ4kyyrTFjR+!qxP_BI33K; z5n`$jkBnL`K)$m#Y)RNSQFj{m8|K;E!XCxpPdSQNKWV()q?FI|(-HH%Vu)(#eEv|- zp8)plJF0UUYkHF9#>TXu!J?5f=?O;ENSggA^H)3|%2z;L_{f3#g^ODtB>U>!OXOBm z--W~NurWPfpb}WCxqoE1Jm0Hr?vS>(r{uoMM}OEY>C6YA$7{gp;&^QsVKe0^K3JPt z->#UnsWmjxvgFIFX5T7!H$zOfj`~a&k*G`L+SGWQwI-|z0O68=?q-*+n#0cHF-uj!Wf^W-I9}E>=iqDJMz9x{F7_@KU zK$&JB0k4j2$d7!8e*JYIvlnQ6=SqQYt~O~u3G6u}??7540C9(4c`cppVxQ@L6La?z zC=AiuDt~KMPJ)nlHnv0>@RKK2{tUdwU)p?hZ`pz-xe*#*XsufvQo1^9Scs^BJ4+Uo zgJ@9Wu>RV&u_~iP&OwKp{7aufJ34d>^?;1*%{oZ4Yx=-&D~Hxo+t_+El5V;dh26-9Wb^| zTC&a+abJuz(zDCFyIA>F@+TJHCqlxuOe2eVDWXR3dt58OQR7(Vzz82;uxjF2-vbO1 z`&HI^S^w7vFIZ4uTgSR= zSD*E=0&*fuweVx8i*P&kNkvGfj!4T^2;`gIz$<9Jp;Yi1{hHAOi|0lWN{@{=W(4c&Ga3{7l? zWd}%2s>+G3()?vLmGk=K2>Va{Mj_j9o6CJRu-n-znq$rGeP5pz^JHTI>r%gU9jy?~6o0meo zpkL}YKKRho@}1RKntQ64ve@LMo9*DXU$ZVx>C-0i*V?sKX?km7+svtCC9cg0FAbj)Jt#px^&N1`m zJ(Kg#qHt6M-@hiYxH+)OI5M=%UlC1m#`x)gzFu(YBWQ08ZX-HXc^gAV&262J#0!Q; z*jro`|7k>i{ZBNPhVwXs{_)qmj}aFIyn|vuPB&b$CVz(-%1{DJO*Y+Q#-6qyF+<8W zCDsJ})zo*GF`N^Mp)DW!;hp1mEcK(660USbtRDn&8{`2%D7|cv>`5Q@uJo~98E)`F zzBYkS8x1>+^Ag}ojR==X#qL#H(Zk^M&S8)(#KJ>eqKlE>lc}=F--d zlSXDC(d!#@^b{8nW`9+^(ZCq$7bEU##UFcu$VyP6?9^}){N5wM!VScq>q2MS(e9c^ zF9b&s-iaA9kCtXlAMXke4Gca7uV()3w6i&c&x!%CujH zwa(U6weAR$6e9ddQRR@rfZ#$JZMRUWsWndf;q*wn!1sRoo`=@p*u@PBE9&!DcTR_t zj!+Zw=DjBZ%}gMl-zx&O+LPj5!(KQQ`0^GoS7Eyuvsx=^A+*^K%1Ql3`DVWOE*5MrVEB9K!bn#eWCvU9NyMFl}VY8zXf%&Erh z%+!#EnsTY?0f#|DO|E|3z=sLd}6mYdBSyW zxys|KOxToWCM#$rLLBF(F&dhvvZJ#S^S$1R=V-Mb3Ln$Z1plG+sINnF0$9c9{sorJ(96CB4X`YL}(kJcVDvuk&t`3 z%aW_PI9DDcV$gc!IMdI4ZXoz`4+j|+H449PXtYoyKt8(YK4{mzwd!Oxs(Ve*=XUp# ze1g?S63I+iwhZS;)+z!trgS#{k=ADwL-*jAeH?gSDF^h z2q&IGT=^Ln|U38FDXdUvf6XmtbZN zn$m2a?wRKUFDFQDD&%Y!eG!aUIQ;z$kaF74}Ah9_6{gO0b~V8Wpe zr6P1vsuNDQckJ)2M8>6%YE1HitSS#RTQlrGlc?jy``OY^UymAExH8F)HsU8+f3B_m zQs*GS%4&371XHG=DowytAy7!7?pBGY;OFi~r;PWtmb5jkHdMmt{2k2%BmLUToM*bT z3rGKQC)wxK^3|dClNb0FiD!3eQ8&?)1Js0{wNKU;^YD2G``M$0ZZ(DrhD`-^cLtnW%be|Bf(zeanRtK&`*4?1^O-$w9=kyUoo-G(qy5a_bZ}()QqdEO{1dh-=_GoB^*!9qY4(O=ElhtEn=G&4vLBDxB z_7hc#|{n*+jgRvE$hgue7v> zz|T;hnCQ@CcIplAw%c`O!Bk0;xJX-Wu7qJ{yvqpHOZby|wj|NW55w+s?SlE- ziM`FuydY~TJ!@z(&4->mtbA}#Qb|ea%00iJV6Gh!+wbe?wz^VLQH4ZDM_(~%|8_;u z*fuxggc}B82>55Z1v^vn3{P;Rmgeb3+q17h3jhXqX1;pd%D_;zNYjgiH6Y5Vfn6Y za-+)kSHdd=nkwoqid=akRyLdGF0?J&USTyn-(8tbn0w~99ADe2B);sftu&`3zqDCt zOTD;ohT56Po+vKNTFSjDx1b<*WEsmA&W?^o>FI^o1s_`M9uC=>ni_moBT+*2`KFnf z8Q0dvzpS&Q#LSM&jaE{B!F#M;e-f@Oj#gc|D@gpxy zHFbA<#LEgN4;>B{Jg=0frqD(gUMc${9|lM`NQ~f>Qo1;@(b7XmIQ{f%rB)%}c?mDV z9yPAB3!Xk*IdPNcE}f3O+RNG4*hmrf^Nm{ms}sKtb&Zg49UhfnT)Q+6D(XlZoDO0V zS{ifN&HCXQ5)m$$&U>|ByxjWYH)I3>>eMX2P%cX`+$`ngcE8u=pGQXwjt1kRf4v=I z?IvPje$$PAz9U}ie}GPO?|#E0f8J8O{pkco%W|$v)5O&D$OX9P%;vJM0#UD}Z}ga$ z#mwyNSe5h3xm>KQtSE$BWib$}i`@RMe8+v({RAt`8S4XDyN8RN z6ddnRF;L)GWu4+MILXMM8<%4Mo87jJ#t#Kx&?fhmpa1k&w!_{+o-@*RV5=@N4xr3s?|-p zU64teJUMy{V+~Rn_TwhVz_JwM{e@nmC)-l-14dNMFO=Q?hGfaf!@hoaoim=w9>(jm za|i~0mr6+Cu$c0_M}P~udGsAFWi)#_c8*>et?^BaG(DOf{}ZwptEm5ZKbry0W)mmL z4tCNdc5({|mzLQXlJR7rWb13JWoy0)W1&W?NodZEmQ4y`&GU4a*gKU#!tCaFuV zr3zoJySM%kEwxMGTW(yjN|o4 z?(xaNXN$9~HWCN^BOUe%zk6Kjf0TKuiwsr44gNdohnbzw!qaKuA_K$5?sM6dG^_z) z{j0SqLK8}{86Wpmh9of;mOd~2UDh^z1}q|~(Ul~C@+!?4P|CK7!TU-2sg~)Be#}qN z)iM~NJ4eB4DFDmn&ouuob>=zLRNM{>jnK?3+xQERTF;b!LIQmMkGGuBJ92tBn7m)G z6Yo-ShPK;t;S9TF;I)b#@+7e_8>3CSBpVWqih_ES;TL(85r@{e0jJ6^im_L z4!)rrk?~M|^V&96m@}q2-d`}#X=1-OCeJA1lY=Q_iiPD>a!U8E)_4D#!Il4zeqEFDK@${u@Qb zHWh#2^vVfkL4j|TE?v~z%HvybM%k+(JUqYCYJj(_O=)``;>&GZ&}^TP30dEWG&Ztd zhH;kXs6z|iysum9E{DIZ%s}5OqNtROg#}OFZ z8<38ptv=JiUKdLbfs+=Vct|RPuIgY-5vA?E`Td?DA(I?_`T%q8M_h)*Zv75=qp*V9 zNJ)6E|C;u{*Fso5g)LkOgc#zmO4=+(OL6bH5`NLkQgi`dy_hx_r5o|Ew<7vfcfb1$ zc92Nx#QS8$`_bTJiR68&m)TZoP&1ui@ai6UjUJsM!QR8>I7b^aA?rF9N{f?N`*Dx* zwEI>A6Ht-3hhUw2BRmSiTWFaL%xo_G$KX8jZNR9E)GVlcGJ-@Zp&4e4rA4Q#q=HXt z^RP`lx=mLO>-ur^TqpAGSQJ7i1W&mrseuyVmR zsP?h)tzGVyXl*_QVxcMFaD9o}@3CS1L7}HCAtw5o?|<4o-VK-;3+|P!x+^A_Alsl8 zr^TE?L&WBR{*A0-|lBEA(5G8=bMPY%$7{FbJWaYTO0lZ(2 zeWy?+U+4m?+OE~4l0ddr)UY?SUQz7tc_Swu z%Y&*X_G9T2tYomhcxbO=+N%3T5X^fNRz;5)PZ0+pavbo}Qd1YjXaBK!;T#a8uzYvX zV`L#?`6jx!+#~x&Q(ufagEgKCBY|C9N|$jkJU zE1>jKdw&_PK`Qo+dX2j|=eAk;ik9fsXM{gl2Xo+~&{NKn(eE??h#S%?5r(LM&LQga zGp7IHED*Ep;bA(OFk|qC&=3^xW@KH!0aWaKK!n<5qbz5z-ZPMV3*wF{DIpE;$wY*s zD`%_T*VRtc9)5_~w!S{{X@}MbAl-gyKy?rkU78A$Y5bD8X}S^atP_iN)=B=)jP8;0 zjS@pRs2QmQ>iQC&Iza!L3ZC+DM>-@Cigi;S-QiMSXe$E~+;Bv#GpB4;%5fo4)3pRtWSt1989T3$B{9!FeWadJkO%A`Nh&*&+h_t%(_3^aWTGVii9>;M{PWQVs~r$e?(fF&<6FTa(cs4!FDAk}oG- z;=QOX3ib$L8h@SILvq(VIJDAzG11P0mB%YI*VUIJKk=e~7)$Em*lpqv7 z%Jq8i*5W0I*B`G}3rk8O%gPvR+b`!@oFLq4&yj1b=jA@`r9~|P=d?E}jYIr9Tc}F( zHtk0C%~k%}qR||$j7+00l$3iQ%_WU1xegpYmyTRl%_+P#pEPFt2f+Wpm_+~LlokvB zS^th2`z$gy#Gl-eK4)c(k8!U8f8M6swnRW8vpE;y^Xhhls%EKJ+D+kFxAS=Bv{XN$ z@wT^0_?FLmQ=o697MkU)$q>7=)rQ4}zrdI^FRVX7lBHYp-!B|suq&X8ySFSKHLgNt z;7({lHcOzn|M3=ri+IcV=h4gjfs2^ah*Nb*6ud0Ro_*_9<6_LDAL81`@-yS-fY?iY zhL!hPw%B>{&h?%U-1=zjA4B*H4ftDa2Mx=6Ulf(A>gtZ+>3eq*m}fx06BT`ttmjFG z1`zS&Knpt3^zc@Lwh&Zu|M|e=?9jt&?y})$ce3$S-j&7voxr9s@+|^X&L(uyIZSA%fuYa>ZLNx;49Sl>JWRA;Ec@ngRQ9!ocpc?=D;}&$!GH*x zGsr-f2BV7s_5Vo>xWBALR~Q){ZrU#?Z91rE)o8FL$mDl3yZAXNDj`v83*sv&E!FJw z6@0wA%*)Avn&u$ju_xtsJv2C&E5AoosP3v+jDX~6B#v!UHcW=XVJaHJ^YCHDUt#{Q zw)622b_Sw9i2elZW`{1v58w&-t{MiE-lF>@B5`+YEIFz5@8Pt$>GKey)ywlgt>^6` ze9>4nKZlL2JCcEDKihiUz;5zC^9z~i!F52x^M9Wz$@m|-og=BpBVJU_|sJZ>QZ+1!wK$mr}zToNnHyZzXQifs#F zM7OFiu&}0clmAwJh-h*?y!b^5^R5Y-ffPW zGuE7gUaeF#V~W!EO09G~j1`7;uYDeAY*yv)QI86I>9@Tzaqn;sj&lH=4V8O4F_z5v zcGaGg=eDW#))i^plN`6L)8X!%2=~-WCxMS^v#ZE{qjk3G}A;^UKJJbh6opM4wd z@~wgh)QLb@0keq)d+5=RCr#ie#Okcob_Q8=Pm>jayszZ>tUL^3Sw z6)RTp%~|W|75nl1TPJP_)=wHF8=2xqV+@hFk3nA98NJt~jWrZjc-6fUKN#y`ub+j2 zT2CI|)+Xa_?D6{RAsXUCb-!0@yY~Y+%|8l&*Xiju;*8#1)4DRcXS6=^g;5Ec)EaLa z`Le*VPF)EfKaG$NkKms7z+RutFOC%d6bKgqm2J%~>zP@7V6ipj~>Gcf^z*JdGQ+q--nBRz(%~D-NQxi{yoOx|UBLnhC4J|D#DI;Tf zOsN$Rg7~f2UgQ4dJMD$@^`Xpw&`hZJ1(RcT8kTMIYHGfy>v_DKZjIqCl;6t7%ifLU zKQ`zIKNfJlr2Cl86%$76`RVzMR=#xx7-RamIn5RiI36@Dm%CLw1iV{u9esxuB|J+0 zlvvty&FtnV-A(auyqK@Dkbv*KbY|lI3g2@Mo2g~ZT`3a|gB)DEt4ZWV%?k@51t+xB-oZHQWB=GLvhHcjJQZE-~n5 zPj-Adpf+E*LSXmJl-sETHytGCieB(UB*2T!U$C1ZnO{YP3?DJL-=RI7jL;6O-jKS< zI-gyMb#B+!`;xv>oLl~w&X*}Rgy(orUO35El{v9%qKIAQgZA7Ur!SulOQYX=K?rx& zd*rtPx)iZ?c;qowu{%ZCs6%Gn=uu`nt=k9v$I*LWe+E4MELWj#G4N)JG}zcKk)=oJTUV%Pf>O*~owS zaA3!)^Ry)Ukq9%O``uGwqd)7!Q}Sw?;MZ^MoA&CcTQ`$=KTY19N|3s;H3A(7jImJh zzjSee<<=Ho5;oPzlS6?jn$v~#xk6Jw^C#c1xCKsG)U$~KFr(MY^d=JO^NH>*c5aN> zPMdsCh&j`+K=A7^{|Uu-q2AEH%jB?ll|U_P>2fbY>=Asu>X%(oLJvV{n=a?H55~vR zIFTEd$M$DSwHI4se)g#>=t)`>eUW|kij^So36r$|urDl$sY<<^Rog7jl#>{nYF%(> zAyQGlLws-Jzw}w^EEW~p_04-N=OfQ1aUzTMgoO@PcspM-D_EbVA{lqxY$;G|plSLL z@;h&1u|qwr`EYWw#qj}Ms$j_%hm-}BuO@#^wQ^<1dC5BU28^I~?7!O#`Um`g%((^4 z8#BaJSX6oFsp;wF+nsbmLBDBP?)dol$>Eg`*xRVMN9t2y=`T4)Pej)9uRr{?ci+pRJ$X%b3ll8`oH!k9x z>AeDM;)f{3mWzg;1LTEolaM^241xhubOoO?J@mZyn69MN()&pr2YGc;y?L2Cc;khX z?+nU45_VUQhj8prd#0Odb~F9Zr}Z;>E!?ujwEC6wyw2ETTeomM`B9KwDH%$jz5M#M z$>9~6LVeQcC~Ahi5jj03 z^t_|>p4(HNGWprpB4481-8<>3k~TX0mqX zy_K#wTb-yH#Fq2gfq#Hfsd`u}zL1qRy%9ssDZeXaA-u3tVJEa$IJWUg=^01i)YRTzw(_}GT##Gc+rsA zk>&7QCY3n=5ab8WGfz6t~04hiBKA z3gVP1v#U}*9hPQoeRry9w%Rj}c2F}C6UFjXD2xa#Vxa4f4yT&(Fv!D+zp8~Kezp)i zfOjW$XO!h_6z}KiAiH1+gocq97l&J4Umt4`!bUPoqt?{ajK*ipg;*gSOH0dE&~GB@ zJH4sbQ;V*{45lIbcd+)E3_z&m<7^;a zWY~kTZ}=BlT&y;sEg6v^>C9NOr@`x_0~K(<1x$`ULxOE7D)4_>V(;gWHyT+Tog(^cEmH2NvggueX;mkm59W22+id6xg$kJ3)U zkrjfvNxKa`L-%mhGa%@_HV^RrdsY9bDJ3{`;?YI(Y>+cR4WW|Te_{z-1&MlC z+rBJTTCc(CQ>s6<;89SZk899#*=`IpM(ufe>K_yBcdtZq1(aAu`rzUk;B)l|%8~2B z4Rq5L6Gz49SMGG1ionGkO`twz+SsFG?hXFJ!vs3bybyIa1pC}|!ixTd8^u5JzlWWH z>NbExh1Up*Sg&5$w}RXSh!0))A+SY82GRNX`PHgJPD)|62B7pw5FLOb7|A^DqL89L zwBbmjJgSCkt9ClcPk1}?weKi_Z+a0*KQ#_De^vz>4nc$+MkOk9)r@s-Q`);;!a6ht z+UHA?!+SUJ0TQ5Q!_zr^(jmfUjoBrUsPIGW!MdBrTI4geyW9PBsU{*VDoA+wyP=^= z==i@z3PFJT@bHK%j5B*#7&SK<_bY$54dMUF-%aZX0FAw**!-!NZpQZow1CLvSS_Y% ziqVr1%q=NA_U>~{PRvhxZCO(hlDD-dJ`BGlJMh#Eu3_f91ao> z!d};J^i_SH9Ufec$FnG*VP0UE*qP9-z26@|j4e^IIl#r)DipJ_QJpC%FV%uy;JZ7B zi_F255XBVbK!`*L#(72h;?oy*369@>@p;dV1gP4mH{g3yC0dG%MDT(!@+O33mWG1aAWdboXmn3!F# z;$eM?)3RtZY=B{XsvF}$)uuOe)FN{Mm(F*=3^29p?)Q>nqpF-GCN&Slkt9>L>vR}M zYA&lTnU0&Goh`}h(B<=UP~qO_Q*L;9fyl00HPBQ1h1JTKNeB99*~f7o19)RU*6^?o z>`kY_FP(YvNx*)XA)t%evt=8BCkJBvWX<4yQFdc#JEo)kB37RY5hH1s-B`4c6}Z)k zw$qsKt$-&rSGd@<;tIhtRJ4uCaDIwfmYTBY38rG@7_2MIB#F z=uHQGTYs06fkRTreqU--gNoPw;j!piMKt!s$i~{qL5{`QVQ#&9hO4h&vHroo=`^KY zR#b(zuv2Mdmd3rxJausN8Vfd6X3GKg(?wU`UWb8lyo?sQxlay+MOcxAmxf;x8eH2C z-^g8*RtsbsB13i!OtVJ!0zkSqSeD6Y6(s$f2%XWuo#2&>ZFmBT2gp@P-hU(VN(u7? z2{Pzv53hVyU^>JTKXK<5j|k!ZgvkQUP}8x}Rk^|pA<2g-!@LGpEGDT2^hP)}4}lqD z&v1uZ)+44CKe|I``r}Rf323QYeEfYsd}$ig>v{HR&xYSQF(5 z{lsLy1*eYp%A+dqOA-}FZHpb`y z$|5sfaPmpT4G>c*SuqU0s42JUD#`F8Ba`Xl)%){Y)Q&+W!z0^-X|z#qZ7thZQ`Ho; z1EH_XVA;PXPRyCs2n%KD>nDD!LA@$3VKb}x{OqgQC!~#!u0NeEgSB7jqV0)>p0Dn0 z>(s>3<~w|bk+zU(Zsz)(r}49kCN&5sW}c)JxN;5$qQ zAVI0wT2_*_{x+Ji6gGlo803Vb?{{o>!-|Dj{Gn*MJFUFgyWWsHIr>OMB}E4GZ-7$A z>MN&0DO`apqWm`_RFz*@Jt1Q(_H$S{aDljbol-yQsurUME|vIb(I`1lBlm4LN+}&eF;0}wMB?P(wQwpQ|CH20k-1$*$C6U!eA3}zjF?a5{ zs0qU*K?^b_ESWJl{2n0S=7T^2fPE6p2*ul&!_TZi_v&A#J*-KRfWp!6@C&6xCpi;CkM7`O=r$JW#EnsF z;+vY!{$pK+Pz9=192QMFl%f6v3>56oUBm^dyRW}P)VqjkNj3^*c%}dyc{Yh5PWQ_ z@g)JEEyDnJ@pJH}rI?;*DMqt#;knw@&h*0=s*8>$VRg5LdDi8=ze6;GGTAG{@Pkw}GbhI1_p0 zf{bEw=ZdyrYBmTm_$U}g;SugF@bO*b^1Y@|TZ6(tOhj(__GVC>cN>kX;SQpltL@Sl z#akbgpM>J!&<2>!VQdSEJu=T@20QBcl;}Tuf{ZDuTJusJ02p>m$Ar_f0rL5vt`zzjRVe`3k7DFm>i9OQhW{BzJrfefYIYweTv}TkJ6DrJnu7`tfXjtO!cHuXeNoZ>(}Nk?icmpFfrwHT!ItSSl;;( zhz9eg&65+Me9LhGzk@O+#agzBj z_BiQKoJ3toN$xpu0XK6QXMg7h0#{GZ!SRuENRz{?W9Qf&<+$dv2TE&D%BdMHqCq1T zC~#AktU}8Q57VLyQuhWa`b+nY{+ADHW#t6D-}Q~+c3vLSzdv?VFh+=pYpQn)FNW6> z!n+NM^oF8Z9liQz!xv4UFVAVw{rbDnPQq1gfIW+<&d+%iI3?Af96N= zzJ?TvLF(X2T(eCzQGJI}rOO%2X2`c4~OSs#Voizr)+ZD(R2H(_i;W zq`=H*-8=+now)H{+W*3IA9QB$veZ^kdOsbp{Vw3zLQp2x=-seuum@$JTY|3kqn&u% zE)W4tnWfkU~l7H&{40{gC?5Sfzh6&M^?i8A+dX@MM><)am|%9mD46ItY?q z1Ng-_H$aGzoFT(cT3SnrCI4pS&#cRJyUw<@#Y%@3blm_dW^!cAjCU0w=B$hLH|P&L z>v0RFTves2gDq~yo9EMVn^O`>Qu@yXB>ASBR)#Ne0b~a(NZ2nH z`=I-_pO(sMsExdmuv_61(n?-7z_2vynCPwLa@x=H+l?=kGni<-b~tbv8ML5vx518@ z($zmz6vym-eVuIc;GevzE#bhXxpa@FgzIL%~|Ma2|bx%AFKf&v`xlqwKErihh zBtpB{dCEh_>shB`{ETEtBW;|9c?ICI`xrQ4=NB5sHeBLjoyIS;Gh~ii?Y0^w-~xEl z)>86W_C%;_bbgxl%KU6q;$#i|#HJr!qu(lp+lksq9nWyxbpBku`D6*4;=ETbaQjs7 zA@lo_U|GgBe+9qYt7PBPktl9n)sRP}& zIljBq3(5&WccB3FitV%fTMaeVRY5;g<&|oOl@ns~t3=`(*DVDfE`y*`;>}bRmM=e6 zu$n&YtN2cGzm|5Z+Nx}{2bbPvcuzC<^72GSPY9E@9`FM13Tc|0*0jt!yVF>33j}v}cMl=B1qtr%?i#dlg1fsm?(*I_GiT<^ zbA2Cwy5UFDch#<4Rco)cHsZX7ljsiK-%$Nu_yBi4;h$v*fXm-HL#G7+a5>qsTz{d~ zd>EklwYKuvH2UDv(9i&qUOCXyB`la$_rjO2=7c5P{rZdCC6uJ9-Kdg$72O3wAI$sM zldb2JQL0{8m4=ktM_bpk{ip_3hq!|5^!}4@+_-PxP194Fg5RqcYY!sR=-lU=kI#b_ zP1}BWNIHnDEA2mQ>a~Y`jTr_weFu9*cn!$|h8Q6O0U6J~hW&I_JOonA9Zl^9_TZ83 z4fFU%Urx%dsZpa@QrFuIPUGI`T{bH1=?Mbrex7tZl$DV!9k_HB&ZngH*EGv1z3~|L z_xi?k`U_G_@|bGzLy$iQcg8F)@hnZH}6O-1K__`UqO;9U65k74p7;&*&~=ANLf8c*N1*y(*` zL>8i~_veRu4(G>S4=E^a3wH#uE>q3jYgu#Zyu+W(t;0YIM|=~JO>zUj;5MbmNlhR&X;P%X7iWei@er6y?O4xqmD|i3 zx<@-+?7Y!DM#7)KgVODD&9&wVYcyiCe7XAwNpmBDT)DD4c!fO;W$bq5nO@92G;9KH z68Zeq!Jo%;e-){Q??xx+Y+nd9u$0&MKN0vE=@y_}O5%6+yiIXmAL*4zW%f&K8*+cC zS!OytT_E4&=^nLmkd{7MqsZN1Sn;|(3d#2r=2AIBo)CDBgAA=7iK+bMS@d@bb!fG~ zAu6PQE8nKWNCE^yXGM2cSL5}9<)11)N=rac5T}P0xdUcHhd_|cOItj&{b$je=I%TI&(7W=cD3Ok#7Br%E)%;yb=)DUL)UHzQJ zJ+5^RpW_E|@-ANcoiNZ^iMuuP2iD_fikc9VuvEUb+iQFImO%=3y{k&Y7P6|J!&<`Z&z8nOv7 zBO@ciqcwS1+3j%FQL~A&5pFTSK|rJ3i`%d-oV)f>nA|2%ztZc@K`a7)+QJ!d!vd5j zf14Ri5Z8s#cxh%A76ud8H2Tfgm;(G83v_gJTuvK80OQUrDA>I6n6EX*@P4?aPT-)-8%$n<0*Y*urXGynAn1Aqf{064ZV z{1TXtAb)6>bLj57QFfuxg8Ywv0zg+vDVhH>-TlzWU$cC5#uuDx5##sC6}|-PD-{$6 zKYFRf2k`U7ye>)9@^rCGASau!8jG+wM)>>WwB?pb;}w-DXb)X}J6fh47~IdiJ2Vu? z^mO)*kFWJcP_WcjHz~Uz5PM=JCYbxhgAaH_5UygT{kPB};h6jHhHx^yRt1DN zHZ+{lPoA1D)-q9B7g?LUKQXUhN6bKxe?J^M>70-5ZGC!n*})+hi3Oek9Schta{Z3? zd>@xU>Pw;UKl#r-wP8?oYv4T5cetzB%)^3TPxZLvmzYCrIgBp)#6eJ~1bD)$HfMCY zDQ^Vh_Io$0l+=j%tinUzdJ&umIya{Ed}^dYsnTb&69wyNyPGM%Yfelg)wJO)m$~r1 z{VXTUXS1OdQ6evzTaqGXb$hyAEW=@nW7n*QTe*E?xk-cdzB!1QfexPl$_{&#v- z(2lEvd8@|!c=C9Y}(yNbETx7^~Y;t(&uW@6g36cMzt+* zDA>6dT>=4xWDZB_*k2e(h}h`UwQI4XCPyniTv;x6{k=ATR|_*$YtS1I13zvqhq9Rg z+|Ec!*x2EA&6r}9lw%UJF-dHnFM7nnU8k>KZn>csz_2 zCW@XR6wtB$v=2cWY@VHAwY?ol5Ljqn)cdiPQNqmY)ofHmmgCQpsc(-4E(z+m@t^E< z-h+&PR?o6k>aPWdZ%-M)JvfA_wbi6H_E4jHQI<-M87fr?3Evo%Lk@dP{N8Q;im+I& zXx`6Hu@OH~30mrM@OkJ`)VXte>U{XvB3~g;#tER4%_#o}C-XPQ`7m{P^;H@3Udd7K*24A6WRlX|KZSqS3-NC=QE+x5J+BPwpg@+9gw-auR-TIEY1Y&=`5BT8JFZecmZzd|8 zPaaYwaB&=%BNh#4n))B$rp^T`Q|!;;bXM3DOO;li@fiM^L8PueoW^^zR*$9Y9WZi2 zdbff1F5CbbHjOM5SI}uzZfWl7cYWq^CQE-UT`Vbfry@yje1Lup#(L#1T}M7Hy4Q7s zlB@gtl{Up`z>>OH^g|Ox&E(SS{?(-qr>UgT3m_Gh3Jw0A48&c-v#O_;T@daf*Nx6P z`Tqr#a{jsr^1ZPW?Lp_(-pIMLyb~ zztM+C*YQmf?NcFFwhCOk6~)^p3w@kH?kT*@jpv)1fA6P@98TJ5h9b|fG%%yn=H}w$ z7F)0Y7)8{3_%vwo<@4I++H8%Cah~n$ru^T5Ldzr$IjvP3&YZOWK1&=U=0q~_YaDyV zFV5j9UyI}2o)pA}sEHwQjHAQ<mUB>+p1FG!*%pgW4M*kBDDPRwIO!8zPmY3EU)$O`CBP zu-8(#oY=kY55aHQk)6K54y<5g8a8lcTM1p;jBGIK;wYIZlN`0wwcPSF5g2Z4;F4@+ znQfkQ^GLOEd%C+ivUMC_bq;vHGCHO+@!f^*ngX0V!6DIY=#2+cI$mw>#s3e4jRS2V zjcF~{jfO9IHZ$Fr9ea8*l1t~w`aaDAgO0He4=rrn&L8@@OA82^MmSX`bf{==@C@#m zf^brsC1=euXHX&2hchA2;vl`uS8oC?TjyQ@mx9>xYpBIROL-3e-Us*F)jOwfC$xjB zs$R=ZkjnJj5ZE*0rDu1QC*<<3zqmQDm>j>M`xUK3$gI_X2qoDB8H%p6qGiHA97HEF zGrYfAylMUJvOm-g!QLEN3>m?Q{7?nQkwBo^NleEok!i;`x+nT=J5MhOcnJ77EHt_m zIAxeGVWG}aB^iF-3>e=yr-Jq_s>;?s4lq#L+GQl~h8)dDB!GKS*DK+-uqun^6yb`4 z35nQ!8jj9dBxK9H`S+WFcaeHR|Jc4qE`TC+&b_M43jyyDPLMUCG~So95MyOJHjTTg zh+u^KfhEmvIjzA_9Rurd0RTK1&euNb_Z;%yQ%!We1jL3@%-C!}&&|V&o+bHbRcsPo znRY<%Bb{0@nbv=^@&eqOLh&E`EXjgGIw=Q=fVzlzsEZg44zteXKQ5-gSEJv7QuDq^ zocZIhwa^F%H~~qkMhg;Jw29^)0PVly2!__Q{J*}etqT9LTK&%>ItZp{!Z-s}{!-nJ z=gNmPxeuz^&R7Ej17!+7gM+{PjE@%+5)z7y3<(VdTwl?|i~e0Dj^3%NthB<$6-2eV zy3C!k!q(HrMMc8@LilAd6PshG3pr8ncfJ5{v5MZ5OhHrtE+FEg0uKP)xQ9)aZs-*$ z2$b>ixC_#9TMvM{0i3=7J1GYT7LGP}fFfanfPj!p7?_`zN0j$>-8>mwo1(^mctnV# zAlnf#;(O~EfgBV9Ryxzk)Bn0^yM6;04o%^Kl zYBN$)_)1rZ&bQ9BPSiRUQteu^@lFM-%*x6io&Io+EAG3~ph~RV%wO_N#;C;mRHf%w zNK~KR2uR7ozr8`-x00&E)=YTmAuoYJ5@;i7xOSYm;xyI6X7*jd7NADi4b)BlHFx?k z=k{p}3-0YJSlAPV579Q7%ZBXHAaei3)v+K9rQ4w%iR$>W&GL$OsN zF|0VP5SX3LEKU>pUog1&A!93DHY2asy4pQS&*y3e*&-e; z`}fXLqOHzhs6o3NUsrqka=Qy4b|tIMug}tvji9m7+xWWUy~z`3_p)MP2=Yn)*LZDl zDJ41J+nv7Ss@bp{vKCVRsZE59EN*P3VV|M@)m-I!VZQpAPTVq^Jqd34&dYbAudCIS zQvpD6W#V7~pd28r6= zaaC`4?X_GaMD3A2Zjj}>^~lzU&31Mh%4XDKe&_{k57isZ8EFyG?>>FOqn*K2Qt^&| zH|XHt=G^I`vq=04;^f#_#Gfc25a`B>N^RN;2KWiZiB{d8APOL50;#fUG66SV)~GTD z!;X>8IW!tRC!JSm_-D=i^X~)0s3_13U+?d}#G98O+}Wu9Sl8rmcy9TW%ASR>bHjTl zFN8TZ#uJUf+Hi6EZJCatHaIxM;NG~ciLWwf6&_JfBWJ)hl? z^3&d3FAwqP^(lxGW#?QJ#!()dlfT2?nZM;?g%JbZsQ{+2C<#y5oUTy_A6}pCY@c6eBR$8Ti{{M7laGU!r3uOo(x_6MZ1Lb;aw+^!u%Q$&7vHH?qJq{@{-Acl<{c zD4!Pmi(g(4ld;DbG{V5$SU(MK5G(I)9eI;QkuGNLXohmv)C2Jdz8w~6Jp5&tA0BG zd-9YGPeP@cV7*pv+#BZ{yuR~!y$7ziRjPVW@~PwMaV(j%AT?(AiJZ^s!Gty{@8|fh z*B#Su+KeDIOjQ^}1~5Zi1n}phfbZOXq|so%8qcoPZn>|?g|#SQ4VAM|Oxq98vn8)( zt3tgsuj|;DaUFeliF{;11HEA8!EO8}_uph@(D4alyA_*}6;e#iJ*?hVZ2a9Kdo#>2 z%IOy*JTW*|*md|%YPK1-;ivU-sfj~_(A)YL%) zdFG2ZfrSQHa$-iyQ=6vaW}kjpNc;b}xv7-O{VPx8+60<^C4pBQZ$sm|Y|>Zu%^8Pq z!owE1u*$-}CPn4CjEpkJy?wV?`5xx$7}H-j0Ebkr9i>|p*u0-Ruq;ieWSL)atp4Bqr!)D@l3-9_01~SE)g{ zV`r(BooF$2`i2^lqv-%S_I}X*i2Jy7%+f zn{ES%>h5-!l-TA^6TQ%CJ`UF@i7G!DaIDvk2RGmGZVQljUdYOH%gw5(`bUMRtBt~9 zq`u8^a^a|Sd{^Jd--oB?Ac zx!6=C5ml!ARHTWUdDs&TZa8@XD2yPi^}bv2Sz1$*zmb<7C1#Y_ExDg0FB z0y7rm5X@65X6G!q7L!XztepV9;inh4z?Z?rl+Hd^G7l17Mm}kBgJ;#%?VLpH*v(xD zftwXj{(F81AxKC^KD_a(#V)$m--HM{NeMmVD^EB*A2~F8AN({ffX#lZaq1)VM>c-0 zGR!|GqmMiaL*AXC&aX;CE7{Ecy~{gWlb&6pd)%iSEy`4ET#1YE4>=LIj&1C5}(STSlFQT6`h_5W7v!b>r?@z zK(&;%^!wzO1Q!zCys7~B&Cd5W|mG*e1 z*Rc6Q>_BYg(F?=Yr(N>zd;7!=TQ&RU+DgQ#@;b0$`p*idUrp^4tHH1b>vPR%?itUv zJGA=UtD-v3y}QPac$tcR&w_g7(5XAj#)e^B2^YTh>sr)Z(FKD2&L{}yUuuMM2XKO z#E(3kW4;1o8|}TG5*Kf1sH>RBFd8j2T=SjT?pWwk3RHihZB$Xe!wu5DSkUw09}8;6 zL$gm^o(&wSw7*}&-H6MO;^nMXeWjYV5SA_(eeh2MmCfWTw=)CFKO%K)@f>Z}W#@1r z-uR}H?j$ZB)ONk)$uSicB$#fdJBMD_cmdBlwBnvF%?&Wb1x-hqq@rRtXmy*cG!km; z@^0W}F&LpnRWof;^&oG~4jlvd)E-i2RvH=v!M*jmL;=vJe1B^B%~8zDdulc!QPq-> z?A*c)jhy9?qQ;Z^WN?@20r=1X?eo`F-obs7@}+8ioRXWjVIlE zGk55KzRy;??0d^T`{Gr|QEaY%kKlIPd&Q?jI5gy%);|!`Fc4bHjfaPqo0|*uBRP2x zkcW@wZl*Yf2lq$U0%gIza6Erw^@w)7z|QmSA%H3NrDS>;aOYOx{f{G;=hROAX&qgd zwL4WHG{|be=F*;$a{E%gh`ZNH8n>}q%h?65Sy<~zuG7+yJEY7QPPH(FT%B?bKCG|} zJ!MGp3x-&Ai*^s8ONEe{sC52vSxfs4vt59S?~%7=gTqyd=bRes_=ld~oVCwSB{n5b zo?4549*3*PU=hc%@iLZWu+niQK$}Z)y{J|MaJI_L&*!+q{RiwdGqdw*%1=c6ydr}P zDvT(}6W?3QDmN&F5#R9=A$BuH{i=wfull7bYeq+kRqUA+=aIu6^A9n0*nxDOA3FCFBFL zRZm+a@i4?QMTSH!nu7uX?MW^Fn>TM{kwqpaCL$F9hxz~fL=-^Pg(l#XQ5m`}6DcKe z2ej7i@!E8_Z84V~z*i%v-&BCz_VTb2F-X>W)eFYg;Y+_+V&z}lg$m!Na(s&{kB|C5 zb}aJc%a?ycgUYWxk<5?LeP)J{{1Y1+8=IOZqmOi zhyUcH0Rmmhmy@)f;>+bF_W_A=t{f6t-v!B?bm5aUo^X|!`8k$ z<5o7}J;utn=x^MM>c)pdW&ZM+t`gHqaj|FfO0A1GG7Pp3UoB8MECAXlt9>)(U$w#h z^+${X_SRS+yjYc=*TGpJsG?^`r1jx}|N22^1y*@Io_4bnFvOyfn)i38(HS}A+AYMf z7eLh&OM^IDEU+1OX})&~j#v+HUf_EKMLBH7k~lmU+6<>W@HFVKg}#(82?KOCTHB_e zpR}qopiEbK+ohZLpA(Su!M-}C>&*&sZC3&|du<^NI;r4|G9oVDKFICWKnPc>rTeDu zO1I0xTO;3lh74;&!>#QG2k_MU+jxOqe}ItY2}V9?+ZJigaAmy7m<$LloS=A^1iL%z zN@^Ksc1d5{*qtab+L=F6VYgipzT5)#d}s*{lgFy|F}`o*1!{uZ9v=Ce#RUj_FW@`y zi39bwYtFaf-0uCYX1t%EIDLQi?>CICql1Ns6L&XDC(qqqwqG_{cO-qVnq%IOFzC;_ z@`m6#vja4>HzEdBiHq20K^;dMOF=$EdxeJ6Nwj~0{`}&{#uz|B^|@}obJT2k%^iBl z>S9%Uuu1q9DFSqP^*iKO&&Z&Sr8!IHR9~EVXO+$C#VPts526BPS$CZY{gW zQ1Sp>yG*2(&y@Y8_0FAR`GR87^eRVniDRYR837TFe-vgcPvL&LX304yf-{{2{9Wnc z;%HZBwDpli>_ZE3I6x?pEMWEOeEH0^;Z>d(Cj)*>FcV2ccXud4H^<`-T4oEwXn9b( zTk zul}8vqs1&$fdUYql4Qbt4QK_+n|AQ?WmEc6xgGn5hBgBa3!-CUzKxh{0!AUWTZKf8 z`&l5n<6EZw#j$-~HKFq(xF(B6#F`tqKF}E>2c!yj8I3gB{AL*(S4FHxnr?3EIPS!Mg@WH}waOtj(mewPl$T6bHP zt-d@Fvqe2HIB0QRLa1g`dkBv+%c2&Y}e?@M?-p=pk=NhOT(iOo%OiAkH?vR$an76yXIzV zM(748smmXYH4j$ZH$r@C=-t`;%i7|$6V|NzD*w!_!&Ys;3o0Ct!|NOyrtLEM=T5?H z-9DHr-{1YHXXwpPwGKVT^wp{9njSR#=u7nxr1DH`IWac)6+{0QX6F4uiH584)}94o zMM&QM$L`CeIi(Ln)L9w z+ArW+9g%$o-<)>%T8K*i^$cIyE=GCFw1xepc9)hG{&Z_$o{B@Qp%n57WG!Df)16Wj zG5)1-=j>fa)GqJQw!3%|UeVxF16Ba`EEF&HK9QXuD;%4(Xd1H__{H4osWh zijUvuloU;@iDX9V3Q8Yi+qHGuPn&extM(Cna5;Ta;q?!kx`>KIlat9#J4*AUp^1Vc zPyK=4@*2Tm070INc|vSHo#b|F)0R359Nqj^6aqUb)uM_l&O&lAtiIymg zLj<;y_q4QOvGM{<3s3Z)9h(FlIqcU?W+*U{pk`Jlk0OBnC-ciYc0hoW(ZF6w4< z*L1YRLwCp)aJ8b~$oR$-z&dA*c7(8z;kj=kHOufv^at_SLmtfev^HOO(zBG@%$C>~ zkgU@Qm`AVSMHltu!=*0t1b&>8In{~PjW4L%O|Yx z(Eh4_N<1ud+_$lKT#h7!grJ`uZcMiafBw;ghhTh&NlB3gf)`L&;|6vD`vJ3TEMR#A zi-Zf*ww4@*=;;}=y|_CdH_}!wk0B3%_tZ5380+QHa(@&26dje0Wm-Q4+%A9q-V!eM zQ~xfspV1i|@3_c&S(#Q)QXem}AAU(W5UJEVa&mNa_-U1YgwcS&l>yD%mxYA|+2yn# zKi{Db&y;Qdc83tK+NGe^ZBJ!3?9)?M$+7+aWd13p;ISqXXSM^&Li~8-OfTwSx%i!P z1xGITB+P7nkt@=+-9YQ=c#V{<*uq)pyuQ?MF_~oGU?L$B4d6=U3d_hK6%`f93j9kH zu_aMstF1(D#D~6Iq70guZPU=*wGdHyHOonKnq~f#w)sn1Mk}(}f-d0y_pxB(c%jZR zr+cEbwA6p{@FO8sbp3%TNv2$e0MS>V-REtk^&f|SBA3F-P4yAS=QEm#l8mHP94)Q%DV*>v+4!G60#%v3}r|X z35>cr$CkjM^91-}96;UP<4czkl&f#K+fh{x>-D(N;jiy_7m2?Yod12TsMQC=;uMsW z%trmF!0h*rjoBW@Y<<0NR?RY>gyE!8D|>9N*Sq@tv_IWf!l+R8SP0Cdg`(O=GDXmT zdcrwq0d2wh_MJA)zR(%RCjR&eLM3Hm!-TPG)&g8KtvLLvs~!HdJ(ET1&Ro)z`$Ym2 z&`Bz0fmuz=msD5B>s))Oaostyj&ptX1+g|$Y6@&{H4verlfG4WwGHp`H87q89AC06 zg`(l{d4YjmL4r#f!%W|`<+#3fnI2PW-nhk@MgcyK6;>nC0sGba*Nc)85*u?d^y(94 zJ9kga_~sNtrbmRM7d~z06U?k*7vWx?JjQk(*j*tZSKaq`tY!j_cBMEvf|G1IK6l&9 zX=7Fv!nWpklib%>u(T*g4Da|bs}TGPRF)T)gs+Nz6J~l1=r$-g-xn+#Dhn%T%_SrX zc=Lo|)8og}Dd)LiA@sI~q8B0r06xalnE!g|BdjSZ+Owxl5|xrgp7^KXe! z%t_M*GG}M1dm#mbkPlc921!)>A+M*2QH0^Y9UmL9;L*{bU0q#!4|Sd2G0`JVZobbs zbbAN$T@c<+z!+hki1&v8Nptz;g@iLfHD%w>XKfp$Jgb%F3TA0;Z>W zl2>$)*^qero?<0+QrKuZvCG6+uxolg2JB+_pdIXE)x8W2x-ZHvUjhss*X5D` z7tdvH=`=7fPF0LKuZ#aNXqcYVc@y@erTO`-@B}i&S4jm;?rIMxu3kYBJR_GVAc`7e zME%L!X(sqw#l2>^ex}UqZ#LQm=WRC<2R!K`DQClJ(u2F*4b}ujZ!u0i+RTy#rBIt~ z!epZ0%yG>WH;Rh8aKg}#UjMeV_?<_AiHuQHZh{!|r8e~b{{AtULQgg$(#)2TkJFo{ zv!3IjJq`*OTd%gZyWEmmIu7eqId5uZZwlu@E1Z`RRy!1(awC@1PLdTo*S1d#5Z{ocHZI+(3lWwvS5p92#N z#p|MUM~~Npm47}cQ}@Bh4Nf)bA}fcg0#OMo z{&tGRDEwSi>b~`0Tk-EG#SCo=Snn6d_1x!*;a)GKnMN7-)SwvNhlY-UN7)pSXsv ziFo(ss$d-V6|-+vLiJw4a2X7`Ve-~6higW@BWkKU6>rYib^0Hg(dT&o7U zSAI|-qTc}L&-dNyj|;hR{f1G!$;>cM>7GZ9d@o)e8Sb#-E9vsBuZ$cTMjgjjbVQlp zg)^bEmg*@`ho3NnnP@rXsbV{mS!1oXpM&G+1z~IU)jSRl$4}bfe2pntMWAzynM=yj z%FE^0WV_i$S{sk|_5hQ;=H_OHu@pCc9iVPMZieYgDp*@R!C={HhSt8D0p6?vjaAZx zUHUwrtyTwYC9@wD7LxLM^TZpYg@Ff5YJkhhV`cYI446`K!eR9y=e;gm_NC{1l5J)N z$dqKa@e+Qvu&#DZyUHK|VeVP6q%US8Js&wz!FlkRL9QJp4w7?#U7SZY6Vb9%0r+ec z8Wjsy;V^wMzdx!O`>0+Fr!Ex|&jq6z`kZKGdn|TR3 zWY}Tv4inAT2G@f~1jK0nHNDIlNK}+yMd8SwUWDaVbPZz)6Lx*)+it3*{Se*-MXDqT zRIYsrD8&+$h@xBOl#~m@7D$3&=eIX9$gu7g?GK4;me?d2ZJ_qzw?`6AInqL(Wa(+T z1#ceS-aVlNae><_y)?7}`ir1Vg8U^0p->=%Or|S<<3ZaLWofMSzT#di)ehJ-GE9`r z$Pt}2Wdt}$h{(#m6KpRiF-`_np-u(P@}|&O-j{&NG1*z?+&HxfVGZoA-R=Y#GJhe9 z<`!lhU!w1sQo_p4?8$M#yBQyTN{ufrN~@~k*tT5(MlqL~JhN67U25%oFHhj@1RRd| zRu^*pLeRtLSZ+gjxaONXkE8+11mVxvy%BesXeRV#?? z%Ex2;ZO*vj)tVfaCkI0!DIbm-NZ<(Vpeov~@kzM%NF%w=sWoOh#%9uqy`oXoNioZN zGB64TjAA4xgvp|z1P|~5pM(mq;gFCvI0ijxHY^T(8O>jDA9l<${dEB#(gHMIJ ztnAbCr~@dYLqY%Q;IRr=EB@soa(Arjd)EzT_hHnnhKsm$ivZJ3JR&3P|9Umk+&ea?Oj0p@|^ zF6+gxLVfNRD=AIuIKI6+XBH~y@7+N5q+k*Oyw%Z2YwNYn!}c-F4_+BVQ5A-}6?k>g zXLWp6vs`e5zFe`c9??Jm$W!7+oSabpmC38d)^c+R@wgM+=)ejBr;u0{0udxD<|@X4 zzB376F&xfT6x7$pH@|f*Rc}D{r5K*#;a#8kDGgAUoqos_02hw(a)uS32Wy}eXlJp7 zkqAs*zHIK3Pqq$Yl1zS~k?k}3ZmJqP5=^C1wm?UQ43(^{Eu$uo-qp!2zN1PUO_}-> z#$4Eu7$)yhidz581)%a1Bz>8SE;#W{eXw!=n72GMC6h<`vrB?Xk}5VaPk&wIN7`1TqgaHQMzlEYoW{*c@K)@b738P~T@N2SS|M27ao1sO zscATkHE4Co`$nPTO<=@|yzruANAu+LiKti8M0;MfvZXl{3B${0mlJJl$&Nz zcVMl$dYawG_w8z@-S=XpbJs%Q>HQ1@?|=jQfjYtjEzNq{;*Vz~3P(JFO3AZL6+prc z9oN@_pL#fHiJFuLc^CA}EhMeo&_hmlj&(QuI?6W(U%b%27GZqkGI?h6xtYR;I`KWx zZny7S_a3|nCyH5dCEnn)<#c!kjgTv{lubXAa_TfiZa(jV)LG_-W>(X?DJ?s?F&cbB z_ZLRx(hL?4qbje-XWw^HD#$LRH>P!{qz`Zh%_1w6O2t?{|58pU-LC%d99HvJ*!=sj z^=fY0`yMm2Gm*#nBO(sNA5Y!k48tLuefrA{84C0s17?{?QFuSV6W>b!xUv8I`4c#| zbEJ$=N;`k_7VrolMMv27%oMI#8qQaQGD{BB$GyC~1R@E*mShr{{Oq_=r3Px2@uC$U-nHie89E9q0(5lQJVQkek}Q}6 z#GkCb<;2=x$c++kIF*-2nJ*RMNTH0DAl+Ct6VCK>0=8;lcs6bD;8heo|0Oc8%A~X44IOUwD9KYA;{H(|!?a4Zz_!Uq>J)sa@JvysscBl+8b^0#y^M1s;{+(Y_%@gxXH;qli(^a*m#H?rOz*~EX|DpR`v zywgAH`v@Z5 zNmqs(_re&}Zrqe5=c6G9p$Y#OF*!zW=GN!=9WZm^(EdIOPWV0FI5lv3{8g%MR)jen zM4Sv+M))B?0Uy*&5j*h6?c(gbP114JNASH{ALzq6ZWiZ{L#NmAbS(n!HwJ;DnRmJz z?`OBH{E_RSlFWjwk_w(aT^SX~8DH1#*V-}jd z&`lK_h}X7QvZm_!B$4Sw+oWfc;kJm(ZP#>a2dT`?^6JG?hV=%9s%}@+xSY=2^4RTs z+gN4UiQ4ExA7!ey9XpSnOM54Y&ozcmiw9y|5J{k~_<;KWL;A~h-Q!{g=f%!y`S!-{ z0rz?e=XmY9Zlm+0IJdNCjP9ckZNbt#4D#xw>GSFDSiXyMs*jOcgRbq4#6c>SY7o$` zo98DOxu*3JLab$FNuB@Pp{qEV)#hb-)8)0bi3m7ta(NW}@(@|t@PI9fpPwJFTqVz7 zprS>Cue6jo1UKfqMBp75L@N|%CA3@PITzfGOdc(vz-mhjHPaK~GFac1wxZLLYQv(s(vXwmpPrtc zJ==F@iVF(}c?XPw!JDPNFW$w)B>)sv6;OtHTT&vq)l;|%0ke8?m{5E(9mJHG%&n;b z3}w^3#?)mexhRry8PJ8`JL^|;@~7qXCnM#WJw4~E4B@oX(n#NYNOvO}FmhNM6L(R+ zVj!p~G8f$*dWbDKIp523m>wL-tI$bH$j_tv1_ywYC*ufj+)J*My4=`k;FTZhQx&{< z*b)jHZ*V@W(n#g;7&sSF`uvnoroIP9=Woa4|2w_u^hF2;q{SA_`nHE$jDa$YSO(Hu zR|a}3S_OL98wZOL_?tnZujZ$t>V zYh!cg)Rt^eN3D`ZTN{GlE`1qP{FSfo(vpU(Sj4S|{pPSP)MRH8$F{@iP1X8gLk52D z;E&!ESXKUDrK`p<3Oi}xX7V6S7vU2%6+g@KZ#At$OTy2hUHPP192O}7rykwQgw(vb z{9U*n>0Q9_;=6%&!^J6|64HhD_+>19n}yZAr=`@W#mc_s^BKvIcMa^88=(s6N5}wnt61VlwLrJ@w=RujIsB3guji$>tHw zouOi`;5Qt`x@>F;35qUv@X2{#B&o}H+8+4fcd;__F|{oSZe;=ApRrjej$?j7zh%Ep zRE!U&?To?B2ls?0!dH-LCiEs6{76g?yr+omjs-kD&prh}pz-QRKUPK7Rmy}>e}1F^ zO{>&t%iZ~x;aUn%sHlSL7wC5Me>w%fn}RDaxYp>2p$RYT+&NW&|IT%d2sTJJIoHz0 z=I-uNi^u5S=07K0RYk8E*D0A%NqxjR7Qv`eQJO5&^;(aEIbm$F;NaYy+(wR6yDC@n ztMYQ!DUCm@(@3^)?z1n@3{xyEzaXGn=Gk&|daGp)Z;-MbsDenABuMq_`m4Y!j6Z-}JOc%n>PxiR1feVM z*mxtL_VUK(vfKX@OtRbX61~&qncy&Gg);n%xl3G=_@KKm3O;!G74__bK&$hJG~)aU z`}^&dcE`qiHqOUiaUzjxnfFjHTx;;jk!c};y$@e~=JK>$x4G$%7Fu*p{UQE84Z!&~ z^Y&}cR&E=z0+o?^JHZ`Nf8(IND`E3SJ9%qn3hz42KG>q3Bgd$go!Fh&8HVrQv{2{R?j8!A}?DK+$B z*5Ki)RapcG)o`g~4@qamLzvVqEPvHF=)W`lM8mM^}*V~eg zI%S*rb=e2s9aR3(_n{5D^_uw3S{?lI!ah0i zMSJrJ;Y7ZSr_t8%DDlx{WXX}bee9>h$JObEOnc%IH)}t4(w6*^SvyPmxu#S7A~06R zdoe$hWKPikpqg5Ib(kAqPP|bnP$Kxeh3;|Dg#dK#OaT{f9fv-g2b+$!mvbaIm{!2s zy9ZyXXM5@tSrllZxnCUJf)cy8DTM;-l+L1q#dm{CtEz*3!#^TUNCfXW^@og=e|`EU z|FV5|FDYu!wlco5Lb8=CLgCHdu`fE#%PO^xa9-WErD&!adx9EjXT@Ltx(b`N^D^)T zIAJ^xpDXZ2i0p8BwqO+u+y=V;7cT&S99oniPZCnFA4F0#ktUC)>s}C+ZNo1)BComk z6#70cxo##27f}x5HuTgtU-?hkCi%7kb~MDxSsOdOG;hCUTGt0}TV7<3{_+-|U$iy; z*+-Kr$A0Z2d&9TyMDtyd811On{S87K-&s6=l|>>2Ac-AL%kscl4qBu=yQ9fFssc|k z>#wC3u@<=&=PyO!G_pyyIHzvAh9C-*W(`fNG5>SsD@6G%DOkr4=n1DlGCX z1(pgULTv!z_`G~N3tSkJ`hhMne}^*vc_$hb*Vgnh8hx{d6OI_vRniY3v`lTlq&Ut8I^jeMqAieB{o z8MTI-53?$UO`c>)OtJw-GBYhU8tm=}bV~ww7p{c2?MObc*|c~)_WlHt^Vgu8V{JCr ztuNx+)0Y+2n;2i2XP!n%rpx1OiCp{%ltfM&J3Dj0eN8%(9{YVC$>48b=^cXtG$9eu z!?;^}&mC|*YF3!ru9eNkS8*Ps5{R|6a<{O-><8~6KC=;1)I6EKJ_#;39`z0UyfAuzEZr(IkPIarn@i_n4vj*jm*Z3C>f%VxRYkln=Jb)sT!+C$` zdCmIj)>ozQ?Z0&pkci3ayR?EOSjaVkXikyC-JH*aw0@p_Z)8Gs`m2haAsmdMicmHc z97-Bcc__jt%ICaV!}ce7$Ey^r;q7+zcJ*a7-32Nf0loBl^=Q&yYsqP~XXkLC5)-c> zeL)suQgR42wdZFk1`O9fbtc~)3T!HM?1BDDeSQ7IbXR)O7msNZ;Vld(P!dR0J}bhl zLoMU<9NK+G5K*)5n7s)fFxOQ>i==;K8`C@09i=sq0A@ z8yhd#>}NWSmy9Z9!`Zdpvz}g|(L8rit~xA)dH+2!PAx|gJyl(-OFJE+f^Jm}9+^X+ z|3>5fGJf1-eFoxloRKAY9u;(W;U8Olc*y6ziaLIHWhUJmWKb|uD+#;PUlHByhL`2r zfg7J}AF+FN=c!f55}sf{zZ}#ipeQtsM4Y?f$>6e~j8BK6m^FX={+*YIBB2B_d$9J% z$+n#hw1}Xvt4f zcN*8dK_)z&m+J4*SjdOPoSc+gWRi=&g41SuE^~ogY`puI8O&M;)n2{gV|aYUF-O*epIxX4@N}lRiz2NgRK4;~D;#ck8nji9u+od%lf+ zGbx#|7RC9puXZJ+jE89#Y?FLkvPw*T;%s#$1eaIRXg&42X+hrTPKKIPmMPnMB!+2J z@;kL6caUo9+Bz){?9_UPhLbd!3S#bF^)xOhp5Dtgr=W7V`=IUzwb9AO*CeS@sk)(d zJdJbd{=aU9++9HHHwH+X_#-HF$=$%dl#z>e!JA}Ul#}d|n0rRKQl9SF79;q_qq&1J z^=;iIR(*=aHS{?-zoEJK9~*fb5I-EBmoiHF%j5R*b#>q@*CT!w0qE$9z`r;&zaO*n z?E!?NP5aqisa$p>Ku3U2LEwSvUvan6Xjfca9WO~0h!N;=Ja4FpYrRlu3h3T7lKU1q zUT^-wBH%gzK4}kO6wSffS}E8h3VhKym4aiwaWEwX4=Wv}OLnZ+R+#k9A#d)H%f`R| zzBV>}P3|JCVEkF!o}a9e+TTOI;h8DoT`qNPyK1 z=PG(%b%@B?D-v#q8mjz!aBBH#-I-tXY)@NmogK#P%BJc~=V8?DaTz`3mBzcQLA8jUdORLs<8jSk4W zD~f+qfyb$z>#0@f^z3XeFY@yr!02xaNWX@Edc)Z{IFvLshX9TV(DZBt8pa>pHv_(J zv=aj{A?PQN!D*A%*4E}1zym|IiKM2iWSfustA>Zg$_e_Qiw^WM3Q}^#>_gOtpM#x) z#Uklex)Y)yK5rX(g1iQy&Y+t(hOm~r?{hB%9+&}AKkvnX{|&#B&#v{}1QU`}nEG&- zwJHTjOy5|Od)ddlhn2~M7zTyzI;7jMMA$Aoyzd$4r3j2W%rLD*#8YmWGPEBXT<+J| z6?%!tBqHP@c20 zB2?7lX;Y0h9k~F?Gq+voDASR@NFWKYr+RrO5O-!yPI?7_Oh&{6$3N7H@93|S$|#wT z`4q!9)a;ll)|UlJXS+nf+{cR7cX}WSP_@Lb|IB4hcu%fiZl-0J;Wzts2k@`vKC|kepWKfg0^`^H&V5CVHTZPv}A8{qDy6 zzqrF_@I-c_mmg=U!L#wEFN>yV>+Ui9F`sI>K`t^hpUNaKDs8A(0TX+=xXHw{^MjB( zoW?JtXxRpYJT|iV(3Ow4KY#U@pf|-VynZJyR?tOSeZ4DGJmYGtEwYsS6#28X(9~PS z?7hN}gdoLyHfgc*TfqEg^2WFWG{3*BB#nH95S#U)-H2}=!f+PLcu%KP(3!M}2%G0f zCrtgbgHItiXvqWywivWlI_0QbSC``H{h@BYRftF*7DxuCGjxl&u$_~z8_sDGPa zCqIYvMgEC0Ne*)od9M18c;?Vt!c;+jXawQ_sXJd|!#Yo0mw0?`!8eJ(?;24Dv~xU@ z4e@^v=U%75ON9-CD4EX6ImT<$ej`Jw6@~D|4}YJXn!JR$#8FYB!I}`_Wws@iBK|B zHo)RHL&wpAhY7G;4(H+jW!#H8&8o|p2CPs)yf|!cHMl+$P-js5^7p8Tdgcb7pAyh1 zQcYWz$s-{aQ`z}ahG4ZdWv%iX%U}vGJ|U*@>iipR`}p|y<|N|pevE3NEn^%#{vhBD zO}ZtTYURgq5?C|R@}c%H{R?J8VPX+zj0V}}CiD?eZa z1%6WO2T_s23M_(*7RBX6E+OYprI$6y3Qu1lX3s?iI`F&$$|vVdIf3iJQ-1#E;P@(P3%^8< zPiw5I(&6k{?yc2f1g@*9ottSWr=oEu1Ly z*y;ou0iO9qHJ|ccEtHT9br<55DWb4*C4WeY!C}FUa=eQY<6i69yNdebEpoWEtbbHr zcXBQyJQrUIOuvJ>w*(4(iNguM9u`n6rORTs|4Qh1^VzF!zyh`uDaC)4E;#f2_~on5 z<8>>_>YB2>f`I~Fv2Bq;&bmbKxzzCr9)>dZi+&OIr$nKDd?e{#d+q^vUsIf#!ZYrv za;St1E`t8AH~NnZroh5FWMMp3Q1_)`|+h%w9i2{srZ28@yor?63>?Oxb7{Rr@vC1@+{4>AJTN z>AjKd+fN$|!?d8RefC_#Ijup>5T62XXiZEZ`6MBR$q1M4X*Ycl3(WC9KF1S@?Ae*d z!jV33M34lSYPvfXrZZV$-iUuYX-1DeWj~l{`QBblzrnl6{q=CB%N`k290r~*+Vv`J zK7`nTDV5irzD|H#T;g?`6EQGst&OEKUYwc^m&`G3Y<#F<(qwAULa|C)5E^CSwYyIv zhx(0UxI@Jvac?|cfz3O+0EApYWgz5{{&7x|>G=$Wd%NLOcA=pmolTFu4Na{W02zc_ zSo_L}n*g7mTZ?4u^p7jrrvF+SI}po@3?7GtDL?v*g3b>p2%{bEx58ql{*jCR4LLuH zQ;<{;%*UB-+xMUQZEO!F$D8I)Bs964L^QdgwSV_g(T)D6piw4 zec=oC6rt+#O!z-8fGQmQVuK4&u03Fwbo<40vh4ah|CmS?&o{dMuo zjX|W%I=Zb*>e~$=zGNC(t*D#nwPZl;#aMSE_kx=%R_mE~lG;V7>W$TsP@x7NVCe$J zP#;9R1P#YDTD6A{&!olaZL&zfXU^ccSsgVCG%A%-<5Skoh` z^j&bE5>}QM??>67yzM9WUy@PIVyCc6$K8SL3J_|dJ8=iX*a2ibjHJ!v(ip@Iypa1! zAu@>S(g0KNt_|r*Fxh zA2Gk4T4+>}x{oxb{G${2WNR>TekXVYAWQU=)qllo3e1u!TQreI5vBdeV$&&6bVnkFgaTN8dMIXZyey$>)z=fZ)(IzG(SSVV-9*z zdzV#hyzzZ{SRt%p?1GR6^m`7$%fQ{ty+nUEEMQGdkM&m|>b?>odm(J}yTWttxG@%R znjH5#WTX`9pT2x(Gkz720Yb&=+6~~F|7%7?v=L3+UYGc!Lh$`kyX$1eJR_LWgyJqu zFc4ebO3JRY5(-wo7$UI2vXx$|?wOWxolwg)Pw?5s53ygQk^sbMEZnR^dD-(#)1NZc zw~*XgURlIJn%WbK@;ntP|C6c#!Z=5m>gy)fp|Nl9$MSHBZov9;&UB)~qa%uVVnf(j zIt+h07g1AUT{d7>d6G{+KYP(G_0bcmf?+*B5}T0qf@|p{dq(9_;cj3Sw?yqeIAIYW zIfS&gsZMUS$(+~XZy!e{uaCk`$0rC(xD(@O)8rsL>cz=}~K z{UJha=j~5l0k2C5=M&X8)pg$k8+Y`tr0&Q&e*1ZM+?5X?=IV8W+~JtSI$yfqXEBU| zZ?1r;)-AEG%kq>C*CAf3^FFui1cCI@1KddLBh}ko6Rn5&lEfvNd38XiC+G5o(Tj?wjCim%w7%q?K&yzA-RJaP|{`so8x-flvK zWgCQ#iMpat%G&a;T@?aS(Cv?GBk1G2t17tl9W`%lZ|}v_Uu?@Ad~)+}5{Z0Fr;%D( zp6ZKZ^2iXJ7eBgVD(|eCjuvDQLRGD#V0w{Ywk;)sT5wr5xYDy3EKpEp#lW_M0%gW` zL!}EsJ^&w4xY|d3h6~j-oj-e6QgbJ-bFDbIv|z!-i$zfjb!YUfywwy*TQ60c;dn6l zv{*B9S1g#DAdJ2g5W_VbE+TlqTtq9X2p;vFFI%9lh*`y4Kz-yXQPO+N?m_%E0Q zA_%*=4kGS4Ji>EcL2P&=FU2D~$I8T8ZzVMy!2T_;g+s21qYh^e-DabKvKZy}8k4nG zU3T~JAKdKEnp!b=dL_5SEhsfl_?C9DqQj9})l^g>-`Co4oNB_8>Z3!6<|LqEoi3r@0scDeG*X|#Vle@|+b zpq41>0#`i09>Zb$PR+@wofh1-xA*M2H0l5Q=`8P3OqF>A^>Cx1Uwj9o ze)$RpHAs#XYOg7~e5C*tD!HM0)kLZMaklT5Y1a7H7YKA9S2WzgavAcKakuSpLWBsp zF01!Rf3mcqV{d|#-Bvv|`AxQ45*7PABd&Ycv7rn8#X1PWX|MQ`U#s=-qH@e_zW3^0 zZu5N8Rh;HL`0e}1Y5e*leeCO&!n5hkhDJhm-zWXHOvq z2x(Wepx_`!L%~!1hW!kr(W!fP!(^xzAM$)={(Q1-zNqHLxbL%#H7@X*kRRZlFlmd; z9U@e}y17lVzO1Y|EKT7vR~mt41g}PlHXJS~{q`gJ20q{b>`#fxHnyID*z-SK`T|jR zSAyHekGjvtMX`>_w^SYXFKY67O;MqZXWLx^TJF_zJgsrFIW~g@bv?PL$n3%*~6p3qOQug|51dWMG-b&Y} zyM3EZKYZ@UY)E4}OMOL0}G-~5iE+xA{Sto`0VfxSukyj z|LPv3Izk=T@TXz7_1!a5X6@VR7bO|Y{I=Gm57z?)NlBMxM*MdC2z2cQ6|m0b$@mC^ zI#RB#s-4F7&O7{mx}}^=tlCUm6faC{wyKcq3PQzQx8Bex(Cjs5Zvh__o_d6}dSAWUwOPFcBt!2L0RhQqJ z$9emqu>%OxE`gmJy=hSQXh0xYF zxWn)6t9%L8;Es6q^CjwP-=r!}GDPg431KlgiCC*YERPHq9!!K*^52{6>EHKJ-c=y;7t9Z~93BRz_N> z)NA-gYA}k+`Jk>j!)|iDxVC&$4^&2cQj-p+X8K7X)%pI{Az`xV7T3!IYx|jU!_Yca zu7O2L&W6ygUsx2~52XMZvb&{dG(?#nWVo!L|-S? zs|jG_Pw?!wWqrge)dlH7^@5Eao<#bjbcCxlLbktTWJW^md`?L-ju%Km9Xnux%?Vp` zt8Y@+00CD`3yZ;u+^BE&=Z%i^YM&8|KCt_vYR zI7iiZiPg(zYz%+ow0R5=bX@eS8NM?!elUjxuG(1Sv{CpnSM+=O=;qq5HO|09uSNIw zCkGzZ+XBeedgz4t*4@e-2db<}-tkXWX%Q(v#dB`1gESlOxaP3naFnU?Fc1sbdtP61 zFZAa<7v|)o`25?ST0(BKX@Lh*Z!NhPrXaYe$LbyNir*mCxaTu{w)<19==$S_3Uj?~ zu|E?UQc&Mc9n>!%1K%3FkZrP;KH|UPKw49F%1duA+1kCC7JSy_!+zGlgHJSj>?(gp zxlOc0>gVvFDx7@reIm8|-0Jp8V(hl_L;+w4MK-+^o@P2ybeahGjNRQY4<$@OHN6;; z_}&}HKhCRq&&2%Mv23h5DrDgHm8yJ}D@hxHJfRhzpF;zFyw^RScbgd|3=J_1pt)9I zSU+qBsRcD5IA7K-EVHCA?&Jt)kHP!-#@mrN@pUz3@3oIEJ#S9NJv#k^eE*xAo-i=& z;I=+|g`QnDVA5VxmgM63i+uuTTDfW$+lY{}TiYnbg7r=nx8H>dj8o%kowgBA7Vqrl zwoi&oJ{hcbfRoW8tt}ZaDf-Gm_fd$v?YMo+=0jpiN$3Fn5e&k{S%I#udSV9PgL-Vd zykiNc91xJulYh@qb_Ax4i}-sB4Vjt$?YcPaY{3_jWOwxdcL7&p2&^`@sN$U|R=Xl| zQV%GvDRi>j(3FS*veW|{7{GI+;r}S^DMf7?FK2P{yFXO-=K;OLFp{SaiF5DTt1++7dcr=oIkmJUrYcy}de+ySPvQ@$z z0b5%H@&rnt5Y}8tkrSSRsx|^7KVeo>m_S-$h<9CtyyL1<4uIA7QaV( zrgO$OMs(|U+MKpUHgl0WH`O0Xp)TZ%jiS%8u{UNtt(??n;+968+}4K28au?V2lGo7 zCuR1duyK9ScplhB`EQ`J-^QnAA+MDEX^oDOk}uW&?;VKn2>|HyM(y~}m}Df8Y=+%% zP}82vpSKuHtAj@h6|($6!~uO|mmF3uaxP z{whwe^U;zl;3-w1Wm>W;-Iy}+=XfkY59l<11m-4`1DpZr?+gB6N1Q6btCFL1$+@x* zmNq&v+S|)tvWSL(jxW~K8iTWfC?}(MB9+YA*FUaRiB^WKfs*hMCSVI|2KvJlkg5Lf zj_RV&brty`TIpy}3jOSbwR2|{XE(dqe=Xv4mSkp$w~;oV;YVTe=%e=Y??J+v`qWAz z+lY<)at*{zqhA=c>Pil{spUs%i+xe=)Y#?nEV;A%nUuS5OVb-tba#O+@Gz?_+|l@; zivPZCOSIVoAj~tnVKp(W}flFHrVx`ADv^A-1eDpz$Ioq!ILx25yODyj zW5u3;7s)A>!)b%Ekp?f-$H?w!y<5H1c^TSItlYS zlb&cJnUUy$)oCC$d_XFjF9ibzKMYe@e0E&F-2-4$^!zU1LZ^Hwa&rAQ5qCa!V>T|k zh{#opvhMP#j1`kcgoWL=-sP&87sh2GhEP{;!JK%2yb|2D^?dtY^V|8no@guP7aPn+ z!Lx7U7BEzK6@`j<8rXNCE>ty64Ed}Z3Ti30=1|FXlYE3YOYeKbU`{xL;V4lH#PBHA zV=||J$=Xot)VYV~lfe0)fg8Fit>w|wNo?|TmZj?;ad}R)FCAn#&Ox+PJ3TqS+667T z!pSvF(nW;|lwnf}u4w2G4Ew3f#8k#Wls-`4eXfXq*m_1%Yn%Hqc3|mxWux1samrzc z8p`!yP3Cj;$a$qsT1t+Zic0%Nsawd))qa6oSlw+A&GlT_C7`Ivc`c!j=JCG0uBqG| zzM*%}l4ZoDB#GU(!^w~CtTEBc45U;*Rt5oe#2UcJZm#`{-KnBJAgBg0)Ar(($aE#l z*zgETA@TiPA~)C_l=t1Q`K|2wQ6y)6G>sPSz=kJaNzZ*|iR^>3t(2md1rs#e_>-Sk zaPc}@38{VEC-1`*{hd@wHl3F~!HcF0Qj@7zJcm7kg{v2RfzEjK?9p;X^z)8}@Zk{T z$0+JX!HJ%-J;(ka+8TS?vk||zohZ`G5inkg!*gQScz<4tF{QXJe|p+&*dv*O+-R!bQl#X;#eEWaxx&KWp_)Ow@(pSG%FMATAcYFUB0E9WlVc+3U zGug^6r@Qb}xdGT;jeKlJS5T96_!T}bXM8aXJfuuzm=VDTQZywa^Oz?{fWQl*4aToA zN0k#KssBDMG#Ji6NLnU7rT{a&vu>2tQbqftcq{Kxm~#ONr6Sg)_+z;sNi3x)HS4m$ zolo?*kaIoG=|b^9Y1thEjOZw6naizA3Uw@>{0~e#j)50C3^E$+-0fG_yawp0S6Sbf z=ik)(iTaTYpE8-5b!ah~h2T!NTa)o*G)(d}oiWAJ^AmnMC>M>t1ORDlaHHSxuB_SW zYU2F!$9SHfiC_-nOWRKyyjrF~EriV$*5C8D+5S!0u@vN2f6H7D0y0>jAMua1SpYm` z?&_6PX_7l$nLI0N19vU2duG=yB8c21%PMc>{;P#Du6%UOT^c zvW>3^@zUXVp4?WB?=yYQ zh1#YAVJDQujHcsI-}70wNZQ31f%gf6{%%!|h%*`=esg6|iNO{gWJ{&kJ4pNWFXEfy zsoi1I4ZVDh2lT0UVr-@x)0^vv_fh1Z9Nd-HTNdfTBIS(^pqu?Qy{kq79(dQ8Ns}*>VL{8Vk@+qI|9@57HQUkjG-m7Z${Cev_ z&XjwCKupHdmf?9h zPdvnSIM&psFL=_V9DuD&V{=R?yB3H&C^NmrBpD`SDP3RZR+3RIoiiM|2i+L$ysk06 z*ci@fM6pNc^u@719DhW}dMcu~I)RS~r&LI<h3$;I{xV=XgNovAd z`492JEz2XeDQctb)wFpGV=4~eUhOqC!Ebta=Gjl*|m#q-U{6;pyoS zh3kfpQaq#TDWkd2(oaJUS1loA-pFr&m$hECKzQSCTZ|5BNY6ui>Cn&i(xBYoN8Cm2 zkPPW8T*Xf_{0Kdhj&H@EsFavwhEzg~T7SV=#c*@2LZ$b6acx8;Ne3j(W_hzp0E;_Q zCn_Eop6c)kK6$c8&(TG542r6%CG(lv>_!*sZ_R-kFGk;50vYx^M@Rq$c)#G>+#Da^ zxYQ#c{-2E9H;7?V7B7Q$er8IC4OJcq*}eyFAKubjxZr&*dofr+K&+VDo{<9ayp`*` zv}n+n(JB^FtxPE$!Qa_B!mvW15z0J46iQc)IJ_0shPxk1aN;ABH1yt%9cZjAy>J$ z4`nyASRn^qh;d$uuidyjrEbDFov?`e-WPyL=ORd|cutiqF^?(=yMPVI-KE2v%le!C zKA`$b81hMIxTfK%Q?wPs*ePOB!G51KhvT+T9|T3r`pAZ_!J zZO)iX)^2S&WqD@s$uuIvfnpeRl817({_90!RB1!2Sx&xwncTGIGzlg@Wz&mZ_()^p zOvW>v+MN>O#=Qh`CRDgKWRLYG-+fSudbCF_kN#xDp6j$z14ev>&(p1hZ^`e|93s z!s=gn9QE;Iu7Z^P_2Set`d3)_rJxFa}l^;;iuP*pRMP*72o0BxteW?aNJ4kK7kbXxK!`%hcR)P`xg zVk-IZpz%!he@uLdp z;)K`lN#l1BF^KF?@eJPjjY;dmCkBX9=VyBvaD3|yI-nNhj&-OZrKW%EVdN z)*@6T=<)J!L-XaUtVo@<3k<;@{0SMD`*a)#3=m5BJt?iRm}ku0@vy$~~P6Jyf*6ndl{DE_ozB!sLX=>V|@uvrg31@z$62kePvq2;m z)#P`0MmoCYK|7YvbkBR&Rv7V}Q|9!q7FG~a%@U*UNUYhCVR#-L9i4_oYCTOv-lWEw zq{ylA^$`s&0y^95A|kE{lVF!Y+&AmEt$UW?3k&}O6C6hV1*}CDq!MW1R}4S}Ctp;m zts`M-TDTJ9`fV4+>Xz87Yij#s%FX!Wx%tikM*W1~#1ibc=PyCMVlo$7Bgn>C{;pEH zSe`Y?JKUkCTcwOhHcEYiSeiH{7HaiW5U=*Vu zDFPw(pEyEPQe!6e3+Gi|A4;H9sOi*~*}K3oN$=h4g3&yWKhTx9Qf^gJhu!9PBqRec9jcUVlM@u&N@d`N5y^g#@E0 zKjn+V2evIZ2t%z{dgHX`mO6R|w!nn)b&P!}2Q-ryWc5by5}wBFQJI@JTT}DD&6Y(` z7Y#v*sKWD2@cyhkw6l@~7SPdJeidz;BY!MT=&UN~`+7?`U4yH?{~s3sq=++z%5Zu# zJ4If)Zm_h37Kbmj;{z!rOadjH@f^e6nA9#!DK<91Q{Qd|$7+7E@sWtaR35^%(%P?& z-)3jjk{ra_ZvsY8TiSw#kf!2vT3c!~~8 z%g4k%wW``yfjWn(Oly05oE5LNIL&3hF)(>6sC~3X84(Ab`5WFRA63ed6@J-0r*ZPN z#qF)gn>Ibnd4?(uS%Kr^EyT*-D!ssj{TIenHeAX7gnZJNwZDfCt?l7+I^nKF)*Xsph^Z<$WW1KnGPTp_pUTcRsUd&@dd31XVc?R?A348x z6vrH55-z9_nY5xh&RI};OG`=(EG*cc8BNk@=-w9@{)V;!(o&LqKH+HBd&(m6VhM&`Dp*iA(xx9cpa-bS@se zdz0=DeAx4TgYuJ2s~sPtL#@I9L!4J3|3v+P>jy>lG27Ef4y`RDTbT_bCq;dq8&KdY znI>Cgk<~%-_~a%=k4O)@8Yim(8lVba;;KT2VyI0_?+F`#t1dFkE5NR4XZ#;~0TGd& z)GJMm>&ydkOqo3Tq=IYgq%J~6wl3gP7?{bSQDG^nux(ux=}2cSXrj4-wx3JYvKVDS zUc6Aeo9vVsnh!~l7ME}(_3Vk%qV-zyzrO48Zn@MDk%*tRny975mQN&{_$c_`a(uSa zYUxVKrzrM2jZ7!X=E4h=$|uRf%firb^hGvNhPwCSQSnm=yUWX3MZ_iqq2Gj14YX*a z#SN*rySIV{5LMq15J*L-dF}z(xFoWjC~qpWYk_(0k+D!}#@_odYSdz!9gq9hfdjRriF>N~Ox4e4Mp8<{clM5tffMuq)H2#Ohkb7Pqsm6`3tY zgE2P$m!U1APfa8&lIpIr0*Z=g<{|nyZkqb~q$>?J8TmNj;nz2(g%G<99p>%Ct>7a0 zxlc{!&?tjrTq#hX9}luvT`;E#r`s`JeoD?OZs+YGg1;X#6Ivc}KSEES`VJPyGc^x{4Clo3Ws8XZS)$+)<)?8d0h`ygMfWcc?cLq9oZfWIo+ zF*MnU5o#G0FTLs{3ZG~k@lfs3Hihp< zPNRMf+int?8?BhA`8!`|MNbE$3YP#LH{2t8t3^F88@66g8lP5hs7hw-IU)!|`H|Z( zxE&q`E)W`A2Iekn56Qp$hDQ5Xtr|jDn;bP2%UZ5TRK7dp+oE-8!Vk%!A6_!47cFx3 zu`4-(^ATShB(^>)Q$1z5LB^-UXeaqm^#_6UUH`ihf1+}ETG4vHf#^4UkNxaqa8-p} z^+Sm~2N*N_my7Gq9|Hicr9o9D4slYs2|I5TSy~9)tS4{IF&h1@x?jsB%AuwwebFA9 z;=MAi3OMFWST7(eyJ&shtwc%MboOql-b{^B`=u52u1xsHgB*-%tn>V4Bs!nK*)6lr zn}coZ^LLo$Yi2y*AK|@5)t|z0TU<}m3+Mg^{_@Bdzi(4^?&Yz_4cT3G^nDo4$CnN* z%YbYRRxdOeEOEDb?yx-OSxxsiOee3=aIqzJDWWKsvcGq5?y()Q?nB?!_eN^J_nj_f zH>+G$1)Zjq9y%{q-YU-ETLwALXM0(}$zqSdjljt|Y93gCegwYI7sEtwd@KABLS*pB zPD*3;%E`#p>Krt_S}oUS!ooJVc^m}wakT~S)U6}G=r7m(-RS`2QFHM(2Ae5hSWp6i z6t}mNP+G=;YN)V~WJh)m;`22YoeVhSL_nas{LhLKKEKv=f2wt#)I0OY(P#a+$n8-@ zqb}ukPaJjvYZSqMNnz?aM^@e{+r5eZ@KFKHNP{LC6sa_diA5_uXja2F`-aiewe>US z1Dk1mc>tD~b@DbJ+lz;b_WmANRUt%ZPT<_Q&bdQeWyT{lwWQ5z>R6sjw7$%30DUHM zjGyUYQEV^2naSHJXUrbIqBfzk*(G(Wil{(-etn_L-WFW_mvuCD9R`9rb-9eS*!7zn z-1LVP>&{hLX2U^p?r;b*l6WFRnruMy2x> z@MVowbMm0m+fEISLb_yALsjPedjsa9DasP?aPF%JI|sYcilU64pWrv9A6SZ$99c&O z9G;TJ?ci(_f+`^*#mi3u!dCD%ur8?xsPgwQ`E>6+LvlWZZyVg?mzXE;tcSVK1sIwf z3i^KJFJSvAnP&;+y_+rP;#Sri3k(hUsH>(Rgo<^sFonn4i>L{3-S%fnZjRZ}IWNk# zC#sC?5e^NO+jMJn33%qflZQ1cBgt}vSN=^3q6??>Kjv5*B4|qYT$_npD*ND z-MmpMb%Y0+)F)@w22ZQA{E74Qauz9>d}x)v9@jx2vB3PUl!re=(w>Kd00ciH+Q`@l z!%;zJQs@G~C=QvS5L#>Z;cZ;^JdTQS*b&VnmC!f4>v)D2^fO}4dFhCSt}3ripTlF` zm*CZd*)-?X--4{Wggl{_E}4J%`s-6(6rDK_yjeHjS^Ipy5o^Dc#Z|4G^Cw>6 zIr-f0Zvx%MVpkg%Ct1h*|3d#_tis~$C`&hO+hVOrA3CQWBE#etJup7dR)xcPClow- z#|EaS(%Hv;G1#A+b!ih(bBj~~xjRLCCy#gP$uTUWMzeo};ybyD?)|H+vPmSkXIK0* zj;~*w1LFimPeh|I*}~OIv6MyNj)O{)=-YqAQp+TFVtL7pe^l&Kym)#kNY)Rw)HLx# zt#e|g`p~!^Ry4;x|0BeR&LUl02$covWA*;;&sx3q-uSu;Qf3Jz^(PiT(w`EEhxWpX zHR#eq^DI*%B96RE=z;&Qq9dYzaGF26h9yeoC5a6yjdhu9Ufwa*a;SS8+AE$osj$i3gWI3$!mF>ROMnA^t7KnLNU@LBHH< z=gpPo`3l9XQvxv4T3HE^#bC>*RrLnquU>3?G6?+**0ELgc83g_(!f)jO)wX%EYDq? zs@Y;MVn#_@KE%Q!XzDUh)nNG4$B-Ryto4|5tDYaI!o5o`iGfDe&6!sb;2ra4*%~rt zy|gkn*EgQUyKfIFZtUtR1^tq?=kXx`QEwwDnx2(n6vxic2*I0S=lR~~=WN=o``~Om zjSD)g*fd_|gUm0lvqilB#BPk{tl5(*wBHl9NxXX)eYAFez8pXb>)F+MrDA-i|4Ojo zzLV8@{O@iVlr6pSHu!Es$*c?BK!GfEMi#Pt37>tD6#nN*rS4OG$G+-w*!_A>wil^{ zSz>TEXj|i%j0|S}MLyN(?*}yls0?@)>z;i9YtD$gxGyM!@HwG|EUZ5PV_$YT%8c>6 zUjRQQH936auL?*>%x4ZJktbxM*iV5BV^BM?(P;Mk4i-bF4!?{?a&SedaQW3lJx|z` zMFvnzb8v8Y*j1@v!!s;2sDo6e!`aipe`b6NqOhTgY>o81n5;Irqr~v?%{De0$SP4l zMw+-%l$K$dbQ-rclb2fy&n96tbYP z1V82L>a5cZLE18yIm<7{aK5#L7x(fZVBEPXEyhtZC$;6523H87TL#Gb+vy^BwluUP zWNr|^n?NP$nc*jHO`s!{DgBm4~_WL9uzOWosY1k~19919A_yQS}Gxs8r&8Ppr)3kUW+aJ0DEp z(SNBYBrU9jgIv%~XV3g)2&)?mC91AwbqgQ%{_`Tf1)}8AQ@}9l&kv6-2 zX`j9FesdBO^BLj(=)FVxybvJ0{#;DDyM4?|z4n0ay|t3{(fj8A;p{ELqU_qRQ569x zL6DFXQ9zUifuWS{9=ZgiQy4k~DM^*?uA#d_5Ky|CK|mO~hR(fsp7(wC-ao(Z2jC$b z$E8|n3;OR&l&7bwpqL)|Q5qox|S5FM;3L^}x zE%SCJaHemvF220+O7?NRco1o8mzTBarjUF@a(%hex|9MS5)=j6q*6j%Z_oE zrtE+DvWZ0WqX*Ll!rhKaSVFCl0mL{3WJPWH97?tgSVwW&CRg2Ttge`_Mwjw3BigQD zstRq*Qx)=SY+=)`=TUtGwM)2p%RiSpwzd}}p)g`rYS(YpOtLD{BMoKadZKJ(*iq^Y8UJ>k}&pEfPn-JpC z04ZR?5#`4LK!faqHltQRI`L23c*YPviv*KOEjc-m%mekjup-|N+WBN;pP97iWX0u! z;c%wM=m2^FDRk9cb*6ythf(qv?08WoOww;+I@{hV6aQjVGkK*&rW?U-G~9dx9WnWB zT9F^(7bB(mh~tSG{s`=k@Y(v8w9LnI?uDJ;YPf%lV`Uyh8TVc31lDIqB@`bwcg8+VHqd1|Fo5-0jgzwGmB#L@$Z8k=Jocy&t>u3)N9XF> zWI4sbQ5i?)SY~{^K-5naWIb~hMCt8)B4ezGN2@inwm>dxuMG`{zguDll4#T=D^Bz5a--!o=?{coI!e%qp}-@v{j#-Q=FNdGb9rnC&IlaG`0H(h7K*H4j2qLio8gKXD_R;n$n|K|Aws#%9jjLnsk z7vf*?83mav)lx2dI1P_1$=-J*OK!isaSIO)As-)tn4P4RNQiYDa2^xx*ncDH!nRVN`uX;GbNButozYG-e)K z13I6O9r)fb(fPrd*aZ>L(5zgoWDHqSuerCk<6_*kd}`pGu;p=ezqKVMBm~<@FR!A4 zP;YV=23m{fuHc1*SQwwd;bdZB+Or@JOjw*MH#Vun2((xng#p7JBeOWl1%B%7^IuXi zlp*ZzGstUWf+(NPj-$kCSnr=~y z#8tZG!Kq56D~Otz(!=gQ`S_!3`!Br0a2ePu=`-L=Ox!dHq+AiE=iqE7SG%&G2m2;K zf9I-#>B$Yo9#hp;q@d67G^8oo#D5$4dH2U$O=I45yp=K@^vQ+CPfHfNqYp0?Bwn;~ z;#8?2HpbQi3xM;cFA}1PRK2S+uF~DvtZ^W+psG64s_UrOUGj>9e(OyKz3G%wp|Wq& zQ|?ERSrS?1DJl0Si|HyI=p>$tJ^Z7pQvrA{+Y${m$miqgKeam$PE_ae1$=?-1K+f zCekpoP+z|h{tKi7qhKY406+4Rg?}(7?}Bw|ul1Mo!@mQt@3y1XoHCSIoB{#@>#)ky z($UmX&U%t4Z8L^0iiKe3Nxe4n0BzdJKLSE}wX#Zg6O--^uBnbc#3UXsQGk+@4|8C2 zjjWs^uBZ`~ro(=BBj{D1<8S4$ei;1B&5SdT1oa!x5bOIHb6dT&zh8|)Yvc0nSdWa~ z@8{ew7#IVV&WJ5EFG-GGn41`FvBZC(J0dS1&!F&?`U$P~C9k??eAYUy1vIDTR%93} zM5N)_ueUJbf|ys+q@fN?tu(PL0XQsVCqmrMoUP{jy26(c22tgSbV}Jdc_aMpKC|8G z!!_qanGI$JIF+4!7u50Un>u;@Th_HWsrlzl9HV%uc|@rsaElT%i@(@HEg`R5Yig6NS0APZ(``aSuA``uz1CyBhr3 zu&J~20e`F{)rkdUrz(d*yTZ&m=Ojrkx9}o3Ro%~Tk5mDF@x3t}yJnb#qY{vLC`Ap4 z;uY>v+B zc#Q%JU5wIWPV@FLgV+ZZ*2*bVsYdLlBZ_BvrCw1%Mum0GD+J|Lol=%PnE$Nl=Lbz#fq5aH8iPsURTbJ z_b0{>U*ne_cuLR%p(Qt<%Xd5%f+H`qi^$j zZa@w%zs|m@=dpcr;uc$-n)I9~v*zlwF{1{x)muJUcTXCv3ob zj2f-UDedDIJlaBBCDrTu5s36z<%xgNj@TR9p9b!E!r|J`XV3$o8teF&)a=C0TXt7G zPU-C2=i|)@K5AgF)btBHo$K}I$%h|be|s9N09!FnBF{0UMaJLsXIwv8swVl-Ud~x? zH-fTYc}pCs*-=`tIT^Xv_`J!6#O}ZKW>@)I>=BAL5guC{fnTGbZxk4kU*ZxskIOEj zM~p%SUy?rz`3+K#{Y%u~=)!{VI?U{xSFy^c{H?jb@|9fND|_Z+&OcXfFL9NcCtXT- zQqt%^n4uQ1wp@Q9Hdts_omgy9jd6T{;p5ypJB_2-AM86*@Lu9s+e3_v^C$V643jHK zvAP71l;f7-`NH6p2p;Vt%Nbg(O3o7}Nb=jcS{QRec-HpL5wng`mNJhR`h}Y+S*A!y z@ouiX?a_wowik}*m~FE!D|bs)c5KU!3n8K2lb>6R6BQcmAhaUL`wUXWloB;2aY;!` zAi7C(2b56eyf3y-JsB=a*mUsNZaX{-ws_lY$tR?$4y3~ZM};EE3W zH?GkGih2r9YvY^;AVM|XuXcr5{r6*c%TNmggZyw6A7&TZb6S_C59}1Ax}BIp-gI#q zLO$Q^lKw43E}6u?Zi<(wV^?Og2<+gr%+j_j%aF(-`}WH}COlv^mpoBwk8yS8czYJ< zj-~nrF&OS~Ht!PW&DNPZS}2jVhA*^sz4P+Yi(BhMEviyj9|kwhw4cBYLLvStS?3mx z;Iv?F_vR86kuR24Dvl!}97+T^2kNWx1E09zE=*9cC(-m;?Qd2sZd=TA7H^F42zlVO zHXdSOY$WsC@qAR+dEJv50E|gR=zQd|-XNADmFZN=)jt*6;fZ2Log>I#fSL!tyUwh6 z&PG?bo3F)t4})FUk>plQ)9=QXF90h{ca=5RT>(j&6ym7gjWqKOH+Q)Zk1+XGY_p!8 z9>=cQ1KOV!?=0->YHb1WrCz@~`5)P{?=NIQBeky6u=uUmu)y(@agknQtZ{e5@XU-1 z6iOVDS?02A0aGUXr|UZl za>kxS=hSG$JXLwXuIHlo;%)ylu!jB_q3i?J+H{0Z923aHN$_-!YTlg4KS3-wAU566 zruMz@BS=@_!{++@hGetw$*?dCAIs8t7R}JuR+UQoYjaaoNa_5x7)pgowLqaCUsSSGX#^ zP4)S2^aF11)GMh#1i7aNW*BInL@+|{;fS}=4`oF{a69!i>lvJX*^pb_5O6w z!diL#?B?%e8haEX=nZOmx4Eas#VbT{{usm3Y|#{pcHlJvTMZ<7k=bC-1Fb(}PvHW`&Rts2PcR_R6vCf4KnZBnx&2a5c$t z=T)n$oP@J5a^`~#LULxW(Bf1dFKG@Bg6S3|QizpQ8e*0``7h06?F4|s3X7<||A z$eSG@?NZNz(88D1aQ|}}IDbDe@YTj<;7WLp_dWCf0$bt=7qcWI2IY%e8Mp+be~)aj9>gM z+PCjId;c>P;|xlQL0tw4HwLcMx53-};{yNqZ3;3MGQMQR$xgQ#<~R1mcF?I^^;cRb zcGh5|n#V=_S%c*d#{#n5WVKIYD7`fs8*}`HG>vfVER>R6cL#TRn<}Ir=5}*v#8Q8%nh^-y@oqv*atCuHCzgs6@{eIxT z+zX>>vAJFbY)XdKtFuMZm)l->V90$z#8zOCvOC1=F|`geNkaIO+MH5llfYtB9Z8Kz zs@!|1rRgZW>jn&xT2Y$@r-k?NgUHGu_xqjOgZQ5X1{1m!V$-(DjAKFj{c76u6?Fc9 zW!Zk+5Tp)E$G1tUF1-@IqSYWW|!an`+>^cF@543v!zGc z3Q}9ph&`@d%6bqcRw_25ltg1s;`o?tv7#hpWBtbI>yH3b{2j;O!!&QZ7UH9L^*9EtCR=^>kUy;ytWSkpd3v1tAG zfLIx6xu&(u#n{Be$4+96zLAjsJj~MHgrcKTp4T9XSI!!iMw|T74z2uv=dP2)-#BJj z!=|&9kg6UEJ)SkI7Aw=HerJa=_7AU6&sG?ln0#P2V5Mj6V{pAU_P)C42X3kO_I}3U zOicL?*yfg7Zql3gV$W_*lMX6(W;RbfJP}8fbIxK=4D{_JbM_sTZr$rr&rA&?fd2Ck z1T}7?=`CQ=OVhTET?d!E-007WE#Z5Z7#OFKH>dar;HeuXt6$?lp;|4Td~o={`1b&U zr7+NAn@btE1D-Heoen%ypFvlMEQnu>s5vxr-%QF9d@w9Z1|of>3T}~oGyKvUc*ZP~ z$KeBBYA3>+W{yvL-#1OP22`qosPEG(ViHTPnbzuks3E9Mg1pm~ID3MhT!{RAR#8j= zfQv2jsI)DW@v2XlO?do$S!1^;6&Q8MG9lx63WZD4*ow`y?2WXW1LEkw!~;qu2)eOU z@CS8gsM zE(jRUSC_rd>^@i&l=r7En(B(8tA4PF7ETlotozA1l#hU(`TJc7s^*AIF{)Hd5tfi1b6 z{Y5|wss)7D0YHEf3gvU%d%EtFi0}CaEsA>Wl5>$>$ntWZk zKejsOK&f|CTF_PK*;a9=Cf9!7#rK~Ed~Kx8KkJurakLhmL8}0%L&L>|r?|NIj==d^ z)|`C@-m?BA8#Cg#(||xW`-}Is`lS$T#LJ(+s0IduIrMW+f-#%FX#lAbl!u@idfaB4 z`ZdCZaMZSpy>`yGXbGjAKdcKYsML zf2B{)R^k~MdJOzw_2l(U!Qzd^7)z zKK0<5{r!#a`)~KZ@8rbh+S9{hoVv_PXrUx0p*&=+Hx``j!0l2)gI_cY*3k4(< zu?~2Xr?;>h1y=;k(T401YbP41JUdWDK7QvgZ@t%HC^hT`2xRL|e`7z}K_pa4`O~kz zn+|A#=naj&?QIpmR_3F5-oo%_1O~`^@~6Cn9`#n7Brr-bb5q9bsRfTl_-BjsDKc>X zQ~Cw+oU9Go6FPP);49^jY}z{33DR%hvxI2X=0C3uI*}2-9+EO+e&cg7>=0>1&EI~K zDlG~{yIDp^-ZUz4Y8od$@NqVt9OXfa!C=R5+>EE|_79IE$iXX{?JlL@YaXE^a}4>rUqTb=4By zcYjtyO}3uw$I;X!<5wpN94+h39pTQ^EPg~FPAGkbzdgqj*t=qI8(R1!Y$p)Mvl)eu z2lrma;hGuC`Dp#-{0wy;7LGsfxj4rn_kdOb4NO%&(Pe%Ak=^2k9+*YBq!U=lZ@=dD z?Wh1}q5xQDd#e#LevK@34%X11)7ULoGopIzKOyAQOCF6-pfCP~KBj*m|3iW|j3nGh z?3tmKc|Ftnyn9nuLWCKOIh`qXn{0H>UyD~~n3G` zbO-sBV_$_7xuK@gxMs&V?4|cGKC;yMPhubwiBv``fe|&|oA|#dowTKc7@V`vB-T3z zg^CnbevVBdw}DFVsG`d^zV9NB6Ilm|7}%Ix0zTFv{tQGVv*f)ftJ$57nxL-xI+{6o z*e9^Pxh)IeHTW?#fs<-|d!}JAuduxT(vg)mOTe3{cIwaoy%je51|WR*Yis}$&Sv(P z^_p|YN{r$f8gZAD*bdly>&%`2)F|-JGsMhKki!sH z9#TV>Pr6JoO(^>EVTKbPQYn>NVd4u<$G6KvC(DMcn!jX!$VJL$}55D24 zUqOiK1z%PgqK;@K2gj{dYDw25?Xa&+G%^AAz?h*}pDN0}w5P+lwWW1lGG@ z1V-0P@m11Rxx%F@XHIAn0Ng6Be~2}(%dxv#McwRhu;754k3XrO>Vty9ZRhdpG)$T* z;ZMNRlYM)zdVxR&=A6eeuj$lG`OfFc$1k#3azP-h+#2Ww5?QtZ*`lGA=E~uRUTJ6_ z@U)S5cNhgz%mq`=R?iycfAN`uR1XAq5`7gIAXGq2Jt-xUS~y7qe{)~Ri8DQ2JPSaZ zbmIsG5Ck8BeEb3cbLPYO6p8L;^YGMODu5TIl4c4iHO}BE>u_GpQO~Xi<|kCU7!@@| z|M8+pbLubDC|%W7EHuMX?DSmn|1K{tUr7=cK^o%Dnzm)u)mWnfz_H(hnFM)X`4W6L z@Z|CcQ~di>HtG_6vj?q7@fz?k}89@78@BH!2VU z@HfY7J!;G@GU@AAdC-=S0GJeRKTKcV-85OW+$V5$qPAM(>&DUOCyuLs7q_kOR9G{m zUuhgm_QyljyM+676uB4^#T|f%uT)wl!ySX8fm5hfNgbx~ZHUfF>B%%y_^#_G}YVq#&8*I3rttU#}%ID&# zwN-7Ejg`HY8*Q(8&7pO{ImPU$YT@XIt(LE;-+grLU9&4FV|F8QU8dYA)9tpE@LnY( zvbLm1WYp;XW420qjIZ)fel}+jsG+ABv6?qwVXYc|w?*^hzDs_E-R+5O_>JRr+jAkK zMH{gqI5tyOtvF~-N)m2ZwQjjt>lLV5CZ?X-4^c}4p*;a=NVhuo@mW)h&C=iRX}Slu4wlbX=`QG5iBP0Sx|9r z!v-@sxchD+2S=qtmQK#b{j|2Q4mF0o*BZef13j%7*jiEGtat)2I)RUsI9DE&;hrz;H`TQ4z&;KV*#$Sy?{iEt9M{p_Vi*la zfmoty;FK2p#1czE{*}9@f^>VGkx!7By!!fW3X2B@+&A--7ZSg8v@ESM{pIG@fd#gt z@oy}%bSCcbxkr4zIwEl^&RUSC{cvoKQvAJ8Q4%~Pi`iAZP?ZUKp_6OP$`?O0r(Z_*#qfLap+pg{v!x+t*tDyUpvqHC*B=q6qoBJ}d$CXz zFOd70#SfW1b8NnU`%a>3wN-td`y`bwjZ|P1DM)EshW=?cJUah5We97sgfcvE6dE*5 z*VbHL!$TeTjWg?fylXLbB{Yplb(wExg08&{cOC#iiWxT?K=#wo3C^+xW~rNE#Q7k{ zP?t54bKM|g6+>rpybCj3?rO4pZ}&B2x~|;(D{z?*-)5rBnpGy{6asF?UC>rUja!<#XK)@T&Mb+*@s)B;4yzi6M{Gf(!o z3h>le7`)k{{3DzyoxTB?)F1x2Fjo=1LasF37FaDgbr$;0`?~0N|0K&|bE`)R4PVfM zvHesXlD(gb5vXQK!m6T@#gLq1dT8&#f+D3+X@*1pIC5_VOdTs*>M_0cJkh_d-{qYp z<=I=b^17T~-k-Zm9IH3c-fiHT(CV{7U~{qTc@-YcHLfUh0uTU&7j{A}k9M1{b+0c@ zf^yCQR(qSHDwE7yoAr{Hkt79Zla)ahH^gEJ&t|)7?twwosbO!&DTaQSyMl%{+wlTN z!Jvuhb#+MyGz!5q-j{2DmVW3|_db)P*-U%$l?ylgB>u(jWD`cUR`#egL0(hTw!2h3ksU#5YwJgRZL(>BBDzqi3zxRsNNlKZ7{) zX@!Z!;ewUFap@8xEt_4xT9|Sqllg8~rYtV(tmfX38e9B*cD;Z{OPCwkVEDs3_J>k? zX66WwLZ;0l8kwm5ivk=eSMcH7Fc%jv6&1Vf{}3w%^s(SGYY1^sXEb>c$;=~d^e}^* z4Q?G`xB?W;nKrtpmH=7Qt7sP7y)f$by=0rfdIli;@1`LQ-80b=+haY1*&?2;_KtIoXDMGz>XC*Zu|I_RM=~g--;S2U2a_};WLjUOK zXn1`5MMgAZBiKX8;E$4$lBQinh5$R=+gO8?-(@E`hZu`C*AjuAU%TMVFFV*8IM6~) z!mOux;JxqqJtmyk^CF69kd3i+S#kF6hSp-}={j?Dv{`gBXj61=y1QZLbD^V<%*&p0 zwYjTPf`Dx= zfc=L_{RFsDYHj+n3bMlKc5C+ev)jBKB=UCvocGlr2cj>PFmF$#-fPU+ViOgRFEOPb zb#kdL>%SE!sl>mV;A~~YNS(O~-Hav3gcL`mbc-%jd}t@A*0K9_;SQd}jkz=+9@|b< zA4^V_4uFlQg{CCm^8!WBXvO}cXSq+SE?*;RJxetHxzYcA>-oX&G0yK&9c?(C@Oh(8 zT`$V@38Q|-MwLmkPNb%f#rFNT2CkKA$lrFyeZhgHfQaNxs zzZ0(9yzLRbX9|v1OR<%iXGs&v9T@z!u>wYz_H#upB5pg-$e-O;zC|buXJ!amRx8ns8%v}jC zT5^0km$wL(Ir4rULPo6(4+{4A!tqCwn%!6JA{$%U!WZ8)?t(zUgvZ3p(*wXeJZve& zdt-ujYMp)aws|9y6sh;fzDY?}n!e|fvbj28&_wl=Wd3O65o4Cjso-sn<`^8ql7GR* zoC4bE`h0Ey5`RXV+vAG5{U2cG<8f5+)Vgt08IlsTOa2s%Y`Ox;lXm6o$H|L|+e zu48=vM3q@+Y!>-AmU7C|Nh~Wfj@_!q3Gx=;JY+3+h=7(qX4ZI?9CFYZcDBVmS-0SF zK{8a#Q#VMQ7hWnVqDGssz7=)b@?(eSe=GQ8Bw=aS2(|gq1wdo}MV=2F{9c=-0s{eY zWNwCtAcr48O3gpOT}&;@*>35cF6!`;CRP32SY~6>>;@#`gR4Vkosa=}*v!O+POIOO z)CrEcjp2j=@oMeYMX_x5f|f|ZO6pYd#s2)16GQ*-ri6UM1)qXr=X;wIkKjemK{Qb7 zC6Ly9ZdvwP>9KQ>mZ+pTu>g#qEDay9muw@qokZ1;^)F~Q5<0Qu8L*F@bAeb}S;bd7 z{i?ug&S94|#P(umzIG2&BhB%<#&Zyse6GC*n=H}0?PS?D(9!87*3f1Dj~PV&rvjiL zPJ|9O)W}ib;)GR@v~uDNhoBb_K@}hw>9u~)aD=LpkYzyyMTI8wMAZqVk~_lBZgZIv zBJr|`)1aAC`A5lf`RZE0!UCu+nna;$x7GS)@yE@Ljc4wR?=~8R{a(ejtCm)pc1Jk8 zQbzli9b4(BdNzIE$!2a7oQqFDLwSYG2|QC}75RVORD7$%E45u#@?2;Cfh@WcSUE{6h&-d! zVzdWB#z3tg3!0ny6r63?%p|1PTXkD{%=|HEjclfJ<5ZMgoZU!rkTob=VGpzSPS>(M z2J=dGJfRF+&I1MiOV9up=uZP|=PJ(9j)q9CRKFR*DllK~$UvT6Yg3*^r@@l3JX$+^ z-n=_JGcOPLl-yt9=8@<8Ixo@&4nCPmzTzynMR{ku+ zJV|n-NvOZ09V(&K>|V{^Q2|y9sH7S@>?z$txT$ERc&Nr0(xJrlJX^yyF9qJnR)@}6 zg){XQZf=|h_nCN+$)S8Fb3A3{!yF{c+7fJ<@7OeH7Yig+Rf%fnKH^LQLON*O+gTZK z{0jy<8X^Z$ZU@QZK72T^D5K~Dl4UL)9z_cpab?%V08aX{pPFy9;7o~?DfK0^+! zkx452JUhT|SUc^)NF*IU_+{64S93zMzu}d}fzb*39R*wlw}qKd<;Nes(`h%&ojo&f z<5F05J9<5y*OI%~BI@a(k^HR_uW2*+&tXqMKX2>#N!;1-E9|%w1L+l$UJ{XD3npA8 z25eEhQKOCp;T{+7E5h2=BLObxw_Aga{I}WPRH6L!Wo*D8m-1aso;c;`G(d;)RIJSc z5zNs~+S`{j>wefJ-7z-(K&9IJ@xny$ao;E&1)!)D#gg>RU8=G&JUHChydNNA$FTaM zpKSNEgd!INH3xp(Mq`L!?2&bhf@3)~oTK`Kp!}{2YKKBaoIxyO(Xm6}8&1Oo9tmE# zW3SzgsWRX3NqyO$l*Khy$ho7YIRe;XKv_|urXE$?jt`chb#TLh3RqX%rs;sDeE&W0 zMr2e+`Hb(4ihvf}%#etZS&ED1Q#*fHriS73Z{o#6Sd5=Outk?WP(Qb? zm_Uz99u$4W8Bd$?$wiT_*IpurDW79C?P=_9`}XIW>y$(PDIk1oT}-T31% zL|+2D8%mU$bIhquXR$u6dHYQsFnW-gDf`SVYVERXiV#cS!gX2tcj#` z0ND-#f#a4H>+MaOO{-OXQODI3_s?o{gbrq2?q@YZ5y0A#Exze1OR(~ype2&daz+?0 z?5qhcFEG>-z#5pnib+EIa&cRVg`!grnix&}c^a))b2a%Fls>!w**V}Ql+*AF=x?p^oBrq0*v-)8q{SvvY6c(@i0pqltsEOc&@JXna6 z{ffDX0(gPeTQIy}2j%zM<=2Jx>J}IkFysm&-|eo6=PL7%%Gt0WhpG)1C?`Wx<%)xQUEgZ`RV=4e4k zMPx|ZyKA%3AF#B+7lp@nR_thu4fw-;C%^rDz*%n@7}a*{a=LZH&AyXa>Goa=L!mjP z*2|+F8AFf2dRaFZ-xFEVyXeP-en`+*+cJpeWA%5p7{i#s#C|r02y`Z135-5;7Zpsq zTEzTII)MBpOSx54vVw?T@YBmrCuTmOkzs^$M|9@!!J!z=x8t zNq=h_3rR|Lx?hl}mYMn(t6!EX^XWLYLh)1LKDP11qbG{p0wdf6FV)8dUVQs7t9-fI zH0Ju=(nnP7lfANQn~2)Hj$fsx^kC%r<4kQ%;~xUHd@z_ROUu-yJ_oMnL(FP}bCo{b zu>r~i%;8$fPs}tb$Q~2N4eN`!1+x72dhRV$nSrrIyf3#sM@Q(p`d9@Y<$ZLW(X(gD z07M|%B4wg7Zg} z^3gH2>y^$;r%T$H>)~pprvLB<8XVFF-ny*RxCKaGD+_OmG!51Jjz^zINlXv0ZkxIU zdB^6uQdV?$eO4_zw<{`rr#42VEnbQ?1^r7l2=+~v&_2G$u2;gMieB)zm>m24JhQ#Q+C`97| zm{-eLck+!#v`|Ni_S5&#hxm3cMtPm{6ZG&PJAbprs3AQq#ssKM|A{`?@owG?ndKhT zNW$`nd7)t6W@F@@trdseMZ`xv zIoylj+BsjMWEmXVr?)XaTcx{PD0##3C5$F)T9WS9uolhUMvFuZbwW>5v*eU^zRP{vCo{$qWSq zXG4=`C@vniOrqUPu3_;qVrKifu(RVF0XM^#xkhIDAOCzUEl$kWyy#N^sK-*wkq1;b z+!STvbbT){FC+2u`E85OEvt5BriXvG>2?gP*F}q2s#{=m^yBNZL7!s};VAlC2la+C z$q|p)Y#>4t5m%^W~>fda6U$T;_*Dna>@6qd!TmK|Y{B*kpRSP%Q38z5GRe zX+R!8K&J!td$y#1`NGOz8R_E|ieskuZR3_K0d`!17VW|Nmf`H-;V#m*mbW@*Q?3M&PLMY!WgI!$F?@`B8;mcb>@nJ=ruTb5(yA+6Yw*(s&O zxf}YGBICHKyYKcFyxM__T{$PuB)4U4sJ*XYp;8)I$z++bBCB)>HK*pR(gVyBEf_4F z(VB%Zy=(m^R9mJj({HTY*tlbTywKQh1N^i9DuO6;)t`J@_FeBzJgRWQwnMqGS#hwM z9}n*WqsC@o|v5M_Rqt^!yB8NR8>{w^!H!@XhNVeYSzl9L-kW~ zGG)t2^DfNernnZ-^TaIq+f>hE^dR^hjQJbw+;Xo`A@AXIP>n|JAJ{lD_5{;>Vv?4Y zdxB=Ef+5_vBH&p#z{6VGzw{j!C8TGS)AEwgcjMbO99yBY$yRKF(*}2K@#zi3ROrxN zl>iUj#hq}zv(%z8&wkq#Z6VhE`q1~s6BH+3BXZ%wpWxmnD^|YGZqr0=?kJDBgVVzQ z9e(p{Mt|Y}=e|4RciQ8NJ!W$boTkc|RP-n&X2!D(11(SFv`sN{NnS}Yn@`KX>$SZ& z9vUI8nlt!-S>ZJkRKf8b2WPlRUpshb)tRtI*Ex&lnDOWBqzsxWAFa5xxQUrlNOuk*c!^FUl@H0WmWDs;X5?v z8UHr@CIeYOkZStjL%HYKM^3It|9nG?JRmM%24;5>rh;0SGzSxt66Q03>LTsxkmTg# zx)VK@dDxdyDQSAE3cnfGFr@x5%Hde7BxU&My=jp}S?iAR^+F4sz_|I_Cj1J%(bGQh zf=g55Pm-xOpW3Eh`U^kY+ke7Y&&?X1LmIL8B`(t8Ms;^@c+Ny<&MSF(av;Zigls@6 zP#%-w?27)gTfM5L`)|$EQyotH5}!!?igs&v!C)chdy@lHpJyieQPMKV3Y4nrM^zj< zCh0i{58iL!X}%~C2Yg>aI?kg}++l2Rs`Z$#T2(v=t*ZtvLJaMacUC z$0PG+#04a+R^O>w0%8-3eZlKIF0dS4L@hGDt}1+?my`3Hl!UM-|0&-HViKOaB_Iqv zDm14qmetYk*nXi~^{CoXUM|#N)1b0PRnQ_P-vZUzu`kK7j36!D;7XK4?frg|b{}%D zD*9;CqA>q0%H2UNA#zfH+T+^7N!DcZ+I)hqcHpSt&~pcJsL>|SI*hEgSrN?^aF!Jr ztmL^W7O^p(;@{{Py}b0~XRDS<0BqB32v(XGpJ0H6kW;IKJO<=K7;9|I~#Aw9x zjZ&JVMo0g=JVVw0@x$TWZ9*BbNK1PK;}T=4GW@u9LAxxjNtncMWK1sH+lVz4qKq3j z2v|2^WXhBOI8t}qv4Spn5{JrW6y zD$dBD-LcL{1xhfYqG+6^KhLt~q!0dl#(y|nb6X)`d5o?HYW(BLZcK~o!GH4SZ86h; zJ6YrGe^TH*nH~Qm|B3snJA4@u2Yz_R#&^Q7Mu%AH=JX}gYG|--z%?@$7ta@>0o_Jw zL4!dZ$PO)iTVWw!eF^VOW{t1b(9yzIU%t~hem-#UBA-7sq>;J01-n{byjWuxnWhr)=?1zIPpeA()66xl>-+db$+K#gk;* z{J3>NKq$m-XWy`HUN0gN>IIh!C?wgu6iYMP^jt-!*lVO8{wviP&&IsEfAt7Au{4DU zOPPZFcx0%obm4+ccLj;81lPQxveMYL7A{|mVv&d~Dk@?@R`K-r_ixSBJAOTudN8aZ zBQ74`F#RD8@5mcB0ZjY#vlz{N^x%FxzY9xg>oo+-eKlGi$)SWe1p}kq6;2V9$+$J& zNUAqEU1^37=o2E` z`!2_HCs^excR8!rd`Ui!Ik0?(Tu~XBzfaVDf5~em=T=UQ?T}5}6}hX~HPn88=J7}u z#C?6mI(-x4X6Be>Qjq9R*kE!;DQP4H)k?2O@LkYGV5YIxdU??6c|Mx9GkU;K5e6cF z?2QdemioVhxE)fbnT*-z`ILbPUKG*6MH!UhL;S|g_o0lIOcYS-`*G4!cq2tU0! zdf#!IS8^owkh-$(&iaFg{DbeRPuSs>(9k|H?m2y6fG?_=?Un0fiLElnn7D0USk^eu z+b+ui6CKj}Jp~V+K1 zgBKO8R$lXclSVVGJ(gA`r>34DCxAE+=0Trew&b$#Si)%=Ab+o{zl)^67!^)G#4tr zs#@9Abw4?zL%Qn}_(Dnr`mjy+#*L5P);G?l!pa4A$v+Ld2UlPsmhs<7C2|EMu}1Hy zJs7UUBBI|r=w&@|d-87}^V9tO9ThK#iq?-j?M6I7mv?ej2C_{PEyE`|y@%Xl@?WYB z$D8yW1;5FR4J;Zsc^E`@u5OL#n}&BSzjjHr51y${v1?#|RO>*$ZjxyRu88;8In#yC zJ5;n`T{EwzRYTQgwF$*E`(lCOk#gzSX9})JQ@h?pRE7q0x>7;3vlHCcj3pxv@7M9& z(nn_xBusN8Xu6}jZOcW+AR6>wzdwqE|Me$-X+CX}HV7OyZ(w@Nt~s7!BaXrg0Z?LF zT!}7yEAJ20GrZzoJ0yWKkxxBVO5pZ^q@^Xv9Q?7XzL>}2Itc0y;!Av!+KH2AKf!y3 z1}+rT=@yd?6Z^Mha+sF6R;P=hz_11}PZVLye)@jn7pZo|Gh6WuLui(EOw=)?p+L;0 zFuzS18nA)Nkc4xL!@2X1V&(&*_syxd{gIh)D3h65O291dXp8*d8#Ke}mXO@Aee1>z z`o}&of|1qyg`$PqrCxCSG`gCrl8w+}_i82uU)xvmSu}-i&DoDhW@;_!-9WZuZBVrTqOWP-Z7f$r<&jhIhO*7fmco{&@QUw(JuF0EfrSlxoq@3Qy6^0~megX`j}g+7C0m1<$|N|`f}BVpd1 zMOE7@{XPW2Gm2dJw7i`+RN4GovECmaaiLY~sKq=PRLX#c+TCznv^c!hy4Va>OCh)A z37iezIm$fu%s)EPi-nzfl1)#ucMn5o_E$4Z*O;4PzJFM-OS!qm#+Z#4sK3C!8_~7L zB`lows-({E@X+a^CNK~~-*aCaY@Ez*Ts2w=p|kD(58MAR3F@|CAHP_T8E=r}yYU5j z{AH1jnK>LQ$kM?^H`Gd0@`cfd4N7q1EBRnGUb9QFf^%f~Ys^7<-znWvK8wzeM8!}BBIbykDwXW;ynVFb`KRQ&#v*VS;EYLqV zh&-OPi!2bUg5yq>8Z6|&RW~Vfb8_&yN&s%NCdPED5{moawt5)m^q;E`^iC$^J!alS zC*i|aYYk4-`T#zE4mUJVzj zG|q)*IeUm)yw^x3A--$MZ@~6h1i0hXBO?>D*+{fX5!HfHu?)f>JG{WgJKM4pzNv*O zL!e@@ow7Me3nBj$$0E z!9bH6%E-2`q-3>|)IhFoY3!VO%kyE55$rSy)L$ip{;7TAKDhls_is&6%!e@_?hAD9 zcdOe~^>|nb(<5*#EG(WgFm(IpzI;g)lMK8&`;TzqY%N+Qr~5hT!Q@vkr(OfAgckq& z3F|>6hjJ}1@&YN?|HIW=M^)K%U!a7Fk_u8%@}i(1CEZAONJ@%GcXvsP)Qfb3ba!{R z$bkbKLP8F4$O9ajyYc;gcZ_?-kUt#5fzR{oz1Ny^uDR9*kL%I)%GXa}XMU4Sy{w`- z@J*?+!UJ z$B^#%{DY#dK6Y`z0mJLT^INYxgbB^H0D$R;1|NI{z+==+%3<wEi}IUaWdaIQT&$AEXSG zr~TfmM1WZ7s6NqARZTq4v~2sj4UpVU>`v@+E+MSWa=Bf~AN@FYUudW(Rk7lI3fd>r zoctI$f2l8WB|f_FgW81;N}^j2^}XWJjXTbn-}AH%%-vpgj4H`}8kVMs6*R;D{5eS@ z9|<@9Q2-nGA^&g>nSJ3M)N%Y0a$v-3|J1mf)62Ka$_S9a}h7CLCI#R^{}7f9){0ZE&)=_l~m8Z z>-jEdwYW1YeX0!Z!R~tg>MJ=f`2+K3wGB-E-miRkW##2-M0ic_3tj)2ZzKWQP*6f? zrS7q2{&?4ZN|1o_Aigqb1ELD^F5RMa#S^T}S8}hYurw0_AJLcZ-C}wsCLprW0~B3S z3-QJEe_!$YjT<2gHmrfq+X~^wrTi#+)fH0AmA>bMmgO~eFr8^E94aBE-eZ%M3wviR zIQhTS?{+zBz9rQx#Ok6q|27S_FBzUD&Gd1m&44o+%glpsCFh^o!b^UqGjCpOoU!CW z=xBiWn$fK)qZ&Mh$g-C8K6A_N$JYO&V3)ACkPshE9-2LrXUP1~pAlo>Z*xC?ih}Nl z2I7Jl)NfIr+weHnB|e2z-q_=CqEP#apvRc97?4-HMv*Phw)x#_)YYCwLYm)$A(jEz z1t!4WJTL-8GkbpWEV&!UoJ!q&QBcfud=(^yogEX!aTFDo|C%gBJp&($fvK`eOod6J z%*kZ_T@i5(NiBk&0W!D&nR9(^Ce+SKTTGlH6$(guNeVO~w|Kan*&xi);cRC1UGW|l ztL1dc;I6(nL{y3nZrkw#>Vu%nX^!NW%WlO_nl2#8-0p#g(b(#g{^U%LLKc{Lbs1V{ z4Kez@Jo5G?yGw|RFD3qP^r&mLuy=R6qw%FA?B?qre!XL(-xS+avk zRoc@%1#G??$p`?#cJ(Ba5)w>B48*2liwc}xbrn6%jjKI~JQA6>4(xy+c293Q51$te zDY5W-T|D0pe;3galITXBmJuIdMRuG1gugO5)b8>@33XAgi!Uuwnc}NGpJS^l{_Wb! zUUQPgZqzku8IGu#sE0ehaP;_(2~w?^-LrCV#!Sk{=~|*{RG4FBdE`WCgVnd=QJ-{BuA~|H6k9)Hx+#tEYa-_qjIduj zr-=x`B34*B4^P$f>oK$TW{pA$;TaJ+hIZpTC!Q9=Lo2f-i=;8yHKui}-XuNgic`|h z9(Tm=i;jy^g&!f2O{-s-nr)!4rm`JTZ-Oti2SUl70-+W}3~xOyoZqk3f}TRkU)@?^ zPi)nXl|8@>Fqdsn(b1G}@?~4s>kX@`Gpoe;2IWl73_nBfdY@}nu6-jieXK#ZycNGc z&{DtLSPAMylexs1gE6n$5W^j0xBt7HJyQ3pCVk4C%l^yC)jT%tyAoGT4?{m`;AhHJS66ET{WF4ux!Mk7VpAZ7fyqA`ORDnor_PS2(3{~FzozgS z<-(!rcgVet17xJHj+fs-I0rtm%L{#6&`j9Lbo}%DEYX#^MMo5|e_T!b(VP976RSs* z6>-kiccFxRl~T|>CMD&Wf!8kA%?+vpmIyWUOJ~-tuQVAUskdDmrm$-@GF| z+?|+N_NSQo)064^{D(}}y`96u!_VpiBEizVr*63q4T;jMh%a)|PRy_~oOs0L2+i(r zeY648V|r2&;7gY?qSg6QHDZSYJ0bT zGG~_@`QhUepVGwPxr!q2axzAadZ*YhFCs-Ch*XiS77h-*SLrA>xHCy@X#qm{-O-T~x!R?fobL_y>({rx8&FGq zJ{>;k32Dd=Y{s}WZAZ^VybF<4vWX#LVz~a}%-)ytQCd1@*t8+@0hm|^o^7K^pauP{ z&xP})Y|9 z7<}e&*hjj%|7hnjH#<8(^tmV-8RhqVNsAQ$_hx}mp}OtesM-VKPwN!K#Dxhr>N!i- zCIoH^4p{${lJSLpcGB!!QCj&S@7=Y~6h|y9pz8V-Twyi~;8?VkG6$F9i1eMSsSP!M zCO16mu3J~sv=C^FJhEFFj7E*Gjg+*H^~u^DuI{j~ykXp6KU78u;WHS1Up@zw=~-(4Gy<$OuQ{^PyXN% z+=u^&{&%O3bz zD`g7~V=veL+(ZmyE=aWDXCV)*c03Tj)g9l`v6A=o)glw@9iq-DZ`Y2LV@{0-VCKss z`yC#{A|mcjZe4DpL8B7hg5R{;nV-wJZS?e1$^P2h℘5#-bZnjv3n>)>z%w+|#bx zJh{gU*Gy`?JM#^_)9pkiWtI|sJ8kY`ogboRs>(Es^vWAXs$xY}?ti=ZIyDXVO}nU)5u;J=t>^vvMdnJ2U8YW*X=t(RZMDp86O-3zzI$TA>@S1U&6s_4*dxDsKSLq-lEysn_U?I)DWEgO38{af#&JzE=36P4Q$WI6Tzcj`OazVMCw zjo^L@#QV?tYW2a9Yjit!#d@@EN2d@ehQgYNoNq5rdD2&GvMnfbuElpO-v?Ut$&^ml zz&lvJyglyCrJFcu9GqpnbV&9JSsLt4Vp;`1v~vb_tZ(Ncz6Qt-!%JrvnQ4WcS6kk< z`#4SetX@qQ9ji1Y?1?_1t9E)yQP?4u6xKJ>ZgY)DQ<4mrho8&R@~al*IDOS1USvuLN8bghZCehdXKrJejpJ;&fKhP5XX4RwPHJ70c`o$W_gx=oP z+;J`AHi)Im9|9fk#KmFK;NGwe-w;1DOyQE?R z{0Oi7p>h9>-Y+q{z3c&}YQMeSpPDtV|Lwk!Z05cmD}A=5>^EQGqmUvTJi0y@e@al~ zvFhb*d)QI6?RV3iidRNyVG)sz|EbpTy$!u^9WuF(r^6*RT zU*Ir{p)}K-+&MeAc5@gTH?7tXCNei-h5OrfGb^1ePM}=5B$?x!sB;hm=eR27c1%6=dvt?XYJSswG~6`WwE@!^1LE0wjGEKX2S0kEw|@ zng{B;Y#)?unNS=usV)zDF>lm^z;X(8;lmo_9+yCxKN5;IPbmlrxhOzvt9PspR5%-k zTQ=h1HUxmGh0$w&Kr>7GnVIVr5>E6Tcf_9^2z1guIB+o_i#-Nk>5ra$iXfn>?<7 z?Q(qia3i|)Tf~jHgjcki7(oLZnUY&LDQP64mc(^^DSkyLOL<20x|m~$ZQZM0K= zT0?*;B0vcNWsw$8qrX(u4B0rz@sb}sZMZc(#L2K~R5-_3oh)npxZemP>Plmpa zPNI{4a~i>r`LKjx>A;(1iZQh>d(2%LDW8{3HS%VdPJRH^8mANz`;LE$Y|9qc4LxKa zlJH>d4XgCwr2{wT<7T9idL}{Wg!Ds1OjCiJ`kj(P-9}JPnYFj}nY#dpoOkAi?O#ar zn)kftRjEW7x&oAvSOxa08U^8D8BLEiP%HLDPeq8iXoN@0dqQ`20D;Ab5jGM-oD6pO z>&MT7lRYFW`=Ukf$BUP-X^_J<#vrm}DM^3+$16o9)5RKKC-k=MH}90odrJ=U(knO| ztlaoHwAv89DoUr$a;iPV6f01qe)Z* z@6vCDxzfYO1Ova^9#n2e1;oMP1n~n(PBCU z#vHz-C8)l;EPpl$%t`QJK$UW~npS#V)gF(YRM>DW%>BkZza$a=R} z&HK8>ds$Fyb@{u|A~A=wd^Z!b&>ctN+KzGa;U7aVvKnt?+y>IR;>+tQo$CuH$De{P zKU3I3s5;hgm-k1pIFnzljvqNfzF>SICI)th`7-aawMj>?jKRUY-c=kr;w4&Z7rQ+{ zzs3eM^2cd`AIq>*v;AYpLezlm)(IaTPrB|YHz%ixzP`_UCJC(S>59#c4Vfg%>ydUJ zc9a{wb{Xs!gVKxHrSb2DFraNu6q>KVG7mV(aE}@~uE*MiT@l*0t%p+W7tBstZ#^8J z*!iF^l;kHmuajHOrbI;OgW?u$-D8$Xsa68yYsh#`1T}?`)B(8en%L+b{HZ(a*o zi_5lz-Cm4MB%Qo}l9?o!++;Y{%NKo>5|7iLuCMuS}*r5yza6At{pbETnUB^khow0+$vwN zw>RB!w!Z_t-gm9;Sf8}W^4{PhE?0{!3cYjtJC~RLPf$nPJN)T*)ku}5L!5*Ut_a>K znPCDt3P}Br%9dB0W|30N_v7zxkYZa;z=)hO1>Q1fptesD(|g)TZ7*zRyoN;k$p_t% z6slJmlbYE)CayFTk8T4!_kPg>nnEcAVQn1M{R6} zYu^uHdg;o<7Cfuj?z#8n33Ql;iK#?>WGRj+!-`#qn8)PnrAgAM{ihiPnpxIZsX z;`(*=+U+&zYxf&V#*xIe`aL!=N}SqNIeEIKsbwmuO|r4B7r**nx~PBOw&BE@msN`P zY^7e`WRGOGD0=jr2Fn9}=m!@$^-diVImb;7H%%0>6)z||C;KK(mxpw!jMgALQT7Xv z&%C9KSN6#WXQu7{Mib%myyd!AfE%RsqLPvtCNK{B+(h_#OBrQxPV@l)!3V!aSUX1Z z5)Hl@k+GAOU{4ndMz#Yhi;D{vslM}M%r5G9Ybw+l26l>s+qc1i!Fcp%y>uZ4K!N*M zPf4YqV@nP6^??PF#b2Z!owgB42jg{J*7wsMGT}n#(6dWwpK5(b*3W*nxWwb_lVm@c zzPUsQDPA(m!3c`zCbJFvGIsw>xt{f&U6<*$qwtG@a${F>ptOyas%u%GsD6p{?edN! z_S!I6H@3MB!gL3>-?-&KQkUawh=~F3wfszC=}cS<-~w?merAQdhNW{|C9yRor0K1( z*giy{b&;mf=mjXAN=A^(LCZV}#EwIWhf&ja6KvnjQqcB>lMw^eU~O|Ucfol|@%#7h zm0$=ly>iC4fi+rCG!^nXeGI%#`)w#*FyxlcdGm2|Ifvbn;OYLdGUzz1KrjB6Gvkqv zOS;Q9+M~;YA@lAIq|eeqRrH~m5<|YIx&u24-3_bSS1Zb`^!@j0GO01Yw(39k7fj*= z8rSK%`Dz5ShCAU4h7xey{Jr*kDB5T)^BG2G~5q3kzhiXh*^Lm-2G>QqQ# z3rIBdZJHPX+1}oHT0?6t0GPcW(h|~jZEbSQb`|xhwxol1ZmU0zY+v-$`v++DF*+-> zNk%y(wckHV1`AOHou5c zQ{a=WY2DGSOBukm1D2A>uA(03$&Gurq>-M<21VHG;NV&bQyv|o>W#zSVS;`ogwxpC zxw;q4+~ty~$)Oo7{`^|`LIid4Ov^xW#jg*QgC97v!S5!kk$q4)M>_%Ig6@ADODXR- z1NY5lVpW#ll=@-CIat#W6D&{UukUzl!bsVDWp0*!S}e2$zU=~^ezqwqhQDrD_~I!y}4kS0oy z!D+(^P@J)y-J=C6)%c>Q;&K>3P4f1CFpzxt|5e_f2OWDQ}~Q*vR%c;`9z{(}63}4orQi<6!e6M8XN>DN+84UL1F5A{t^Myr%>O-q zSnLa%Rf)@;<3fj5lMOsH!U{d@J`64$4+4Sy3z@e$)q@N}_|Ej>5KXC=AHq}KYnx+* zPL_FhrO`ZNd7FC9@4X?Y4wyw@<6=hi_N1V@Gl&22Yhmx==slqR>Lj8O^Xr^%&xuH& z62P0>5s`HjT*gTN8*G zlTM^re>U(^86j#GOBOSu$v>3;vWdAmmmQV;C}6GO{o82^-sg$5-J*2q6N0}ha~&`9 zJcatilq+&>gdd??1z8^A0ENdY(7{oFc^I@3mhwDxBQg|>6#RI~4_&7ql(HIVKPHPvU!tjZW6n;)mW z^{m65EjBl7u@jFz0^L{O*k+&kS(|FUMDF0RhZGhtgr zNo6UWiBsoF@mgFZ`2T8=qXJZ8=o(K0a9o^Ebm{6{)tVz(+OmT#Mw9k(1j- zLI3X$-5qWwUJ$Yig^@PXNlgXC(OM#nq*_JiD38KMDnPwfd0@Av)8QKBrw$ZQT_^o9 zd+kWdK;XK#_7dy9|oogk;gW!3`REnpAf`GZ*f^IzgXl*H=b#6)zFVBJP~ z)Tw=O0f8CVNhW?_;vn-+-1SX{8T}(7;wRcp^1s($zv4o`q{rl0@hoHbQ}P5|amw+i z;`7qQAuagV)8%s0PNXkD8F+XY(WxGZO$=hw{jf)>PTP)%gQuPF%_MRl4!kSV2?Tu_ z9&-K|kmB|Z;u4QqVb&?q5Lo9R_ro%S$dX!4SC|27$^emD(>Sf=aZ@F@I)N{9hM!=j z6cU$>Y@Jf07gT&s3GB&CrtQ^0FFpJ3QFGeb(oauMef^mKmlr;*lYM*6Wxqb?UuMPY zWTOWIccT{5(AL-48U8(^OsczIAu{H(fN7)*1h$OZumaIje`f8Vtm{MjQ-AwOso%CA z9deWj*f7Vt@Kpn&uhBLiMuULj>P}f&xXJaOk*-B(Lr)?Ts|1@^=8W=K+SgZjZf@@M z1h_)MEt(>mFe*!-y1iZNrS4$D9MJN}`d>fl|2<+D-sc$pdEGOq9m*WwWgw4v%#~O9 zcp5Gq9TYn0BmxRndaahk5yI!PXjflF@-J#R>e>nW48!-B(Ya5y&e1mwe17Vj18vvY z?$Os3?ErY8uD7szR9^j-QbPkA+uqTXGKF*^wI`H5__YhI?>tz3s(M(~ z?Ut1TWi~%QF;6PAeOx0!vt8`rB*$Mj%l|S^5E=ai#g7L{*$0q+Wx}2bMR2UhK?)P< zf$ZBtIHjT4zdDvWCh#;5R$mzclW#P~1UVPDqRM~0(94r8)X3Z(nZg|PC=7guN|4aO zOD*%x&cz@VMY$vVYX#V8EqThkb4ygPO5*L{^=+U%K*Xhcis+&E6ob;|z3$+^N*+*i z?6+7WfjsV=WGkM-!D9Y)5^@lLm@&tv!{zm#EY=b z;N2s23{(4JW-p8$egB?@2ci20-~B~Q+cwrNG&O)+1);*!BFOcS1N|((8;bT5zQgN{ zkM^{K=5MY4<)5Pw_Uf83wrSFiUo$I6qt9l!J}Wh3EH=~@B8hs=G)_$q_v6} zTXCVINq?b4_mwU4OgGCd`JJWl_x<0{d0+aOrr}Oj3`y)RG{tRfY}{d23B&)UPXILd zkpAy9Vs=k18op0h6yYI--~(h<8_C$wS{hV#;UAU`ydcbZHa7>%7J#ukM~ChdC^zii zE@M%P0)MK|L1UARooqvw1;SHN>Se+x5~2SZj2Vn zQ`JW}O<6<{03tep7U*M*+Y7GBTQW);hTk$TSzmHhn>-;XzdX&N;})hCLTaqE3B9d ztsdM}i&LOh4R50c{^N>z927u59FHgGz~O3+cl>9dou|Olo&T|u0w(xcM9-B67Zf=m5!^YNE_ljoWy=~mU-u53NBx+YUuvsP8i#EkoPQF707>rD z2ly0b4N>5x*dpqTe8n{P?lP|~TqQS9KnFDS4;*Cc-fVDPY_Dy72N;_lMJ*&}Y`mtj z7x(zl(CFw3A))kzg#~IFh6*e8e+PGTzHuL=kmRc7RP4l=c&g*@-F@UV9sUVnTuLC5 zmFb4sM~5VWpwCXb7#Z-aC4C>*eAM&DtM>0K;0Cbs4dCD3jLYOqWPO#D-~3GL19{4T z_U?S9p1^ z_Ii_NbGZc{XnG%!rUHU@2BYj^P&&|~fS%T-G%B4OJpBmHwoghl?#4ve9YddOu!}jB zlW4g{1rH7W}zk ztRZx{Rkd9>_~wIv0u#MPS9lO~@`d2;#Y*_ny??Tc)KfC_7znd8wX|Tbx6Ly!n%`)?*1};w5n4wUzV5;-Md6_sFm@m1 zxeLIb!nmY2NFPK|($3EF_j+-(YImjG#Wi$kMvr$K)-~ON!19SUKPs4Jr`fAN0X$^8 z6~H1Jt*IXL-Y`11_^XNo`(4i#jh`UBsEgn&WB-+P_wo{&zs~Ztp8CtItciUvy=sM9 z#q9-m_SoO@b+Ss574RRrMi^O<6tAMDZqC*~M+yie{#3=TEg7fQjR(#c??GuO@ULdu;~!c6FS%8#6W|9F^Euvh#p&Use&R?!Mc@B*vg=V z&*bcEn9=dBnvxhUmQbD7ckl^{{@+g^qoeeEsfRKJN<=fEbzj> zP=CB|zqZUf40!CrKM0F-7>9ta1+J)+XL@;gL7<-(;7!_MU~%^lWDfvj7c88ZhCq}h6WUQ!WH#v>xfh8iL+H(&B$gRDjf4<@Gmd>PTe(WzL zjrcz=02w1o)T5{1QFwFa=NV71qmHyxujGNY78Jqltb2d^fDfU}rymRt(V-)>LQBlE68(|7)&+C*c9SHpI+5dxo-#!Agmu(It;X9qag0vP<-+>QM zt9dvdPo2|=#pne9elzvpWPvpRQVoD`NZ!zifK@F(G_%f19s(CRQbwRgXX7+@W74y+ z;$F|L;wwQA#ew{XxOM_;lu@z!970GbOaqie-*%D`ABV!m#t~$FrrNG6po?e_X8zFT zG|EovY-=jF5^OH&N6G@dILaWJ*EsEHy4ox3N|6u%HdyAm+fsrk|=x6zQZx^P+p z;^LqJD*lGO_^(qdccp*ONR_>WN89^o8`$%fTAzZbSKep-0)+ngL94(1IH2^u?Zr_o z^GE|&ytMSq!(^xZwcr90CUy1PVorh3Lb1E%EXCju`QbB5KM5Py3Shcl9)}KCJsa!(t zR9AeXH@N&`bF~`Cr{{TkkGDB-co-#{!5-=0v(HB7`MhGsfXwKN%{x%`>o&riF2Y~f z(Zj{|P((>FKuBJYVL!pPA}hw!Fo5(JD1$V))rCbvxvl@-R#1h|(V%Bd=%ICjXa@Rp zhJNaTKj<8g5gcDM;Aa)m5Gp=7L8}$H;RW0KKcol1UMIflv?nng%pcdPiSgSpWvz+w zJd{~Z^j&7AJF(>e|5&&U0K+eTH!$hpHIUlO5t)x<^a8UGU>JwcR24VDV8R22THn9k z|I2f7TOPD#XasN(fdZj&hYtX0A-OJ5)z_TKMZ29 zlxfy!>iCU_U*OzaB62Y5BZ`3I3#I3!9fFVWpCwq&ysC&_$yH2(+IgEXyQo;}IZ}{b zAxTuK|0#XC&ugBgwy2bA8wW!#A0qn7eY;kNN<21m7?RZYEZtDmr;?!Kr!;%Y(yFqu z?GJ9qJ{3^`na{10x6^6R;EwlOj`4F`L%-h>2uuDdXwGACC0LJL#h7V#&?AMxq~Y}i zWYe}l$M3wh0j%F<4gUq891c(?Wam%?30Dn1d~dYA`VKy!+8oDS+A3IowKtUIbeI2f zj!($(XagS4dK#!le-W1%q!_zSyUhDi47E*W+mqo{Jfqd0X`$23nZL@VI#a5_L$<|={%eLBBhN~5E6$-k$y%cJ{fu! z_LHY-$ZnA&AKMr+p6j?7TN)fwBSqBC_LgwdvGal_H{_B>ecMW5v;MQNSPMCBMpMR{h=>Q#K(>E>kcCw19i zV7xwinWxFwZTv6L?vdv+BUS^y~V>V3wCi2ty;WZf?phz^dX z9Lq(OulgYi{v~|kuCUmW!IL1Ocq1)9=J_7`NqiU0V<@uiQZmE+l$qOnjc=?f@WK0M zG&@Vi+g2CLE>w*nrB4FGA}QpKW3tn{2EdJE7mqqF2Po4T()>||sKetuoDYuIL%pw_ z2?)D?U-t8Pi$nT@Xx}3)Z(@ICJ0|NYN-)MIG+cBMhsX==AK4cZs$ z_~UJGDW!0YpZMR8e3vqZ{Op9dqMTV;_V`&+J{PpEQ!TyHRven&?N!L^vB4?-xVq#Q zmzp||2ty%54fj^}iON4tmK90F`wd1Yw{>=O1V1vHSc5xF@o~Su(B_8TmhY$p7&j1c znX^?nXntB-<=q+Gx;p*Cj8Io2|Dkm-Z8cGOMe`CtoiI$?urS&exB77>_06>vCb>va z_CYZ8yqhPo3CC^)j3zvU! zd!Lsablp#q1+g3O*ATG%jgaIXOlY~t)&6(A|D?H`hMEe!0DjYFI*!;Tr|z1PkvK)d zTw=n8{eo}utVYlIde}G6PfW~mxgLBio|64+YATat?xH(MbVA~krn4xo`r(_1)yssO zya4VNTP9F%>>0=vaDF3c7F7FlSFT^L@N_}Xdu~p9!Irat$k3I0CaX!gOj7a;u*j_G z){ZLdY2Ib%O`v8d-9gX0}lP8?2ox(r&ycP2Y6*>(*TS^x z5u~HDrvkR;BU+H-p08p}~t*jmeEl6#iN9VueI=3 zmKzr2yIi^KeMHWkNZQ}`jP8)U<>?w@Wf6(fT~d+hI84+dynf~;Se3Gv5@pble04wZ z@T`1m;VLz6f!BtD!0?pGfGJQlini3_NU^=}*H0I!#go=yOTd90{ekk2d3#bEJ zk)d)gqp!7nF1mcWx~?#0_mLUB{lc^?Av>ad*H+gDT^I)9eFy@!O1Mf}Zxn-u>fE}PaT*x1@?sQJT3Hbsdo zjhPH{-%g#`A>|+&W!`vFeXlsjjXfWidAkgRrt5S#UC!vLXX~T{*Y&eYeKvh>sPg!I zI(C^>_IMd1yY9Ihn1lQ{r)6&5P_kC;GDCUk{NE|~8)KQzPm7XI-ssf@oHJwu9i4Qz zuf{3tU2e+#3VF@O{uOE9nQ@C@E>g+J8XdsX(a&tA{0~O@WMcV-Ti>F$U=D#A85ze@ z*Zuuj!Ir8-hs*9arhQCoF0Y^+Ui=dz@s1}BJvxg&_I98i-X~jcF3eeKz^}D=JB3a* zuAI1pqazeAVx8xBrQKT6VKiX#K_Tw zU`ywi8?xZ7q(Pa4Q@gVJRer=d%-_=0x8ae?1(o2%U{No^3AugbS?+r%r$lZXxGvx5 z-T$E#`N#Gxr6_{wpw|&1K91Zd zKW9FU&{u3*WP4`_&V;sWk@1#8Tox+6M1q;Ce~&**eotr(hA-R>$R;SC`!G$UdyLyB zyX)2Frl1_lS8~jr;$KyU{|dw1JD-YIsI`NSksgtq_}MwF)T(OBuK$upo^N4MG_JkC zVf&W4=jZQHAemdpo)&+FK{0~LjgF-I6M`lCF3%K&vR2FxU0utpv6$fc7IB}fKQe;U zNkiwUI^v}eN=<69Ei5x1S5#mROX;#_d9GU5%oD*-cB3@p@}DApf$g<|ZK_8_{N4vU zNh7u-w;zbHyG&ZO)rtK+!9`+q&5IJIrmMQO50`T!Bj1(WA1ex844rO!I^9HO=!#k2 zI=7iYprc+|FXgtmiQhK0>!%x6$PjX6%{NA9E`9~=c<(o@VM<(lZ6<;#`A$*6+Vb!c z+R?3{WyH#4H6KucvD_bTKJ*&Rl-RQJ*P|NQn3=X!Hdz^&&8msGq@>v!IUfl>{+XLq znQL3B*T1?^kIk2Ek7kN7zf)-sp7^O1p6rqFV8yGqSB`vbQFK_V{;t)0VLnBi4vA{t>ACkq-k(6@W@0#DD6c4sHj zi>;#X9WJ?1He!JB%F}zzClU_P)5>#%k+{+;&`&mQjIBUcKh%AZrt!g>s48Ila2ea& zhE>QhFvE*q7P6bSta4ExPj+39KZZrmnm<#KE1x;|_SqtQCrERuF;Y3fteb8ysOJF)4pe1z!vMB$G|qZtuZ&ZKRFnN^(d zKrzoz_cd{DzP-XX2gLygg(LfVo5gWq*w$$Cx^}szAD-Kfs2}TP`+T?cMC7%XC)^n= zTPdW>Cnzg^dk5TgNE6B)^$puV-=1{n*6xW@L0|US$Sd8JxT{v#bu62=+cSKSok@S< z)am)NW}80hM|Cd3&icl;{ci3XDCL8Fp8`E(Jr;#nh%oiycs8BB_C z%gh{X9F4cIRDFMA)S|iUmHnUiAm7aoI2vVINd{Dguv!Azi`bx`d*=fGND$DXZ@-&* z#p;pDI^GyjU@MgT4y}FeTk{`TVZB?w1>RTqBheZNyPuPE76>kjD~7LKxmh{eXeq+? za1`PC7?AQi+|+L+Lx8P9A@|zDj*7?({#I;q&WsAJn5K?hbh@^)fhuq!-WDNU@)?eL zW<0f4$+@QtO>HN8tWBEpX)S!VDsET@PpEl|BC6faaJ3%B?RcVVcPR7ep2ofza=!XE z{MWmwNpev{<;u4<!IHKq(e{T{#EQSKc0{rdRs`Fh~{G_ z^*5MR?ENl}j5BUxSXpFN)6+>Ez2rFMTy`cFk0qZyQS$4^$ApFkH>w(wiw$sBcfS z8`}C6?b?W)+jwluy!rCCM)VXrC~y;YnhR3tXx{uC34JWsO#Kia=Bc1+eu5eO+XgnT zrTY}$FwD|ixZZwXDs~NAT^OLnxZfh_;o&iRsms}ifYKPahHS5N*!hJctFe;#Tt5Hq zQSjl^fWM);?7>^$g!Y{$ylg$1@pzHx!Z~f&F)(cBBeBEZ{4!w6O!+y(EzS2dPb#&4 zT3c`T35)r3F(69s`Oh}0{PdxbTm@K+vp0dHBN=7hX}4?ydo2NQ7P3G^C^^3+M(Yjn zEsQ;I4MlvofTU4zLj)^A4HxO#&vL%Unf0rk$WnV`j{Y9*!+&$(`-Vj2+V?6YYPwV^ zc=NT{TLxcYKabaOKbVw1{*JbKwUi;zY{Rom@N8U_9lNe&2HAC)sTN6hVE6V_#^)0b zS9QpHA#LMPaxIQMvx$G*G~a%BeYn}uZlZQgmLD0FW0f*~jPI!5F!9h2!;mn{xZkDY z#dT|_yXT38V2p4&a$@9<+eF)ltXrDwQK#kbj2(mN{G(nh4HYaOtgN|-0GO)U_(sYT z9^~rsgvn^0@lT%XNVp-z*fguc3o)oFrG*~n4f{GhRA#uyOD=>;28_ z%c6?a0UBf3uhCKhm5~*izJtyDgXV`O$@#1cwPzoos;hsR@e6YAG`FyFI+|A}Hlexm zQsv3*d36LlEpotA_PEh@7;#uQH03Xfv;6zCx+JGRxgijKge$K)>e|*W88KR4&rCfr z^lpqFZ!8wyKd<#+UrqDtEA^C{68>o=s>Hg@gEotXMohzfh#pIgV%4^Dz2LZ1zi0ni zczC#xA8G_~_nXG;>B1>LGQ~QVAg&!6g&wSI86RXWP#zv`bu^uS2e>;aOZp`-c+{~=c zEjWJ=Mk-TAZC?;EA#2=^ABhm$%=c}&Xy7`hjk};kdV42jae3b}C>_hq7>}>RI|kuj zmT%)D@|XL!+-`$0qn8Kb7eYuXyp%VN3Q=~0k+ZKclH8uUN6B0IkjgC-eZJn_U+}hli^5AE=i-_8qyxF-7a@tz zg9_>U`ubinh5ITBBY@)0Jq9CnJ;pq-zYI8_sr70z@bGz>4}qv7T^$_Q0i)YyxPIzC z-PzW%{FVka8=Ab5A!O;@g3O-zP^LXKbvTw1+}23uWm|rpwC(&}#EN7zC3y8iBmg~q zYERuO<0l?n=U!7~;1G9ys`}_clkpggamwN&&282*S7IP3;bJ4TtXboX|E|JgMdDgQ zTmqx|mD6!9SO~xsRt8;h$l$*W_#*Vj#9=UeXzmF%)*lY;{_XQf!(Q~H#yQ@lz4lg z|C}Ej($>eYr;So?4E^hzZBj2Qipu*}U9r0R(kKy4O#uhBS^i<83V=oX%~;GHz2)aL zFm%-=DyaWFQj_i8d_&c`XTLI`BP(G_-;O}U3?TUUv={eCU}OV6izm?3js_4`s`xDh zol4|JAD;xzs&f=ZHIGdHF(zHirOPflOnFl=AQrYq@03MtJB*f-YvB^bW(9fvVE8Hu ztBej>q6aOjdcrk0vpSEP#)zk{MaK3jBmo(%6aI{H&o@v^LIF8YhWjnt)`S8lHqe+N z6XyO?3iA7%jiB^0J=6tSCDF@9hVPIe6&&_1y@R@Cqv`TNQ+`W~%kzN5-%*BIr<-I5 zXT^xmP35VBCwI4BI1{Y(9RDVmj_kzIc>wZ^t}eP2@++f z{{QlYvE~>(hXR+FI#4i5N9?SSd|xo7fbc-l0K+9M+t`)-f2jJ(sH)beYfuEGm68@w z5tNW_5F`|7ICM*M=x(Hx6p-$c!=dBQDH76Mheo=);eGJl`+nd1Lx;nG!@Zxqo)vS> zwbp4FCLfqU9Q4|xFw6^8*#SPzuccA1=a+Mw#8y%hOhXrV{`qrL2@%nJS8rQF{DeMV z9q$g#T%}-i?`4xpNk2;}mM*oHTnK$RVn#s#-nY?F^_N9_-@@p^1!M8ohNWV^Ct`xyRw6 zURw|;c4GdDJGvjtNJD}VTdN~k@b}=PwSpVO3rz<|e*ZPCLxJXbGxKIR=`}m6XUzKW z4E^bB83KPwy@nVRh~Q3&sGo_Hah6eF^B41 zLt_FWN*vvQQ1R#&Xd+5(z451|NL=}FARQOV!*5me8>wgi<2jvP2@?V69zlHk*Kpxi zvxmxg-ABI2=MqLn3Mz8mN6}6L_m$Go1Bb=Qb#g_vTzDTPeK2A0TkZMY+4+G|7tAAM zXJ=>8`-w)FZGJwFWy8Hz)5|sMF8b~rnn8OQPHh-4_Db;Nha9%j!3{9l|KlJBib&sT z9;_?*mY;3K6EkU=%z)*$YPB1AzlXXZ4euK;mmwTiZVmW}W)KY;A$46d!kGDpyhcB~7L(HOi$V8_X>3u3p&V1V1&-l(r0mY;zTJB{u8rwe z*4&=Oo7`P>VQIvH4%04*y}Z2q1`W0Qxsj-g^hDX7z9L2e(Nfzae;@I^kVXM6R~x-2 z7GYiFq~Oo&w`$&vLNr&q(_k>$;GqP8IIhI`t%9!AR?Yr z!5?$3kpVxff=C;kYR8!fp55_z1iH0*-tXybR=hMJ*Ga^NAKKCVEH^)dM@4&rTQwQH zLh)E52-`QCvv+A2SSsPaEas8%-s%)oTlaDlpx{FVi~P4k{@u>gzlx~=Hiu^)qv6Bb zZ;X2>%C<}-;Ih6WJzm(1JpE>z+G0lGl&ydq{07XU$(2;RBy+K5XvyxLC?2Aw-fG~f`xuk=7#D&} z&gsuoP$AK!zpw72Butv~e`ZAi&SJIoA2Fb7!|0v+-<}*v@{O-6ifRTvS&-{?ykqivXl`h$0FqweWGOagvgIJ9T?T}~{@Jw{PySbn1;k|#1%;ob zhFw4t%C+*212hDeSkH@;=_^z4U=Z9$x2M3p|{3+*dSOx)`g#lfL)D&`fCu_{Y!ZqxVX);;VY7!{$m%G8f1b&b? z7)_KKJ_56Y&v7=U!PEgAr+?JgAltB}a`_YSPv$|xYXZ#Fxn7&iTk_*ac4{f`+g&Wv zuP)B)MS=q32NtYvswfhS3 zkq3j>eb%~NU81P$IYZdW(G2$lcAoXOG0+iFdd9 zpxa=?{WAovlqfo5Yg?%1`^;0rks`(q~l2O!L|M6kF zbC9ymyUJ^sM+7n+NF_2qA6gV$gs^8Mc6wOX@U^u3_wrSni~n(p=|Drp=OHlk7>q@# zwXp}1*Q>uGVycCMJ|W{KZ`43{jej5g-Odo?8w1UHIu`Dinh)T9nIAYfmSch=#qpke zoIysEOP6Fv`T*>DflHlm_IjA1C12-@c*`iKp{GdU)PN%lb%EgY;^Q1qO^LO^&5=jP`RBXz*8*kAKTXlX!P6=)A0`P~ic|7PGcxW02|yg03`t%EWL zPZ%|;@K?|6RucvKu-~shqT^6!;V>H`m>ILCkH=CFEf4g!o=X<;pU6Ily{-?e50*l8MZb7rL=|OeCt%iLxws!;fzg zYoT=UZ|WZyuFS5i&xI$0XDFi!oMhgAis=jzuzL)AmDSouj~isd{oMa9|K($4e@thY7xqk8l;7k79g(zu&;2^9M9T z^Q^G-xS0mdj2!zq(04}=O?WRKJ%K?3iS^OI;D>my ze&$m|bqz*}=*5!k{E_t3#YmTMnpWwXmHcdboQN)~jorr=d}j(ky=i|tP36B-5il(n z`>yq%+e}hpR+Nx}j54ga!(>UrDBM_inET**js;e^X zF1~f(m4_34ub;2vQeQ=%JnLQmwW^}ml?bg^Kr9)iIS26)rQ8Agnve_V!m<{e?ch0k z4=_WcVN5EZCla71bKec-j--7!8{XP=2lc*L=Eb=dV3|DnOaBxoVq#)~1!8|q{fnse zdTx#*(oX8{nzI2f$$M%ml-nR8O<%V6M=GLJIh|-MUr|DN_?&m;Uhp424r(`mB%vP| z8>Tz+yI+3byngMKw$4c$wS$IZt+)n9I`qiLf$1W<{)pQLQ#D zKM3W&)*ZRRDh*%h0J;IjL~^XLja$C=yu3zb^3*Y@&Inj`^X**9{}-ZMQ8URnoC`&A z#i7V~P#`>3hIvou6F;dp%5*`-y+Ty``Mvp=z)qQW>$21MC>Y_aP#2f)*?qrKqo?)V zrsqYRs&+b#q@?xnqG88rzkirgK%fMy)@fZ3hYTQu%`MUOj$$U-D~DjQf})f zErEDKA8840f5b%V{rd;cpFgLGHUzUXfj^H(O{IQRcY{qyVV(AQ8(OnjJNPv;$ByXxZav6;^N(tQ!JfjfO(KNYf2#jO)& zY_|vNu8IjX}*#fn|OV+#UlVfCIL`&dL^*ux_Rli)Ah^ z-;o46{z)|4ho^Lmo~k%dW38OCKM7KT z-+#HSP`_9zDkyv&+c4}+;#u~%ReBvKy$w@3%BA7n)S%=@$!d!!TjL<7H_!iYWZ2zO zbIFO0N7b42en?}pMM24L*%sC3xT2yBWh6CP%yeHK#iX$HWy*+;i|hgG&#>$=Js2n} zTzF69OB8XEPs%mv@fv4iEynF^L2e&dAflYu6FiwPXEzCXIi1RZCmRaC-D#0b_jlG4 z@PmzDTz5MdnHE~Ofq}T4OFcX~>Ug4eYv~!O2d?$6H7Z_b)s%8o9!fuE`_Xmm@GMUj zr$?ig3~C(ZPGp2sW90FVAi3hVaK@BogyO)5zOLKvUrA7d?3;#xmkf9Wl%O0~&z@=! z@AW{@fMsQ-dg4hrN1KgWa8P%(98G@>IC1HB24e7m&ao*OVA84wG4;R~-=;6WXl|ED z-dgq{U#;Vo$WZyW?DU!h*`3DJO5@%?Tcm8x7sHA!7vB|6od=$h!SgioXD3D*|Jqw% z@Eb1pZKo=a-SW3@-}*x{dAYTSGN{(TMg6mn>_*=5dX=FSWr`aN+>Y?FR>$VoVm`V` zd(Pcv!vZ8p1_9rICc(mmdcKdr!cAx?`C_$_jmFHaz|Hq0myUBw#i6>mYT9Sce&DH6 z>?@YpTqG2d%b9w^;p{mvC#R0~_#hemrlCvoR_V7Irs} zW1%0uBN_Vd$eHdS1s!Reja2u@FGm~i-%IN5_osiP;{9%#DgI`6qe$&0M`%7T_stl| z?aQs2g5lyK@SYI4Y%b+Y*Gdb$-Tw5f6o*lod%4r{9%SA3FTpj*4$tb?D! zfs%&DQ!}y^nx^E$-5t~5wx}K)&OO%4*g>qW*9Y4Bp>q~fAdvJ)A;=Cq7xY0M1Ru`#z6(|i|if` z)u5n$N?ZVOECn%VZ55pH^Hi_mswC3DZ!4lIhrpS1hT$+sY6XSV#Ri#O8hYhEj^!eG zeq-exRB$$Tpj722c#BmsMk92ui>=DD-?E+}N=n~dX0NX<=wH9is;i@rHYc@Je@*;| zfZ%sW$CDQ?ezY#4C>r4|JLy2vUC+N_E1-B#Cyo^w40m@)CVcBCHD3)@jKFz>aW!H-9^Y~ zvUrvLWhGbn;Z&tDo-$~%=Cgl^e_w&1Ev&WHrHr(&qMcj2XbcI}i>$Z4cXV)<#x!1F zCO;-b@uX~w%vbQ!v-5A6@(fOX(=!U%Vd80+M}ZhSzK3^|a@asd3Gfjf?BVb4|2;a|A4e9IT{<&AKji1n z(Ti<5X=%eb8`UCd283huulsn1*10_*GZqSq1NIpk~qD{;U^&vlTJp{QL^m zS;ZipC$m_eV2@kk#+{AL*(P$?t9U#CpN7Ws6pl;iS)*#B>|)dCQ*F;f?d^sYr^_>) z)VYF~PROmpxc`tLD?w>UE-!CDN@_sIEwtm%K7*B&`&+8)R^_aMj^bUxRHfV9u=p8c zCNqPTT*?^%SReS*BgouCmX?;Z1S`TyV+uK}s6P_H7xvPe`ITgnzl?0*c9WC+KopEX zTVuG$0iIwV`07%XSIvJi#kPO`F4vSTR03Gz`kbw%IWL8^CP?bkcBvtj<32$$ z4ihVc7UUiHNb#BL7NJ~$C0npzovyH}2?Ia~%0l_ouiOjN zZieAeQ2sOY3So?_{Yr@<;IszTMkxCbNWKax_P4tEVg0UOTv{kzFf@) z&OxPUPLo@bVpBKRR%zOx=-cfCLS~>!qJUkfnUeC>INAcVkjt7~(HQPtnx2GC_HuTY zUY?CELKjb~Krc9Pj9-R{-wm@Jm%2G_SnVV84Kul;SR}hCnOg&cVeInaMd(JH?OSxj zMulAZ+4%9a%CGDYLqC98;|z0{U{iQfZUO-ylm zPer=Tw3faM@6KeA$dPMh+C9W}0rSiIWhtNkDQ1LTxd%4&`oZ93OU89FBc_nl8pds0 zl~jP0tm2YX)P=-^S8IlDl;?~1|9~_s_vzhPyB=&)S>^-XrnEcvWq8S2<4oCLXPe{| zBc6R+sYuD>?~*2-aJ#ex39%g%B!oVQmCVAn-y2m$NR7UzTX0S5t=BF z_`&;VW8#eylaSyZ8ZwsIxMe9;@n$J@)faDqc}jKUT|=^`X;hVFwhD*Lw!>j+-~9#|IAiV{~kz5x@2bxQgcwa4vV+3BzPVPzW<9WeU|Uxn-vW zeLZeY8H)<11Kqoy|8@1B?^P})yN_uNCwuZen%@x;ZlPQi8J8Cj?vO z`f4ZJAM8TAPveT13qs7`XH=;8n}P5a<5yx3&+Y(s(UE-+7Xp8OALnY&oO7Y1eOLJ% ze{>5)fu)sF$~iG3=4R0wcZ&kEp>^$`ZEM7RdA#hx(oC_xKL z|6r;{lYa~HsDEX&a+Gw&oPVV;;2$B>Y&YdM=5jNeyYl5*@Kjn^x5<0 zdL@3$stDEB;Exdz1EsMZ_n#+}(6be9QUB_u&-{vADKm`5RI}(R?taa3z})C3Rix2r zu5;NWh||;tdqDT5xbx@NMS{oP{(1&4*h+t->_tU>RTMrlA9g=@G;vV4(3!Wh+>%+i z7!&h@zv;kyg;ynDt4*bn3ri@*`4ZzI8F5VaY zw1R`Zob9~yNg?l5AI{sYmACKsr9h*S6+qF1VsD4aWuWFIs{IZC*>)EXr^0E<%}H_P z4w#_H6c1gmSh?-Of44)d>9Ky~`n#`hXZfLjEX%FuX|Jf3nfy+_ytPo&i0jf_>tYw^ zJKmBF5QSU0-Bj%bfK zr4XR30?B?Lbr@hP=fN;LQ7D!WqgHapOdHR9{Oq=s3w+=E26Ih5bvM@+F!f5EMn&HO%&uvV%V$?Md8K zYjqXM9%h@3^}B@X6?-^^aR1RfIU4J_0W4yc&0sF?QRFGyz}4!W*}?6`7M;I&_X~ll z{~(nXuPV;BbD*5qUbgojkqe=-Ts9kZ$>rZ%-bA9`v&-^mvf8@ID-0WPpY z3ma|nd_62?!!J)H6iMDvj*wQYyQh+R$NBrt?z7N$4ou>EgowDEa>fdN@(oNP{0hi@Dvf=vuOW*g zOC#sM-W6vIk$G{((4E~)Wd%tOz`72>>{$k;({tPq16iiT=?+x?(z#IlHiyoXz{cD- zV2Y%&(o|-`dL*Z&#b0P6mve;=8hT4Rerj2FG_9WXppgX>Tp+kYAwcpK$dz!T|%aHW$1xRaZ|?i2{Q z*Gf|nYbvWW;#oB1U2o$K$4f)Y%`kDAH+9~_g9 zD%)aWF*5b<7*OLIFxh;#yEeM@5uwDg-rdE=QMmp05*&W~ZwAfn8Q&l1bE(%33J&f` z^+lc^6N20|FPxeif8S0PQx-Kp+q?%Kadw&9Mv>AG;sRnUP)>o8p1q=$;{>T%u%=NC z+gfpAZcRlzYPE9>ZdXslQVxf58k=TdEkqVKIC$jE=RO=>$0Y&zEC8|rynb3rzH3|n zFf?dD)^QTWYfCQqfdSzm%_3-zKirxBWi(PxNio_&v*r4Sm?_Ijy|lo_>ql)NYoljY z$ftjgT(e?3sp$RfZN0tFx39qV80r=(Ob2F5XR#vab}c6!4YqMrc~~hsI1IT8yypLx z{FgJV0h*2Xp?2xK?zKI_hyu=rqtNCIW<5hb-F`1GwBs zl<##X+IbfnxVM1LyFMTs`Tr&x(0KRbbAZYS43nqgpf&?FMFC=GD|eorT{+$CH@%TA zrVoP>t>fWeT&$uP31WI#5A>i~1h9>#W!ufiW6G75bkFRF6HZB`1jmN=)5>;3HphBuNH{ zXY|60T1)b8a0LcXiQaAn=6UIEdG9ff9$C&zrQ1-_1EPs$-qgmX`s!Dmfiv(hxO;ccw0pg%1j#yf-W!z9Y_Wa9IH4Rpgq23O2&5>moX75 z%XjAbYI1s3Dr;i(>CMhcis?)hgVz;N1V(*;xC(rQ68Ed87*mb690()x-8?sXkkYY9 zZo#Zkix4o=i@8OM(9&%_l;bd}-!rIh7^zg+(RvMJ>s|mN&|rp%iD_G2M**18!zX_^ z-T&xK(H*FJizT^I1gT}A+-(wI zUNQmUn$pYyhR!~A!FZh9z(D!E37UCczDM_+A-sB1Sv@tdf-QtW3H-GBq7AIDscNgb zdaKvpEO!bQkTbByUr15VmPMe2Ia&mNEn(;XK2wJOGL4z+BlF6{$~<_Un=~M^zZat3 zH(gBB9%2vAVK&g-Kyn7a#KGXTHztRS>YpIc^D@Xnm!&Z9*AD1+lnn$G!1){}p}wSg z{;9DH(#L8=K9Ykj!09eES2$d^0O0DxX0yCwt|mYfg<4@|gyJhxvzE3awxy+|IT}Nr z{Jnt||Hp&Sr~^?JAqmOdxP$a#!e$@K_ck^~n6mTz$Wt;vcj!1)kP1%P*?s{S{eq*x zE!i;1F}a0aIf7?JE={s1MbI%rDNg~ za#XW;&M&O>hUT-|kqHTA+LhWx|74f*7SjUW#}+en@mCioiVxXItMEn2UkD1OjE}2E zMn%=Sy#yY@yyK#vH=>c_)(}@^0WJu*+-KlQm6x;EX&3PbnK?bMq|=SiSnN|&oSpalw zOzcBPG(p0k|Fi(qK@vdNQB_gXeF4cXx&z|QJsY>gw(R!x)e_zh(IUz!Jw9YgBW8WS z(;L##T6x>9dhRNXtbu4 zQ5@4*WH2(#QH)$?WQ~1A1lk*OLXHCX+E#;GB1olA9mgAZ1B|e_{0r9KT|KT)_;E2!KT zxN05hL5d&I0}2SVNAcPpdrWhH`_z-J$5@%rZlE+8z$ZAeByzPUVd3KPGPF5Yp}Ix0 z==J&I9~>4IdlUu9Ewt%pN0W(ny}(0Rx!T`j=-(Q-SK9GZYDW`=JQVb~!1%OyV2>}NUs>NVPgUrZRMJ&Ilyg`-t zEjJvHNPHPDyn3p)%MZi9FAq46_gV%^x1mt1cv3T-^X0QIoaIC!)H2PD)b;i1K#z5v zNj3d*?8)pdiHLnb#>;5|G;k&kf36@a9kXP&UinZ(yNIM{%)DY>T2hib!;Y6sxyZwi z>NmhYGXf-{JpG%5=x|sqxn-dRDgaC6a_&j{zM750A@B}W%6}c9#-XPe~pcII<=DN>4rHV@l8vHM>*4|4l#5Ya1aQP zBq(U?NNn`tEtb2&9k+F53taJ$5QY7Ajp~Ec#69W-?sAXR-Hs_k_qs+q8hFJHALMGq zu42ro^{gLuw$D7}itKV)r^m5P6~vSZ0LUe$;9s!XwVqwXsPUYc_Cw| zy2t3Ch3G57z}8j^Z+d`Sagvh6!R${bc1q^a9=gsr9)(D}qjtE+f*T3WYif3k% zMX@t>42~kdVw19FwX*IX(y2KWFDh~ET|NhY^+;lBPA^0zxkamMHmCgjz9-9%F$Kse z%fVpVyrliNB=<+Lvlp@r6SHlP%ah&r_k#&QO0aM zHEdgJ_UoMWzaw?{rT2OZzfO-_QC*k0@^NfkDw-_q?9T}#zQ5^Fw15Y%sF^r3 zxADY-s9e@ktXCsgF29%YoM#hNopfM;d1*8?Uze9sxkAkM1h?Z9sTaEfwyBc-rn;*k z%gQiu^XV2a0(hu_Fpbk{kzB?cHLZ1v(^n#M3A(G9{-OHOqcE}pcVEDgkM^gPR)c@h zv%)B#R6{$Rv@r~WjeJ%oz$mMkX52mjX>vsnS5@dv1Y86MTeXglvdb+6_Dsr!> zp5+B0o8^kYDx^44?Df)usjgI-z`ZaAN(o?H&4HJd|et7xLxh z{(B}K$lA~Ku;a149fn1$F0>cYAB-%1;(zz`Y)CsGIlgpk_QbQj5EZEWmHe~X`1@{x zn?zCm{@SGjV9hcz!^SttY_Y*4WU;w=O&6Xea_z-1f~cz9-r#tPo$E%*|ANqBo%YT{ zt0m;vvJj4AG1NU2{?T0iA&^8|PpRi=v?~4rnzOeL{NR>Si^tm)LMX@2pqLNjYlGG` zLxf(DgA^|!J{~a4-R%jLwCLSuvOr?Dv)qHCTFLI;->h7>d=SEONdz0bJ@|9tL>pRL zYyJptOY&~vywKGu=K!2Cg<8SXY%jUEs4K-6;taw9v)8n-?n?~Yyru+=H|EdjQdC>o zts43&&(V6Tw;`UK255ItF5OPgLycXI5jUl7;~$wW8p*45^(i1XOrv!tq?5mmZ3pkW zCEmrp^8P@hZ_WSE+maIee+ZkT(7^ekxje4xpE}puZRBjB2SxFHeKLG8l41t!7~%V? zP6j;F4KZHzwE=g-CNyj3TzjptvHhUJ?}l{&YHi%nKQVQg7G`{`zc1LOD{qD!D$~CyRX#q0Fz3vztvt5gFu%MES^R?XCFM6_!by((!sgmxnskc2Bt|yX zDcONeSjBwQl|9wAV7cef>acnT4lP z5Bsh+Bs^`W?HkmgD+w2cfBf!y^K#a?3l(8k#cW1#?)OLWai64+zdxI|`Xr*${m6aCGlDL~BN%7WS;lTN&F6dD21@x=qVox}?A|`c(z{gqhg>tP zfl(e}{O9dX6ZP%w291+lZ5t$ZZ--avu9m&5z3O~A=a~wt7m0g?Eb%w5;+A-B=EpU5 z=IfqevFEQWZIYB|$F|7Qp%vckAK2jh=5^C@Nqc%ZTJtzx)Hg3 zahh3^cDw6Ptd0)?38=39o({=14lYv%8KExKcHGTWzeRn%U| z-T1img(#;{MTeRD3%rV&Q_^6XtZIb?DHvI1x;GBwAZk_CG<$n{dKEwmKR_zMgkR3e z!j$5J;>w}ZSd%msxw9N96O2Kq>^p=zk;Pw!y;do zwI?#V1BnI@%OLa9%B!YtXDO^pgUj2nX^|fvFZ_h!h%Z6?r1}F#r+D}a(~VI_pzLs4 zWcUKbmQ&6N>M<}k4z5`Hi*JDROG6u-I2=d)<`;{fynoHr)ybaa#GS{e_D?=>_EPt! zAB+(Jv00V_;5QE6Y_anyf1wZv7+=V7S;4YQ~ zmZftLGp=6|(=$uV-XR9H>I!Vch{w)TBWL!+n{!T`D_F)w*BQ6hy*?qurWyvE>Bi`A z9T&U+>~{Ee=3x&-VdDkkVfjYY!4Cper#^k{S3m)#iI2i>cetKi=&Lt9A<18HErQjTuT^kF~QR+fO zi%C+NZ_NiUELq7k{B(6G8lYMFWvZ6>S&gpXnBXzJvifd`ImLKQ3XWpf;$w4zxk@{n zqA5pOJS(1*e4XBvn=+@_dFheayX~{@$v$vFeMHiIOAW0^84VwF;=g@J==G)3@$SEH@h~p_UE!Ipx4QFZ<`jzGW<8W2y`ZQDWSjbv z-{bgVdUdq5s>&Q3*dgr@hhvw{ zYu^*PhW9d!E_DZ;&z{zo{+1V3ZZ5MlAiK8tmesZP(2bG`6&3YkJgdLAH%hE_Z2l7( zzbgK*Yd&onFQD+|FDp96+xNXZ6SxD%?Oq(X94FJc zEM(gAhR6ThC00Id|Lrh~n8f>gyX7ms?;xycjna4-7TtI}_>&FO1K`W79rJXuk4WTg z%~hjdHj@}cA5KK-AGJj^>IWtHGkFTuoSvb))ccTIVxGL|`y7jdhP&#NV`DKER%Gc^ zt5Sxy4s>_HsZwhIhOT<^9Z9dSI1+>myeL_Y)%paNvvwvIBF27NQ=N0h_14pA5A1h- zI8wtyi7xPKwL`!iarCUMTjv2e-{?2D=3V&hf*1~{i*%BJ|4o$fgE(Qrkb_lkre#q z^dt;1nSN+FueR=_KiMR1zdacprboJ|y7N2hY_WP|_P2kWZA{NAm4!EYWCT`L62YSa zk2%ZvJjJ38PCUDi7=bJ{_JpA#Ev6i+ROeLZK9r<1<)#nCN8mK&t5fkBpWy?`5hO0l zGcOZHk2A&J5r~{z{f-#MJj5MQ&Ur84);{*2vDU?GT`~h%p0+smhMxkF$h;_{YwMBs z()hTPehuRKj^jm@C0osjg_KbkmtJ~W`?pkY$ru1%ks`tnl!APxbU$cil{G#)jhm-E9%bUfys(Hwb6u-n~!wN2w z;rMFvd`LuU)c8Tl=PT9*lpHS0*K7rKtQ{)B&{@Ubf`IKN_r=Y}y_V&eImK9$to#0Tevm#)bFyRD(&0WP=2I9%G@w3F93q1{7htue zd#MRKoI8xYfecBL$l8qed+(~pU`sG^taE;DB&gD5=?iXSFlZVI7Y?_N94eI$>g$7S zKuRSW(P&Tw=PafZ&dYbUdfT)lB(GPvjvcCfYioy%4yYxn?5*j%%GW*|2usVye8%NU zE;OO!JyfP)o<&LV9PUq9)(=QOyrz%OO7fY!)^0`OVrkLKJ9AsGXh{;I74DSX<>B~IT>*FlL9h%3D z$Znr0O<4o>TI~nMRuD~T*o9y>dK!lE+JcUE6*;J#5kTum6Ioo=0TYjjel>- zDJzY8@`Cr6yi#|Z>56-%Xwt?8Jh%qy4e6vzx|u9q9kJnN;zc92kye$ zqBAnjU(wCF;|`Cd2c%Y*%-9xQ6b>}}0}qv%$NRg|8lNbOQ_D)V{eTj~pVzW0&_5`( zEvzwqnLcf%IJDvi3JnrpQ1ZD6t3h7l6f6N%BVf>b8jD+QNBZ1 z4@(?>c>j;vt^SSz$J%HXNaox>IG&x@%j-aVb-9kSq#+<=AA}g~k6Z1E9 z)Rbk1I67iku9O?!BMmb<4WwMT%-EL9Vp#p}$r@h=K1XZw3k{PghDRKh7(zGI(Yvr1 zpx*kdGm1>BVtyegy-EnxZ8`S%qZ&QL$X^n5M5o@L?ILHB3Q>^rUa(|EtOCZwmrwWo-tv#KtO zU5b>H5a0ZEv_D<1$@AYxA~T+(MS-1Nqdwn5HWekYCPs7sGJ7vZT zSeDIvxrlF?nF(|>Z^Uds@23(!x_@M{g>a7L_T|xlJr%{pquRuVj#np~FNx$J!M?f2 zLb7m7L1}b0yAh*`dOM8V8@D(y4Fx$RqUT&uRr8k<(C`Am1&JA-)nytB+)qCk~)0%hjqIhtO8>IqXt;(i~xN8`F0NMfl#hlc_ z&>~#Jg}_W*rZzm;j>=m3^sVYl5wcYmttWrfud>t8g!;gJU;cIbAl4hAESt-syU!AZ zdxYL@)&`&LslGQ=H>Q}W`pIBdveO)gpGI*YO)6_PSJU=|eHDCPG_3c%B|^B0BtgOm#Pcd;t10h)uAB%xZ5I9t3}o(H{5p^mTkom$_q9oO{F& zhUZcNPf;Yl{-Y~e`_{Lt`BszF7mrpGJFBtQ{umlX=8VU;M{dDzp6{oaT&tA?;n1;l z{N`>h%7fU{_32vTjH*(q?B))6^I`yRT}qWF{o;q4qU+RBFBfxt_gI6|V10VSrx39V zRqF)}{bkCun>fDvz12-;2PBfeIVZiCm5G$eMFNqD_?73cDpEV2u(=2|UX~{(Wu&DU zcOgl0b(;5!j&0t|O6rL}tvycp(RA!g{K(__VZB$@-cByP(I_ zfkVW^=rpkrPxIO0Pi;Y+ibzqh4ang2pFpdhF4oPDAVsc$@p$$xsxS@13d;JT=w0~o z8ZVO-CoGk$hGU55tFw%V(_jq##ro$n{*FrGcZrO8u=0Cvr|H&IPMdkdvWRrMWtYZNFRFE4yW!d|)yVe#rJnG|MiHGN z_3~XOpBDvTqZCJb<=^WOOpE5p{&4Bx7=~F5*1pRO7o%w8UBuJj;+G+`USc@Gws8*Y z3>#0@z?9#h)QyEj`KPp7M(OI*jr(`{WAmh9nIb&^0?Nfg67`nj)ZuZH+!nn%y7<8O zw5vLkn-G;~dw}#B&jng#JxPn!(Uh=8@~UwRt9E11g@!+YLJ?M!;C1ql8iU#L8%~e? zH{`g+RfNJ0&@UrvZ=j^Iu7wNRFOE$54LI9fnf2xcj&k+mb9T9Pgr<|varjvEG^Dg| zW_{UDiZvg9+B^F-Q@+Lf#iq#O9hV9HE90Y#n8Hg3^E(>-2n|7=Bi^Bm7~)U~THeEc z+uxaVTjY=uK27A}#Fn^vAq2+WwC^2J$4OGy=hjbp*w-VYwx@sYBF9-gG26Ubk4kDQwMQM2vhxK&bScYUq~Z; z(L3+tLHjePEoaZP@6>7K;rWI$uRpqCWzSU|;u@`@K$>HO_l@lb{Je7s{6Ux3d3GYE zTWYr5=(3H0S!&ZJwi_mb%9*4y)vE%7rvt?XTnai`zbfAcB`<1d0C9np1|8R<(Mp# zSN?`VFRV=_TI|h7B4ZeXshsM%w(HgpogGOD^722uJHY=e%J*izg)*tL+z$QLR{u#j z6;;@kS675I}fMO(DIMLGZQ{usz-rkvS9 z6BARb;qb6@H`OlFk&tGqZ)nc|>yXd$DZxv$K8r9Kg;d}5H7RAj?0xC8_)o7=PF-vC zcDriXRnwz1|9^kD{piK&b;}ui17m*tfTL4P4&a)Z!0mMa<~! zeG7`#WO71Qukg4oJiTWq=%8M=!JeV*O(pkc`IF-6wr|cf-WL%)N8$j624^03YNZ2y zWslv`1Myd9YJbe?b{#9H`Dl4atEl5YIdy0^q=5)nIfpfNcH(cug;CZcp_@u`LTeX$;UYCH485X7Pk6XJ!DzsBy;kX zx578Em;p+iB8KIYYF#0zZMS==VqK*2JL^Z~r(FGJh+l1OgSAdO8v=whey3x#bsGhF zT{DPGkFkZx?gp=+>K`)6yklLdhgSZSMIsfnf}rn79HyIhMCuqi1&K`Eq-k!cCNHRncnA z8$jGMc$;a@PzaB-p0sfft`4eBLu#TitKfR_txMhxdk0#$N$Mt#II0S4Us07YG2vc) zzW1lSEhGG^jVhd*i!R4GwTsX5Tu10#V}nKRY*1;hU_Gf|Ea(bgvn6h1S7fr)MG786 zoqZ`iQs%w}ROALQFsM&?xKkF2sEm*ZA;+esw|dPtY&)~o_}zCI)GM4rVg@V71hfUu zBgYtEn>DWz0~oXgl|H%i;_0}jXT_SkO!4p8*l~IhS(37oT@mP%T~xH2Y$&^MJ&W#M z{8bdZq95;8ZaLgY`<=z>AXFhahl>g~+y}irmf1C_5zm#GI`F_`s-ChgoR{B2irVX7 zk8y5yTh){Q)5|iZ0xP-zu{$qe@BoIH;~633ky*c+3$i;WGBxF+Z3?;R1m@A5>6dl( zk)rMVU#N(Twtd&Ft-1!4_Sz~j#dgX*bdJiNHMIJ=Q~ao(m%^J_y`b~MkKUSv#6UK- z7xxi8BaNJ8JG1t6e;K!H#@A}F=y)I3vO^(6|IIngy~S?SCNz&H^8tjh=gz#COrLqA z*iI*m^$v{ay87B5{|{Gh9TZp4tPcYbf+r!kLvVLr0tAA)JHg#uHUtO`!QI{6WrMpr zEbi`Z-$~y4e!sf+RIz{T7E^O(db)eMpMLtfua3pyzgPfT3DZv%M|` zyeD$jFv`QA!DAFWF7+GcWuozHM{f0UId_yo3B5c0xj_|f&P%1D8S~NK*Mbej@mO4~ z^QIOzMl%O{uF9oQJinx*R2=@?>J1zk?9VOEMPsI8ihQhn&q|8l3HbvW&@-B=M&rTt zy>2^?_Hhv>y?)ilY?g~*Z4sVB7yLiRwAL!mECkZJOD)#Gi2{VTjFHI;fca*Ase{=E z``|PF^DZBvqN0L*^GQfZVm0hNIg=%EAhSmkJ&D>7f#1rQGvdA(l$>z>OUo1 zdm5qbnU5*3+LMmPA5k*kk2ff`T8~{3c7sK8pCB1%SxzNRM)&GBXHrwD@ZmslbQ;3_mp{O@i>XdX>jMXj@71_Fbveh*(R8(D@^${2TJN)U)Fcx)9R`s zhFi#uJRKbDC9b$?mnk*lRx6#ac=XuhDv_6iE1sn!PJx8AwU#QgOO3slD3Ei@+T;b= zfYFGS)zip?$Nx)a8q64ZmVZW?ZbCk-vs$FFaD8zH6pK9R!Y6pC_7tC{?tT_M1|y3- zU&QSnWM2XmCL|?M4#Ep{922GF2H99=C2rwNH{3I&C$yaBm(SIz(!R3t;{F$3^Nhaf zUcA1k^{=XK4GK&M8|2AlYXlsm>2Ft%o+jkdRyqmc^zq$gaL3yDjE|C)C!aQF-0QEL zVM$>e)@|I2Z2c69HB@*?D2mMCj#ecLIb3W(WwDP={w3eC2s?k7tn9=P=L^xEys2Z|M?z zu^P*O{T4w8+=rHc3S;e)HDHNeJw831U0h@f`o5k0i>W$GC!W>BpxpTf%?LbKH_6l~ zOD=sW^mnqg2{AF~V3mN6NR7>`HMBA>eMr|B@9omV=SHgU0$pRm7s!bg;^zH)a@{sk z6jo*v$91%`ql%1Vh(D_}%%mYW=p1p#{W(0tZ^#(`|0eYYaN5?c{?UPvbfHL>)&Em> zUyZ6qxLQ+K+Bhv<6p^lN!E&cAjvVtzbGt%k--CRpZHyASj0DkBONn?l0)L6k9l)m zOA1Z1hOv?6HiUrCOr60V5(${#w1kWObAUWQ|M*+}{NLdV9Aje(U0C0iTtd9n9-$v! zBXj0_f*2RAEF9aLOu3Ga% z&wr-v5Cv28{|0`aH8CG|RvMUG`%=h1qaG7SZ0_bI7uzS6Rc{F!#{J%$z;C9zJ6jz3 zlX}ALy>jyAy_Es^ly}c=>_m6GRasF)5VZ@pm8ZPfdKR6ME&c6(r9~X>FE!79-ypEK zqban!SV%~S%W3};5V34BV|^}pNT%2?#u7kd)uQpX4z{I#-!LpQCW|Eifzm0dY7c@6 z%3{uxNwbG!_g#7Ed=6>;#UhjAU;n3Y-R8%o3bRZbd7)?y~*^94C_|H6v*n z=bvFoU0lF+&er;sBf+YB7z$CP>_nFvqPT1KYuPho3Y zA!fYdvl^fXh6j&sR=|*D17L^OfZ_;>wzjre4{Ts7Qg){bC;xj&AT$4?%H$?irj$7y zV5YS?T-fwRzSN?mCGFRXLYAMa)({ZB$iGbLwEneIWx5cSi@o(710YYL`8}Owk}W8y zm=N3PD}v$}`ChO`hK5N7uJI7n^Wu`=n3BhLPKmF{gU3F&0ELFBsp;9u;?ZT~U!`l{ z@M?Fl{^W`<0GJ>=ko0_4PhI~PeQ|CzSK&j*@19XaQ)J#IZ|G)yqMvBJG%NW}h`0c= zrK(b{bL2>P@F$jv7W#XgjS1U~CH7vE2wgGHq=2FyAAkCDkKpG5efjMjl^Su4PoLs@ za{Op^KRPiS3*OO@dzNkie&knCU~#_@q5D$P44Cy4`jg+{TZ`$3ge=w{w`(r%0Oj&s zVd4`1(>_i=pnA2isE8`qf;0M`v{^f243pNrF0Qt61t1m(PPWw~RFWdmO zFgf=Bh+S;4mt1K+B{{kFH1m_H`ptPwFOM&0dr?-b6J`-dLpkuue~*m2oNS4Eb;AD}tLZv7;HlD*yg>+}A#`bEaN)985llXrUpx z?csdt(`5MfQeSf`P``2`WyN9XwazCzWUN;hmQ!b05|7yt0F#*C$SSFH>FWvRfBveVH$q`)Z`3uR+Sfqb!F5TD_nj3-26FmlO*>SG9LSs^x> zVR3<^3CS{J`DSYQv7f!2hoV1Zc6BrRC>;TFG1;uf_)iB9g<;?+nNqZhS;6r6Exc=0^B7 zu_>wLWBFIF+xXPiIJKZZ+FqVLX3DfZS_A&6yR&p-?YGm@#Dy_3wWB=I6LD9S((jOH zy{$ESRHK!6nD(iVYDvpJ2bv?K0Jq}Ikn{*p9-=j^B)k|#vVH4TEJa-f1NiW8PF-!_ z#(J@CIJXkOr8Y2YC&Lt-k%B#Mxmt0jGOe>IzWN1BoV`5vZco0MHM|%p+2jasC#O9kuHoFD;90R{ppL0B{NlNMj5r@>zwa=n0vbU!0-$d`vM12aWW`< zHf^ESBHoLwEjl7X%UVow?a~F^Oud<-)?zx#_zS(zB8t(%xm8Nz_MVFNSh)pN_|u{)VA-0T$a+?C2My8kiK%+Gu)Eeagn5v9 zuU#pFf0IKZn+m;No^HC)5P+VjfUIkQ4)h9~g49*xKU}j?TY0!)!pkYgcAeTv$>+Yx znjyEbs+K%5%G5bxX{+-AauQy_zKz`*!K^QU>8{74t5xlpZ30`0h`s&WY%Qdi=!>!g z_v!fOUwlm|ozjHcwGk>+mNR;MsOg`DOXs%3xN!{UV`P<3<_$NoC7(IAqY@4NthLIJ zrO+06(YGZamF8_Z&LS+>0V>|czvnx)g)soQ77?v%qH||nI z9Y0h8hYx;}*f%)PF1H;r5it_2W7Mz7+CXbdX(KR^zQ(NCV91&tl`dkO>)Bq2ZC}+# ze}~v>yDmwA=8+N+&SpH76`^+59)etc#T!D@mOfv(Gk6@W@kK?Hkb*tBD^<7p@&Rae zCpyH2%jR6CT!s3IJMlU^z`vt#IQ_y(ANt$n4$W72FvD{H?nsYY|ss zwI|{mb@fkNp@<9IFH~6EkFz8!kM~T*+kBXO6Ca3Begrd9`VP^Gb29MtuB4Z5EvO29K5{EC8|FuHSoG~~M$X(hCV(!h9d$8r-@LP##-4XDze*WoRUG-Xq z9yph@g8#^U0%=zzh?G=)i#d^&&IXZQ3+;Vulk>*W^-wQZ_&j^ELX%ncf;Srb$LtKd zMB;YAI5VzZ7PZ$L-L>xbc`IN(=~B{QXG_#OebGRsH9q9&D z+C~(!k9XEgRyOjl7+DIeQ4jLjDX4PbPYzk(-W&#+iOR{b>fF*3g+92|yS)2=_81Xc z{zQ~Yw$J*#+qZL|JifmMvj{oott9TiY9ANTY7j z8Q^BLhktzZUa&Mn6ghOh<4t$pvyt!KO_z(IgOBQ4zxPvzBF<`6;_S;choIkjBOjVC z-ueGXx<^~A`>e>i&#^Ge*XQvnX|mwT@VlbY7ji~B{_TNiazgP1{tJZ=CFcC?tO>r5Mu8BJR5YVwb zY(BNSpPG8ZqlKsc@jJ`jRbdU|FV3^`h}JWoMa*65^Y2RQ6MPfXHR?u8>SrCDW^(^K z&Tpzne1kX5V7OAN_)8S;+S2j%+BcK))X-iq^CW^fqv!Cz;{_|4eTk3e@;ig-}}9uwCtf^QKq`Rz_3O^HThE|{0TEGdndHJ zg}V@~eyUK!bjPlQC&9O9yXqih_I5vq)1~bi)<%l3`zbr!=nS55a?pU0cI7s_Q#3Xv zJw4CP7AcQWx4ULB8GXW><$`FxJ0U`WlpWKmL39unes``AnVqPoVXlR#aJ{J=aT&N9kzV@mT%#jI zl1fj+=KfBrnJ(a+tkm1;y)l;ifY;-<{Z3j6^yzEFq@v!US#WtVklWkBMN{lgU%m|E zPQ61UrK0*700DJ(rSE>fJ~Xo>|f%+x|UA>J?hQ_Z=N(Fixkd?Z||Db6c~6 z3jN#_sYDE$3I?k%P192tt;fG2A}DcT6dC$e5*3P~zS-LoQcSnBeD7P|9LUGM@n*65 zCTr-r$YUDA7ZuSm93!r45KP$V_Z-%Lw{3Qe`#^r|!f4p98S(xjXKH1+HHkF6#!e-g ztM_>N6gF2<=J4d*S?tc8IRxQk%+$T^niva>2iYTrlF(8n!zjV@)M7IFnH?E_@e~U| zH1_ZnIQ7Aa^s5D-u6-H88#z|zQ^-qm@?F3plhN73&|dUNvqAppygYx{f{U=r zG1uZvdV7pZf&iFX+J0T8?%4sB`~tkC zSphBu)AdUq0{p?#e9b{yXmC&EUf8^6(zs7#w)?7=9(nchVh8yo^|ckZxV4_i{W5NF zu0okdcG;!X_P2qyRD3a&FU*l1$3!~rk7jjBczxLsPWjWN{HCg}#_IL^<|thYgpbyT zIzzoys`={`_pAzO8Xw}Ax6AU?N}(eqoI6Z%kY9x^{9Vn>4iYAmxY1nL@xeA1@654M z*_9VB#(s$1FOOr$SnF?;T~JYJ&DEx%U=`VFo?I&_N^eq_=*uaMH7Mp^knx>$p-W*y z;i{sk3l`Js)_Cw0Mk=kZy`=7meKZLZ2ZsdpKjpH<&b8cnr`($NMB3bYE+|2@bY@cMb+1N$z@t%nj6KQmWr*`xF*V7 zK=$Ya6@aj()Y~HeR+hH7)#~gG<6tTR&*O>Qkc(7cJUd0|`nSGT6;oHM)ITJwx5>{P z_|Fh8J2&h{>%Es;o$pLqZYKCd>nfosC^@P_5+JV&5n~jl4-d<@46o7jb~CQotd^2N zk!ko3=1310boGXv38y18%kJI`qmQ~sk1XMKn~ofr_53{r$8A3t$6q+Za1`Mu#)?4M zJrETBhr7u09n9;L!JSZWU<*h7d(=xjsA-#2`LwQ;a)omC+ zw(Se99&s#A96A9LtWBIj<{jVi@w3j=Y`~ZyJlq{+rOjw3DINey3PT8LiX3oz_H@FH zV=Hi>lRRu7+d9-?wq(0_2V1<(_z4~i_b|MErJ8rT34J4VgdsK%elnk?S58>+_Qbrs zL0(M586>g(7W8b%xLhyLo0UN6`u(|hh;V&4lM%E!n`66hRrCt0uIi+V9Q7C~QI}7d z0_{peFT`K0j&8x_H=7-6bv^Ro$2?twXJqlX{(6kuNA5H$&VYT<*AxS<40l!u(l_Nl zD_ukNH#5Wn=X)r)>>haD_gl0u-RT^=yCOezT&+$Q(QmD!h&0tiPNbM~d5q4oGsW~9NpB`F`r}q$J z&#g4MaAz@xibKMEa(#nw1s0YC!f;0UzDN$^R9z7yHrUd%TJV5isZ7>y*9V1ndHFkO zk@8P(FS+@glk1KA!bb(b#^d*GcF3mduxX{(_g$>e#UfPgyq@!mX+oy57lWOTd~aRFnTt$nGn7wc)*b^mDWkaC-+r?2O*l{X(@2A{JhcKypo4>wbo( z!BqQPCE4_4C9_VwpzN*ukqEA*#zEClt~Nov1e>+Z%*|i+efr^`f4wXmuYkM z&APKCc5jz6=PY$c#@m7!bh$ zr^({R*x8zi*>Rcgm+D>eQFGn7izm&pe5&cX>N$Pc#dSv~ifyqF1_8D`5|imuf&3_* zeYBWNJ)$bkWW(Ia7{Xq(IV#No`1Y`pwRXjc=3->*$JooWRw|`C~#c3fg^k_2qKUtO4WRAe$yT2h9>0!ruw+|?^>hEC zufVcBSM{^-7G7v81#CH!o1*@0D4VgG(w@2b`egNB2VSAnwFpnylTVPkOHWQ7$)SJ1 z$zEq>-*ysKbc=fgxVf97`;=$yk@%6JA1M>2Ct`}bQ4JY1=_>K z>j!||`YVHTTjqL7a0TRtSAw;GD^D$AvG}5dWrC`xX%Ub86 z9ZKnJo4MqecSX%eRY*qF0uVuN?a0QzcQ1J}ej|cz?9{8SSx@%VQ3Q8BOai%@-ikHszAY89|N1&lGQCbU6YXIJK%vNt1tAJI`7Vb-Urmsw+527BZ za3M6DoHX2J>jB$iF*_V@9FukKscazQ3EZW4Sw{|eJUZ{2lT0sXE#NlmqnG~|3*fiB z9%2F&ZPR*2=%=^YO3Rbs$UVy%)}P{{DIYEXIvQKn=3$W0K$oNd9KXONciJ;Myv_Z>}bbG zxBGDVYV56ixi3*#y4SGgg_j!G8O4UE&mZO@iV!qiuy3|H6h8dOpT&LjcrZ~>M>!Ai z8tf&)nkYI-MK<3m@GI+nqr&K(X5Q*`_ppJ+eKecc|D?H=+4@8GH}By~K-i+}1S?C5 zCLF&y(F2IF?Us}K0IQn%O$+Rl<@2*XHLsVA!CFNoTS<}dNn-n53|vcb^Y1uIC%P!k zA^oo6J19F%()(2SLNp z8B(hg=DIh%@})9eKzuu4UH z;%cn%vM)Z{H;|FViwE=)|7aM)(@{<$dxnw^N7?D$`(I__j8}tnaKE5SyduG$;2n+@@;~Oj~>dJ)vT}H zzNy&vdWSm^feMRTfm0n-7eSBrvHuOK*AvYo{~pWBXdjN2uisg7k1+Yf4~ZGMz0I&+e>E%t-!jGa+DoJq z|FNqjGt!CK4^(snj}7j<$>{4ae)3mW6p``qs@ujvPCur`9sU}gcWX^KIiCYsW$4Q# zug%PwHasM*c-}ZLj?#;a#s+eHojG@GLS04eeAbv__b@>*bG%Am#gs=?cX)1Dq z!orjvu8%yzI7~is@*_<*;Xtj<~GhyYzl` z-P6{RpeJT+g>ez+-9gz1!hp`YVG0r*ZVo@Qmv?vHael)@_x8t<7y5zMeeCSgzt z-d3@mk3HP2Tf4k3O9OvGWMQQ$(LhP3G1^f;Q8(Od-Y_|t!*dXqWb7i#z*P}_#dL#A!g3AK7ioXPspQRICasasP3(^qcSB zct7yso~0`(KU-U-A(Z9yY6G&eb$P-4U)>)iFTtm@Nv#if0%0~9?FR_49VJTkHEl{4 z6UjI8wlNXMM?EdSBj)ZPi-io77s(w!a(frr$XZl{2`@%Jdc;pRS#Px{3cwD^78?$x z3LTc}{`D#bI6Fy5kcmL}Kc5<#Lq z0OD9x4FC^wJdW4aKem;(oFnR?QebxVz-`khc}Yq2^Mw42Y-+emc$I@%$6x*4N{cb3 zAdDeQ882T1%Vtq(``m0}_@Mf=T&;?F4NtP=)MJ)c=|VY?9)pz@)3G#6(+(j8&&@j+ zhhj9g@`o<#qPCaU#OeHiARB4>B2P^uUzDiSB@k=4cor+myvT+nQ$EAS*AnZ%PM;OU z$eY^Tpj0Ss1C#+}ps;1U7jsk!Ad#L-IXxgb;?gl(os?Qt5i5Ie90C@Bh&d4|6(7r2 z8nGSU##NKlySp$sUy>f{R>gg@@kr<~y4TZfgl<5p4qFANYEm;w+s6{D*-*xOL?c|- zP4HZ<9<#fbW>?lcaa++)IXAY0z*iFx%bBJJ`6YrF#pFBd{s4UTIQ2l$Y~Am2+@RU>1bOSMK`%oNfE@YE~@Zy8#`Bu=(MCTU+s+7c=eX4>RXqQ7Syz0 z9o;mRyEy7%R<)(M^i4!rNQeA^w%vvUCSNVz0PO`3*ae(R{Az}^11ehOxzU^&01A^d z7Rs05cwII^u~DP+r?OzPlmmpCYbj*HEWI9=g{(XaR}ecq@oKux(I)Y!{R)Ug!PNL) z3IJ}Z{wO=@Ut+ZeLbf*PMw9lB?hh*pO^|%sFpA&1{kqj6g_7CD@A=-Kz>ZI<6L_)D zcpaGvzdb+4dPN|`9<|FKLN1vhcp9tiZOX^XWY@i;q3I@r&X&=CMc4&S!qev$W$mf0D^N)SCpP(`8)2WX?WF#bt#_o|>jaTa?>|m6mu>%$dma)I7 zSf;2Zw}J{VeF+6$7uvLObQ;mA#6=*A9y41EVjz@%e1L%h`kMu>6#rig zM0Ue-gO}BYauS#s4%-Sfx#}i43xopNDcrYai^89Ve8i-qFxlyfphxB(wJof(eibqd ztIF3s$s8R;7=ivG?`)@`0&xobvZdlL0A%5PxY++0Uj2r@_BY*^2RffG9{5H|8k61K z+(ScbA|p+QcG`?h4Gk*+vuME$_M@b&!;iI^S z3_$&)4~C?WR0nTWx~2z&YPYFgO=q>Rv|&cp^1=3d0vK8O88Fk2BE7!R{6D5%q$;okk5b~Y9K+HVvQAH1LZTdDI9OI6r0f2YTP)A0tq%{>(P zmE;y9E%4Ic_>*?|6#$C+!ft4H_MPIF{j>D<0cjHMR+#2$>bK`eq1XBU|L&*;ImH!P zohrepkEq9I)fy^jm?*{da#Wa7hiU5I=&DNIs&E|Wm2iOCTpxLgcj`(8Z}-FFFC(0k zdayoUr~@o9>MyMTNP%e(ekOP0@=B|wOLAJPZp2D3{pQA?#e7kEtvn)s45F^RKZ8h_ zvuDNE_$bSOBRDKDY9l~Ix%Aq+hfqZ(acE#^596IgL5@v|ps=hgA3t9KrY%w{QIP(X zZa;Q#-VVWYTw+Aq@Qh)v;CFT}G+p{T|BYX?%bFxzkT{9$wg~LSGfW;wQ_;n7$@ysO z9S_0bty@mTKx=4tIDHa}=s||3cydE&4dbXmAQ* zvs+fHK@@KlW1hb3fh$AHTSGNM&IfMc90A|&Q48({&_9+>H*f_o*z?Vfu!ApsO`?g4 zcla92K^}3q4JXmsDI=iKH5(!_HdcSQWLQ%;_sZ1>h-;+_F~*a2T-g?qrML{qS~~mC zL2Bo>8|Y{;KodE>IR(1h>LBWxJoZP6%5r!L$N|Mp7# zk5Babb=9FmoVZ#47bo(N37wfdpiZN4&@5UD5?11;vqa-FBdBPS>kc3Qn_CTzj1C8O zWPtxHeKCb$4-ELmzFr-#>Oi%!dOI%{LfXQIqO(M^CCRT5dtldwGeU&&yzLA3XZ3o=|xyM$|cjlnL z{PcZEg4UzFo67w}lUqk!k_=nxCrQ56TRd;Ab9^+krd0iimxy%q^Fw&=CBD-$v<%Uu z9!DHdfNHwkPU@^Tu^{Z^*-661kb<*eLB_W2Wv_@7?nFS_4X9^O_i+0$@+6V>#Ne6d zhO8U}itJqp+))@YbN0M?I~oQ_ZhQL0>elZ(f=5L-yBSe;x--joaa-XH<$iYJNMoou zWWLMaP`6u7lI1Ni5En$ZttXg)tPGZR4T z!LS{SwQsoz3+?N6N5*WK6OYA>6sZ<$HCoN&0cDL;kkAuISaqm|B#th5)uE##%!2*n z=f7lE9cjQeDU-Oasu3z&yJ&hjc&-;nA@S70#7-g$r$A_D9_1XZe zqVJ#HIbaQczMl{x)I7)HrYUI5pTFGxOu-BALP?HNt)eRvCj48!Z|NY3eD#yFkx<^k*!VDt4C;C(i+5@CyZn}~JF^bt*{wJQp33q!`Vw1M zZWtVCd(IZ(0HQRz(v-`0j0C}YyPG)B!l%IA<#~xF#DP0CW9S{WraAIfqknZ{vo$95 z8!k{;{23}D2}6L;ej!;7TY+R4&9*Akd@9rXnk0%r{i#WDcx$NAcM1`uL-JJyITIJ0 z5f~1uOt9GWfA-;hM8%f_5k(q{T#t*26SO3k?}>@C z0y9VvKf~rCWCfzU?uL7J{fqR&2WF~kXQkV40*p(1BsDlvakaA6pVLO>2vl^>(whH#N_Nfq^lj+k3E6O5wTus?u#~jrDC^=eLD(NZ^2Gm#WJZ zoALcPa^#blk4RPx`$gCc+UIy^UER#)GX|?8+ke98@pq?ujwENRCzn#|U|{W}lAIYk zc|L(PrK%>;e(T#vRe*;vC2xpau@KN1v%=mC?FP|-j|k%)Pf(j~PINr-1s@q$AUu24Jy-+TP zc+N>FQ=uhf?{_0)*9bt~ukHOxpdUv`DUp6Yd4;rHu5Dn!1h5R&5MX`y_nhUdPv>8e zsD%Xw=|B0r>h+dU@&M`|Tz`rx&8T>MmA_S8a^frP@8?4QSb>VG$T4c;RnVeax)$Rhw_D8w-fC3EfgfAjf0} zay{c;+Ve4_an&V{`u+&8{nRs|37{>-E&WnyJN^zizw(9T8h@yu#(px^`v<{H9vdP< zqRfIU#Alw-#dwR}WYTNSaQWHHrjP~-*VwFfb>h)jGrA?^?F1`eGrF#4>@08b-P2MH ziNmV?LCBp$hBYKLnL|&Ym0&nzr?1ytxA@99u zz?zF-6eybk;!88tq@*T&K=V!_6#-%MGx?g7*q^inu`hbW-o9^RO?9<2Y8+mIaLWP% zU8zq{BCV2H?Ai&n@`BWD=bxcpe!jQ{1fg?|nT&jF z^L(Nv#I{5AQJxEv4Io5Dc#O&+LW_CFzjVBR)4?`*T}4~WJWTd8dzs|*|_u82$4p04J+_V0}CW0|#b(fp4D@`oGH)9h(# z?YU|@<0gn62{i%wI)n1=_QzX}gyj zcHNaVZnw+dBnbg0|9-CRYbw8g=Q|hTxoeoe={(?j z0vFG1)O{r2O>w}4^qRcz_C+qy-nl;OlwnVW>2-d-IVE&HhIY4gHa3JGn#_)*9!fj7 z-;e!gM>anz5f#b83Uziy=#*z5)`I-l{BOyVX1At6z*jE3)v)TR6fQV2uVjv|l`8d{TKF zp2=O#dU|A}v~O*CToCA#3-?KTW4linb=%G8lPAwh)HkK2H-mxD;1RrCZ(ta7g89d8 zB+>U~SC-jlCtBvPtVY{~h}TXaJP(ZUnU~PYA-8(QgOdZnkiP9M&@BqJ*?djes+Y1K zjXm6*)Aq0Uyw!_xB(vobPFbFl^({MX1g4b3M>9f3$jd8U`#&?+5^3&buhO-~V}i$)Lh0BUm0aI>TXsYqnZo?+Y;Aln7LU*C3`1WroR{R49Wk) zz=D>$hKfwqXZ?dVqz2hH<2__Qf9n{3V)Eh?jhcJgens^|A**J+b*^+W2l)w`16LF* ztYF)>ow`Ix=Q0AwcOvUN)@U*YfuBz;FAprFq)t{_1FOMJDafS5vmSU(wjDw76aHsi0tEpbINKL}BDDa#|ZcoOQ#x)=o{OQi3e`v&OZS*H4fG}3m$U`Tj@?bR zz1!eY9-GTqn7Qq1#%co95+oO`={9exWQ*eQq(Wmy{Ia>igz+#i=u#T(2v8>^JUQ0|tZE(6V@4@1eE*cs`lz$g)VfL<%f?Zz^v6->U#!mwVWl=|Qgprc_)J^;XgGRcL^pKEB6HBT9o) zdqOA_2fjWd=c+kO81&K=+3aHRM4%x|gTn@qcPPSi5@wt#{pUpQr{2$S)I#H0-}sn& z6@d5&{bQ4lC1~W<=BzyF7x%Xxh4gcQql~3`s8kY;Gl%X~F?^(}grS*Oq?8#qyWPN3 z8X@v^b2F=Y-)RWa?WX0WgY?M9|NcK-1@KuISCEk4UVUBYG&xSwKhdrm+-fK9WG#Fk!iNpK%cvCy?~A$5?%_OwNh{b+%~0jxG5f^O!bxKL?>0< zq`g#3U{G%A5}j6DA|fJLG@z;b*RF%9`XZ$tlcPLXD==VLv{wb5C{yNE#Xp_v{k19; zBP%C^w|U`oMg-o7C&U3%4_l(vuq~(!(>` z%tQhzB34Fq3uH8

c_e(a~^9f0rUsBPKan(%RZOHa$HlNh2Wp@0Vw&SM+jkPA>+_ z`L0kd%Q=+`{LQPJP0nbB4U{uxfZp~lT2MRHq_})rXfCZxgcDyktxN6p-!+N-@2Erh)Y?`~6$=_MQ+$nzl&jDrTb8q!q2=Ma`oCZ^%4qpqTbj(R3O zen3Nn_55A1^&`MLlmWUI<^#zz?jsLjVaa7xHUFgOM5nA@%D({jrneQv#nLh;gPE5a z0j3(tF1gW<_vBRQ@t|ZTVC={@;%B5x7#~@cwGMC49ynP3%D%T}Jv^*?-F7uNjNW|3 z!j5a8Bt!#8IU6_)m9FYP%-08oNoJL=zsBm%ot{;Dl;q3|4U+Wk<=yu2@l$-@PTZ{W zxMJaWoi3XmPND=>{`ld;JOnJT;(39hQd}!B$|+q9g{h@E^1w(71~xgS#%hrRaLmL+ zERuhTa(uTL2+yt;?i80SegTiFhbUV%t*=*5QoyYOeppgUXeB+4OG)w2f!1dIMXjZ# z{2}NS>;0TXl#n;Ed9r408C|T+;Gb)qXS2h@oX;r;2u4M6rKs@S(^{{TVT%F-@k3mU zJht`Yr1!o6Pom`4^7vc!@^BaMF4i-v33GCa5#id{1hpd-d!Dhd?#?I=VRYa-nB&$G z&nr~I$4#^Z_@% zYyV>A7JR{#9sSfg^r%Vs9^b;AMJ3=>aiUhwH4VYp4l`DIeLRsZ}f0`l?z0%5zP-*!20u;DeFxSO` zN!#}mU^fHuReF&RgFwC3wVG1OMM}j*EmrE$(Sug=n)6L%TZIy*fVW3U#29izck3^@ z4xdmb2Uo)Jvx6)sw8n=wb-4fJ>@0rp)_EB9r$^}avd6axcIZ!wNlLy)XNFhzK%;SP zU46(iJK<3zfQM-NvnUQWFq@3T^Z}fUPS;Z(ST^2scq9|ZP_ty+N7oSysTPAz0HXK% zeYVZTMVVt-qXFZEEKz?A@An|8=No_7_iK@nUokIVhur)Z3jkJim^mAX`P}gsVD86 z^8|9wA)ZWz!?Q=yb7P+L;yWm5bo8zKbl}lu9&0{1vVNrpL%XAJ17H0sUw3P?NOjug ztOKRPivMs0%(1qltN9GiNU}YD+e_j|2d2yEZiTa2zy8iZV+-F7y7!2w@XNu8VaF=w z>EIv9Pg35|2RwO3XN88*G&y5kTgqk~hwbv<-XB51(8Veq{O%%-_&7JHn0Qaz z#7o1CBGv$s?@>_D-)re;ih8b9&K%xsH{h)1_?%Y3Tw$j)-yRR5uPUXSt)Osb)Hw16a+keTYz{|v8+L1V=dC2 zwu{qryXT+LAkbe!%8YiSshG=dXP$2_kN+g=^6t4zi#2_%BhR?RwvPa+v_RMMFvy<5 zr0Vl9TJad@97 zyPa>hNAI1`-1dDSmhnT2nlJ27A+TuzX8;zm>aIlk9`lsY-9en$Cjvva~(c11aobU{Jcv`W=QYf z_vV=0u$1_sqzIhv{eNt|1z1#F+cqpJAW{NSQqoFyhXIIED$?E3-KBJ=bR*r}F!V?b zokPbU9YYT=--i2sp7;H~?_Y<&0nXlg?G;y?*LhvbBrwRc8J9x+Vr<_B^Y6tqU#D`|tmik#=KU|%?MufPT=q*oHwwr64H{bF?Z<_}dNznvM$8#;n~@&3eyH`1bi zP$RuQ6c>(@IM(6rD>^+ppYY(@=iS1)r8sC!?ZSqCu-A4cs{zH}iLR+txQV|H;5({X z9HjZm%cp;(+1D89)py<;$k{T>)`skSo1qsuI`(h}sHV2qH|7nJEY^tUXwi^isaYv1 z)^Bj=Lnbj*LE8>nzh#&Qxq+!?bu838`4UV`H7(=>$Yy7kMDhBh#PW+b#HIzt>@v;M%f;rUCpkH4AIqd)R{k^dwxGjO2WmjW1o~&8- zuvV;Ehe%PHx*as!(eu)mK)>q=qE6^;?$jA8`Nt0+10pZxbfVo z$7jg6=Rw8nQAfZ+GV)Uw%$JIET|jOgQFjDxlbm-m{(LKNlgzb#`6$Q8aC(f4iRLsq z*O9!-y?lA#z&W;l$GuI}l{(?fO!>HLzBQ25{G8)FndIU1^&uS2Xgr~bL($hcdu4Ie zQ?iU$0#0#27&e_Z2efU{!xyf;-D-Dn4B%!%Im&k_4a_kqP^&ad0keLu#)`h{<8%w}8a z>H=tKXt1SyF+Qh}E$XdyW1l2d`?2eIhoDQPzSoshsFN6>Z(}rFYWdTRXW*)*A$}_g z|EjKr<MajGFL%AkoFGQhy<&>RTvwb0j;E(|&PvrOUjzz{~Bmyg^3E zxR;EpdbVXj2{I>1>n}7e4a38K3y)f9Y2`flD=;M5BA)Hob(s|+trj2OjdS2jyCv*( zxzF52W`iM`5}$nfKWGzdbhv777&|ArRdf^QiODQ3rdlmcfVP(WZ}W1J_|mIXsu1g7&(i3W9omN)79~B`>|7zt z8ya>ZtI13H9YTG!kNw*;_T?Zgvcl~M->dZPXaW7PM}SUU5;CPaN*os!lVJY?%on1jL*+m8ywI-xXQR#%fz@C zIcoVyo|N{dSc=7@u7+T;6t_-r+|>=>H}9;Y&usB5OUd6H@-E)$F($dnb2(ji4ySN2 zUEc!3Laqdu`S**4F@{&LaZo6WDDaVUs&fg2x|+YKQDi=#^k6oC(nB%lKq=Dse_<0s zinQF<`R5U^QtBa$r%&2JUtY1gYj&-Le*J^J)j?qmp}8vNbclFDU(&T95?d4fjb9at zyBdK<)|hMXV3bx|R}s7O6KxAIKON6nX`39zfgOc?WX;O%QyHVkjxoPmTo71G%$lpj zQXnf_$i6Ez&O%19g?em+G&y|T|tx_ z;gQ};p>PSRlAs{sA}dUtJI5z_t#VTPl%ARe2fYl4GoLqWfTv+m@&JUm+!-=gQ~*IR z+!=38Q71x;xcBlbf%9|2NH`zoo%4irT66x<Ij)2Eg?}<4GL zF;8En(1YTeg3X8KN-O5(H(y-!Y*tPKDDgvsq!+&aV7lAy4pF822ohkU?taw)&DF7ph^d@Vu0-i@q4_>Z9=qQ{ju`7Ux6*jYokX~SA&Ga zfy`_;&K;E~Kp<$c4L}(qLeJ3($}Dj9h5dwiVxAzYZVrlDl0f3CxB1R?mnFh~NtMOb zKLhXv1G|AZqWapD951MJ;zPogNayW@rcW|YC#Xg2krm@?qw90lB@>bvkLwDJ_Ps#{ z{^6Xz!r1|YI^tBd%>O`7(FFPcsZg6Bgim6B>PU6R^v5=n@|SJEnNN!P(X-M{K^A(D z`IZ+)c44n+a_X5RAUlsb?N=EBr(40Ez6!ZYa9B;m_Fzx!;>zZYD=$?2%&JYJCis1s zI%QsvGzG^vavg-L)tN-mWHVK`_tzclUZTJrCTu@bxvD1RWGWd5+52vP`*`u<^jR($ zOh83^CRJ$CGOah1-ff(}j8Q&NnR}eUOG;vEPb}^ib%vq(sY9Zi4pH zb@aj>Yzm=Yq3mrW;}c8icPo7CaNirRsQdM1t|pRUei*&$04rd@S!xs@;ip_&m8v8mCWW}5CmY*G zYb0I)xKMJ;i;Dpxk7i@^4pAxlgI3zD7uxbDR@zMF;%@#bFz#@zaDf#IUNpWBer%FrTKr)*689imwP5fYtdAYjTCLZRF9ht_-K6fmSwax z*b4un;ZfvU?m$|gW}&m0d9sAmw!MOcyjy~%9Y&rhk$=Hcg*%CnlT{%=-k@(F^Ee7X zT}sP*&7@SWovVR)YjzYdcF;_!c;21}1x+wBmASDVr~+3+But|gNV(vaC69y@TTz4> zjXf@-oDYo%-@U{Y;^#)zb+kNp5a%}5lo>gTyS96Y+m+PstYek=C8JUn#1J`IzSzHK zFHgO7yMIBn)R5FsUTtl7J=Y6rSB>?9Z%4rj4>igN=-XQf%r}TyL;D`=(9T^=Rt!BHCWLp~SEY zQOV+PRF+(eZHFqJX}cXi`*JukwF5g;NY5GBv$BAGq1zi;lWa>M3PtuI_;tFL%Ds9Y zZTdgQe8Vc?1WIS5{4N_=ogCe~@(5pQ;mwr~>ijHkBBaaYFzSW{5?&Wo^)lL)_U!PW zCla5k?1_?uytY4eQK#aayf=MyCty3j8ED*s5Ty~M4f^@|GOx8z+kL(Yiy;KOIqlu)q^Xd-P z1X5>z#8A-bX}&tbq8(cV>7&Ek#n=1KoNN%w#N@qy^0oE1H&`piGV-9e1B95vQ9^9M$LCf( zQHqk@8`p(D@MfOr+M2O`SRdx$U+jHF#un0TeQt#VOVky9kuAjE($yVI)?nL*e@nPG zkkxa3q^CbCM@EgugG&m5ihKNV=kl1GAwx>m=am5Qpb6*b6aAWX1km1&ELW6H* z(XM;*cl+q*au^!LIs+ILT0mTOu7vEXFQrBO?*H~aHZVFSOi-xpuah2PVfEd+1&Mr? z;;%oN@*G8KBG{|LkLxt>xP_3XjrRTC^LLQQqds$vK_=6SlkK^IE$T zwalQ*Kn(8>Fj&6JY`>Fi*O;%(uWa^_N9e~aDkdG+kvdYp}I=JD~%1>=gn`#Kk0U&ZRAbTx24 zI+8g6|A+!7xlDy$+mOuZxbR1UT-hu2uC57yAdnt80zS-vRT_G4)oI@aIrzUni=vW1 zdyGaT3QJvm+)gM==sZ7BWu8D(vugQklSZiCjMd{2&T#v-V*Msz2@p#_MY*#{EjfW= zs}55iByuQaWMpXR=(@+dp5a9s{2l!r2tHe=GLnhh(*PFYx{HLQB&UA&lLx?&xZtxr zsHjNx6}!E%R}g8&C8H-7^5OE{NV-MshX>CN-&~ejq$%bBp^jI0nZ}ItdVmF7v^q!@ z7f71sT{IIGQEam}7Lmjdt9V@WJX36JwD&4%4f8YWzK^AtTGhiz=aJ0pN)uzlUkzI7 zD~PGyr2fRN;vYq=)_^&DTm_t!5&5q<3H%@zAAr?@z2;Y5nQdq!g#g|F$RbF-P#x7w zRq=_v?_``e#^3`D?c1JhA-C2RnJut*+4>CdK4!5A|CsLo?$7Nzjk?;etkx7-O1qta zeO7baC9gp_qp3UO%Z;NX`i7#8ph>-5okgOysU5~rz)~t@-95z@Yl%8w@jReI{mw|< z4*4gJc7Mxgv@(a&LI8OLq9cH?LTR`r`@7Ba(RmX+orqsm^Fxm-Ik*kcQ5ft)kOB$H3Y-^;~zp_ae)DlF^QR{Y{$3QV@#>o<4a%0Dfd z>0{yB2kOwL#U_AF@&E06Y*?)>#b`h#0~mjAUgrZ4UW^XN?0!)|#&1O@Dw;Mi@l7H8 zg9H;`8^8Vj{ng%FtuPGE6DhgPKV*b=pfc$S#7uyg9=4{sFkmm{gk?W)TI)dve9ut}wzjsqf%Es0^BBRjG~kg^4SwYk)h{b+$zYnrxAtn?2qnIM+$#BB zrDs6|ZNtyIUe5Us{9u z%N!)lEJOL^%-jbEm4+yHQ~|ols?~I9{0HEFvDJckKRZ?_cOy(GLwT^02ktHbV!qJ- zIxq3=&=jQ&Rgo{HfLL1WTirtWpA{>;U=Qwfb9=%|wC9x2IK0sVyavr_O6dtjkqcfS z2&=1L?Ef9huNi6-ICd>Oek|p2<^1T~z|%m#Ojn9yYiSnc;Ho)#K=1FTHF{NZuW9O{ z*0HwN)YFcO{C7}Ls=(9Ftr5X+X{N%YHVFwd1C=A+U)ip^Z;dGh1?A@%NCL2_#G9{j zWWr6^+(XDroY-9RFal6hBH5kf4DW6lEksO6*mJk%MZ?g_ZPG@@&Kva&^e&Ipmvl}r zZk;VxDqqP0(do5ZMW01FXY>J`hUf+-itpo1y!mIO;Ofx&s6zM-&8d$&*ks=BlfcT# zil0Ak)+Fg86688#iTF3Ca2&kCd`<78slzG1z(4}ZsW65;2rQ;qTYt0{>tsh6*sym{ ze@I|LjZIGvirMU)wEsX@pxrgJFUj3#q=&^`IxBVXgjiU`d(gWsFWMwosE}EbCsGv5 zBPR>`DS})e)16d!Pf517Ro=~>jay*ot@V+HFUxP$G+rL&DFZ%m$Ht<4}pDe_VeMl@)dyA z3HoC?6M(_n|b#5_4<)nGB`aJ*#^aU@|2oq z@Y8oyl1JzcCR2!%nYHbYQAz#fRKt2_-pZ9ATZOVFBbo$99A8$<#3L)V8}>izJN4o# zCMGJqvQ7S!=tRff)~trD3M>RvEpc9@@K`eED;>I4!9d*jYyXW26is{hDOS*t5j;P* zrOx_^BG`$s`+=s0YShJxLSluDD>lJvWk_2or6+h@l_xze97yd`mDWnl*1gYHqu7YG5$w51ozGfwoLTPw3o0~yI&e+MJ;u0r*XxqJ%x85!5s;K6*a5S6E?VQU9Y85lHy&M_7;$)zMr%G ztylWgwYJxK-ZkH@kyfnWSv4Y+#B{2Cv8G4CTIgPSqY8WwN?UPms;0*~h$w69#~xtzVw=J#lpQ#bib|jxv?VPHlc;@H~0{rJDIE+a03<>x`K`^ z6_vGr{OC%FrxA)cm6Jg-10;OFb%)^l^qQ(?Vy=0cv(fC}H4;{PE$Oduy}ET8 z8H_u27-Tixwg1p)L~`kfkqiF{rPTb`y$o$AUc%FMTb5I%vNdRmJQ7^pI^Uvey%%{d zzq5H2cCuJ)Z6yaUQpBGSx}9I4|Tu;rT%9Ja6^>%Fdw*7I23k~1+7zhh9&V49DS zLSC>t)e&lQDjNE;t4dn6@+ZbZliqFm;Jbkh5zi~Vn1dvlfujt2)9H9s)1i%o;kE7D zoyL3>_J>OTOkcSnR4%riMjn4-JJLbOPT-*EboV;+4pSW1Fl1%US<22T40{fHvmcIj z+>?BB5{dS%oMvSOD1)O<4Q}`mC_cEl7zlnwg=MPdDed7v+dO}Rp?UtA9chC%4r+~o zcVYjX_i^{y9#YIeLVDKN){kKZs!eCwtBA){u9NS+2Fycd4WssP-gT=oORa*EHNm2D0wS=bnZZU+%O!rs6*xNwihW=PFWpkV8r11&gdn74a`_ zzFgj~h+Q1^?#{bmSa|PUaQNTNwO#yuoTbuuJKpD1roJ0Yti|54;M5b64YiDoZPe`z zyWY7$tW~JmsFoTs(xd1q$aW`1WjeJ2DvEKUb9!JVCADV~7c?+Z2|C;`A8)YqiF2h| z8WI$9zqq|2c7dfi`Z?#eP_5iewltx*jiV!r;7IgWPd|pD=R{G(09tE;7*PB{!a)6|4Dq&rpWbjQ zO}<+niO*#4e{0YNP7SL?DZ8N+QFBb6eEP)JHm`9UF}Jr{>vp z;l&{?-l!a@u;c4ttOypR+8CtJkvyP}4D@~IqhNbNcIr@=Y?BpAecJ{7Bb^sgq03S{ zxQ%{-150{_(3oPvrl}Oka{i%C-I@wX!w#oDYg}@YDH24wC;6b00UC*}vE6qarjF>W z3jBQj#V!ocHH3J3~O;w8sDo?H3$a$70 zdPDdb=zf63d2ehk+*|&ux|hdHqTVu^pVS_c!L8HxVF>tA6G6$a|+azJGd!0@G_Her%hqDVJ(ot&Q!@4_2 zC%pMn9-5~QW3xGWSmw2lpqJB+nl!r|NF8&TNlX;QV#3^ zjvhZZ323E3>t7&;=w0Qjp8S={E&^Wzc@lOws}C_TFA10B*i-*#QDJTLIkRo-3O6fX zH;Gv-+dQ*sf}eDI8lr>P)OwpN{_3#M@e964Ox{@FlM8z?v~iVF1iwQd zfp|-$)m5(9u#9{!1)2NcRDG`R;HsrFij~XBC=+^tKal;czH){cXSJenu~f&bT;Z_& z4G3%enlW}ItOd;L+PCJJZkXnnSBpmvpgQiM!U6Mt%F%aI=a5AB+O2Vv)O_>r_l?$x z>qm1P*(lH=jk-;>LT_w5|ITc3b*8&K&-jo**NdZ@dzu@0BsHZd+xjYi>Ktn7w)iR! zvMmu<@xbBJ=k*IU4Xow5W|(as_W@T4BJCvY+B%};;t8$rQn!=ID-&(OB(RACP4){Y zkI%4PCo{LJ(VS|N!l$2!)bppiGV?RJx{K->%hgj`FB{oZPoxD)V zh(5-Ef&Jt^EnkL@`j)2~%d(f!ESVPl@TPo6&po@lsrOuRzBreq%mkL9fKst@;FqZj`pW9cJgcqEV46ha^X~dH zip-61rK*If$DSyOUb^k?|G!V&Du4Sn*%KiYM#i#S)zO_l)ho6xFr z>g}AoPWchMMJ$`ScVUtNtJ(w{Fom3WRt><(x$}#7@d5842#@xGYNH)}v2yA0VbC_e zN^{xz{58!31DtXub#zC!wX6p-ATI($3_r7nr?C_oz-P{e0)DeCVezuXWHUbi3e7Pv zs;E=Xne;qeOyn#5w3cpO9sL!PLNoq+t82{X!6XnNTFQKDXl(fG8Hwtad9}3{igUBo z16e4D!`mGtzk(){_CZ_qL3>l98DR?mCD@I;C|LYM^hWxb(X?>&1-|CuO&e-NHqbKBK*D=JJ7x;grUsJ-((^B0 z-@WM~-5ogs{7-Y?lwtJ?uN{r4Zwf)bV{SUi0Rcp92_^IY>j`?c0wL<>03VeJ>+|o0 zeF8xiz{PVbef0(#7Z<$eWI%#ubyM}c(3yn@)2cq@@bK_y#&1`auSnB77rkiE;BG}m zU-fU>M6KnT2dR_eXxiGQQw9Kz=Hrlu6C)#^`7CDI3-i-MR(=A9G22-HH^C<3d-mdm z`ilJ>NFaU>62$!j63|>`%f&XSXVutPs+9f&@T^*(BbG~TqTa|Ge)H+F4d9fObn;k$ zswyIq3fz0H-dgAX=Qdw68d_^s0kEN4@l(mqxvcl-3gPc1%z|N+(p{O2_izMo>#UY- zSs=c;Bf!kBh~@izTqHd!7*LZML<+cX?)`}SZ`<*?C^e0&7PFWDby&2F_X|`&(cJz! z5L{}1^}p~F({>h|z_|-R&wlf@?2DntA{Tg858d0UoWKa}>CBc4eS(X7egZIb00iWx z5D<$K6@7d^bZ&)w&}%+FCiOeYHele6aook~^T)Tg^rQ)A_MGZ0X0r*R@7B|ObL{p^ zHP1}{{+fta@i|^J!DbG|=Tc?nJR;unr^>~X@G;0zPXqL11JT9SH3J z3RjTw>E{7G*hWljnw-;?j69Aj?~Rsq-Vr@DSM$Io1skYF^_Sn*GJ!Y^?k58Kdue}a4_{aL3ij(GPKr)X=DBc2 zqB@A_I}l^mTeuF*52OZwBk9v)LGJLl$R79)q&bV{p~pi^{IAnX2VD9y=bH5bC~Hfx zE?GCoqsxWOXUlOIMgD)(wzkYAs)v|Bj)!`qG5<|Uq_rq! z#=L{mtw4gQv#87ndL(CNVZP6&SlSfOO1L$GbGZ}evF`G;5epTIok2ab$bUgaQ)%@S zui_b_zy4O6RR9Md5AnnVIk7&p|l5_KUwL5sYC#N zEGlwCDZ=Yd@(hR)^&}+Q7t64}Mwz$Jfn$58iig>&ON?&!P?1<1b?nEjn2Hs9zY4!b zaprsLrR?F;`F)}Q?{c*8<5|SP#lbwX>g3!)Jx%kxkh*ER5$h@`lJmT6gC?{izxw2`!GFDbUh2|N8UM zgEI5KFD%|HzV$+Gi^9B)2+&_Rn*4Q~=K4GFxuj9}((5**rG6dvI2)3SG*aPQFUbRv z36TW<-I}LK%z4ab^n~J8wgP6YdzMBWrnV`Vox|@f=PGJl?Qu3?$qHXF9rcx0L`$Gl@h!hMp_$=~K5rQL%&)yK%jR;RoF3 zhXcnt0?xY5KvBDkt)W7Z+YROUfS-B-vo|-*vY^XPY^`V7+Ol&J3^uxxAQ#=K>0J(N ztgfCsg?!Gf9>cQ~w1DV=19%?C-gx->#(q2J=G$IPpmd6g#6bmUahP zy(Jh5ME$~2NYt7y_xA!_FMjhtD0zSC+y`tO$YV{Y^2weA}Hw`FN zPVj~KeAl)7H>=hSkJQo_S(b{0Cv#x$Ds9j@}Q zrW7U?ANrM{Zr^nxvEN9S+!7|j@=qlHUNVY6l%8d)lSgFl5Y7TyWVOm+dm?)PNHP4n z;Yk@5!PZ1s=g7QbJ~hGz@NM98WvU&h+{QMFAg}p}a;nJ73mZk`t>kd+eTsB(%ToXI zdunt@@fm)K)Nd0sY(oJr$4i=w8AFJ*PG2SR}hUuuwk3j%43~l zTAVL-^e6PfqSqxI^ER%$J3hI14r z)|LdQa@qh=)R~*Q*?Tpg)^);;QeBR%j>R*uCx5>CgG#yrCT8lC8;!U2(X$LB->+aV zoul65HrXqOSDSvMHfG$tBZY}a2rmq8G zLyy$ECOWx?>1r#Yz6JVTHa4a~7QUG2QIo+S*sBo_cTC#~8Cic1ZxR94g<|=mZ?YJJ zExIT@#fw=dQ+-%Vu$;pamNwqDE{o5@+D}!)dlI1;n^mL+6&&gGGGiBGSCJR{t=vh# zyd6W%gxFFm!ufHQ+9@`z*Gm=1Dk5)!_&-@_+N$&Pit(pk2_=`%CORzErt-bvUoerP zMRy|9lcVT5tmDkg3!>}IpQ_Gk3E4j6!U-2k`@(7Yy8Lzgm)F6+4usy6j(Ywu3nuHi z_{Ed`+gQK(SXfqG?z?3lrY?nKcD>|bhv=@w$Bn9JJxj}5F24ImpGd39i~>8;?+WlFJfhvUEWiZ1Q-ywL;3H5`09 zf!Dhu2bZU(3Hq(Nq|N}R4?;>YWk7as{@&Sfcw1@DRp{xbmNmBA981<^&s|jOZ1fJw zD9B_cOVmX7iOoq$Y9Nny*_a%f_VdR;0dW}a&|R=UCxVl_Fphltwt9Gx*T>2`mwcz9(ZpW zL#Uw5FRk8aTqM6EjZX~9KY3P*Mwj>_{sqoHH#ZGiazTZ}JDhJ{7cAcRVT4JU;V9$9 z34{ev#^a@ng<`S`1^%HtJn(JKVn7D1~MeR63jf{Vlt%A$jIoY_PpdRw-!jM^qbQfd>)4N_h%Ys<+(D;G9$DFp^5`5`-!1^ z&TipfHRGN;Re}HyWPZ?7=zDh(OAToFYI^$Us!6foyE0Q64UZyL@avEBXBM1+JKF{3 zh`FP~cdK$MvSKFGfjZtP35y=SY9<*S>!eOLEq%-fZSo`t0oL~e2s$%oQ!hha82b%%-|t{J~g zO)DO)z(wGzE@er=NgRWTtjkW#M~@+NzWVa1eg4Fg$K@u|Rq)S`9Nm{T#D^^m=VIW} zN4NMdLTBnq!?v$pI9XmZB4<1p5{4-i21$u+YEP*|ZaSTC_!?~~7KiF0&#&ejYD{Q^ zyq@nuhdX+uwzr`NM)H4_J0+V{;SMN0lWg-tfv+x?6`9mu%r@?4SX{I`b)Ha#B=SYi z^mp;NTzTDPt^U)v99p_hlbAOzz{H?OdMIkbi&zmUxxXr4$ zRbdlY{TNai55En5Ol|#+WA1(ZNV!LIu%zZeu7CXV-RbncpKOL;(nW~b zc7Q+-W{L|T?yWvi228tG&}3*M0@-^sq%+?kXv-iAl!CiDw2Pr|uKv4Q-FS#@ZL=Mz zV$-#Smnh4bW0X3OC4L*7(DoNBmxwQLkOEpQ#zPv;x|-NRVgg@7uIbNp;ya_W$I!&I z;S@yaqAAQ?>isP`^WfF>sHxMNT|}7e{QIdv)4_&iG7;FTT&88a!7!1{7iIQ0R0#@6 zJ#yYqdHd#k0>J|f5G;Pg+vWodE6+%?yVZQrK*5q=A0{et?mLjgZBB&gRh3e_-yAdk z4&n80s2CXVF?Gq=FIB~z=QC-1zn7-}GO@7!={p)?x%v40)c_G&_pZ$|6}69=&y;d2 zrNoOqJ&+NHUZ_u(ZPyHWN0h+sD77H5nnTnIj;mD3L36K&h0sk7&WVXB<>`qlBQ8BI z|0s`*_a#;yiMyDJ4Oc(na%Od4KQl5QITzA{UHJyp{Kv!ZH#se9P^(?JHV5ku2ULh{ z&T=?p^IpskHD4h3A)9sCXe_^pZ4Rux`cF83uoHXPf5muA6kd+7Ri zS1c?sSo69StmrGgU1PhP=LfTG`7u5F~X_G z+%10WB(4sxn@5&y^megz>Str{Dp=M>3K~CDTk`bt*AbUZ!+R?$A-!_|TeUta4sDa~ zT0xWjGU}(nbMtR@I)Fl|u2}}}^h1o(!0&C184CSN}(p-7sP<@`>8asM>|a@qO}0y1bihDHzook`NV54c>OjNPy@}$$Df{K8?Cnypp8Xib7lI=Y~R9y17gmV9Z#^$_&?*+J-=rF-S6L4M#mY|9WoupYT%Ev2O=UoT=t`K{I49*ztpM; zJ@9|^TG+_};h|Hk&5%;x7wo`c^C6Fk8?Wgl|AIOdQfKKB!rmnBz7xX2E5#(W4V5jQH_QDB~V5* z?FW4P?3GL~S0uRW_69-tKQ#Bp)IF1)8k(V9qva!&^px|FkiGuGrx9y5Vo`ziYZ|ZR6s)m6YvX zaaJyPRR)Y6kQR)9?kBgsQy$8_Bc4m=g!2F}V=NKD0EohJM+-_5cCNBrlfuDiC!49H zqo)2jGov~-J|6hLx=eF3rc^Plg__&5mD6V|Y(`ixGS}-ousfSp$4DlX-&okn`||+J?|f(}=zqVVibjIn9Bn zJ)(H^y6ltA6M)9^P?vHW^*@&d1^sEa$sc;su%J;ps}!Yfwh#T#W28l%P-XC;Ib)59 zne^c3Wb1`*F30hNJXFM#RI4rEZtOn)lR0reLLU~&w3-9lFc`xORV3?&HQ>h)W1k`p zm9wsP2EryISiA@e_Py$kPs;^{N{}@=oA`h|9STswq7Ax%qqSs!b67!C|I!`*1P^G| zxE3Ug$UAe(-4uTo4k!daMXD7nx)zlA*JEwO0FsI%6G;46C*d@Kq@w%_mfr0tklFb7 zaM944rl((k3xS@a=R9=Gbe!zHFTC>fv!p}>-q6qx4?q7o;+{?g3_+@9OI+-TvGg+uT+7rO!O=Ow? zY%stgP`@n$_tc0O!wm5<1`s0?>wdOle9V26I7ZEKnDht9QegRg<;GKU0I44mlGH>N^02N4H zu;KKT#FgpwWQzLqc2Q1ua=~48H>2SHMhjD4&Tn~Ii$b;NO}#HvG9wP2)eu4VN;I3} z5y>g9|Mcm3S+R*@U>nVL`sWCd1OM7?gzV0Lb4`A&LA4)+$wTkQ?ZLYMHYr61B8m$qPv$he_&_Z`^3Pzj4q zmZd{KI@oC>}0Hh*_i=q`AB#^_rbruK?8?9MI{Hwnjpm}_`AAes{37`$cCU`xYYz^rrRhUd%*3QLIcW)re0w@ZMyesB`<>*_r@_1Rap1{Ci+4{R zFFWo|2w~b;W#ht($j?wyw6XclPVM^Dw2YL2B6Q03m^f4*SLd(ukL_V#-HO*95#k97 zI%>R|Tjg}Q8hWH927;A7YM5`mDfYx=9U7{^xM04vI7(c!8_u@dep^XGdT@kp}KuD6G#=qX+^F`fS;Hg)gH!a z5H!;ihwF`W*E~IKySdjp0sU{jy>IgUJ`B|W+=joN;B)F6IZI601&Vj$5#s0Zj(bJ& zP+*(h)qPQ@N7-i9z^wxHPHw=_%`{u8_H@hH{;~~h{v@+D>@n{Mv>R$(g5~mmGW|Ol z7lG#6w0e4d*#>Pmx+1$c4tKUe8thz@^kPd9X0+7B<1)Lq$^3R=gd{AQSj!Ag7vJa- z)@wVFCTKa4s<1akm){(!i0rXsIeo^L=XZ2pH2R>#eU*3@%8=(-V;zRD5__e@s zg0r$FGVGp)^YZdcO)P&>V5FvbIDU0%;dQa%1io8ILDI$daw9eK95-*$`emWN|DHN- zN*V;k9ANyCxSHi}w*Iq1$BcfcYb|xc*fl*)5}=n`dvFgZ7%OrmxiKGrJ}c(s0Pz`> zU=Q!9lbguNtJn;WeC3R8ANF=(pa1e4=E*~4o}tKlupTE~l5MQbrXY6yaQNC)P|cQi zg6C1Xug7sl!mQdjJUhHg^7%Ew00)iKCs{G!7;bXg5$kvlx^JDA%Xid@<<-_T-%#6 zQv3|vs$m5!J&h;i-02rQtr!Bk!j#`EjRa*{cw-M(i)7pgFEOyOm2DO`I#*jN(kAgQ zNU!}y8fjd5$dej$6x<|kW_TpvsmyopelfNothU-HR%KJ~Jt;ySc4I;dN(9>bmq1+w zYSVTLv$QsQ(9R}e?Tw+dA-bW&fz{B>DEx)N&CBA~VJ&{;GhqFrZ-@I!85^+^^z#DD z7}X~1Dd{fhU7HKtsTF$`a~Et-F*caZwF6rV%nlY7{=N0A=sYN$JG~X6a%t0zf4jLI z%;WK`-Jacgy}Fmqn61S}215GYMUfZ%%s-aLjgB*m`dM;+YO!Kgqu*(9ddHEZAT@AQ zM3vu1&6)|RiB0ROqdnYmvL#)3AoR64 z<&a>4W*0s82Yj=MqdrW9qsv6u7$-qhq&z9LiDoCZj4`JWR=cFp4@BtSedjxq%P!TN z*w0O*VP~7;>;QZ*4GOyG<$r>S`5PALouh|vDj6MJwtFpb7Yd0s@X7s-8Adj3rBPL! zt@U6gtxegIsNO$r(QN!51!tz=qHe~8s-!hH4JZ=9vPXSQPK0vKHIRr?$lFuvm48%m z1{*TxyX;q*aj>5qaEx+nTAJK`X;K&|WmoPdL-o~>k_WuMI+33?sm29Y{Prl)w@Gzi z-_oK)FqE4?PJcVeeda_@(CSBg*DuSfsQ$bXv zia&j9TX))Tu_fBS);Zh_tbOLmbk@_=hXgGhe(O+nqO#iQFb`&AHQ@T)8OXV^D+`-t z;GX~1b5`$+$ITkbzT_o3Zl1mo$?h$sI4A%SF~IW6kI~Br^qhOux!^u~=*_G;%wp97 zFJ_@^_Wf{M^Rx9Qlap55?#;vA-VdYS&crlQVg#-GxU95(wIe{DKJ`pknf_hP7oK0?zjG^=Qz_H<02nZEdwaDy8|p%wKz5P6(l)<>zJQ;+?Bxq} zw{?g9XZA)n&@OG3+rVSFGQJJpFq`YGa<1kJbNoKU@a?fUS$Xtp6@VFebltUEJ1vEsD%K9G6-h&x_GM!K0s~+?EkH&fj~n zD=eOKQ4x4mrEo!K#AJFDE!(nQtSN3S^g4L7JB=$nx+kLwQE@IO{Bw{DG`LzlygZ?( zK6BNt9>CuA3(gp(zdlnqvj=23HYPGC^5kpTQ;BOhy@ zzCZrWnA-7+J0=*Ds;k9Frtz@EL8`l(!)%`9%v)1RX`O^2Kaz&UfzH%Kb|tK4rDD7f z^vP1wYm}!qLYBr8q6uMh_l-QOKfMrbNK(0N3&_v7!UTD}OxUC;-zc(|!WZ6q(bm-6 zOKPwdM9CR&v;v)J%pW~3mT$dMZu98Ck{9;mt2Rl#bWuUIT6;<5;OPDKTKP^bN2pLn zg3pcq4^>|Q73KE5O$aCtzjv`*3`-X0oOhpn_Ves#@59OU_8n?|&;zko^0}9Ftsn0ce5JdB9^sLG7-$b9 zVPe{g`U64vVqC081pvxDBPirDU`#ZXNan`|^vbBV)V%3#JbaPPcs#9OQhi>7Tl0U1l`Ep&0;f%C!Rx+M{&yN$LcXU zBDj)KU!^l++)L=pG1i3B0}@A=8^PeUA9;#-K|j$=To)mrFwvKk3;KLE9BjREXw^dv*^{ z9iN}5eeGe=5S@VAJ-t{8{l=mzy|O=F?~lsT8c_(v95`GOH#Ipw*PSL`Ld5p8r>K3UfUDDJZs9?6UO&eXXNaVk_Xvi-+31$ z8}F!{Nx7``PMjv`yizcHJjmF-9W6)I(eE6)U@zZBY^O*4X`E<#0fg6=HwPzu2fhk2 zKEg^@r*FLkZKE+%bSd}oUqE!r{i=M<-!0x+E&)&;@N<}U(^KS>@bg9+Zh&2Lv*yOc z#7fFYk=gDDZqbw3Qo4Qj?!dc#4_wTs_IpPM_>cLjbv}Bj%m0IaNzB^kC@*Pg9VS5P zE*IBv>Uw<;rJR69#hJ-Sid3P{nF2Y3j-W@fiM+uxPNtPR2pcc_cu{3BG=cCl$NJiU zXnl8o1Zd%focLq%$AlP#wwBp2{GK#-8VkF%li6NEPR>ci#v?*Kj&(LqWlp-{h%_%c z92TJ=to+xxuR>TIJ2(efg!)8I2Un|)vPeq#A5(sQF3e3q#&EvdGDN`Tiom30vsqBB zZT>cbaYbg|l)|Ta`MSvxXItb3SES!3NWC`RG4ql&^wiq;gqyek*b0JgK2Jl)7;q;> zb@UaCZMZO=FMkSWA9IEzo-M-t>l#X5JCYQ*F+iXe`4zBF<&UZ~2#zsXh=^3?ck}an zs0F}OnR!jb)8?!8pcfSm6+!OXukSX6YWMd}!>A5$WfO;foz`>V-s4Gm-rEydrlloW z*opl1h(NT$kg0S>=W8t7f|oCYI+K!QTMmRfmRGp`wtSE$Szs9Nx%L8Hlm^A)j><}n za&x6t2Khi7r7Lz+!exlh7uX zjdx2xRhi7IpLN~hb6rWYOrA+4p2P;N7F2dO+w!)TGW^6ko;1X%M-6tZL50MQM~otC z+UkPR{WiEK;YGy9C7wFPw_`jFrNv2Ir0V6np6VQ2`G_Gt!3*c%sSUj5vZaJ1NZ8zA7*loAr= zFsSD!pf5)$Z?4W#?*4#-MK|IkL4PAzB*LVJHi6Z_h$PhWddS(ycT_1t$cBu|_gWxI zQ^epFVtWF<_hl>6z0byd}AEPh~QY=5TFL!>P9+*9dk~NnS6fMLH0{-Y)sbM8*38s z-b;a;d7E4?NFrqPYJ#+ybA0RxnS@(8MpFvJiW487a5l?%>YbA}s-y;iA?5IzZE;>Z z!CU7DCdpUH?URF(aj? zk!}z_CWt`<2&`kCiaR*4P3gK)(#1ZC?j1Wp_8Bzg2r(=-9U@a!Q9ke;@4rTl&rTgt$Ge=q_%6zXD z4vUNBH);X$z~jQs#J4Y`U5@Fkb5Bl<7NYM9m6aDi<;h0=DUFF;fWd)Poz)ccWU=Ph z*2QJ0c9C6zn%!|rX_4`UqLJM0??&({j$+`%_;l`f)>qYQ!ehn+lc*)-Q z?k2BK+61_#&eQby%jeLICpy0Itl8Np%uzqS`zaVail)2#t`H>U;u31wk)17I&0!cB z(J>oNn_Lp}K<@({%0fo)Aw; z(d>7>N2cgd-{Abb5}`6i0fAqzJX5Dul=1d;o0}b+fR?lMiW&6Wuai2}q(BVY#0N=2 zWGFuoz);Xa2T0+)^}JIl4L1_QB_Lgq11y4xxpP16&dyF>f4>pXfM|EFA-2ArH(x#t zn9xgouOl?(1Rx?h4*+_TsOaiO8j|GZ<|=Ax_5r;5zr;EPPL5<`c5`#8S-N}3=g*(@ zCv3pT5uJhQ0ehQxx|7$0k80vu5Q3zdV@)@a)Xw>6BoIp#gi6*Ww?hCW;66 z(|d98_9LW#*f-&l#2Zn1*LpMJ#@D#>{~4&pv3N@!p$?~ zAS!SYHOmBd3t-iBB~PzVjAv!uuf{Kg1vHO`6Xf>4^o`^02`FuL4`y>4jq!EN=#hth z3Vgo6>O3^xw#mCqOjTx-Xiy>rnLa|W=EOxHXskE9{P2Dwd+WcDiZ)r@jERt;+_)m+ z^LW|09C85*cw`Dho2uUTeDJ@|>h#y$Z4bdDpM_7vjNP6 z#>Y3G-f3KA2J4RUoDEU%@V){6$?7PDrn5=ltaH zB#;JBDs(p&=4P&i-?KGPiiU zr7)-lFwoh58#4V_*43b2i>9>#3qQt_6L<_jDU@-^vTsMk+Ihy5Dgb$+ZdVJg+~$S@Ws(4=$Ip%qxf@eZ-Y z5u(<~7GR7(;LxIP&eK8FFmP6H95(Af1$`xCELsL6XWqRsfe=6YzqkF|du(D(1#lif z_7FMaL@mcd`@+MTdy%`0J@z$3bgZa8ytXY54ef1)S#xh^i2KQG29Icy-T}9(p9}6P zg{ryD8u{sWUC#L@N6^*PXJxR8dcmtPl&!F5M$H&}25@#bcC z!I+MYzzEu8$3J2bl{?P!1Fq#$#OGt1Gqg_RfQj330-JV#(J2isvGGvv9X_f#1cvlg z^X_$UOhK)lfKcEUSAD8-D?ony;m_dxW$EYa4u+x40 zbHBLp&WC$2jr{j5cOAJoj%^ zwgKqk`Lb53-wu5tqs*+qlWopLeO+p?j|yf6)vA&#+t!bqp{X_NYsk))9|RSPchv6F zslWyRw&_KB)1b1vau^1Zf=7rLkat^2{L9bYdu`y8#wV_dkzTNRFc~Dymi6-$81y`56w1bbin|S zl&|dVbn9$ewnzG<1)EdX6d(cB+;&i3)ZTlAWP)WwCDqu2hWILGvT82iH2$^a;%8Ys zu2fO>)#J?IO+j7qOx*=nYQ_}aHT|)uV0|)~h4rcP?7|a!Pu7CDAx8JbwYuScpHjJh zeLryKxOa|~&d#5j0zDNz+5yv^$0B0QDgVLK$vMM1ZTa{%XVawf+05om0o1mMvTkT{ z#T(~axzzsgy;GP_f0POgDp{Wv`e$Jk4iB_S9T(hon{?Qno{!NftW{Sf9CjAeD!Ow9 zs*d<9TwE=>8QW=RZWaF8YrXcv&_9m|xy}8yKjL=WsFHMAa(5i8uVzW%_|?;gtjeb@ zDSjb+%shWNXX^a=i_Cxg4Mpsr4Pgqh_BlGK2hr;4p`QHXMfbzEu;X8Wu$jC(y4W(b z1GTCKbr6Kx)t*`qK4-fqq;YcWl~p*i)diTPB_TA=T&4*R!FNV~T2l=(9qZKgqJiRz zNT1wiN;%qFP{|Np^_NX^M_wq48dXVqO(IK?aZ^j0-i#vGX81#a&F`rd_znb*)oVdD z5?|L<>VHp>yKj|peA?9(xCK8h_Kk{cYPK6h$5@AX9e zZqV7I(fMqW)gEqrpPU4&9Pk|W(_6WNCfUU{dKSIh&G$(lE;Mcb?beLElH+mXDj-sM z%uDW)srk9qK)0#?>;ywjZPEA+Zz4853rG*H@;-SoDBsf_DR>duGI#D9?bx@)mgr|l zI%Pj1bl{}4FEZ_QB$Ns|dX6ik)IFGlXug=UvgV<4Ix2B>>@0pM2ArLhh*n0;i!vSv ziEv6$tA{{B8a@Us%i)hjoxv*5N&j|@M%f*oYZQD~hNZcur%rfX@#n>y^Ax3ype^y; z;FbPuOBKP+$idQ>66u?k1Lfp&pG0-Z#dchl5A9+cR|^*y(KiV9g%XPPh6LZ>k20q0 z9hm!HiQP5}iHMlZv+akRnn6i}d5gEyw!$10OcGHaO{GakTJ-useHI#mgw3(7F)=E1 zDh{i0nT8301=LsM7jQCCyVlRzt&WchdTU@uO}O5JC(%OvRVk-2tWNw{q1XD|ru~bT z0=_=iXxvlLW(zp_E0Ypi;y9v*e;9~AuV#4!h}u?!7s^MI6QoppgsD=7c-|32RUbxj zVMFEU7G3>(7kx#5(|d4a=%bIVts;kvCnMkYnL+>*Y}iDXFshxeH+URam1|Dbph3(` zE6chEi(Cw0d=S9ArZ;NK%eo_8386ZH`0}C0Z}nrt!hS0#5<=u8s1LOU+*7@^IHeX! zWnZSUg>x`s&D0K{B0TK{;|HjDB&vSxoH>njXI*>F%wOMBtxsZ3_O|x9VoKTD471eV z&ARC|?7S+Tp90UlSX}W`P<7fbSzMcat@N!$PxPW*VlMsUnZC%)Q%A?!?v0*@`GZ2? ztKZ%7S+qJP)KiBx6?s4cdM0D(9&MT1k@`*pbyy$judh}YsuDNV4_0gMJQK(QCwBxd zZT8)lpQ*Gu^SGwD`YoE=MV3S^Ts<=0k4sRwOASn8`ZaS$$Ku_bSVY{teA7g)a8Y!< z*@JOGe?zzLd6;6tE!-!!=oPRRiO%Ue%yH+08cmhjohCB8J}}1g?cnsZfrs~Zk6ryu zFPslCnQ?e>U^aR@Rd&*v0-aa@7`K0(kZ;{vUAxYg0aCuVak&czty*=%>Mr~uJUp8_ z-;!kmfA;V=b%ubM!tSGyj3N1r%-SP_uG2h&*n%gipEr}Ku(_aeQ#C#GQ|_0^83!ga z-5`7s%O6ufyOo=#I(}N(axHx6iI2S<M=>E<5C){&ZEAJ9F{s%=VSjWVURCeCDtg(VMpP7 zfop@q-T6)DnEb~%se`HV_QmB1dPnK*F4##4BV}zq!FwW4 zJEeF}Y<$a*dC}O_V`QSex2gQFJWDSi?0xG4!px9fI=mfdW@GJ5N}NOe=bM+YB;Ko> zFp+2M5>GQsvZ}Mu)w`L&ss#2U7sfzo>T`>6@zNV(!q6QpIEeveXBh7Rc|rRUCCl+n znST4%CZ8dWC`t*pMH};tGdTjDk=0nbv^f<02PFOpIgX4^t){FT_yGWv2IXq; zHvl`S&0^gb+L(LQ8d;qF&PzZ^}ppRlhHfX|`eUlen?5VuG+*nB+CR)^Ot{ zq!N*`jYrSvRkL0 znnzs`1e!Rl2^7)isvSd#07T)xhxL^_hosYefyTsl2${t3rDzZej567XBz@QPpuH2e zA;g6-GobOrD8O6gG0hD4^$V(&giu^2Iwxhw;zef|r7+6KErS=IqYO@*=TJmMG#xwt zW0`ImOI>7ntIvjR$M0>uJuu>6S7pmNgv5Adr2j*6KXGX%yE4!AO7lv5Gq=|&W;6h} zDVk9vFR(2awp}6yAV$Nr*&2e?)dzDdHRa{=-kQJ}4uXg_5w!*mRXSB290BeXFd_?^ zI0&#Va~2#?v&jIz;~IdeDCbaBe^mPV`s@{>#tE41igDoL8Ub1rzJ83g-}t!@-v+qy zAfv+Fi7j*+`g;D5C*8x7Xlhoa;;~4m3~|EYRPV{fwIauUJ_8tb#&(5zbEN3RMTlWU z$|i`JV~d-D#eHa~jVOHWMba4xQi8Q6_snXM-NdTOuy5$6^+_oR4PE{u+qU}bzGtVP zQvJ)(G~>y*O>O%6x0CvDs-6hO-Q3{w));L*m)nG-<9_{%E4U}5MCAMFM#is$^r8kg zQ^C&R@`~we>f768FoPAY(&=Oofwk*JiOu6Ekiy|*sg{-&8DII0x3EC&El@c8&%@4p z`Q*n%U6Tuw{&1AK9*q!7nLen15|JOt(k92m1T5wGq`khAm455;;2>2r&OkrPL*7M~ zasUTCazFdHI8ruAS%{ZRwXlq(B(z2P2M;K{r3*Kdtv@wXV+mhh^JFpY8BcoSekk|# zz&n*%mp$Y~+T6}e<0W`F$&KvffW>Gu%m}WlIKCjMKa>GZEAW){W#xT!zB}# zdY|H1^0KMJ%H7MOI+<5r9T%qD@@*+Nn!TOhDVQD2b7LmR)9lTy6*HZkQ(73#1CU zT6h3s4adL8;(y%8<+E-O>2KIVZHpcNT=kpa0Pj5q7Kl+&+V#0XAnO_z_Kh18ZfA9! zf@-2iG8BOL`Fc(#9!N<6YOL=0pzH#QHr?N9iK%|f^u9S3 zUq~VpC~{0#B4yrw-1IQ~Q&+3#*v(Onjb6RdaZXY75K_HUec#)Ht+j0hc>x`8x=%XrgyKJ)nCH4|9}~AJ2@NyEPZLuUlpCLX zXX32U<~(a&SdhOU`@8&bxED~01L4QdL^fkUx_ECq-ry0TGoQ51>Lb|_lc;Lz#{Mo>7nN;^BW26SxR_fMl>L>lF@EjxNPKqo|BCPgtDA# z8>l6QP?v7ZMTY@hf71knZl$5Uii}L#M(toaPFn=ef_a_Lh$TXZ8Q_GbZO?+CfdAti zS_fO5wodibUS0ODL~{U``|X9D?O$RVZsSxi)E1kL+*Zv>Jk}XKSLN%e&!PfEQh}ZV zHw#fb6QGH43MlFJM_^W(c9tC4NyXwgR@CWKh6V<7Z|LlS{@;(NC9Uh0Ui*Fev1y3h zF*dm&_T0EhD725PySyD!0eR3+90OCKWyA&O8J;Ni{L_DFxZXtY1jOg<%ip%P7Oc{8 zbQJ5u8QHc;LMiV)eS)$0a=Tt7*)O;kpKfTKgBnwh+_PGnWXJC{fZsA?J_ESMhd3I3mLG!%1A0|sTUb;r{pj^569b0aPJrlF#SQZTC>Zm6_S|FEw9do5(}2ZFk1A2N zL|-Zi5Vzz*9RZ$&$&RhAND?goQ<*UTa~K6Bs``KUgy+5305d#tHEkXA@#BSQwie*g zM_h_0DK@!bNKyDNP(ljy{Gp1mP3C~UQ{z2QkA`q@0jA%(>|ARF2Tsk3>Y5u$Oqv7O z9JBcRtjXF$W4Udh>K*Gn{DA`KK1cjNIPv?V=iQ(!&t3TgJ`)bthomjn@I?(Z{K!DqBnbgN=0D>$W5@gPrWH+XqfQ#>mKU=+4 z*nF*OXeSRUVjZ#bXaw-QB#+-&xs+I491EAVmdS$Ff|{?`ftl^5gm14==X#jsdZ0bc zB|FMN_r3uXuHj$OT`fTR`U(;fXhh*?1JAIr|J$&8H)Rgo!t?V0EDtY zB}tC*j=h0YMzkxC0kXiNY^i$JGLb^ms+lbx9=sYK?^7}%0vHfiQsSh9)dFD0-(-`; z`=ef*)j8i>GH+DUk)yBR1XdC<+QavN4PBRVgjw>o;)+qfeb>3RsWqot6%>^Rr2q(M z;MhIPrM9S>n_VE**Weer{=TzUB8^ZhvbCv1vDx!(C+^q!TuYHB0FdNtXq1^$y!L*; z^?NFh|MiU7TM ziJ}6$B-ocxfRi2?up%yg93;B*x@~<>HiVEkR$2MUVSN-bL$zA6FzJ)?7yBt%S{jBm zm;3EDb#=l@st;`5?itMK>uY?jJr7WABhL5e94(Pk%MWhgM=M-7pymvz#!_xs91`F$ zwzVSOUE~JZ)OZj%`;k3)A_in7)QVhK@38_v8Oj2~AD^1SMX>)F=VdogvZKqD-M#d% zUf)fP2(a74G%CsNkjG1gJf& z+sCvA2ZcM(@yTZ{s$rqIc+m%ZcTiQkFPKtL*)5m~lhY@Cr~5_vKT!@DLXzs`-1TeLE?MzP!h z)L)3uty>vXagPf3qp4HdO!0!Bi;Xs;5g@SDC~bP&6OEw-Cki$DxKs-ls9~V8yag5B z*c|MP2)vr`)wAsVLP${kIqU&tCd!}Ayns#P+`#`pyC{r%0rfV@Uz!%&+B)_D0O0q4 z0e<6qDtvlpdx}LoKoLcSIu0Zdkn4IwLTbyzh6Z1j<_1;Q{s0qy`8ni{8VupCOZmyH zbulYQ1$GnMJz6v;F(82%O#j96hMJnas$rNnRtEym66u=e?p;sY40wldYev%(>mS<_ zY^pX<3OS<$qaL^dP3gUs%(HVVTIjK+-Jjp9d;F)61K{L4E1kkwL=nfhNtr|Y|!Pp0OP@(Q2Ba<)a!cpW+)h(dFKS7Zj-It4nF9O|o&|)-ZZo9Keq}i-@k> zJI7%`#kbdiY6m0fL7aZfW=FM+dFoSq_&6WK=5*`5tLeoPjQ_d3@ekmLdHPMj8-3E{ z?e4}@$E0@5mIa)MUdLJM&C9xKXO~8*xCpAD71u?%eNr>$0@ zAkDQ-6sQ{mA9!=upmiaYt_@U_YK-@lu;jXo9vO4gY)Xz zi+&TZX4Fp!FLz;&dXi(G(GKn-xCn^O{=ZJRPyKwc775fpHZ?%z*<8)FcW~t9!Ja#F ziUqOxkDU|;F8Pj))*4*^uBH3;j2RNiqeoxdOj>~Q00%1E3S_bIuODK=ii%&BR(dxr zw+bF2S&(x(&x%YewHa5j0rv_w`#Wf;saa|4+Mmx7;+irp#=MZM^=!UtyY;(rshJ-D zl>Uu22k^!WmX|g4-n~(nB&q1}ki!xdjWJ38WUrApdzvfOO`ZZp=0Z`cFBCW9sppVk6hM1yEo$g$bl(fLa{5dW;2_ z9}X%+nOFM+F8G@TgYgySj|g`@AbI+#wn&oc-Vw_YZUeE=X0`WCv%4Va6EQ%Ko2%)=czq751netK%f2#{eKcBkeJ(4dTzNd=|`pBIV>&mA+sXtdLa;`fR?>>(j zbd29_TSy)#rWKume>V?2GJ*uavl{nBLsnjiZBp)fz8|?luMQ;1K)bv%0$EL4b@A zNQ*P&R)gvnrsf8L7+61%e|V++&U)dhvQ%RU>vPKSNt4Z*01(uHqkE&NfieYy9fk-> zQdt+sdlqbvqL4H4#gEVx@0+`Q7}Zq5k8|_TP9e1FK>S|}|LLy7*PdI?@Y)(U&{IZj zJjG?S!{JdjRzp5CmVm=$o*j{9+A&nKkm?2t00HIoOU`Qe&2`{-<)^2>-zJA(a?P;P zv!%GRzYMz1LawfU(bD)1sJS&R&sTE4eWPe_EvN!8W~#h=nqULh8`zQL*YI$RH_s4i zk^3U$tplgc^Poa7Y4T}RAtUDg$=NGtoz={}Dfz*qQEsuP7UJc5GZGqpU zJ4Div9m%*Ed21zl1-8$xY&yj67?37lIG8xe;`dB!xfJDRx@i(Rf3N6KNKp%48P9vf zIT}>5V-q}r$jz!vZt0|Z;5~Fp_F1j)-AsB-`G&4MNv{WQI#ALwMuvKG=JY&xe12ZW z{%odI(e)XM4p5|v!)CU0##vEZ_YqcjuO^^fdrQ1tRot!M%V|d(s1S?6CL^P;F8U zB=Rd}E~|T@oD@8B)=x%e(2?JbmqHbhche`6(xb*zm8GT26TTTlP~(QQ1BG+-?I!$B zzQo6aTOY=L(*5`m>06EWVvUu0(*ck#$0w(T!{Owr-j7V=Kx;@EvoO>ja%fJOiW9Tb z;u!O75}`wDKmGiuc!A zPEYT4u9UgvQ>-XtkPk&4)C0*c`6o3sH72H}Mh|9`CB!dZy?7DW(NTIw^@BV;S(Z-A zgO5d0++)P30*{!uH|t&KzqNj-!#dSTQ77})BF_LhqcgmNhXgp_VD69>n-%RZvF`vX z4oG2LdEF$Bi1c1>6+~pP`U5`G3*H13WBTwRik~1zF}AhtsI2pLgD>8pqh9!)?h7%Ob`0O$?WA_v z;~^n+XmZ^{6|iX5-~W; zhHdvhR3Q2}abNO5>eY;B9PE1NS&NnTZ z<(t`2Al%Hq)EVM>q!_I6{POCGR*=vrN^XMrYPB!6SffI$LxpDj{mUmbEG!CIrdTvV zcw%9+uN{X&iUa86rbxp1OorajRao9sO92$&{D6Z?NC#L@4iXXvA0Li zrB?>}l%i3>*kwH+@v9jx>Z7Lhl51t#RowL6RMf|Gj&Nj1X{kKF`V1*lE3SB05n(XZ z-q)M{mPAN>$-VNB8d)?(D&cM$Z zD=WToV+^kLXVUcIa;)z&pg#*N%p0S~ng|oV;n`YNb}F~oezdL;Kz}JtC^r2QCkq$c zD@+xEo&^Gdz+aNpAdL>RNV>YZqSe7}i?>&%&igZorD7h92H?gYJZT0zM;j?84waMr zW5LkjjI^H}>i-P*@2F$GSkbC6z8`S*4Fjts(;4%2D63mB8t?7J0{9RpKs2|=;>Jsi zLz*ZqMgN5s9SWb{uW#dI6D)aze$?Hw%?m%B>@v;dXH*pmdHWu;1tO>xZS&DBt>xCS zu?b2^-qkE$%BKUqH^;#NK9bnj^-j!M`q~EJJy-Ge_CBRpGs)Tpgix`z3H8loWh}PB zRW&0zNzAP2`xi-S&kD$Y!3dg=d97TFphe3lVU4J(C z`2M@t0A<(n?-7iOC5Jztwd2n7dh6e&dtABK(~~DA#EsfZx4^w3y@kK3=}5XLv6Y_| zF{FL&SZ$kl`sq+nPfy3Cu-juE7`mi!dj%*CiiQ%=Ev8y1NhmfL4~#NjF2!#g1Ree{ z(Ll|pT60>ZG053=qq2*B#1x;FA$4!{VzOi3kU;;pzDA!QkIvvW*e_hj^KSwxtC$W{ zi`8Ii5_IA~KLHSAW>|=;sEBROc5r+9gMVS{6HH`9@`vR)O#(T_(^vL$t|@fs?;i+F zcJNGW(6I5=c8rHjk?S7L+nKpAi#=qcWJDUuMc7qJt1+skg)>Zy#hjcxM~33bggt;@ z`LPXe^44P>j}|YEN3t5PpliKFc0aW{KwlblkX1)!c1o=%Z_h1D&Hj?0A0`ti#NEqx zdWjUXRs^9}eL6)XmTM%L7?udpqO#m2Kt&;V(99e%FKioIKi6p$dsHmk3d$XQka`OGgH7 zf)REa(HHY}aO5&PvDJR(5?_u&)yR|rhAgNYiYiS|A_qFl%~gT>MnRyL!y?PYTrk>b zUW>?5BjarfuJg4YZYm{~@QV@q5kl(anx@-O1=uYbx9-WaGTMFHZqEyUSc26~&!hdj z$F94V+#;UW3gydkIzF8xa~Iu3?ka`3++w+=tUlNDH}760u_8<4Wag%RW)C)Ip*DQ^ zAplBH@(YJi#$cC3Dw=9zH3*p=Qu@4KO||@uhzE{TNc3TUoB5j{kRlgx@IXJkzFru& zD~sYkhGHsF36v#8icP$;aQHd~enLXG) zP=Dhok4Rq=?1B+?8O3ETmA+a~l3^w#Lvwdj!^kJ|lZ@sodvElp2tmF3#v-oSlf>xJ_zp z@PTT?OaE->4hdECeE(VSy6I!jmO1yCkEi@9Lu@XUP;M^W40cwzbz@4(a+jS5G1WSY zV*|b4BWpE2B3^5Z1P@St_h@1Ap@NDoYwL5n7D9_ka7w)RN<#<2+ysMCQk0A*pilBK zY1Rj!d{|*3D;}1))E`~5&!izK@phMw>yq(nA=K{^fUeUq4cPhZQypwb&AugkDMKPC zx0XO#QjfB~?&78WILTFzX+f5powXLH?6~~kow4EI6P!XE;=c#fU|h1j$Xj*V7$@#u zvl$*jOnC3fzIGJOWK1@Xb*p3N4V!fFft)M};4+XzJ$v}JBVvy5P0KN4qDFmB&8_Y??zt#yM!qQ?RpWz#!x zP*s|)0JbrAD4xxgl})S02S0|cC(n_$z1TMe&atSgrHTno+T60gf6e^dpJ5=-& zf{?f_Y1mX<=8&9z;a(rKKNsXFp%tmc7S*ky8krTz7CFJ>N!5>(6(=-e&npl5+WZ2$ z<(5C@r*eE80slH)0eky&qCar;;6OvEvZx_4c68)Zn!XgG2-c;C=4emSG5;EsW2dIB zB`9fNCTKc~GeD+S0y=6h9Dg5 zFqlO<#me-kPl#OLrz5rw%SUkoIt^YD|AZ*WqTg$t@KV$bLg2h>+-hhRMscsjJ7E7dCj_ z0mF57wi^Mj9bGwbn5wnegnp(<@x~mjZF$kz36`+z+M#VW6!N3|wk~x3Ow#(asHkQl z{f+@tC>9oM4ON^Vh42TeZZwAb|JhZ_{`|fXFsTdojYk2mY?m&n8B=%3R~ts<({INm zbaE~0Nj|>WJ--z1Atgso$d_bPpt;R)X|0a{ZHG4t6ZCLWy5#q;UFru^F-XhXyb4N` zbx~6GLGR96Nfi|S-qwcyt(l{c{ylyc14A;psybY^rm?Z{hco2} zHuP=5*yv9q^$h-bm=&@1ezTKg97F(@!eGN6_3JCHvwyV!g5@7&oaq>*%etY?X!Pdh z&*tW24d0<&tPMDTz9COL>6f$-$b)h$8y`1DDd{rZuhm!xA(Tqc?TcIrw;ZN&NpyG~ z!@VWN<2_Q`2!DIfu75cFQGeN!N4JCB?{Ka7V$hZE@OPxOjwiaA70ZvaOZxn#he%F` z3PF;V?gN-pxwWug4;5ubR`w8vx3|9z&gZmQ@_C7dgPQI_Z{~@A9L7)3Kgq<5NwqM@ z%x1_mzaU76W8*&NUon2F_ywxW86AKUY5Yoxln1NANzM4%D4RVKqbTZgq|f2YKi3GP z%^Cg#l|hM8TuVOJ6<0BhI1VK~9BZjDmLM8Xi6&~hfiv3JOAYM-1>uvVO=G#7Sx$$I z%>$)ElyR-r3?c2>A3JAN-bO}}z2yPpe$Z?yGOErtW0FxzRk?Tf!GNE=%2Tg1_$e4n zLUv`|I8QP$0eBm=;-Vlih(A)u6xPcJ#bOUD{3wAQ+>e$0zkv#er6_vUQ~<+9%d^%Ho(SlUXA!H{I#_?QuajhK50l| zpL2CJQo(x0X_wghf-l)WwjGx~iJPiM0-F(LJN7b{J~luVd|(PR*C0_4L2LD7-#V41 z4b3qCWycpG*lmFXY_1#<%Cw(XXl*P zZ{CzRlN&FSn@F^yFusWcM`=FFQp+l1a)=X4_|B13@~D8Mt#C(Q{s&4+EjgAy1KjE2Zvq^XjFKR z5=uT$8C87BJsw}Oy!(+)z~%3f1tqHe0DX|F&q%g!Z2?Y!L=e^@6w1I|rui<8P`RgL ztmW={1e{oeh602?qhw_EHMQ)($w-EU?jrYM8LnLN?9f0TS@I$TA^mPan1;1ohX(dacR>{ml<+vyxoqL zjiqYMcqibhOogqy^zdEDWb6L>m&~#?0g7S6A}+$U@QWTX@N>YrA)*D&;E`T!{q!$e~4{Ka& zLw;;M!=7`)Tf&3Axs_F175mCdnBjEyLt{FJ?4Es7VU^bH>FI1%Vg3%7e6jun-1K&e zjbf>`ieaKJ46X3zrTW7PMUA+8V7%Z2)NmKytm?BkBv2TwID=wvqJU$`qkj!sfo4kj z7c0{KA$~w<|Ldv6YKx~SorVw5_deeLt^}Sq>d!D^Q()UhVdJh?+H_A$_9XT`okE`m z*oYCy;LSHbEyt?gby*K`3f4GJPMv%jU^edcM|Cs9+oppa?B=GM!xt3Em;&eXNo^4D zc{xY{M&}M~y|;int}w5KZj)RY$Mra(UbE2hnco&TC-0#aG987!lvPIGEQZW?hM@0g zML(Ts>i&*C8>k%XWK|?UGbZw-ArO?(IHqN1KgaGA9pii+^PM6+4NoRE z-vYS1Pf2OiE93LuSLIYnHy6$2&8b{RQ#xS>0ue?=M#k38G`Sw+a(_-Pz z-F_8bP_QLhesZbt0~EmQ;c-x4FAP`4*-6P@xvp)P)!00@qAM!35as-y`k_4K`)meb zc0Of(&u~#eLlU7s5&)9|qg;T!n-%2!Itx#W-eg1?EpZw~$%R**z}Km`1FJ%mRRwU( z=;Owsm3$GjW}<(Scv^!=^B{L|VM@!j^u1r>cTz)Mc5K=_#V0pHen+h0U$3b$A&Orx zCZiWd4SDn1`i&GRcaqQ}#^bP6Dlu=e)1{R0Di1F_V-Vynr9B-oE1OZ)u|K8Vr)u}^)bis#a!h{nh3f4qYFUQSO3@6f28+L%jq2zrN{-07UkD|Kyh{IaP9X1E%RBh4G=bA^}LyOG0< zCpyLH-1hX-pd}XruhwZ#hbrTHO8chQuBz8PX(@{eC5s~~0$}^`otjR)XIdrOthw|@ z$X3>;TLyACk}frrww;9y5F%QF4(BEnwPgNxAhYT1Z|5_Wr(BIQW+Odv5^_KDr$3~u zyVGAg8D6ZZQ$%ey1iULR4E?fPH{g=HU+E|g=OZjzT4gBt{Murf;wFDFE{Q?+% zY;5eov#o~}5Rj^Bxz~l`_V%`NsZ$TB+2M9k89OiU_rBOy8;83=8p%NNfS!S2If7$2 z@jwOt4|sT90I+LqF0V86ReT8%b^>TrA*TsTL~&f#C1+ z%eQ7p7Ru{72Hx^bO<7GTQ5r}BzrY+MR!2?G@pwVq{BrLtYA|Z|wf&1Yyg-yE+G(jw z8BBd*r`B@BZFI@ZKhlPbKfXg*>HF%f&qO$*$2j9vHoWe_M}A!a&mT%DbcOjpnD*Mr zQ&m?VgHMGnZVb%u0VeuhLNAzQ0Ylq11jFjr>dv7;bbA;k&-|kdR+>4~6rYESvuFo{ z7&?l)5B1Nvv8{ve8j#hJ4y{DI*01ajh})XpH2Rj1UCSL3{n{+DKf_(JlgUC16);1R;DMkSn%v`h=*r{UjbMyXx;ly!l#*Nf01+fiH+_=YQJ9oJ zY|puWp&_$aaSFa-6A#Sla);oqt&I{qE^yId+)N!pBFuc%O}%(9U4x|yGV>OOcH1P^ zdwLuqe#;6l)=VB?WJCj}!fae&5)^S&NUMe5*HC#kQc^d2RUym|M-gDu0`9t?S9@($ zVjK(w!oVfOEC`|&T$H~Hmf3;Y*y4RXCEddjpj}P-rVS zH5PY5dShM8MJCQ_x*P72C>Uc`Og!Fnu6#l-L?F)j1(0`HYoLwE&~3|(6rPo`vW&H= zsIN#aF__e$8-C=&e#?UN!dSNlo<<6d+0;EUqM)p10<~_fpCUI8uYcp<)ni*4PvpWE z&@z0Q~axE}5VD{OV66bQ|>d0Y}5 zFB>=(F-&vXdlWV$)3wt*F-wM{Xk6lzHc^PXzE&YL@8*ip5m@J}ZU+Uw~awWke&_rKH1cQwRp*X>AiVUQ+0wn!PqeR_N(y^0l}@TXBg3Tii9+@$F&M{(yu{i_ds{^G5YN^&3d?YLmO!9m z^25NBfD~1`2j%w;d9k%{_;uVCiiX+uxHqcFdr0aNE>})w-n#kx1kmH{^J@>Iw*y| zI$uOzhM$iuv}o?BjJfpud?pYhTy3_wm2Bqav!STg4$M33JPkE4@?7X0lj-9u~Z{qnb`;mD~K27j3&d z?lSIR??3Z8hbv$(UORs5CZSsK(tv6LX_3hI4X5h;OSR3FOB_bCBx`H^X6+3;0Gw6i z)51O6M;Jx1SfAMe`RbDh4%Xtu8#`&}HgTgvx!-0*k7z#P6+f9cqi5!yY% zZR34FPaa`IT9Xp1NsI*)M^NX$7FTN!@}YOg+Rsm)T8#EMEh2%LE>m&zY8SH?F@x9( zBO{{;Iw$3Om($ZvL?TafkEQ@pja4I<2~%#W;XX(`p6$x*+rC+~)uSTR=GhV5l-w2< z(r3Z)O`g{j)aOqRIx<_5ul*Loi%Dn>p#@O)A7bVLdo`fND;ax}+dxp5Pw=8bv>DYA zYf3$x3~GnKETzyM%nuen>lS&|1JniHDL#m{@%gwVq#d>kqLX4nqZt7!8npP&VT$x7 z+H+=+aGTZ9(opu8aD&R}jJTZ=1{u2C&sQ82#g(GDnRgz2E8|- zc{?7SwAXl^Y;WA^*!mbiMBa-_7OaU#+{{fJ00hs-m~yjS>4u)k4yT5;XKV0baY@3k zI?}x&H>rOdcAwPF%l4gjy}NfkD8d4zIql_`b1e66olUu;)Zfzm!eY%frs`eL1q>~p z^GagjaPEv456PtK*HvykWMTBzn;G!>mfiT8ClD_pWhTx}%>jpl{qx3E>eleA4y9L` z*Sd;=NOrP(1%?(vtnN-25K-zn8pZqzxH2O_%D0wQT6l?{nfBXXv5Jv{n9!+~cr7Ef zOd{c-;w$K~h{@LwO^)aEw;A$2XEBY*4fS_wVfZH==pHWeKiNHAJA~R4GvYft$rA=7 z8YGk*7QFiyTG-m$!;r~CbAaM~j_j6!tb985dIKE>L!M9ez3V4LBpCM7`1I2qJad;R zjvGDvCnOSEeX93-L=)HuA!XNf)$5b*j63+RN?4_H3oc`OL)OnjB^^U|OkWoW6UT_*>d}5y zc+K?6wCcp+tE!axzXNA_89@h`J7kW>Fx=^V6ErKKq{(&!9(sjQL+ zX4Y5B^^Q<70#Ft$Na2rr$78xi`+!Uoy@P^$5J`6r)|4-W4!eg8=dzD~9T{`1Q5pH@ zAT&Y#j`Z;jI7#?&a?(jw-wD3 zlzgPU>rp=))5R+!w40}Xk!gG%<6y)|yy^%a!{5Xv&V0+98Q{xzEUVo!9T~lD6iDsq z6ozIMbH!;ez&ZDQUH(ga(!hh5E%7pw3VaE*Z^p$#&2-{hN1TjWSxjtQuphvLD>+Fie$W(if`|KgwcLM;aiPhz$=bw*28rVmyXkXO!bPDT9U8~p{y#65KYC&Yi<=nPGL_$;o zNp6|nV^fCR{e5|ryRCGoPyvK~oK!c7O)}RXm_QZM3LOMb1IY5ZW_6t6hE}7)q{A^pJM6DK9oB{_5)HiKEQBop^A7v=s&h|kI9d3apH9`MMyLb-_o>lMdGh4T<6m$zJtCEw`|slKRSq}cYzcN@T?{mtH;dWs3liK9|?{E zHIx)8cWlVy3K-<=;HS(CBzfaR&x0IwdKCe725fi9rx)6HTbr3NIsfF8w+b2%NdL$P zb)|jHsG~Y0>nIWfc#&=>0UFAQgv#W9!M*$drowa-Zf_R^_z(T!;=PGFxAhv1?46WC z02p7J04 z;`w<`ULm7PS!HtQxf_s;$wtYVjJq!kqD&SwvUZkjYXo`lFMa;K_i?}P*>f=lQ8589 zQ+>sj-#~VGO|g1yXwcx_Ob)Xw83(JhZR%r(6pD9uZVJ$NYZ9DQ3qvYD#X)~>vRIr~`GLOhqRC^5+!n>4C zQr$!>JzmzG|10{MW`ViMIZ$Y4-~ygbKdp^!G)0EuE~Z>UOqO1DOFkekl($o#Gx zz7V0MFMUMr)5so4#UdGGhWtIs3z0a_rc=?;HMJ#GKh8C7yt(!-P30m|c)>&HIld#5 zudS*1wX)J_Es0{+0G=wpYLJ4D10RF5dq0I3CcWWav^j(xi=e^>kDyRhc->&ovXTs< zTIDq@u|8QDqu0@Ksg%GdZAbk_X+$|Q#pOHN>Md?C&8<`qEIwSn+8C;quZAjwqJdw4 zn_rQeKRX`QGs`>9#=7~Oc@?w<09=TQ(dRavh2*l9LN!83Bb7}rqA)NVrTpGe0Q8!+ z)X$g>w_a*S3%Xmlhcqv-8Qm_?^%76a582rX)KA#HMe(}+#%GJvRMRP9VR+T=;!OE7 zdlZisKPK9&hTuCUXUvu<&hAlV)Rt;HGwbKi3v7lY{aAD6^&O{TD>4Rpwl9n7NeHDe z%Wc=UX=0tRW< zrZXgjm;br-f}9i%3rm%(jLOmRnolm6DPz-~S!we1v|@ZUJbicfs}CRaZr%EO+=b+B zqn=!SO#$xq(HtqxtAjmdO8GR9GYPggq{8HjB~JFn0obQ9WI>Gr%48G!0`T!VDlcSe zO-ed6xAo3j?gWolS?CtcRik}f3ie4cf< zeNEC6R+~^SPJV;ldiLba5){#p*%Etr;QtQ=OZBn6y}fF)90rT5_uEHVTNagxJ3-lp zUQC8X?Je6nuzYNqP_d#;iP(u5)f~|s>BIR3`~u*ul~?P(gsJ+~8H(uY&aumb3h~#L z?^<#qGCjS2uME(wO;~({C7C7Qm5t%rvFM6~vJC%^mnuaAOxBoQ*`*>% zjf2}pRi;N@23X~b+oA2K?K6{%k6W+y%zh0hOVB|Vi4xNRLQjF%+NxiwI2yRRG76!p zxtA~KWa#9g?y8#uGTNP!QS87&!eu9}4tsHL&4zY}=g*gcV@E!owHA04E%?FM4%yN;za$jQ6O9BEcwZD<^E10<1ty=G2=`&gjJ<8^ZaXEV}q$hk(54D zV>v~)7LK>Wd1H3?l(O0TYe~P)k4yrOOn*X>-5KwiO-af2P7dHTH5&p4-XHQ&6y^h(MEtn-c%aM_Cb=%2?XlaM9TdfGvduy z!~^YM;^X|3E%QwvRza~*$Vzp6HL}UangO=R{k0(v=CCHhk|z}%OJ!CsSv3`EdJCjbyBW3-!t;C1zDswWAOO)SgD>} zNN-fv?H0!hN$+ug=l2D(?f+lqn?=m%e*K22|GLrPfZsHkfz{zPiGy3TtEabl#5;L{ z_8A-xkCOe(wAdOOx1=6ZkrLT6y>#ZFqN!$ed*FL&gWILuP!~m(8x_$-TV+2QbMR~f zzkQUIl}5TtOQqV?LSLSk&(t(a)tmS~UH~-|iwD!$4i zd{g9tV&Y_mSH$Cn*~LZmEE_wH?2>O3cjk86Atj!_L;$HZk@v$uz1&uzLjkG`@BtuP zuG!hD1W)pb!~ljY5rfFTFPYh_W%%^=?ROF`uC9JFOwuO!cc`xFGR>>uYvj-0(4SWz zuM%NYroJ{Mx(<$DMZ}6?fp5lp9Do)KG`Re&wq>p|EyfLu%TGNcY4dpc;g7`AoKkJs zF4EkJm%R9m@nAYc+S^fAzQL@z#!@^38T348ky2tStmS0P2$i6mPFsn3a4i5YsA+x| zvsp>YQO&%a=q_>k^0B^#H@i?gjz<&7MTumHM*NV*W1>c3mzx_#>J+s~?LNEJ)7#ii z%KNX>bX&p%Ghe>8F-ex2&$n3NlAWnMklEtP?}#mDe7NF|?13tD2cS zcpjp?B*G)HjqkvHE91qz?85>jKB7|i*+8QAVi;B@&gRt${)_n7n?gPx=Sm(jOjgGg zdrc+x!&jg1?3Hx$Kb&;54Q^s#EKp*5Xzh{8IyLSTWAvbBqu9L37W&oWOW9z?IS|B0 zmmZFzOEhWim|BO5GA#fadqcYOP0S}PyY97HqRp1_{jU2)LP*7br3MS2ee^=6Gu_Y#v?Don$38H8blyr0T z0_^>ln&wZ=8rPRoXN_&_z5dHA7 zG4G?_WJUT)FDK4zC?e#$T++ol-#sLc$U7s6aVd{v4BCKnQas^Wn(U!1F7t^6gav2hvgMKB-d_p@hq9^ z+?Ia!?1xrFXl_VuZdAI^Yu5wk0g#%Qz?r#FIU@H~e{9C5J<7TNduVvu+<^-j7^H6j z)hJw4DorjbTr6)7EvKiqS(AiRi9mjd^pE~X(8kV>Z&aCSF15>Xn3s$IUw9t&Z^?oj z*LTxQ5oUiH*`=M^@E!YX_7|smq)XIU;!IHl*{8Wj>}V|^Uw`I6dOP(0)mim%L#RRH zGq<&?;-cDbzeam3(dyZ6k&ODKIR8_6qn`-4q3pX!!`e4TsplEz8e!UB)Ik9Y! zZ+hX|prC8NO!8~rnhzkReZgefNee8&Ym)@eryGB2X`RvgNo;yb1igIFsZkcZw!{w= z*D6`*p04@M7w>FF~hBk6F6te*TaZd0>0M?g3Xnzm_JF ze?ZkhN~pas{^XBK`7H~}L$MxBXWu~re|JOuvWjHuWesE3&jk0g ztUuV|K~GPMMk-^hrneqzu8s>XY=JzJ=Rc(erZQPCDRqWCWtYk-ulS)+szRw0S|~2T zNGl?ms|&%8edtH!VzpFg5q(_dfKiyb|KaD-o4=N?;qKgDOJmgjp~lKFz>3Hv8Fxf0 z(Q=AeorA4U`up#U0$1})M{!Vx9pfqM27Hh=9&La4(`s~QiE9GlaVzsTT24QO@o^}0DZ!{J_3s5T0M{n|3S&Ee#AMg*4ez$@M5w;gVG(RL!F`rWp|Z^1nn2u zotUyy>xLGZHhR>LIrYykNu0w;oH6jA&vOa;TZ^Ttz9J1R^yho566c7G&tmI}6bkSs zZEyOs>nK*UhE~R46eXp$0$r?)%ZlB>?g;t6gs-bjLyP)bgw*aWM0Vi4F}dM?xXL#? zjl`I<^LDmTvWpN#kDyEOUed!xCDYb0gnp;q1pC6#WYZ7}82yYNr0 zulEU}&sTAjGx=Z7pJ03Rs+tDMex&wu+LaS^`JcK<}ieX_%|Jv-&JxxdD9vz~?w z9=E%Dve3dqwm)sNs{pS%zIitLOh6$;0a`pe>9v|wxL!H2`&wS;JecF4xtH+p;EK_F zwjCiEMyd0l1#_?|gFV3N1TE|f@pER?{AH0MA!cS~`rb8O8&kq0%3Sb({O1189J&TN zaADE$LX1(+@JtF_EA5(Vp6O6?D{boGak z?Y%qlm5MN(&QOC~E*X!DXg*~;PCA{qLn^m*NCmv5uOIR9ei$}dKKq?7sj8~_)Ntyz zG%UVRS9qSBT*^HE+(7mtx1{q74iOO%b=iTE=tJ5Y?SR1K)K!|zac?($B;lX-u6cnX zUtgA!9||3qnnERT>3x*o!Tg*vRf=-<@0PZCM_A~hUj?{LazzCNUS8gB$yOQ3^L(kv z0(QfHv~iFI%!`4z0g8^JqoWaEWAV>aQqn=7OTmjPT1waa!^Git7X^EOxn-t94mqq7 zy{N2T62WjehPRL`s)-%p@^!Y-F)tCBu<*5Sdvxonw~~1pJU4s_p5C9mlR}SJa z33v4fE1)uf2m{}~l|JyWI6HrcTd<%YA{M5idS>#FHU4K}v1yxI&|A&?=nMtBOg_*g zOk3pkt7`3W?IQt$tdSS-AF^{@=d{FizOU$WKZTK+a{o2!o4hA=lLfUD6+`vZpN!oK zP)EdNLioUA7b;uDA_8W*N0*Qgvs5pyhehq-uI86jVO{;e(zjCM+FQvIF z&KDi|+Fsd0f9ag*w?3ZaguIcuQ8h_HBq4D4qyJ_*0UacTCkzX;%T!)qD1oQa_{knf~c@ z_?xkGD*9T~BLxW2P^r)ZodQ5NFRYFL*L&;y4{uS>328* z@}jj+zN+wnjo(zOM=?~RxRw?Qdu{DZ>*xs7%_ia*u~_^rNIYR_ptP!V$g>lhN!^vR zoqU_hWkp%wTgplo9XIS12E=W{7OMnw#_ zLbc>g(J+lB0vF%7i=ynm&b7O3B*3|}ssf>G;VmdAcu^gFLHZZF!~bTShe1V$pCg-= zDKc~c;J#b8R#T-@uzNRr>lWh59sfg*s=evNI5W|uPnMmw3)r-9k%c1%hnWHbhDgX) znrPvon!J*egF9ECDF&h={Wm{l1yZ!*4>!iuF!maH11X?aVKIw%c<2eS-kB~}z|t2o z04PFhw|7883Yf$B5&0s6`&H-w z=L~W~_c~d?Wp_o?Ge?|6022?T%pz@NH^ZA)PoqNsh=g4kRA521rYoZE z>@|!#&cjdqr6Qy{61Z^e1AfNlj9YkGC?se@j_)Rd&8!ZYWGxML=lEH#yFaj+qEo0PSo~&(f|X z-dYRu|Bajjm-sYTFVFhurvU+kirBX6H;^=CG*!3r1uu* zdhiKf<~dP+EhzJ6_#bZxXoxVspdCW<{r1pmuusn;& zR)JmLLYMf)rcl~`we-zEcX8Io^b5St*N6v-?5Fuyaj>r`v-;Ay85J#{o^55|5mMuz zeHq%M61RZXlop6u#A-`%vVy|)Uj~KeRDgv9ib*Ns#veVj!AC4R*=0>sVCna3ZLHy| zqu3S~Fp^^2qm1E;u8Bnj(89pybZ}DkqXpvVZH9_U7r>`%`7WQY=2O#%bPg(?CrtbA zYGzE=#b%jZ0Ty@gN0vqP^jxGD+qF3?>?H*8EJ6wa-TrjZdBP<9qvo=$$i)G5^itw@ zlJ9E0gh~r{a}zjshX?C2wJtveiSeJka`CpmKLNR1-+K&$@fr)yCp8MCafb}()C~u6 zW0;_nQZiy0Mf)Z_PZYfvFRarE^(CGOV9i0%G%?Zbbet zrKSL*kD_0iAtYCjDi4%H)F}%q7o9S|;)fbL8?b<6EIxXY4%>8x0|{6j{vJx2Py4@3 z-OP%S0%AxZn96AzmNm3MG+YVEM(k7@-A~&n?AL+%LgZ8$0C-y~idJ0*|KcZTXc&>8 zARlo3-yBb*!UtWq1vN@8FW=Rle&2M~eF|OBcG}2U(SR*DJ#Mm7_idwyC@qy zgF*sIDItJy{F;~MHaeNi1GmILU*LVsg zBgj3~E%JdDN)3af!M1`GE_Y+&xcpkji6kuwT_cEDE4^e850cO95V&_Xn(%}f2(~`?LM=Oo_?aV`)uD39He+2~^y8w5`Pm>E>0MjW z{p%@TIuW{q&X;=o;}L;M&yDkkf0^hxcb3NEzb8A=ZSlcZYYyc&kUK1!6OF9Gvo*C- zV5E>ikLKqb&+-Wb237m|NN=@|t$CPHe#VWK8(h|QQ)~H4_4EzBB)Zzi-uZ>Z^cXZX zM6KB3Ty&C1Ui8v8$PBJonjY`{dYC^dYYJJ>cnIfHQM{o=gh(`2R2&$t4-pX1FjvtL zO^;4U5Qa&llU&5l@rs_w5-Jm+iTRx-<}-$yJ3MPR0%Y%gZj1fh7uwE0y^Q~y@e-TC zJQmsv-6CFhC@B(jA@|A=fn)StnD#zMgR9Yk@&Nu)i;hi2&u%@3sctkfni}=mH_QL= zoJFH#6v=W#E?o4S+8Ta-$-qTFxK?46MN=YtVZtRN$lBXe8lMxK+cK`1{3(85EVK4% zaQ22Sx!$Gl014nPaDl)R)TB*Fh1Lr^0~8^*-HPZXK=P8UnZAl(^l)HfnS z@2=r^n3@L1u_>FTutt3O{Ie?NpL%qsiCou=$1 zr)s@;K(EA(x6BTk&RZJS;#NQsfU^mVVXGqBZeWi+?}NNkt&ELDT)SVj)`sv{w*);-qeoiT zLwP41nHgg0W2(&|wRw-IkAD^Yd8)zks2EBx$7AQvd$*J05ZNWLe5eXpXsQz{zt?L) zHo!U%ceO>GEAvOm8&X1}u}dpZ2u#TJC;r{Lcdd0!vj1|5t;@`0??~T0*GAf+|I;;* z#P)91MoSA5d|i17D+X{}3-VmTj~nR4FL_P4S5R3Y?o2tEyD1>fYl4njh)jljWbOikDztRn=56o5JSmEAuf5EKASK)w+ZchTGS z(x%gy4$(M5bc8l>xa~j8$)>_6Lk*>87wW_&!Y<_yhg$g-0fghGs|OrVSvR7YTBSaD zzS7m#SMXS6wEuS+(k}WKnvX}qkk-MctG#H-ZCm5uuO6DGq-%c&D4q!)tFfgI!#?d& zqkxc;Yj7tNJK6b!)txPf{kgF!ci+5n2LvopI*+g%%@Kn9#X{ZUAQM-4Q`npbYuZ{c zA4Em_+sH5N_VLiv)Cb%Tet6d=_bHWWeoemGHak*NA0g$$c_U*@W#kbQT2}<6>+ZVy z1^Naezk!plY1y$$;p zqW^ZsO1*7^L!olbgZw#sx6svMgQVybqZBBCz(XMbx|2$!2GGMYt=RWrpJHF=E`8vJ z|@%;a2Qe)O;Q}^nan+SM=4J>WV2$Ng9@bzsq{OEj_^xg8XF&yY zzNVBzL4+Q76e+Op4%fwPIiH?N@92PFjv0f}lNI*rmt|fKh%kS*GPXGZwEbVh&3Dbb*nO_WyW zmkp8s$l{kHm?p3D;l7JFxFp+vCpvIlF_n6vMu0j^cih;#c1&9ci*mYaiz zUm(Eu`rql|v9}Qw6$#tht~e8pmCb`L&g;H6tw!{RY9pXJllzvf2@PjZ${U6amoa8u z(PIOc6oZw~Dwhd#UcXR_9itepNfG~6hP|<+_c8tQ*7@V|?Y2F1iirW)S-+BP2zFFaV&w4jgBMMQ^XD*(-g&De6AK=6ePhL%E`q7Z_ z-Mm#~T2MDhZ^Ql3S6>0RV(N(Gk4}Ssz4=Gk5G}3nH~B!;e_+@@^yzJN0lX*G#bJtW zIy8lqx;<$}j*Vk}y><&d6g4`4DJp8!QV;1Lq8O}Gwd?7Js`!EMOig9A~_yT(BX%MSPTMhpbY)B zo{SQ|@Hy_td`g>vG@5DOW!3l666%&Lk@|eonZMCK+^Y>~U~l5WB+Vjyx8m5=_6v#^ zxhD-1c^^;d{Ja+B-8)}|AbFG3QU+Ob(+F`0>8O&i@?$fgH^{=4;Xc$uHG9sBzI=;jD)Bjuyl*jvLt2~O&1qDUt?1OvUPq;Wa ziKe*O*{>hgz+gm`eoIxTTZZqCexPKie04*NBx7qSga(EM)37C?SI~vEhIAN@>=MZh zy$X91W9)EMj}|@0lhC`fth|MC{n}Ca>}Xxgb4!acy>s2QAbK!3LPuKxBadkPO}+MX z(HnlB zS;k|2euctK_eVuf$_onatzriX_AhzwqOF!!Y-#s*o0q;!K{R?+8U$Z|Q_wi}A9`V8 zI}@15Qq+d98)Us!=}52TEqL3~f&~PM?`i$dZ}%2y__eJ(N3?8O`Nc!6=4GyhkHd5? zZCr&`jSiwv-hO;>0MqzYw7b z&3i=u@B6N9XM+p$fK7S^vpja$i&+N7K+kdKeO?)#iib$-Cb(nri$t;?C!u(;Sgiba z`=L!D5GZk z1_;QDdC_B3y|&ufh1adr$x(YsrB25;dG%*S{MVX_^qJpbUrqTxWpyr8;vu0w2t#$ zy#lj8grnWKk42`B_DQ}LInPB3h#JklmZV$!B;RY1Wp|m4TBwyTXtZa=NzwbyF!zi3 z#LQ%tHE;5N%y>46ulwYixvcxfPQWzZCq*8aua`7IhvbyyUnJG^4R%T?W0SZ7nMm`L z%GuGj3$(p6sQ*OR=k1eTvSRIEb+fB)Z`61+A>!KlC!!dGv*7jY0=HM0O!vl+Ob}>E z`I%y_HKcg9IYbkj3{|~@h!?)MWnZmWSk1STGd4znOKuehWuXN$d`|_IeUFt-4&D(~ z{R*Ccp>*p|JK4R_8PDjbdD^=puh!>iUHa#4Lz`KnUxpImx`Nn~-OBn-aY;v0!?mkd zH2w^|CKju*oRL>qn8M>lE_=zEuu@D=H&LZzw;N*3bb8OqyT|3S z6&JVhxBB-+Q~p;3CwzI%of_k^6X{!4ivkU6j&%b|YlF)YdzxpbJLUxqdO=~Adz8dX z*B~xd=R?>_ktyS2b)~Tpn}2fPSGff{s{hF;oXnD&O#KX@?$zVuyyU)p;4nQqyhiAa zSuV2)TEtA0+VD-EPx8@q8g##ll>foMU$%R6KGU{;{vp*)IY)>it|-`tE~uR#8g>0m z{@Hrv!H#m}*X4G`oj!SopPVAm(2oi?%HphoJjH`n?&mG^Gj2@_p1mpVIizbmp(faO zTxdV9j_WWSQQDbGJPfKO^jZ2bd9pPYi(TLSFUMH-yt`4O<(%rJaqyPGHs2 zd4aSkX_WN#%gT>m2yq1Y;=$g2|4(+p^&K9=*Fjqm#zI(x?oInGJrKiBgz?Xl%h;dx zL_}Q2HPji^G3OGcnwGxx)a4S8?i-o!pHVK-}G%m-%$>@rIW zi$w=s)7)QXC)HwK}Q8JB#tS2t)Ga#uDidovlb z3OnvOnFw&i^s?-lL^EUdE2PqIK&U4=ztTt+r0@Uh5Tubf*j^ ze4t#uM6xzFg$Rsdq?d^AY7F4Y)M<#>FmM$JvfsOGIOcWo`uu2)HG^9srZ;GfZ1HT@ z*6|Sg^uA$dwH0^R#JrB%R(N$)-p2`i?6yPzVPe4HOF2nrN=$JO<6%r-Z135oaE)o^ zi~qUC>tRYXIzIspe=H(8&gv13LOnJN*wv}2VfD&*_my4E4WUbE-EypLz3?lpy2DjV zRbZOC_Wnpa#uT|~ z#fdudeYD;nI&vm>bCpj=RxiA)K|&~QsLaLetJGsdFTg5V(n^)d{cMUaQbJh~91 z>?2>l+ko=#4I_Fj47)kJs)v*-c9%BScv!KyyXo2Tth{cCJ-YXS@vl`kpW{6lPXpH* z9nb4yo(8tLCTLN{p&O$HQ6iB#VKJ3~fp{eJ`_gB1@UU!p=Yi()8Kl=a+rId@30%a6 zg)IncV`z7ZpX(&n!ohg(h|zz=#&E-1vf4?a!>uE;4dOO)u3s$_N!Vr- z?~UH`;Cyg3siO^xSR7pHZJV9$y&`y;k}csTxgoi5pYD^}R$Ju32svWQiLlmsC%)vK zpey6tYc0kZ+1|R;^P}-_p|aLjEW3KK zPhm;<0W!MM8`XG2c{d zO2=js`+ER-ok3v1P1c-6ylAUbWsy;x!V8#%3@g!oYM(RQ7`s?_6gR@I^E@waK;zX#n=B>^YmZ#~9 z4rM4&Q%hCzk%EI>yH4Jl6T(9KQ@!yd;uH(MxSt@X*}-Z5C@wpz@N21Or)do};d+_= z$-M}ncrm-7g6Z(-**ggD$G5|Ef6?(XVQ|VaQNx+S^hxgK-ka&(C?ti4dhiRJ{>K zbf8(xY_~S{L|aRrx)D#j`wwIj?vqITfg9hyn4#ou5LYO7!9Wc73f^W8g)%euxAI@{ zkUb5dtJ@6FcV2mr=Gyrnt@K2J+kaZPZuiL*QMW}kVJ}9W#+t}zRDhVNYWK-U4HEwpJ`wK~*UZUS}Wk zC&az$uh0d~`%JCyHa(1Slkj3;@iJ^7YCOmDBSsF6op3hRtnf|z-dA!}HtgzHI(c0i zbWXrkUr*<|Y#8V=%{-hQB=s}7@Ucu2C)MG;+gFEI4H*sJibif?b$jd@kBEZoR=yzY z1cMHDokl#S@Px4U@u-RQ4>k`q-v9Uh+efNsG`eYJ5R6{8(F?F$UbT-o94REr2#fSE zTmgmi&86J25cH-`Az)RSDYhceyifbG^ z^xcMm#Aqjp@9KUDn@unYg&hHyaKq8yNxQz{TCz^l{9>_w2Vm*Aix z%N*J~LfdKkb`wZ=I$g&GZBuF{P``S*Udktws1%{alRt3%HiSbvZaVlpZBUqd`rCbp zIQd4AL?ff}H=!JenT#pdgr(5o(*2JkEl5P7%O)TI@hN4yZrHlsM4Bi zJI}vW2JUeNl!!gOfQNs+9?g4rAp1v!JvpYei~>C6!t!UETQq6`*cSuUDoE;Y*<2H& z@zt4Bl6@7sLYkoHn|q!ue8)3$clUQOhHuYdjBV48ZUuGei!B+o&n!sd2Wrp4_J;^J zGkh;KKo^=w%FG!of7D%_~{lD^Rxr)`NFWsJHz+ z6o)dl+^W2?vLm;FRj*^b<>jq7^&~#i%gZAQVZJq6 z=C?j1-qe#c7#x??$_zPaUd6}o-CkL1Pc?Y4{x&`ET8$qQ;?-)>oMmLp8OrgbTKZ@8 z7exQ>-vi>Gq@Nnfyx_$$uI7y=J~MG_PkLQ^K|gfs|BJgS`iBdwupcGExGC?i4DMnv zS7tnGfuDlVk%yCWp_N=Y(mV5?^qEt{17YrwM;@D7nf?4a)NZ>=Yk%l>q{>g<8H{_l zs#8UJ_Vw=Esoa>S>Ocd>B9dke?{en&9$uwzkwZ&n_7+_4mYe9*79Fi}`dWIq;bHC* zV;W5tD7Y|bz(9dd#ccLF_Z`U<6emGsnT&l`rn9_vNcV}Cjrb}5A2R)!m@_XjQfsSiFt2~5GTp5#5RWv)0L&8Zb;(b)thO}YoiPH zpc+AM=9zJeQQ?dom9~^%g@fY@V_V(Um%S~P%>RMuO>%&nfxdkq5~266i#|RQLt(Ix zN?IBkwW^Op&b3})R}0iVrk2gC85;QxMgeddpAC|&^SLqPUBn)1C%EV$m7V#0FTsd1tasMakCV@-`2?}M$k ze7f`|5V#qnUMURX0_{}4nauu&<@@_izL!5z2g!MleJGhGBaE=OS zdkmr2ZBHYPJM?_!?@ia8A<$jnZ=!Qm*KvzAoohbd*(|9%e$nSUr~0)X_k51>Cb(~8 z49%_f*%lE@AL(RF+IwAACi;LX=7vj)uvY{1U^RWM;oD`QCHM%6jhRg867)aI@>YSC zul{HV%r^`huaASnD>Qgm94sc!HnLIj$f%@uo!>uD8n-oB{a~=Rf)C!Bc+6w!O{2s4 z)Gp@(<*S6p#3+t1a{0@zZB3}~_C25N_a$N8w;OJWj8$0I3A1=d`z}?%mk|+kd(r$y zZjW!4yeTcYR#%ciLa`l@!|`u6*`fRQih3keslzf8B-JV;p0{S3c~RCB1BO%1SL7K~ z+K7S9XJX<;(2MT`C3wZL&xTFtx%x~diOY9#e|=xyWFNlC#3{>em_2DF61m_LEj|CMBpwk~2}1M|1S?n;NtEbBi{6PI(WCe1qC|9}M^^78h%VM*b*uBudfw-I^Uhy; zUH4x1%zfsRIlpt}oQ80U79*DddeY}?TD|lNhi5G5rbd?Yw)2(|jcHzH6EusfpUdIr z&}CZ1m@kh?kcx3yZBvP~I}hh#WrBqy&}(a1IXU=w!y&^c#uKtjb*KKRAK8Z7Rn^pd zW^HX<_-~gl9<}`f)=4u-OHI4GCDEVtlV5sk)xRuv@ao~TC3j=$>D>x~`4iZX-zL&T zw%_{j6V6*=K+~Nvp%pIl2JwUDrZ4Wyy<0nhsnRVQpQ!D9+zz)4h>3|iIy+mqNlDw} zm+G(pnv7a2Hb85nukQnTjHzpDC$8QP0h=yQ3iEu3YBdwb@hLyUu{Y_zqTjbJ)YHk} zpP4&n2Q+7PP*kVGz*>fQ9_#A4{9XMb$(2Lg;UCYDK7wNzj=5LAM~dCuG?Uygn@8s# zsOvMpc?k3A=;)S~mlxjEQr6za9+;vk^l1q|^tV7a5X)yjGV1DdM)RU6|NQyWGNl;D zMdW3LpO>X*?IJuTGAz%hYOwTbM5})yUA^`Ev-8iY8UvN^wUx4V%2%3hIty-%+l=vM zA=);_fOGuo7lrg#!l(zrZ_hxBSOhI%*J)#`_=LWO3H{e7E75$BSkrNzXg)^66%vw78rB(v9I|4O=kEO-$YJ-8toWTN+A=tz13# zekd2SCTqfhJGvk6Z%xeRFAP zzd{vbsRg=doh!)9wje2MHpT3V7(23RDl!V`<{P&QpAo-l6ACQ-Lr=?UIak6H!QAUI znSV?TiC8;|mb|k0BU~Zwu*i8K)4BrbRp?(8r={y$)+Defc+Cv^vKq-#e;|{{{I!8I?YS?W20A*dJdvC6_HW1V%Rcusx*b4vK!`C*``-Y3pn6 z(GLSJ99`TWWm>FYB<4)T;V$_W=m?|l8kJFFd^#jcW@{>+jNmJO2k_YQK%B{?J~Q)f z07n!onE!F5mp~B?sOYS-`%cy*K}&i{Ca6Bh=d8_OW4H>sj5Jn1=L#o_}r z@fN@3CD+Z+c8Hq;;Tob0im@A7RCQ&#d_(*9RR1zxEao;MnFW(uAAniAH6*Y>fBtqY zTR(l9$vm)J)b^G7wTe@|L&AIWOmxq_G&6Cygyl>MP!GQE8!U9V*Bis65@7wPTvhJr zgS%HOCW^`k%Rb1zsi=5%5gLL=NCryY$a{NxQ^Hw!cb7n$rI?tu6e0U(qSoUjulM%$ z1}261m&pJgUvAR-`Rmun020uJj~%PzDA_D#pYr|lm?|o<1MNh3k!;d{n2;WoA1xg7 z=75*H3YkKa^*K33sA)gd9JTtc!;YAI=4vxaj3Jw?nwdanu4);)E3%3(%p`_I(X|q* zgocK)b8;$!I6y9c)2xb|93jX)FxvQCOA#?qX-PvCTwF}7BC96BS$?TV2rD;JZ{JG#5d0%v zRO_Q=DsfiDNowmw@pWMBpd;?qjL^<127rZhW4S2@$*K@(!Lbv zW(%kw3i3n4uYJ0dyzF4}r2h#D%KU6OSA6}2<=K#m3x7m=lBvaX9Ey|UDaWYdjVRjo z$qm8NHPp}sjTGLW)m01p{NX^FEq^OMpLKJRL$N169L zKJzy<44l_rz<(ijJgKwN`%h*Ocg)tXi<^!aLq~4KBj#}#$X$gT9DdhRX*|+nCDOJK z4vw3q9V8vuO-JUd7p}KV(=`+}T=cU1Aok<%O`mR?v*stbWR7J_d#S`C4L9jZRD0+}NMo4w%UiC^S}HQ{a&O*!4( zVtb%#DuQ!L_lwaWok)bhc>kq%em0Gs1M%Eb=vP`ovLRNZPIRaX-YC+|1hU z!uIhCMmEa6HgRihXfMCJ592#(F63Ed`od1X=cjUNBg478BZ%P6=E3V9X9wPa#*3aI zNewm3-i%yfr@$TeOqHvKn4B3gU)tUdQd5n#=BN)e3d~W3(6!Z7>}D(3&D%>CA1rP; zH311t(UdI29YHP0%&CTpd?DK-4bA@K`^8qk*i~+bwvA_S3zmCNBjbVMocs5=?t|^6 zaTUbi;1BVQGp=~=z3bME2X1}IYx*d*&G{Tfz7B_kdk+x^v4#*LT8i}kX0gBn6pH%t zP=Lz)H)0uSWnB%bQ`FrmmY0#C?9@#qzIWkcQs)r*;=4eq5pFr%QPIX#FS1uSzws+@ z^a%TKP9;RQu5F!eRh8o2Z#&q(LVhD(z!3+IV=7ncg=b4RK;l8{0{OVY^N_cVmW+*# zZXWWS*%NI=TDQ|lyPD}d5E_-JqM&dkk&L?mZ_nXiKzyaeQn-`rpUfw-0i#F5dzj&g zA%%-bW;xBQHj!$b`-UAZmPLA@$)+=uW_YnAKjvgkA|yt zxnJxyp=Ry4F6?bM`Qd32Q+iGP%8*9CQqMn(%WmhLRq3-`7h-$FX#uA8gE{F7ZKge$ zHi#IJ!{)3J@iTg~z2%CSJ* zT$uL(+3h1##L>Q9a;H0z@aT7JWr~Ku2!9iw-a35pHAzB# zQbpf-^dz6ahRu5IsDWmWrjS%{MAd8QY* zWrWL&H!~j}7t+rsuOjypbT}gp-LWNg8k)IDYqZY1Zrt3%TAJ@4?ZM{9WVQFpgz#cdl%VHh@h#4hw^~1FY-+3 zpi%J%yAHnyXOeD1W`&7g>{~q)+v9KCjV(tVb_xrK9IANuk{I%O{2t)iIO-B!{YX-K zyxi-tk$|jSwLJK0|4&rJYi0~NmU$DCMj8bh0En&r@+HG%mO#F7X>bSW*sot5;Fg-y zOdhawoyYrY(ldxWVvP(aTk+NRYKDi4IvFl5dOWsx+%*3XHVS&24mO8feW-eXi=arz zTdkh9!Fxeagme4q`Lm4Hkp;FJ3A#caq|I_Z2w#nSVht1So3r}luhZsfe82b%LO6gW5!8&#KFtICo#7*dC8!JV&nVR6SMV@WD*R1&F zO*jv>--R=|9FhO7I@3E$PllI0W=J?G{f;E8-Z}90`cx=uvCVmDrcufodB6lwe_0q2 zyXW|@Pfo)}I2DH5^x(MM!m7INs@pYK(mDPwsXI#iM6i-clE0ev^B&geARb$LWj6pt&>gWa*zxeUmE;o?snJ;Z6(fCXeduCs85WmWYZRN(WIHlIC|DG*aB27G?^l~Q^lc3fd)+{&-d{2#IJfS2%%kkrMgDey z&FZ4paZ@a`=ir<{@1l$C$;pb6+l)uTQ|sfq-m5yT+5p(!IYcpt>@ezRl;}t52{U7= z2L1?kUQe5nJDEvcci%>)2wpsui-T*mah@G(-@vjGU9W=~{*%#w{u;d85lE}7467?k z<$gfHzE=s3W9}3*1HG|$75A5%ud-@5{}n-7>t9ZIT326@zxtG5{Go?Y*KJA%qoKC|G-vv?g`U$_0^>Qu72w$fDX9hcI)aK^%q3ft zTmNdh3It7&*gD8pFeHMulI0UkBu*b?-m>S0i*^p8gVL0!);lB}dOQg4Atm)7-3Q!B&ZLEArq^#yR-l%4 za3t3^ijPDyZhW^Q5M!LEU7|%hI9`ubO$Zp?G-x)AOhv1~(T}qR9?=C_Lfv&Hn)<`C ztOQlYJ>wbb#JVpUym{za=7z6&Guxb_#4xa8;ZzkNX;p) zjI3$|XNZ__-<+ya4qy1snttMpK#7wXbsuudq!AcS1kMF6Bi<>lmeQSq+Jt705jG!k zifgv;n`YZDmG%1yabbyrN+P11jO#+*?q}(f?S7C`eDQjTYI$hfDYD@;0o_Dx4R83z z`vkW1w}r_!+7|_FO=#3Kql0d8fBRUq~`MRn!3rf%{lwtuJ>yPQzs zr@V&fvrgf{&7|J%+6!hO6ER7nq*bZ)n-m|df$o}T-j}X2=2dPPh_n4&Yi#;g<4rz zbyPW=;a7vCA*Qhtd6$>74y0;f7z`%ixgHtg6A1+cB04(5i`9m=niJVH4-|}WUtcYJ zkws;)ha<#TV2!_Z-3Ic_Y8SV`V2ZUsN9QGrwfAC}pw?IYE5IY@F;5Zy_j?7e>4gW2`GI3_>mN|G2Q*mxSM6;VrusM=VYbj_6dK20B54^aow@) z5=|t!LRaL0wCJ?UHAF}@_nR$u5fn~DqtQK}`BMu=atb~Pb++4O*3eCpQrq8P+Tb(H9mup-S(3%r zK_A*l9S*07x9{_JYQU`K$&1^^sA|2ER}Jyvu|Updi6S-~}soamVz&4?U%{wesF?$(w`KTTRsKJ#RlO_|f zaG%hX;`p#0ksX$G=RZ_|)BV9;l_`~HErF7YDqs`oi1`tM34I$d22w+=W%bG_2OTh9 zIw0(yaWq(K_uOt`4eKP(Qa_dQg{df__C|mG3I^U{BeSGi#s1$7ntAbLi9rj`RXG_M z6KeOV8Tnn+#p!pV)R&HhnhaGwOJ~k_GFGNWu!$!5$B!wB;zGs_1k%c3fK48-sJ+zl z0WdlsOZo z@sKY!6B8N92)&xpqobo?kW02><A>u4`s$xxB}=eo z;Iea@_NC+_K&{C#dn8oXWgdTWYAU8iI4ZFq8{9{0l>$|b)fz5C@=>3NZ9?<6U@|g8 z+Sxbw>AX*4B5^8nD(_R|QAH^vJ#_|97T?i*L)R%FY(kAiYB!TehHs`Ml^=E$@;i=geR5x4e$J zkFYCdtiihaR(_@u#)}dD~2V%Nnz>w--vd4`0yc)Mtb=DIPJ3eV)uQ~ zSfkFazUN@2M)c301!F@O|BWH&qn3=1y)$)idq75`I(dix`&iT7-o7xN+ZaGwK@}Ss zE zI?&%Kwyoy3sA2&W9~Zqgg-olPwhq9alF;o>WqO16B}&H?y}iXjp*C8AKm(=2&)7Gx zpt`UyZ+24?bLn_8U06gjEok2zN7wfRxyum4=99!_~ o7_{SNjiRTge_vfJa8P!5!F5&Ia%L{W4+jhdS*T2jl>Ynw2hzsy`Tzg` literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/debug/mpt_fixed_traj_visualization.png b/planning/obstacle_avoidance_planner/media/debug/mpt_fixed_traj_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..ed1dc2cf8a71dd9e45a37abee419121484c6a7b4 GIT binary patch literal 152291 zcmd3NWmp_ruq~3{8a%kW!{87SoM6G-A-KD{LxA8KNN{&|7@XiPgS)%F$vG!S-n~EG z&$quX>6xadd+(~+C2LiO$;*l(BfLd`fPg@jlo0s@0Rbxy0RfEz2LnD6m<2QiA6_}U zmsElS4^KFwQ1Ev=M^QCLMH>@G7kztU2vchtD`Q3nLwjRmYlqJ^jwjIVg5ZnT&6Ly} zKiC`VJDS;8lPH;48G}zkK(Mi}v2Qiju&`~Xhq7^RC;cE{W8Y5kXXV}s4Q6BC$&Y&} z<|c-KAc2q+5ms_dKU{Y4RK9uwp3OGWb8&gRd;f++e*hC5O;o__9!M}&|yY&_%x{2LP zzj(?VyU`LMy2&`XvB1Q^(G301fQz&fgJY-?N~|2TC-%FK+KH74%u?H#e;bi9;u zdTPt-a=av#5cb!6Bs@O({_#8^J~ubF9w5+RM%}cw=qZHQTf*DB?Y+`p6O2XqTn=%y zon~V)U8G#PZ+W`bIh@XO;T!Sh*9B(Mf>|+V8$d&KmEwgMVxdeN9aj*ED&_Bag#@%h zO(_?voRt?U`ZRTb^tydn>MqOfRzS9T^^0~k1aO+}hV_dF(Q;XWmtU}%fBkOa?cLp7 za$X~_QcoFc=;a*eT<95>q4+q#b-|3lV<&^VtNUg@*W>0mq{{NQ6nS1*MrBsa+wx{K zXq5@H9eW=gxK4ib_ZISQC-x!fS!q8Y{{DISlZs{e60mW*f@at=qrJ8AYuAj^A0iZD zPc+t7$MzePQW1RO(5F{r`);8M(+gy$5zI9FqzL~4f>jZ`!t@&)Y&sDAC4KPtzOi8H zyKl>VjU;{$^rKl9xmzh|X!t8Rz8b<*DI=Y2O>out^m^=FS+RQYiOG4z-eOs z5$T9Jkj=C_1Jn=A{-sY+@>yoTbkgsAi1LAP$Y7p4X6^Qv?~N7{o#Lm{gv51vM#`Vn z)Mp?NE+Te?<@T_^!f%U`0M^XDX@ii>cZm7nW&x#W5ku*z&4iOUqTo$H<>t zAXjtZ%}|pyMTAzeZ6Xg1k0$4Jr@<%>eoWKdtmf=)aP<|P2`R6n&?ifZJoHztO1yJe z*%;!)>LKRzXWam@QILj=>1ae+*&>LpG8?#+r3q5Y=}io@hSqU4#Hve<7TMh1FJhGp zGEuagsCm1s&|b34u$<_w#X& zV!&+h_WF;>i?;}v#HCVw3r8q<^emaLhHpRS?ds~H@!G~KnknhT!-Mzh(C4|};N+}r zmHxd|_vEh|15er#ca|;Yb@DCBz2r3qL-#w!#gi%>KM;}nf3?!=8T2=2DE_)-Bh-g; zJb61pTxQ^DgRkt}QAFV~uG#X~slpr8_GM^{SfqCe)=l3I(xiLzLvP8QGrod&)#u{C!f10ewrfK##rRTvILn*xE zyrH^oez6Hm(Xw@UTFQcf7%m81UJGP_=BtrRir79DgP!reT|wIdmJ&lK*UuFl}L-QFdFwcZ_9 zSmd*!>fv@wGAZ$NC(E0AB+w-hBXQgx^Tzu)S%Ub!bl<$7s4FxEINi*((*6`Rq4#A} zRSS{`wKEF8(h~5odRwH!B$tPdc~>KKw059Xf#8>LpF%h zfcsjtUjBTBe#z-*5sB9YA%2WE`fDqj27czQ2+ipyGvPU+ouUElYxI+r3re?)`|$15G?9nm zUweRX@)&~ix@MB*`C5~oUNz2R@5gPO4fU(T`(5(Lb%VpOFxOzD!e$-FqF;*z4+&uH z7^UY;qmd1{^j#e<|LftLS_bXdj#I$_kD#yD$%5(LBS@Lg?ZrIiLk^F|D;h;N$9`4o z{1V~hRh<(4nnD``)b*^lsHhGvGOBhU+E%++WR{GLzP@S}2drYB$HYyAfP#4x&Pb+i z=FJ)4OXuYo$}`u+YwV*13p>4E(%XaBX9n`^)-9e!;e9as^hQ6}kBc=d9;5{|V?XdHe81k4 zN!|M~vD!r%4whv<`ZsS}bC>2lkEbi8Ojj}sD*&K*+0v<`})GT&GzJfCKf<%W) zp%gdZF!?-~D8+~VL}mNr1Rbi!h?Zly#qj)SPQ|w@!2L9#*?Hu30q>4Ti&UdFT#e)yvF`Gm5)Z~uylLU~6bd;DJEIqiLJ-`2G ziX+={=n^S4Z`#N3YqH`E!NLX0M<)FOHyr{u9PUqTZ8(2vBR0DC_I4vC?P_n#30`9>?XswNVy=J1x`jxgi5_m zDE`dW7tX)aC-F8hhpzB&1i`0E#rvxR;N{+ASakHthNqn!E4@m|S~seY(cxTW!}2kJ z8Jj$=CSKM*6gnBtT=`4$IbUMZ4QNm(`dhi+&94;aZeCJWmWqojseaWv&EMZ2yH@7o z$DWO|FJHe-iB12LO_@8wukP=gn+zul>*%b=;mkfedp`+eeNt4syU2Q3T3=oILy3Dd zHG$=SiAe%DzKb+fQNeQD{_^}m{kQb~{HsJWuWzmG?_}do|ILg2%be}yza}QuxxoK6 zZ153w7?Q<$so}cpgNR79Z5o#im4HBN>kt~cS?yoaVi@YGV(@J`xw%^KdOj#`w;rqd zeeX?@Nu)ory;!f$bo{jph?5+P%_4tU9J(1ag8c6*|D1(6&%!-SwaEw>J-tQwhHQR( zp<;eqV&cpUC3shoCZ?o>%^p}Oq$MZg1|#Foh++Mf5qMo3a%r#y^r~e>kGE&Zd0}R$ zP7k69U%#?=Tw7AfrmMM>8mrG)0wyLVD&{$OR75rbOzIRk!OJu`UTTC$ z_qv`x()#gu|<3cN}nDr zJDWeyY%VOy>5a4Rw36jgPm~SL+4O{DorUthWE#ab0f0PuPz_*oWZFSm$V zURkDctP2V$Eh-d_8a;Y>nqZC{EA|6D6;_M&5g z&RN|TQoD)D?&LLIq->2aO~-ad0s|-XEAug~kiF$z#cF$6yq^JkMv? z*>bhDFGKh>BX>*@)jJ7_#)vz|_|c#oCRl8<`$11jn$o-+mUnP(Ulpt|mm3U3Lxd@B zLoV-hs2x56A|#1b*NX)V*bkBLl7~-54+leUq22Px?787nu-ko{NmrzVbOrd~lRmVg zk&=aE-GgW!FC%;q6n@(gZyf+t{=+x4PQB1}A5gwQ%+F#fw3<_4Z7rBYW9X$v!-0eE z&fx~5&=}Xtm0P9*4;IOZd(>2vnVK=zXiGXBh{fl(PZluc+Oq-ASJuXQ3hH=WdvI#2@GM3pz@4qXx_ z<|MpRYbx@mgO~*7AJC;N{kRh@+e4N23!s^md!j}<9%{)X)r$3qUcH1ZsN#%N^qH7) zg)DjZ1z||`yT!=`sgJKzuD)i(ei4aEGKLEV^x$rMPx&O_*Gc+@-jlMoJ-hx#Ej1OsF&F+yhNe^fnZvkQ5~h4=Z3x(&b$;y(w5E#vB)Q^j zH*&{ysv|1Oc*HGPBi%zqG<7_MFfVhe$lUQG8>v-*f|o z$8Xfr*%zhr6`oR@Opva#V|uenHp)b|HgTEmU7@B%1Zts5Uc49EfDuVJM7kpm$FIsH zFV2o{wk#{P(zz;$T~K2>;FWN&Pq$k}9t|_H*wO-GyV;WMWT_1hF5J9lOmvp8dypI) zI#awF+(alq9s;xhQ##to{0jk$m=O*SbVNh6l*Rl(a{@%4F`O1Yc=FN5Tlm23R4M3} zsD0{*lM2WUx!x?_aVD$O<7a3hq3sQkD@>)^*0+7a=AWQqTbgG5l!tcAM$$R zFT8t>Y8*xyo@KZ&(aoqasAY}10^!vXr+20Qss}`P^QiKlII!aYT>L><*Y92|Oh zV5B@cD%bQCrZtm65PfQ~tfYxlRd1IlzAJ#<*I4=Du0;7!U*WabtcdknJn6B1+a?aA zNe1GJ)sc0%p%0O76Z$f`mn`p{$x%&J#%;%!x(>h}7EX6C&$PdZy1Mh{ z2dQtC(wmeL!+kv)Ss?M-<&Ks+yV&C^ZajK0Z$gn+5BAfy)UFIFULDlWhgZX%CXL93 z*Q>Gvz4flINH3DL)8ZnF>(OgPg^Z%=la{#!Evt7-9_Vjo)3|GToA|T@{1B|5i?{_w z93(f68m+AvdAm4rXT0eOyTUrZl%D6;+}y63oNOp-9^ku}xfqSkOF{zBds*K2jetms zK!C7^LX4rV9p;_+a(anf4B#$Y{FZb*i)k^uTHt$Z3!h=bXlDN~ucbicuV+1vPza2t zR`XrNFA3c)3h+yUWr!PxKbBr*uoG2h1&8!PeO_$%q`Pub`1v!5j;TUO&#RT?_cyrY zd^c=ydb8 zWfjQ^2ikJe*Oioxpz$I0UEO*?>rkt!eYOjiv+V_v=qaPoV+_&nX0}V=_JRX+-#&|Q zhc$TC)_LC6RT;L=s}WUX%mvs%P6n z7!Tffzw3y1Z4x(G<3+e|I==1z-<^=Hi#6q<6r;P%5UAEb0)HX?<-r&#wl)ceX}K#+ zC*Zl8kG)9~*R@DOSGC9gkd8^#s)4_i)-L8CwZLKR zm~WBWWrD(=Y2%*J z`4%u>S$glqiW>T@9rcgir()$Qef!{j_2E;V|HA}L0$iWOn&{U+8T_)_QbK+AZY!jjl zkO{`#gN&h^5DYCpARph^f5%WgS}6jgDPa7>lU*nCTY}KZ63!a;a_vYP>6YfYIQXH7 zC)h&GPVKk=jH?m`7?tf@$Ak}b2@}Tz!GC@I@%<0MndG&@L(*E%cF|R`vEWSV+G66+ zG`M;tL`6+@5@z;Q)*1GXqIxytx>oqHD}b~JDZ)ktE8gcl0yIot?722%mJQ90k@~LzE%LQPBGJd4F-s< zqXJ|Pl^7)SSwZQLTo3P33S}o>vY|Of^YQdZEYJI4@`0O1@7T!&0wdzfNN0ANq?TX< z;>LqJ9QBkxug@DimFkniZvAc;CD_uY3qXFW3A0Kwaz3QVPm0g4`{@C!rD!&zn%!wm zTMK8ez4v(+R(h+V3#|Y5}@k;eKg(g|QgF85l1{KVo$w>!H zF2DbkC5<2{WeEi$vy`S*a2Tm4=LMOmzw+nQg(PqeFmIplK~jQ~i`c?cC3UEBIWyL$ zrlMG=c*J5*Q<1F&=~<3R9De1b=>uMqb!_KJbKsW2jdH)>ip4N(3Z2-jjh_I{%~!d- z74aKVO=JX2go$E&)P{qlTbZcX5ycsF3))gChmQfpU=r4*@&2%@rrp5uIxaUUxg6<>DAMC-?PI}uBgSUMU&!{aP2X9#JzZS2Jm0yG2x7&O ziz&WfFMH{DeEY2kM}8|opE48FDYRgao~juqUxcR;Y}(4rgg)2Y))i+XY!P}!zcKaJ z>7MD2rK>UG+cG(BzYI#xFBY*s`J!lB32}osXYU;x+}2wmyy&D{8~e%HRHvHJsG&gP!+>N1`X#uuk^6O8<7bzQFOO6(?o$&I7@nQk58CLzL4`sbN``4A zSH_=kZQDLr2#-o4R2k(4Sd<^CH>cZvAy&nX^|7X=x*66tb7qnouE$NX{8C*RS7Rs6 z%4%>^09B%QW9b@8jx2tB8|OP12lN9W3r}{*HQ#k#6mE_6zOVrM+*d zgUrin>FPl1$tzs5uV?ov5x0>PeN^~gG*3YDxwt(2z3dT#cZ+-n{U_$16EpdY|Dl=PKt}e zPGY;_cU-<9QkC7p@$Q_gw>75S4Z+}>Mjs7K5jh{4(Jt9*ac6cJn0Pm3jL~h}jqJj$ zBSfU!nUPN8RU*wVw~ur)Q{8N=_~~z!jqQvF^;)_t!rx|(eK8ViW^8-W$0;uE!t>GB zB_cR9nw}tBy6bdanKS;RPE?>NJ5$84J#E&kMF^ zav8!>KYf}Rf!dcb-45q^qq9?XrmTM}Y)jek?OcLs{*({4kU(>1{uOBDnMtZ1>)gl$ zYuUpsw9spABTN#wmuoq6GHObR)I96{5 z1l}3le{iMOI0xlc0@<}Uti3WGFvi(4sC^QK2mC%g-;b*t-xYl|@IkXVUAtsHcVKUE zG0n@INXr};PxYcB3n}gIm-zJQ)3xi5yu6uKaBaV@quuOGNl6(L85w!ar1?7)MPb|6 zh!Lvmi^88Z;c7Un8p7qVr(kA|*u0F7?jv6C(KEq?3D!TKUgz|@+YB0Mh!7QZgGd94 zx*En-;N?ug#u9l1OwHxw49Dy_qi-#-S6!(pE1K|zMpYOByL9og7q-ZXV%?g*nG5~M z3z)Oj)V{U2hsIQ042`OqWmE=#{`$(YM`Z4%((}jZ<~0p0JgT#+ge^GnY3QbuahV#$%@L*-pnd)=FPrcUG61QjlF)t+b?E zUOGZ-k7bP&=4USCT$h@Wli9P3WC>+OMj~}}gX4l14Q3aIOjT7CE~|kEzUpkl)YO!7 zbNye@SwehjTl!Wbu{ZBMMz=39V3VU+TQn#Ja_?-UWr2ijV)~L2z&D;Lwjg%op{}Cp ziVJ^L=HRBq;e_Ln9MKS5@5Cc%d*sCcE(eL=Jd%s&ht`|A@bM>~f9=!?I2;e5dFZ2h z5WB$X^R)vPSrhhd-KnuJsL-yVZp!d4vuzX z(NMqX#y{^7tMNZTC)#(v;gLTtDct&e0;OR-Q=)EUY<%RjwCBj?w66pAr`!O>06AnnPWDtWKuAeRB@1`}z*SO7 z^Gp?kB>>;d%xumw)smjfzQDD01v}(hN=k~AQq(_lm$)FbgEVKsrNBk1vY2Ih|4m*y zw26--gUd!oy8uC6Lt}8QGvF8GnRYyf0J?%X)u#r`NUCX~yazKeB>xK<^!E(s+sQfJ zA)_I|u*x{ZpmCCtLe?)v0XI6W>kX^t`v(TV^sdbdA#AwYeV9{=6j}MllWx1wI)b3y z1!mQYk98pt`9>_mlZjviljkw;W5lXZGn&nhta75vz@cx-P`|evm{vZu?Rj1BO+HkQ zrDwJMR8hfdn$HkI4+QP$B+fVl({Kljo0UAm>`jNIs#!0?R#qk@0HItb6l-*nY~^Lp zB#jRrLs>2>4f=55rDK?j^87-tQIo7G`G7;prk9GYe?zilWFZM3-e!-cu!rzCY#&}M zeV2?+<}jP^et?4sxP9^-EM_!$K6Z>;7_RdE8g6_vJ^CkPF;Z5$`!Jn;k;NuPoE7Mx zP2}Jb6e=aXJs|DQLc!KkU(MEd9l}C|QWf8r6DgAzz?$oBH@0_1@u}x!xjj);Vl74J z3gp`SN0G0HHO_Bu_*jIK_`4T?7we>K{W%I-zAK6y2g6GVb)}sQ#L%X}WNss1tMi4Ia^c^BC4$RDP*gY!=(i3;@e>pRb7R#Gwgh;*;l zD)5acM5nx5R~ZsTomhH2baz-=bQv%RD2G=Pfr_itXG@aS6%3xwQqR>)ak^2vBC91( zg7@|Um6AY~jonn=4prtEsc^)`e7nVn{ekU+sQ$5`KQl2))!eAxoiogkJPJ-6Kf^-OgZf?Cc zE_R#0K0|mV!!X(PS;1d}+{)GF`R*V$*;|7_L9Jx;0=x3EuU(L@abOj7%2T$x*&wOg1M}0p6VYIrY{l=^)U0xS@gVB9x;X zpu+0>eChDY6U4Y(iqN66I1HC-VG6CO&vP=e`rf`LObknZ$;#}=3(a>bU%T{ ziRa0R=ab&a0`dE150lN5fJRz@z|}pnDjiw{yuHVbQH~Z!d{z(usmVdK^|(uM(si?r zX-R>o3lBuL9vT7WEi_E}rZyJ-6L6k**P)b#s^*kF8-Od7;B=Gv;(}9F5`pKnS?Go? z?S^Z+QCsd%t9|&z!yd84w1#&goBiPS9N^>Kh31mjKMwJGE7+y)XOnijSvXs7acUiIiB-c?C7ZrKS`#<9z&pOnU8P`fj%{3ELfOSBV!+iE1 ztjs@85J91m$-?~GSbu#e`~ji-uM5DvC5itdAc`*$6@>T;p)Kv$B`L=I4dDIy*>`e9 zvbhf6s`Xk`3NhHVBG#w(GDn{{h0=rV7M%B)tb{v{~~FFOcUbq=F7TmOKVb7i+t6J4 z;%#JMsoRf7hn1UVn6gt2!dzISmX9Qa!i6s;?oHKdAq+#!cIw zq)=1fNI+mqeAkOLd~eQJtkaSjQck4k!q3SXjwrjQdULTPdQi!5;CnLrHT)_q`Fcs} zxwW^1M=u3)TeZs7lyl1@ZAC+5^9$Uctb^&&li+jqv%&8+0dN}9Egk|dkIEt9wHwv@ zc;=7Z^7uFziJ#v8Q*Z!c>2?UjZ?|0NctC*MVWlXm2kPoex?ARoC@LcH^U8pSp)F;r z+}GCpsyX-=wPks8Zlcsa@J1vk4E=Mc!!C= z9MqI#JXLLxR}HXtO$kTwxGfFb2*tV~hiZ4FE4Z1CzU;QOmDB)QLiemOf)-f+=pM9}|n%7Y1i#HxN-%-EQ+yyYAr&jsH` zHmhHnS#XTdWvMd|yoTL<#bkihTU3Edd3N_2xF80A2~IVD$&f{(+Uw%du8&j9ebUnU0=pxv^JyL>Q8f$1VexXYEHY;?>zCjpL<_k!I*d@1KlF_L0 z&5TFl2EO_@s~_0F=BPS18Zb-Q55{-y`k=5&2ey*PJf6aVqlB~AqpP7~iHOLe+% z)?&qpKu&Us<{c0ck%B&iXbJ7!;+Aj8;HAFdTi)KCh z#wy=k!Em-mdWJyJ(O!R|-A$1Mq)fOd@}AO7r>u?0d1WhHMWbXi&4y65%XutwYKjlRXbb%( zT=SQ`iREv_X6mKQN#MA&*@D4_JI9zgE2KL{oT**#-zOZPvCE^1xi&2x)vtmza4$F} zlgZ!M`*a7!MLcDFbLpi2z(q`{#V9+(^Iqp=P1CznITjaZv z0V=2c*=4Z#*yyp&Y=6Z+o0-l33q<7=@pUKB@i^jaa@^~}w`uA0g@jhCGJ;3MW>~wN zl*`Y~_5~M%WaQ+mNCAh3mLDgLmYbZA2)NNEIU1ku57G`-r)k5e%VbFN-sX@UI$2P; zy#1M`dh#)!!-$${DHxK!rCC9QA?azGn~CNE!?rOLnSHG;R!ec#f*Ye;z%R_|47|{V z{>VaL?SC2r9c)d%&=vGyxp~oJuhIY4*!gq_ zJq5NOcwanrlS8ND$BQx8jw%ME?t+H}0x?%i3|UFg_fVRgv{`V_>gN8R(erK|wqT@^ zkHgB^6+us=mkm_Yx0Cdbe!+_F2LbC|{uBK~M7)VGv;T8Z=+s}mt$$nkCuxuDj1SJE~7g zb6S+UYYH?Th>u%9wAkAxLS3~|i5JJ!Srw!|Q$79_KESks79rI;fuCqs-?*?ZfQVwJ z=NEG9*0y9H9w?w~H<&{%dYtknN*y>L>ScKRf)Md_w{Lt?cswuachq&JChl@c5$Z~* ze%^eJKAujC9Mvyn=*V$A(#pKGL{u&{w^_pzjAB+17<;XK^8y@V(CTc@R1-OV&YS&@ z6%asOM=-bDX6m%M*SZkG8iA?u67^~r-!`v@x}uog;yQM3Td18ZA3<b6g-zQTFLfk$v|j&a63}UV!J>R?zqs7Gse7N;?P_M{cDz0QMNlB%A?q&G>024W zayuf?;N0z2bIa-Qs_SN~>8)Oda11H5BtYe?F9Y>#J%32O+5tL6cPG~V6Y-#sN3>|! zH%E=#N8ua4NgSe=^oY-@FJ0G@m@t zS0`bw@A3HR!0Y2ebiP+bw(O>chT4WSe=sy5s*@MeKw zowyb{ejXwl9Kt^Dg1$MMogXUP3(7^V+58sfWg08Tbu;#WlF6FtX; zVg$#Ulx$8f>X=x3m(Z@utn^Tz^}t&Qg1H7C)EATEvB4 z3}Z}L1Vs~!>GkyWK~bSk0Y>wi}m)rb-leH7gcdXYH zdd%;5Mf))g5EVk?{`rMaY|dukz|#GS^YA;A2%%xJ=dZ;L zH_R^fQk~?F$MZjw=HhWZ7tV}a-{88>U@|qWxqixkK_j~;+)*d+pyFC`gC8JX?f>vH zGH)0&d1?)0ca|{a_mbUSLX`WK&z{CrmezscMt-|I9MWjL3owywh;;$Lb{6UNvM1R; zA5fXDT*I+@XUJ~XTr?cSYl~cRhsDE+&R((`BbZ)C1PvZBxZa~YpA6CTt=^Kj$T*%| zi?(mo)_Rk?QwNe8wceL?>^W(*MIhl@>xQi=^5*S$?yk|hQ*jb!w)!PIJVOj*+_(m)p07Y^M!g zNJN~e7|XDrsQ;8=JP?F*?=m>d-o#VMm^(d)6S)Q6tomdX714oF+J>tc&4baAR8GYD z#gYB#V$J#HsNEi=IUNbJf;gEMk7#jXuMinCAp6{csIuhiX_bxA3|aA!iRL-GCIThZ zd-(TOz6)O@&!UkroeAG-I3Bq-h!L2z#?Q5}!rFMFSU`I<6iB;jXGtzc`x~bXAinc7 z6g||@m<=T(ogeMfrVNyLbx4s%@n(E?q8X4b>mlRN?Kgznw*PJ;;2-bvyX`c50iQ`3uGrYv@xhf3m|NDt$C4r?UJ0wufC$CRr$|&?*RP9tNaQ)4 z(=tYdBYJ3fvv{V~g1yfRnI&{m=Pu~eJkg=aubL|2p==7S-Qy>^v?NYMK5Bno5qYfw z@3#2o=S?!++4~#8l@BXi;Ur?)Z#eVb2Jn!0PGUw-{B%Kk%^~+dCIuAdq z*Z~UB#e%^XKRKbhL)P}d%aS( z_?^|`0W2HjuE|E~oeUq;N!|2rGnXt;jowc>9%t;)&70Wnd`JjyKIx02yiQ1HuzQ0d zUz<2QjGS(3Kt>s%v;Cu&+J4|kph9sX70RcGqY0yR*ruPcB!{f8i*T#c`<=jlqDqZU zNV1 z)v=0xOj(a@*hdJZipTlFOBpHSTgLhHr~QqO$9tB_R#)>L83QNzMh?pgL`}MvRQT^7 zY{>u4lfWM)R3c-9p6A|jS!;RBj$3E?JiCFDTL0Mt;|^a)2KB1I*NE7*_j~z@^78M% z1r^w;aD#=NodJ1fRp4|I2896JwW#IuboFpNcf)ye`NCP}Q@R~Z>Rn_RD-tw4R9s4e z^+TCECl_wf;zT||FDS{LJPtP|K&&3y3L8V$j7LOlV}+in9!@1uVJnnuaC(g?FXmHu zRz>pX!{W@%?+#Us7JG(~b}9y6Muop}Q(=c*kVlW^OXrxIH6G1((DX&Q)Q7s#CbMf0_Oo?kD=axi(jgW9q zdiwe{Ipxs$Kn(m@n5S?FkFbac!{^64M(clRWn#tq8ggHTYxz}2Bp&-Uugmk@4z!*+ zcCh}GmlZa7VlGn)8u@m=F6DgaN7JQETVBH3@K&;OcDut$;D0-XOV7atL7Jh<=Y_*l zOcF~79Dzq$d}YVa^X#LbG4{n~gug=ZABWgFmrc2t|2Rl=9*O^lWc%+o9{$WuB^bp$ zaDIOJUwVd7l)?Ow7noQ1MX=O{g@x(QRp?tO#r~7kN?Z_t0lC2hdORU-{yZ~-RH{T{ zNcm5nx(?^7Q@HI6mTSSUZdK1qNK1E{Od4r|OW)put2%C^k>O#>T=ReVqtug7MEQVD zl1{xZVEz#uA!z^o)H38=i`&Kidu88=iBB-7M8or@S<8+<6}WOP-?4>@3UJlK+7dTk zZn*}nOQHJIghNh_I;utouwL)0kJxi}*F7fK?_7xl_!XIldtqbi;R3n@WXZH)`Z{R~ zi6WwO%eOm?g<)cj#*m*ftZY%y_xgX~Vf^hT9`M@h0zIx;AqD@!jbfkp-a}78bn1bt z!W%dRj5lv=o0nbri4L9lz_3MnI>Gt*`Sq$@c5;4}8nF0T02PQN5Y9a6B%iE1ux?MS zIIMzgt#UffhkrMf&~p^eJ2?-bn-YWkV_FFl22PkAN+}{^)r56#L&~#O+%h-{(krgP z?!AjxAMuiU-SatJ;vw7@wdn=nh|ojL{+ipTYQ!^@`@4ORWCMW)CAhr&Jy1}^wS3!kWIykC+*b`PIMM0{4IQ@20l-Eswk=-`LejGvSR}o`VP2SBfedqjjYR za!Ck{y!%p>9kpw#DPt^5OkX{y_5~A2T$*Z+0dr%lGlo_s0Xr(t#7SGuVJH45HSs0~H40_UJ|1sFcsU zjHaxTO3VXw(vQ`pb_RapI#947a^>}YJ z^w_4m-4M*W?6v*ZZ`Ilg==)6+Y^92OH;)wHrkenXgZT!IzQa6gspil$gM;xrK@<=_)NPj z2n(~TXNcFqB8$b}3e`eT+F(10$FdqpBV#6zmYiJe#v1{#Mepb%DCfbM^_EK@g)nv4 z_+=z#{>w4Ltqdm05HRng{-U26&r?$m0~=#RdxO`(SQFe&=77Aup5`#F{_W@d+QSu} zn(|sc+NqJzY3KQJ%b5d{W-HnRM{vpppPiWnHSFx;Amzyp%Vi0-mZTZO0x?OB6Jlml z8MIdyqz~z;XI#&4xq~F9|1QD)ht_;DdyY8(Bbn3+L1xZTZ^-0m%WzzXMlSTHH(1{f(!Fl=XfI}YL<2Uts-eO3)k{u zv-+8X;KPUajU^tq8HR+oZh%bRs8y(n`MV>r=L!l~xp)cd-5n~YdYLp_@z=9P)gIDx zFFP(@>I5>dAgPlw=D%XYs6BfoTAfa|x*#&SY@TJ=pxUqc3#6az)QKzth`t~nBs1Ec(SUo2-x9U=)L6G+nBo5YJV?ic}-iH>ONlG3}1FWXnNr`#7?((~3=wGUA!0`x$+rijo~B zboAvQv2IbNY5;ss(-r8HQ zBWrB1H?83$1nT^Q|L1@xGkn)az;W5pE$}mOwUFFKUDCwo`8vuNZG5>Cb6E=y{=-q| zNj#|ss%d3&7S~HWelKUZ=X8b@Z$pe1aFA@}z20P-72a-dO)zza2@SJHKZLC~eTAYc zVp|bF(&3!S9hu`hzjG6p3Y}~%8^J->@EJXJ0TJ1m?Wn#r<#~_`T=j^L9unjq|C<&4 zmVyk17@RY)5nn;wK8X?*1g*Rqe?7N$gA?@QbtZ&ckT;uym(k9{=`ECR6wqS21bW&Q z4GZg|r4mb}f^eYHDU$JX+;FQ9=7hPeYU1i*(gOy;k7$>PtHa|KH&duF6a-2x%7llu z!9JU}+{hhO^pR9i*(B@lI}k9x#JPP&9V&A~{xqro=FlDu9YYrQxdMvldh?Z9y(hig z5l4fGr*5LmLDxx+1>ki#$Z?_vc}{2IB7D@w3{nZ52f>@KKmgtr_}caO%=I(Xj7uIun1^Zvi#nJh<_MhC`-Gs7YbSus=#&Df zNYL9a+8yChjh86?5CEPB_PfmsFV9;;2tD^*(CZEb$70{)WAU&VJ;uh(2k3AVy(=G(lf$4q(p zhx$R?GJw%tDx{XDHtnff2@y6M+L^-l4G`EQ(?Zu;YGx!*2-T92^6$ygm*ryR#Jjj@o& zXw$u)_EOnxi0QPFtGL2MA^XU1y6@x4s=T9S6`0OIGTzOmS(w)m{5ae*`2%@U&ZW}h zLWfA>i1M2zE-8$!3<>vFol$@1NUB^+PL&KGk7Q9PrS1wt30_0cS9R6Ws8`YO zz|-2MEkvtZ^kZn4pQw&CglR#<8p0bX8@~|#Zqb@W28<;QL1I`$60$B)c}mcC!qa$l z2z1bBQ!N}Ulo9rvNFblZl&8DVk&dUZaNzWo9y*UPB{ek$F)?aKmGQ5(F{9Gx@*!4m z562|<`{&g*0a8*@&IKVfIB?3053tl*>+l0MG!538PZxEL{(hZ(0yo1^@phqZEC@+ygYkgKDk~_U*iJ~>AylH8Cle)Er*}~sZ2xD4P={8lzu%h z*02*yAeoM3vc=5TX&?R59@#+iXB!od5x9?bu1@>S7i=Hh@lw}^BIV+@RYt!j%QJ|X ztH$Yl18GA&K_)M8s3xblN9+*C&KI2$k3_O1o(Hi<)M5 zr~l%e?+iw$#fa&}kSUs#JIerJ&2rJ7)7C$3+?-Yz~SBv@x%El7)-aQ@Ah!s<3X21D^|rrMtj642^J&n1{8k?Exb!_Q#} zBjj@qFJ$^EdOe%Wo-I5)yl7hHpE+)d{G@^UmAK7#M0&wqsGUwz&9r+8py~?cY@Vr9 zqHA%sXbwDy>e}?x9VBtPv&~$b-Cvpq$kQ9cSDRYu-=_Oq{H)EdK6&y;KEITjC_>b+ z=%Ml%OY%%l|B$`3@j6X#vln$HUNdB<2DJ=S%XhMQRhvREqNVcB6u=;g>t_x~bFU9m zJT_k4gkS`0+HH)jNtNM=w;p2cnjYq~XN25rk^hZvGZ58aYj80CP9PP^jPJJdP;5*m zf3i`VFL+q3^WIH$d^`Dh%Cd@!aXoCzSzbOQH)>9S|FIi&n5Ue!Poex@>jpn`&Kwhx zZc0cb3JEz!wV33%`9$!z^+w0!MIX1+fV{y-k8ivE9zl`mWGr;$Xcx_p6^!w|jWRQ~ z*$fcRx82%}NU=RB_DtL6Yhe`%lgnxj3B!2_uB;av01mu1<^_~$XPwT)N6h=IkrTBa z0d($3(?(8KftRXp2Cj}aeH^Se{7~yauMd};hO-1SRA;yKHuT4ek{V3AdL!HH5n>qU zJsaYu>SLxaUIu$2#2tD^9Mn#$+m{eK$gVDcDR)Z82yQy3FcTlLb_`{{Cg?hSVcto!rz%S=q?zLQ9jHi75FOKDE&H*Q^QH1+)4X$P{JoiZ4iWR+6}-^GlmgON{! zKkwqDb6wMonjew*%-UmH5B8i`j?9zG8TLl~JmTkow>Zy*MFqwSOI$=NehNY3-7DUN`*oe|US#pt`ngT@(^51h?Q2+}%C6TL|v% z?(QxjxI+l;?ryuy?xR^+P~wW33hIo zy?4u7R*m8iEA1EBO_4$N(L+2v|33VGeIH2pb0QUh4iKSyEq0-inx@N&lXNOe7@%tX z5gXgJ%`Z#D$A>@7!g;ssP=Z%syW-<&|MHFJVaB$((GNq#VPh+%hH1xq3|vrjZLE!5 zOQ7|Gb4%L&<^%WragqiW!-STSoT10#UF5*Y?WDzTB=^RbXV*q`BIxDcYvoOW8mBE0 z+Wb9QHaeo*4u~Ij+a!vZDlr8z>T#=dVRgx9#I&2O^(j$GG2nhprAi3MI?Gc0-AxKA?g zqoc5VvMojw9_;>CRSx{b5-N(G9sRFc-OR)NpO!JHRHD4Rd?z4(PUiD+AFKyDX6w!^ z4>$8V77Rc7x>ht6+KlmqewyHWbC`3CW8fb$(bfqRB4Y?yij#RD?&@uoFD~VXvY13= zh^N)q>^$M{Zy(5ZA&DD2EwQX7uf?)Uo-94yt|@$PPy5wFH#?n}(MSy?_!&^mCk-*7P1)Ysg_sv}7a=WnngvY)^ykNAA>IEL8#)ILZ~ z$;UusHpds8hLML{iJ0ZGhnj1KjUhtwG&oXrFw^Y3qj9Nxb^VLeQ0Izm_)~jlI%r^G zRBO8X-*Vu;;+?E!)X(=frhx^0en_+rJ z=e@j}ZE~gz<{CHuz45{`wf^?}3WxsUOH!EU1aV>T76@1K2JWt+(KjS%IsB-PI{A7+ zABxX`vZsPCBt+XajNV;V&y<=Rn*F8QZ~Ae%PQ*tP9@Jf9LuWLj)f2kd5l)(Q7Q`G~ z%3Ezly^ta4?#*Yd85qCT7dP1MHCbzeADz(>(JRNdH6YlS9X$KbCtHXu0&VWq{WWHw zhdj$u(Vm}%Ch`L++4%tf>qV%BtE+3&04ou+{Smc;*B zN89hN<48-j(z;VgUaq$fM+aEyHLqW}pFFgmK`qzKPwr46VvOs-YMN~q-uSN!QOYVj z{TeDKTRD2Pq0#1pY7HHOsk{#h(az7#V?1<{%@MC<8Vu`lA1RL~Q0I|z(`s>V#jMX? zGhR0e>{cE4H)wsV7)_WDRxw(+h@z7-=PyL9d0x8BpJ)E@j;B{f=1CTXTh^u^)@62s%(iSNP5u8Z|23cA9$v8RnI3W=ggjfo#_hk)lBT={Q zHz(PW@5eOsT?(-fDws7OSBL70CgKm&yz(3KJQFW2m^RkByV>ixc9cZ+Kg4Ba=?>O) z0EPpxSaj*^g%hW!@V2RXojG~{6g*e!vmm^6uwJG4EEUkKUC?!E_%GETYdEFn5ivP= z$Y2~fv%{|RT)CFi)$S-3mm>wx<0c^`-MDaFXmw)-h#SPbym-Uaz`AtrPFH^Y`ZYr+ z!1^ING{2i-(iR!R%@A>aQkO$0EV|ee{J#N{`@Zl#ciZAKXvemah;8=FLbW=V@6tQT{XXNsi<*|VqHgc?_u!zX) z;os=o_C%&=;D_BoACGwZ+XLKa?#)q;blNjRDhL!VT}u{V%CT3=wqJi%up5AGB1m|# zjvidSxK_*S52utT%(=7oQcB5|C5n2BcA&~{s`yinA;J~X`?w| z#h6FpWSjoMd=n&CgASuFxi!87Xg3yYnb#YMT1A;}^lZ}5==nE}oagAO03HGx$bMGp z=t2K6B@kPzjpgsV6)Re#08uFahQ!Lm5~^M1-+0#k)Ofe*k@6CvR~sI+{=@Gi`R$Ne zx~Y|)*u5cFD6$VIP|R8K6WU@C@iV#;a_Nn`+bS-t)Qgm-o=Nz;PVvdKpK1|{1M&)ArYtO+Z zl)C0P+L#C_Uc&{k23ciWOxJ z0`4qdeSrsZ+Ilr6*&vs}m2i6kn%5->I8WXchI9Ynq>TgOa~#$jli`gXDLpy%`i0Ru zRc+?lS7l=4aK3cldAsg364M$WGQ7HT0R7tgV1+XpqxAQ+ZZ}$>;T4Jz^U$&x^uqzw z4D~V_;Dm!6t&g<2heFn5y&dEt%5YSCD(vBMvBd_>>+xx{>_|piXtV#yY-y=y+@`e` zT8r%ROH6ikt}xq{_l-OwIsN*L zR!a7()nBWm^$?cm@5aC$_=$B)*-1dm*TsKIt~6XZSJ@4_doS((d~zGb9v5sNvY!eCV8z91qdLC7^Zau%F2RA!`V|}y zecd91%3Cib!7M@j43R%7$hp?WDqL@K?kI6@5l``pfZP||0kFo{9RKdQd?dE@;hkfXO<@*2k^t)-f|IXZ^ z%OBEmp>iX105Ex+*Y=<-(`c~vEe4t?wY|N<06)dtNm@w>?d9o?|39WnGf`1dR!h2I z;0z`E5{xo9m5gvO5OCoL#isH&)Ae>>7)T7Wd%#DrC;HQ9((!%>`bgIZHe6jv^AS`J z{(EF(yW{PJK1s`2ZLq!G${>{t_@DhVX-LSiTV&MKC3AYF`udxU#sBYv{bfxP5`C_`EHex|fHO@5 zfBNgA{L3G|&MaU7s4x(cf-{@Gju)GKq&ZXq0KK5i{bqABg1+2cms>zNF-8zX$itLe zx#_~7x^3t-*g#0KEc2^`ZFb30}L9C`BeJgwD{O&taC`O>$%KR6?1HREo*H3 zTrv0F({LLK1`GHBT{cyeqv!$)P;9-8i{i^g7|s!JP0^Qn=Y@&i0R67w<#sz2 zGTO926m)FI^nXhai#Q{MHq4Mha3t__xh+e5gUs*{M78K5)^%~FAwu3;worUzl}UT{ zOq5(()?$p*j09)$WzsgCTRyfU6Uc$h7x_ls;@4L5eQEzdvUy1No)K341168KMy3zk}v#C|cc2uZ$NcQBS z+S!G#7Dm?~Heus4C#vEljU{dZRGnK|gTvb=w`=|m?k!M?e1w4oQKiQxAJ5MTBu~Gs z^fI_B9rZuzTe!aijc2yuJLA%j^jHX~u26Abri%QcdzUy`Mqf@sy*8|Z81wme(Hi-` z&Jbr8T0uHgyeF6m`btB96$M3I$#nk#4T4MrJ~Lcp=})BD>TtdYdsU3CkYMUJdOh;> z8Y@euKk9v!#yC0w_&^DRAzx=weod;cRmsYjoVDUOy}rT$=a`PH82=_u4c33 zmG7TzR={7=k;EePYHSR+vQ%c?eQ^Egc^{w|sQg`5U7G;XcxTeM^C-8|7Ui_~0q1A- z0;cuRr|^`F;gB^G+qWa|pVnt%g;O%x&c5lMFz^m&Z51`Nm#~)0Inl%cbG}))SrWD> z&>7clzYwWKzZjY>g3Tb@4_>4S2PR`K;4Y+%R$D>VQk1?fNPbhuLPj2(?IDZ-li)uw znfwy)r7hLLxz;aNg5qF~`J z_IaU;ZW(=>9lRpOGuJgey!@fESQ`<2mcpLu>AyqN+r8hsv8I3GzsokYQVRGv9+^!+ zq2c0jIK~Eqt48Hv}>0G*vh10UVnFxUHKHoIky| zwrSh*vN^o*6mP!>r;v#}{Z16ASTo*r7&ccjx!rv!9Sh%LSAg`ap-b|wuCbK=p4cz- z(dGOSfuB!>AqnBEbH+hG)CufWu>FA~3?R$?Fo&4roDn++R%{^*K}@pT*rVGKIKUx`>*+HYcNb>5Z_5$PIrqu=31K9d2Um zm?JfWfUnk=l()!+%%~vUR?KX$rG*KxP-RTb{Hfq7V1OhiCGH&|gfG}yTh{L=i;dK^ zo4xXKgyU|WM4$SE0p-1FUfqdyA>23(!^``IAXmSKin86&Y*p>ng7>#Sg$A@i8PPiB zCeFoa9m~rRRd!Hw?HSA0BXn~vmgCSJHqky`jc(8x(^!n2_w#i<9%!uiBM`VSIVyR5 zBI(s_H(MY}nlAPj^3#tthv^Z{rH1EtRt5%sd^@0#xdN2^-@EWqyuQ$k4(`s9&tHun z!{E2JL4WGUL^}ozv_cNHwob>OAMX~gIqr`6Z3Kd4Mmnx)r;l7oXxk&aq>}}n>i36V z&M$`rzE5bwf9KgiSY;VCn#N@A12w#C*J|$pJ!bo*AMvQkQ4hh3et(c3It2e>K7=Uh z%Yn}uBu!cY##>f<7am-XNk)_ZLa#0Tr? zF0wf{eU6a(3+RkR?Xep*r}`*ift}gC!7AU?uh%U%sP-J6-Z#!2ZrySGdowBin5iME z#UcEas1)jqKOLEF>E7Yq)BwEw1bVR_B$-N17smn$(@_oWUH_HgS!`b zDXLaKv3x{1Zlm8nW1AlM&5rNvY_YUJosjTohA~nPnocY*!F`)@ohBj@c?wxEMyzlw4c$ni4wpy6j z5ZIc%*Fp52V5(2ISGQ#RW6HFRjSdhSiCroDyO)E((g@dxW%c#`CoPRzO>Nr*G}}p< zX^qhZc3*JbGlkcO)R~Q5%{P2rJ=g=?{ZKP$!ki~hWZr~RH!-Q+PYWoOz1h-f$%0Sp z68Yq4B>JZ7nMT9s#oE^Gp#F4su?xj-Je|nHRm8g@mH)Y_(&g8c9uyqclViRUqo05s zrEiy+R+|0X6i@qNd|#Iz8NbcQz*eNLAvrX^cWcFuN6W|F`Q50WUn+96+%Ehn1i?Y` zA#Ydi3+=>dSyNgZUwJ(nmK@Ad@ky6OgRh1%Kj^Gw+n_`%^EFA)oy>Wvm89YX57zY`|eP{n7!W4BjAItMHFx~Kd zAHvpP`bh$ZT=z+w+f;86d{w(Owjm;h9T&~L?RdPl5)RsGKeR;Z-&}w+h;L8ns*6FE zwVks(@yg}q&U6EoOYv*9i-X}O&<~_N+i52ldU$D5z`cBE=~`}r^w`*Wd;L%C^efBFs9^TOn=Lrhm?rcCHpZ>lJHV57`BPDZa)+Bd>P`0b7N z8h_Nu&Hg!Pf4<1M-oFnS_dBT>=24Cn=p;e%?aBI}{Hhl-&Jw|gIFtGZuqXco^+7)8 zw#%$afY5hMXU0!`A0Dj?RTm(efP?z0Eonggd-RX6>yDVNt;$hc@?F^?4aSk`%~2w5 zvSfGRpNTm03^k;c80dJ8dG`C{V9MVidhqBr2ZX`90NfBXSBdeO&)etkF2F=p8SvnK z+svmn^!FiaXhu&%$qUX`L%B3v# z-6r;@Sd1);c;9AJ?mB8~rlwt=a|0}S%g{fP*O6LJi;j8h=>|QCia~C5N@e9}xjr9P z{?LIa00o^5=;FFAv{!r=6#UTFUmXcszF7Krv!1`HyNui)3a-afe-Ae9ZC$yB-1VU4 z&+1jdqTYcwlR2MgwK+=9b_MWW{@3Hrz^*rrKi0bXWAPOlnjVTxBT!ZX@Ri~se0SxnfoWyzCwo)r zdEZ6vg0Yz9)%W&qt@xVf20>2Pwc?>$-7yW-x`@J#);+!yZEA`A!z^&d(PsmVVtkMj zOaGvza37?u0_Mj@H~v;Nq^u#4nuwf1?Nm04kbJks=yT6D9V3KLF$aBO?0pWRO=#0F zHvLvU`<*v-d>9pyJ8P6spVC1=1Hob_k^h|)lShKXEYzrLse*sFqyK`~(sb9O)mpbk z#6KTm70l!)k9J~7Pe5i|U2!PgsIG^%<#w2g0e59|HU5@&-cV7^xqlP46S9ww=lZ-1 zqrSb%U}FUJq%Jx&pfD(4Oz|n|sJ}E&_ttuKAeS1kdibPM1*Yt=cB|eQL6Pljr_0FW zf%53LtP*qchrI!uWP#oTnS)Q-US3W{Y*AbJIeNW@xQ3?%SguQAD(+gM!p!-vIq%t7 z?k?8oo$be`yhz;N8}2M(#*Q`_D0-09)!tJvCXjnm5cXOD9%IpsyIJq6fCo-xBFwVm zZ%vl3XK!7BnM%cSL6R-CM9|5TpT3D9r?@C8;jyG`LgeCiU5 z9xNwWxmLfSf-Ks<44f`z*>Th^W)^al!lKB>L+Cj|&tV^3+aUiU^L#^DSJNg);fpI| z5KEcmY}hswiDVJDNZ+rnK+!@po0aaFc~|zVCok{SHa9v=y5hr^q}u zo@P=wbw!1>W$ObU&zCR4@vlt~Om2@GI&S@_qYf@ECa$WBFIRYUKmCX0`W3I4Zy}mO z9kGn?`7cvTym{lXW~-}O)mopIp)yCTx+7d1H;#!xh9a_DgM))W*X%t2&oGHbwx+p&VX00s>vhpleF>mzS^y$U5HPi;oO22p@}UhZ!hH3Wq3NM+ra4P%V6>U`ftZBTWtzQPK><+9oQ- zAm;QB2<6;V2&fEwly1>*^KvpkLQ}tOy0ZrLpRFzroWZsEGq`o2Apa`>0rb$pFk~F>zo|TY4^Dj)NxSS->Ic0^c|LeJ2!`_!EttKjck+pQ>dd@7w+w%6{sg=oPYr~;fZ;^dT-mCJf20MO3h zABIq)lmfIneSH=Zs~T`vZ7s9{nLc_z&|ApfHiWdl3h1cq)96g*U$dNKt8nLplv(%WM zF#3Z^h!fBLi=e~=T*BR>s?K!rKejLRJ||c3TW=# z`a*O0u@_|NpVCB83}}%<9-{vP{<0`<3cllNSP%Ktw(Q*pR*t`zG23xUW~9UB5<}4Y zNASVrxIanNfz7sO>C?lN+Es-1WC?+MW7XLl(6-+uhL;OulXcd8L~TO(X%M zD2un-pk;g;)`63rW??`ihJQGrDoyRVd%E>ijY;pNVmn`>Vn=$-9^b>B@d@$X^|@Y} zZRH-xXa7^Mo=Np%-;?WRkJ6lv2LZbe-au2s*beL-(P`S*&NFffjoXD!W4T8pe_*-s zhS;!LlQBE;d!K;}7j2m{OjL^}ef;}9e7e*d^09C(?Tn^ByGm3L?5YFM0d0pY_M~j~ zQMNIs&K52vv&S7sCdhBkU-)u;72v=9WtWx?fi2?;d-GA@jm?f?Uef^{nD8_L7~!Sa zw5K$@xnotd^27jxr;=qPG&l-OaPn7KVgYX$CI0M;(fT`r^#fL)&8m*oG2Rs&gQ37H zH;do1BaJW4`8KYZIH#^*?OAU@HMonG8XO@iai@l-kyt#2FTbg$2N-#`9WwV_5PHU3 zV@Pv)8a{i_eB## z4^whwJ?3_;RexN=Swbp+8+Y0iVi&N|iPcEnHu~_fgY4*%`e2?C%H_*D6L>tq8dz)| zJg)-#w@AC|kAB@}dzagfC9ao68;*AGY0G!J2MA2Q?bd0oFyl9X#40`u?QhVv+p-tj zU<=%Fuy;7(bxwRfVFZ7p`wxMN%00y~?a8GQmb21>8@ky^e{b(-(EvW%%PZ6MPmnK4 zLM0+Z2STZ0b%~i!l03OsOIjVKhIHO~m+sWrFHn)|Z z9q4&8OoX1F3a^hSNJ;a$2XKbMHrJzF)@JakO;=*L5Zpm$=d zCLhev#in(^A_7_(Dm_Mdf`yaJp`)d$Lc>M!Laj(&l50*iGjb*II@tDKlx$rG2T5rl@J^ML7Cv~TKE2*Shs z<@4#{Tl1#xW*&nJzyQY0vfEz9Gcb~+!uAP(w9M9CU9UBuI4aq(mb8RxKX8K0kQA}N z#F)wUW|KdxB{fVAe{(Lm0~N=VAHuc6SJ+L<;N16^WL-$N=rZxA^uO_{2K@Nb^w~~! z-^*~pZVoix8E&4< z_HCG7oK-g~i~M3Voz8~`NU(ZTx z9OmOk1Hg!%BV*vH=!5NgiI45zi_{{@Qbbsd&X(Ut4gGhtAuq8w+U>!w8`I*hj#$+B zH^hxU6e557Ek6!vWk z)$U({LEzrP$NlVep>)xgW0-BQ_=H|m?164hP^moIrv9k;P3EJfrp-6464-Ad+rmn? z;XsE^%s^)8a^)wisK~bK-_!u63;=~H*JwBqFzNii!=ev$gg2;O=U(oTZJvjCy;{+d zHvlIeDe^MG>KXus7E$#6+DF5~xp?oN3xmjHt`vMS`k8r6#IUwy(@DjO-)#|+gP0hG zj`i2uUICWfAjYZI6-0-bVvR$X_*Ptcy5>|@$Nz0TFD`Q0TmtBDxzAc1M)+_M9VtL% z>RNZ^PKQjqwj$=-q_$?TN+Q291fcI^vssmHuwD_DlN+d}K|w)TX!BsFq@)xh7vSxMO8*=ytW-Pc zh>EpU-e*eIg*=(yT&&y+6HZ80Sd5n*D3VZ4C(u84W2tlZksIWgYZTc16`2wR6}1P@ zKA3w&{*_aHPwp<%mrMV4WocHC@+m9!s4E_uJ~MhtXX>SS|R_+slO#?=;)#`Xw@fLTx@>C#SH@L;Qb%l-;0}7 za-65%&y%Rqw(BTVy5C>?V%qwKUWnoIEt`sHhmr;zxhVBNcM#4Tz%*&gzR9*FBC$Hm zVih-QP0rMm0%{!=wtMeNFBJ+BG6-mI8>s<&=$rzij&V6-V>0|0=s$RRgunm0cYXpr z+Nz|^#|vGRdOZNfKFy+5V=N<-M8c}Ha^0C%097tg2|Mdjmbj|SCI3QH%PfBp-;wuz zcJt#YO@1#O!&ftOEENGL2koCx4O0uy9( zu|)?B00%WxyePd?-zckqo(&4DabRhSY``*rd7{>`2w?aX&@lr6(+5Pfv{C!}`#*G9 zf$3QL`=-*VCd8o2uIZL2@dS^rYo0Q#qb>99ZQAHSZBPT&uL)*ZPd%Zd5<2^c77 zXn@~<$E#r!{v>n(-Z@8LPU-WrCvXDpcan6XAI1fu%ceHWjk>62ep;~BN~H)mxq2(6 zcp{I3}4n<(M5fNkyCiZ^qD!pF0|)eKkzD)$E_^ z60XZ?q!P?DLCl{Q0#`=pXoB|PTamzpFkpfrTB2Nb?%oy{99(TMfB?isTMk@+9|$h5 zs;Y`&j{%(qEF)<+XnwEfz!4Cj+j7J^a%C*k!}|^&^zPUrW25*VFg*C&u5wHNsA-*V zUxUpk@VGp-OkbHjHBXp?l@O;O!qOnrfZ>2awX`(oWIOls3y`Sh!)36I_Ua_NXU4MR zz$Erp5D*j>M1dvz5Hu@^W6XBedzv}6^6l(S%*iRamb<2gTQ5svUK6kQu&lw{nDwjI z{F$3{4+%;X;Cb8~+eM7_QKY%0C2e=d26Vq9*YP+!w8KxvDrOcgl3p1X&88mQ+`V298WCG$(H6pY9(~_ z>BmauDSDg`wCG_53Vv4l#-x!bLW9v$Zv`9lZqTrr%zR*AU~tFYux1hUTnpWJ_~Msx z0c!ErgqNG3;x|{v9I72}NIlN=0_m5%ub=Z=A-^C+N5jlePAp|ydgVo8HGCZc8ke5G*E!g@p%M7ABf2OoZ(32X>K& zp;Hn;>b(gaxdl-s&q|5*9W-85(TtsIgj=K4gMq9$Q1$<;*}*l(#ur zq19f;r-(jtL3Bb)xSw@oaf3)OPyn4ukWyqVRl9aBUXnCkQHctDIXEj!uqyOOu#-it z#h7);No}nm)6gEShr#@VY91OfF>zzL2I{Z!BV7$PKLKB19$5x7BIFnk2SwOnmMWUF zErNL`%B106ij>uhGzJC+9OV(tT8alO36gzMXU0qs&D$6D#?3S452?GE`F!p2H^Z;m zu^@2i6|p*nLRqw`D3-*hI-f^$iG0{@ly%j-gZGF$gw;w&5F41teq4T2uE8U(0bl7N z%1%iqrkHx>uo(;e3DZ+eu~`qF>JwFwOQky=(QxV1J>5NYGxtb=y@2VqOeyo^ncTFa zdrB^Ig=n-%931VaJ5f8^5-t#`X`uGz7EN{8ao-NvLeOe6BgMmqjK{ zlTM5)gDgXKivwZOw3dy3nk9{d(v=A9@WXsjVn~l3a4p)}+A=Lm`%&fXrUM`74=$O< z)TNu9XnsTR;)IGimeQd`gHa*@lFSn%i_2+i!^H9}&9{~r?q-3D*ULu33_chY zvd}yUQ_MrFw?ah-0jE%*%0{ELI;pL%(=(0gmYUwZa{DnzGS2s8DWm-HV?Y*E-Pxn$ zS4pRz@;65N!Z}=3%Qm^XR%pejPX+E<^TW@QRNs&=5XFv6mXev!&8T4f89aou*|O`T ztZhw~b{4xnAFEnU1x*Kjk?kCT_=1#(LG6!D*SPMlW_7h-5Ccvm51b4LJvz@q%}hn< z%*Ywy5m`Pu(F=-n4mQh$&Vz!iu{b%t!H6-A04ciWp+s4CiF)cE|cEe_TCs5$KEPXX#46*BL0sSpFYkcu3`f#=(2hlz`82*@mc z2;AH;qrTdAXxgf%d}`7}$U{4DY%bC~RRZ1LOUM@{t73=tn6{vG=iKs;ku&kxnjGo7wj_HnjI z@^voI{N`d`uul85fidMU>EY&U(Q7;87Y;XEDgLjq`M~RW6#_E@1xswun0IhiIFkn( zG^x;yhc{hb!+@#jI>z;SEK=r(g`T;{7dbgEu{Qz!x_heNJT`#;^ThKRy{(io=3<8c zcYCkq4c9n-vT3thrqv*#3-yj~ocxY!>DR&Bfi|Ktfv#~J&v;dBdjuW$seYY9hANqfm9$uE0ya*rs{teTok33)}P8P=l zsGtIS^wibW1t^E2g-Fv#@ngQyB&15-&Uts&^%o}|L(-FC!$46cgaeNh3L3hkgmvxS zlf{k84rjnF73EhukCoV8E6n1%^44twc2|T(iaT%@2o6=l53%G)x?< zeij+FiZf!|kIX!5!6luPExkm@Y}Sk2bF>-@)o#pd_q*&d?qh**A@oWwKRO1elwMwo z7}N^2Q#>-M9meGr*}q9X!*&lEu;sbE?EQ%y&y_R~=7$GQ;^|Hgc2OJ3RK4l%vfS^6 z-L{*AJYS;Mz$Wk!Yn-&m5qWlAE+ra81V6_)>Rqm^XoIhzei!(LylS_iK2{NVp28jC zYTiwE98I_C{)Jl0+HWNQ^7a#4y$B7;hqT72E7WjS8Fh_!j`1{tsL@l_C)UH5(p!zC@J=w9P^B#7_HEN1QXwh5Q@!fW~Ko|ldN6dg7Zir;w zCMk(boGOhdkYZ87X56y{YnDsVV11KLuRQ>HDv(=$*3`tAvZ%`x%F@b^!;T-!UCdv3 zq&(^aQ?rWtGiBGQ@?b)G>b7pCivgmg8b+)*#Bg<}Xf9fW2;elN!>v5b@&PKKw!Z$y zpkblX5RhuZ``$%w=~D!mr2uy7G{gNYqxtxyQ8jpYJl%jf8DldS7QPfpZBP7=k-N(6 z<`Q_h*A6vh!m#Ha_gc#3Gt9?v;he)exeN*=^4l*NR2fSP>^FO{ql%jm)C5zRM4sMjlOC?h)PFN z-kPXlSkQ*N`Zq9OSDU#|A5%Y2b3f0^Wo=Gk1Z>zzWWjb9b;D^kTggPESwI_4Tzb4w;)~VPcb$RuZ7_N%e)0BLsFzG7qJm{f8X&zqtTb02vhq z;vJCP6lpO26b3+6uFK4f60|SAHsQ+}V1NT+V3TIFE01iB{CXtwShgySB3%-tQcwxK zxfkP6!Iy}>U5!Bap27rBnG%)uhm~T649Y<+g&&VcVnne^u3^GI=UUKPmCRYNNr4IS z(Tpk5bK3kjGhczI3k)?46ZUr)<4XftS=sSKNO1mhxSaNZ_Dzuy`QPc~fA3l3{rFZ_ zYr}!t58qgKCPaZo)M~;G$gVl8Zm@4p`2!80IXQTSRM`exb2^8$U+saQ(ga8=qR&Ev zIVfj<%vIr)!)5h0Q!H(D90%JjU3MpxfYRa5-~)JN=1Zi@2K|Y5fpNptNQJh~C{ABh zB5&|8vL5Fe7Ft~BZCppw9`?@o`-3!^9~M_!E`|UiQpp}-4N?BX_FcQkIQ1&$sQ7A- zdZh`ej;9D>EHSYqV!ge0ND!5A)84!R30uXw2p$Gi(k{QvTAzv-+S^vc_%5Py;-c5@ zJQt%t7=#d)vmGB^y{q~)tv<8FU|~e|H-%3D<2>UapOjpfz^A#(CMosGiOTvIn-079 z@wL6nr+G&dIs8pxe(XJ?j)t%jR64n}HyVP|n9Ip|%XNR#=y~Y*t~@srZ{~cgd~S*UEFEGH@phjVAnWN14c(_UIMf4~x%}=6xR#`A0pn z%0q?G1C4^`)_pR!8&k($_bCPI2eaCrBZD%M|J1xN{?x$ZYv`~sY8T| z5I1OuiHDb`SS0-;OQ5W`lpgbCCQlEuwxPkpp8<&wJK7cWwL@}NJ-~T#DXw-$a*-Nd z(~crB94OR*V%N&bN`SZM@Z*?xjsP86cfHl+gC{NI5`|*V2E)n8iD?-Y0YL#!9@V72 z-VQ^{0b@{rE9!|GTUti-jtJjb!u05l{kA-^N}YY%D`{~2UIMDQr#WH9t;xKB$y0jGU~ULm991>@=FmI>NfsfLjU|O;hhJ-?}* zp7-A@IEH^;Y}a57X`NVd7sNE+dk4#raJ!Btw51!XaIk#Wr$E^oVTeO1%+t(lE5eYq zsj;o*bdE&B{Jnt}gSGRs48edH%lUXbyLo;}Yv{7qkBPR;%2K@}m7gztw@pr^^(NsG zrBty)1t}4}=inW|!!EHUXrWI-rybo?Hp{tRNDS*wC4-cR=zj9yS?JDf;)un)_y+?y zvP;G?Y*Y3!_?S@~XcYJ3)yq{AYZdyDW<;;qhj)DpEz98gCHf@O55Ehrr*ijE+0mT%xJ7N8m zc>PXV{wZLhgV`1aF4LOtMdU2|B}tV}q^oKM3~M!ktC&I+_4N*Q;FZX2R(*B7jNd!c z%Bll-yzI6_z9ITx5R&K(WEH(;Mz|0#gQtL3B6ZYwvYae#G@E#d`UCFN#A#H~O`siX z<5FK0ZhCS+HF`oh>`sDFwTba0xQtEhJa@e$7&+*fd1HLQNfU(x2E)I$$x54ZCm7WROKq>?LJ2HsygYS?aV9Y;=+#aDdkN_&V^kLZ>V}RaylO?@1R{p zV9Pk<;knG?L1f&#{h52E);Q#Tx$MbRw-3Ah5u{a1;$K=u%B`jCY6*Sj(Vw$7GJU^E zYBzUl&i8VTX`Db+7=lWyxzHYv6*coKiZiMnq}wx)58KD zF>bWW)#7}4zK!5J*19vKx2e_cwiaM~)oncJtlt#>Ar(O|}eqvP+s zXxG*UIq1`-W7Mdv;E{>DPr0E&=oK;Ebb!PsHp5nWcMAdmqe>&odgY<0e^Q5*hE1TD7e$>Z;p%r`eqmlv z;$pW9vKWuZGrwd)f;cpC_YzdT8uiRm40}$kE0yboLBxfE?#9!*R>gj=+Ei>YWyd7~ zeM~7Uz>0OmJG)8t?@CKT{rsVr=P>@Iv?Q+UB|r&5}b?__y9~CH|PYZh3wm zx3oDo{l8|*Q%ZBS=OV)a!zT_md|@k@md3mNOHbnV@+gZEJiI?lgc}_F&D(s`BuF7G=#gR`Z2bU^uj>a?h9;=>k%6rI|!>G3vxLr;_ zJq=-rlO4c0vE@lg^`W5U7{(uhR4(Fjv1N*s-t`>Orw$sL4=M^_jqZWbJB8<)@kf17 z@^LdUAum!2S1b~yOCnB?oSa_nkA)sz#F#9x)9m4c$K5qWaB7uPYip%abqkyOw`d4fxvM1T6H z9$cRze#7Sd3;b;DfQ^gORep^|XcXe*0Rg`5UA~Ox?dAfU0|tbi1Y=JJ2uG(nvtq3+ zz~;@s_5vbpIW1?M$2&#-|PxgWj;$%E_GXB z4iTC{F~YqMX-Xi=j22zwRPY?DeYMqVd~D@1K@~92Qz&E^){H6-TZ&8rPudMEDkqaF z@sYwA;+BJ*y>6GIH7jYW0)apW`}>{rc$Sz@ZPe~z!o*;;{TgOg7JZh?1w3R?K=04h z=sPv+4wa*LF3~Jkm+KW^-d5XCH$6Akzp#KQ%O%5sxhsB&R7TBKWxhh?%-0adyv)4N zGl*R1@TFo}=I4zn1hx2sZt@yR2a#gXS4fF8SfI_|l^7(Df#`NP?L0QCT2(}9HvD)M zUG3C15}i5i1BEjV>KstvDAmO2nlQ?A{XDqgnEqL88dc_eDXIGbI{G|lWoKz;Yf^N@ zwx6o}M3KbhbOUFM>h<}WP1|J>^UTdN`O}#C@UBzab55M0+@ii$L64Qo@!qK)Nyu1K zrTq<+byI$jG*K6JuH6imm?ES-mt<{2M2DwYAl^8BQQ20-iPk5JTD;B8t9je4M;NG7 z*ii#n)^D{(A_uvzFQl52Z`mk1Vn zU)g=buqablipy`8R?bu_XP(@UNstZ7FF7!v+`@_IOMQ*6u;L%hy7OA`GA*Mt)?_+h z$cyFaa!no^lSQ!qu3eKP6ePra>QF`Gf3t8d^~{AcR+6xN!U11NSJ{nd#`n`Yxz|Q#hA_{0y=%lc>aPM`|ITo)_bQ> zNx~u8s^?jsyJ18WCh4}vJD$V3+DbQB?!&kEZB_KrY5AwJ!8-Swm)h_e&P(^=KNb-k z2hy%H+Ko6JmTNNu8YZ`vne{s7)4k`SsMy(Lbi|cO__{0t@Hbj<>n3Ms6@*f^4Veb% zrdj+GpH{kk13vVfR@kinn9O&Lias0v=7klDbpD)K_B2t5!z9?+)dr2v;y);67@V*q~@koPo;_hZ**jTaH0J&L1JHOX}lQ(r16Zb zTwJ(PF2AWhmTB-VMVqD8%OF$=b#iuD>NkSCO#dj41;j*whogS)4}s0~4e_{ZZDT^e zuF5=Cy1Jcluy$uwTyMIFpneRMX7uA>Hbv?!b5iygW@zK%`{8B9VQ`Pb=4GE7AR1Zh ze^Pxz@n&R7v7zUgu|^UbrtZQDIc~7Mxvg8M#~)jq*%ipXF8_(C4$8^NAbE$pef1%5 z1{}Qu-o_Sm4pnv zcHedIh}QB+_6v3Pd^f4>>d*r`(J+r(o9T6t#+vYnZ`x}NjFwfxe7qB_&@<1fl{UBs z)&GS-IADrOpRTH+3Jw{^2(yFCpmZ(b6A&a0^sfRlc8dRc=ZulLy9FQaEDHwsy&|^B zOEk*NEv%?%@JLB3WZT|J?GC>?i&Ny`#%Z>&Z#O>J@058hRdmY2s8JMT_ih z`Oy=jN?fo$mtcM1ws2K^_$>SEQmChQ`0JoTbubA?GC{%QcWR9}Q4Qztf?FJGD8#)j zqn3T#e}Qc<2~`Q_K}(z!k9u?*2%uLl6Kgl#TV25!jCQ|m^qIua^uY%%a&nNSb=W_6 zvXXJ}7Nij&K4WWkHCwMr!21O~0{vkA3p%`t404`csEjv!b1huacj#jbOTAB&!ZGpq z!IFX6@^Pa^I4kZ19h8Y>-_wlCoU3|VCbfq*KgADX6)jOK1PgBVbII`OSYkBySCdjK z4HOwPN65b!FF;ZxcBKrYgO`na|7s66^yZ|^=fMBZB&#OM@a8ulxB(vDf<^PgVU3Fu zlF3I1w4A|2F`H8=NeHl#dhfXWdq;T8^5r@Z&?3J5ju$?U7gDcqBbqH?<(I5WD5G@M zJ66ExlBaaV#`6UCrPZjhkJXkQdeGx$n8;?1elsv`;40JsAg2>b%m=(K-}X#Wra2#zDEal<%#_K8wG&7X_=KU zExfk_7RO$XrHAtTc0Cnq-W43gUdEW8zMzu~ceYij4v|2QdkyNt>bP8tT&G%`zGRvgpRE$N3Uq(JeRB*(uIs6Ua>f2+o7 zFr@jKSH3E-L_>HeJ+4*#SvOGyp#UT}!Q0(pUEpi8z6|kYN2-~TAD9X^^F>U2%f$st zH8iE&xMGswkpFa3kC;m4sy?|q9nETAX=K^W8tp;Ho~RbQO|2eV&~xfaURxocf>{Q2 z5`sHzTKYU$5%w7y2L`>UOU;sFVO$BQ^9)-58BqoxPj74T*rc;vlNTb8X#=e|BBpq} zoy%+6IOU|0|FmqEk0^)?6bo^WN&JZa5hcue!iOo0E~fdKZ#pz-5()Wu1VnEMFp8o{ znYeT%`=Om=?7?-uO+q<{eXf(Ky;5&#O)g-o%Vh`lF~FFzyIeAsO9Rh}gsk$IbdyY3 z)vNoiSah(W=EXOBdJ2<^Gm%y)M=m!`(=#P^uCGP0b}YH!+ZpPanj5#4f3Hc@!0Q{3 z<-WZ9y_5DCR*49K-52pqJ1lfhM)54iK;Zr#2|E|tGy{oI5)lD(cx@FTH@MFxp_jpyy3T__1D_I@ zW{8v$*z{R2i=+RWJp1mIKFrQMm8NT$tUQi+mq5^_23ZGnE zRWvYI6;%`iej61y>wrcS{2Q53Dzd8nJW6sxWa29wI251>gV0Ds)c!Qf_q|+o(Mtw& zv9&0n3z?}xhFY0l8#DhUAQ}U!I8s$FKu|h|>-Ti(mNQ);cvn7o zy2P~PfXJ>TM`YZfsmY?~_6X>lA%X%*Q%ZPQV(A>f-}>jo0CJ&?%68<}U#ewdtitI^ zWU2B+qAd4iUOxR`7Oxp`;ftB`ZB%9Ne7`~x^e1hHul8iGpfm_NH4larzgeAAO` zT7p=@cP=rlQ3KyMX(pC|trXP6@K;m4^Ks~4F*?On-y2PGOe{R+@L)uu*@S;`4~eH4 zrjKUBR`BKHjQi|3qh&F@HF7RPgbt=AH9#r{a@xY`Iz?{J!V>`VcUl6dhuW}l&vJl z)IKZ`_swv5mr2&k3E=`Uk9b~MX~ymtbvKwL(KPs?X~4}g{o%VpaMqm)cY8%3%r!>+ zG>(;w7n@4`fwtF@^tR9RH~k`HX>}+u{03qsZxcUajpnRMu7mJZ+TCR9tai!#A0VUS zqTpId3l5m#5oI&1@*JcR2!>F2xjRcH3?{hVgA>6F6@v9$E z;Qk)*&cL_Yqc~_{3Ry2uc>XEF=(I5RT1!SIV|VF|flZb0CX2D{()Q}tx%vJBqUQ4?!}yzSCT9wm;xYN~ayw zpAVbw`$xe^wz?4;9GMEU4jpt|ZfeHxHMY;JfnH z6L5=ni$-_Pdp56M!B(E11$$;T)Lkp@nI8iw&Zha-9+Ere2|I*%k17A=ABn(f)-!BZ zRsAIVpMIhL1?_e5b={pc{k9fwHH3btrK>+y3p3wKBB%O(RMh@(pWY>i#&m>oj6eyr zgwjso-JkzLGNFIb4MT5i@)|EZD_t4?jB-zOQ-g zWy&$u6pG5`I3eSFybcb@NPRCjSxBG0_}OG$zbsuA`q63zvrkzFkx5z9M*agvidU2s z3OmWsMyV1#ZOG?3l1~L#K9fFg=1Oix?M6j0srfPw*h#^C_h{fBl7d2oKb(dn3YjFF z_;hyoDVgN@9FZz^n{x$+Hi95DNW0>%qBtQu;*mOr8H}P^*1L`|-P@HeRefWg?ep$l#7+t;IyUT&I z#0JAn1bK>!^#<4kE`2{79G|I>S<(aWCGco6vDx!EHQ_yGjB=|S-1ZpqyyM9k(pD)7 zszlPlc?+;DIc$dz+NVs`l?0V|o=}f6!8Wp68r8yBs*S4Fkj5g>i4HXa;Hp$H@k6PNnY>aZYwv%aE-^ztNFTDvRCBy z6wUooRHHci^a5(5HI{E4pSE&iT_kj0;F$k|4zj63x1YVVjhvL}pCif>kIJwEAUAim z44a5+SVU1N%CdAgBLf$%-qrynrMHBEh$Am zYiFU`MJ7w(D3Y)0s{A4?b7l;CGJxig+V{D-9Z^CnIlS44{2YEl#Z|x0R{mx@?TBpN z`k2>+d5S zCfb(2K2`>nL6(&#VW(gC8QZ|~6vPg2JM9KIt#;UWc6(RgJ^W@47!Eke-hH8U5s4M- zB7SX+h~x|C$ZUUsN;bexejWLbd((xny>k67`83sULji4vP}RqS;&I#T*~Z2og{$zR zU+w{4d9t<}XRlHm%Q~#QDhfc(Q);5)v6h#}&g76#i%+2{%pBeI>r;|~getSzX}HF_ zMkm5!#@OCMoNnqLVKFQ`0%4PfYdgBSCjLX-idf(kpRyV%9h<|e+iPf+aqjV{!?^+> zT!WtvvE&*>77*8i@Xv*#l+!$fadcKw@!iHrPUH%)qt4Q}z!%Pd2a+$rjj~fVT)N#~ zA4$aL5d?RZu}f-qs@;;OXZEdsHJo-9&HEUJ9R?is9?iLhEuMHH4d-LG*==`4Kl`5U zHhV2U$ZMXUp+4W~t7rJU6PxCY_^Rl*8}R%kd*xQP4ww5PqP{)5-r!dZnzaA@eeC63 zAL0JP_3Yh_gZ^-TyQ5_HT-rHxd*^C^TT035D^vNt!ug$taQ|-GC1OaE{@~&2J#NcR z2G{V0s_(N{{iJs{{?W^cMnk}e&;8(|zUckLV&il5YiL00QS;M0ar*|ehOUHY;IG3+ z-y<7J|3k<};g{LP%GWcOr^b7?m)k%@uUaQmgQt}bv(L++nzu(~Pj}^yUNx&5rG%@! zkE<6L8)N>Nv3_FbJF)HIE?o#T7sKrV2^EA6>zmwmW+6;8|MQ{P3`1MLUh<$q&AK@i zM?O=9A2f>yry}H#9euNr{?kX8Zt>Hp*5u4+vOrN0Ci*d=k+oW@qNVJ0zPm@LIGT1D ztk2C*OzL4myX9qA=p@R=vEQ08h<+O8QtSv1kb19HX9J+Czw_s}8u@flMSI1~9E~dB zc`xLZN4Y#gGn3?&4HtN9`a`#BcXv$Gry{m>g!gYAE!I0ozTuAlOkByYr9onk0fvHh zr+#*aQ&P+)XeRAndhU78o2820o~THds6Fl##*@k41|QqM87UgX?4Iyvu1=CRS_LJm zCGo$#0BbxE&R$*29sp=D3`yp6Eqy#-)L0J6MG`uXR8$&=Wuo!8%>Pre$G01stNU)T zP|*IX%GIe*&up6?>i#*yAREs^t?u{a))UUB1E1ToE<)}qvpw9WHSUUy>xzc>fOjJC zUN;IS1DOLQuNR;ml;^P6)?;(^Re%oX7i4(v=5^>%=*DK{28;?!hOhi?>gYUZNE^)M zzfbpgLfmeDAknzO@w#vc=*brHC(eFZ3@Eg@QxH0ziA8I?{-wK`WPW=q+#&q@RQ7b- zzuNt}R1=IN*|=G^$opz`y4|~5qeTw@}ooto3B3GN5}=S{={E6;4ucZ+DsO% zpqXShJ>Z79<*ZHdG7B}UGo&Nl_ueQSarMsVCG=Tf)pvFAZk6z48xz+d?|Q|<`LM!a z>qyq5c;na7{e835eQ3Ic21N63Q2x(D^M_`VgcLBBy!S(r|< zGkxj-=ChL!VC@6sdU!Uv$|7^Z8vlQHB1tUHgrqaNkJ4UV#{`=Ub3P-DNat zODwMbt6ST{;It;V`EEuS*K5dQ<#%t9mg9m=S~`|eP*{qyAO8YG_K3?fuhr+3F#KZ2D0ryo_zU|{`!NEOY6%JNr%9z;L=m)Y!xGt zBUimIf-7xr=L?&Tg5pIZHJoGleBWtXV>I{EZGOw)j}mxcALjZb{chn5+&BZ=|FafF zXsrAp2sBSn)=~{$yNSw+2>rYe^noCGD^XCe}e z081o~YgG`$@UQi&rkiUL)oH}0M?d*NAM7vp^&hbHPGQvACdRr2Ng13J=@FjLco2nt zAvSb7wH6H?A0AluddjM$@`1<35b$_#z}xfjpZRm8nIcmfp$4n{sos0n+<0|zNL`?ge_wli2H*zCItCIm`cWZm08O#XMN zxTJn-9p>f!ZW$g+*O=t(BwHX-p7^t|gUHOd{`*nkXTj`tMW>SjdLB(@t$2F%g^!WCt+BZtg%YT2Qh)63ee>uT&z zzwMsZeqSElouxO9(71TMlD)GJNND$-udRWC0a7?CON-={kkFWeWsU@t^R-#w5$d+5 zkKvI_g=Pj>Rkg6XK^acV>2nu@q~~V_ZQrsU+Z6Bn6kY7a{k8t%ApzKl@G)LmB@l}Y zn>Fh__e_G`9V3q2rK9k1aX%v1PkHI68Sv1ZV3FMi!{RH zyx%W!i1p^FohiB&hh+1WNw@CHJdfhC53}Y#(_p=!{-T~1B~Id+U6o*4VMnw zg6Kc4bPo^Qle6vjKf|Xa(|#UoXQ^?XT>1+sCMH;$#Li3RwxH2+OXrWGMz)q7s%?8q zWN^jH6nrk4td%lqQ*J0P4_7_gw$g(j1Xb4jjXXTJX}h=1%)j7j`UhqqlJqAcp{2K?d7z~3{hTWRy!+P%*cI9-R*+WYLV+~p> z-}B@fqlHWS-l}#5HNjhSnf}sJ(?=&lRVl_g*q4QEDkVcq$Th^G>5HHdTW?U9Y={mY zP4Ua{`@B2I@RpL5pNlp)O`*uCRwusD|81>PtF)j3p?7d6h#8n+=ER8p27uPf*)PA7hQS?W^`(Ei=*y#y4xz!YL!GbD}Oru2d4sr zFb8Jh7EB-yEu8bpJ^{IB5(nTE75Q>mwsG!`JLbMz;$aJ%9na(DwxFsV zD8-*BbD6qvi=PbUAMqR6ZUulM#Ywa+_*&t*w*>e*psd93`w2IwKxM`aGWB;jqT?&7 zP=g4&wg5xo>AG`{N}x!G&GoMOqJ<4|40JjDyT55Oz||vRcK6{&;F($-6Et`vn0F=U zc5wG@!K1%l9uw#sI>uojV1kO~)V;(F=<@&u@H0=fhlW;e+(+9#bj=Na1?WbLaq6DW zrM!;mR|bmwz2RODO;*V-_uDr@t{n^=csnEYUs+$yRV^kav0h#AAGYnDOuMh2?)yR< z{4D92TggTb9eff{UnV9{`izH8{l9ZRuPM&W=^I~O2lS_v#|6>8_GXb z?d7?(CREHQF^Dz_D1z94jt8ZG%ItgKLy8f!D zZcw&1P5SzV+n1)dfshit7Lu%#d@sVh3S-Y@L)|8%$nRr)GJBiM*A(FdFN zA((6p6P3AV;Jq1FD#o&uulX@p_&fQsp&S5IngXg@iLxIa7vh)7VeA#pfSChQLG@7I*M`2cIs0& zYdxi3`+*$$fYLiKjpmxtdebF9Ym-Y>FHh)lm|e=i3Y`o*X&$qkGFv(iFG9yD$tUQY zSL8al$@6Zs3l|C$>PubZw?#qYa{d(8G&hm@Ea3h~ ze58FV)ONmOv#&2X+Yt0&IOcLpI3Ty^KWCo-4K`mS3U5H=N1Ys^kN#YD#58?aSybFY zJh>7IOA3C^G*hPt8W6P;g#sJlR3c271_tM32AkvtXwjKMCUOUi8B9ZHcz!8rj&l0( zrEeXmk+Y=_&3vp9oqp^PEpx3fD6BufmV2~3G9pkKsf}3-vO}^6wa8j!@HH7P9dZnK zG!+WBTiin3p0_wPaWp-fgA+ipHg+skWR-!4G{V4dDxvt<|k18zs?iIaU`hy9E^{VZs?VkGcOTH>|d&vL@I}tH(HNjX@0on7Uvnxi^XR zr9}O*$&*qzVCkM<_~G*hIECS#DU719LE#@#okK(mSn@dl=Vzs*P_w9R_#(-SJxipF zQu_QM{lNQYjWp!p^zm@k)QU40qQtWRem|=uD@aD*D3EHMMx_?>z?dFK6<(6A+O0(` z>r?{-qh#2!RV6KlckWz@#cw$Cb%VXV-N3&=x6bu9dqt|zt$i)mq537g`0m*X zs#;D5aKKQbeV2~hE%0aJ2Va&4up5c55?h`BXzXMaRS0we?Wk9a#2pvFomL0#^y^2A zWBJ%I#7eMRc}@`r+65%-()27_l)p+X*N9MPZNR%&T~ih+#M zbGR(<0&q4ShPq4XQ2~5zGN#Q#^6WN4ZzROGKsv>euB;w0amJXh_kE7oO2G5PbpK0*OaiTc~ zdJI48No&p)Y^c#-%l;g)0!CftZE@J`H}Ft4qh?hyDOz!)jGcZI1}3_^cZZ>^!@_64 z+WQ^r#G=X^eVC*hl|x-3DhW@AoGAxtRV-F@W%)`KF4C2rK7&*c!U6$f&AQqAQO&ik zR*SLiRGvtBY{se#LIf( zr3~#}SKLSycp>K|E6aKLw6%QlylcI5>V%VEmpHJ^b>YIL%TnZB^!eG7f@2ax#^=n& zQU{aRsc=fauLi!jJ15i%gSyG|Kln0*Rlrr!?>PA zJk=Ws9tj-y1}iQw!v(|M7qb z6+hmdQe(j@JJF|v0JbrzsDB{JVlT@5hig1wwcL-(lBc43jpM~j4;zZ}@{B=1*AKuj zAtlxS^Vy06+5~z_1r`arz!En+WW$oXe=YFSQiSZQ(kp|%XcCHQ_;fD=$bw#V_COv8 z>7{~VB*>IIF~LIAsy{^q^$^^&7Ul@ujHOpM7KJGMlw-ewRf<+$Zt5j6m{e52$^hpF zC9PUnRZU+P(2_u{gbfOZaF+j6f;Ex`EIESAHkj}mj4iL;{~4JeM+Vz5yWL(p=ADW0 z{G&0FpA|*P-EgQzAz~?o(jErf!J>h_WQssPt-;kpymq-nfiBtJyZ3W%5PILf;r>Eg zIY9Nxvh01j(S<@=+b?S^onvqEAt$0BNi>b-;%ah(-!5C@ES;8NzCs#`-s6^cv+bA9yo9>inKDwP(TVL0ROHfIItEpb}xp5mCocXEwRAf)bJTQ%#1I zjSa9^K*R*hx%`qV&@QacwXFzfNwPz)>w*b-!^h9Re{#~tg8ZQUpd_PQj5TNJV9SRR zAlHAsqe+A1s5kp4v~}6TCc%dou@2JzLz6rNOr8TkoFqb+>q*@mjIK>VTq8k_r7Eo= zMvKt-7Vavr@hOEtI))157v4B7mjG71ma|JJ5_-?4S;AeV(dwwO!;6VXsazzJ&vhet zOdmU*?EO7kic3~{b<+@N3HY1Ml0Q9OtdDgFcw9u}pfI8WL<4Y|Mdr_58+RlZ`X3}5 z*g(OF*wAj$!^;w}24OZl$LT$-3qRc^47FXo9D4Tl7G-V$eMcV{1WA03SXIDNrFGID zF?1a}VW}-8{}o`@fVqZ0ZV7Y=Z_y^hU75cEq7rkb8^lcMfs2~Jv8T)YOf+#{qe8rf}hO8*H`4DvMVk3}` zJFaNh*KL!OzSpsp z)_!iS)o0QGz1c*1`AISFjgJXQK_7w;^2p6#i}KR>!%hr~g{K5S1T3JjYRewDbO)&SiBkKpHFX zV`tD!Z*`{$L3-uhw@o?FRzX|AlW7Wb1=ESRVi;4u@0eHI+?+iWg*cCiIg>+*Kr2-X zX^e5hQI!Ht@LCfhTDRZjFqNO7`fYI_qFBTr&W{yS^G{qn(M^~vjGPIQ$^znR8Oiq@nJ%k1G$tQ?w zgvdB9RLxj*vhr#LT0606Vv8c#V&q5y=}iBct1^^i;j>{KT|PS`tEMYvT+y)6hUJrn z?r~t3)6InCH#AXrGV$tCw~B%=a!ITFyT@`6UPLyc)Y#g1Tx=?jGm#G}u{dd3@ToYa z5d9q0Y`{`%E}mzr5LVh}Sy|}jASE_)%QTid+D9qiTEDr1Bdw))> ze%|blh9VMhM3YedEj`qkWY%52fUm*=GikGN`#3N%LdngIo8S8(2L|AuNl6-57YnVb ztem&CObdZP)@2p6Q5vlp*U7BX-c=FW2H*P%wFoi8p%Q)E^hBJ0M2%-!T z#09s{g-gm!x@jp(5n`tDofoOsw$G(B^^0%^{dI+77rKF_4+I|0uM7kMqZNnT=<#?H z1>5u+8|TeHSV_~Z$>^>Ez7s$s?X>QA%m>syxXZ5oejND$_QWZRPiiCn4w-yecPEWb ztFNIxluch5)rtr*P#!N`n=Ox;d4&FgTRAoNT8BXP4&}WPg~0s<6$I5)mlfnw8Q07F z8mdzv)J`fj9UA3bSL%&hsMn=+kAZ+lhB375Oz8s;2<;nMQN}!JfqttPGN)&ze#jic z+5NNa-5oK30J1G#L*kz(7QU6ZO5ry9dFLOn36gHjs=J{X9Y;R@}mk&EFX z4aQLdB|=}r(F`;9B%bEAwULDGh)AoBb7nF~;WVjIbF;6%L zv$`QVSc0>p`eKAPXG_4;Ji6ECtIyvQ&KYfU#_Q|nhk#4~#wy<7*b2S1!ou$yRP#8) z0RQGA=Du!7oI+3*E%SRUA(*bZt4m?@+ij)~Gz{~OvnZ;$Iu>1QR5(01C@wAr1dB!9 zY32I_K`0Ej*IGwV%g#glKGQ0Sgz%MIL=Tuf2KM0{PjjIV+iV11^UvLcrhDEWFE3p- zPeVm9{LXW|pvf}0B!glGoop;>Wa7T4Tdn@GTsil6X=qKc5f%;~=4!4b;JWO31JPjBpEcZ(R8))w^;p!{f`QW!pCjQL`yGwxWPTa@#GLe@o(*W730&1 zL5pcMJ20B)nRvCo__cUWxDi`)gdc!dq5m#Aik3JE*CyDto#!cg2%F4s#0TddQ*ev|#{agd+9 zkZXF(?A6;fRX@!UoQT{UD*`KPf{~b=HGy)mQ0KgTn5Obc3`?>cScQ<{GL66;5j9T& z1XT(#5Xh?RUVN?8E8;hpna}NLQDr`Dg~Pgt$I0FKBRZ@MDa% zqm6A;#amF&WY%Q~-Afo0Xh#s+_zVw=*-fKV^UZh(+V%SG%1*OE+UTU>bBIkvYtn8% z>h5wT+}$Yd=q`P7#y|+_jj~U1T=S5{8PH9mtgfC^yzbGN=hQDNaMPEldwnl$TBl__ z)81d*FJ#f76kP?(Hz#ld{6W9^U4O5>R7NPwRRPd z;yVE$4p495;u%4w$jp>th>7{HaATTvoF4p9Bw)8fuO%-psg0xN-dv@P``dnK8VE)P zG!C}>#_w{#7P!bxvv5mZ@ln}luvmT z#MXF{@-WW4@yn4-To>R&_UBui?;KhhUVF2$q4LDANIkdz+Y6A3rleD0gsqj5KOzKH zU@RwDU1u9I3oP*iSwljK$J;+aUivVmAo6#+414af2Co^0+tv#kIuj7C+xv4_*l^o>$=CjjB<7=_akVTjU~nIt^{y z-woJxnT*tYxWZ_2n|9S-tPK638*kI@1qTq@@A-aRVH9vVU3Ky^LhyNQ`j%YB+qkE5 z>%4iVCvdx1(4x=zZEX1-+CGaHDcu8c?CEw@Ntie0*`eikI;olCOLBX!-L~pk*(2rc zt2^=I?aB6u!%HS>c5C{nfpQoE9*Ft8BR2WskrUrg6A?f-boxNNGfTQ%VlnS?)$$$yntx1< z;B+a+S9Z@wzm-s=%6U5^X;M*d6F$kpKt@9`Wo)G0o-Xpm)ZXt`WOyT;->18}cBU(f z7FnOEUT}ov)iJ4kad^#QyxNAb9Z&T$D(qnWIfs2@L|EFhey; zZxK+20#nTatSB_YfQMmWm=00mO66cGB8NfmwIPbc&M z7r=j0Ke`(M%TxBa`z1^stUPXA^G%}&#|^;e8-om7p!T!c&o#1p_JG*i2soCU8TfgLt81T@U$Z+4SDsb_e;%KfhUCRR3`H|axZ9SCq#QUo{ z1&H}2<@I?i;QW%*H`Hg$H^gD2J!)6z9Q)*c)T80B`*m~Y^d-w>^~r&0iU6#A&Z2nw zL=p+?o6Sx;t=cNLX`p|WCrRguoVO4hqaU5u1?dl-b!D6_VsUzqC;M%?gN( z&5QM|)mRsMpEJE!jL1K2buKpg=#ojP3y!`_Xq=VNm+#)CNieirj%A#8MQ0e1?B*xy zciml3I0+m4i&{yB&_ZYN(RTxR9=rbaZhtey|3!+6=Nfw#Ot49XNHD{ zk?OiY(`Ok!0k)#FPPB{T*;UC&4zBccWvt+uni@w~aG@2jRcFK;@ihY=AS^#LH8ssS zXdhkWZF$$WV|X_|H3fr4QZ%;P&4>2X%Awagj*QfdZtLT_Br<7x zcl@%ZTbw3{_e1*&s$6%^jB)ZmASmVTu#J#Jp795u}#a*Z0+UMSaT$w7ZarX zULhDQ@9`bz%K~9U-nU(0R{3~ft!@^;ab9UTL4I&}*m!=3NW;V=2?8;--EG+0yTPw| zuJsRRC%(DvZ@BAsU_WSkY_v}!c6kyqe?A&J5;ApKhyP;4&~U3?PU{9`v95VW&7`9o z{s>`aJHFB-8i{YLJi~pMmUqlDQ~D>yzb47 zr@;F~4;s&Cta5#jU2#NE-aBYf`ALxpkvH<72Fn=+HBj!$ZzDi>;F1!tSvLUkX5DPL z2n(&=?OI>o|Ni~^0|mv`r6nRP34n=j&AIWj2al2(_Of~R?yXU(I!imjyjso1&`ajakWd$U&j&||^4nVGZ{ePX^OiXuwG zL{hA>d^&S@+KKD;>J`jNHHqE4(c98sUDJk(02vI61g}f63wXdRzk6j~lGRK6z)tcl0mz5!h4&=JM!zfVyRC0Vb8Q)1% z>CP=TV)a{bPAIaZUyOAM>(rJzM$IHCRWrYAjrWg~$rOZZv&BcfUi*Q`E%9AHhz8N%Lu&pTE%{q7xWnqK>nncGt4 z*8ihsJs;G}U9r5}s$=jCWJk1|PV!5RD>MocFGS+AvlW5U>EGV2u}+&|drP0^Mr{b& zMRq8HtjUk4O6Yu`ho-eGkrwgCe#4Te@~Y9t4;+Z0sq}$?N)$iW<;ln;>|=n zi?d$F*sJ1Iox?^`5<vKGkvfC-BNdW4qj?vJO|SmZ z2R;vx7*vUpUaZ@BWeiXYji4IB&uC_V${Z|8;4aJx+mrZ|)~c z0{{;%V8$K%FVkB|#bsfI`7TR}hlJKvz(Q%$a@BtpeCG`7#`kXGb_NTN$yv@gIE>A= zzJuvm-3{0ISHf1~KHW9k17%puCBuTvksQ)!ISkEa?{W$`E1^uZ!URmMlX4+`q?hjgy)Kds;H|=0`Ug0?6~Lf zy4q%ziAo^@0CXu9`S^i&>R*7BvbM3o#LTIyhSKro(yGFNpj5jM6PJS5hX;;LhY)TU zaBso{y-<&gAInF44YP(ULV90E>;T&$XK&90Y?h7iA^v+xu9m#z=PF-NR-QmE0q%qw?OfQJM3zIaD0Cjzvb zDrLJSNpiivEQzfm9VAK?mZ(i+zFk}ZHlF?)n(;XQHuTh@Lp$*oI8xuryNhIH-SYs%77GRxd)>jjqFd(&#gpAjlLwo2(J<9sU@KVq5!v7L4`8sx z2g9&S3uTHSWwTwM=v;LZ7qpsJGeVvm`Byc`>r-XO=tKf{IA>g z_cO^E)QbsFScf*UeVXc~bw+boi)x1f6Udj=k3~xv zj735~c9J^2I%=}3nq&tAyLV^LV4S=@z!v;_CWb$X{5ORC`w6h(At`a#kZ0mz_j)?c zpTEXAlGKn?M%XZIYJ!jF+a4Q$qKW|zeqKnqD&v1IA>#l07QN!?#ggwJ&+{ksb`A5O z?*tWUh$>~|h_9_LLJs?g(A59^Kgj>@|7z{-7qgH3A1OY=D%pS%(uC4P=~4Wa|I|~H zLE4<9JzHOZUBjQfyu7CT08LL$Y6b3$0zO90e<0k7E$}ltj!8ctD zTxZ9Hi@#N)J9!;qu|?!ceEXhNsv zWv4P=hc(Y>%jJWm_PZQ_`IZ3qJ*tZ8&$0?FbK|7cxukg|YfJIR zC18*npxh2;%6uOtvjNi~H`!Ai#Qc_!fZ*=X;B_!jLm%J2)J&@wGFYsfuLR=M62k#B zD`xRHh97CU!O4U)S`v^oUPIIm+5wUvyf4E)z`*loD3c?Rm&aAYTY?u}M9YcG#pQ}) zUf$Du?OIx^OA!=~s)gqpkeRi?J8*Yb?`smbwiD7?d_Dv2aykGYiH}-cp>O0%3^Q!hnU-mP(W`82nl(C9i(?h7Q&0i zes}3Qa~h{oBQh30ha@iy3g46UbO5)APp{3-0h;0>qaowQpCAr^7t?bF?c{$B$)2Lr z2C5Q}lTBfLJGI9Q!w{xjsBZV;OKm#2n8IEmF^h^f6-1bpaMY#bb*CpixjnnUCoSTe{W&rT;kGB(x^_>iuA6CB7O(0qGHC-aK_>qTd-hO9kwEm|ZqGGY6B_zGN!XJ49-A?Zsy{+eK07F8mT&odIF28} z9%nh6R?I9^^gn`X09@>3VYK(VU|b?0JtR$yT&8+$`xmpE=;$v z>j>ZWrP}h1cGsiqv7TW=i~8@80|TA^1^v&YW}h-fOS3_Ss$;6YVZnCDJ#yOzW(v2TQtVNW@CwP91;36g?CE{P+7YmvO>oKcS4B> zQ5u>;Tx7KtR0xaaPvg!gLayY&OrhjD*Da5_7(hrfytVdu%4D==E4#88H`-^xtSXRj z14DcMVorn7VM^E~0{rIc1$S1KzdsUpMiB3pZ|3QBXYG==e?nA*IoC}~^cu68*18VI z&f0rL8j~Gw>tip%VpfNzX1%Z9P#+Ofr?^-7ZHD{4x*MMn-u}7SM;yoP?t_yDZ_0TLo2Ymq9;cOvpmA<(0n_vj{V^o4eBSMgWZO{kk8KYH*Wxc zy84~qI--R5t&O|0d-&Wwgtkhou<9uARc&>3b$@q?DOhGO)Nr>n?mD*@aLtfzILn&j zmXOcsHpCcQ!7M<7ny!w?yWv=NQGaq!gu5_NifF_1!k#?W zv+O+>Vx2k7qQl$&D3%Cwha91h$t8roF)s6gJBzySD?9MJeYf=3-xvzCIKI`;(JqjV z{+Njw#1>72jEV6Y<5wMLcYo2DQ`fYg#k%D;#!y{}2*maGrWj({=h(0=?3IFkMx@aR zFv?8q%Q)r7_+@ff7|Ruxk86+h{p2M934Ogpo$fHsFyo9`PEzYEXz*^5s#fUv8DgV~ z#Y?}EajBs=^!$!_$WF5;nWQ;A8wNGbFmfYN%0bDO>vZiMW-Kv%PsIpZ#c|+rcL;*@ z)$zvj#fY~w$BozvR3biZ0~?Ve=LZY~%T;&55}xYn>OD(2xUce;^e(HhRMyaxXh^cJ z?*a&<->MPv6vG|Uu8v72#@JeY#MUIB40j2J@ovA)0x^&%mMVY zw6CIIVOriSlHrmI%{xF%CRU{Grpp>^n_OOB<`7-2vVS*oR`+wL`u)oI^FA@b-$iGf zrknixDKGvM;+hyc7tBoSyMON6dwMBhjaGu$pq>S!oxvLF>Hq}(NZB-V!S0uv^^W!$ zfN{p3agnEH`NW8C;CZ^B3m#*(^C`9YSsI#CN1gQ+YhItXQx9DVwLCk5lNm+26Pwz$ z*w1EtuAA7|^j$4N@|A2x@5d9g`dGDz-{~ALPJCSiN1IcM9C~JO)Py_ zpRO+|D^tEF3Vlx_n~Kc)nlpwGNDwI?0WH+57#b=gLTJj!VWCrwCMiTvsM{Eu6b&~_ zu^tJuCaS3YH4j0%mi+EAXeCwfyjF&6uz(p7^sOWT9Q^0RwXs4<6EGx1%d{Aw63}l0 z`Nhrh*B2DEFGfASh7r&~JxT3i!WczYdQS zA0v)56y6`ibF6Z} zvS2p9CeexnboKYtiS5$oKAO9t1NGN5e$C>Y$Gqh}Fto;~nCNbcTx*9h0#0NGRNO-{ z9%;oIDD(99A;wP&z)8vO_W=(aXLZrgNinB|~??7LXMfr_}x6j9f}p)+6RmumPSM(H$c#ZQq=| z6F#3>^YWnH@K10uho+?trSNF`mw~o4^**qZwuKh=+uW-S=9zs|r!4rbUc1~#^99Cp zO5?GsiNSH_%Gf+$VR*&)T3mxfcezy&-*&0wPsc!ac^;pH5w>GpzDv$W};!f87&zupB4O1CTD5SGE5t4&D5%?z%l^tLq zE6_2o_OVzbRe|tOTz~6U6i9*fD$vk*Y`W=z|BSJbQqwog3i=z-(~`{(kw>v*`$Iq} z(2WTWKtl!`XbJa8qeQcBr}dYypf7%#g91_;MKO(yGwa8xbhZ0Uao(bpk(CrBb+mCc zM#6nCM=vJk!OcckaI`vGYs;c&tAnIzSLoWMvksArpo!x6 zh~UP?hRUbJ&*0qBPCWx=#6nzJLI4+QXlQ)ko{pV@zi}>bzhhyF3hpKr*Jxl`P~XeY z@IYcI6x;xO@C^)E8VL>OawXD`T@9Tp6MeqXien}@FmRC|UX(;kx z7dhLij~~?15!qcCzZPKybQEm0uh~52jg$5X!y$E$n}q)Fw&nFeEC5|3i%*rz61h1iwiywE5fX{gHJV@AbI zVm5jDuw~r~m5Ry0pAfS|G-9*D4%Y$*Ga$6QXQF@3zPK|sBA~6Jf_GMdE0O;VkvLm7 zsq@_#Lln}%!OYU$Sz4NIih9P>;5!yGvsod18`o_!_g~de_&R*_B9+L>BQqnV0oK#E zZ6d5=ohc&zj7C-N|45F3<=Eypdh#}Aud9AYY=Xj$ZUl7}Q zhnbc2OGCZ-Z&jKOac&?hs3-spXNmP7v7S#-?VS5~&tN;$*~lzm{X~xacs1|gjA|Wv z&aV3mgQjEIdB1K80O|jwNuwRJuXZ42asR#laZO)JI0jEBL&(t8Eqy%@GPNLv z>ocU3T{2Ig@ri}kee|yg^O>vAb?xDe1+PXX-=wnn-*8JcJ@oV=05bxNU?;<^va^QX z?ZLzeu4u*l5!f=EU;=MTG@L#=Jm2jxO1Nu1*)&+*84A;SLQP3jS_)l-^U_ zEDq3+2@_*A9FpTbu0^`Tae|%_TM;_16O%&Y*1qCuxaBtF6h0{ca=%YcApdLVr}4^V zWat`q$*4srYiR09L&$9}YniGoO*HFMY_uh<;1==NRWHo3ruaQDvk4}F z{JGJUE6%;b3W!>M^AMe`H_)JYJ5% zR2KsD8CxG>YB~>$pQ+mS+aUwW2S>?Ai0j0usiN}M+?<{)yHx+V=(|Zl#?Q#-CV?Uq zB0|5nf;?C7^Vyo+TSFl^t(9d?tO)E{RPOE#g++4-10R2U9|~6cyG*_>#bXZF`_mz! zBhH=bdu=jAEw|JTP1m;pq)M=Nyz@87?fJuLJ(4i)bz?LdR080#{XfThzT_nFTOAvf z7qE!`Hjjz1EqOt8<{MrRQA;6NzQpkCH3JmjV5_esmHrO*kRr+5y^I~C`afC#cXdt8 zu;kF9WIf68A0?`r4J@zDr^1IrdT=MaFMclGJ@;pQ&FNluJj<4Rc$yy@3{$pU9I+q0 z0GLG~`(%p#?a{ov`=n6ZUS6ixbpU0|`FKoYzcy0NV5r>^Vjox=nY^?(DAJ;b)!Gxx zD#sYNdc{kPbf~()-t0f&%_OIFLaV*2eSz4ruxDm?MKa{tCB|@YWFgAG$+)GB5JE-8 zS`j$~DmD4xPjWFp**9{ZKJ*qil`%^psu8^+a)^sNiyP>4P)iVb`Oko)keHG}9dv*{ z3Yjhu)xDdRh)>@nWw#*8$Z|^U{p{qZ#8Fe@eLpd23*lw{j<|FqIIKIE)tex$Gs!0qY=W2x#pn#n>`o4Qr!eRmZ2m8XUp3P38 zMs@2S`25P^W+h|h4Mam~7JZ_B{rWZZ#_Fo@4iX>emwzZgw~1_Z{zMt(K1R^`nt#9C z$!vN=k2>D-oV4-vWZa)|*=T*(GpFCB-~K3DCx`1YFbXroV(J|(qv}pyuQ+Ss^lvl} zNfjHDQCu*a;ZcCc^$S;Zx&=dWDYBEnEZjsUruVkyzSemRO`NL%BeI?h(ReMfh+gURTBu+re&?O-1w+ra?bbzEBNFwElPy3yRhK8ckS}GY8Hx4Tw zS0D{Yb4@VQfE6Ilz26RdUD9-}D@=tWpUl3Ir01}rBv$*4KF}))=x+3xQpl4VzANGI z(1j&@d)S`o_+gYpR4{>ihs3I2cul6@qm~~@Sm$JnZ((om`myV;+L4I?ZfaD1 z*FL9`v9!znme`|qV$sc?j&TgbzksC5qaTUYhPlQSCMNv-gJ=vj_Q`SF*-hO^BIf;d zB2C8Slt=S^KMsCFY2!=U(Cg?pWwYJK|-kCsGN1P=a@Q zoX<0YAj$YLbPo{zHfNFaVG!IT*kMG~{X3RWY!SoRef-|4bFJf84;-nHk$27 zpR*CrRBj#AiZS`VVR5vS=43lFAGr5KG}H8Te{lk$^8r$!lxp$CDtR zdw)Cr1W#&H@Q(`PU(u%>lt?rkFV;U)l-KP%OPs?w3>|x}PwG)9`tLl$1osyK{j^U3 zGSvLzdlZ|oCtLDZ06CsiGScvZw{qbgH*Jo`$pE2vB@HYlO1-2+49x#l9fszMFOP147 z^HxaYA1cF*rbyT8-Nuj*7!2vIQ8G8qewCtq2&BVdw->Gxe{H0)2{nd-PL7OwsQ+Wnkm=9)#URIb7@vOT3{WkIagc@L zA}4bXc2R06t(4F^o=nRhIJaGX{Kq2z`Ogb8#DHLG9?}fEH4Nk6flq0)!Ec%OW^X(g z-(!ieyEKjP-9+!{=*4YGSFza|)Pw`55Kd3`7ZyFWItl~RluL{Q5bg5yTm{|EB~&9F zP+T#tdp=^1vd6QKKo|gzXy)Y1bC!YTOnl73#YIJV00sJPD+o9+xCFdHRn5vPac5_) zrJKbIukD<06ZV$7^Epy(iw_rk1x!{@ByG3bUjxP`J0iDG#gB$pb@N=k-L4N6iSNiv z?1mgHwFMz^*kU&_XvF#9zZDYgEb-^Y+D>`Y=8U*lKeV++BwQP)gwj z3*zCD8Tv;m;n7oK%0x+ss~qYOkrlgURU7)LdZ)R}hJhB)ROzHq?e7+5-=qTAkxuHa z1EQqN&rFg%F)?w*%nt*!Xpiu1QQqLkfTxz~ZYd5mfML$q{gAd6DtxZUpYZZgb?%AI z!g0^kpDE30W`vdem<7=8^-}gTWqdqP*u3ko2mvv1x4y?9@044hq#RkOB;oiq{;j_^8xAEbJdxVxLTMUj*F3BZ5$iy zvSF6_gb;JnB^NRN$g6fcyqPx87aeRn(DL=tDtEofw|gl@DB%_kWt!I#jj^RNKx=JO zicQ`DVDTdeN2QU}I7(pF{L8ST?|||f8pgv7iZi5 zyW1Hk)|k5ayr`8kIk87|x?*i@{fgUi=u5rQqoxHgRzTD8eF|>AH(RCeF=LJZsMk0H z@BQqm4MlmQGD(T!R=IuQUheIp%r?f?y!LYwRv9Oew9S<_bfAYR!|K?cH5mP%uo}K? z2=kgnR$GD`p_q<;MEH5o;Ggw=y4%X-<|=1(t!HA264f zs)m7g?r@-sx6(QPx6MK@$fP3zuXe!!Xq?*tFf!UrKD@4*11o@d0NBF`si~2 zB-C1$VzDyQ*3gN2^H;^?f^=#KojX?DZw2$3yx=IW=`QU zMNKkyzX7x$goK12vP4C!*Qf+s%*M{y{!V@29z`Jykb(uBv-#77jDNkigU`XdRS*H5 z*;%VR3<4idq1my5pE`M=A2uJC)d6tigIAZdd{PXMkI4fGe0Rd_-N=QbWHzQJPFtj)#LWk*`e`BX20P; zl+S*)VIxyovEjA!xnW=H4uBxgscnX2aD0&dH ziSWc^3`ArV6B*vD-3T|bh*zX_b*{b6MN*Wmh)*E&Rg1EqdsA_D2Q5h`tqHVKl-ZI* zE=!9$guU}TV&s^{2y=#`JO`oE2qvee_d_*`Rt?|%-IdR{w6%jO_bDL~ZD1f()($06 zi6?trROPsSJR*39mkVg}&hvA}s|P06aI5U;Z6G`2(gE{x=%n^BvFJ)uMesrmn;a$* z0!Ej6jqcUC-!wK=Af+l0bqNn>Zw8NdsyOMhW^)Ly@E#L?;vv9as`kG!`ZP z;uiVo+Y~$Dkmzg~w;r94k$-k)C`1+801_(}=sVhFWfu%2u{7%=e?cSV8&3%EFI>2? zD3A2csBe@>E}V#uJcWTIEO@E(#mAl2troYp15x8`sxda-Nku@!8V2Ck77L^*8sPZ( z@ssA+Ccfs2>jSJM!_pGVrfN|iBe9ug?t8%Cn5R6z%~S&}<4Z~#i= z=|pj{-<>N_wx+#Y&k-Do?#>woF8|H*sA{FHk_~!1efV!wK5XjVQ0unCah{MG*jOv) zhYxCdK6JF^=9ZT2@yuj;$dx^~?rftIkT!Ux$^--uXf^pJ&=B^LgPq+M-GY|#C#JjK zomiH5hmQ2uXJ#ym{m9AVRJCf-fB$ygOTwx?^8i|?UZBE>2;f>=tDfZYR{5J4;z$!;7gPt3V7E%vqs zCuUsXq#WpKw6IY7L@07>HEOMXNl39Nb~ z{r_ehx9L&Z`E}gMOmy0!Nk}9J9pZDWEhXOSuFpeqvUyw_#z*#g>Qp4*n3cG^zjk<% zN|;sVq5ysYR3$RE=S*gfT5XvpwrEf8qihFJv{Zj;z@@DN7^Jo>oQ}q&l71MVnE7uj z;6;CAN+}>L;ln}!harBNrml)0_?np+)4zdk)Xjo70RhxldlhvmRgV!}&e+h8@#9b2 zs-i=lmzohfv@HhYOVulXUeEoi?Xn`&G1E`}bp9*pYin_yW;3n`H56dC_zyr6MgDKg z5=-YO{Y0znZ#+wDlK-B%9P;D~?fLlLykYuQYX8H@!;nfc3`gl0@)@^@KGK-Hw51}P zoT!P+b>`rpF?d*iy7^5D5HzjG-#B#ad30CB_HV2l8-UWX)G>J-nedTGThk<%a#ZM!aJteSu2;Mj9x~Qr(**$d2AlDo zGkmsq8mJH$g{@qO??gh2Zi6iXAUvQADYl zN z01TH2gRlq3#n>&(sd(-D3hw@yH^MU+@PZ5Ycz%$~s$&J<3$n^TjEMO#U%gYw!Q3SM zu(LxV=fvEx%*S*M{;6G_J2l7e_A`=r^1yhG+F><5U6iyr(CjUdQN5MP9 z=q^m_o}YY5zVGT?tDY2~(U+#M*&u(8-lIgHQ>RGR4vUIH2e?c?$!0N@FZ(?yDeU3? zr7)$o#6zry2WG{|F%!ib#ouZ)sC92ufZo{3TSJ+1Yxcso^K*U|@-Xk~!X+o5|*vT<`>>BZHimAOlcN)B(pvcavjpR1zWLwa=@HydMvX`|VXccGoSV0HF7~=AB+1 z;wt(F)BP<9j78+mg&R3_|BdHBAVew~*XZ-}qz9Tmidt_7DZ6R9GfxyC8)3qdNN&q5a`#J_O=Es%ap^vv3P&y9S7`G>gEn5acm+vU4PgcU@gx5r67dNwx z^3FtmRo{N1o`10Pv&1>$>CM;r>zi`9tS# zwWcUW>RZu^hhYpmn}M}~iYVt9g4W@jn83|sv3oqRyS*YiAy5o_B>MJtie>un-r?Nd zKm8)Hf=NgueKYNi_YU~tBri+s-G*q)XaWN#s{zUZ5vcBl)FuO~@jTl1YKG{kwQXQ~ zRFW$bWqK%5O1S1pH1*F`F?+#IQgm&q#hW#ptE*$r%jLYd8J)~79dmHrlt&p(tKEDX zOH064YSBafK>r%5t!ddW{kEH#*r1{tBQYssSOu%kvZe6NIo>ZuQ2R6m<&QnDnpiWa zrGVI7QSz%F^!Zv%J^pd_Z7Y{JN@8weIATqRN=G~ev2t6jz@`h2tMPZx7kOqMifhly z!}B#E0lD=ZwZD|CtgJr#!VFL`zt4{oyHC-nu;8*8hd}xP+})lGQxsy`d2Q11YzJ^C zfYfxX>#pDE{-!v(j3TVr>Cba5fx2M>0)AH zM0B-^X1@Sx&b3A*4!N%!P^x4)h39s!+wde#Qp0pN zk!tmdlpAce^u~oVR*K_v0C*Z*zp>6o@W!E2p;(ptULZW9wu@*JVZ(U0rOqoh$7dJ8 z>6pKkmr<>;?ZhsshTZRWpj=I*h%b~{j08|(x^xn1ae5!GANm7GrSW{$c4dqEbbfMT zV#TB3$fwEwxMn)NMRK$*_HVS3d>7jh4_e%_pW%ra;HRPgh*&38H$v1eH<6B; zyL#k-ft$%3{_((_Zc|5KYW?1CV#1wG7mNK{VB(`g1!CuJO3y=}^Q~t&@6%9X{ej9A zMRZHQ*iyd@n*vM?Yk}HG^O}LJ_=SYJ6_BHI&Yg(iT()alh<9IJcC_ z`~zvla9@`|0H0Q3@=0N&fHrkYpNQ*$dH-eU(MX=BlXE|H?KQl`Qm+E#u>x?h^K9vg z{2J`AwO?ex`D2|^={|tBiXo^srzW}La@i^BL{EuS+OnfA+2y12q37)}c=)AnAmh#9 z-e#Si=&SC95}3L{Wy{Jr%4jpu-958aYpUx7vFz&D*e5VMnP$-nd-y`yH1&_J9q?IS*UKp2iEV4RppCS`+eL+4p2MYSNoBh1OZ?%{{7ybN+ z`5;oi;7lPI?*{C5;~Gg#qL=`&eSF5lYrkHqB-~tTtSF-9$ZRI`FuV+L7>`0p%e@Z~ zt9EOybTp*2bgQeBBfGYiL_?$Qay7bPIwb@)B#^}&E->xWb@kof1e2M88gaI+#`QsD zij$3UnU(62R9o~7wbo6llMHf;cWGGbkN72aj57Fy(a{cLvqC4BaScf((P%K?p(-hJ z>GENB!PigiY~ktQuxy&)n7q$h2VQ$CJhypW!cUW`De6*)nNv{yu;iRoWJ9WPfl}9< z?+V~_#d!i}!J@e}LPl(o@e+4*bQe5`y)1cr^y#-GLs-ViZ9E8;z+<1lVEygewN99I7WT6 zzb>TWai>qhE3VnaQO0N~us9pQOC|6Wp=-JCX+WqRI|UXNLa!4WyU+IUw5~T{lKJFn zblgLXPVziX-f>M1HXWlv_a8dCqrpG0_%{m?$H@+V&bR{bPH=?PJn*QNoOy>7h=K|W zYj0X$M;%WIYu5wkvx-u#YSxl#Sc7Dd-~XvGo{RQ0Iay3h5gk19lBT%+z2W=Si;&9O zgq|pFOq_@P_rOx%mp)xI%haLYI*MBs%eG+={~mQWg9n?DyCi?SAcSrfWxoY)<=&OT zPLsD162W;GC^hALGU;0*FA?!AKy(w#}=q^Xs)E+fRWv;naNFKXsHqFhG(}bKmvMib0Nu}6T z_0hL%yofr(4>w~m${UTCpVtSUPXk*N8H%gklKOUWNqo+MI|57C)Pms)yMYjSdiv<} zJSM{Xh!_+El2!f}u~tmvs)#%E$@;4>ig7T=2OTIf7q_)#IX_s6YdC1uyPAKvTY8`o z6eL^nJBd;1CP@`Uf2CqT?MCr-#kwj)RetOT z_4`1&3>S9xmg4~7@~ammTQG#7+N<$A!hOyM)=D^=qhmPK|(;w%#K@%|qz z0KP4k{S@m4UxN1+mj%0PD(f-p>4b|qmq5p!w>B}#Fvk?;K(^*E$Sl-g#9nvnwCT0G zMiz7{XBIu_ty&fL3%2B^dPWtB{u}#)SUH02UbV9C6~nl=E0zSnE?;M-=La|wt)7v; zMue6E8zJQb!#vRL{PL_caPR!YbKdzWP~x#QA?o{(ATKr8;A#42bH?i+fj5P~v70#V z0gHT(JsoZIJ%s=|{(c~q(Y+1d>UiM6bW3Ld{^1h!Pu%!mP@s#f;tehfe1xe@#ofAM zwc{g}47j7g@goa~(-8es?ipy1iPZI(o+U>Yvg!5q<@}cE%NL?PFWuh763Ri^KD9}>r6+d*JV`3QBW$jhy?zpB9HrXY-kV+r&) z3T&&#ptrt~sRWJxa|_M15s87QE8Z}dc+td0q8_yG2E6qKez-s#vnJL)1k`n(irNgrt#7nb@Q8 z@exs9D1Npx+B*VWY8sk~9gb##~M%nVpuuo~y-tYUj=>e|;p zb1EwTqv1=dE}M)u)yRbOMsIu4J@bjg87UBL7!f=|(RFq>37;tj;Wv2@ z+MOhw&5TW%6-k!|&<@lSM3Bx{8G$IjW)B(BFe7N=$F-{aHy@YJxJlK4roRS<%~UB~ zTu2)g2mEkDvqE@M|g2sG{@d)O#vOqj~Ua#+UP0>@TVdic%}!;rFcim%zOXH8pES57)`Z&USXJN$dtu zz$O1V-Sk80ul;BcVWm1)YxQ;S-wWW!CGysf3(FX& zqCuzJw|_SD{rtCP_&dKwoSsns7FwbR$HMEWJ+{8JmlXk}*-FiCbC=&fG>2Bn{!Y0i zKRk&wTHCEHPq_du;4<7{ay0Ti^>q-#$a`n8`mKe2?bF%C3$eO5u?#nS&WE&Dm-|wP zL_=gV2PTpGYh0f{lU`2gu#b${sk zwQARRxT=r>y*Q&RN~78;Sm+jcj)yloQt5SM!fM#4edRTpE3I8=rGgs=EE`iL8t#iq zba8Tu6Gb6}N<@hUguxLnG#l+QZPsakb_cRo<8p0OHsLXQ!>0=c`;(2G*OA&w8WYbD z81&eZbo;+9xhU5a`(L@14eD)Pm_~Zh{f0*=*hf}(`yWT2P-;Cf*3ztlZH+Z-=0{aX zm;TmOns~+w!Lw1$ebwgh@eNdAA|N%Bw94a$ivjkBPy1iV5jwuuO>_V93;5Y)#zU6L ztQ3L=s{a;v4~(SD^I$QX3ZrgHTPqx}Q*CCJ#Qx^JIhFHX#_0xs-!h!I2)~zh^R+5z zVu1l=adcMq$H^_m11Vf(y2U9x*3U&BZe8sb>IqR$Q23o!pL}4zUtL{&@eBz#GkFn3 z3sm27c^{iaZoo-i8Z-FD__kkHKtu)yDhtbzfih{-M>%=}QFf zM89~(#KzVM6ubv}%oi3Gz6BaW(&jF{H*lmQzU7Gs59XkuK}5)~C`1hwp~C>ciEF*W z!WeN7OkW-0F@jyxK@b{Cq)>u}=wolz9s9d8Rs|4(fPzP3KFUvpEIcR__5m$J*B`F5 zFSM71@}(Q85OcaNvSi(>$|&rRgLINt34GuOse31;Sg4*SiqTO~!Cq241U)&8HIqMe z@PqPbazBwgXY=zP9UuQp?%0TjBYcPeR4qpWMY^SJ~P@ck-D`m1Q={Ww+MN+ zhwks$(IIVTYH3z4UrIO36NO$rIhFj~3*|VxT2yVk_Is(>oEqMYuHn0V!o?Gz==9LL z?>aHDFZJz(H7#BiZcxC{{ty=4m4d43^J=@9)ieKy2#L|v&gjI}?|=mfw=cVGqq#XT z!!-AT??E$n)u$Ru?2cOpxbE3|ey%thf}!9}*Qmtdei|DS$*8;-$J{)d3RhW1T0@*& z`KnBL!5rWDi|pzeZ-|KQ)sP<1SL3-X{dSo6kPtm>?&0fQT4aPn;Btra%lVCD zBWwgY_fNNuFJu{6%8%+8%XxQng?;BRJDzSlkki`WIQ$O#_KfwiAES2l9aqTx5-6pd z+j(N3+_*!Q05l|gGGI)N^bZk*atU~0)Zl7Bh&aI}*z3fw@fGW;LW;=_-4AoTMcsG# zZfNJi4Mv+e=RZzn6{Q+iZsdR0E5JvZg~@}~e6#PH)!{O&Kjl9a8vhgsJZH;7@3lu^Mx$h$LDL ztCcwRFHNqU{09zzFMSm1I@y~!P}x7v^Ldu2CH1QM|M=$JH`fLzNyLm=b?i(OW&Vcc z=H}9nf)vw4MW(~Wr3k7?l>U1c9$skt=XJ9UlYs$s_Jjf@E%vSfV7>~Bw)sjW$7d7! zx&im6=*st$P3kPW$pIvS}m(g^P)xD!FW*s-@tN%UychV!p(NrUj7YJ1O^|t(@!f#M1h~ zUxjerZ%Zz?nsrC03F7i zFe}o4sv#5R+Q{+Xo^()UCA6y{FpYX>f%ywu7r7a#1Oz7EG2?(Cse> zYqCve86wIl92JM0vn}t+Z+%nTrkc8Hq+Td+2jB|Ui&Lm_j0~NNtE=yT5M|#=(tLeQ z_a3H7WJKd{QizlkjY)SbWyF^+r&ogiHdH9Py!nqcRTaFlZjz`8u+6Bg7LX07U3oRp zbX(sS=qIA{2RBr23}2reRnhBO$x(0=2@Z-(eCOB5>icZdmPZOLK{cn^scIgUoY34; zZKk#`K(GG8h~VVMv3^x)BI6-$0Xvrlc`}ECiK5MW!olL6%CmD@VSRpPw7KG@L2^Utj)H`r zTaXS*gwv-jwyUKAyVPCY(3{HUg**F^5+U^3H|JioM+1UzdoSX|$jJB<(8Tn01Gz2} zGc)?-8frR_K@IPyRrSKa+*0(kJ5Q0-|L-mE;>7Z+;JDr;6j*w|YD1pqLRlz^LV>IM zlqOKe`m{3G!lYS@&VJ4SSv5Gy`0Sz;6u)s|dM0z<++*)6FE0<=t2a5^6ov{&>dbws zkAYv0|G$1c?uzYK8%i0VE?M2z+*i4~lY-3BV&j=0Np*K+MlF7HUL+oRP|LXBh&SZpXrJfT zBIR&bFLbY^`l*FG(%k2GXB`NS`2O$1^w}FWIi+hP_Us)&{WXS)fuyjbr25p38n1oi zWDzd!>e(~EO*&a^6cx`-*b+kP6Mu1NwEp@?4Z5betel*{y4k{_rS&Aq{vY3t7mBD9 zJiapfTWioD0*ZZJgi<(44#eN!FflWC=ZXlRy ziT*_ux_fQ-qlXgJ$kK)HlzHBG?9Mf34wFksIq>stl|mrmYHIj^7C*#YSc*zsR`yey zvAB$kOxB#Ufg1lxeL+r`ZCV(u(iAUXt18(&#r_7C)Vid>Om69vh#-ow;y3F|YSrqc)*K34#fY+>i zc6N65eA#P7757Po_hxFFC;@F}&@2S{m7| z~c*mk5^boqAbV zZ#^HbN&G_v^R8;Dp*4&PQeM-0KX<$i?sGq@Gji-vfd-49l}?a=a=X(RuTA&R6?Cix zYk}Kl_Rjo;{R3!nTVad72TeH0;_mLekJkdMx6>RC0m36?L&I1u)2`Y(;VIrwx)NJ5 zo7w_vrX5EEoC0uGfZ$`em6CcpInCQLqH7d)J~{blPmExUV7niPTXD(#k=Kl~W(wZ&k3u z2S*{>aLt>FISl#dP6wCfQ4%((9&Z~CH?V|(u@i;`y7Tsay1PTB8;F-QG>_|Oo{ig1 zr~zJ6yTm$IIsfz{q_{Zr# z*yjVRK>o@JSN-nM9AwI1S>^ELzm!(*o;7!>#HBt^QSkzExLNn2K96lQm%Hg9HCM7K zu@qkS2KXVqJ_fyFm&H9&ojc8(*TU|H`R*Jnijfh1Tc>kz9EM}ck86xK#f!zO5BqDq z1n+^kkpplfa$mO`7{C;pbweBK;U0_ClLR(TtmJs81|=;x|HW(bDxtbRv!1DGd1V4&-ol&6rtP(rL9i_^Ff;yD`{q`1QtL*a;D2GpKYu|$ z>y}Hr0bQ(prHzZT^Bg3Wc$+oSY=JLP5yfWHMm z-p`}~3Cauo<+r%OtnNty@^B>v{V(fWd4(5GeYV}wijIrU7`!|~ouxlTpjcaC4OvMm z$mxN(D?GkG2f%F@07;VzK;V$HPr&-DL# zG}Mp=zeMKQbG**q$97TDk7R{EF9JIZ2R?q1y-Elvv^Uj9fO;n7%z zJ?L_AJ+OX>J%yQmeHXS???LOH+q8hHg7kz2DSlM&JRirkJwQS7b8#_p=C>!$$fTrX z-gZm>ok9ZKe@x_4y-#@x2Y<0)|94ys2Nss6e#rIm0!n%F=RxFwG#ofyz70A zScP!z_7Ea~F=4Rr$0-RQPnzsT<)wHamtz^jQWOCfL?7Pk1#NlOTr{VS$Kw0mhaUTo z&)-FwIYPTyqT;g6`CB|b1emlZ51Y}vdW9Alna8>MrB3_$(C0g)gKNWiBMi-Uqor(3 zn;ZeneuH|sZO%yQ57+QqA4C?*Xe~4OOeWKUs_ywJ-O~p&g1%)~h9yOUy_!W!SDCF6*+%hgohL7}?wb~sGgqkPEH4d^b z_g%BCAzjH2muyK!?g&Z`Yf~w2`ob?1+=`XFGi9>s(9@fr=R^~ry2b8QH5_faT6}5V z6#jytpPWi#eOYX4`R(P~C{Wx|;5mAUT=IyfQDmU#nd|&vxY}W<(Izb@53PO3$p{u} zbRVgGyc2jheoHW|XH$M~fU_JnSLt=oq{k`nf06apVO4!m*C-(%4N6FdG*Z&t-Q6Y9 z-QC?F9a2iSbR#Kw=yr zeGXn2wU&44`q;F~MY&LpePRoH462Pc;#^ICi7M!3tj9A-Yz%dDcx=pb-eD>`un1iz zdfc);I)g+i{Jhw5JS_-1wFOWY^_iTO2q0Te4NL|5f|7|o8XN_OZJ=6;hV8a*^XHEv zBwup5Fu_G6;t0R+^5DDAb?4*Qf5t`yld<5{N)I*fkFV!7JPvvsl7#+gyOykJzhO4u zb7UcI-?ZsNCXai5zf&zDP!AuUYH~eO0)nctWRuI(4QygQI|4q(HVn!cI(L9pl8WHd9yEqP|x#-;dW?8 zY-0k!VxsBBWAX_t^Wp_6&GsdN*7~BWeFCa8rybT@=^eJ=wlU3@ zqr3QTnLaR%4b;Z3^-1zBv)nDUIf7G?j4*hV{cApu_?b>k});jYIp9k-S#-`be7Kr^tQ;OzR=#sY9-4Vh? z-6zyIEuL1oTd^6xdjdUoT^5CwL*d8!apZ(4tzeu%PO>+hRp+f&)C+^S+0i5Om3YC& zkF3h-tq9>K?=rjS2M~5$Yg~OhPZkt>Y96?jC=pdI-DwOSFrJn0!-KHnH`YRV9!(Bp z+8t{;j(lWSkLvGueeQn?&n!|%5vkt}eox!D2!3C)^Lx-?(DS0Cx=HvKQ9qafos{;> zy!qv#Ezy0;a^-GV(}G>D+q3R7^b^Hs#}$$u$8t!?$J~wI*15eGE9zQxdv2qAk63n3 zBl8xR!M*|rFFmfS>u~zGgM(j=+;9JOwIy=75=!LZwY@m8YS{3@X$n4~5V!CklC0lj za1ht>&fOq48DD2Hq`N*@ePU1DfY6T*R-PgM={jK4!+$_K_38XTErzJ#4HuE)1SD8+#xeP@=FH{eqkgid;=`BBlDK3Kc_VPZ?%dOimXfEn# zU&vBwd2&|!nH%T=tE73a`*<8^?{FU*zkTq4)7^MV#rKr!6#2DfH@3 zWC@i%zP1g^xGhMtxQBB?PC}?c8KTI{d;nm!VKOae7_q*28QZfw5j#jaq&FiXdW+P6o6poAWYmks=hSen{{b#dh+uqa~MDn2OQ znG^FT62N@fN(y{0pEI_|t{2Cv!Sp*D3pzbD2H>LLGWqL-9w`t^9_cT+bwz`tz+0U! zpZc>gVG`KkrlFxeI?nz;hyKEQ*d-WpAGvKzyB7bWJk{u4?fsX6WoAx~r zpKNE=Ml3mz0;rz`jw}WS+ClbdioI$Ax{375V2{(i+>MhzW`qxogpdRGt&C!G($3m9 z_La7SuGRXn&YwR9#K=1KkKWzxm%pcxLNIE6*X46gl`W_e?6x`Raekt)a=oFlGYA`7 z>3qIWP3Iu?N$5D|=6n!@yOH>!7pN@_!|eI#bj6Qx&gK>#*`5bIEmk|q|EwMP&iRY7 zI)to@>7FFJ@D8TyXt$QB*?|HfUR5yjV#q|WpOOiY>&}|3<(&kB-D&b&$nH>z^XP~C4=uDW5HIW*B{I7nYEm=e5z@1X^`oGui*jAazdsnr4dZ=ua0*{K_ z8pzAP$AEMrkQAg-Ybcur|Nb-Afki6ugXJp;H3LKCOKe!g=2Zh4Zt!&-yVgR_JVL=P zt55R@#VEDrc32Z!y$-%ZjV%FWEjv^dnAxRzS}yk5^4Xshu1x|BB$8ta8!;mTLe$a; zg0O`JWD$ll7;KMo4LdVt^N#v`L-!^VG4djW6l_u|nq;LWPu#Xlt|!9U(T-C1g@Jbn z^gM;hRm-j8rN1hPuEXgaN4elE|7L2U6=TmX&uwOyuL)n5f{mhXVVCd~3go#PtF|$8 z9e!E~mOXpW4m{O9oU-7d=QXGX^$8>@gsr!_QAxkc`yMi)DHw+w8hhJ67OC|(qU&%f z#c+(x&UM~v#>cviwUWQGjiu-5raONh7of4d5Kcw@4zotMJdsoyrXDjfpaGkx0C<>k zr7Rw7lkHvh?-8|lA02NeFxezV`?F;g`x|uKw#KtrXdcdaKk2wqZ7H-b51P1FdmdUg zS6dElMf{E_yxCsMXz;M!<^OY=`%uG1k10}&x2Hd-banp~tMv3+YXQcI$|ooW^7^GJ zuq}hjq>yzM>NkplgAGZK19#B&_P{i=^@=pxl30EH2v`TXQewN=Q0$FMM1aOL`?OBE zD3;E|Bw5e1sG*>$-h94M$s>Yki4PIh2Or1Kh#o}$;!u{fb2X0Q!ggM*F=FVi)sS_Q zCB79qA}IUI38AOj9HhL7`S0~Gb8GZ+)v}gwNWOj;1vMsY_;=nRG-Av`M92LXmN^rjGd9$HNKQ2KCwXjEaJ%?N4dIoY-)gxyU)S8?j6ONM5td_nb;eV$RsBB;`K@~DcPq7-H(jxO2v7edk=f1Gkqh=eVL(OF0by%4teU>ngaSmxW! z$GPnVck%%+wa9dXp!A`iNq~v2kiC@f%%n+)JvLdt+l#n8?>W3iB~QeWz$1oYvH0)S z-82vL*!x-vp=46BcVUNAM%_>rzbu!22tfQjWGRb0U70(y!4d$I#K zAuHit^o9t*{(ui+q|T7SKR%B1oq9Gsl7ox`M2oc;ncn_3%oc~!uU_kQzVMer54mif z_nhk;*tqO_P!-rdE5*yyI%7Zyc=U#wck5@UKE0vcP*jcL6&`We0SmkfKn2`-|jdX zYY5`<^0CXy-faDZb4&(ay#}!$4xiBWk=*VIOA|sSGns9p4hK}f7FQBG10I5CHuSAA zbX;7B=5{ zTE@+<9S!i;@=AF_UT~gp6xr4yG;z$yMZP6ud-0r~&fo6s%VkgA(i(VPuUqh5Z=GJx zYs4{iRrD;@sTe&yy0$;x0gao5c-U0lv*CBIEk-IR2WgZ_z6Wn^!8BGwWx&>EHydLduzZhutled%Fk@ioG{ov%11{-z6AHFjlx#m67 zb^$?H*dO$J?`X5elQN_5Yc)|o{1OfwRO*9Xea zVtQSVsL5o$k^Tg4eTxKb-NYB>Szc5#Q^I2uc>5nG_BKalS}(yW*#CUTeAuq*@Q@XK zK4Xo$U7@bcbrYrc2uZoVb(wP7iHQ{w?H8Dd7kK}^VAdWfA^T?9t{+|SgON;RsK;OC z&b4-I@1=ksV*Atszh3$HcuGVOr1=KkoL4{eFG*(}TRmLCQkb=w#lcCxyg$(Q32sA+ z6Tr)XbPE(AgU{@VDS(L4%+J;V-J_-H4d1STIA{Ivn+2DAt+tUR!x7yDAAtW2069)lR;AY7@c+16lmmE`0IuCdHFD535@i=12j>uu0!^4`P;f}M!& zdQNaCyfZg;zjHM0yBFvEV7>RgtUOJ3xF>E?#y_2`pmG_VL`;Gxhg7^9=SXx z5Gcs!!dkR$53K^;C_*3>UV}^9?9^^DI_O*f=rp{m)#-qwaN;$loyCIAX=o6#YaSQk z3n8g(u|Ul6?0m2I_=RKOq?Vk@m$Ax!hclgRJmk-B9!IRydK1u~Z4<8X#o2R|Y*BU3 ziuX%U5{N&hoO&H9dMv-tb;8-<6kbtx6oXfytA22F?)UO61%el|6Rk=&p z`_|JAr~T6o>%*d2o-bJYa8Nz89RiR)6k!ZIp?~BacObe-E+?!WH$7<=)6xF1nmY3v zfp8hOTOnva%nYIta`<42GrZPA6S!bypKs2ZcMDMXviXPvJ514jU9Efgf5NXiQqojY zn|YC7tGMV#BS+$_Izi_56<%HSgSug=*ZqVeAoz`(np(2OKt~6ujuGx8sTu|f3)W-5 zFMJqW?)ov=L9sY@Kh3iQYJ$6J`UhTdjve*11=~dG8!E9`3*Y6YR`ISQ!WjT78#LM1 z#n6X5cB6k2Nd;iywdRR==k|N!sjegx1euCU7}(YBUeuw!>pFT4>e#2x zSB|4|?4ncDq)P|(n+j~Yx)_+b0W?kdUH`}g6^DK*)H<0<7?>pCe~7CamM5)jgGx9_ zHK<)kbWI4zx3;}KWAbB(Xc`T(WI~7IML#Wns-}|=k;C< zCPlA0=HX#NXKvfe)ZajUG2jQ1tL1#V0x;A^sH=h2Kwfo1LBA!Rx_XDcc4TDZNp59;`QGY3IkV90S2Y8ivI{qM=7s5|)->LIU zAG1fnCgeyQ0K1Hh>|Jf`zNB%GC=erJq9s9h zKXmrrudFh@$G|?j_hk68W#Ziu4?l?*RyCL^hzIQ}qDK7__CcJ?5{)Ntna?1QV;{m6FiW{DFqNiTde3&3!9U*-zCb28vo z&HPEY;Z*#A*?SzCNRAM}BN%*__}=y&t{J>(L<09;A~o@)1wOZGw)}8d-JR*NEvyX4 z0rEpcH-9u80$D>V+=96(F(63;#ic3riUjZd5ASlCsnX};T13D}=d-2fnc^PZVrrHkX0I;8p}rlNX)0MY(u1q&LGvWA~7sGtw0&$Sao?e zEXV&nLO}acG)-@0joHokdlQY~FzV}@x+V-g0JH{z5F>i6y_sQL2TRr?0DliKF|+i) zR0_3%7HPnEr(Oc#<0W6)7tB`AwRepu0(w=+&ngrmsZ)VO;U2yHhPv*N<##zV&pi_( zdSd@(F#tGf0gVX8n}`B1|5ap=_>V~;EO81-%Ij8CAi+ZLe-bQzzv{n#C3$V)R}2T1 zS*MioSfuo-X%vMqx?YzOo?l7uqq{Qe+##{&g#Or63qADee6UKZKr7wl=&TSy<39nH!jQ6OYCzxl(Xm*GBSe5x{BUh6CJA;KDNam)Q)ZQtVOFD1?^;zGceI z1!&P~u-ep=V4vj&1F*KCxysa^CWkd;Ee;#DMg%Sh^&45yM$q`{Z@c-S(I0neFV=C_-F$6$;_=(mSsF6GDg?tCK zk%$?ce01+^_ONN;T`j^cH3S7!u7vwby#$tfK1VJ8{%A#I-OGDz%NYj~6?X|p;oSf> z_U50Bp^m;z`hV#}zdz0-3^>RY8uUOJw`34tY}{kvKf6EU#}425A5}KBcXky$(*UF& zV?l3d{CY2d4=RvUiDM{9kYf8ZX{Awvgi#!&&{Qa0Y+S&Gx|_K=%mILa6kd&rwE9R| z0d#m277z;{Ipeq)ic8nz?Nt?e|Dz_i0}9IMUk>m#Lkdeb*}1%Q2~qw@S&)Q#XyfB{-d->Lt!gNwdFudgUNn;Fp0{jr>wR-IDT6^5fP>?6V-mSOHDJ+1c5c z`9tzDUiQ052ke0LZ~qp>>mM^|fJmi6yAB>0NQEZw-rkq%!`WdJbtDu+-GoC9SI}lM z*cnC$ASmy)RvKj}#*ngOv)S)hOUx(y6_49xke~?!_jiW^8rp!|{5D5z4oGA|O z#qsc6Qbh^T-BD3f7lSsEPrM={xL{KvXubjrd8mL@yPE@mXoJd>9SHCo*y@|J z5{K_fIswV!8|IqSUmc0ytf-7d{ykS1As|Kj^Ct@wp?b=il$6wfw)vQZiwg>rkOeL& z9tA1>!jHRl(1VwrcIJM1Fr8KhvVnJ!IY_iM84cMoo8 zSiV|&+7-vavzJE|dodETxG9n2%mdIzcR8Z_g8(_*2UAm1U?W4>ngm!u|*Y~^bFEWjI!hfp>hyGjD~ihsWz&IuGzU`J3V%1H&N zNDm5^w(A`Y7nEmz>J(-L5uDoAgdX_->IybyuK$|*2*N8iOMbZg$}s&O(pO4KNA;F|l$#6#T!w4&XDWl_~CKd-BDxsxm zXBh{t@q`QR;D|r06+(db_1}dA>%?Bxx=K~9{D89$I0~&gP96CV51Y~>i)%WN)?Zq5 zq%&6}E=aRMnt>%uwm!3!-sPcIlzebL)pn)?>wzY-K)U+u@e&81SO6poX6NGtmimT< zO`zS30nk_DPhv!5|AZpJ#$BSf0^Ka$YxLq;AAgw)nPIS zRZMK{)u4c@cf8hQFd;iT251N3AawHr7JP}^9*ln_Kam&Y0cBKz0UZ)>?l|cJU741h z%TP3cMW=R<5r(vs(*f+sSArj(-D0^}ts0C&$d4zulC`k>SHGmJ!@G2$!PP!i zY1^;MW}DYSuUEC@5Foj>5B^6-WIG1l-uQPATmprqP#Vx1F0Y}1eZdeOux(UloM<@f zxeCX!Dim;P=fJ33*NHWAxuR(mgZXY_9l&^)a?=?7GmtK8M(vw2lp^z$Xnl|9$% zd8)eU#0?nwS!czkSX&={@Y1iQ`ugNossQ?b%XzZK8K@Z(QLyiFU|~0a8_ySnT4!e5 zJDRb;Yy!`b?Tq&9z3#hjVRu^F(NyXG%BzAA&xxfQ85Rh2s?4P= zPMKF{1y3>+g6CT4J@|XwD_Min0=lg72kiH%@05KCfLZsfIejqn*N)>^HX=fO-R&@w zqf~Tdks+PuFa?lP@y5vr+M%KJZ`m;wGirUuYq1^vj~{Iq7=|IQ^O|2&Q88M&B!{Nn zQ;I*Uq8$lvJ$FWP&r}oeV*q*;_c`m4%4>8G@bO&N>giqN7X&CF8T^x30Rn;}ua!B& zEQ5TV^Ridk!s(=2Ri*b+gP~$Gav|W~^(w!{2Oe}y$Gh#S-Z-4kR_{mIO+Bvf&}*yn&(@w^pGfSvz;3ARva}eZ)|Xd>{Nv1e0?M zZ*|S6zL|U>wONh&t|)NeLh@=GN~~Bq_d0Y$&H}O9gAas1VcyCl{9JBVu;e`=y!EZt zYceDYFBMBW$FbU@@1dpw|8$C z>g`3mKT3x|^~xN;5tq;6$S*2_FIZsRnXzC4x`~Sl3qx;hZ?6hW%xEKe93IKADGI)K zgn=r>#BPI-y3Xw~f6obHX9AXkk)-jf0pk-MlGeLjnq~92ebV9K$?LdMv7nX@Qoz9Q zg)G)oX$Ol5cjurB1YB(d3kz7izSZ+kCGW0-_%kP=ju*$=>~9@S1W_k|tCe6yC`b%2 z_9*pE;vcVdKBeY`O8>{S!Tgp9@KhVV7IYw@E_p~vn~+k*hAH{iuls6$I_kolda~J@=3)&G!XBERM6R~#-oE1Tn zeI@m2WMrh)@5u{LqtZ9oF4ZHN)h*h3AVC$-^w@BiOc%*_2qakQpnYjP`<<^bIH=-` z4LK$Z)lO0&Bc$y$eEG|Q#>VTHD9eE31BnM;96b>C*&D8gz+QhBDu&DLd?XhrwQ#nX zu17z6IRJE*C;JcdvnPGa*6Y1%5}4HJzENHLml&rVFSL($9Ux;%GgBa1#Kh!wE~CO0 zU&zWLQ&$)E0uzaW!J>vr0ZHQG7W@uSCkzY$V*^O9yi6p5DhA))(s#4^N{5!>W%t$< zrKJ}SwVpD%4YDn#ve;#_OLeZ*)7x+IkQ$hR^?eV=9qhKP+3;(FJBdGh5;1S=ky2pcmdR$#9m`G1g5#`vpqE7| ziYo%O>qW3W$C=-*YnM75e>#f8a^vhD)1)B3RPqCzw2%uMIklq1PmO4rSa`?9MU0Oh zCmkQT`iiLj`J`AHJDw5091xXX$x!V;Lm@%y&oMmUF&;YEa|KsoMgwN-;yA+4(QNK?gG)RJQGA%C6V730RgdFj*csaC z@0or$i&fP~oyoA?b-&oYSc%JxXqq)J;TmS96iLA<4DbX`)X!VUE zQVJ3~mc_sCSDd+?v(`z?9zBGrCC&ATevT^?KLAk}W+<#XSs70VqWV+A5qlg-y!3SO z&0Ce(6YpSoqTAAPs`vfxnUA)ht_(w$bRP`Z6=78DMbzAl&2#t_O9dDvlRbbbw?y9T zY)1YWE=yqeZ_0gwxm?uZM=LTc7CTA8b-Q|>i7@|UWW$3W)p~}O&Xjd8@K0N9FmV`k zLd4V7LIDa&ekH8b2TpABndAQa_uFLpyBEhF6%FJntFkd>dv6# z1Snqv;&Me`U!nP={Rs!~>m?9%fkWm`cnJ{W4xe_WVBjMv0uHP zfUaXiQ<+LPIJ2)+^MG&#PYiI%%Us?*cbsyL`TI+v7jtx;_DmaTYQD!rMev0$c~2$R zJyj^1KkEfSZtOa_%Fs^N?t*=2JnKhWmXni?cUcq>lG6iTq#2LNW+5V$ppEg2FEsQ( z$3kV`s_4i*%2?Sbd*0W4_qj@PW~L4!@7)(VJL9JQ6nQcK+gRB^9Qiz zX0WX{F$y4>p>(W(OaN%Zm(FLK>7-loM$T!LVuSF0w~0`!fsxoyvM|q2%&R-TH;tnc z2q1pS#+g*$#P!g*kSexgz|$_4`~HfpzWD&qk>KK&q1dUY;E{0|`+7o=^XHGghpF5Y zuAf|OC;E=N(|8@&&VbURu4p*p`TeNI<8R-PV3Pzj^u~>+n$T1~LVt(KBMO}!mlKno zTsO|}!XFT$=w_oOqV#_vaFfq`qgnw~YfSRoVJqloF-^{5Oa581=|^q<-sHt=h%$Me zk0#nMImzYQk5s?2x0NRW>+Hg2Rq(?&E<#AvPoQYUU$EfYw|}Ogyx@#m;B~*WZe;z+ z;O(iSlM}W1gyI<2*zA3ChQ4F$Sy)Y{24yiJ@dcbNZC5VOZ@G@lwU>9lG{9L)1{aA+ zE5)hUU9Vrqyy$`Uw-33EakWm-noZI;VB5L|$yf7j+ZO`EvsX?7QWY_DnVu_;anGCG z#-Jb=Aoj6fJ4M!D$43PuY)D8*_kL_-INNpR>*B;xehX%BS9Lc*>!qh8{)kKm%I5cSHR-TE$~rnr1F z3_ta6NM5zQ&yAt!jn+6tCz)_bo-pqSRFV&;*c|JB`8GJrl$$t(1MXq(d2$5JZAdHu zXV`wZ;5)#D+K-v}NY(RjtNN=UuZ8tpEej^ft93^F83GzX0v-6?3S*E)6=>efTCgQh zAObP!2TnUeC?h~J638VN{}XU3PHJDRxxKVp5kNhFkSxeY>=cic)tFGQ6J+aDte{?% zcDi+^eh<7*XkQps)3TMDHFF!I?p?E3n{11nID?zDz|HOLSCNK*2u||$&fH8N zMnLQGsewmC{2x9Zht~`^7J19fZKvP0g31NU6rtCb zZ>cD#P5RQ#VD|yPji1$rUP-?fP*st?K8Wzv@-iTi1FoJ4paQ<*)xL5&P#G6c?}cdI z5CQE=ue|srN)1XrzIp_jz--7+mJzOmd@(X9tqA!Y4mG2q95^5#vLH0A;i_p5$n$$< z)VVYM$&-eqbpc{oTbUBV)dxx)m!cc}(8E@F(Ju`6@2tJm@~JrbdcP8v`{?~}L{lPY z&-O2)DwM{sg4cimdM+`MBFyhgADN>anFr%SOMheLWZE>m24~DVzT>@tZRcu!!LYzE z3H%4Kv3-gqK1l~tG;O{{llWCKfF1-`Nl;`21ss!dd_w<+3-He=1apYVt9I0mZ56?= zW9i(&#L=k%4_fFn1?Zg^gRvi5%2fc})knwqPsPjc2wKgD@5}Gi%s_PyGXt6>f=Kz# zZ{?&-5@=j#n#z0k9sVuws}KidL*UN;T}W*6cf~C&EyFf5N?VL?PO5$FOG1hROvXzA zBvrX3=T(Hu2$Cj>2yDCnxXPwfmmdo6>v;~O;ty53Szy`I>r>*K7cuaFI=-Q3JJ#_= znMF9IU_;EA?MryT;Vzi?Um_2S^g4jx%)p>7kh**y_O1n~VIGvrcW~uM6IvYbBet5b zpmqE#+1vw=X}~>m$<*`P9RUH-*K=F5(q-Qw*@UUbw)MWaqSNS!{LzlF48iqD2xr8l z{X@^I-MWYaa@>y#gRe4x|1M#wrjr!d@2^!XhG&#Ec#zdsJLi{HRyy<}LW@8Di-k{1 zKC6R7=>n@kDRH|3YU6#}C|a8NAzA&o`m2}iW~ zoo#e;guFP~LyO5CwppIGs0RI2;Bw_&7yi70BiVZ(8 z>Aems<*a&1N5dKF>^auHb|_sEy%O{~u=17$a2-NQfC1h$sXOq7ii=YAzm$Y4Q}X{g zXj`;*wrXcxT5^7O@i=6`1}HxP!0&Z05<&UD${})<zd{LIB9daB*ZRwxXWWFQDiUZI zyz6CYS*r2`5We$+|1Y$M$*tUUIyN?jTIyK>C{V~4(V&b@GJWx*gfn;#A+G{%yQW(6 zuc$sRc0J0Pr*uk}O}nuAoFlWvLLlxERDs4bb;ywkcG-YDoYfae)%ax*Tls(I5c>bp zER`V4W3VTGaN*f)ZD`@P=~2ySj1E!;VjJ8lRlK=f57b5@t*;33&cgwl0%`Uih8z+9#zt-rQ1FG5zVTz;iYMl zWuZ~w2JoV9YnPJ$%n6|yw-7sE$Flso5Ad=;c>Bu^*tTESF$ON?G3>q~(26)SGgC?T z$lKnR9RFTLMa78uLqcLA=CLRl5QRK?kMKU~ivqXpl?EU<0OAIq=)|lnSV4d;Eu!*eW$s#7Y!vaqJ0t$^owBis!%Y7X+H5yO(`yg#G|s%Db2va&9O zi-=+Uy}g<1K6igb4N$3p6*Igt08B0xHZ~l)7;2$sMJE8x0x7mt!1xw7O0F6J9fsRU z8T5&6$wftIwGx97B!6+(cKL4;G!(EACN50)>U|Rq`kFwh1*i4I4m*pkUb!^V3Q5vVhoKoN;+;IY}i zEerHf20E(-KVeCTVd31~;P}tKdi&RstHZc&pZU~^Asxmm@az-7*_;uK#HE>w1EPh8 zQp+0l^|Dcvwp3ETM^-}s(~2MR@je&-pu8B{A>QLx@`VBzK<9w5yuE$K+9SfJBT z0~--XGVtN%x-RVCIy*2!Y}qBccf*%T!I%bR;F>bgRR=62TOV*Ihh__-W-d$|(hRYB z$-z5(_lM$pHL9ZMi8+gh^%`7}C*|E%Znsa*xg8I2aRtXPT#w80sR?TV2|`HuH)vDd z%298FNI8TujbJgAq5IJZATU9sI2cMo(83r>Itk<*^9doTAy+xa<39cr1RO(DixdPf zI|ATQZfQ5Sy;b+{@5ZNV-dTmYBXtVWdo@3uNUCp~x((lw4QI9S1R(uE<$o>A8KFWo zulujsXwSQ%LZ7o#zml8QUyR$b&@b3;5xL@*C*7JfUDYESRPNS}ZE;v&X9?v;QPtef z2z{00!8H}>5Pno-EXN1|EXO1@4MSXwY0S2o?}gwhvz{crU&o?8L4`z zsSht6&!qIho3CcM_#-#?cy&t74h^SiOqG)ev-?q7$saLnlP9f{XCca1MK1!U*EW`9 zAvE!)_b6%!6+r#jNei~r>sz3bpktPvJ$7uiHSij5l@0Lf6k-c~fUMk^1x{IYwLOIE z6roUmV4ht3j|fA`>O*O&>BwI1-W29lWjms>y?Gu!?1U+$`@!17t_M(L`|nN_NC;@9 zmik!-1-@`}kTjYd7ZzSrJAQMV0eGiRnsd2}H;3f^-7CXvdUfcN+H{_pg~dM6vc2WB zfdEWGaZI(c^k*7dH}JaQOu8@9&X556@b^&sRqkI4CbaUJSk$DfZ*9L;ep)N|%&Dm3VTG$;fL7JX!2ihu?cT1;R z;z04n-P09tUEq}(>%0@KC1rD5l5;FD(qw(#&6XZ!=I1#jjV=}9HvN>BOnt@i{tEB40rb%zG(NRyKI_ME>!THUk%CWsaO4v?3}kHYh@WOn?H zY0q0-=QHonBsLHCLXRzGlLq3%X>;?xdHM0z8Qh2EIUI$oq9T$#HeA9Fg|=hM>{G3I zUy|!THwAEi#NXDgSUJ?YOf&b39>G78l?H3brf{IExZbI_Nsgcz0&Cq=4AEq)&h@X} z;9dPwcJF~HKi8`Tyj8|(sZ)wAbd^oAe3^cr4ajVZspjrSg|ZT1Hw*qzv{>9`>xSDL zyP{n(cdToLYMjQHF}B6duJq1i;(dZ|dzZFv9zapIM(>&Wy_I0Y*FJ z5bSHnu&b49nOcJVOX@RYjjbsgtT%gKP5~b-U86^0WjL6%xpg3FktnqKM|^V+nJqs) zJJQe8YTnE*XP~doqvO@sjk=@YG#5KZYtb%ZZ|$~+J^qYc)vN8-5}}2s3*fqeaOhl; z;r3KyRLZLvouc};8=IOW`L$KYAR?!#*HWz^HF{cF3q(x2-d)#%?CP1OKF%ZGeUaeO z?n6fbLnJL@PoV%<+85+d9BFn4`SNuhu_)}ag0Si`H%MfCPyKVZqT;xUbTDO=$PkW3 zu2xT#(r>7=)S7?C&GEy!E{el?Usap;H*dF*?lTW~L|2EEsJ7TJglcB=}4viU%N{8ykn6m&~ z77N^rLwkGF3-6vLu2Oe&%h3J(-bxI#Vl4O~Znm^Ux%uv<*vBg$XVpdW&UYH~-IMp< zQDl?-P5WFt8`xt)J%{U(pf*WGs?OqfQ_fT)XppUI$hgJTBq6Bo#EJsWckH3f`f}?^ z08lu$+%7MFdV4T*h1;qmo;6UKYhL$j>x0>~;`Y3@|0Yi}_a=d6&4m;oBJ3PaHb!++ z7hQZDb5~2RPaWd7GC|l_h%;YH@2Sc$Jb&0Hma|Cj2^2qbWIH#eBhep^GEukGJ>ffI zg8$+DLOHHxJ5;Vs>3cW$Iw_=nPsaweNL=Sv)M>i zNsD{tlrHw1bA*!V@#J7I=mzDl*j1%-0xD^iJPC_(br}ZuqFkfy<805 zcP(_BVX>(5T+SqeKPW9Dez~c2I5kwuy`p-8txxd#mb-q7nKkL`Sz)l}2t{XgNUPEL zgjp^RzBwtj*fa9m3EQ}Czw~9R)S;?#U)30=xyECLz~xvNrXZCKxv8hjydUwnl+=~z z;LV0_9R-hPkPHQA|FGOekxpy+b#-*M;6VP>(pW3l54s~# z#1CCaverJomT_BmD7365uJJX8*z-y2`7^CVebdvE07`|VbJ`P6PEL9f zU!I>EE!A6kczI=d76GSwL9;WoFv0OEUoC=C5?7}cnKi7T$?ArXOIcJ|{MN#f_$R%N zG~JXX*5j5)zNtT`LGzd6zg)cB;!LL9btm{QDC^n|xGW*9XK3vx|28z}uc_46mzTZ3 z_U}zwxv}@O^fDvW8rt#c7`#l;FmdO_r~^f!NxFpnoV!*+rJ~D>#jd0p3C6;j@H@A z6{UA>3(P%z3PnJ)&Kc}I@uI9@tme90@amN8k8kPCK_R4%}rs@Jge zIeR|o4YW5xH}qNh}Cg@)<Je+K@zhi=!4Dhro;MBQjw^gQ<^qC3*5VbH>a*RyF8006QTiCQ>%^`-va+T8q2U)>%Q9v&|4pH@K%xTZP0 zFL>1nE>?KXoi*l5G5IqUc?ERRgob>9(l2UeeY&}SA#dHEee5{0>_2=4)fsm6MXwJ| z*&WlP*y{x*!Rg(smd^h(F0#L=e>>iv4x-FF4&Umu#TVyhYQrxYUW3L3;3h)SnXave z>v78(XrIOHwM|iSM8@xsC)Gc<`B_4Qi3EH+ARv`i&9`Ky=%H>=Gh7_Izc;HMpXZIY z)TMZF`v&R*U2Jy}GQ{`q-+~l9v&YBqC%rZ-BwTrh5BY!ZZ=?S`YO>@L@cU2+Tdw+J zmNcw>b<9w*03fdlth59x5?|2!K;futL+YHK<#T*?J@1?BnNc z1BjeV5iuYn16aQwhTv=J*6BuZXPpLHsfH+p8H=?*w39<~({EOmS5t&$ar-h^2=~*~ z;i zTwBPE!uGXXsUkvcU$J;T_HMt|GC%ZgQ{k>5_M?8@_Hn^v?6aX$u8wWFV+c6<(av{* z*verqmnCe1H+}cE>$ElI_uq~JJ>GG_eDsM*XMLYC&Y!Y3IDORIn`huJRMzv47eC98 zqQ1$fL-Mi<>|AGU45=T>76_mq(5e2Rc+qD$2JaEXZV zs#Oti*MM*k&)C>_5nA2^$I6l!b$l%zT8-IoU>@I>Po5QMlkoB-?v!KJu)&K&ZMNEC znKkv4U0n-rXX;zqS?O1xpJLzB@1Wa4qH8bIVhBmr9TQc`rLcbjOASG+oJ@vQjG$Gv z!_6B6gDg%T#eKNj}&iZUrc(7NkF7EhCRSrz0Bw|$1jcEJ7Nsg)>OL1FJ|{CYuPDg_>! z^(NOu?tsk3H`9R)pm~YE1-hESH1qHTRskzOX zRqFn6T_^H-4bp+`Qq$i@MLKfp9%Sm`i&@(0lfF#7uxZ|{_1x#B78ShtDldDpH^>%Y z^>s|(SJ6+GYG9e>ev*M|xHub_X!Nf$J@bRus^cvb3Sf^_mJDEejtPy?*)8yRE6sXB zA;+zdQ&CY_bAy^h%W!Fr>hl6pEVb3L`Oo*@o4#CY#}h=vcOv?wI5e_U`FnfI_)u`F z04ej$gqGM*ggTP>b-q81-`B3}Hp3gcZI_jsf9SHn6jgEBYUve8WdRTi;k&!$t-{livn?^9*nW*WOtD!zdbPU_?V&GJ5 zvO+!XaZj%o9|ba4$8e86QX8D61#=MT@sSB6ex(Ha$<5c=&jkPG@UJ=A$8@uG*-5Or z{xyPb-bsh8E)O1Vz3~7aPPbp%L|2d+K_jCzs|A-d_Yqdp9#L-WYakYLkkoMU1croE z>@HE|R2Gjp^3g;hXfYcTU-YK_vg`-9vzL;%(woH^miLFDTnz*i6quPcq<vrZ*G+3f&mP16)4K4)JUZsn;s=2xywHL&nxTt6HHZG8s!zl0sWz`GX*ih{2TpOf zs1ZX1YwY_YpJH2m*o}ak(N@++OAGrc|Jg-Y`?SDMJjC7)e7O!8l%i!nhFo(P9$U}G zKmE6CR4vW(GtF*SK{0sAfP+&)d9YoIIQup249+R}i~&uQ`Y6q>mJOM`YopZeXo}CD z6;&uLY-RDaZQ&_NYX9d30~f-TtW}b6GtU92))`L3+#-XGKZ!BYzoCgAiIiWWyQ2V{C>j3MvUU2L69)x!z+$WsGG+`Ptj=qKvZ=SbEz1ym)_3uZ2RQ9IeKRozl7eGrPzP@um zYczhWJA$CPzSGw|?@uu_K%_@znQimO4UiHi;OwXLDOqdW1jM(osyJ zRi%F#lkx&Tyy>YoQtcN^vcaup$3X4-w1~Kl;ZBmS-86@7mLlPDIG}5&!H~V*rEb8? zB_WSX#(tkx(2MrKuP1coiaNn1z2%0|W7*yq6GC1hX}w!V4F-dO#R^+`79e@9}z+-uC+9>SMsf=lC#G%%e!?>pbjtmz-USk1ck);)FVRGr$p&PD@Z=p&-h@bac@GxEqf zJ4`|xMf+)k1~6QhuN-r*8&HC%2jGNceYtjSx6hGRxnr+4muT6D}?Ou{Nwm zRKWb(*Ws&>3J~r<4wPZSAFznkS;*!9z`)_V7qkvP)I3R(w_|ncskZ3O7gh7^Tb*7~pH^z@d*JI9kyi1_U zTI-X*`uff3ye*RvE2+eFJ)*14{Ldyzk)1E6aoX%v9Ld){sSKRP+w*`k&wAlkJM+t> z$zbz2xUC>yt*JI=uAp{ic_Z2GcpDnE}dMt7N zNsrR}#2guCj7hhD4=@$|>eytm%%GjS(WcpC$cSe&pu&Bg>Ky3wNT|;S_fD=~1QgQKoC%J$=1Ok;~rBYZr$#1%y1%yuqtU^EflHbDxEp z!Im_gPErQyq4U>lXYVjr^eJ>Ia?gyF2moVrhccKSG}l7TEM-0Tqg1^+oxYnKzty=V z4Y4`8wq2shLuZXudn|Vl&p>~S&a4WX85XudU~#itu|-bI(CDv_!(q^>QGAYfXt?Mw zGvbCCkgup19Sh=77o>;a_qIn7TMnBXn+VW3SoRJ<4%Z9XeM>{`N9n{nJWmt zl37%nS%F@o2q+s{Z>mxxXJ*4#*aYimkf{mE@*bpZy~~Y{mk?_s0mMF5{LOMXCWQ29Q3UeTD zaVRb;|54N-Jjx_=0>pQY9YvZOej_c9ulnoETX!8%w<={alV`5MVyd3>2gJ^IKRh}$ zD*JF&|CbBUHen!;;XzwHInka8;DRV~GMHQ73m#aa&^8OlwfyK9OWR1(u!QIB=km$3YDn+Qo_0c~pm zj0GKQP28wB#M$&?54L9pjzMdk`p71yfem(|r&@WvJ*r2B`u*{nQ*(VY-gshiU}|@V zRYlVrpWjXMz9Z-Xpb4TPZZxIkLjia~*I1S#x(B~$KK{e@*dYLYE@%c0J~itmm#^C@ zOQ1eI#)9M8R{nH0a9iq&VsTemUXsI{LmvKYLQN{E(E99$e)HP&+yEqTx-VCfAPYNJxXcFs{BPJ z1gAC7U}}WI;Q6N6nqTsz&YBUf`MOVu*>L-J$BZ}V>p@8!ujcOyR58V5_h|1TgI7ju zHW|-D^*lgNs+U{dqckcxy(^h*c(~$dEGsCM_400#nkjucHFD{^bfbXMFXttwxy>t| zerLUp*v9yxCl+4R4+oIplJokUxFe0tJt{A2Gme$9aj z^*gu(wz~fA;bWh-4YSu9z5hx$pL+HeL<+zme420J zH2b5cI4Nwtx0QPApyMM`Br2b*G|E(>LnGl&YKeC68o%W@-y-X}V$yjHuSz!fN)A%oZCy{x$K|z$alOfX2Dm8{eoEhzJ znF?YN^(Ayj7J#hYg@wk-aL9XtU|TmC`1zLp1sH55CZ-8%ol>cNdTle^u*D>{sCqhQ zi>p=rMteu~e~w(YdM`JYFgqm49Ar!NcWtfOwY~s7uiI$twA1%KmY7dWK|w(WT^hj& z-Od4zP0dD`fBVi?-RoA>u=Q5xE4vAQeTmNK;slD}Gep69+#BIv-+;JUH!=VH zwP>Eg>3scQI~dyrzZSV*l?`uILSD&ea&q7A$%PQak` z8aq#b5zJQm=1S zW!!;?(SLCqzY*?ypVI49bAG#l{@+saTJ{}8-}k>w%fD;UFJE2GgExAv$0$xQvPfBj{lH2%+B5L6iyLX;#? z3sOMBr9%p1yRguTFad+A#nir4_&>Q&h4H9;mWbydVu29f5<$#E`oEu#KrScgH1?1J z>M7$pc*@fyM3^9XXefkd&?c2&jzO7ExE1A^++>ctKVP#TYY-I`{cD8?XQ}_sOQ=Em zwl!CebVYxR2!Rtd4|m`%Yr(?B#qu0wuDulk?>mi=Awztm+ZF`eGFmkGi|__MJb3Es z>yLTkLkxm6-DI~`Pa6CWCpTcEql@@EsWv}n>Xr+_t8mCa#J*$aP;r4*M&-)PUo(Gg z9Wr*4eR7A)mS(v48ekk-F}oixz7S*61x-e6z%2Yl**|zgqR}Af-<-iGk@<73u-}+B zG2~g-PWxjx@7}%p_hhH7wJtw_jW#!N4Gnd!8>#p!3zw*?tAzEWf38dC!0&q0GnUMV ztUt`@NPUeo62b84lcnsNnxf@Suc}=s?)$+4HhO;~Zt_8N&jZZ_%q~b8JOxdldiML0 zuUN9@B3BGxm_yzs z=SA9F2!E2D(cfP6y{7egxELu@zyvr~TU+ZKK#T;rf*M-=|IvjKW%a+&%a8Z+^Ye@N zi+z%1J=O4c7l^iGhrB1%6?Md|DU}q4{|yaKe}81O?8mCgiZ2Xh z1NxmkD^W|4%m>Cvr@bE?7%)Pu}xXXaP5L%u?W<$7l+X^nqVnm!2g-9bNPj z{D&g@aC)2G!Na7vqs6D8-Mn1)_~XTQzw#lBnc+%`7VVpS%=SZ*9A8`5L@mSGSFd%) zAdRWG?K)bKZ_2i^fU?CjhvY(-o1+C=if%Z(M^rpe{@v+P!`J?>deX3eo+>oSnPy@2 zQ(dkk!y-dAJ+o*fF+=6lB2`x?!nz2OT<*sqX9!T5JZ|RYeXKZxaEJyvj{&eMck#sf zPw#}RHGX+#d&9y#%p8z3nKuVpOD+Bvu+p*FwAc2Y^pG4ilW_ckuj=yt9?(ATmqrG_<0&k1blY&@ zyt*H1x7H~4R3EI_|4__|xVuWC+&$-V+D)x+f+^#+#Xk?JHD~QcX1Y3-IDm(LJLht6 zn2OJ11^pajWH}nKw|j52>`xw+5Z04)Y3KVqh)9Y*8}r#c*74f9Bl%sN z_cvC%{nT^3NXFa2B1hL_WQCjn;w|aiVy$*Ub%uktL{!B5vxj}<*bO?Pf~1KXqW zyjl(@xxU@egB9JIwTS?M8Yf*rPRdZ}PC7y*}2M1Idj#G=#U+*%L5jASk-h(7sVR z|JnO45u?-+k*6H9tK1c}~pTFP}=Uz7uQrH=nY8$Q1ZiJd?-P zP_wo+@{xXX-4~z!`?>a@!|@CL>>%Enpz@R#>6mS7D`$h8Y;fP-Xo*wVhTvoUiHjeG5TCM#W0;~F0 z-j-ahCqcM01x{-mIa7WR88+DM-85t(1#U6;g8-A$>p>Qj^jnO7`?ZH-8`%8@;FuCL zaesUPZ85I~dE3Bmb+pG@b~`Z{-qW*+2qm!9`1R+mZJHS0Q8g*nM5Q|LbP4Cf&o1*c zlN%bMK5liF<%tXi=XAjeKN5@!d;M?^;v%@3qYpmd9;mpuVbT^3m)3(-c^gDsABi|v zzP7rp0)}`bf98)i=y}x(TU)CX3iH|m9Mmlaso$0N2et|zYTah(3PyCXR#V119^8Qj zD|UR&ILs5Rvn*%LpoG_rZ-Q`H)=)EabDqqlHRoY~jR zVHjcPTO;3;+e#J_SF0! z+BBT>y1x0?cNh5jk&N@UuVP2wOp*Fo@Js`=UwM;t{M*({YH7#Ul`DOqanI_4WMr;F z3>jhFVp4D0(a^_&INQcsb)lQ<7v34|tO9t&(VgwZx3lzlmd3tp$YeRHhgS1LK_L0b z2a%5T%vD2DPxUedGgj7)j&}qNG|?l>G&cs@Zcup=PM2#}uJ;u`+O?pnNPVKXO7>J| zR4X*l%R?P@d-&)%R7tD!nq%Eg7xy3A|7S#2Qg%c5Vb30$=n6hwgy|{yT=NqvFbmrL zO-u(*A?L_$_hC_jt2b-FcUm>C&jI|J zb)!%1%m4tIB^1i2M4G8wnH&-Z20i}##33UAA}p&<`V}&zCEE#KSaWHZlq~r!SgV8G z3N@_SBz?JtMb@U|a-_wm&gWJf*YA<3tKIz5#a{M6sm@x*1Brv*Em<;r^f#Gb+S~x2 zsD%;~-bc409}b^{x{|xv(T)cNO2L?Zi4dEci`$B<-of+mmI5tV!57v5NuSwj2R+}$ z^t~to5@-m%BT&wB)kUj(F}j*V4832~Q10U!*H@Ps_p4>{Jv`Le%2zO@_C(e!NTt zwN~i_zIkNwkF}Y^QugRSzGXM}Z%EV&`=oS+LbK99;zxSfuT8&HtpxwX=}LVv0IeiV zmxnLY<&*$2O6yZuq2~By^1wYMLcpjU-zkwpE_M6aZ1)8y14_7PQb|1^k_5?XC=AO>+Uw|2$2?_v zV~z55Mc%`Nv5y=q27Op1--uVvxTsd7)W({sID8wwAHho>Z`+ea_S#K81HA;SgYngn ztG8nIAV*A1{YmnS@1=+O<`_nKurPVBDU41W{ZS%?%q(N6HIt7p(WHwAfhV{* z^_V`Qky^^V2v>a}y0uQqC9@T}y2&M9w-*QO0g7-lWLH<>8FGnJz^FmwCv=m%`7|eM zuS@LD)O@eFWus^m?{_@Rjpo@_2J8c`9ISbcTphmj3~7=e{a!l^co(aNt>`D$1Dlmdi|Hj#jL< zSH8WNJtP9K81JODOt6-0@*h=^12hv+xv+Ox}6Db4r zr#2aX9pzYr5N56W*6vfVMV8T#zg_qL*y9y?pd_30OZYr#Tpo5|`oOwXcUQFk`%D#8 zc%?sbyjh07He3Q89^p0oSE}@m&n*;va`;Sr6Ul%@%&)a}rWbqSJ4|kjPIpQXVl*0k zpm<*ucIkFx!!e@xX`sBB056XCw;xv`%4q6j*YqN+{#iXpfnA6@72PHV)>bm&d!ptsyf^vb$Rr@gO=g}hFv`~S<4BkBC4#+g(C3* zOlS_tQR%ecXPd`#Ust`7jzsPF+DwR?lF5o4h?F_u6-ySAaVbmY#K?wLM@8aGZTh3g zlzv$xgO#Di8V$hLr#h~7-Nu{YQ*#n{VM{BhurKf5=LEdU8_)0U9lxz%`o~y}{lqge zQ_*0y?wquhZ5=F1q~&!kqPe#L)t#Esg`uU8ITNNHM5jF<=%rNt@%|<4=|5!hpzDfO zF)@JNZEkJ>pP)xmR|SN4|1)nxn?{rGp&V83a83LfXJFS$`}EbKn{G$vk8wpZ)6ZBu zyVdDF39YArp4iGbBOl3GaGv?&*q=*Ic+Cduxnir;tA7r4&qUI#mknM09S|SHlF&)` zU5)q0lKEa~UTAOF&-edlld(YsLZx&`Dqxm-Q-iXLz%5eSF~VE;Zpk#p@;7U>LKuno zR`UK-_R$b>n@~8FAYy2>@sJWILgEdEy`!HBzMj~T3@v!H5hv?eDR&#rW{oY=^#ca4eQ*je3LbKpsn)zGQ;TSG3QGDz$31y8Tud<3?K8{6OrqFW>}r2B_LMEXG6Tl8 zcrh}&m=^IoZ4NoJCY?A&3CMBK?62pMKp=NkRikJn#0(EfB-^|o>E=IAz8A%vPxoW zixXO62}GBja2mjaAw)1xjH@rU?EQOrb=4Hm8by22W-9h;PewE9!{^4UBE>g=Cs2Pl zp~l)p_#W?7sbYA!*#A%Nu+1xfPuGHHmjV8uO~Yp1)=9JF{gDsTldE8r(C@s30_qSH z$!o~blfN!l3pbaS(`sy`3KK{X0O|+paD4QUJWT&}TgUgM3qmFQP9K#>|0BiAy0ACj zU;62p_e1BsRuhDUNnT9j^ms||4O`Eaarv_pk`)0%DLvI7&I?@i&?Z*yNj2|$Mqk_b z4&->0Da%`@DEwg`Ws@$E05Oy#m&cdI-HmcQgRFwby)|W>b|d8w=<~9~L%1e55Cd0f zAT3OnV2|4#J_X?N267f`8E&?tMCAKRzcS-%U$G72Q{!=%-iW)uc3oo2n2@E;aP>%y z0Rs8Q8<$#LH?0J$8cd8#oqC=VsZYneDh=g6o9I4%uwU`iddkR!Nn6P@WKmZ}>T_8_ zJXqVfuOLMIq)g4MqbNd8Jw14yI65rHRx3H3>0Dv0QJ%~;`8beTCIAj_ zM6Q%eV`52Q=9mi+jxdKE)Z0%R2SUOd<0mZdgJn{>|eb*;x?9gZ4nh8-d}Dov*ZO zsSbNnBV#BhYjEfs;!52e87p%EH1&hn!oID@IiV9VL!&SvJ~HSrA2p#>KAD10ng4(j zZS=+(6(_R6(9!~vhnHo3m0mVb_A7C#UwT)dlU&)^)#qR(4jo?tm;^5sLlz%9__f^6YW)y_Ve2&xKgaDtq#A+7(*Ppfu{dw-v*X=esSqJfoV8q#iQkk9J5Rw=SG0St5!QMPWuxk z&mIrA0OwbG%`m@SQErmEFa?XgxVTRq_j`ig{=6iNMteXqEvLRFEEhx1pC`Hz+#q#3 zGcaMxcI~Nyzri&nh9ar4<;y$wBB#PfO047CJCuW|tk}8QjPKQt!3}Nh9YTd%e5{%M|xWBa5l+CF4sQjHw(+ zGR*JH(0;@0m1R*YpR;3(1mIlD`VJ<^u7)bH+m7$A&T}zLbE1(1-u@Kl;rD#-3KKfT zbvh`)k$6`PrORsl+kNosAYqs9aJt=6z+uJQ=yv?0f{z6c1HY-G-47*%F#24|C}p->G2n-48btJ04Gl_lK#p7ohTo^V&-l?Wm6i|29o* zjaU}W#2_oV9+@+^YOEVZ)6*wmD1b)c3E@jQQ>qCp|I*c*HT!2&aO%0m`X1Ty->B%r zgdin+!G8Y!{${)x?M4vBPE27yrCCzX0iPTd(SOsrqx7nmMj-&psD5Xd55-Y!#pQOmyvsH{ke3hN|1TGS;mv0(H*u@8$EBv`kELm~9+>-8@KQxj5IVdk{CK{$ zV1?OAur7FOidz$!vxVDIT1%^kEAT$1{8z>5&-)kyXf48K z2YpZXln-KmUQ zcspL5gzS{1-=0LqZO~J8I?klqohXz(mFzLJZIxDd=F^O~^$A72Rz`tlR}{=YS>*6ZlQgr0dx)GlQu^@>Pd;Jvp4VGKi_XIB-T$}nAmv)9CB zXwn;Ogw2O+YOYpoa_a<`nBP!Ot=YhP!1PV=uQ!Jr55~;`o#DU7P`tk^KhiGYSKRIF zH%sq!KEoKMy&{)oOU+jNxDs{n7JlOnfvK*4Jat$xa-#q$mxhQhX07m$49NR+BD~oN zXR;Osi6iHvJ!6uf5~T}0Np3z1r1hQ3EURe*1V7Fl)HBp`G^8?{>T|$z>WZ`pb0jo9 zy?}q8e2fR2Jm&)@$`DNg+oDWw6yCEX*Gdkd$=Q+_x2YiL#ql!g%gVd(k!GFOYWFkY(P4hmxLLinOIk%`7gDf*F+vfEU z^<_WTvtvV{qf4L%@1;Dc?^IJ3RbU{8W5%n&mCOC1=}f^79krBzYN#mB#jO``_K`{G zjjnKTINopu^$^Kx=?e#DgnVQF!utAYVq~P^@MeF^51pH$!aVjm2<;K~O$b9ePL5aC z3|se1UvMJn5rPNLmdx<&T%=5el>e|k4a~F=j??Q|?44B5(LSA9ZQVAUNB=_Pv(B)B zcg{yBppUc?Zx<7e&vQa4#j@J-XVauKvjp9Jl-g)@Y}WxTA?F#|&Ma)=T*eQbX!^*} znbGnvB`4tba%;nyJo39go0$iajhUTPNCHl2(Y0q@@{$H;#*^Z&Q-mv~i>e;{m7mNZOHPx^K3 zx31Da;O|8Ld8WaGE1$3e#N1e%aQk^Ojt$C=>g8{)kmeE&^B3?R3mz&G7T+?EPzJ&A zJ^LVyTM8cYyP*mspUl&TZqr*{9`T1H8_1iidBiSyK#_sjKjuo`ednDtouMe*SA#Il zW5jK8o~>}~MXJ88)k_w(!>iQXomOV@qye}pukNT(W2hhXsLd}-9IsG?7 zizVq5_o|ABh%`VmBIX?ce*oreFX!VWw_wpg_?mm?9*S`VRQeQG6Aam-+TS{wHwQpdTcR~m&DW) zY?e|mIm$`d`1@dLmc7eEPh?@@weHW6m$lpz*U;%{e9{g?L|C>5O$8qqktibW$U5SS{9B>0d0{W?> zK@!+*vI#Nwy1_*+RJoXxHG`G+99G>Aa-rmTlzp@_;pDVS8BB$Hhn7o5wc!B3rZx_W zYS!`--taFJ$<@koWlApU(4={F_M{Fx0&DR5*OhBX@c}t75`?J%%|!_*vFyo?^e7TZ z&i5l?nRBAL*z{*cG0$7t{~AJ7PN6{oLW`jOsqty<%kLotxw+`E*>6^eMmCIApB4{h z&tK~vlds;7`r?Wq#4mN?eO|~l84W!7oqiQ?e<2|F!#Qg2!NX(Dha7?${$vP7%Ev1U z#umk}jldTD8ATBhLE(<=^B%e2W1bdvEfj@D#%xlQ4B`hd)Z@-`zzgMf!jF+ZC;Nam zf;YA8bAXBK3;Tl!pG~tYx`|Z6bTId$H^0)F=qt{e!@EoiVWnp8URW(O+Cn8-serb~ z2j5TiadrN(oTHkbzBI9&Ua?KAX6OeOeiyyIMx4LB?CIYi=?-jj#RpTk@C?U$IQuVF z13j((_<(UecBty&J7V6HjO1K5yM=Wz=$lc#GzS2tY22*VTS$4(z-e})lD;hX=@L@` zSxt@h1*3OvM;v!NyGs6_36FiW?;jaa?8rpVueuWoQOf_7w2DZ|cS$Tf3G()$d(>yQ zWB17Ru5_WLpg45yfMtMs1m9iB`#wqQ65M5t9pth~J01>ut-lQ7q7{*uEP2Fz$jJB% z;Db(kw|X;6mg&_h{*k(qb$oXFz2+db<95K-jea zy_%WoSrVutG8GpL#WI%wnpJ5-%deejwSVwS_*-aR zhe~RsIJT1yTic!JUUN3p%eO*?NzWCy4qZGtvsd2CY2=VDQ9d{=^@<@5E5e zmRs{}u2~I#p&3~yymRzgyfsu>;XZ%Cm*44wkO0VZq%hrREZ*PDeGe*)M8wX|qW{*aixC<`E33Z#vy z zzK>xXphkr^*Wc<8JgSY;u1_uENpzm6WligZM8#*}}h$?Ec>JZ?Q>&9U6b z@G0(qYO=*d2h!FlDSk@@ZbwwHEkFzEa=6dpdoKvy{Khvep-$M*hjswXqNZGIdT}bF zb|*V>;D7Dcd7Lp}dfuWVlx{U}6>11a7hRNq9L0N_`MO+tV3v>$6kW*V|Fj(zoC-sv zIo!{jNu=9U5K8pll{%^+c_2@W}~^ZBXR)VY!yeu z;%|ZbStRL>Ak+Z?)}SQ$dq@o6=-N`uc~y5*KJff9MD1g*JBP_b&6`b z>T{>_e5uHJ!IhI9Fpxcm3@TjzRrzd+BD8k@6&#MdLYyi2#r(c(cA$m#D_^UXg@u;P zIL*|^uFS1c)~Te*{)FK5AiyS4DJ%j^WS`TeJ;9~=SBA4+z~N?gN2Ft4fsLnPOwv*b-r)2L|8cWqRg8QhZe)L2y2@9I8=8t zbboM701~3<4~cn#kc_Kko~4Jdz$*e1Yv*4aKhcl{mur1{=-bmqh1vUq{cLX0@%9+J z)9*3s{>1M8bjy`<hY z@$*=&Y+Dia-3vfx_K&FP679oo^Eucf0=eOWbQn};kphIRb-HYKLebXDOig9lALpUH z`fQUc4{zx_*ev$JYZy~T=;o5e*$}2WXG@7Y9THI#N_)JCXU2m*t^eM#4UX3?kqA$Omg`lXyaUNZFv6)}>Es!)nR z+NBHs5UGSTb=XN|+{R%MIlK9K`bI}WVvH=jJL!UWGjUkjw03)ZIXEXd#c}oCVX|gU z*vw3U(CblW;QS#ZAOYoCZ8!3+T!EU5L&quLYJ7HUlx|2^;guQxR)P{&@Qy0CdSx>H zJ1m;rO9m~FxF22G*0^aq8mFT1hz!0JzNz*&7pt&{^xI3NvX06rblbcO{kL9hC1O5_ ziJU5?Z0-~cviG0-UGd6u?pO#4Z67mOH6;>*MYxEzB$#ak>2=^}az9!xqq#7VM@9ce zNx(vj$5W5|oT`uM!EAE1I{%Hh3fYYxEpHPv_h7pK{e@jEa--#^*>m~y!Mj5ZiLqFh zD!n5kD`A&_SQ;+oFr%)VIFGmcd8az3Z+j&QFPXevsiOFe|4Af`bIG^yD;vWR^ zGL&uKC-<(<7ZY{nPrQ861Pa)aE9Nb>%cXoTXFd>mW^LKcJ#`-*>6ZvkdPg5Lbh>$Z z&(NaSZF?yxYcTRHGQIi((M~ig#2Sf8e!ksCt*g!j7fIns-K~xHHwq%0zHuov#~gNT zP)492{CX+ex+)LA0u1u%f==N%UdG+eJOzK0i)vWj{izu!G{^D|x+%vlmmzSjnCkJM z-M;qsDOa~2t?>Hgsb`M3;mLLQP5g}!Xeh8@dC>#Yr)do2{vV1+O23ZBnxCVVdx1Z6tBkDhzF8M6&i z!UR?;EuKC*zC%w` zZGYI_^ESs_mNR!|;8qst$Wk<(q~PlRo*Jh&+OXe5JUe^s1mY7opqQ$N&}V~3BmO8T z2tLD$A)e*v=^wvyUE_8h1-K2JN2BvlvL?D#5N+DW26RV9j3hU?pX+9D*|=Mm2Jb4+ zBt|ycEMel{m^HUlXjGUt`$a)~ElCqX*|nM}7}Tkm%obR(?}QeophPTlaz~$A?(~U_ ziG|Day1A*zt=4NURQSf2^fJA+OhE|!iQa!k=SI_8e>jYFi*-@E?6AJ6{+o^4@mhIR zRpqiS9`N3#L`NyrZbJQrkRyews2fSgbF=RT6aQ!ZMWq*f7EHQ;hkY3!Ga^ENBa5Xo zVvn8AYx~e=Gs^SH`z<2yO5oE$F)i9J#)X9-WML_C(%Fp5)7&g*-a8>=t?1a>t{hv=f zCSqhX6OT!*Zhs~+$hV%-t0 zuaI+OEiL+hvA?x+DVD;n7a4K#He(bW?;M*w@Oz4eKQk-a=Eu&caSgQwcZz?&hb`@G!zv3;h3fW%$KSvD+ehmOm%sX>0r1M z@%I*mg}%P;9NmPnIXhKY)qVJyZ!0lFinLa9+9@cU-PHbjcp(B!;&DOZivF$g@h*hy zqL2eAB47xpmHgWVDX(L<6E%rPL!+$*BS!R273Sxr6}LAnBI;~Oi9g@6&PYCw;%mFO zj5OvLz3Ve|?i-w3u_yRSDH5I~NMs>p4os8yqnj{Zr^vW`yb;~h=vzBgN<{%doP>pQ zi~?S8q6WWI?xXhid;+`~=w@Aa%H{lkbW7Ixc5lc%+D;O3jNJ(l_GkTxow+H$7g@#5 zCjY7QZwmY6g23*4SV%spA8kUd5`(R&(2^5dL&oorG8|KLvoH0oyL}qiS*=Tsi z(wLSadn!X5lI?OHf#EEq4%T+W7vBV<`D5KuBnL27cD0{(=nN|!smF6IgTvV&=A=H@ z-^aE{3f5s@<{oC!;)ca*iR{6+x!p!QMLt>r83h=CNq2I?> zO<6|KX`!3NI=&(dqQe4^&a0mjD^E*AlXU!?|S7pWryYa6bzb?!s z(q1`lc}!wnV=c@NX3GrNMHJo$4&jA&TT5YaeIK|v@PNIPm0n zl5?AT<7V)e9gk>Xac$v41R@-dt?9PH8AGSPcGI+KL=vSMDK00r@K_8V;NN4o9_UQ2 z0PwJI_m(PHp1aa}Gk(5Z4%z8|pI*LcR&6MK*>@M@y~prgydFww$Y!Mhe|N|YBhC;B z2^A2u6mWhQQnS{tMFudv>iXCgmpw9#n~b#C0)}n!zkw#3c#gpmWj=lzk-4zkp27i8 zMn!Zk$JUyTRe)Da1>>4)q6unA42Epfn&w>lU|L>1*rUp0cUuiHv`2PER&_dfUIe%; zzRz6+y?v^*(QuzigJ=VP?U-)H1vH5>`9Eqb@_0sDw1u10UF-C0QA7~9sq@?)bk6rTJ!Pxj? zobXfW*u%dOpiVj@es_h~Vho%Uv$z*ymT8j8-^~R&^lOt@LLU-)o9^qbwR|F1F;o#ZN#LMZy)7rqI zcDD#V?c(JfaI#FXFPOH~M^tFjzm%m5auS@t3lEv7V~hhBn%H__K>8e)&bnzORg%J$ zekD&z@^oJ!s^TUHh#}|6F2thc-GMdkTcG_wMw#rl6|+~BEbe*rDD71sg>co~H90d~ z9ew64V#Qc;Ilb&P|LXp!F-HB~4@3;KBN&>G{FSZ(LY6{18qi{X=J3C@96AR_5xdo+Bd34(4{o zmbtp>aa(;LVE4EOi5^>_9fX_mLd%VTZ?1PxGZ}l`%Z(FC`oR=f zI#_o7ktE1;J#iZsD-D=b zi)(kc)1!G7q&C~|VzpvY{yTpFPh|7j42Ol(459S6Bf~+7+9fn~;~tI!i)klNq*Vk0 zRw$j;{Gyvc-|mm;njC9i8p;_ln%Bjun$dQRIPk}F)jVy6vpeqW^{iW=lb`4AVtBMO z-O)jum9gP^+&sT+C6SwN#A{z2FwZNL7(92KNLXvudmm1r%cnudhxnU~dBgZiod8Ac zQ9%rO*O<2NosR-gB7q;nl>K9&tAxnOBlU9hlrQHJTMlXPY?nxi?`&?Ci7Y|W0SiZ6MCx|5S-rJ{$HK^# zrkj?K)j9g_`vz_Qf3yF9Xumwv7}B?xbJ~ldzOB<`_e0*NYH-ZCtl#B&YY^&E^KQBv z_x*%tDw&>e->Tl}9x^QGbn^CV#q!Ig5Y%@xzc5+!-~C$q!IBaHwJgl8P^83vlcTe) z4z<|d3613s#O8$QXK!~VhCb&+_wYRXaC@*iqXd7jQ${=>xp2?uZc~aQq1(-FRq|!>A95zYwA##>)i>1mwgZP8h#1v?_2*rS zYE{A3XkoGF3E;i&<=7hdr!xsN#hlD2*T@+C`VWHti>|MLs;cYSMG=q|kuGT|DJf|| zLQ=ZByE~*C1f)ws>F(|>={WQO4&8OgyTSMU{_h|6-Zh4YF^*^Nz4nSZpXZr#twl|Z zOx0#%*8@kL$^d7coT_0%?w85~3kvbOwbw%|U0mr7md8-Y@m6r!9?cB?;lBB2`pgPS z&u_^o5|xK~TUW!&t6dPDlKuY;GR!#1GUg} zVO40}kiYGk2=U5VO}zR7{gv6sTJ2Wao@XIJ+|tM97SRYuf6a51JlX2!>5q>0O+F{3 z$LJf}JYv{KM6re|$^4s+kIGb)^$=us_zJ)igbijNX*c(8|1Y+Tqc%$@=EpuPes@k3 zcu6n>Lf}5?m*7QYPdPd%4R)@qosBow!KKb!$3iJ}7Ab*#YQ-3m=4`B6+t~>%EJT+6 zoT^E#PkxB%ku=!|DO_$VCAy9C2X0*9*Fvl)623=>UF6Sc*)1^)9Nb$W;EbTf9=q<<3u(o!ar!a<0e)lRR{ylh9&H=M>hg-0(XSx;3An}qE&qBlqKu?rlLWl8f`ce)0Z({o?ZI}1 zUmU_EPQQN|IUHgS@A&aH)vAjVm|AsNku1cG+@S z`>(27Ltawbl-RNoHOuJi&!)O*!KvF9Uc!)g&HM6`G$y^(=I{6@rFXwGm9vaN~ zb75iOb;9wJFiKMlJA(f@>x07*fa&!l!*CecKRO>+9CE%#C(j62ZVx<~_8C&%h8sYX~E6k6sY*TlC4$k*vB=!w_(p=C9XZuWi_E_7oXV~7 z{bE3|n~>|bKW(p^1aXpQ6}=g^NCyZkR;R}y1)%P@ovA|b!GTuMMzInddrCwaw=+OH9e2)w^WnytTu)gf zvXp=*x#YzoC$g&#@b~{ys?86xIg%z}VX>!LDt=saRu`#ATn%&NlI56R1MC9oRsQ8b zOv32dF*k>ykG1-876oyxxb@O+rGxGKRQAb#6Clu{>~P zE31$P#+Y0fDvc&jMv0R*ZEFW%88NwJaxY?I5xjm$r9V$hJwA~?Q4lU6>Xu5^3jgwi zsl-%i2P>*J{Tc*-vnXfasofED&^K3zn~qFhAGVGsA=5k> z!3W=g%SVSEoXt%10jm(fOnml}rHbAcPl;OKOHIvKK;k*@uO{dz+z&i1Xx9ISjQ;%- zZ3mv0{P}cwDmgE2+Sb-qr4}m+I40_8+N=*$1k9BYDp)H4#)JFI-ygzgX=#11ULx#d zlBN_xCc$CD8qscaD(3CPe!M3Q>u=l$Z-DmAz(-s&JXTQ7Ka5faU{Js@cHF{`KZ&;6 zwTsH91^y>~684E+K2A~LfruD|tKf);X5VNHz683FA)3NxFGnSG1O^%gE2LoT!|~MV z7T>-DF6*uao_(x}VEEUW8lft7d`u5;^~1gQ<8lLqZm!=E>h zo+>1qBiYr{^HEYxp#-faSmcRF50D}>QCWSj@MMp2E|#*1qxBD*gw&L4mvQm6I;aow z^;}bqQK&Q8Cz6pVe~YdOv!=dS2~0+})tAGPJnN0q? zg-0hI0w^dRi@{5wpvTQ*GwIc;`j%FKBaVWDXCruf1lc|*qNxC_8V{zFt*kws>&p#3 zd>}7Z5f$L3WayyO8Y1d3+KZ4zTQa3sI zgJ^I4SSqKN|FHE%mKPSIB*cQ8jsZ^{NqMzXasw~IaT(RAKX_h$FY1Bb((k(I6R6_Il_DZVl*v^T#Z&}$ z3^~_+ujO)U`RyxX%oiMopN?EXOns6P9fZ>{WubyE(xA*H>)+F3WQ6x+Y2o3v?PY{Z zTzTEj+L%zV=~ZCfP{>#}?z5u^aU49oiAE^K@8w~@wbT)oAQbfThqiS3LLItv(le@K zG(%i-jW_r8m-@;xL~p0`b6#>U z^sS7VqO+XMgf85yxi>jj!|q2O2}x53;Y(CtL=j-?7hvgI> z@0wn>0n;>wnAa^edGZtpg*}z^`4t;pS!U>%#e%o$(h=)#>G~*wjH3RZ#@f1T->9xE zZUQ-!oOH%X(8u}uUT`c4yn%_UGaf+J8KgQs@_M~HN#O)Vi=4%mzYCWlpxI5j(?WxV zEJ{q^OUr_#ui30SJEV>scD2TiD~8GJ6bBb;zmML#^TH-fw$Ih1{Ll{>a=j<=%^(pz z#c#aY$!wfEU45QzvSTlTr_CxDL9!A@P5a7G-_Xu^WHsL%KBmTo^ucsX>TYS2bqp$! z?4J~(dPOF5O$3SkH9FSQy4TAAm?TCd_pAa4AVdJrs8|vq?7_L!z6w#^5EjK|1R?er z6+vQzZ?6%ke+EUY#g`dCP#WTq2?B6T?(&s`-ig!qUc~C>aE!e3QRRGeF8!{Iy`S)3 zdmRLLk;mS(dJUNa3ykkqelO^xzNO>xOSLcYnUf}5&%l&$*@tHoNp-6xyUVT^T=@xT z8lz&%BjJdQG0dCh2SuwW>^KWecUuqhjXaCFwAdfzwpVHw%1!9Vv*uSkcl5{nWzr57 zv?1#ge*{qu*wd7!g;^`c&J_-Amh%ZDIuKA-OKRaO*AA&oCpxnC(B=N=zX77wH!o+s zowCk8Ma2mKUSD*>1yO-KXvl(^XMte_(D2bZUFseX7S4N#>)2k_>i3EbFt=?xyk@h8 z;GmGS#3CdxfbW=;V-omAW*F03O=D%=DtfrF+Jk2nNb<)X041A+|Tzg-gDE#v{M z<(UkoPKl&}kadg9d-{6wp5Y0Cii-Z$*&azMN$hufS!StTF9CF^^-ujq)>2S(nY$%^ z-n%AUl(s&WqY_+Xlm6Y{FVvjgq{m#qx#qwT*G3Z z{?zh2yz)Z2QU1x7XovdC_d*mKZg%=n?&2A|VH-ge{StR1g9!)OQiIo5F&!7KrKd|3 zxOQvG$7@22C!HfMEcPs%6}IoS?^R+O)jof(-_R7{;fgBm9q;ewY1dx%Xy*`gwwK^_ zb|9t5(6lXBbOO)Lk6MfEx zzm}Ztd7<63aq4svIv$b$=)2-m9}FSldpPK^sN7#?*LHk=&W<#y?xOV^R&M%P!eJAT z`!dzvpN`}H&-i?LB)})tsBUZr-{0frdBwGj!eg7auO~f|hQh^myItFUov1&BB=nB~ z=KqaNg)__}%=ugNw5{e=Qq>$PCTK`fi*)*fc4Nab1ojECi4qblHV2$}_MfM(;XBDLGUtwBTePJCx#hDnS$<-yT{ zQmPKXdbjEi_aKS?JW#jfRCB)kfz-Env50F)^_+ zWgarSXFfhYSJ&6CF)(b$HYOuK4{%f)V)QC6IMM&x5|P^q&mDn%cYu>D=W8s@du;&1 z0UTWT$-&`6baeFR5oK;{TNJZFvdBZZeE_HYErc`qFU-``@PT8G+nG?@d&tRf#`3T_&QzwSO_5Mg5SC|L-X;C=b|kcDWmRzIdOvVXP9H)aMH6pN%FsQ&TgZId2D3L59v(wR;k zH|;lk4?{*L%Gd|qHT;g6&no7Qrwlghc-mN<6{vOZ2>GrpNYzS= zliHv4LKU0E&7MF>aD%L1Za2-Zz8GEf@5<& zt?nihVe8HIK+B=_dN$^wi<^zUhvYX$eq`<2V1H2hrVl*VtzuUTgA=d59kbb>likU0 z3T1Q>505+Mo9l@z3DF&ovH(wUr5(iqh{@OGG}i}kp>g~gs1c*rJGC=P-9FEIl#_T@ z9bH?VPrOm7++^fn5 zJa~_^aJ}UM&rzuIN9#1~p75*s6T8Ep;WZZ)q6b23+$aFB5(Nx{x=Xo|yld)^umj*AX5gj~S26c$eWN>Vr}@4J_dH9?rvxxSE^A|Z>V zBOEW(0(l>l`)dPSa-|nz4|5zz3(FZ9B@2KJ$- zolJe8#+cDozZKb8uS`$SU8-hd?0kivQ`ibJ&YYD z$8W)bQ-(KPxlk)>zCebsyF%|(6ES1r$PAC28((MbCMUjS>1csNWDW@Mjn zX-4JT98v?TwE@}kWuBu~Y-Bm^&U9$b|M=`)ce3ey5*7$u@4O{?q`5++&Ww6aV0yVw z)!;xV$c?5boh!^th$PFn)8>gR3n;Hxm>r{=q%X^_AOZ*w!Jv@GGE%+;qH8xxa_&ia`ulD%Sc#tgv;I z1zfd`<`VaZ?p$Vmd;80$OFim%r?Y7v8e5(*T=VwmTPh#jqkHQYfYSLCz4V~d3MeOY zwN@C+iw!oh(95txb>Wfd_86SQT;(YB`d|I14jv@Lp7s3asZkX>S<7iyxa?3ac&G3z z@m$ar;W2t6+Hc*&CX)|WhCPc@$sZLx5JU5%wl1Xhr0Feuuy9Y#CKe`Y5E&XAvmZu)c4|th!XLu6TwuvJUS~YT*MV@gY@!w48w?DDoYyUAJ@so53+F=#4kS$x z8GOlIeY)72Bi=t!G$Sil3u|5P!uGG&t$b%P>0|sV%hv?`(3<;*liDm|RxH&o;itM74XL4ef- zos&;!duL?Gn~xW{eav@dXR$|G)bCrcSl(&|^=#m9*`NleDw9RFToxvlssB zP1n^Pld|V;11H~owUqX+Z#)W`f}VgB(ShU=?WovpBHx&aorz2i8P&JrY-M(Ry>3O=qZy{aoA=(&r<+GT(n#b{;YLM2nwva--w^DNW+DPH@YpD`l;mi8-<|O*NRbE-w^~cfj~T04@dS;alhps zd9uEI{X!KP#}i?NAQY!Bc{$BuGK<} z*YkL)8g1Xo+3=oD{%Sgx+S2T!exi`6t1+^Y7klg!v+4S#Ax5n|W@C)S#iNl;4INyv z)oPR%BO3b-NQ-t1AbZ&d2YjoGNj9}rMQc*8_Q zAI?AAwx3}Qb+f`X8{Dt}uqWVxtm(%!Ivkh8eK# z^C7_m!)3A=iUct$5?;d7Dh{ZXj8}dOx0Kh{g&P-2Bj>QUIdig`M*ibvAF5BL;{St! z2K;GgX!>DPYAoP}yr}Y%jG84%ncz-%o4nzvOgP%2J-1i?TT!~v1y>+@ZNw)tvv)mp2x zG;-SIA`H}i*DWF#_?#kcHng2}q{U}8_lEEzgGN8xZZZSgo1xHdHTI$xgCll!WIbnx z4|b~h?3F!o4TTAF=*xU&_ z93eRz+6#65TB;q|O+<1iS43@C!nrTMUw6ye=mv&;s2EPNIX}tD(Z~MhZ9K5vbvx%) z=5ma@IlOCqQ*C%7e*;*0;1$wkQz8=OsQ7>u-un!&AcU-(uqP_eb)4_{7xMz%w;Axh ze;x7T=Nr(*yM7=?N-jMgp&%IcYbjfFq2GK(F!=9HqYI@HhmD>P{y>C0qJp=#w*@-^ zRV-pk3;pK-qRP4OVWZCFa^JMsDYW9H;&HL1UGvO(TKUjgC!?XHXXb(vyJt zUqo(%GNlaDt5!T##y#kXRVnAEST*!7kv`SphXm~@(5#Vt+v8yxLr5m3Q*t?wpf8`6?)tTP(P^(J+^z${}47D41Jb-XF&ba zs7{5Eq{5_%?O!U_zzFDdWFrAji5&h1UG+_o4>1LogW32c&e$z5BKB&$0rtmJ;Ql}N zdVHu|%zxAE$8V@LS^tSMJ~aiQqAQ)C`yUJVl;I^^;FUBmc6EPB1O(a@DyeGn-nj<>Aja;ibO3s&^3Jq~mh^k}O5~Ce<8>`m zx_TfzQjf|MWai|`k*O#}LRjfi5&@RT$m%6O0)8+F3`YPF|e>QckY{D+*rg;kDl``|C1@dY3#9=z>9Nahuh`nYuW*3+sam{mt2$_Sducy&GGj2&K>^jr!E}C_gs44n6ln+ z_j~iP^I9aa;Xn?S{{l;R5LwOX#So?gt|td-v()#Du4VpFqvWQ#mv>GcH;c`4_@IWc;%_3K%7$MbW6XT1quHO$uvOP45aW50b!r z^WX(QAA=eN`kpj*rwm*bApttvc(}i3aq&&z2Uj8&|KJAKy&`h z6KQ!B(~rI=K6=x0G_q#G;?w1Lc-r+to6{nZDXB=j z%F%E}If_-!CqfCGw_m^6ckcegX6crJm_T5fd3rQ?z}VYm+-Lhfpze@T2O{D73BmB}UYBQ5yXXVEcb>R$0&ft~K z5JhyAIfi+}vu}dq4KuDsb8m=URw)n8dHQ@IK_|a2J$jT+sNANbZrSo++n<$N++N!o zS&im`zD-x1^0oDFN$3n=5^8=3jNVN?I!-}fwckU(7aN5jdC0_ni@O_a)!BCRyV@Kv zQeYEW{Ij~(pijnsJC(L-#eX^%?-YL5!p(7$^wY^O&}zRssCDl*7&eZvVIzEa`Sds_ zrObc`JZf0TeBc?OPM)TNzOv*`nhih3ynsmV$RN)b1&*9S7%R`@rZQup_u{=AQtezE zw$8=>Cc_cPw-97>PnEYT^RVHWSVwX+lD-;9vZ3X|8y`>YjfrWr-0n@a|D?eM3ny zH2$V7VxPOrdz++71y!!5R9A8Fy>LJ}D|_DlyF#Op-}B#tw#JxJ|0FYPFLL_^&^dj_ zbR(}-(Cj36Fwltrja*kXy5?=Du^$X{xLF|VqF0d>MB)SvhcdAG5klUUn2#mgaQm;> zC80Gbgj+~=9dy>avC*dT*i&78@mCsMZ!4#eizK3`|AHIWEMw#<)uMogzOJ%|IL^rI z|E;@}C36*HvZ0=id^uzErV}4i_UeFBnX0Tz*k%nQ>$DJ4ZtUDZRRdz$2O=8&2eWkQ`)bk$(1vyDE0Kxo~EXYd{0WHGso&2xkfP; z(a(q?Ha$+pCV|?uT9MxR@^GZBzjDsyLr_e_&;Rk*-MXW~W>*J`-D)GX{@}v+xU!}z z`KV$H)P3AX3(i4FziQrLP$9dz8CeCYPh|+2fVwZ*nK@W~sgqyzfWf2!zd(548Cmd| z!F=;dKtKSl#M|aQ4W8YIw# zdT03Ck+Ur*_W^@I=T9 zIXjt=4;A84k{zsn5H2PBSFz`QjMO@1>Zkl(c!gope*8&F>t2B@GN|&X zw-q9G;>3f=J!qFI_>Dd&&WH8OOS&Sa{AC7=1U*kD3soEFov}%q{(|$Zk<#;{iKe6W@GRq+F?XSE(W|ceaf@6$$+i6LCM6P zbak;4vj64Fg=@d06a^n?!0aB$(d5YD-qPZ2^#-Yu^ufCimJbO8OwDMoohS6z^rRwIg{*|T$gxb+os^GqYG_J1 zp3anjq$&G@^>#vX?XJ#iT{nk0674(6CDW>5rd#_@4*`GYix}?8^?b%1d_1< z*D2TUTn9lZiUd=`Lb!13&kCbXu5Lan%*3DeBS)RoIilr`h`qg-m9KMIpWwMz7yU6k zDO&*+C-(g47ltiG`5JTLnN}%IAp%Jqi@cHjJf7k$q#S2XQ%mCf-r4nbEMiE7FGF%U zOg3TgVjoUnQbDfnc=^`+)Haoy!|zI8X7$rdtIJh>8ezfZ8dp=$KFLAv#6dL5TFm&W z0CUjJPF{(rD;+CW%0xVN#l@=fRZ)juZDwjyF^T-RO7B6!{jhmP{AvVIZ#gSftgKt2 zTH#I9KM@Q7jl%zyEtK`VZuBe#(k+}F=mfeY!T!HaU5Shl^rpXH*Tz2^2h&&cN7P824i8ZlZmc0Q@RA@s1ic#-PF z(3tM^4dNWX7Gck7f1wcbg*Fe({uK@v^tqQ^FCkycIiWO<7l!f!V|3}FEgLlzKCUgR zswe2uwzSpf7j9VI^w%4uwdoC*c&R}Y~8;XI$hA`ucixolK{-KBYQmEZoYrWq6 zacbQyJD<7>b!}>F$e?$&8lT1usx+_ed&nJ2Mz{0rH$yAqiEFQOqMnl0=n3OdooO2F zjiqzwkLpIk*ss)DT}Y!DoX+!vO1xFEf!NBqOb@%Qs};fCw&xwHLw$U}312O}Ed_2( zs5dTajSv>=5yJRe2Xvg<6^}?X^FzabU1M~6X*2DBO-<%7NBH+b+0MnDne#PI%NjVP zpJr$PGkjt9e9^>ySLZB5LUrNjg?s$4zMcOVPt=6TH46$#XUNU1cG>R(b}K%HSY-4D zv6P$7UM@GxlH#H5l4;^2z8~*3`7-dbi4r#zq;FIGxV2R}5ar33!@o442JoCr#n!Xb zV)t%QE}Vh1Sy;!Ni~gMD1(b3H8akI4tA<5jb}txn7yTn6!R9|*IB60KI-ySBeeCYuZ~U9_KY|ej9=m0k-MMT`NHbOV(fLJ6|bfK zxtTRmMY*sSmn{N|zcFdK!K^GB9CE_==dIiA^OF1Fehnqf&-%hV%q=%H_JriyoGo^v zVMRQ9q%3@qFYVpJK#9k(oOdbC_B(7r`8C-gQBLg5?8aVc+8MT})j{UWdf;HYGd+U; zG%N<5EQ|BL-rz!g<|3yggNI-L*^d~=7eJfGE=lNU#>c?GdpDnwjQ84pA>fwbp(CCk z0$9ayE-ig|wS8^Y8kYIG8e!`a>ICeiJ}TLT;27r|B5aP!>KOt>M=dn==y< zqXVNpzUuCpHpr;`jv?nkON(ePuzoGGJt;Mn@PO^Cetq2_D?6KpmNu)Q;p4(!G#ZeP z_nLrU@ah=c+5Dv3Jaxl%78>Mdpewu?Q&PIzi3SaCGASS+2!*kdlKKF9nX}k$O6qJW zWX%r?jn-N%e);st_c_b zO~wH%up5O+8OI;mcdUO0xMfYFW#jO|q)op)8(dSd`rEL$jVPvRY(Z-dj@dh7&wU zs5e&*1M-g~`pb%}h_XwI!ng{C+3DySK|sEKFbdIs^-Rt(7B+UEJEBk^NdEN!Wz}lo zC)CL_yh2Z!vNZ?Y;a*)003@M&c)S8W*m>DA0eB#>_TNw-&{2a!i-f>cf5s#y+Gr=I zb$0|XIFY9~(5HazT-AsHE`|AfDX(=QNg} zkwAGLQ(r^4=9bz5*_(le#O%JJ*%u!I@?1;aR3Bqu;B6}WmxjY4>_Y9-dTt>am&1#p z;*&fk_-8(YuwI?Xo}+fIguR7~?D-1H<@3iU2zRUk8@EkPO?}nSSon1lfzKAYwPhj_ zfj=cmhxu3^#F3#z6zZBH0aOcK0yIrTt;L$*Kr3SE&Kh?|rNZ6ro4nSKDLl$ZKt))1 ze_767eFWyoOe8fKnP1TJr+f`OCt!Ct0XsVu<8)V}+JlE7)=^mvjiOgiIVA?cM{s#I zIZsWjO#jZs*1|2)c-TGv9o$n;W@$g?QZD^6u%{76lEB z@F}wkIekk8^@BRUHAp%v=)(Kgd)1D;6zd*5qD3PTtJ+5Xgs1f2*FQ?l#s>xtF8Gj8 zvbCQ}0}q{RnmRzT027E=0@?e4xoC8<1Pm!b%RIPe*VWcUUEuv4#Hpr@`@zEl>sNX*zSAvqRQO<4 z@Z#!NQbyXy&5otACz8?)#O`!^9OYtWc3b--Tp{9!9>m))W@-`;Mt-+W(M3&lCeUPD znlVz}RRtF8u-rP}{^V=jf7KnA{&R+;=B$UZWzjXP&aRC1h$RDs5ER!#4))#LJwO2hL zL~>+gd3daW4Fg|xXz7k6Q^o8YKJ*lpRzPb&Y73%|jUe2R+o)J_!1q!Mm>eaKcH!I% zOh?AT1BWV0XNEu5G}DRT-5RQ`RXyA4X<^2L!|-wb;WUzr5$IS_;*r6n{gk}a@BJ+t zd_VgL20SeaE}QzjIY@r${%n?+DocSpc#y<}S#S7Ir>~8*dSy&t(&byg6bX5pT~+Rt z?0Jk`tZHaM4}%Dij&H4{RfhMY?!yr7p$Jy>XDVoXF5FR;{6*j8fokR;KkxiAo}fiG zSCMCG(x%ZuII}a=rQw8UTd4Gv1Vb=OSN66G^RFQ@klnIcNw9WOv7R{gyvd}r79n{c zPKSIs*1i}P1a{O}rP)H6^lp~#kkU>ZNHkAM1ZsCuy?aWZlwi(!_m|h89fM{4v5XaTfs_qaU#!{{Kb4TdCIxlRW3ZGY;z>= z#xz?LgJjh|7;&i4=J|*9;~mea3NLGnk)Q`j!IL*5DrrJ{xz-iO`^6qdrZi*n{Jn64 zILw(lmc%YclzcSBtIN)D9N_VM`{$=&r6F zjKg4ZuP&ZVWBxvVJM(66 z_wvLEvM59I9Qf@x)kP^dR^!a|!|A!P_x6{OjPJe8-kPGi`lsa_i-V>2C-5WSQOH`o zzUjj8yV}KssGFj~I;Rc7rqRWAeeQy{2k)@yB{u5$@8S`(=X%mRhk0Fy#0?B(D0$6Z z#7e95t)=GY;2Z9FG=9Ir%RTKbY-t-B=&jqGlgW!B8MW<=49G(?U{o3M#oGo>v^t&7 z@ER!`(%q=mHkzx`T)0b^nO)ZEF3J6I=dPH)hugZtRYOH;p-Cu>M)LxW8xf^9g1 zKS-@rRF;#GnY?@7^U*^E3$U<2Y0lv$HPePG^|3d6bmgBE00<)!2_QRIDIr~}X=h8;21B?}W{`y>IlH{Ot@90TGWBZdF2a$-B5ns6Mxhg2@P6TIU z%ND}zPG~lb=Yg_@`|$9>`EBoy*l+G;RQVWV;pq*(-yGpP1Nc&J;$X6@Z;BaN;T-?|Ib4}JuWcmp1BIUy49vKJSiuDw~ov7M>O z{W(7z&a1sjTth=nIr)(Ok&ES}tstoM({$2|-lj3sJT(Mn(Pu@&Jf!R6OO0B~%1naG z!Lofm)!cbt4Vu``pU-I9;*_=e)vcR93kkuJc%ET!EIPzKG>-4Y_;Ug^1j7FOTsVe6i$;af}_mrmASOAI)93yyP*7X(sr1pDTVlC ziiqHL8w%EqIv1^3D0T=)#C{0E(pP{#?9J~MhQWJ*jVF2m0taff`7R>XkO`=nSQ&( z?J9ae>P47##oOV}Q#am*cb)sh-?!?7v!d>iyj$*gD%6@j0UaWsfjvhJVPZal)pVjv znOPbM>z_I8)FzhVf#Yf3WkB-fiz4OWYs{*2f27+eYCgp-x!w?NkF#F>@v8;;{FijP z&rh&6=_iB7Ga#e7Zp9bbSIhez3W-fmCm#1fs-IX9N=k2h-E=68Bc)@e zwvvM-scQYTlXp!+*ZQ-VAl}7)t8vg~oo3HPYcbg?X6gNXcd;E90H|k>JNywq;8zlaBtLUcFN%<)DlWq#3>1F*|%6a zSlvR*4hapXB&~@VKQY5MGs`P1SkZBK9a2tpzL9Z!@7{RCHp8YT!qh{XSybWEknBcA zJ*=C5>YA=~iHC)%g>Q~lW_~G%&+X>B{}C-=D*Ah(K#ro&7{Xz>rFYQf*4eQSz|Lk) z%!nV^9txMwsU*?YuaeCdYG#|G5d8@XM%qx{ymu$5(rAnteP<-M-}-VWh94KdU__Ia z=8~G^T^=6r$UBqN+@Dt;qvkv^v`+aTtUQ>Ehg*nWU=A`i{Y$6-NQ-gR9}6?&*qT`^ zl_zBzZnVPk;Wc)V+K_r{OT40YMjs7MMh{J|*G{V@kWt8a3e`S2KRqBl9RSsVJLI9) z5yaEC8|FptOx_w!yJ{ToBPS6rJJ?0qk#rv4ChX6}iaUSPA9`aXs$2$1)VC4!(-J;4w9C9C&yw$nf?P=+8szI}82IeNS zeSs*BI5{%~E32#yX&tE@zSIQ7Yj$uwB;DM$=h%hE0#p+Lj^rL`9o{`(+vIWJGq&cPa)ci%$0+{d z%m56}a&r9;i)uz|O{{8>54O>0Z4#P}u#t%-^L)Z#*E{${eJWXL_XxqczXN-M6Tev! zRr0V+szrCzXo=O5WF$1~xD9RLlKsd49AMw8<2mDua=mUOl+L!DHR@TZiLRRHG9;#d za{(-;OEd@l5iwynw{v2z^^!>OxScF!BOj^nxID*_3pos+9~sD(VW^MygksU*@_X_8 zsR%fXk{^XnrlrYl;3{S9-KES$P)xT187b<&OglCyQ1Wb>GmVf*x#5}ZzIk!N>l_de zP^8&dGknfgTa2LN*iH3t+CZgC>{{|eIzw6e8-BrcgIhomV3HJ4SceB0TO|RpptR+h z)~YrISXy1-xT|C|nl5E%NNH+nDl94rTV}n?X8{7f<25ic(gU#@XLvf*;^>QXy&}5( zqPM0trH%hyPj9}}6@rpFR-Try0&ge$ngDdL794DPiA4C-wu=ZFk~gap^@oCmy=00V zR#}q1TC^WQlD5V7-Mu~A%7(%|}RyQ{0K3|P;?LyQhU4oY%z zztB)53lJ3mGRDW{Lc_w`-~3(bd=_+e<`5bh>T)(F3S``Ek9*3?%ZG%7kTNh7M=1dk z3^1}?9Dh-kf@&J4dTJS~XL>kN-&BMK`-`T)I6_Z0V2ZSw8-^q7?d-n&PLc`Ky=r|@ zZc*5`x3^*L*@55|Q2f5O&|%HO3H;9e0q8tRN=~(x%72g#FEqlrY|+djXC%DPjgl|e0S&_mK+b0r zsc6)X{jbStGa~u)%%_iWODh>f;I71nxw%+5nwDUYqSatl+v?WI-6yQso|#?_1gy5o zbrucA#TnyXbezXqh;qt&+|IEnecV*+pAz`J#J@~4%`bT@Xx~TubXX8IHDHJ9oMmWX znA5KI4D=B`R90v@v;rxhfQ%(C>3?gN?;o|x}TehSuAdzK8#gtOKJmpRQg${Y1^E(}IU zFkxm+)i1yD=4wq_?*gLoJzLr6qhRt+c^%WnUbz}?jZ0d);Rtd{5E^T-0`IyV_k~Y* zC>K1~=>(e@8p=DLA6`2E(fQZJf2D@MFWgnip>~Dl)n&10?a2+ z@Vc(`(9Ep2zPtoYvA0+a?u^7V(4QRa-X^FA45a|uarxiRL6K|UOjlFo zMLu;ajIdVzG#UQhKg*LBcB(hJ@t0Ka4ssDI@2{eg+4a^DpgaE$RbL$yRolHyqmyR8>|U+3N1$^V}*~E3H1>mqWDp;)*w>0N~*DddfcZNo}y=$9CXYrr~91#*eJ!*bO&3T78ePe{@~wqh{kE`?Lvx6}v($kI%-LBQ7HV?*b`^Oa@6W7L(A&Mn@8<9D&r$dSH!lfgVX{ zU;aHPB#tHFp+(@K~^h+Ao2Em$eJIubqR8191`>t(%sB^C=0u;Ys9DHmfy>v=7@9 zPoMDid{*QF7egLeWVyoa$AcI9X3OoHi8Dv$v?4+ZpWJqK3oOfLt!%AaJ>N9VLr=wS z>Drc*XQ4IE*zU9RowXedy;UgR$K#R*FlAn@v$~%PwGl${9cCJmi(YAuCjiQQ7vFBK z7)A&iUx18iOhb)k_wOY1xIvDZ7ZgM0I*n6`J;h?6P(*NbhA=6~0uZnUJD z9WTXZ^d?DUQw;fU`H0;&8`na%11~O-^}YNf0$Z_52eVu=)_goIJzM{;DMpOw_d~h; zskLjkvGC19(K-28IA~_3yPo+jZ}Srr9EE9tXi?7uB5lyNYjMkX+$uR|ecWh&J&}@B z0s!ttukC{zsBcH4$*xYl)gQLWh6L%z;0a>9F!>g*L`~;!*myJCsk;+}2iXqT3@`SG z7Qw5=F0&s6PERZwj1-B0OLc;$FWTCU>mHlm%I@f}-kpGcI9gGyi*&J(os{zf1yEDX zA-kw`j{8?>!l&c?R^Z)tePfCy6V4irn^zJK_f<>BOAFWaHf=FcV^v!B0ab-QSG?)u zUOY=eOxVciByL;!^S8tF?sZNy^l7)WrJACtF|0?MPw%%{AE!Mp*1kosjc*jVy|K05 zwr3b*aDc1gLUmg`2eaClu9VBUZ8b!Mr|`yqryfSA3EXwRS`2ox@gyZgWnDgDOY7qJ zra(PgJCFF&Gf}A5Aod z@)wW=I2Hx7fU&JoQJ_aY$SH7t$jGw{4_=$*16HtZ4*e2o>cb%Hjyk>d?r$jRg387q~It;SRyO|(7wyYwNUFT#K`k#~QuMzJ`I~+eQbgFuIh(4Fyzp2+hNr2WUvX@P7V(?rr5?v_IzC)uyY1AxDp2wNKjq)@YoB5J zPFh!a@mirVr^p%%UHDnYL~W|kea&mKH5=4{3 z4jI?%oIeu7>lhLy{}r;IC0RV@Zfn>SPSC$3Cev*TgQhd?>>%Hf2CtBHB#FNrsDq%r}!>NBn*3Nr(o0}a4dX38&>RD`n3vQfp+%Mz>>FGlT-3W$dKxye9UKx$r}Hc?m%B z7sOZfC5qum9g{9LgkGHZCRE`e*A}mpRD>lbj}F=Fp4P6=iSsUIg9i)wm zkLU5(UoFEAx2%F`y3svoxR_GYJ>yFUAMwpQ3~I@npMQ>bQ3{k6F0^60eMNeqZwn&( zBDN+I`RW{K8J6bAOMTezZLTk|!cI=I{efCmhV&aqCrIqQO>vG>TW>)Q|Cd!P`?$D| z8|J2Uz)KEPbRLdavV(G>?-_!;ln(7erCXL0iK$B5I3D&9?#|ypciZiszF!Q+sk>as3PO>? zpkwFc!E5p$Pt|viARU~@mj*D-_i-v}I&XDBxXylC3c;zd0EB}4N_3#;I(}Tu`*;5< z5&47fj>$rFIl(j4sT`*Qo^NTYhP1^KxQ-+bRttu`V$6phW8W_>z6T9bx`?`qMQP$Y zZ0^xWlcYj9PwmOvJ?L{m8#vA9aAkXE2*uW9yN68~Q>aB|R>f<}LzmY%V7s)d|8Yf( zj{ZjYmS%=Iet0)J0ht6vM5Ha6Pz=01=jaQyYrQRg+`@-Msl6Bsw>S$fnEYiG2*d*L zY9YN}XkuAgBX~4^9q%caa$4S4B|NSx%=6s`kf-q^P^ZmXPSEQGX|KuUU zx{@t6e3L&n+++ghsPor}B%*hVRC)4!o8NtC?bq~MJML)Ushu(T?jAmj->op`DJA#g zJ~Dqk<7mas4mjSL@6#VN{8T+AdXswN1b^ODFaIshmm8jV|&4j~Hp7G}klR!eMIP|Wd-7<1wR zK-_>wm)m6zAQwG%q@J^BK9+_-K}FR9I*%r4aJdbn@A@*%eyqQu{|qjZ zI=lDXmFP7W-#@?-ORamA$!CQDBm?Q3;AEBeWR3=&`sCTgFV;pL^gI_jbAJ~5_nq|F zvAvVbnQK%{o%v;lDfH9W&EsoCgsc(xc7?&0+5+JvX;3~45~e-%>`SH8QpevkPW7*# zxcwomC`zycGOM$wN?uclFO^`?OwnGVDE*&Azuw;GZM_ca@Tl5vD$w2>$`z*Vdc-ZL zVjTAy2ZHRFCd4Xtx}91NeC^%HGe;dF?cs2lsJ2`-?m=nvVmTm#ee~DEmq^|UDW6#^ z0mpQU?|)o<00)TOk^`)Y$jF>Ecy2DAP58Vwl{2^N9F;k&qoC#Wgoe8y7bFJopTQhi zwNlY2Z)9*WUuNrt36UO*T@OWhSlT}C%ku}PveP6{UDISL9oP5oJ-}-ex(drscq-0% zbf!qk_{@@aYppr0nuaH5v4LQ4x;MKb_Roy^A)GJ{PYTPYo14z@66c}Kxo1yIVc;UT zJfNioAd47`c>X7$_s_2wXll*0G`20;tf7{BulMlA=ljhTNdQ53Sy{Fi|B@FTurFp1 zNx&wq2JZCWS$p~6;THOV3R@{aph7AtFQtD`etKTVYzwHCY^O~(QEJ=P9oNLhR%{J? z))uN#_G%PFbp{z4j_e}Absr2qyvAJ?&+Y|Q`BFo&jyMMb3{A%E{|mj>;Y>4;f(lv+ z+u1!zP$uxx;nWC_a7p*-oN*y@wL)kr8W_v3C*Cl1ULRBe_R-UH~A2_w!wR`?OB}GnNUcNpNpa=p{d?8qa zvAk$Fs;Xn9eF5sr$qwuvADRh*`Ji_CcL{(kXLKNVa)qafhnP2GlPMH!nsq~9EX5C~ z!gZUDR322z)fkt4g?+E%;M|VQoEsa|!F{i{j;d0U9k*{j9? zgf!9$dZpj#!UBKKNkLf>bFU|+`uL`;CgUR_gb8R2NJGG7ACDm8c@#Vg<}sVqcT`HIp{;^LN%ef??q?bKD)?F`DjObPq2L?dwfVyz4xH%&jb! z9Qu8)vD6~9Fd~IVXXIuK41_xp`GU7aO1sK6lnh~l)Q#I5dl-7K)|)m5PAp!sRbQlN zk~+rP#QzJkNlJbKe1_Fm%3g5qo>SoxKM!h;c|@-f)?$?efm_d#>9~q7)*3J1#)lXc z9Ge&4PW07@ESMk8-FU_(#6w%zYlJ8*GutyKF00~yAdd7hFZMS&{m6RrgVN#sii?j* z2rK-=vZ&?rjy!+JC@+4ivTGT?z1>$NUJ@roEW}M4&>~eV0ncG;##_)wT?8kV%-z+>ib)F_hHsb;u>OCX$N+UoUdcSHp`fLt z?$at!1{jWeP=5-|s*5eYRTF>}pgK)2)@{2yM339&@Hha;Q*+=xS%eBogsn+r<&(FmgDuylm28h- zSGuM6*~4zMt+n{lT?_t&7WSq?=$7)k*&(>)p$o3pP~CqIGC*xP^^Zc9Vt?O2Yccz- z4e`=sxRPjxFYiPFpv}WEAj+mK$I_|$MMT8z6w|_LWr@pUAWx-T-|-~3*5Z6~;bvNDGy1E`trH$0LL05+0 zW?Ns_;r@epKkqym2f(DAHSFS;x@6uGI*fRS6*qZAFps z0%dn0hXvGb?H9=Ln3>H&`_z{{fveQCnRX0H&CA^jjAgaPrRdMKd$1zQ2Z0Fa((vZ% z+Hp|bs;k@ff#bscRKexDwaABq;FCiM(<~dGySYE~uoiu%_e+o3k|}ZNcz3_jQd2*G zK)AWNf-~RFa^vD~q{9i`nwXdb*D(Ri;MUf3fVcRdmDIzIM@p&yw3o`3KG*AKehO$~ z{OCybsXUudc%s>4SdzHEZDZ5dHi&9ILw^E#Y{Vq{$lwv2kc;=?vop+N7Z;=2;1vsv zi(ORJ5?}ENMY4s}#-VX_P`S^qoam^Tk1JPIUyRr;rT-Z)!CD}9fSz!VUI~o4Kq&x+H$^`|A0w|x9IceC3?HZMJJy$a&X>y#LdAG zv%bFWt(VqwWT=I=v9UqIZ|7TGU2VtqkDk^LaIrnEV;gYHMJwc6fn^lCkJ}%y2_Y&* z!8P!k;2v}II(-~$5fGTR;Tyq8DAla^`C<1BGc!Ua@N^Bg9#UhykB*KT$@RLZIY6kC z*208|+&qMFQtp`7E7*Y)(O23igjsuWL`@0VtCt;eCAI#bXYN2hvzx~^G4+tU@7VpB zG6ZdtS7HEsvB!!N-NNGSRm1(Aw)2I;l!HDFq(2S$d~iCzfq_Z_yMv0)`s-jLfsyJ@ z>)xK#WC`knySToa1p!io*O{y?ra2ddK#@ve|6fNTyu z3pnd=_NrF>dOJUf+(-U*j_kTZ^6C;9z*J}BigiZChg%*TKr=rmWP1^q7hUZv&bZG7 z7cgmJqAL=4&jOtTs#*Se6i&Gc7`Rmhx$p~*cOJI0JLwLnw8tp(0NSd5zsdg~Kikm7 zIYM_rdtzu`@~6cN7zC%8L#uKU_0`D(}KXIeZ4aD^cyVcI=_YF^{5z07t))Rh zqxo81ZTG=jf(88*ch42;a&f-#ky_^hB7z>5{F+KzktaIx5iX(4|DpeAB7Q6H0g{`3 zSWm0E0fCn{8o7_=+=%#QB#@>B3v3)8BWS-h(IbOFohr%B%=Fb@Yr&b@|J^f8&&3uc zF_u#vAOLt(Suc3LF2>E>0ST_xJE>i0ltGZ0LKv(0dQ3A&G#hxkm8_&iNU$jSfH`TO z`3#+Q+Sa=JBad+A+LhmVI> zn>0K>6@Q+F_&ZH^X$)mu8GgQHP#?yxrfH4qcijv5In+`>eW7tdByhLMgC5pspGA!7 zzGq-zp6-paryNiOfqRn|0ql$)AASCI<=n!FU?f6*G9ZqpCp}iBjQb&P=h}I?cQ@YV zFEZlC_+_;yJ1;i7iytvgw2$!EiM1+E)MaG-%!jp6ImNHGsvx-%-YKTw44XM%6Fn;R&y=VdOR2(myylHaQmqsIm3j zx?78tGLt?gVI~;XOykpItw!$-D(E&_&Y2wrtOsl}8a0YCGE9+QBa)qz^zzYto{f8f zZMmJK^y=B;h0RK#WxI>iY9(>OrDnDJ1{%DnBo1rUwP}-IUx2aO`*0eDJ}WOv%$L6} z{`{@sAXOaLYzwHJ7+Mm5fwrR+u-3LjxY;i|Ro~oIS{w2_dRh|DG0HsC`(s)+r&|yK zuFw*rqGv!EOBt|i&~}^@iI3eu=n9Em){K7VdA)G`J0}%Da={`h82A@bZ~#d^Rd?m| z$X!)PkNBk4?oz25q&6uZqCD~Bwac_sOy4e9CV485EqNakmZlQURM#wXuxj6M;y0gY zuo6s>fIY;P4|4HU?#Ak_PdbQ`>P}!owGUaZtsWXbv*-_4P#orp9j}o;#B?vQ`LAbd zIZV8|>a9z3bZS;5j#*|V!XW=y{WC$Dn4LuOH{JI*1LcOYuPH8AYSe@gL5f?FnN_t=UoF+QWq2Zt5ZBVfIk%z6xZPSo}&PiPS@r6c8a zM80%ll0WJcN*p74`{1r+^HlyUZ|i^}co%VbWjgl_%&=pvH=Dikvh z*}a4^?r0i@|8fDM4pXh8U2gW9HI5vuJjs>3*Wl87wE7qD8#&OCIbI?er+N>@PuXr% zFNq9WJN{mMGt=keeSyw;-}dIgwL3X{^6-{wzmk}dq2%awvT#bZ8Fo`vP#;9vYE@RA zTmjBtD&9Vm1WTG0(;6-azUr90i#E983zjS~X2jTq@<;oSlke{c%nN_rJPajs(B#u% z1qRk-rBqg`VhH>pBrIx+`$sR|0(!aK7-qde6_Dod+YIOWw#LSn=BWB+7Hdr%-1n3; zPQu;X(SS%8LW3~i$1cvKLw0Jd$;{FNc8a9E+P8DWSptDf$nL&71j?WcxG|jJZ^Y5r zEDwo=tGo#L9t6{t?v8jwn?2}eVy^UK6JQ|=IK{KPCQfh+qrRZ`;JAREDT3xL!%PUqc%o_?FslXxp}q`;}Ih#;7_^+@z42rP=gI>Zww+FQtFS z;LL#2X3m(tTc`L&Y&)%T!&>e1VT>(@7^;0?#zYdQvG0|2yGXRFhxkn+EG-GZ2Sfd! zcFT6Zv9&=`QZ2|rlYS4k&y@*O_q5M^EyTlLTJ?H6w`4i ztWIK*&U3tc$kk_vniJCn39VF|>t{~sjNCQ%=LX_%-xJss1r2Fn}>>FU6ZHF5VLr*#s)TlEr+y zQ~PKgp-2OFccL%l=f?0U0q6I+wL9BF4U>>p5CsGeKhaLXb5#4z4^A!Svm|c8iXm=m zM{F4=M#Gs}L)b!DTXU$}xvXN1sVdo8&`#xj3;pu>F|V>dI&1KZnmYmqRxMFn3|JuIPBpu`^pR4@F(huF+ke*-G0YF?^(Ed|SgAkUM6wW!y`vGNGL zRJ_J;)%6s%he@Xmzu(DlckZ4rQX=f)@3ujCHTk(I8@9YZtfwrwz1m14wYK&3>&)Lu z8#z*B59Q`UQ)zZ29D^(2^q1CpeQ876V}IBIi&H&ZTh7jb&Q5~)i-ty7-!VGqMj9ac zGVIWB{&{O`O^WV<^YCK=l3hxsV;{p0!{)m}Mdyv6f}-#YdC`OeWlF`Ct$Twh6F(tWpBd~{y>^QV?)gr0^?9~TB`m+2hYryz=lM??x9ywVD^yl zmvKtovW7&{NUfoXWRoJog6d*%oR z@iaqGU8q%P{apQ0^(_EqaSC5EDhNU3SeTh}GBXWEK)H+n7i8OTv6IhzrzMvE5#Rj% zCr_eddHwP@XkBw(WEt7;-R|M$=F)uUMz>F*@Xub+L+J;H+pT1h(V0c`RTJH=jDv{P zDOc~nE)5^)`{^})+jG*p{eDy#9-*eT9y{aLm>H7Ib^d*S82gypoiJmQxu@nuT3 z)n|cuS_Q2Zvy;|dj?7`_34zvHI7v4^p&^-%^$9%)Q+{861kq7m;Yg8mavm-6Ow7oD8Jh97fe zw^(9@kj_Z5w`!-sWal2iQ9v7%VLM3MWKUTeqfd8uv_Z_Z>map!a& zpB;J&u2n4`Ij%vFv5L)HeTyC=T7W}lCwqZ%A|ocDw1oBHZqvSaE)2+sK*d+^C^_ah zJR}DsPQ(}xGVPXPl5=tMCnxO8)ta4yopj-LxcIZ+?AOwNyi$0Df0$m+;0n&oy+309 zLLr66$oBdznNs4x*xU(vz;8V?t^mYBn3uH*aLb;tbZyu55JlXW6{@(4R`>=+(6iqG z1Il^)d-$IVU(f2=cU1KeEnI;ECuBJ_my8TlBm|n1Sx^x7^bhRS++X{T-&&`hzqMH_ zYIXK(0g?em(=TfnYs$;Z=eCj-^Zw_?0x($!P|0X$Y+UE5TfXn7UaUE~+fg_yo)o-e zICkrIfYuM!PqoB;M``W}2UV-N0mk)9!~Bz`=HJKi$f&~;ar48X=Y>Ip$UKfN@c@DN zqv_$|+8kt8EV51U&)N6Ise|8pfswlPWxhI}ej`POQM|#g(7_3AuYW_~|EA{^uB5$= zq$FYo>>}gIyST6y*u2uHVhs^O#3RnAhQzyGx*oEzr?=E1THo`mJwE(dzXuDSm^qX# z@ro#u%jfppS{4Z+6=`^8_FaJgtEHuNO!mxLlo^QkOwn5KS< z!vlX&SW=Q!&KqjE=hBCj8DG|w(pGKtBVb{f0%&L|UvmNLy0CHp>9L!|2;;D4WLb(Z{TG>75)N+%L zUz-oy_1JPT_Hs(#(emYTiW0Jo{)Lp=meY}SP=**nn>%)jA3TOXaT{8sjtv>p5v{ZDL(rT@I2o8H>KYJ}O|U=3{wXo^PH{B6i>8kzl#g$axiB#;?_YEv0GU z{870a_12Eb>3v{w^fWSoKqAfZV5|bA8n#yQh34lIP(`TB4oayUx-FZ&uC9W)IYTP1 zb;<|@2-f2JiA?~LMte+R2YG*%rO@3q$Zl@=J2}*y&W%@mqUET6cct8^9X8q8uB$Bb z{LR(jHT%TZM0IFaTi|V}FSWy6cU@xVj->&4rZF*d8@_iss@ROB24WFS`b?E+Hy{XD zPu$gGGN9Sz(?i2igi5D}ZZ~;XfQ|X{lQfsc zj%3d(6woPD14ETTSnaQcq>65{tY2}62 z&nbpUY2c$tkEA;MIE1=Y=XTS}uNhtlC7`U+EVvP5^f`keGR(>U5#nTY;@nfHSRdax z;%Qr28VaZMVA%tsz}Ahhc$vY3yNaJDZCNnlJc@w0mVKQP&Qq{p7WR;48`w#OUDVo2 zme`NW8C8c{5NR3$f#H!QB(!@7WG}<;b`b-!;g{Z`FwdcK22Yn|!<+CUBV`H9w42za zM#GOFwfUf#Tp2(G-8k?c>c#&rc_q^fD%S4pBvkAZ8Kmsj5ZJ1m6?hd&nZ24pIRQD2 zD>%&x3Ij!>#B#|;#E*hA!p}XKCSe~n(|0QnfENFu-5#tl6?P3eGN$0#spL_{qe7^qAwB>Yl4U-W)8(=ZFPGEx5W9 zbi95FT%5eTpA`tLhBJI*@yprwdSvEqLVxVsinn5?%NZ2|wxml63keewT7i+p7RTTy&z^cB*v0ZH3*3QPgx`S7YS< zAF}kVX_=AaLw0t^#E?6)Ls|Cx7)d>kVCWG@ZM8%*njKUSn-y_gLc?_$c{uf3@}X$?a{_EEmie#1&KzMP7Xn z^Cc%mjqh4sL>smagqor)n7AJJ*$pvXEn?ff*%@d6r68qW@S%Bt(Y;r1$lXN?5{|!w24b+RyPCI%FfvA zhO(O%9_db~E(M8Bi(r6R(8>Fv#O4E2;BoPZmu(&V9rQ=FFZIrG81L8ep%*AWl%_W3 zL72Gr!Vo<$_*M&30VY+3(#DO)!r7T;Vqzk@R2t-)lCw#IpyAZM-{!}|+A~Yq>d6Yu zcKUlCu2X-3RliGaH_LNWfsRLp;!_WU(HA;6ZTtl&nK!7K(QJ0JZw{vVjs;vh$-`?k z-G0z?NM_$sDjPFRe9(yVG>zo&&LYKtr8l*Mk0h<3azvz3+=8JAlN z%06-*){0wOW$}Odi-nu@-l|ho7XqS$>DH+f; zl^G$jw>Ha~&dzr=rI9-jMp4JBmG;u9-l*LjX(wUC0$D~De8oqqAKqAdfBgrT?Y?>` zKlR_xRlm7>e;>yuM2 z(-ZmYp&Lt8!8h;x+(49bW@2)3)u90{igdU*(^QKVrUmdqRTgOll+T(N z*4Wq>eT37#SdOO+-Nh_YW=YRZ{L*$?nG`PcDHSb1EHBso!U#Ae#6$#h9|pjdcHT5sYZ$7~D)h(7qOSb;a@VbkWM7^Qy%&7N~+G z>G%xC=>9yM(Kn;wBXxdU>I_WE&7Gbq?wGDNAMpxKU-&N$3OJDdUp3_WmLU)b(%1aa za)>f4AS`|xE1-gJJ4)u}#TB$ubJP289dk?5_@aKVewhso4O-$rLOBYCOzywPh@u9I zUYuUT^`FqoX0lLysVLJ5U@6!cXJ*Pi+^agi2!_NIz=3GG3RV?pc*Ea3zWX?pBeN&z zsr&4D(WC%HAHY=MqI6j`de&ADG_pz^hKwsby)xr%v$NlP29_3Zz$naYnrQym5LDyi zS7G+Bv6@JK#OA`X+lh(3XoI=GoV%H-L#~0t@MZ=!d++`PtON_MtF~72+ zK52V!5GToGUi%Iszx{@Qq!ccRPXF9(+KhnG+Lv#}$^w;{%HB9Iw}TR5yCPwA4_hP! z3z0!l(Zu#_U9|DAkB+gSUo8tVVI!T>KHgNwWp|8r;m*T%{eZ2j)rBLlze1ncgik`a zJq=HPw6cBBNwY2sw{sp>EJ<|b?+EsN3TK{3)EdG8#VpH2M> z5D28Ep@B@+q*E&HCis2l;|Duj3t*|0{fKk|Q~uIPg$QCaq6b9Wg9?pIKW@4ha`P#r zG#CVES^L0urVBC2qrcLECVmSE&o_gpoIm^s>G^tmw6l*oeMo;^5A|u|X)*(E;w7jL z=N4CohlavmpPWDTdkXpU?QO(1HZ|B9~jdgj29E8uA#0%TTob|1EZ!11%_Ue#i*q@KYgOd=cJlb&nG=g%CA7)e!t^njH<3ABUJ))vYWFbtSG z1x_LAy#Bf#e*IyICi~7>cOOwx8gLrF{=lF3!D)Q=YRBnGWPZD!YKl1T_=XPkvVuz| zfDe;&P$OAl%V(>HK=%@;;%Mr5&Fduws*nsw%#E% zJ|z^MTOJR(w>b4Byt_`>Uu$V`C&U?m?>K-E5indZaOAPcxZg2e zd_Z=8pa#`;mhMc->`DUh9-#MX?Wq?7Q91hWB6^+*SX9G0Q#9vr{l6k4w<-vq&n?Az z_fmsT9UXgMdPKv^^gR)W*{*2;)IxxD-co4zZgc92)hnq;X}-HnVG&O8_QJpY7@VrV z-doq&4yqemzSz|`KB&Ae9B3z>miW4?julbb`)$4LVUJK?ePbimdi`VlI=^V*De~gd z`tM6ZY-}Md_m6KFSuxCeKYJ+1qwp7eq4v>l@f+(iF}(EZ3sWlneB0Zxp`yS*6BB9B`)fjW`{V{dhXt8|9A?%PFQ<01P5MNH<|72InU@{6l>*`w=?>v ztR`=NWNXxD^K4L5|0uI~c83|}iisoo;99shi6zx+N}NA?W3N?9QhNT0qV6X`dhv1^ z7e*!mS6pt%U7gXVa~9amkpI4dE3xCig_~Fj=d~l<7GOnDO*D6VEa?YPD`F><)s9feQ_`_G{A<)$#4t105x5 zXS#xm9_;nB!FXb2%&P>4uA1i;h|K&Hjv97=+rF}$@J0l`h4k~TS!MMHcMz-?nc3P3Wm!AEbXHc5~fivwcb5;tXUSWWi44zFTq$L z{;;#A#YGIzxqMm-s_#yKlK^yiK!2&!EjYDpNAiy^#$JvB*wMutpdT5pp0$_PEvf(L zB%E)>b^u2dQ>GX*Ps%O)F2~p0(HCXP=oqTF5Jg~HccV|MBad#K%k7+LvMh5(T&i&{ z2d_aQK$Z$6Cu}P4bjpbrqlRtq;xov}z17`?^z@b*!W;3Js zjS)44yHaG@6S9U|An+Px0ILS^ZllKWMIf@Bvd73Z$S-BYNkNh3@zVQ2Wy=vNb?SC_ zfLgyl!gPJWaN2`WJvC%Cum%Z(eixf7@Do3Oj&!S3FGtjfXQFVt z1l1WEbG8(Dl0>~>cOwuok|AcD`K0$jBGkEFG~rb0CLivW2MB&am%si%PZH( zwyxX^k=Le=!_G=jAFY{kw(fl{Qti@+cX)@(kz13M#V1uwjPqbUFi_=tzt()yP;@;= ziyQ;Ltkqc@<}>JM%eLk#H|Qs*^%ppK54*!0xp4xg7)E8bUco-(K1{FDJzgY|$Axi> z>vZ@zyU5|E{~BK_Th6`Dxm2Me=_r=Ea1xybVZ;$&ME*k0@ z%pQT;U%G1*xNWAtJy!EN$4d?_mH^e z2h_51dExIR7UORW9>1WYlj zr0Ei7xH}eG!gx(n@DIGL5!WCXw*=;{3I{3qZXV3y+E(_9$<~fy3LY9|g%8MMLN;3= z`700*wFn-jEZtK*CEfI<=kUgeXUY4IS9iLPE5rIC8BGU+>$Tc!>pjNAf0Lal^aZ!@ z4w{xomf+m1ojx+g_{4N6^xSs6-<_ls(f|5fFogAUoJrZron7;(#1m?>D(QtMLLSOkzPq^M_EDwM4()O@>Q+Grg|octO~eh zAe=3`riKUdClP36sR}@xpJtD2Tk-Fk+y>yWV@AzIYZ+Egw$eQ#f$j(x88>tE1mq%V zX-Qh{MzhFszjIu-Fm556$zMhFDvB;+&ivSb!2W|FfC#u{wxRH>9ek+ZD<++&zy=+iF4u48h0I-D2+;tIe&S}W z^k(-1?tuH4Ua7`1D3cC_E7iu#h#^BJK2>r5^?GfoRXhg{4Uv48D+8GSQx-a^fU`Xv zm%(6yWN31jVUjgXg`{K2c8WaJ1+zoiUWyn9>w771&o3tCx8U#Ju^>f7@L6g78$U}+ zS#9F;JBk^{rQfUkVpJO*{ZO&wrPUlP@Og6DYHfDXRVG=n$LY%-@&T77j@i_Ybn*++ z`X!AV1w?KN)4VYflgk?b0hlHM$cg5>4&z5*xkHxD_KO<TTI<()svjN{LFk0-5nO!P?}5gE9wi}*IO`z>w? z9U7BepkEdf8d>wFAXEcr-M2GMNjm%|?f#3PqlX1HvoP&cLh$9K=f;1M_VEis&Vif+w3_Nr^A!uED6B&K!Sn{V0?AI@aVvg zIo>+Geo9&N^!F1x5kH|exP$*uLh7*`!iaXoXUGMwKLrxa|K#qpQuO za`1Zla^%85HzT$Qj2&k9dpyMh0xJ{DI%i@C%$Egq+J*FR5a`=_&q$bnNFEbF?7%>C zhvtWy-Rj!f-=6$bvL)r^(ap`mjEsy(|KF@b!n=&nl~|rVwyQ0PnkNL3qYcFukpJl9 zUyfPQ)cndkv)Vm;3MhQu;#%6+zGA{@s;`GBLnV#NDO^YPgI~IJ_q!o?QL*2QxJbZ_ zZyKi3t(H@9N>`Z06RTyi5rl)Z4{ z>utT$!<*R9llgcis_W{O9lU^+9sQ+&7|5tCdh)3ef3DDhQg|wYZ80>>|F3DO9FT#c zbgZ9zM!i<~e~tnN6kY8J1v0Gg6oJ{Qo~r5-;A1DZ7_QV`bu*EYt2v7xND0ycw$Zez zV$_CyiMtn=obR3Ncq!1})2Z{O<~T>CBv*uRvLXxZ93HLqSnd>i7!7SM@Aj z!BDsoFy*<#xa*?3`+Q_gugR$o0sw}F$YcHc>p#_=Rg%JT1#t9%d{!hik$wlLKwXoF zYH! zY+p+^Zu?bbWG>&Gj53RE*b_bBQS1v;mV*nQ`a%Ea>0$3=Qrg|!UE@#rW@@V$cDh6T zSI-5x6~*Vn67orr=DJ>D<>^m4DkkO{Q5zI(+ZuQb8&sXwpIbsgz7nbUTI>Wrb5U|$ z+#fubk|q2XF^jD^;r>3*#0CXMKtU40&1P}r5LobyR@flWkJ7Sy8Bj$!pd&`ALYf_z ziQRL>b^d3U3oFta`H40d132?>z#&m55L65KbYPA#5Wgef!SJ6|=MPu^O~r49Zi^`V zXZieNY6RI_sTRVA_XLdz3^}+l{Go#4`@6f@MMbD%+#G1|@4UvJ;!K*C$v`lc;^gc+ zIyHrVxbn0FG9&=vq@t@!>ZYTu9oD}Qx)!oZuNu-gsxkn;=|DmS*rtZoZ4R=YvY&t@ zF8hgfIXE0^f0;W?Jo(%4FD1Y;!NCgYzY4)=_O_@RHLUA)BB4e%XE7Gl9~eSJ36`P@ zD1aX?{Fwh|eEciGmL*#w_jneKiuH4kV~-a3G(n!lcTa~khX3U&rQMw!EIQ$cDSi?r zjb+USDt0yi{0jM9?yfRyUS=BaXp<>dV>-iTFI*+T;zdix8&P>=IY!ejO!q+<4JFL@ z1emz9U|L*4g5vuBu0ocSTxC^t`vl}Cx-n_-2E!OfdwK>k^PA`wp)ztPp~1WP?Y*Pwduk()Ca2G)})6h*R zFN(HMAnl2%eRIRexUHrBZ7mtsVjB=<*wI?+NU0>t)FZC{o)#ciS`G+i^bw%qd55S| zemrfHn~4U+Q)&`4)Zo|s6i5LGoZB8Ctm(8L3W^U%;T2&WMM2C=99_D}m7kht<| z$H@e~d9Dzp0-O)#Q$UvhKYEawaajkaZVUm43o-xx{)Qxq5&&b9ypJO|Imtsf*xJGm z5)F=P%M!{i^6A z@nqz+BjCGyOZZop6j=r!4@|jY4rIyuzUHe_q-5w5T)6dR-oiBBU-UaURfk`JS6I9N zwT?0n&^X;9np1PQ{2B7;4rmr=^)DYLCQju)`qv&fmgnc^_9UZMgb)v>dS55@{rv~X z*yz{%1ewz(U97b+&%?*aP9YCO?tnq_<81>5_>}~>+|Q^vf?1rWGj z)f24EwV);S|C;*hxTf3h{UHj10tzBXN(d+&k|P8p9uSn28X(=BBc-H8EIOsTV~mn6 z>F%yEV$@*#-tc@s&rkl~_1a*2-+SL@=RW5;*SQWbR`iPGkRRNQaGGW)ARsz5cYag~Y&&2( zbgy3Q1iba2HN#|$-6gG{(O!elNg599-LB!#W%KaN)e3ZnPxd7oZ>;A# z+1_e5CrxKEy5A_po6K=6GWx)$V*Duec7jo?RNr$KJ_Cvv+^-0Z_t$-uGe4-(FJAuY12CA2O zS=2TSf;847_3hjM5PJC7ak?t1s@~a8U2D z94)@MSF3Q={A2C&8anV>^=xwwTDQe5nzapKvl5zui5iP7S_|yebYI%PdVAu#H^hHw z-w$_w(y39@u2(mlnihE!aI!ycCf+1who>*Jm(P~l*~~TVaRy(7 zy>r0-MSGFdSg0Ga{P~xz%f7=`pYuloR~MWGvr}D3^V9tdhf2#^PKO@n!T!rzo~wok zZzMOwBDtGR|3Y|Pa21p#+R)n3KUiL;+zk9mAlVP zm>Ad<`vTpEcSQ=vU=pb&#iL8rKslWF=eZ6>W_)Q}7|?f;t4J@BKzY6GST0Oi{?q+W zUer_*35xQ<#tW_e{^YlUwZn;~&AIEJ(_-ey35zd!kk=@Pkl=}6B4?r}zQWp?k*#+; zZ8FMeF3y`@{B&PHYvfY4AG1d5-pCwlaYw}c2pC2)aSxs);C=vyzTb}?pIF15uc`!N zItdT5DXhH~wW_{TwVsV%{tQ3%jNUGS1`>&0uKQega$I0y1;6X|nlSgaqlY*JuVnXl z_hu-yd{7QYqV5mfMyi*$0c{=l+oq*~{{4{bMNdliQxUU+?Ooi`9a-@e%6npqWM*C| zzSdjV=jM7>ZkY8iDM*!OVvd@F`&r^>Z(Cni%16DcIZ|c;PMnWZyeODC*;=0%>Uwj| z_7C-F@UDhyI<>0nKV9Ec5Zo)$BsV%S_|K7qK7Ep}%uY?sZd4>`V`mp?;ZD(uuTq#d zBFFA??FH4caKf|N?Ch^ywH#l1fdmR^IJ?Y84SfkUSsj9&zVmW-6D2U)X{HH47=2c) z^SeWO$Jn`Vy*z|kCT4Lp0KK=kFUq+%Z^pU8%Rfe11MMQ}DCiTA3K0-a`AVP)fnx}xkq4xH?au^=;j2^IxEWxI;?jl8!fd%LiI zHg{=yr#M9?NA*<)`Ocl2xuV-M5-YB3Cs-C&V%^qz)%TEv2ZY+NwqA!RhA23C*Y{xi zil+4n?Dit$F-6IVA_w%0#TL3G8r5ho(9}OSUzfb+Ya&i{)D$Ct>_a8&`z%TjP8Hub zlMz7EIFg4L-WBChr}LEf05Nvz3(|sr)Fcs{uEj*R3m3oT(wqq2 zodSB{7{6@X8kr+hZyIH3menXACOzfgz@OZ;tKT)@dO$Gf5aFvcn z?fWymqLT_PGD(*g?y${WYCt?1LoGPR-_@S-KR(v&^_{m%TR@ThtUXl}GZL6A#mFNX zE~_u1rY1I76RG4R0HTVjzz{=3EH()}XJ}yeHO45xMZ4CX zBx}h$?8w`KSwDDw$ez{6Kl}eucFWJ>0K>~Dq)OU2Q|f5ZkHeqC_x&WS7Oqb&e0@@~ z12KYTIH1-O%901FJZU9!x1P@R+S4>EH4`>KWNsnuc@$t6`h~lqsEOtz5N15)x6O?| z>w`(>gEfTTbaMH@3FE6Lero&-h~baKj$&I-E(X7Lm_<-Io`a8Vrh%r6lX*pt!Sstb~ zsRvKX2&`(!Qu<_Eo7INIY|w&?h%CKXfllv8C z1hIPs=jmb#x4Q#j;Q#$#sbrjwEIE41$#*S?Vl&vJ_`UFQd{Qqc^_UErZXzCIY9%tZ(%6jDK46ifrZYIGqPvpenpir{Hm3 z7scX8&3TI%X9+AEuJv-+MTjfwNnh>9saYy7)5g})s~uBBMN+%ny0L_v$eZcI=dAth zGiP|k;`L$G&`&eRW03a6Y;}j}FmYtd9NF8Kypdx>^S^9lo;l&0+OM3E9d?u#uV+6K zUxP8c=-kD8&PKq(m6gu!%untK!i9H$4cHjM9C!$i(GJ>w&h)gYKb|PiK|?GjlG0d+W-aB6N zz6TeZ@O@ zLV4ALV;AU<R28y!Mfdk{jK#;+1uLt+5kHS0MC|zT&e6Df?>8S0pK*<`J?x# zmM=STcj!(l0At^`kbU-s^(DMrl5%?^y>F2qYj83JlZjqwZo~Mw4iG) zC^o|tfoZJ>4XXv*2werlzqHbT-OOI*u>{bjuSY)=IrQOPy3t8HquH8zE~KD;QRJor z80`5@`G6S%Vt8(@MPv^~6}#W2ka?yO0N^0v*6%GV&k1bL>IdI}4YX=nzT@EQWE4xj z)UG}kud>EtE7$5d7gsXfE!=gkuz(9cj7vG35{nDC&J${M4waED<)C-1k(J zIr=DOCuWV&_s`*zOfw=^FlAhAEd%va17_AngHs2gvMwiSK`R-Kvkbxf|MJBLca{A! z?|2$Nh2RuoSKlMjF7MTt8ukKNZ&Si4 zIsgh#(Lboy6SieIg>hPOKq6~AL{a@0x1RB#n!5TO#Q5lFn*-ziqNDdC;#8$Ez~jI0 zf~)QA+~I0{^1cyBP_9$OGZpq2>=A!@+aIF#07+(+;!&RM;gr-E!LzBN_Y@(=g#You_g^re6U_rHz=CA zu@3LfHI+Si*gD*qj;GBKRN(J&X=rs?l|lO4otiBoGLtj^!GJAp)J7s;`YhE{=R%Z` z=8}`<*mLI5xcDBgiNF1wz*6Kwye;32ZX!RfE1-ZpmmvTfod1Dm>TU7hJ845RsGR+o z=|IzNR`!{sq{b&P^GK>PZ5)kCoO?uSMh{z*mRAyY=N` zp0Y_rfgg(?i(>&*&FtG(tar}dC0XgD*hp|ap{c<6IP^}VT!t7vZ!YYPl;p=eNy`hIlVZBp7Und`qvi@v>);5%e^*V z@EIsFaFJ0<+c*tt6Z-g?cfgu&dZ*0iC?Hem&M1*Adr-O{8Onwn$SIiKwI_MLeOtKj}Uyv z5PZ9k8D;<78UW^cqoB|VG-cWgGC6{8d?Q{n*Zmn=H(1C`b^BdTUY-gn_xEdgdHDrQ zVy)Ay=)whO^HKukkc0ugp~M_6d&r1+^yD}7&hHo48I-z>qYP7??t`~~m?UR8h|bAX zC76@&&iy8E&%kq&b%cfTsY!@9yNlF?&AiGt4#}-}v)aVJ1yZ+x-XM#k8*bNue@vI` zXg1H>N2wv8d;|yq;Ih#cDp&goFS$tVV#i4JAzfP*?4DB{2zDR0#CEw?kG~1_6L{C6 z_w$pV!2T335$RStPbW3oS8Di>>kj+ZjQ9@z?(bdistssD>;<+!q;IFMN98?~e{wzx zU>wrMj(3a104P`$l^fCR9-OJsbhde{EQRR!C$rIb=h7xfO8OyJAi#0_IALFfaT2P7 zc5e6>Ozej6eBsXnpwxE2o>KkXoTqht;mJ;%|i}MVCYkv4cwsqAJs|09=Xu3S6-d!PEi+1=L+IIIIgaM~C zpv2|GV4kOH!JSdvIO>~`u=-uQw$tF!Snipi-#6QvLEuhODtc(J{?G3}V_(>8zP|d) z6DX=&gE7dSRma?OHOa4EzrNMe>&tqRAi35_01^KxN0*D@{sQ|5;R&oC zyj{;A1YwIjxyUubbL$c9^G|gxh3+hxfb;ETX{WTAPN-^|JAi)L|4!6c6?;$>uzbNN zY2qN#cDsec+LU{p9fZ;*%Hhk8 z*bBrPkhOEp0A#1&;JnM83_NwIA872x1*0H>7O%A{c%liomKW{zcfTByy_wAx4(rE zYGAnZqTo=|D<2i*7_9*;BW-FqiZPYC$df<*#q8n>=L}J^%tP7qzg(9z@tmBbYULtn zjP#@DnT2*6SL7q|bna1ma!!J{xKZJUep%7jS6sw%F@`z#Gm9U`>$BxZnQ~Qu}6` zd1frDl1AA#lOturONV9YFo+~64eR`EZb@??&Qt{qQB+nYx@oM5k=yF}ud#-pRu7mN zl9ZGL&^x0%aHW~b)6?mJCLVf7}#?kwvdBM1O&4#R8<}Q{65x*i2)-aSi6pbioliU=I zPFk6Z_yvjqyaHIs7y1I^2-p4d^Yfc)n^sRhXJJV#EVTJ!BP=4KRbl=x%c9-hm_E0# ztnABZzATSa$W3(dJ4{mbVN6WYfrBTTwPn-lfzC1PQp zh%7HSr2E0S%UvS7n_e`an4P5eF-lk~|32rYm>F7y9PQbuVP%3QrD zsk+?<4a%aYHzKidu}rT-Q*$yT$yNbn(Adwen&G(@mM3EODQe)liY{! ztXVtcwynL3DNh5=`1rW0zP|X=w;KO05MWu~^q>LQqW^+`OJNwfJa};w{MbrNbsNrD z9nl-%PV`DT{ShFdjqK$Mqty1O z;_3vN;!wj02jfg5qFO)2I{t>=@zHL}$kuNAs3VG9k62u|6A@c|q|@;mB5~dn@TID) z=c+-`<=kLzMda?`gB#cH(rh=w)S6J)#iTNtdu;+;%qlJ~?$08sfsM6*BmlKM(p08M zGk>Gj@9bEZwvFwGdVgPRf!FWNZViCeBMv6$yZU$1YV# zHyfSO7o(0BHxJVVl^7F4H0|`8TDB?u*~+@f>{a^4wOlcpg4P;LIAZ*l>!uvuE7COH zN0hy^o6jr}zbhS|C6b;^?b!JI$evH=Q#ZQgyNL-@64eQ?>t8?^9i;Pw3kwU?fp08N zSI_{ZWdlt}HM+2-V(B0^nV`L;-oUIW;h-klE%OZ2S7wg+{EA8Cx+Yz4zvVEy9 zw~w4}z;n4WVD3U15G)zT{ae;mVgM4(&_}vS_}EweOj>oXSs)5bn@wssV)?XKC)g>t zG@y9Dy;~t5F#`f5BU1aSY!4K4iT3pOT`K0U#3H*DLga`MUZ62xM!GEACjVok#@I&A zFJfV_NcM}&&FY?L6xEQY$mHa3NKCSnp&`d6KNq@gb7oLpGde^J5Zbn-yCXzc(4S(e zPqzDJ*BNzQVgm4DKg-Hw>W)pfMjg8f*EdWIm3OjtcEn|c^Te=7M3Va2TMTs4H5%Yg z2B``zhNTQvVpx1I_5}Ah=Muh~?JbN|;@YpS%JR$}au3Y=GB-jm*ukqIPD@()>lIR2 zi;%|n4$K*!6~r@S%t97f$;z?zTS$mJ3(tMxy!*PUmNQI0JhS0T_O-K zom4;{Gr2BhmYCz$MnSX_gg4YRe!T6KP*1ld@x6!koHkXd-2hQ+&3z~z&xB5IUpVdZ z*C}!)U_7YF#&`RlRbPc&opoD-scE?CCy*Ds*3X5$n~YxtDja)+Si!FZ#!ilDqaR}~ zcS615eP$J~&sQ0~q7qH6yT4)Fx-Wp}vm^qa)S4l7;nRVl9#k(iWv z+vXbrQd}b7gG+$~@7@1+{<$WA&Ln<*aj_XN4ur0F80gc|bs1HsD_)Kbdhs?^o)?ok zve9_?fMr8p6Lj(DC*fC67VbSXu7l&oU@r3Cj|JTMM8q_JgWsg?F8 zWTugzX|w5{g}Z7&FP``Qo*tGD$p&^{c}hnb+xz$fkp$i7je#XR;A?083E`C373@u+I6Z zyveC==-o5^Gl7UJsTfH5v#I0pcHXRM(k}h>h5u$|PNs4kLkL{;7te_VrOdnDcH;Hl z)L)y>pX&;z^$iM}9bMA7aYDoic}lOPjRiH@ERa;Wu?{|JcXGNi@1ODpi06+v<}0M) z`u^JV^;oy@bJn zX6AnF-MKz7V$v9;Set-Wk0=oXm4=5L^z@}9xrLmHMdMC)a&i%(7dCF1OGE}KI6gd` zRZI)FqVRQWLG{=Ix0scBxn8Tt(u(NBPg-yqpDQxEdYaFcQ4c)TNthFZO~~J~>a;DN zZ2sOiGMn`|_v3KjFVIVk3wAH=003pj*}A%X4CSm1-3;zxZa(}fY^vhjObv#V`=67F zFMRA7c0ZbHIPD1Pne^Dz_c(AGF17OsyhjVQ)`S`~-36z3SJ+P9{?+j%B$V0Sx|4&2 zX?-Cf*LUl~F+swy+Wftn;5{bS+s-R@3#dNISn&)*1FZZwXKc!+e`rUVXu}A9QFme; z_$lw><}}y&Y5G}S9Ol74iL+GRii2Ygldxt8c5r)J#Fe*fB^GnUDPuAXjy*1R-Ox{5 zaii$!o#Wjbn5vHW?!%7i+=iC#B>}kC^cy#Q;U`B!r5ThA<)0OyzUwx_zU3yuT|C;G z8yigQoY?gPQq>(#d56=ArtoCawAhZu6J7bsS4qgKz7xRIp!dXg1*7Lv_!254kQN^Y z`s#c|C5_q~*y44%eZCz&zkrG)>Frw2Co6lrSxtSj;bipZ z2A5|hSZM&Th+&kF4UII^D9N5cVv2RV1 z7rW3CT)4EkiYh)BFY(q67Wi&&d&)>+gs;ztdQKD_zr%l0P*iciNwxG!gECvQ_ zbQE=kizzSrxV&L$^w@XPD(6!WC7~HslwybvQlWe5V!Axn)8Iwrbpr zMD``rSnO%_-pyycnJ*FJ|7fO7=3fm4x*lQ_fi2L?3N9FrK~}*-$ulW{0O#E|xb%xJO539yy$$ z_ZkNZw8}TOx5M{88LKIBLWYB9`8!`*oFn7g{ZLs0;T98k5Gso}MHsM;{C0D_7iWhI zMZSpIbwNbUGV+X%+eVTHZSPi7y1MekqMCyycCMe=oyVz5DctMTnWwPBG9xpCAi>Mc z-JMhc(da~HEAf=8_nRKZ+1pDIq<@imM~}U|y#WxI$EZC5k7jbBH~uB-oYZvy`lNCJ zzhkxM2hn?4s+DI`l==In-n+USWR;bb%Z|Nj=HryQmyb4~wrmIZ2c4WFlo`#slwX$7 zGScny22NH$S6`re-#fZ5r&7afNT($>cg4Tj}Jr{bUF zdKkIQ2}h(&nOQl>?%I^^boRG3FBJZWJhCohC~z}g585@8e$PbmM&Ihjwwb}5v7x*Z zl#}>{fUBp!|5DtN9)`KmWez0)IH{$-wgEOHfSIWJ33IEYU3(2;O>b{eAW=km-VPlc z)BFo}ki!pql*}YK8hzmlbt@RIqG-dq2z-i)r?YwSirLIhMC}9O7H3QNQPKgu;clm6 z{cqK0w(?Kng9P31Uy{x+`CYd4?^Qpb>zR-F)v19ITgRSYA1!T&-iR6&3ATA%5Y52KFc3&wu&^=w@}egKdvIB>eD2=zGdo zdU(z+eb^p{kE}{$qtKVY<1#kr!Oul|auY2X0QM_mqbwkF1%PnKSCc2Li(D>%Vq6KS zhPdLoN742pzrus}pFJHM2F*XckO-oVG12NZEq6ab=HsIt3%&L7i(bdyyGvJcb!v}#V-$#B=Qpyfx-TYo&UXC7UQ3X|vZehOC zOMgpmiV_qS4zrtww^{RtpLr$MQEgPP^#Dr;p7uQWxxBo5dXBOJ;E!iO%1Lp(R(rvS zW`hSE9UZv}SRlVlAKGvh@EwB$(Z}ih`v=PGSX-#ZahJr$?rB7{VwoIRIf6n$@_M&G zpr$cxmz0CLyv0pp9{Klppn~<22QH}U{s%6_RlGn#3<7~wUrN|mHkKFh){*&D)xlt1 z$fbd^v$Fv7lod%T@D?DD&KtjT$I-!t*YEBsW0@y0NvUDIxPD%ud z^XplGbNz(y2PL3Zv zWSn*-AQTeG1#tbB*9TGt_f7;Lz`CbCl)nG{q4ZO0YwO4_5a*fZ*=VpuyeU9YSy?5Zv9}J-Ex@?ym3ToRcH>-XGu3 zub&6@X4ul*Rb8uURrQ3*$%rDszk>$@149xQ6IK8NgOLLRgT#h~27MBc*>3_mys`fz zt^^Be9h zvNHlWm|9yAE16mvfj$HSV`gM#*>0?1WZp>&VdmUP%q3=K*-7?e;@l1iVq)LT{}w${ z^$Z3^3??otsN|A%wBqcceEr;iKG#Ug!QuY#(_3P|AO;$$h+L{*=d{a5GLj(B{jk1wUi^f&F8H2m7}(gFA^&NxQPyqud9CKCX#Z|pbU2upm?^$Ar2lRZoNW&W#W!Vw z!l1Sl!mi&Fazp>eAHP08eyiz@P5kfcN$nbJYMjCU_~@8~fdM6RT-3|UD}2%MWI6fl z%!b?fWchP^=wJO2b64>B<9z}=uCA^<{r&c{>L#^C&%s1qVqRWtpOpUUU<~q?a2 zRBPjzBIVKpi?j94ku^D$XDPD{w63D>TaRCymlK<{kuzxGW zv~sb^d3m9tcT)#YuiJ;Q?yBs56=$c%~w8}9T5 ztuns06R+b#mnkVfF9EN1B5&fJ)%HW8A754!R4mGu`x|#Es75@}+gmH+x@H~!m_h-T z1S5btmhX^+3jZ@JfL4|Hhq)?rZ$Aqae};jABHSwwMuqlryZh+NHqWd#YjOw(U78Spwn7Wy!(zd#nfes{w2R*RlSQQ<5;VT1Mq`Oj*~ zb08200jt7dXM}I@w?>Ke*UY_b1Cz9hfp++Cil>$$4(elzOC-A94~tpvURoe z(l;YSRzNpD!13xDC1BkU@@T~wYA8yYVRnK*!9rx>T1A@b&Sx8tE8Mhl1dU?=Os_s@bTX%ztkH~CrdF6WmX=22YpK?{gz5VLu zFdJqM5t|>=W$`^~%#tDc z_bsPtUaqUuSB$far@Ct~jOY3?M+#E~cE`ajH`)-pFJ_FLBe%)V=L$~TO?D#%EI7{k z4EpbG{^-1D3!m|~6pHU*@Fh$3P-Vf$_nH6`lqEdcieVZtxz z;e+33M9o!o9QU!=5YsoOGp0rkkO(nq(?5Y0l97={m+GG?E4*crH9_uiI8IjzC%#~y zuA5(M3|+KhRi2u>sQ(!Uh$g26G)MK(NFqUKACE>$|I{w8ZI1j1zQJiQgduZs3c<|z z7y0ScS{3?Vt9`#91yK&~#COp~SE+i{u~c7K{v>cLozGn+kWHWS zMzvnKyrn;}Qz%c+uQe@7L_@gB>vR^X%0vokijbnJT;m1o`sNBRfkWj)lQT$fQ#V zJUayO-6SQPVg5DO_qbo|P^N?2)7TLeHQOx8L(5B&y0jZD)Soe}pPpUWqf&+n`EJvA zBp5SK1vJH+?WsY{aOr`-vVe-7p7Fs>G)3NZCm z2O6om;8&ut7fG_8KTkT|9a!m68ttjMdECEc@J=2H^>5Pa&nA78p zpF6qMMG^*@%K^0SUN~mX&HL`p*Gd^Kq~@0F?9D3{j?D{4HgZlEgNP~o=@ku}PzArO zl>nr>G!X%>3!_lJthKU9KcV}PS6RW9cl27%oV=~Wp*tdFL}Os{=UcK>7)DAS-ooTr;&;!w4oN5U-2{Km)KzK0TRs4pz-NBmYt3?kc*M=Tq<4m>BSm5HzyI>=9#eX=%%P_wYZoJS4&SVoHI*S)a;4JLo zZw`TBSgyahSe~S8L(z^qTiD6nhxGW%497%K@baeJU+%IPkKiEY0Ie6UBc! zX0*Pt{p~)9wtcqm3JZhhf4)+DxIXN^+Mf!Iidx4XfGhe2HqT>B!=Iipt+VUSl+^4Du zDF17k#QG=p5T`3D7*EH}9skQm-Z2W1zxv_q!vz=UALPDK0+;7DO z9brbm8LgHZZpws&g`;dzIjkx8_*z?sQPE6m|C%kj;jSt=pQh8>>qXC(!}4~k@v7g? z-Xfkt{KMOe@%%!=TT6#9#k$li{Fla|nL@(L{l4s2$39Ak;f4g zqFy*WC0n0w>rI1t(y+hvb`?2EvO9wmMK5O(*%DDKk%0Cfx;fxV9kQ`SbQl6ai<*_i z8(=yg8tM4f$!A8%V!0>M8hh&cs%@ETTJbi*?6j}1T=jCjirByZW;f_X26;cHh*C~j zx^lb=0x>l*1eOvlYGnq0o&_^Th?asPZ}8H*F7YS%s!&9~V+hS#G}FdL``uZnf&?RK z;eTu{r!csgj~-))X^MM50UR7$!-^FzA&OHoLF(vd85v}d!#;YjR7AfUdpmd8F-ha3 z?gOsfL}7ahg&QGLBS_V;lO9jU2KmNpoFjODrB|`qjvDu;|2`S1Mx%U*NPPXbUY;!3 z+S=D)yqeK_`ta)ActsUN+-L*mrLV))~t62cy73m3P2b zc01ILp4h|1iBva=`Se+i5OI@6PREXhLhc}4^GNMD;gYf1y`4x_B?NT&c;OO-+EGbJ zgEJq1)K6F8-th9j^@zKU9Ys#)J8Gw1NV_*MUqAY1F$HSPnV_~7bb=A&@{_^f;SZ-U z{V_=No0ZCKlfg&xq=bD+3i1ri=o{2!oeqTJi@RrY=yL5j|CehkBRzR_+^&7wb&H?M z9oQWv&ZyfZrG-Bt?iY-33Q6AeISA_d6uHfv$SY8ZC9i!}YA78nVc$ZLGvW+c7A0aM zxL0c`@}mKp>d!xri3e(YILbQg1BL6wdBk$d16+pbWYvL9u3%q3}+ED`;Rgi};v@z`Ge znUXNF7xMjT4j$6b1@=25fUz{LM_vxo$@dh}DK%?&Z~O(Hyacvq zuvomExj$RF)rvBj9`mLCB&umROumo2F~{1vykHg(ra0S+7q#_+sra^cUcUXrPn*f1 zns2LXW{E@&wfs1b+(ykFDiLDxAkum#5(Zh+GUCRODq2-k$asXm!jLS0cy_s-2Ene@ zfnAJK_p|r3>|M{E-*HP#g-`UQpOS&e^gzZ4PNtX%k6If%mPeg$I~}!&;s9}uDD$oC zNuBDbiZU)yOXg_za1m7<7Y-L)y8HNvl!U)?Cmr>Ux8?^oMA@AmC0Z}7RUrg9WMXRV z8J920KCgSLBhADyuznsqhwfh0%VXE7NWd@|Oph}FySKVZFZ~fB7k4DjxXgFm0Kth{ z^)!|x$$a_eWJhDfo2=;G%#zJAk?k!U`Ue+?=~2E~h>};YrMCX?L~KIcQTvlOW#X6T zC%4-cm0D>Wl|;@c(H(F~*jQ&fEu&8c>6y%_{xRLmNwzYS`tX;oUbDtJ%UC^#_V%60 zo(-cxJW$vgE2EVgJ{CrVY(z;u*aB2xpebC<>&^z!wD{?3 zL&Cy=c?b_SfTq}uQ&syh?;+03EsPONo}}YQ;A#Es=6l&3Z!Hn88@lkO_E(|2-q=g8 zp5q$((S{dk4h%F?N_0vY!>#~0wS<{H$-m+OVeUMN{AX6IZ|oerftfcSp%9vpyylO# zgGY6|mK82F8heL_N^{*?W{;@4yNVtwJavbh6V5$hyWIQiuTIv7U^kOqVgfWNbgc`C z8=8Z{%!!HEpTL}kKeV!7*xv<-d%cZDMm-F@+F7vo&}yNHV$Z+@Wq zRw=DpKc0E&{TL zJ{F=6ckMFlE|k-X?VI*)!ZPwtAd4hodaAvvC zMf4iq?JN(s%wLAEd6c{SI*XN{I>$e(7vlYD%_G^Boy^OdL3lzDOmb1JEO)TUA?rPO znQ1sfu*COxwZY^m7BTD1`;Yrz=dy76wyoKJa)m`+^KHf_X`gqnZx|6Fn@2mW)?Rfo ze6vE0G;ks*3b5J^hy{r!kBLiGab+6_VC2*Z-pjd<#HV#ZVmp)h+ihHUZMC(KCTuwx z2ulxrE?mnxJj>v9Z9=E~YNrKvYC%s@sH^(IN&k*VPa3Cd>BWrQl6pHBf-)-2tZhX_ zyuzNk+yttU+yOW-%(ACj&u3qJkNE|h7ICg?A^25|-In0iKkmmarVb0Lz zU^C@v3uP|lD5@Ywq#SFb_dwdAJB!w6aWVrgBOia&w##pgQ-)vVM_z}%&xylb(Jb~F z911lw{a`YX;Fv6YUuX#BY&Ed$-Kfo3{IZD5UUqyPrc^R_87{A zJ2Bug>Q$S_N!oZBCYXk&JIHe{VB>5>z9jL%&3YJEt1pJP82kEY1QAo4h)uuJm8#?a z(#^xtq>1BFB&Ms{<99?uFJsxjTiF|pFlToRAD#}y&;Do`fs;DIWOZj7eV9^Uzkb5A z#OXXqY>dB2e3&EE_QKrJ*9E3x*>QX@9oViDE0Z~-B|*3{0Mi)1l`2@(K5EjqZ+P)l z7@8dSM|=XKvn`XP9bMDh4gLgMq_@^e{1v+{tmf9hHk^HhhXHu_?AFC_3|~m7jphWq3d#XJ8Ph6P|Qr~4TolL>Z2~U@f)X{E9j?2SbOh}L$x)EOM_FgYFOuTTu*-U(RF^+V5n{Nt3TCYLCwNHczL*Pb@Jwr}T|fw8eFGwZpi2hRRP_8C*U4*teD)t30jj+&abd2Q}zG=8g)W z9YjK)z!!O?BQibQD+%P?eDQ|nXw9dybSjl z4&`;g)#%QujhPX~I*7ibx9Hk$b0`_^s(%6>br`Eue_Lpr`5W9pZZxo9;apbIe`@8^ zFE42nQ7Ka(0Ew|QrGnK^Jt;5HRQ-(~n=UxMlfPN}LJy)6tZeu;hAN4DmGij~fRf_< zV#O0CotlbFEl|&5T0jjFHzhO}cRPm&d<40eq373Xs_{g%L~_4>pq`-RyWrYkfvJgk1!ol++Gi9< zn&$lTzO5gb#%bL6J#%=*gF&QNZ%D|=!zSR^JKj?-4RdHBsB26H>N?17VaqqWxLVR* zMwpE>7=F%OtiTMI7>1?|E2d^Ac_-l7i#6XR7F8uE(yD=vys`2zKGP2#p{uhbv67u_ z^*J;Wxm$)U^}_QG#6NejlCV=C@^}SB@Q3xwMie~y@7gq1oX&)IuFHGg?|zYuHJ2h1 zOP6L&a|mOqz(uA{W%e0vepLdv1VkQS!gwLXWX4{~46M)Go4Y<=Ubnp5yN&W=#*lqh ze8pPv)N%j*TM!Psmi*pj#wgRMK|noKQ#PJ(4<(q?)!Rt`$Ncs+TO&*nTKa$y<@VXW zN$&FXIMH31ET?ZexyM)Yn4dh6)U5@$qyoPArFQwBI2@z>dU2wUR1h zPdRpM9?b>E#Nn$9bNtQAkJOvfY`zkyV#Rn{QBvHF08E|eWk>395-q+~SAMIp6=h=5 zzb$|$QB#({r7z>nCsK7Thm-Sm@upV9j;|(ePN@zOwZHgCIsSoW9V+XU`uxhyr_^5h zb**%5u=Vr}j%nQagG%^a#QQ!9ysw(4z=a$fu7O^b@S*!9p2LAtvx{wKFF!|nuhP%` zORWAqZRyDv>O-1qmg_3R!%T6PM#Q20{gk#khSb(x&4Ii4p@{+_(Lm>wxsVM)>isY@o=Md4;54Drkty}Eofc;`;z z^1Ug^3~nXj!b=jIP>uK?`g;x1fofG#2a zk>SiF!Sa2l)9SpDf;wS=rp#;+-Olheg^NCC-SA0$-{z7~m;=KBU=V-)wev%FLDxY=>?uJG`5ZH_4y&#uDIb?##aiuD;Mq)MH*48e^`w zyM`2cuGa;;_gb2Fx$O=)86jdAU%#NI&^6jQ>zSnKTES8VrZ?<|5o%3wbsUY?+xGY0 z8$JlR&}v)&b1M5;v^T9h(;v|%SkfuI<3|R46{wX#1$;HU&O^A zrUEy68YYI&-G6#MJ9{L0-wADdnWgGlRaw!PJ0!BgpubBOH*0a5v?#{4`Ma4wZl3?V zji&aU`2!?|>QYE#)!YYV(0SY&iyqgu$fhSWvTx}f$U*^X^e{qj#Y z0;_rIN~&)PoVY?)HydZKG)+*&EcL3LJ_o4hBzwp?vVzPfS% z+ZoRsFU-$a%)Ti#B_p+C9L*HSjEF$&>IUJ0Cly8)t8`UW6%LcWFrMmM!}RpDQ*-@a z=qx5Wy(4+2k3BB8gh<%H-Sz9D98hrnJv}KW)baLj3oSkPPoR*+EmlWt_oVQKpn69xahqdLI#4)B24BdQi9ygM>S#S)2nFeyn+!xt^0ysrk)s$_PZ%shD1ZIW9(WFqW2D|6ZGa9_>(B>kJD1^>h&0jYmQJ zPB;Gfj2MmoMLJP`{7sMic}d~+ms1E0v)K}LLnEVO$K`zoX2%01ka{hCr$Iw2WME-I zFP~e=W@lnzLd0V)i3D*ie>c+%GWw6&jdtXl{n7ob(o$1BRdiqy5)w&#?(Co_sib+f ziq3)^&(zd(-Xg_+m6-Y2lg&9 zs9s9d1&8MwGLB3ofEY}!rvRz&HGyVS>)gz8!i<37@5&IrmmDaqd}h-FRq$OdM31p& zt^G_<-g1V=089@E>ES5)VHmpMzW>{t_%TLr8Vp6vMj4i}G6_Bq`6j+tqmy_$FP$oJ zV&nwEVnu1ln*%ou-Ash*7kiD8XhqJ`KdfwWrRefEB}+;g953`PYb=>1n9F|W=yLgo zcx)1@>7>^qEVTdKv)54Z2jiC$hls_IDzCUOqvM&eKPijRvf91JnY7DH=Fdc#0ruL2 z_RfJJ5|TTEl5ULenS1K1nHz6{87YvfVjHs~q!av^a@=gk_s`!e^t`ULC#Z_8CktEy zU7G(0@)a>Bc7#}`A`|*SB$Q=F9FSbS?5evvB`ETPPxLo)XQPUL99x48<&}dvo zwZnu3NRZPBuz{c6K!8`!Sp@k`t-4UXLsVCSk@}PuIBI-k?{x4I5V&9qp3oh%;`8z6 zd$rS+oI2h5esPSiy0||kxi{((FwsoWGZbu~uN?Nx2GGT(z7xWC^O)2-1= z?)d>p#u)+hDt|T>InNhV_Kq5}uF0=PfE27eBQ)4qkH8dikK$+JV&g1!Rny972!!m- zt`K%aEo5RnP(6oHAXRy0)9hFV6hieV$aZk?ra6CtE+5k!KFloNy&j)4|8Eo()lm42 z%{?oK5fP?YqIf}lD~EgD0dc$`{Y&cGA6(tR^hLm5i$Vi_{RzI3Gcs} z_|NoO5M1!dp~RV{fEH5)U6uV16{3f@~Cm^|(S@aSc5Qu`RPrLgE0I(6G<^n>%V!^B|N z{|oJZuZ7@RGArmJP-2MHJYlmGImxB#M&M01W5E?nR@0$80!5EDzw8j(R>Xr8ayN-WmXv=k!0_UurIY{>LExXa$+{gDjG6S93=Uy-H7W zuj-{<(dNdJWprc(O!jZl2VIs-Kgo0yMMZ?)asO}JJ9ZvyYvZ9m8q zN#{HI*R0m7l8Hd36`?+@mm%uZF@zSRw;;dIcmtG0nWmti2m*8m)yj+fEjLoq(HyW^ zLT|<%zH&N?tEbj-`mLJpxB*h0yS$YCYjq0i}DT-bGL(#^8O zOKWclmtHc)j%t;Q3EQ@D>Z*qD)>qg+vkoT9&-^c0FZ#dB1VC;`w`ee&915$j=U!y* z)43m7%hS_T1YX*}PyRu$<-1`ZukA{q!y!IWhoz#798FPs`Z4gkqd^Z-O>3 znEoit{@kwYr7M`oWqXFaM-C`z0L>QT1 z7^1u2p5IV|7Ziss%ka!a9Imy2Jh{Ic>(B3b&-epU)9&QTKx5cDP)uUCe22n!CCB1c0~<)kZj4>cPVZ|D<8FhEWxK1nq>lZj zx*)(ckbdl4au?A<j3M(n0vueGbZL$aDR=bX!s@<*+u&zz3aoMIkkSJ|qK3aj5qqJz& zvuv*M+!u^wxu>P;cOWJ`E>m7pI+1EY?P-HgiNO)1%3R}@A9!0e&Q0;sX!;q5fjX%~x ztAJznx<9${z1UQ}v^f!kOIt1I%sBHOGUfzy$B8nu3;z3tLsS+yl+P|rOULzVAPGG1 zk4tCpHugT>gLn}S8J`>)$v=1z6Uxuz9in+qd6_e`&Q*>E^typg^^ALIdwn8Mx^%0b zG^{XkWF2bVK)m(w=s!UCiw*c&Z3h6Q-ERs?m9@1;v2{H|KMD)KNz`$pM(!7M zV@38qR(JJK0XOASaM^pJcd+f^GI8ASwm#j6mvv&a`N+FzfN&2B=08oca^F2v%Uj2v z2*a*&Hjq^YlaGZKp4K*AT6*nA~HLKNG;HL998(-~B2#bnVTdi;x6&I_wd+|L# zT<2tEflaaEa@r8{I34L7&XztR$yIh#Erf#VG~!0L-`7n9L8Hk7U^uzaVs6m>Pwad? zf}95F51bD!i}8`;$jd3 zYxE@TpaCAX>kN;c8lx|+cWPi%a?cJVy2IQoiA&$sT%GF<-NT#{%HGn8Ew0AK3M8u|DkBstE2j~ zG`mH)yQVB;*X68O4O zil4V%qE2Q~BgO!wbRF3a$66V876{6vX4dPt{E-YQeB)5sx3B%fbXuM58EV2OFL`tS z(E@ykn{bAc$n|=5_imy+_LZN{|1tAE#PNF> z{z^Ln;n4iuc5}?wxm$xh@kF@q2qD)`Zh&IwcACJ<7VLki1XQp-E7S~sinPXRWi~jsj6LtH_@85j- zOk16ZwXx6TqXP%P0qgvv((>rNY(MwRdkLhW*@)KvcuVE>pTvo!) zyr0p>m4%TtL7ZMsUmrw;=@f+<$iVz&yet=MLK_-5(_~Dl%j)S6hO4NksE9v&D2*&O zUj{LLt5&yIfB8=PA>2KP(<{h^6bF2XkvnxuRykEw-&A#6p{AN6Ir3$XRQrRPe3EjTD5@_UFq+Oy;y*8#;VK0yQPswC&6%H;xtU8T+L=G1iA$^G} zZn$M|wv*^2dpcRjRho~*@mM@Jba{*8Hj6>uwCz&s&DO%*jd`) z{6?gGySCPg_@n&nl2j^py2v25-C=3|#D|LX@m)iCj1o`e*T!gF*;GhM-R>(q==1Jl z?~RpfK?~bwP6H+DGsKM=1cr?+Mdq`bgOz{$U(mF2apE6qcL2K>5kGxTaWs^k+WIC* z54;#=FxeSN#=yd|n~6`1&B%xvH8ucM#El-Yg$|!K_z#k;bPz8mwh!Xkw;A_0#wK%L zdNF!p9M22Ox35|}uF*Kj;K{sh!hG9_%3i9>!QmSKpQY~@%hDv=XwyaM6la^ooodt{ zb@KbMUR0QIR?~^NkLf=w@O4v^KuBq)o40Zgn>Wc7EoTFXlRI9s9d}IVwA64T7wYNI znoH|tQCbQg&A0R8OI*DV)A&o`S_@zN_ts4tRiv%EiJU#dk7uI9PR#Yowzvl9NI2g* z*e+$(7ohMOYGg^lR>~Sv1$5bil2+zUzoT>To-wLs;`^dS084bnV{3EqAFg)p44BUv zJP`@mQqWgmfRXvzmuvqbY0% z^-H4%GsT(<&5?UOO7l8mrUl=mU)`fbi9Ca)P5W8q7e$oCp=MMzOVedUM<<)-ZJY3w zR3G3zS^6w~6+e$c!f+z^q~UPv*6cRFDapcEpEh}b*qfvGdGFs&>`gYar^&cW+jsj8BeflT-1Ps4`~b<^l#;+0 zZVeJi7JPDQs_}j&6_3w*N}3}kCT3!2RS09-D(FO9xWqGl?S(yDG2=M`Mb{;6DG!k> zyK_d`uy9ll6?YET#EQT7Wig|KM&iO5ZH6lF>CMtbo~Nbl`9UKPZzk?zmPh;Bqr*N8f;v}IMBHJ zTE+~%7g;J8di9kRxKDt01JeuWpQO(Fn(nIOu}^;^p_1B5Y&XEAmF&UA(8d+RulS%> z>KePdb~1=*jnp;ONV%KtjWVU1)@|yXDWcJX18!^z-(UC3F<3fC895mxvZu_}fuG{hMtsoaqbKX59yPR+{?L^#x=bEXg+%?{P z{J_s-!0?3N85cXR*LM0xdu8J#lf%-pOarv-YGxnf>yy>{tM*V7dkqe@sSv`>Qyq^8 zo!8c+mvkPM^)M*JhevxYp7#*ldp-Nk&*7T9442_$>EeX8w1;CJk?k)<9P}0rT=x=X z=WF8?0~j*yJ1|dRN)=BFg;&xNMt2_;(w+}CrB3!Olr66p+|vh7^9}7+04M}3n}_{;MLD^T zpnwXbRX9O{PEPE3rd1$!5*isFRJEw({e1m+GJnfWPU0at{0eSNA?XT+W&JsmL(Rtt|^!B=gn1G`g&NE1o`a{(xI7k`n+g` z^2~~)FGs~0TR-fp8qN0&B5YOkMTF74V{WQJg`Z8hPnWyn zyVHuYmhz9YH6SaP1WLome*O#%1Oi8!_%YxCDHQ7J>Jd0h*&r0sGBY!4UiqDf`ayPp z3W|wBs;ZdFnht1Anhxm`K4^a49ZSdMb7P&Dm?+V#j{;Tt&X()SwtGE;z^sE+8Z_*I zC<31OCP(v4aI+5xpmJvPnX>>OF{yERPP6PrNC^22aRiD*LrxA}d$b8rE%^MhaDO8> zEQB5aV4YnK3Ft@1n}dE16LSv@4>x#uy8mGHFR4tfdfk8@NOP>b>4?B(x#4zxx!;A< zQ^yJdOnX{lktO8Nx1f^k4CsU26cD5uIDc6@ zI>R8g0K?{cvcXe!__Dw<1{`NuYKH#{ivKvo)H!d-M*qh^qH&4+e{i<{-tq9KcPjQl z)E)b$!v9e-jI0dGA9;fED!&pewV|P*fcXl5rBcj4UaiF zFanoTQ0O{Zs7~gz)nBOvZQZI~5R;VbHl8xn1cko6hu3wSh@>7CC1BvPUVWAqaB* zoy47bUqSgtH2A=SPtz;l`z@}Q2cMLECMOl3Q3yvCOfpv-`c+`dIef+!FDpP%4^zvx zg>s8^NZt3U&rR55WGG{5H0)Lzef8n{Zf?3K_y?V<5$wK2W?`OKSb8|@U3@a6+R%NS z)P;oMk-FtOokoJt(Z}OR&*_#nC}{fwzxXiTc4K!q?G3&j7p>refAK~!&pe+Xr@=b) zKvCf>tUUVLw>HfyF1&12?H8dkOe|1JblfWX@66~qgK=+C=%TB zTZ8Q<=g)ma%j$J67c>b+uwT_?76rpYjx+~q?w+d=&Q%`n4}jtg_!{J(@bY&7*KSe_NS{W4EgmQ8q&D zN(jFzP@=|MOmEz+P4X3xTf~0>-xl8XE1G>e=S++h*7oe_SoVI zhSlbaa~a{@4`Krp+1Ib5rKhfU>)zk?6;>$Bf~lzMZAE8sn~je#Nz%}+Z#7@QFpVW2 z03bqe$KRS|Ax*nS*#ues-+3?5xbAmZ^jZyH0}-&<8>}C$_N6lUTNju>_3B>jnF^Vs zWbNsG@|ZZYDXw#Mhv~a0i_4c58kZv6*__T2x>3c+G@!al0)6*kwK}?3SK4qjbu&Pq zh|M;Xe}k>VdthDkDgVL%UuI&(4D;SZD*}g9l=1aaGToVfeEcBS?TOx`I+;sHY$wz! zb@pMXkh+Zu9Wrf4kagYpp6I=YG5{TysQ;J+##Y|iBz@l=>6>CK=dKG1BJ-W`u~UNT zn{$Y^Cy!P2s#w*zxT;`tX~8kdx#t#l%|! z2MpA!s*Rk;}JqMNZBM?YId9XWtiau@!E@U7Q=8 zWZOOpJ+tZjDF#i>%{XM?L6VvUr5AfWY&v!(Th1)eTr56`eYuE6`K z%k;n}O4`KycFCPnO3|;C7JTj6Dl#s1ymQwaYOQ7rc(oUWA^1Km`V8&vj^qZ9&f5ot zLOzQt`JqfFPGxexR~(2fsq5wsv|d52Wdl+xLH{b#>t?h`f<_j-1lJ}00?=gtEcsSx zc-U{7D}If~V2|y)myd)RovM~Vkb3TR$&!wgS6b)pf>Fs}C1%QJuFSI0AH+;Cy00aaeA4remXS08SGxMQc)~B?r+^7?+TAR=3a|BFq`oC!ff1>)H~?85>kQ zJQ;lp&d^GLFzXp2=1WrN%9`6g(>_kZGGEYR5RX~f=~fbY(8Z!@Z^Za$#Zs6 zmgzbx*sv923Tqdr$_|WHNzfQDgO;$e_wGkt_xt5-Vs8Gh7hAnRk0TnmO1D9*j3MT` z-V&xCqqrkRwjWac=4`n4H=r#9T#e%A>TAG?Lh#=RWX>l7Tbs`oO;Q{71C9Qt)Eu%1 zLx$Mogm8jl`Fi=Cj;}Wm*we4L2%z1=T0Uq(vdQ%zl)v_L6&a+9i!U>i`>92P_hQm% z>kbt#!U7bl^1nv&uZ%vf1y?YFr}7nZ*f^&2)@*L<1CkmTLy$Rag++dH;3sVDTt2)_ z1wJ>~dX$nHB-v@bVaSWW7!a6?VWCSqLNY>p0BP?but4$0XkD#3uj*D7U3@R@`@?qjs^-MrN$aOK zwa}o!6HhTVn9Qmf^FJ_wC8o2B{YR=jX7$L^byai-pc1sY(Ve5W7m}WFE|AizVYCoi z7_ORFP>bLRxzWeF&sU#3{N0(HeZtdI?Oe{x1-gTU-vYqq z1G@Mk91_l-yjhYSjkx%NZ#UY+Cpfz{lU$v!gXXtK9t~k+pVdBB%mzwBXD|m~%S4mA zT9bHde;d}%M9*iK*6TkQJHCH99_DMwgf!^CHC|PI#z6<_ZH0O^aIWePs`9u1L^%~7 zxHRsBoER@61eXO^BQ{DrG9=2g#=%f3hh#;zh;alMLnUPi#9rfY9RE$Zqm8PyxK#2v z9!%eq<@A=dTu6X+qV%*V%S&;&zIlkfuZ!#p(ecIbC);|#*Ye!?3^@9b2Q{Ys*;M( zD7(6X`x>ufF9-lYxNh4Jjmyl)(C}+Y3j9Y6jd!t>vQ{(qmRzF3TY3_bk~!9EZ6F(3 zvv(&)6=0 zow%~hgI&881pLGel{Q<`0cgMgwu%*pMll;UPl9gXd;X$G5eQEF9)ga0(7sEgS$fh* zh4b_CAGx`;5BUGM(lIx)K!|Ar(dgaM%xv&fg5+jR51m9Dj=5)xjqkKl!ooKo!d%Kd z@n7HPFiAl`|1sVE5^2Qrl=L4U0G<6%H1j~#_~+rEvzQ#I;KM%)q_{AatvEm%;fiWU z>yC}v|K2$|Ci16KE*1~UN&=Q{+I(sr9)qlA9upaKS2M_eZ$2Cl%mb?hfB9I^c?_WE z)BY70iiYQPO&z2HaE`U}e#14sp~Ra*wH7-BRsIVv|3{ssXNxf|uMR+&80dQu#ARjk z3knL9cR_3*GiY0)(0}~-VXBX%okWP|kN3mxR=i&Y5^VeC+X9;LgDXKP=cr#d&H%oE z@|4z$qkKE9&i(Paz7Y_`WwiwW`)FsOke6E*DkqAVD(*%xS!EOMOc z_nGF~PWYQzXx&m1<(X^>bimUD&Y$%~YF%n^8{G)vR+!Cu%z9j*nO_LO*vg^phv*v^ zXgdCjH{*Ki5C-N5>^7xY<`)7^r>{@)@6NcH0|N%n(Nsl_>tEmy_Jg_ZsRCa`3HT)wnKaV5h@ZT6ZhVr zTUTIuZCo7?un4tw9=&9>nOO|amDE`BdxC!*2Y^3KA*Lab>&2YzJvGVwa!a`%_XraNwzfnoKW;DKv;_{T2>axG2&)(|EV6Q8l z&-%63o2V&Nprsm9KrgY(_+`0qL{r%>GFp3BccYAU%;-Rb<80nN^~U)dwA1DF)0*ve zqhjM(Q?ObEh1xEZUd;3U=JMr{LY2THp0k!WB#OsZ5xwE1WzSPhkG3sWt9CJsw6|Zp zKWW%R9vU7_7Vzd*k;k%rI)Tt}y%+h#5sYR23=S^ij|bH>oc$C+VH42PL$F?EjGc?T zY`EPQus_anuxi~$s#7v5z?2lwBd4@|CL&tDIFW3;3CkBNuf!=tWBIBmLlD$&PiHdH zkhJOEM735K5Qqm4$L(&{wRJ+*dP#z1lu+&3+0C265j7PRnQgN`rscM)5v2WyBfI8I z*oj@fK9L(Z??k=!d~9djW@>kGO1Pbo{Csvgkb7g%0WJS5vlC}vaE8bom^qr#t1h&W zI`Esx$yMw>tP55%GSr8fEarlbz$~Tz1*x=$%#j|6}YeqvBedZc##ly95vJ z9w3c7!8N!$1b5fq?(UET0t9z=w*WyK*Wm6noWUSe=! zVz)$pjQYcex6>Tlkjv@JcM~o5t9(t@MmgU5DzGhIl4Q6Z&IUA7JP>GJV<_A099tE| zTLvueY6*B9s|nnliT5kmtIuLhr#eu4a%g!S#djta(iG_3(V=D3uitax=RiES>cvYj z*Lh^8BShkai=>w&F>xTUzWde7AYnKPAJVjzNRsCDGj{GdW$e(S!D;<$5)ZjY-Y@AH ztbCwJ%HzUl4A;L|jyHZrlP#(KI=~8QVra>C)kc;?<0_%)dLoKS>@J6~9vM$Mmqx8x z;5n5D%TLjl=%3sF>+ey4GR%+ZA_a56x3dv=o|GWj2Ff+R78C@y9L&B4RCjzHa2PfG z!ACnqxxSWNk~lEDoHZ9MxZLlLb0C?<3fuU0s;L&yFe1@|?wAyaLv*w~{ma#LqS0J2 zxeioqKz6~d+#|OLE<}_z)uzE#lwKhGPq;$$qMb2VwV|6zhxezinGNmy38E?=Ato;7^H-nzo!y|zh<4^tXx0A;BE*6anmwXY=yizV! zin#5qA&bVCo}J^?=ffioo8$$@WbGoZCox~`K4H7=p-u_j2c5LBmIcrJ_s|yee1zNo z5>y08BgG2be_n+E4EXZK4Mg9oQvI2hj~_qQx$97vL36gB!}~mW!SrAmg%i4y`RTQ$ zKbFA$`s0f_b;1*`w;aO$a52euu{0BPTKn_)H}g{nuJ1Dr#YtmExIu|+w-LoG)?o2j&4&;^J@&Jw>bj^vp;flpjZ){_hx{NYD;lf7IzYOq;0+lJFUh8}g zkBj9?Tv*Th>|?Xbfw+9DE1d-d2H|t!M*xx@I@L^-@ zk+QL|UAvqXegFR6<9tgkdo{%g(8?;@9!X_)*yx3fu+**rbp#`+EapHd?2(#VEHVG$ z(c(YLFk7i8t@}nODJjW*MpfNmg8!z{a)v%3A%Sb}TVfaxo!sn?zV#LW*(~E(0$9-ab(6KsZeyjG*hZoUFGp zQYJyr$AN0UDMLd2aq3w+tucjJym2W34uI6h6LNd&4sh7Dd}96s1SGw9_h0|kwrzs( zha+~+TWODEZiY9|cN4x+w+NH7z4sVWfgQF4ki_@8+Bk&4NJS_&G;C_ckF*kx(Aw<#Z-vb!UC-;2ssIm+|lUlPvm82d%<& zivFP=tACK#a0w8IS@OAA<~tox{u7Tk=7Dw3>bJtMbXwz(1u8*rCio-qIR%D7@!!@JE~41z_Coy9CK?t_E_Mkk zHv2ogh1*pJ)hCwvYe<-PSJ5CDd#R7vC)H{f$4)m+n=FOzx4Q}5&o__UZ919Fwj+V~ z(WKg9LdSol(}<#ZU+hsH8xU7a?l;8^nu`3Y4=NNMv_fw5>)v*vmAL`!tjW%7nd8e}lHaXEun_fsT(vkEB zH}H4&)U=$PeYiPWkw=36RB1>i}S zr_)W{wB(1bV<)Cuem92PM|X-%nns3$aFW5ZulE}cUicmxQdw)Thx|~NPgiYAZrc{U z1W-;Mj~wtRTb0Y){$%kiRhBZ`xYt~i3W@){EM|+LfA38fvHRR#f^wh#e2qO{@j6jb zQtARu?=)Vw<8~i_q}F-ldNHjaSZ6>P8IYa1aJL+ph37W$G*(q~9@S7nQrqABP27Yp z93yxOJIQdfaF0sn9i^)RW%YiZ;uHOf=Q&x9t|jYv5Vq?blV|dSrT)Lt1;F0Y`Zg`Q z?v=MrCuC_!->~ee{q@1FX&dMM`Uo5lk6f^k7?yKOSqcHw>$))Lbl3Ilo6owQ*;X@P z?xmp5*dH#;6ScY$=RTe}?hGsq7t}Vm-=lS`kFI3zNc`94a-4UGK>Zzvk)zgfG0yuU zNo2nYI49a%5yHR!T%;W}hwQHMML)0*OK17Pt=hS;8mVkAH9tk2Nb37hBk=qD^ths0 z!S|**K}IU&mzGtB)zFVm)ECzL8O>WVZhFXu=r}Bim+a50GFo3DuvNqKDna`u?!S)A zZ_-5wis0ehi?h4kT&JCMb7*vY{Gqq%I$x$e3>2a<*uN0!dju8vy214L)x=NzFy?wr z8F2R&GxaA}o)Es*rE#1YXrffe?qQ$M9fMamdQu+nuW59cE!7d27yVO zy%9xNzNud$5$|qnN3DNB*dKMFXfKrf-!P<&=OaK$e7c+Pn<~@h)boS50D3(AfCU~) zppr>rGerb=PXPGCeESwa@761=_yB#r(Sf2T6m6iIvApByUR)e>ddVBft0$P4DHDMZ zG=TY5?QNXiJq{r=%%Py8LU``!AIU6~vE_q5UB5#G4Z+!c8u1Qd+$ga8$z2N%sH{?1 z9HD-YQ!8l^Vk3U}wZdUtR{=7ltir;}|K=+ce-#j7qN7_cDJ|c~@j5mHlqM;us2rxG zXfUv_dVq?+vpa8VfJHgC&RVH3XptCk|D2+D9kr(4-hcWTA--@7r)nafiCzw@cZ|4*CxKe_+(|FambgbVPw zX0<8}UI8r4(uU=2M~A)dsZ%xP6Rtm`#l$S7|8D^pNibmU3Q=Iup=-i(u%~NZ5%%~i z4(6SI3xTbBZ$k)Y@QO^?=LM8YB%tEvJpoc<0L2Prq`Hz330(h*mXUEw@c9l6SI54q z-Pi`)&mre|eHdQMNd}bu$N@)6Y0t0A%S+LJO5`NL8mLITqp)xf&?*cDhOqm7vwxhm z8kduERS96XWVzyJP7Eq(>CTmHg~gIG@zkwK z>K2+GX^3^+nr!WfHW~gXt?J-@T^a;)(Qw+%8BzLV4wYD78HEWSr%yos1`jXDOQ$y| zGdgxg`b!kDt#<`FY|(it-Fp)z?U6Eld>sKRc-(7e4#CbRxULjXF4*6|zcpcaKsR;W zIRX9XTc3I*{q5!Ifd?OF$b;WPZdE*-T1FTL3kXy{1UYcSo+^tB)lir>ERp;hZhYHj zEa{$Rz2;2d>2#gfAVZp7B#CO)!C7Ai6(XR*&AXc7SZ08>w?Q9xmE^$vLr-XCHk~MV zDZ#4_{<%c}UK$jh6#hG3JW_2L{2!et)X>+{97E&dfNEL8-Iv!ed>6gqPZ;+0LsZ6% zyYs`9)AXa;Pl9%vkhsKEy$?AD_jSzmm#J!}SL0COZ`G#Z7IE%cMl_Z7jnuM5%d$0f zo{*X^`)w`Sq<+$t{j50c0VS+c6{xRrs2!)H}(oigpKA%pd* zYR~T@CAEVXGYR!I#Fd(IS%`Dw)08_D{zm7HLB;aiDDyY3vQ#}*Q5*6L`t#)pi)wf{ z%9hOV3^bF;N=#LKakeWNyGuh#A6N`&&?{}MU0!PWYg>TD93ny%(1q^zu%wV)VOFhn z*WcZbDk?P8n;sP(d|mlmzOWyy~ph4o=?E$2Mp$^`WyI= zrc;hM1Fe^g@8+c0AW2@gJ?6IM9brLbue&Y5K^G(QHpK3{=_HrT$c}h8DML=rH7vpL zRE&pyb#4L2^exCX_N(tN0>n?4tOyl#lS642;x*2Qz3!H9d9JjQ;j5H9-MyV=cJl8n zv>7DNKz_DgGk#2j#jGbN=S86t`px$gKnI3XByy3BcTV<+ibW&Mcac&F!@WNqjuy7_ zM+{B;v%fosF=jd!yQ$M5r6X1*5nMqY_U^cQS;!ab9FCT=WWeIj`;)of2l@E~A7ji& zyfcS(4#~@ToWi=5|2_w~9cOg=YpX+{e&`U+j6%)-x zO|R^5c_~*~oH0aE#AVhQ>;?$DOPoIU&V>rOD~EUhf1zVlp?G2^epP108shGw@`J<3&>1C< ze_rZa5}U0Y7MUSXH{KS4Vom<Tz$^n*Hs$v zOgt?Ai(MMT=Kbms;(ON-*m18G0Ql|2TtVcYl(9!vkBLUtMvwTKSws8!K$B-xOO9ux zX5X4w;j17mOiLHG#H;tRA#N_8UWq}W8*PL4bZQWN9TvE31^d4oF&PihXuBUCe5wyd zzQ2~)DM=C`ejbh_Nqdg1@L*z$$35N;ZTqpmBojLId{M_2ceL}Y%b9>b1Uq}oSPlWB z&R(C4@IEJs*^3%qsj{_DvRYX}&-)4tEdx^vhedt4tzMjrB>z+A^uyfG@U4((UGJv_ zJ>SFG#3BhecRLT_NTX!9Sn55iDi_-7{OzD&X;32v5*OTkn9RWLK7D-cjp(K7L^Uzd-7D>>Cp|`u`@gZx zzRxp0I3lt9L{e#|tFvxR(Y-UPWz03#TNp+1TGrwIPBV8^bvxIRc{?YM)Z)!D(bgI- z0n$PyN$<9k5c~B35GgLdB60Hms9X^WYe|&cdufR34RgmhhWzT)>`#__bTo717)5vb zYOIn$qTkwz+-ZM4P@sgYUlY!p9OL&7|!oz-;T_@ZsmKHGwn_5U=D4F$bSxp-1Trf zG)j}x-A?1I=*EvIBqrQmXF3kcqB)tr>xnYaIJr-$5I}-5I9ll;Bn;s4`euKe_ql*E zaI>9d`>RXv;k#Xn`uYeP-o~p1qG6=gM-9uwr4HU{Py9IjCc$cTg`AdV+~RRkeF#I~ zOiE<>S1fMOLY}z;S)>~Fsf%meS_%Kp8szbGS7f&sB$~>ujZF^^6us%in#{RbnD_|0|%m`Gk;#3#Ewy;!iU=9LIRB{Hv&n@JKo&mu=Os`A4E5U8zYQ#YN&**)?C zPXw2iC4E3&m9;O#Ck?iw22Q(cHTeAB;f+1t`B;PXM$tT&vlax@%#w{!iurd|uDDy3 zOjw=0F=?();S^ws32&-RoM6l)OfM#&|8Um}D(IyN{cf)zPp>PxHXfIGt~#6Rk@6w@ zIhh+jn0HCEqOU#5(h_>>So6{SL@ef@fOBx_&b>SP=Ss#v>VZ?E{U<>qik{zqfX83g zyMQlW_SmZ!k#tn*3*L0W$pncb>g z%3|e-xH~!8@VgM{McEr~43o`)=`76qB>@$v+E_Ah%`t zzawqv?5-AVJv;VX`5~}szjmc>I}7s<7vNz*`LiKDs;3)*)irljMBC4X&g8B9(9-n4 z16C|du2OXznTEHg#_dB9HaPJREIh2Y2AalKF#DsaON@aS#Y!su6T^8=qaVk-1 z0{N1c3#ncqwag-xg1nGg-&kjosM&5$B|i-CfY8Z1I%PURcyXA*(^anQ6>u!Qv!xi_ zo>UHo(#&XOW4jMepxk?8dHl&>lkK7@1ds0Q(Yrg^o%ZSg8XTVqhrooJGM|!{)Ai-z zp2ElDf<`^`*R|3X6(LJhgunKqp1%#{e>MH{kx$Vo2Y^FF@rzVK!Lx8hGk=LonZlLK zk(B7rbe1E_h}K7&E@;%tk!sw%?c8HMy(`0U$qNu3jw_edY)$@XDql{3uiz}c)9!Ot zwcdCduewGf`KBC^q{Z8yxkoC>ajFkR<#vdnhRo<0`V30kgbRX9dorCkXHK1{p&K(T zh5NO3VVL~>YOCToQN-H`t;c@y!)zxlxwa6ZYTT3!jokAgI%nL^VnLH z*6Rgoy$9>W=D(DZUuxPc46XXxziRvbctKS06iO{HKWtQ+U@hT$?5m6B2g=*@yt@k3 z(Or0uuK^~=qi=82UUzL5zIWV0@Q_b79{$4(6|&S$_a7rYh$WI=<)+k9@&K=JU=EPBd|#~cj57u-7UmjH+HGpD%Q;g<%4FL}5^i-z{cKSK0y znDi7<58)kWkH5bOvo)ZUa3p8HKi+65TUffAAl;>cyYnnfwDO(F{U*j~m~?g*adbHv zzVj`yfhL_FVXIoEJoiPzE#8?RHD!AcJDKOeJP*ra{A{pQMu`rH}w0gw> zHhh5c;^K$Vibhj*2QL=>G3u#tVPK@$<$9WNLK?B^sP?M0VYzNEt+XbAzJT>T> z;UyNvZUtH?bJxp9Scti77wTVc?r%YzFi-59q{B|jlZ+Y{^`plG#+xH=Jmni=n{QvJ zc*6L=y3eOZr(?)wIv}IPI9FYRvzH)GsCui$N_qsHApR_l_bCGPxi`~D3(L;bOFsvn ziutZ0vE>o4FH)b)&L3DJ=uYA25Ji?MeffMnIq1GqwKg*5E-xG59ep+-o$ldg54C?j zwRZ#^?I?^O&abC=sLOFTwXQZX~`rF1wrY#%)~ zJNxJfQt;Lm4gweQeg5q=Y9$gb*Gf!aE=I#@6BcffmL-;c9B^HThOae*A-=&R0>Vc>&8F=m8F zDmuCqNExFB#i98|Nb*<>FbVg5)bSK`EJ+lvlM8fP&-9W;*U&N`1Qhu)r3eazZ&S`L zS2F~A`$jO)IMi9z&@mKy|8!WlDQ-NwU+nMKC+@_>5qBQTmH81@MDi5gakt@q9h09$ zp!sm?7#cZ$+MHOW@)YG`$ZVt|UUmeaqUnlIt*=_3l#Z~}T-|}h@4D{mvt3z=9dc^l zdWHrENr5D`e{C%XwL;EP$pzRkCTy^)*89#8(5()$0W-DZhjg89kEF92inPou|Nmnb z&1M^23*iMxgnU>u#lyjv-NJ4)ON(SiAwu6l*fmf?ppKtJQ8x-{3bW~xj5%f9II#H; z79|j8;YL_dVT0VwSC{McJX@x7y=V(k5nA$h4{^^BXy0iM@#{z7-zn5bdswi3@cw}7 zqazH1I^LFtJ3z;mEKe&SkW*V*tCss;rv|0sgJ;|x*1Ge; z<^QTs{^o+6H){aK*>1VvXzsASA=Xh+!V|}8Q>zE!eDO)Aq(J`5YKD7nZ_oeVfjR7LkjxG{x>EsLu`igYpj;1?etj22{ZbmB2s-EUtOaBX z>pSsl5U$kirj!(p`$XMAqnmb>D$ zd0ttbV2Z_P+(Xdgzbc)qw4sf-05N__<-nts2(kX#rncbteoP5E9lF8wQ?v8Fbf;9LFwgLy;n|O(9y{E}lTP@H= zaNk*Zy26$8Mmuor4E5T(qH1EcBaUCyn`t{A9CwL^WtF8rdelW)jh}Qu6`@oOE!~Wi zAL_NluX?M-ph4A~FWKs;*}}8g+ao*laX%gla?b~PIrKOnT*7n011iRS)n$C5oH^;( z(O86@Mdv%FULN;XM~wBI7@56T(+Bzo3M+bie6w=>{d`d?x_cyg{eJ36Q#O+1JsY|~ z=^)cPkH<|w8-%`UkJAWUAtsix(TDK)LMp!yXj)=TSdtoxstHnPYk_ST>8dC~wOQ>3 zRy>dYZy{f=RQultSc6t4m|N&mC-du*CbDchLF*HC@wYK`av#_ggpkb-5=Y1_@G$3o`owpw&1Mci4 zZPteFL6ly|BI#OVj?Z#v4XqBqtUtVBr4?pv zy9o=7S0Fp40zRIUNh#eXZ*PQ=Da7|s)2ysk0wm;)D#Hxd=Pl~$Z1sNXh_;wHXi3d<<AoTQv-*dee(uECu`itszE@ zO8yd8nLRY|#^2P^^z`=dX)Tf3);E1qGJ+q+9Z>w6JZL z`^$21;v)lP#*byPFbpp0y?qz060tBocKoIl=dC~M4f(8>g)REo4fW>x(Fr6qaBs@HrR}%+nl;680!OozM5#;an3n9JNcSX@pW``6tew^j`Y2g1(Q*#vP>9N}WR^K;#&wlD+w}F#g`UomnF)ktwML04} z*Q0~OMD)jgJA&bdZgC)8Q%U#p6syvvTbKGwT=~n^(-HSV-X0Uq^hi9$B} z)haTb@n+)>0(#2>8)Gc%V4>~$_TuGRKN{EX=4o=lbL69yU54m-6>31bOM+dYF_Bx4 zq;E-G?Xz#8ZM+y0*P|E$RA*SQZul4p<&ks;$<*X`*mEnns%(Nm zJLN_#ANi{jv8%cL=a{;EH`7}KJOQj9ZPz8Ux^KB_dAhxfEZX*2Yi$)hX+@`+E57dw z)gHUH?TGPo0LS`^Jk46vvB>CYBArh5?AlYBAv z1LXf@Az^eHHBQ~ucp&66mx$GtT^J;QTOu2kqY)CD;_*f z5dO&LF(_+aRk68>U6|jxs&B!}{JFZ%Nl?1_r^Kt~#-;-Q=W$Dgy{cFYTXgW(4-M~V zgY(H9NnbLwtliU=XB6@S_%rsB1j`Lg9a#-krJvrk$UU>~36_wceGB@t0uHo*(`YM> z%i6%Z4zf<5FmAdP!>eIW-K~d(pK1Oyb^`s)hIZ}IRu_-20GGW$hSuTZuL;dg3JX2x ztMZoIj>dwOx+wyl6)3QM91m^qDiuwf3FxX(47lS*&Sehd9M}Zoj{!L)6EO? z85B0LopH`TDmFu>PA9ri~69;ydl{Ib&lFJz(rm6f;6)mVRMCI&>8OVoGPry;t-7ST{?utP2Rm$@~E zC@jq+&Ceu1Te@#);^i`1h)C!S zyWE12bI=Fk$aLw3>8NY?Qdahb-o}eZ{q4$Zm0mTy6tHk31`GNb19n1XD)g9q%2u4S z;Zez_JXXJJCIYQZH}~+l-LvF&Uy<#1$2BB`W2OzU3{4|*U$4xgtgsNKyu6{fTs63a z+>x>b^H+1 zV`9!EVuRWd49!R(>_o`$*t=g)zHBT9^?ipzXE&K@uY&&A;?Q4fnoW|JJ}qug`6@cwkXUu8BPFKJ+5a}nF- ztVao{dOi>~Pi&&dWf>tW&7**efqnaZ+Zs*laCmShxGbL_yO`XO!^61@3!)$O;&w=m z01ba)xOec>D%4J08dXE1XY{Q?N`Kkk(ARo=;pRgealp(3oGLl1eUYR?l~te%(N+ z0i1M-mCb$+{aTwJ-u_VYQ_Z6%ccEhhlsPk?e+Ld?U`bTcKBK!71F$yVnozQ1OL6O>QsgUZ{=c!V4mX||GE%xTkB$9W z{``EwUQ^>%&7D!`HkDG3Jxm6}t&AFZzp2Q)eJOP3NxF{`+{xt zL)P4bjS0L&cdya=1Us5y!AfE#iZEyKus);Dh2pxp$YdN)CZpnW-lRg(QUZ2HgbCK< zkrq2rt~UW_)h0tb)qkP|>fh8W;{Kq(8ZpoY4XGq}>hp`hiyVkDDQ=vSgyaIO(D-(n!B6SCsT~UwiAe zAL`88fGV!q`bC_`mYvyI_+wLxT6J{F%YMW1Rk(uJW(-Pfv~4oGuHO?~z9q)bByn&1 zQkgoR#MLo8@yQWc&2yE>cR}LI&hwThP>m&y;8QV9n-(FCrfH zSwPynF!DHuOLN*Nb2&N(6eoEejd>PD3XT`Oxsx2hUX+PDnjV5P_+-F#W%jy2nCm>1 z@y?r=j!Kg$@>iBegj4{~C+s>+Tr4(^b6<=?2^pNnGB4rwlW?SRO*al5VXB>DNXT*2 zuTZt2!*>gush*Km27%cZGIFErc2k#Gv{kTlAzWx|*W0ZDawlgcLS?tB@c3O;Y8+V~e>|?YW9h_Y)NjPI>Jb`Jth^^j z$!e3CAsIAo1OBsEk8;q;R|RJ*_EjnBwNLN8ZKEs+MSlJv<&!%1|5VT|K)(&2p4MibSOe(PCq4@8;m=J)6aFx}IIG!m$Jw>m#r zLf{e5^YSsMqtF95EJT8zgV0A!VLwUJ%t{;*bndTQw7$<^|9rFe#uCLWR6DMI zZ0WiQpe%p2AV@KN+h?P$j$3atJw2`LzS4b)4+!oWRpEUxh|{nsQ=Yw*Bz$)A^%mHD zKnB+jjSo#dh_e(oC_B5k853I=fk9_t0p0?!78#VN(p*%r7ZCl;8NC}YgFal(yO#4S z&iRgxVVi231*Icx?P5blcGn;N?`Z2RnVC*3_BRk!8xBt<_c;CceN@^+>OS>)o~1l| zc(PBGE~Lk9dDW9#==XGyo6M*RYy!iAC=YJzjTlV4GAu zoOL6ypvMkK)XFj9Y_0{O5f|bAJ+XKUAqfeabYufE0x>EeHEnY)3$6=#EaP+~9k-v~ zWqFdRZ+(l*Kbv`&>GZ|c_0q>2wdqGguEDXz`Ngg0oeZ++;7+d_PqZhVOq*goXSyF2 zpDB$q{(OO27lHx?B%KpmqUSC{EcW1!!#htR&HdybP+x@n zff~=%lcI(OTskU&Tr@c+-+B>va~)E=)5MYVH_*O--hyjq2Oa8t|4qNMTs z7F`Yks$4hb^YPsa%0wvw0s^QAeqEapk()c90n+lW=p08-Az6@fBA(6E;l~n{5|OF{Ruw^IyI~b6W#FvCn)sdz5_+~%U2Jj)j3FyUgnA+p; z7%BMrHE?BR#TWW5)Vsquo6Bezy2q5@>l8J{g9AhrvNym2DJ-N0UMd2Q87}r7WxuZ_ zI&xySCuV+-Ap9&r7|`3-O{69WFQ}NEmemVeT@wR=G;~f{IFmxS@JyNLNDI}y61GAAqzaDT$oTrY1i5m0l5)G z&y6#gvM|%4j>KUy0u(yafPRe=f`a$BK}7CKYmisngx#jN7VfK=OE-0ve|(_hX+3?dL#q`c`*TCVPpa~!3Xa{S zg{D}M)>YN0YJNN?;4cH|g={N53~}_MJ=2I@_nus3F$Kk>rF~|oivfE;qs9y+ zIy#y|&T^w}rW8SpLe|a^)0Ur~zpuJ>!5U|z`p@3p`qi914K^Z12@;uh=aNZ03S~I{ zd&edn&7qYIhHs>5%il}@t$7moxDnI6gM+WYRjJj~hb2Oa^!zrogw zzg_J1?xtNmN1ASE_d)|7iOrx;4w!wlVe)KgV`qZT89+QKagrk%STh^0fO=1PIkTme z)!zO-IXZl$>yZ|R9EApYIlwy0olwUv2UbrjOKgRL1QtP)&Um_LZ&0f}0Kxx^T*eQX z{5jqin{(Nju%*IAnOsQnJA{U5}MdVTNrR8=1eOE5bS`(lhKzk4h{yg(K_Lh2wPpS3S=T-!;? z^;S_a$JiZucd!*pcO-n5sWUoHn?+D*0>vQ|IAd$-ex4})aJfE-6STgH|{LEK}rvg5R zeTsm1O?F=-E}%|qi8JQ570Dsp#-&`0edbOyQjIPGXj1uhkO0!}Wo3QUjOTaWWSS+) z2NmBHE-_FfBKZ~bb!>Oo$NS!76aordLnaBV5ax%slfg~KUNB|o1&t?)v|E%SE^YG-zgdw1*I?ZqFLy$M5|b=*jLqx% zaHHzpIa`QSNLTkA@ZsJol(`d$(%;b$zEHnuRu~Xmjzx!-o2xoXK)xJz)gIs-O?&^k z%mOoeng2}`I`_26er@r5NbaTrPk5Gv<1^$2%{`_Bl~2C$#Ot`sBUy?IlUaMfvgUqh zVt9Z;uE_IdPi_oVB0!BH*jDd@D{iz3V4wXgzblp<25K>7?;mB}7oB>mZm8$azxv@@ z_+oagSPkFMSL$M373x0*v-tc`^u10bu^;E&JuSUczI`ZRdfeR$wZHbdUT;$8tZJv| zQXl8ZGSBe{sjsiE%6LMT#I)lZY{-F^V)#&mwoj{U)+PP%TE?zI*BInLH$lP0* zjmB^uzG)VjVqjSwSi6Lu;fS{9lI6)RtglazrS1`UI1~kC_HoFu!K_<`$a3V0%TK(@ zyV<)vjh}Wj9r$KJ5HIcHALU5&dFyxf&6_CQGKO`(%Xj6uucXOI55w+ltL$mt_xkyODb1 zTWGg$N%uuK*LAf?q*ohqMa0>@UwHPPRi*8Z0SszN__QUhMG4@g@TMS; zDH=XdS=!7`yqbn&xr}{iJs)ORvhS079I%PCKhI}cg4DD${`oEHaoN<6rflalzRSGc zw3|cd-Fev2xH~KnmhDSQ=;wrs){eQ87FoU(aA$WO2|h8q%b=ETzqAx^F=20id1b_E z{<{|3%-mZhKOMsLI5hoU+zFnzr3gF6qa%j-RtF0GyCsTIfjtHtmu^{(&XrrP2A>DA zdRz9p9b7N>&1ud`ljUe{KQO-cQIf!M^BD%U&xYmr0*lD;nEu5TiS>q$x_+-xm95_6 z4BBlMWTLWek9Pd&@ncq%A3u+Q%X8%F<66t3cOMP`nm|}*eZ*!0Ki|z)tJ~QV&WmCF ziuG>uOzvYO&dK`qjz*j57H(ay2$HAfKrFkK;6P4D&MMzI_Qazx)`!rXfz%Ff5ZtWQ zycNlY)iVS{qxX!D8hP}C^2JU0+X0-<#``&!XLOTSTpS)v$oYw+tZNpgshtSuabv0*qa(oX#O;8L|>;?(O2{k1`?ax|3I)$_>1!ZSls0Kl{Ng|XEQ!Y$ALcaB+QOx z%3G|pegvgb;UQz5J``6}z)4G~YISOvD7C2PIJ1U<)G5G;eV^^cG(g&zroh*Pgus4F zy1c%g`t{4d9Cs?#%mrcR;_mbzn;5h~DomeTV7LkkbvPs+psHUnJ-3@QEmt)CZQ7!_ zxml7r(R8;TvdSR`*v8b6cu7i)8doNlt1Au;4z6xBc<3wPPxaFZAawY(%#EH5oAt~c zpa8YGrA3N5u`j14qtHQ!M^2d|0zIJ2$7l3&PJf}z^5yka6#$1kn_GktV+5bvr}i#? zt;QY-jWUcWC9{x7maC;m+zhL>jJaZdWwnFAM2=#RE2WZC6?{RY^G&jNUl74GN)-?8gu7Wz zsC&*CEhp`nNGz>!`g#!IJ6==Pzo&zPoFSr4WBv44qxP-eA6as|+g|$I zF{+!IJ!G0McwW{g!{ynbe`bICS)Ts@zHsy>1GT`%Bfb~`GyV1ln#k`YPw1gztdfEk z*l5-o!!C(28*LB1nOGGMRB+2q(00BDJWnp2&-SW5BrK~>2m)6d2ut;cUK}n0<73Yb zAJ*a8M}|;Jn@(y-wrG?qj2D>T*1Qgc+s`hD5{FS42S?pV1~%ZHVtc!2oUR|tSY4{c zcY<-7PP$JncBmR0&bA*|?WTD7Ae(caxptt-1!*Rb8vJ4=o<9qWu0F3WWvo_!`PPrwh}YHpVEXUN`^PdA;|K3+Q$WM`A@1ds3Ib68G{M z7C-83y_ZW|5o1}eq!8`F*mV{4eC?FEGxha`)VV7ug|2o09AAgYR46>Updf^VJ)IpN zrd=aNeh$6oBxXDaZwLl``9{K2G|A!SxS#{k6l9|g|81JS@T+g%ESp&lGXtMokV?Ty zKSxnNCE81l!8VcXH6}7L!AA?1(6MMZoe-||8^}$21zK6FNO+&kLO}j%8KM4ajh2| z?yt8t>V-Ff{tdp8=iYAMW!3izbyvpHCcMyqo0*~l{UXYUnK8#wFlW7>&ZKyUj_mZC zCZ?NbVPm1t92l;hWEjIgSA#v?7DG7UGyAQ2K>8kmeirR{ReREM+=F2fV zcFszAD@2rrgf>*J*k4?9-B1K7#Rj;BRYWfJV&BWJB-?;s{_cwkLuqLwl7NRmSy>r? zejNthagHiw-X31*ZyL*x|C$+d(0@Q;Z}(){Wxh6^SnW;FJ~4L*-Ks2x8q4zAP6ood z=<~5_cO6@8XnZn{zu7hTDsl`~$x*F%Bd90LVU>6@18?l8@Hn{FetezhOxxYwm?HJc zbz;)@U2`sPIrLc3yFh4%MEk%~=4|b*jyOI+b{*#R1m+J!vs`*7`EEsMPAr~KR-X>S z86UtB8dH=89jqj+yG4&phhi}4uAO9u(?naVUL+!5rJBh~O{70?x}$ZexkDRqHTz8s z-tP{P!JslzaJPr`?IuI34N3Q*(sR;3QKg7w+|n_6>8>jA@q~Gs>zMdjU>RSWi&nH| z&(|QD>VjQmXEH3Qcm@b=9;4^l#acRfCPZp^cSmh&Flzdr9^ZcSjAU#%`QB8XK6f}b zZ@1_>Z{;+qv*j(Ebu2w?>Ow{i9gq7)%wNdKUzS>wIg>&-AmcNN6I$9x?H`Ub=xOq4 zc+TMPakn?ctZ&p-$O*zQf4w&S?j+i-c;*Y*h5z9%2*m}FUT!ad64tNeSZ6g6)x3|f zF?D5>W^KTa#|k1RGjW4PNdvVNuQpXy}h2T$@9Y5qnCgBIB3jh3xQOc~X{XSaa&mJF4j#|U+? zwK~z9o!2fN@9SkRz=2!=p8596rpXw|Z_kTe6xi_BfPsFLfe1pjyek9p9nRyG;o$^P zS?PO>*^VL@?J;lm4!*qTkzJ553K2>?T6w zeaC(_AhhOMv~K!@Pb7h-stU9sVZR@ZvqHflnWQzyzo%&1y23xajV91LbuL@=O$c(DVI<&K17<<$>ZnL%UE3~N)lO>O`&70H zpr=L(iW`+qC@sIxaGdsIR3;w$S(k6553d=+t|hAbs(gW4-B;zwvx3^S@kWJ?mfAg2 zbh21w2DpMqWzYZ#jA1AMrDT;>9!yJH`{_ElYizOW{jPKrSj}McV{!xKNiy6SnF_whw(J*ue(uGxALLh*$J0C> z5`S?PXpO6JQmfW`%>-U>v)y)JIyX^s4z8phH%-6tL;P>~3S8D8)*xII{_X+=@H8g| zvWsESt1weo$Z~(OvSHSNzeG!Zxb?R+dhU9 z+`syQqh&gE{z{oB&QY9^Ed{cco}Efd_@Pf2Yp)#kJVh}4%&N-xH^4`QwKg>+Xl!g; z<5XQ_A(P46Ky`C$c~X+87tT~nHhlWTPRfAHC4Nc~FIf!lphs-&2QMYktU!rP`E>m7 zVo_q3)7hDIer{VX;;%s5$HSKnN@tEfqMz05aA$k5U2_eFnX`mXynLW2%I(rAr_cyC z;^b5B_*}14>Y-eEp3xrN;jO%W-L+u~bU{@8TVKj#(mWpQ^h^<{6~b2|4MX+Gl`uSE zX>9&gB5eX_LOD@^yv{AJ*P|9THWjU>V=R;S@!l$w{j|O>Urrv@vxior?HBnjF1yR3 z4N57HBWDd~e{j!Q_+!tB1YLcpl)0L0tJ=+iRKHx3t#g0;O0?CgPq%#@O*COqtT(vm zdy5>b=kwXIS8}1VJ#?l2h3V>I+FdxRaAf}F!`C@_KjBs&`;!J5k@sUn*LgP^?<;FW8{&1L{Gh38yu z(jq9^ht_9QL*NjxDm-`KmFEIk4vkq*gWhjkUqg_3e3VOrU#FADOr=Sm32TbV89%u- zxaq58Klz$B&8(=s=JN?_nY#spntZuHmKlX~ab7%!y${%Mxnyo_a-6QboUyFqJ+T|X zH!7yhRDX*fV(G6s5vOqgj4%^-bEjpMRjS;wP2*JU5>ThMY)tPC>g%zc(3CLM@~);m~dO~IE-XEif?`9 zsf)hD2p_t=n2S*aCUXg^n06ZbwwO! zl`0>PiknXz#b+J-vft!BAjHqHZhaaZkQ?wFCJM)RPc$s6vIo=&eX`_L%Tc`+Q*}07 z_=&RYY2U#oc5aIChsvjYqX4%0zv1rht^0NrDi=sr+1^H*A{^kzWb%nUW+-4-z|dzB z;_^hCL`w~^`(Bw2I&Fyqh|A1Il}mpSZm2R~VsqYU$i#Vs;3_t*XupI?kpw6&EG{Ga zQJtJ=vDpckNq$(U8ea1AEV2g*5Fd90MNDje_6l3C|h zQ`Xt9R5IKvZc^e>h1!5^AahqmX$EXn%vb9NC&?lNp!Qn|m0+4TD>{}b^}|EjTcfT; zOAEDRONV*eI&pHJ(ZB6~$#2;hBLTqo(CMlRJhnDkskDE=u+KyYdhTo+u;4H~o&&w^ zV09U6dOz#~W&JKdH|zit_r(AOv#_9+H%%o3tyZNMX|r0c)er{kx(2Xz_RHEqDH1+! z+{r>YH9vYy;aaP$#nIJX{L_0{eC8LNUs_3CM+Z9Yc2WHFQnER>!A<78{-Z=*nQ*&Y zpKDf_-H!!MX{6e&?Ehe88|!XQe{{Hix9_<0!Mff`$HF8$>pkLljZ&_Rn6(lQ5%mh3 z)aIuky65t_Z<4=WPasx86U^7*GX6demc4Vpm_7b53)SHK-RazHy(Npy|Auq7>!a_Z zEf-1O1_2DrR(iSJCRSWndGqRjPqz(YekLf4FFIH6i;~21Ie+bsB%E2ZYVIan2%uh0 zBFh#>Z7uZbj;(4f;vu&P3|h#!L;Ib`>}-u_=~k8~^%3>D`F%zPHBxMv-D1yd59NeF zliG@$R8MhYDKpxWR=Pue-I2mZ^ECUoGG2N=M1=Gc1gR=RN7VMI75X7qhrau^gmFyY zg6)E}MsNFH_p!V2{fblVd|Y48SbB#wrDX6kBq^+Fm82c#E|bNZ+Ster(ASy`mKeaJ1$1TcfG_yW@^YxnDxFq+h-^B0 zjnCV&ALKDr%r8b2Y1xKAt(cYPt&}r3L8Sf?JOh0;RZ7LE%S8qKLR zCOyM5>5m`1V}UXiicqS#DJ64@i#L1m@=&b{?K!<{*YrdZp!Ukw_V0m^2xbAm93rU33JH+42e; zs99xcDfmRUyJjx4OiDi?h+AS5nl^B`e>0^9rPMTjv?r1q`$c4uE;pYZ1VKEZ5A@$t^ii2ij*&lmD@6*rO47 zCiJjs@~!g(y=VEb`wk6M%6tya%|_1Es9h%!VhcEtZ%QEHP!+3lzeBr@0^q|Z3;tJE zY{_wH7xK6tOCSCZ0>|2v-SWRRa9cXlnvYZ86ksyXgyw3tdWppPDBL2oJ@G!?$9=EX zvC^Bb7aTQMBh)Hk1C1W`a(*MOEGz$alEG$2Q_Ki+shNG=nLuWN#s)L;!v>Wb&l<&I zQ>T)e?Mq2Yf2a1=l2C*4{vIIz3n6W4Xx|a}_s9lwA=x4HvZ&A8xhq`1Uh(g-vPV7< zrgrTZyR@K$TDnxN)P->k94~OMJ7u~>p0Ov7{iZfu1te1CxZzpKd`(=(#xa})H{R9JI}R5Im%2M}!+u5I{0mI4QbeAfexiZ)dp!yYi=8Ufg^V9Ae2@DN z96O(5nU>{6u%azeZYK9wAnuf$%L7skEZFHWpb*bCSeGlOeIkD>>w@Suc`#LgD($URa^4TMS}*k&R^Coh|AwYc zrc&s;OXXBBaDQ-HN-O4|J2z1-1mC0o>7?k3pbnOwOw;!78 z$@g4#`hZ-Nk_%D#e~#6KtNspBvf9CHQiKV$c9^cn#>mXtL}G^WMG&xa8j7P2Q>gNC z%&xOZ&q$=bgTnaCV}MjMXixh0R+PYsRIDJ|>vjW^5PkHzHM;E1=&nfl3n^i=vUuhV zapT(!BW(x#Qlsp^81i*6wB>hrLj}eYS2vJ}XQ(cnRomAkO}_Z`-CGLPaL^=J0pL>5 z!Q5~RD2kq8JLnXTvy`h;04{_)Rsz125z93@u@*ByVm-B4NCD>0@#*o76OclIKLUD& zFRx7{*uK`|L7xh5K@aNwLU{&JEmQtJSo-Q3A0dl=U z%=OXfK_rxtCL(!@hZ5SPCj^Q#XG*n7#4#|T_2k{=$T$fTSg~Nl&~u#RTDo9V4`s}o zC|=??6cOW}P%Q-7j=hr;QXR++1yxeh)Ptm`V~YZ+SvsdgmOJa4)pRy#lf(CY_zJy7 zlcaO7LNKK6FrgP9WBEhtVQZae`bMOnPgq(X%Z68OvhXdVBJtOrFfrY)v z(T6tuS#9CsQ?eOC65J>w*~XZ=I5(OozTts;p6fYT1I&ZeY8W!`kN{$|G2}G-o){=* zideQ8$pDYe+=#*5J|oC{?xaom0b+EdSi4E%##{OE#50P!*R=W=$d;G*w?`Cb=4J(>|Y?v61^ZIS+U@yLJQ$vTsl z+UF}awpSJ-zL2F~#(gvFk-0>T?sj`;BE~Wq=-BkHgY)^8+*-w_${Uz~~E+*Cpq;#D7TP2_x2>=`2$u zZT2XW*Y1V!roAsZ>5$p3;X0OOpiEgq#;y>-(;y2byQ;T!RYP$89JwrbPf?yV^ z8;ohUC9qL2CfHS{PHuNJx>bU|@26SDa88g23|v_OI#2iCa#y_vOt2gn#iK$^o<|=>;NG$(H3qW;` zy>s;#VtNQPG``8z{a4*$v{P629N4O#6HSSx3Fs#*@3cM@kdWx2f;Qr+`r}*zUr`wCcTbe8coN$kV6dFjr6z7?(2%0)}xQ*URY3kvo)F6o7n}uBXJMP6O z?I68;Au|5eTaLh5L!}{}QE@xh@jC==fpP)7TCbewr^GVpm(vd}!qY>aG6v&VkA~HZ zaOFKZ$@jI_Uq>ocGI#giWQ%7sHfyRq%8j@T9v*%*3iY~XBLQEXYc!T~b}|!@^K<1x zj~?oW6#R=B8z!l0p<+|CC9`eb(A>IWMpS|ZofsYFYJR|Dlvo{W@j)8}!Kl&iAvjj6 zc3%=&^e}>cLPiDk4-+6JdtO`+Jx2n^)ZPaa)J?K01E*Womfj7b%a$VW zwI(lTgS5=4VEm)O7HLa8MLesKrtrEHEvTM);OiYIJ%aq1X4+N+>!gqo_S`LLg5_S7 zQVxz1-K}UIa9LuR=br94rzV&0j%_>dXML9H zSPEV~Yg(yogtQdQqSy2s)cUmX{hF(uJNgR;*MoNM;*n161c02~pgrhv&H6k`H<8cB@k{AlRY2j@r3J zru5czlb^XaHmL0 z{p`TkiM@KLeU-QFJ+n21p5H^aloNBj7d0M*ql`E z8R-h7N1Gft0xR#F!rH+KxmD(BLcEf5^lG{iL8yeP#T-FzCEacUCqY_h9D^E=Ag>IB zpjEItM0B~$s3&dRFb$zinjBTj6XF_^8h5y5@A%btU+fm_Rz`*|_yRaKR>tz9J3c)t zsDE0xI&V37yvttr`S;ZQ@wDP~f4ex<;SawxeR=GeTj-$g4bOY^PE~tS=4fbkOTr|b z4T%JjZ^s*yUWO;G>_>C@%ey-?$68IanYHA_=!3)TBsbUj3}dyELk5=b9k|cW4;E`1 z?yx!mUlg-b{phSWtOuQzj8^4)!||$fqx~^P`$h6#<98db(be~OqK3CHIHDJxWCCwG zCa?wVuKlz&$M%OMLc;gyd~Bi*u334b2C9%1Yp;ahoH`?(+lb>yG-e{KZKAG`rP{2{=D zr!i6#lwg}G;;fsKE&~~ZTr1R1272iE`~9kt9iE6?;n|7z@|@OET(U6Zy7AlUEnh#ED@Qgl?7Yd$TP66tLFB#Lq63+^tIU@iym+`pR{f`T#)bM0W()mJXU8}1F zTIG&rqxp`Cgfih!Ro6CxRKaz{qglV7`xV*)>e?U@GYP5;E%gAkdm(4j(sYG}m5c|! zZmGL4m+lPDgHPX%W+dw;ZHqlWY(I^a$<*3tiWguim9C6rBfm>I$FA7Q0+zLZN75qf1ExrRXwta z%a31QBk^|^1Is^Flf0vgCI(xc1S%J2n~+!E2XZ5wqm+kvrJ@79PX zJ5G6a_K|$)w`h4{dVfze=B$(>p2c%N=2^V?lP0ZszdWj0ofEr;#^|saxOp%xZM(ZO z`d}FKVS4U0v9*4n+aDaMy5>4u{PZ`YxaFzZeU9(Vo$ztc;?&gyJ=QyM(9Sn5O}mmn z6J+#%yDLeLUi`Q$kxO9dZoG2Bj^G`)pOLFS%eCRl`zt{os7Zy=+su&4P9f$U;WpZ! zRe$bh?%YsnJnCfKR&Wa@+BDer4UVJ=RrC`le$cLH<*m@shYgL%)0kM4R)7M0rv|3G z=grw31CWfC+|V+i%+E@NVSqqBw2BXJVW`=GWp4A4d=DA6%wa90$RC_%P`@r{rn5z*yf zF9~;o!F2k@@91zT z(I==4&!0|vrL{Reug)I-d>kmQ> zdl2q&Pm)sWbYk%q85P{VPrMjv*O_aQCTFN_nV*+? zm)P%P04#v{VbtFFAYfsq%VuQ3t<&z!pQ~dTB_6E`NDqV>hY0kTv8j@_396lb5)5%` z@?s^DVq`e(68>%!I-yh?FB{8aJ$sSbtp2+%r9~yFdNa~<^0F@A-^erde!?OeTM9q` zqPKtthCiBSnT35v&`TJ;!0q7Aj@-NmQP%wexCeq=yG!y{b)u+Kxwuj!2=W2KU$OZw z7zWv^L*}e&z9d%(GmCsbs zmK56Twng4go6S3XgUaArKxaAVnilMBHr;|wM^@ODWpcw2k7M(RxkeZ%|A#QqdL8o; z#L_`PboEw2u-o})@ND}|Q%dpr0GQ$3=>H*|?jbxpJVIV}Aw*+Dc)Nj?*{7jn&EkNn zgniV?7=GsutlHZrMba|Z?iw0Z9x_!L1u^4Z`E0cb7IG!?G_{0m+h>=dUg}1EdUB=p zIZ%2Me)Zgi2GbD!+f20JR@18liR8$YY|amV902)EXYShC}jSZ_Kf`6mx1ZTFAm&jKqE4rW6qPL1XB zpHjk`eX>t9JDal0X%$Q<<>_9iT;<=GkoeuP@7f0ld_6-Jp$I1T&OirOTf6>tIzQ2n z=$=T3N^MLm&n(v7);_MMTQGc0e$c!t#ANaUmhp70J3KnRUM!!hR}LJn_D7#q6Q#Lq zhjwc;KUPN{m(Zl$wraGOn+A5C@O-7mj@lsV>h?9F(|9IP||1Z)}p7rO~n15 za}WAaQm<_~JXs?#XmRoqj@~2#An~uhdYvh8CxywaMci@kWMVUamW+r!AQf4pCR+)I z6i`DTcPXzw$D*6NN1hhYf${tb48-{cBj&&4xorM16H{km&z}a$#W5yJhAkf2m=r6= z3TghsKeBvKjlIP)Q;+})L#Ripzszzl9vCVP_1-y+Z?Q#su|` z$Rs=76jgDZ_fC&Zb;}Y@RCnq#fP4!O9~(3SxPCUHd7O~ySxE%|ue;Qdiu~ExbD#QG z6)4oVN~3$>?u2V^FMj!T0I&V>FyGWh2=f9h|K?~{oVStR7^av2tDx$P^PYJN!_`k_ zx`SMF*Dn&H0>bL!8Qa%mw7`98y6B2X|Cvl2KW+C|{yivq{q>u;&w+#-&mDK?dwwwI z?KN5oo?PwyzU&;sM%AW9?F|>9Zs#v$BL1v?I9P#qZ?fVI2h7nA7xF8_qSXQJ)maR1*?MgI@G8u#Ci^u*fg%hDkR z(&7!~pB7ukYG^#3-(bA3N15VQMl?Dw?eP)PSD{1&Nfs%y?x#bO3l}I+i)0f|;StAA zCd?#%E}$lXOo^FhHp$lvps2Pkvs_Uj4aHqu4tA=KAXY$S%X|BqEkTC=q#2U~K!)3p z+PmjF&bwP5QFO8rItB>Ac-%C3$31I3^x3-ZH-D2AmJp5YgL*ym2Sxm*os=-gE3&}w z{lIhxA*_&?x=cg7r5*~R(R?@pi%8j>0ol~nhcEfXm1S;tjB8aV7IgewbyP{^1fo(6 zS|8H{flcy9=0_Gsxg8Ce6UN*ytPoTB)QoK>MWW+n8P{#V-Pjca_b!aG&-a`EVW?+n z)U=$Up4yuP0(2fOwvm+QLfSW^f3FUVC*85OLgrkIQN@clbLO4&z77_s1O1OHC%5l4 zuBEhk4gUeiZ4-m%edkIG4O+*ylfLgPlYm@bE^WH9_xzeA1A6af>w%}@{Zy#ImAbq3 zPh;YDRVs?l{{j@Fm@xR~rFL5a`E_p&kjUq88<*A&^V!Egu6jG(VhH?AVDP`#;|sBL zhpHw7VkGrb`aSvIa1gmUWgfPE=bmtf;9~k-mw6rbO*)2KKYDj}5%&9{=on?YUxo zYa$tZjc45Z8jh*_jHagG`UuL%Umr#*CK&AbLoEEi>~+{Wu1!af^+QOup+tAAgt%R; zefu-~=UqlTTI@;VWsJk5b=FXd*9LCw*2Wl%G2~E@!-Cn^pc$yPm|ArI_Ebg~ZV2xu zejzbv3u$aUtG+W~wY6l`ETS@9$*1{;=E9%&OlM?mj zpx*7Bx17#5ELQb<7K9&gd~%+dTu>38-b1pTH7H8i!*^$g`>0Q%f-NCC9A;?H{6jMy(O({eg};V-CXpWDU< zfZ3$PzraNGh)5}|R3sk4Df^%Z&`qs1JyP)yOtl2`f3z><79Gu5HU<%*%XelHh_&!U zz&rQW$>IxmT&c|HbwjR;{|9#V_X*X*oocdsv_+X?J+2Hs81IWDN20}^%Wzom$!01_ zqYFq3?Xk@DABPn0+@^X1C32AkG|BUWDE*Y#9m=rCfR~RXON%gS`TR^>=!S@-59Y|F zrHa?^@x3U00(X!i4dk@a*RjBT$2( zvkWVlFL}Pb22B?hS2f}VLP!1>RT7XA#WSBEHi&@qa4X^*U%D;PY|Ur4snRwsrq5LU z$d;vG>aFXdzFnkLOs+EGwAjts(6h-}NLFe?`;U-92iiT~KAum$&$^xbO|N0WiHR#h zliP~3adDRMdgfZ&9WXc_FokpRszUrX z-K3zeKN&C2&$VOopT21X;xt3dfh>Ma&QgbFrp9=U^WcnC!R12|Lz%bd$trZk-0rNb zYU{^p;Ir$M&YEP7lw>FEW>vwNt?YL}wWMJJC+}zx`VrNP`pQUMUIDi0G{4}`VWX#w zZdZ=Wfc8)|^}p;;xWh%YeZuw*cn<9=ug5Vj*dZ=g6es=9Mo-(d=mnISsRE4p2@$4_ zRmgE|cpFb`55d~ku5{S8%LaBMPE@7CS{%AGW?WU0z=sU0Wo_ftPH5?V_`+1hI!rf- z?B!eC+)1mv-U+JAASj=!q7~E)g+&(y(JFR4tebAwxVVNskI+`Zcg!#ZNM$CmWEf|0 zIWl~@a^nc?YrM*uA&fS)&{&u{p$6y$Byt75v95cqG+@5$VDo`rOW?!(zV+EMpwn22 zQx?L+;VUDZZ$y(8!}dlr;iQRkO{7rGpu^PnFK4IJ|I>(eLB*jLPN3pzAv}&}EBAJ! zSN!RQz=r5QTnz|I}y$tXc!+@JJx|jtGlHiw&jFW|?6I%98UCj=wW6 z4520E%VtNBwP?wT6wQG0$S^tgJ;F^r;0it0nL9QHf1mZP_RcZBnvR};-&vonOEu6o z2GjrKgSd@@cWt^jI_drf&uqnPol@_ISYfQv;U_MoT5}j%UMreJPV6cUG~BNj6Vq3} zDxYb(sDdmSG<)T;5!JI013kSqt~>uG76PR|A!q>=&O0!wQ;0F?$~nGl3tE}u-+Wcj zX?p2QNgEQ4GdH)T6<$a`?j@($j=gw6s}LLE1%qcffCa+dsrmtrKaPkPgVVxYWmK-u^IBFHYKXGb`%}`cSdCPWO%&H$Br|X_x z8P2I6AB*0bj*~JJ2NX8cHi$O4L*EPhKbxXy>?>SBv{kB=3#kWY2M5k$IB6q=(~+Kc z&%c%GYq-`hRIXQr=jFIS7T8Fj(D_d}Q1R_495UHZ1P_m`J-oH}`mVK5KFClElcfS% zT=?Agn1~Lb(0N$A*lFcW^0h!sfC<05fZ*0yFN=2$N~~HfcUOr@WycL zopa51z*|%NEmEP|Yfi+a6PSxx$3m{7I!@zwJSjiV6E=IiX!BFE{R!S<-F8RIz9*rE zFrRq7pn5^88G(V^Eb&vXS;2E+nMZik?5PO@+MasxXAP?grd}0+PtHkM!CJNWm;Q4u zbxG1_Ra55fX9bMXrv=l;MvkZOD`U8JA9V$|cOvAf#r^7cR)lj`EAUy)2 zb?0tp#ZRp&7%)uQ62E8ykcFU0fL|eb9@mHQDygdYtVk>m8jwGPaT;xuTT0?Ys#vvq|58~kK=R=5fsOP0K2xPqf=XX*O6v_}4HgVE@h znAp1}{9GfkzyB;0P}`#+kfW>6`suP~q99WjL7M<{|5Tg7@Uq!>3Az??mk%^|>!3nBndx8G?b8j7`sMMj}BydRTc{2~mxRs9OHG z`9Z}V*=d(G6h?X7hD9FpNE%;y=MCnMLkUZNlycy}V^At)96|<>tHLr`BG9VZ(6@!FP43{mHqpT`EFsGoRS25ksC_mX#tCDKw zu8mO&(8VH9__fce(TcdTC$L2tkfMj01N-lk{vB0bi5~Yes#Q|uHps6y1+B7=drA6; z8lylpjSIn%v;GBn1Sf41l$(2m%gr5Rm}7w}H$*a>O>8MPjdT()L-M@t16Z4boWjh> zq%{xo@QoBI(Xh(5@}w0%ib#y8 zTuQM-rU6uWlv+JgB{x3Cg#a=7?((Zoko3e%n1hO*cD%ffTM5u|_6n^}qt7h3{=p$m zl*uiY)x+bI8gFmu6MEzQcsby58}H6j5ymv4iHcWkSlNO6b#KXI#c&vkTMkvGEDopq z+fnuRqV9FJ*$*Fnb={$x=PQKXx0hx8bW0`83hy^Y0q8qgsS0N`H7f2ngR;%F7SP{J zJwa^=?ai%-xwWLuSWnx5r5hcli=_A{l}t=|ULR|Xz$23g^vZ!<@#UJ`hkl+ZcoP~? zlW)9im+x4XpIVg)OjvV}S+XEX{_}{SN&4t=8myYjqUD?O8>~t^64xo%whWGmSCMRs zC(n16zfRsz)-*XBHVBWE@j%winQY@>IW)h0OF9e0ap|Kd5IRhosChR|5Fgw7Qo%I5BJ6d zjZ?ea+gaZLT6fxNO3@aT3w02o1=!k&Oe(T;|9Rf0jR=p&@l=6Iq-#OIi3q_wwN!D@ zS+mugx+Afpxl&raAY6qr5SE%%_(tnx2T|2csHo7cldI(A{_HEDTA{@g<^YUkHnQ}d zJzh%aD+;xpjaS**+FXSfA4C=YM+-pSoFv`f9cK8w+yPxnsuyuNAt@;@A+MT4u1v1G4WY%x`wiHpFc0@+mIVdbt5Q7toefm}4dcAu z%cP_gJ*a19%lhBxg3>$b9Th1_^yiO&Rc~aReBb+b#g9(c=v7N9rH7nhww)IrXcgF? zgjE(rB{52oS<)a%+zaS=E}jgP&l&#v@uk?@A`%o252wXbQCt-ENw*h1)4%dRd*0u5 z$?d*E;=6eZh)JUNeoI;8j0PrZ1s#5gkai1>q|4(fkywvX!MK!wWi%l(be*x;OqWx^FD40sjk1pcsqC;P(L`~e+1Lj?{VnkzN=9T&H9H?x>v z;b(O7VOy|2MVF|pXt}?#JRiod^RMf-lrJoXwq&^7bWHY28(ssowah?_uCGVu*fR=} z0X9Q|;T0B=^VmW5Cb{Ys2@+(7 zK-{p$AL*SJp|#|SJI$j}6LzK(quG#s{h47xHr%OvpL>zP=eViTfy)FjR-qPnsxXhl zRIJ_kjm`CChiBv4>8q4wiK~3Eu&1-pUiMeK)0_qGFE#6 z5Rk%-)=srKp|%PwHpo;T?fb77%!`M_VD>CnuZbiyV;=me5$;pAw|usoW=&puRu!mr zvd{gzX3J4_J?pGH^=E*hVn(Ae5SG@X&C@;sOU&}kkIyoPV48XJBuZ{9LXo`*UYu(# zOD{b2+q5!wqH3afniv^sZe?fGo**-t&ix${RH@}pZ`=D;C*d!VGV|uD1vD&h4UF>~ zm4jvFjQtjENQ!Fge{zL`4>Od7$Z&Jp%QKWq@i^Bud%H!jDk~LpX=*YU>iHu_%*o}Q z3A&Q1Y=86QYG$KxO}Ie_tNMD&#m6r%I;n%64NHIjR=eO62OhR@-zZ0OF}Mt;2>qU2 zhQLETGVq=asfh1{ReaS-KkA5zqA&`c9S(}pqSt~O&h^~RynvsTtWNtSYn2aH>^yGi z$*&%h^pFHMCXJT!rR6Ri!~pD3Ivr7fkrQX<#KiAcfGizVsHO=>Stb)ikXS|ZZF&zy zY1(}6rEGqE?H7?b(q{-j&JP{j-9;2`0uETT4COy(ngQQ!G4=QH2d=q6Y)y!M$1`@+ z4|~P8ethn0ZZihnNbg`oqX}Bd^+oxWyOlky4$P>(F;a!ohl5TsRrFOSs8J%&q6jk} zR?F%YmBo%!(2>(h+5OZkr$uo6**KpwDeSoF7L6cNN+6L(VH z0ELoMo95I@W;7?nb8U+-!m{A3MbA%5T~-1ELBQ`1@+2T(M-KGCuFm zn3)YSj29$j4=o(HNGi*1p`KhS@?0rBBF=$n6QroJ68iM$A}9%byg!ZBgy$Y9oh4Wc zP^-NYPW_KL!W4%DXUL5Mk_Rg@vFP@-m!)MunQ~#MaoBTivh5PeDcyh+YU@r_5^_y?)W{Rl! zX>!8>U!5&5gF(;j6o>QUti47|$dE+DUR6y^?g8~5f?|R!Sg*jYa#@k=R~kc@k87mM z@_4goMO)|f{K-RmtajOxMKBgUMp+PCEkze~hyPUz6;daUTv3KzMzR^AcdCQXouQAE zX(lRA330?;p)yH1tJsL_HW|K- zPC_NK=~pRrO~aBR_ZyiCFt|l$`#8iOVa-9-a@5K^7N1{W*7$=Y=*%VX>2nWrmnZp?wIDOJBXe%YwxVb7&x5p1w+9ZG+MR;V ztvz$4=V@d1nNSz^mi8C4CEa|PoVtAtJ;Dh!r2*pUo?0aaR{Gc*3yVm~`Ly||H$a~5 z^2!~nN=-Ta^L$lYZOe(Z;lY?LFOYrTh@nHY3F}63Y#N$5Gvf;1QYXj5!vhT5C6>;j zg+LVV8Xp1Pyhp96uygfAhSDc`BtHT*QF8bnw|?t5j>$2D0)Y;gFM&1hlgW53=X_?$Nsby#FIg{ZI&PT0c1Wx_~@j}o-7b-JZ&uqibMBrM1!hth~ z;Mcb?rh}a1W56uA=BZ(vu0m(zMt3rv6tLjzJH_^p5?>AzA@%dDCVFuW=ZfV5u$aLi z6kvv-5DL83`yPqaZH)^iqiyUfV|yqS)O;1nqQMX~@o8yip=o4b|L`x!jkH&;oV0ut z#9&E!sa&1Fc|*etTZ21K8^Ku*T-QIMj;!###ChV_A&72{ItSzVRb5E4tdc8|*1d$V zieKbU!FYIh`$bt;S%rlyV0C9Z7K=5!jW ziq^C~?*1icJ|VaaM`3ECji^v~h@FZ)wU>HZE6M!k@$QfCE5%j%?t7(DZXKH$Y<~YA z%f_iDxA_F0z+;t31sij1F;!RD1$W!tE%>cwsP*OfzJpe*E8Z?zP7!B3o%)xXk97tU zAgrjw_vqP}1?IMVx2%3sO)aN$Ehl;f@xap^c+j-6kgNspjVZ7XcDA{6xuV$23!?-zLoTE6M8ofs>fbC_CeN|7PZ%jGAs&mqe8XlRJ3>B} zZx;^h&Wl&^rp1?I6X36R*pC` zIofc+m0p`sQF;=+_A%Z;2iRqTt5n>>cD|3XAR|h<{iojUgQqmiPoa*o6eoeWQpkvt zfZ>61F-T`OOUjm%%?mpJ$st9}+6%|NUM)=qtiEESTb;Naa>Nhz^MjD0hVT6&w`y)4 zpo+au(_@=b8^>Ha`Zq__qCLYWRe~(8A<3ZMoD(04n42+7`y90_0ztQWjpvF+vHQFR zR8o?Ymq&U6zK~Y5jo5fL&z9*#8ku_%FosM`3Hgf|;}|uNaN7Pa*I{Fp#djTCS|AF= z$<4skP5taJHAE$~4yf_8Vb#6)@h8t18|udp89Gd^1u`&l=7b=ks#eqNZ zbk;nutSZ=cyi|NCN{RBGztco?byQ_N^S8V3KWCXKN+*E}8y=aHlsfn0l0K|O)Eu-J zt)1eKHzx3ysXl<~#sv|~Updp=nKJ0}5jw{RK7&Psg;^9YB`G%3`>qGeB z<3ZH5gtA*JU$t*Ms<+?O*_0LO`STpcTxkuz5t`ocj`KIS zdhOul4}H-7r)s6J6vX@0opJ4+6|4juC_F}=DlI7wBbWNyr7-B7mcR;xz^8yyX<$37 zlL5wP;%pC72;W0)m{3?9hxukJ;Cc^S{MbT=`hHNg0HZUj`U0@*AgXQs?= zaIq!9a0>vSvf}ouZd~QtqGMdGK+~!N92=}?_PRJ=RaHZvv!A!Sb$hrJB`YZ!@vq=P z7?B$NsheCMKOoy;u8Zq3BgPeGLKB)JfF=m|x?j_-<-AP%~i8;Yab*XakGD#~lEIeen zN4T7&F^zI8?pji`rBaH38{tisb~S^3Jm}jvRvx>Su60!A_w*yc1kd*QUXlZg?Y}N* z7AF}ehEPb&I1r#Hu=3v55oC2-*PY2wVHT?NCn*JumRk>xB2Or)96%0>9Tipk#gAeD(g=ct zfGC23lyobtbPO?+A~|$7NOy^JNy7{w-5@PU!wfNW4c$Y>J-qMxy}xzWy?dG`M7&u7Oinu%@&&*yq#=4AACwR`AB$mV8e-adAuBLjPH30vqksIhe)vnBuL zk5{eNH{>VpzkEYBYomNO0l{Ar?RTJLX{ws>=cZx$UW}SIy&E&9AziC`x6e_7dh-2N zrb9#4%Lcq&X+nEv_?coQQ7@yt!mrVqM;kCP@xA=U`VGYG8Uc}K1Ye>4$<5MJ{=M6a zx;^%PqwLNzGa4#z&v^5jG9C+ngL4lTJqcuL+p)DvN&C_>f(-Z3EtnFDDmPwoIK&l+ zg1oi{jhpqP^dXH(Dx3Q1?dJ0B#P}xMnbs!c*qQf z-q+XHq*2$9k^FI!pAbOMD{<7BogDZXYC~D(DVkH8nlU$+h2BzU@f;_?mf7}XbhiB=_lKJk-(Q_s>JJA8 zzQ5zgl>If1U247lNXAG4bmu2Se0&B93X0z!1#+>Qrn0ZEuQ8IH^2avX-0}&7ik6cI z6(YK7(7&D-zToD^?^6l*PLFl*{k6_x7M7gxM_;V?_${5j=W}Dg`C#|QdxyDMxo#!jbjgSwK1LL4cg(uXD*(`z?sA=qikf=F zDZRFN#|m@Ti7m748m2q1i>ue;iqy@u&I<)khQ&Y4q{;Ya$`DzRnN|@FmrQp*(^LtCY^tA}N76(|Un8Mk z-%fotV4h2xYQy&uu1QhLG5j;VyJLgdi>XRS_7et&L7Ok;eE$P}Dr83r%bss5kWUrK zu(3;W>TLX?r7be27pBCp z1wDrIrwPm3+k78X$Ids;)?KYe5d&FWOB^`G z(8ZHarZLK$EYCE`GxLH~^_mw-x`=3uDaa|feRd+jiLvbca?2)0XD^#d9WlgFp3n-_ z{xWAyo9Ns|N&sP^%2#9%9ssEr3=|E7Z){J-S10_OL4x`LV@UNz7OrzF&%+#3B&%R8 zZ)nLG65lOtxwkbx(T21Xb*BUT^vBuboqo417R?BOr*Lg|+O?Ob1APfC=WFTKlfOQI zPZYUu6a$G3uS`JS+y{6j?jzF>K(45C_x zwqElW15W*Pb`$e8V_-D`_A|OP;`>a}!yxF4156{`gh{Q4%4pjyY7&)-2ia(Bu@9^* zef9U_Y?UXX`gp)<3i%&zW+%l|>pFuc_v+3Yg(mad+cfG>`_|npeY0kB6V!Tp**esC z&6RnM4>Zcm80W-Ywmp7N&D|8oOyllb?6b4N)oxOI`{rgSrE$IS8YS!ve?yUe8%^zf zQn|#Y`Huqih~A_qG=Mq>)5aV01ENZb`wR~U?f2#D{-ti5)#-LE{mFwspw2X7GhwU; zrt1EVJfk({K{(;h)2(N&#~7SGuPtf6iU1uAZ!z4l=M^4N?VK-*(K!Xt#vKIxiOWiP z0<}9{K5rFz8Mqz?^`^8cyAXi<4MFcMEZV~}IJ*xt5(cXN79P;O z?&Cb%GVR&Becv;MQoXpiwVx*cZnfeLD9V3 zPm6CipAyY>w`$e-f(b$8uKJYL^P)A^YbrNM0WR{3tpD&>fVB5BRO16yNB84Xy-wnH zBbgLvcTyZvdx@^k=uuhU<$x%z2Y%wQ20&j}_NM*&dU|?a^_?rCkIW|MhMpl~y$iz0 z>eeo4_I(Vl`r14biEb1XR!;vAnE>z{9JCwv855?nrzoh4hADkDbgYP&qRf0yBdHND%*;2 zl$n_0Kb5;3nUppie!}=9Cs%)Sv4s;Db*i^)TeX_$daB7=!E(ZAUAG+UiQdFq|LrFy z))#qeNAvWDSCqreB4>@~uICH?iFb-Ry#uga)JxM&+neJ{%j-Qpqa6^eC4gtkyPv>E zFtgf$Z6&8xckn!q{TT|$_^%wtPuq>l-c4#9K`swvMc8dyay%H*aqOof2-K|iDeH!ApWNz4pk1u1Y&8J+ zf=FN`bpz^T7T~?oY|0(`*$E0&l35C_MhJ!vU(>5M_u&d%^ET~73NfjtU*x0M)}m1& zA6?+X*cj@SeE~J+;5l-CsOB=RvcH4YH7aC&bVAGA2&!^@i&_aPM1WaXI0mftsGEw< z3nvoz+{S8^fk5e8=K^a;Q!XK{X+wvLO|k?A`wEAGk~9C~VcZG;TWEr51x#ez1!?N> z%x)#|&fnggYXACt59rGUl=G$*WVna*(D|gXl-BvZl!+RioRrnprcB8%x0qo2p}IX& zALlSAfSvaw^J2V!u{Feq#m5B^JhJB#Tm5$of8F?pjJ>`*j6vjpJGKwkp3hezyAc}% zmP$_E>&lU9sKsUhe=xW8uxBw4vEZ4G)?bo)Ds!l-1R#nD1R|km!DqX?$Mq69FIu{# zv?3_}NJSnfi`Vr$=&CE#*-y+jud1oBUkrSzh-`Surps^DL(Y^SZmLW^Z36O>rSFuS zb>DI&Q6B;{0%?3bAa$tzo;iKio0#OxO>CpKR=c(>Y~+LJV;9@paN!4UGe`+~a7eRg2S{ZgTJTTA8I;1T077+`@*R%i9m6X|iwq4W5rfv! z0sS{=$3zNq(+EiOKP->-ieUHJkQ2V#t_0?v-8F@0W@etOcVH?~57RX8isu>- z&mT)^4ugx;6Z&^u#`*7UK7aZsUR^oECWkgJTTrl_hrkd7&)L>~sjL5y-!^yLSJUkr zj&fCLPIej0Oi_A(ORuO8uqeVOlV6uxqV5D}#=*=nVDDEdaIEwZ^!xdorsZ#Q@KBUu zA$_9}_a|)@Q+W2?6|~zjoP()Rr9G_#P<>|@|;I29XAIX3UJ2j zqIXxH~f~-8|FXymhirDs*!WCgl5vQ$mC5Nunwsrz_Rw6F9pXmzb&&lR0&(5l&9*d_v zo4Z=$Q~H-V2J8(JW$P=LjqoC5|49W*$)6s)e-#T3i6%dz(usJJT0*tLTZdVTd$Lzs z4po)0IMspc#hIg0m25NP2vqQzGiR`#!i&4{!8>s0d@7#F(Ft>B01U}m%is66@|3|D zk+I(MV2}04=xQ(=2x0XqBMK|M#VS!4ln0Qmh_Jpn|-_?^53 zcqWo|PZ|UF)Tvo@(K@$SwUjy$DmvF|c!t+oXYn!GA1t3M_Xi{`Cuyheojg3<;;rLX zQ2aoa+U6C3nB&uw_{j_>0?Xvsj4(aRU7Kt11Xk%$y#q=l*IE=(l{2_4@0-YWc?(!$ zw~KBSoeS$Q*1rL;-#BF1YZg;1M*uJr?>Axc!i4^to^Xel_}wBk>NjhR2QA-(+FnCQu!~g%>lDl{MW#1qZCYGR={eOT;ni6{~u` zv-@8zz_Vl4uh_pZ%S`t+#WkshU6>KYpMZJ1BxN5cMf(8Nn;lqKjgy5DWeXmcP*2TA^D`8S@jnnF?k>B~Ua z34|K{^WCN0mY%vl-x!xxC|KS-I0HvGoHjRV7~zuZ+zC7e3pd?PH|WiEe##RdHx{wD zGY_~^+5$-*zdwDC%10>>U<+Lf|DOG$p$I(X zTATSnp}7OXAF8kOZ1wiK zUZ-`X>|Ctu$lR{B-wyT)&k&H_7bU1UR_p>V6h|E?imwl_Qkyo2_lgnIG}q#L6hrP>Re~z9JcJ?n{j6;@Mu1J8RD`9NBT8K25n;7sD;AH-~xLoxDxbU%8cBcs&`hLK^ zT;90j)T@mIn3cYzT>F0G(MBEvPICPloCxG^<>R1pb5W^&m*(?4k-Gn!EEf7Pt9D&` z5%S9(I7DG2+=2>&zlMQw_(!vJ%n*zD8HhT(xMHmy@KCrNNX*Md3ScJTT|*Smc}~K-N3}2my+@OfL)Gi1saqCtE1?`Cs1a! zL`uJjC(A~Rj|0?rXqO>HkZg?~9g%G;Ai7qwt7l+QCKH#RF+1{q^`3O8lV|z9dXL>NtKdCL z#j#A>mcxC0;d%yNqcz4EHl*(OOo8)gp(wof(Rg zmX}wTQT{VmnN+vuy|2vb+z=eK-tTcF7r&0$tSHfMfW;{~y5bXtoPC@D6PqU@bo4ehc^lPTJUK;O|kz_iuMuBDF za^&nXLo#L>G0D5s;t%@O1pq5En!p{My+1d~zvdezY*O*3O5)N@f@^|!`-Lj!7mip0 zuaDrPtJ;;r)Fq|GL@Aa4OlfF2|8s^sM@&qZVhZJedT}_BX(3tpSA>fCGBQ1m>>v7H z^zgh#KNy`Mt{&ch5@hnzFFdQm!DD$2i*<`Z?$5B6a4YxGnwO|o+36uR_NRow#hJ;4 zWN^UIAal-27k|ml^rwF5M z_Ka6kQFa|!IajtQQR{03O0oKyXPWg4G%oAa(5>%|zwNS$Yy85Ys#g_wbHA#B!Y%re zUIv22Lnv2dmAhtP8g_!eJZi1|;5 zPg>ckpyzmN+dMQ`_){Iny~xc)nPZY8!IlUD#IJ7-ojgsvRah1!ft5zT^bScvN{?>_ zQk&>Q4^sH(fR^uH^lZM=q-a-Kmi&EdhUu`i;HFdi9S91j97zP;E_spJ z8>E!r;*?Xpxgi@DN893>1nM%q&KERMqRUogjr-g!H>J$tvz&xCWBT6B%dg8?8a=B- zRBJtPU?;STiF&pNuL=(8xfn#q#QWct%Z8v%o_*Q+i+y%PCRg~DKn@K6%qKtyx8=xA z|25ZVy8uvY?DRwV^-VruybMUH=S5x3m^m3&3ul`Bo;GtD;h&^$yVW7TN(EYLMqTsm zM*OW*JQ~pDIT23WOX)hwX#+?X!l3(VM~dt}xmr!!+w?2_s|UqxMn3Z7z4K*`;Zx@U z<42G`DClj|-dO;!V2rxO1jjTs`@HIzz5nG~=@@7V8C08$M;1txJZ24S#V!E2u8(e6 z_Wo433Ve(okC{03xI_P8{UmKhDrrf58qax1|B0#+s`u7KYK;O50qWIAd|Vn94m>Wd zf7H^nJk;Z6R08KjlVMj_@p(Q;Mp$wu(W|Y^&HT3%G;f{|WQZa5P<**kY}rCkmpPKOWLG}K812) zB)UdRQSs;XGYFT)o8SQn%Rl3j`bR$GvAWC183Ex9d5Dy_=kCzpa?NGNN^0xbOB+32 z1E^9UarU1YYmo!wG9!Z#AY!U8SeYnj{L+^FEvQkKA{IcC(v#xRAKMP9HgaQJKP<3@es(@J{^PS>I51x(=aQ;yz(!gB2pf* z575^6jn8E@Bhx%D_z2^T&$7%ph86!oLTzT8L6}AEayP@gK<=4VVp&^5yN75bc{UWF zPUntGR3y}Kl)6H#nIDWUIC#CtDkNT7dB=K>IYNvdEfD2z37RE10ZF8DulUu&AOCGJ}+t`20jl21fNSPIW!0{o4wIR z$f-;!eh|!~+EV>Dk$v7%}J%c|7iYa;SuvVJv)%$TDMMcKv=*%9HFkJdD z^XdEJp@$|v1@v>S&B#7fOjA@9apLkzuAy#_p>-518c#Pg%>ELZ-b! zk@0*+ON@%^JVar^5?=*j!(M`57ax**1mk@nzeY#Ei8T2aVkoSlw)gOP>ypZ#>KlMG z(q_s|f)`r*Zw1DaT5fCwX9d!-kS1Z3a;b(uQ`GZE`RX~7&CwPmG!3`@Urx2?p>&g% z^pNGxuYm9qoLJWDF8a}xIbR2$fAgV^OV5|QbHKgyw9FG69DhRIm%y5g{ z!*yMt3zYbFLBhu~J@c$FME$@QhT2~liaPX{A>}SET<}wCR%rNg)W}5i>n~^BS@zf& zL`{J4*GdWcYBfr42I=+#8#S@tD<^)nOnU7vG_F;)!rX` z3Z;#H&qI+beo{PMj0=Bni_*-zpZuGBvU{R61Bm~{J40(mSemVU1LHTdM8J@|kw--0}qn1YJ zO|yF1f25u{ax`@{g#5~&9s)HRMC%66 z1;~9gHw%zN=C$%gk`bzr#R6f9ogvU$Ij6k*@wXmYkBHjV>z(C>8_Cj_0mNP7)6;!G zSKx@P223CG6ln_!7NEW2VpWO9Vte42v*n$UU`&<8v=9x%g4OeOCERcU!sZ32VrKJnx7F)Gepsydpl7iYA}Nt5 zr~s3u@vE7^&Gic1-?F*L`0m3pQ!D2{+qJ9T^6JmW2A?+loXZTw-A^3y<|Ea2a&{h_ zo@UPa@w(waBk^LW4S_%uXPU;%5V1YUuC9(R(WzCu3-_0KmYJ3HCX8(o#m5%TXD{(u z^nHB3S5l*%xSB_fR_ur9NT|des+5+bGV%!Iko>@tp3G(5Tg2~^>(NqjGpfP^7&e@| zhK3a2{#edT{7*hvHWnr;&IyFIB{VM=X`vsmw|;^XsUHof5@-}|0%YCfwXRD0_zYA% z6DTyXa=XUu^#sM5Iq+`^>@9X`giNvfvMn`jjT_Jb= zrP>cwJPq5Ce?(w3JK=4%qj|QrJfG>k3T-X(j4!-#C?45d0<0mBAJT?CDA8WLD`3C{ z*Ajm%g2AX=oHi^8NI@y+uxQb2}}bUMX4W3`W^@4td6!P3BH#9;---wNKBoERT-@$gR2hzzB(82mj&^p z#hGa9UbtZ2&5Czx<<>Ji!2L07qp)vvlF&OoOVVG^@VQf2f?dGKfG) zti3aZ1uu5?yXJj0fbTTyuHL`n6bx}|fS)1Bvf#73LMX#`xC9#hYzj^HBW5r7SRw}0 zvT*fN=M8Jl(8!+q+Moh&Ap>}Bg^5cP13wqfJn#PfPht!MPoWoKoODjP)j z5HqaaJ{tQG4=5IBq15yR$f-NZ^X^+`s7Z0yKZIV;1sU`uCbTURsLSiuNr&i_=NGbi z`^QHE3?bR{IqLErj1B_}m2a|}Nd6$F>koDAMWTa{?lxBHKk|+XrAPGyQ1Caw0gjM& z6__G+s`@nQxmaZISST3?Q#1iWr3$DEoIZ~leYQA z^{3CA%l-c{Wz9N81ULx#ucjiee}M%&0~5f5d$gs%zCE z3|#cqq(yu!`QpE|hW#YJzL*B zJg5*?f9~MJ$j8`Yxj~IzE2b-iae~1yemLb*s+-~(Skp)Ld)Pr-d^|2SARmx!d2y7F zWOdHPy2yD~cmFB;`1jFwajE{KN&~cCK(iSr=Q`BLU(?9DNIX4f^=8tEPbmv5W7kRt z3IaRU^0E9Snx*KtglQD=$#xk4mh%R(exsaE<(y02+O;s`2-gW>*7t|!LO%k8+r8I? zdF;Qz7A2>VSgCBt6_H(~`A4op!O}1mwNPA=?2O{8VaKZaG?Elt`cC5iKZPp*otFIN zwK7`q2-vKB<3KejermEHIDFm^lo$0R_hKGfLhQEUeLmSQgLG)M#X9T7uk*sdeVFzR zocFG}1G#80G%v%smL4TFpG}k+N`1#51Z`)4&odY~?L5FI1pRVjJz)XMZ z?4iLQY#JOpi9z#6mL}GF@)|0fOh;ZyLnG$8y`iSX!{bDsUU35_eewUZSfjt_{9y{9 zH;^B=dd_@V2lAZq&3OJhew+@N58$!w;|u-c2Q_EuVb9@U6etZ4X1=s#p7X@5bQ|T9 zkOj4?dxb~MWkn19#-F82ag;LvQcUOH-F%HsglHrqGuS2JI*zK;YRTll%;yJyYp>1Q z3nOEB*QN#dM4ejeuHV0##*S&j+lZ?VVjbSmU*?5sz8mr#SD0tC9~uB;Q}lzehK4*0 zb&bKSN{6RFrBQ){Hq(z0KQ$Z$AZ+32-h{($cdN#7p(G0)Vz&=kCmVo983#8{fIt&( zNY_;tG1gj}uG88YK9Kc^P3MU;-6b=y^Q?e5hDA{5{m*-I&1r6H$&xuEk6Wjs7~Zgl zt7z+g;-)eN-gv8BVU%JM2yo?ysVM=75X=)O0RskR+>zuX(C(9=+pD2}ow@ik0{{$h zoCxzhafU2tu>Y~N;j`dc)JoNk1I2G*n|c49wnmuL6y^Qp%G#FfsQN6Ycce(#JPXS> z1`2r^$5uXTYMgZqhVN%(t|iLVXl$Z~_lxxp_M z&F_ZW0_rDEqOLtoe0)4ma)A1CvV)vzaAHB$+7uKNm{Ms9UV_xsfo=?9rCY!NIpEy_ zGb!h_GENTfcT{R+8^@wS-Nv`ZlTtT#UqhkSrw6;1;rCrj3f8ND8TIpn8)>YJ? z&V=?T|3tzOz@x-6^)sG(q@ASZ;1+L!#TZXX$$$Jv$kclWJ^2YK2fZKpU+%3Ry8AFE zMb8DFzvh=4lwj2sg@hYWh_c`L@0DmY5?EXqXRlkbeBT_xjtOh&ToIkbV&;Z$o~44vm~<6Y|NmC@82;mRWnpKFxO zqQ8w;c!9oWWR!%6r#HMy_@I-Nn};V7$llNXYD09}sJT3=IETj(^J_#-{sq;7;4!0a zb{_pzqKd)wUu7mi8`+)lVsdM3Sh}{0Y6?WHLQQT$6p$bll!AR zme{H9Axsr7IZ=@219J?H8erR!pWi9^Kr+^di)8cjs*j7@ZZ@UbTW^7hxg~nkJn{q@ z9f|?S1;dicFhL?faCrB@Rx~i6P&)j>7>$Cya{fK*oBeT9KtmZEJyKQ(tC6Gqd_Bfz z@8!v|Aab%}!fItg0O>t6Cs64Df;XT-^{(z%t*(L;sb%H?z%CkHNt%9<|o3|K-_n_0z+x0_VzHu-$BdXb(^*%5ylVE=F|I zLwMsIjpukY;Uf02i&E~aE1uk<71=xD@YLSv>iIl!_0ac}HOqQvYvxv*u5nCRRc#su>6c5NzxaHT~Uo!N>XF2Rp3me%>d zeBNVSdsw=kV6d~9MyT6?>5gy=7JRBrsI@7YjAdw5=qa_O&1}cKm~#Y8Lid$a_0>)$ z>)N53cwO+xLFk@Qncb=zBej97-G;~D@@}o<$PWMfZQ|4OQqbR4uM@|?=m<|h-hcRQ z%g>;0@Bc+H|8ta{D7bQPpqKNBB|bn&uVj3a-eC^Ni41;#&SmGMJV6NJ!MW9a%>gW{ z0O=$q3(`!xfak@~W4JpSj=Ktj_@0sDU z9JEwE&d`x_G+<+*zk#r z`*+WSn*sr!4P8-hc=CH^w7Hd(V~XbMf5G%?EWILm7uaXX6%580EJo2}Re4G4Btbm@ zeQG?d&^gBfx;20xEyGU^gTn!h9;!JBYj(@3FYyL)(wZfPEHgt40}5}p$I8LP5;w?= z+TH8@9lF7*7gi0Hq&hmaOWYp5hqCn0YJ^|l(C@MN2SLo=uY0ZmbP057*k=TDRytv!A2MhrZkM?pT08;q? z@fJCEQp4#?zM5UjzSJe=d?c^*W;=XtX0r zQA#2=QAEalY8G3Yohgm>rnWj-ztYd8x&AwseDF#}jxf59Q=c|uUtEq|2Cce#_GhYz zon!sD{qN=ZP84Aj9AUp)9j>*~U5`RtcShp2*w0cn<$M}>=A8gajXDq$`mWm)uxR0^ zcAQZY&E)KIaQU^scChs8wxa?fP3_~y1KRsQ*McYE0j}0Vk84^yzlj-?2lS2pQqTO) zD&p0rtW{@F`tCOHtNIFBHMte($85euo8-5z_^JD}VwTYtlmKPe#Cnti{UShyuSq-T z_E1zTpjymmnHOJVh%MrB?|-=ffR)Ud{e!D^G@!t<$IVp|zyy?X<=9Zt?nd>v-q#Y7 z49rUCp_{v2Y@_+GMOtFXQ){v-VNoJw|MmNN-y)sr;6ntpHKWs5t?xE5kO0)Dp4~nk zQ0U|&7fzmb-*VpjFrZ*GAFvAfL%{PYt6xj`IPl@Ro3Ev?)CWn%%o0+I>N{wemZa$ThDrQ^!FY&1oo05*KAACSd@TD_a!(WoW0O+ z_jYJ5y+=l6-shRmz_ua@iLAKaYjMK%Jj}bJCP#Z-FoJY8J!wl!}rBRvB{CTh7n zdYhB$GJQ&0_M|y;sP-7cLR3VyqsIOI11zqW&C9Laxbzo6XIgw>tw#52OI%ZB3~plH z$xVX&`|6aBUNJ}ZS@u5{{P)1IUha-w2kdEtC+-G=appy-cK!xiXK4>hxQxh|x z$%+hsSvoYH@_dIvX=L8MpRHKcgFsH`Vy)0d&bDA6vydc10|Zjh*8T{5@kJ>Doydap zNq;)?3S<81?_U9C1uyzy(}tX#De%p9?k{%aAd|8eR7<92bZ)BUO^+IAu1Y`A+w7WO zd0IXgx^>2D6{Ps$z{&Y+o=E*wvP|iK;U_Vn8TF45V*Lp3&*KOcw_&5v=a~4U5}@}W zTb6HM40)|hWyLrkUY<^mWc{wOz1CkFF?0>9UZwC~xUy0H$~2uT%59i7I-@K~dqz5& zMJ#@7l_*a=SZQOuT#wE?n7J6r{g0gtnUhs{^ct5SKQz3%UWuBWK-Fz}IUqP=4R#}iX@iF7GF;g54(NlhoTAyO&CrDlg2 z8Bt>rc;sFt-)E9h8zApfeME&UE3s)??wrpcMc3)5sa4XIx%d=FjJFVH0KRfsEN}WQ z_n}4q@lV>&{c-0W8kd;lWXgkb0f#loR{B>7Rc*KsG`+rir62p4TAh*BQCG3nn32nQ z;+0j;y&F|4u#a(o1C#yWxa&<5;xB30Zo7y5Ghg;*PXW(|d#5Pexq5QN|X z0nE6p==B*{7i5pcJ$LY75!v+fzG`(-5wFgNRXi-yplYC~`Kh=Ba0YfXYEG^pfnmEN z65tE0N;Xx2LIz?Q?X!1Nl4X)_*gDQ!+O>3B`1T!--Nb3 zJq}aEV(3mzNO$jBJ{Mb`#SgRw*bh|W&V!VCA{0ypYgJt@yRL;RYZ4;1CG~F*ABByr zQ7t|`U1cm!qNv}61h=MkMM!e!;3}(7y7fI*WS!~CUr`tC$VEpHzi^L}Ay^Ab&N&+@ z@c6&){+v8$<4is-yHS!fce+HsjZjqrCCgL6xTM2Tt_Cl>k-CX-Q@+N#Rt$k)7ZFcG zc~#}+7xuZ+Xgs0u%)U+U8@tWJ86_3osmaRG;jnj*&zU=UoVWtFmuVZlPAeSLqn%$@ zH(773nQ_04w=T^pAeyO;ibpG#*ePQIf@3ih3@*(xG*ajkv$%PjOjMn3A_f8>Kgv;0 z?K;7rHEN*hoUyO#MK3T5FwW1_JVTgKay z<(4ybu})hEPLC5yAjXt2F=4#EJe5&-Qe!h8^@Rc`C3|N*!;jywaIsZpbB%+a?hmwB z4WJ+aU!;GU5YRGx_p?=~@NC>@ubVZk_Ja6ji$KEFROsN>eA?eS79{fqFB!Mx((-8+ zKGWc@?-73NA!yBf;KcFy{g~k0C(2@y7P8U& zNbMcl3z-4gbTlsrc8f<(a=tV(mn-}I0c$L zXCF2sv(N!%&Ml4(s2C;Xq?KD1xnq}&Hn~^i9Rvjzz-C~D(Bk%M-LV3@2AQ7LKhYNc ze~Y9e|5i7Mz@LsUPcPVmFB*93QfMT8G0R65hhi9Az|x7Ub>)nWRck7Bw=1ZlCOr$k z_9$9wzJk~gDs>>y)4*jIM~&(K%=_HL4fQsDp!o&-z)T%U*s(Ma2#V$SF2$vYXwK?P>3| zzjZ3Q=_WDSb-xnB3G#OSSu!z+Ei)Tm?}HaMpX}->CtJ_2q4}{;9s^#1EOgerB&SQQ z!+q1H1^=WEJq{gDZ~*zbgqq*>xlPNtN#p-ShGTNZ=OrG|Am{y}1gi=tu|Kn_RV?@t zOU$}#Y>t?RjgKui&nB1olLwo6BQyLD=lk+CDXTZ*mZ2W;jUDt5*H;i=8f%b17=tS3 zD8Z95KX8$>C(9(ftPNCvv0>sa>k7^#S1D2#mo|$pg8d0BZ+ky9Vh41fgEvN!HMIE_ z&5ll3A5p)xo{Cfq0gi!cX`WzwH}I4L`<=EngEU&2d4#Rr@W=1V13Mr=)WDaDpt0fi z&D3fHnD>c#`5^3_{gpBs4YiWxgqX$OjsuOO_KR!JbpCJ2anY#Un?vjv;_UhbTy&ifKcF+ZR5K z66$8fke!95!cDCBMQX(t9nV&0OmlURsw|);^`qDZ&J{N>)w1}lILbX1EEx-XeOw)(OuCe6#dk)5Nhc#>alZvKTBvsCT=`x>JiB94Hve}ssItdb*J-dV^HJJ~ zsH!h>XSotCPR{4xe3@6mn99q&=Lib>sKLtWj|!hw!@^Y?Jt+Po9O(nrNAQ=HX zcQz*nwXSGprkOYWfw@XlvuHp+znLC#*rxuDM23sQidda@)@H~YH%1aVR{FFUI9Z3U#mlcNQlnLOVUJM2c<~UQYMwWP9SE6zf ztOQ?_cp{ND(lza<sr6|AzHoC0*iJcW81n8fhIv_jqds^DeYzOczAq)zIAQWM&VcE(cP}i?7 z9SvscRyqxi=Kq?(kxoab5?S7cA>P9$_!84+v=$_!q?7{o3^~$~hWiU`z`PF#1X2v` z>UJ*e4hj7RvZKq-KZeImZ;P!msKyd3ca& zETA8sFssG8=bxFsil+a@F$lQcojhYIPyVuWF&UU_WEjOs zPe`J_F{BB~l$ptpIpsgf(0EPOwCP>lg{q-kCK$&h>#}Gr1ODO5p5M)Vkr}3-)%>Qk z_CK*NDFG|Ev9U2|;R^I%OWI&;xlcFDPqgLBKCC1*MCH#LBJab~D@~Jp17WWE@XWF6 zE8#OkR-cDZWeW&lOal2uvZD>25^6C0Z=Kz;_$~_@+ZuYppa3XGfm%)Owe16$N@%Im zk8*M^MMRqQw#LWDe;NNxV55p9&Th^PEc;hKxjRqm448VgYa&jVPI5d7TQ8yroQ-wB zU@8FFTd~;$7q-QRI)_jR^Fh5tT&>kT(#=qCeCrJhSNsCKl3Bz=bz7iMmRK$TiMRAM zWASElYNzIEtDRdYS95yb(#>vrrzU^Nb|r&R@lgK2?ZOdwi9@J#FT+7>VyR-$F*@o} zfbS;I`}kS<)FYr*74pioABGz2w>cvo$ftevC`sknphZ zG56Vn$9vHuE4DcQN`}DElg!@24f>J|)rf&$7c>z1{-LW5p?wbQ@!VVnl&Ocgh33x^ zJzpQhRm^?~hc`Z8lm!+y`lnS*5D68c-c_Wz7p6K}ootQtoA24!_y&`gpF9_(7hT~U zek%!LQNQnY4^=~xOC=CQ=Bn}fafiku0u>~#l9kE#P(Qy56}3DIk|KuWH?Hy5gISSGrf5eI;JGn94^i9FJH6{@%`pEgdJx1svzGyuz-L7m-xErd-hhK&!i7S z)stKeGygyPdw4jiJI*buVCK)5_JA?o0orh;ohyHJ_!>G8*|kscfh=Bu9;#{%GMuJo z4!|lpsTn7L$i`67W@{LMFNv)}Ai2~fHF$)CO5x)#nB)6+Yw==?7zK{<2$MuHR<$uF zSlCSa1vNq-CP{_V#rt)6#AGQ^@t^?@8Z4U!k)XmG2 zwDU9H#0QCYV(Wk!Bq*Y_WZ|!#_a{lBZG6!j6#C{3Ltd`qa$x|m%=d?dAE@pNo|byT zx_b6JPFPJ8s1%D4P1V7Gxnk5WtDXI_?y=WAA(iuA+QKs$T<=!Dd7B06tIm%TWb$fj zqB}TI8lOq$5Vg8;PJW{ckZyS&r%K3O;OLq0Gob}I`sMZI^li}Q2v*e)Tm^b_xgD>U zfrWD`5XD*Hk^#;XN=7UNdI$hBqJKnw19?GMRKs7}lT|mc3UMpEI7W|gIgY=87v)y> z(ENGC|Mk}?vbm3d^@%uE?J>y3AiR7p`n?&8fzTD(geoTh>oa-8HYZ@OdfZ)85)!(P zH^z{b6D%ce(OxCZK>)lS5dvC#8J)AFzP`;~4J+zv=6UO}`oOx*$o^?`XKqb)06}9= zY+U*WPof*4j@xs0Z=ZRI;!=ukc(mw;xn9m$j$rLtyzF^Y z^r>26+`kv@$-ijzu1_Y;lcO4bfEir)QR^>O?XJ}uVTE@k6K_?`AY7vaOx!$N#eFuH zH6HQQw=Y_qd>#*ar-Dqv=^<)z^8*xOU<`IPi|Y8j*fb)v)(^l*0T-W+Tm%*9scf)D zmDcD>0QK(cv+h#2Kj1J;7k6p{TK;~qu$pr8kmeB#He|m`CuoK-pXyfOaJl+@h-2rY zFgQ=`U{5UeR-b3&?X2Z2-!7^F`$j5oZa4m3T!U3v`Bh%YGstaR?Xo%H(e4=Ef#o5O z@OdXqT6$@9v!Z0WfCl0s-XhU<_JNJ0T~pL(`Q0w+D?-XBV# zy9RP7hRH27%o>KH0SH<%iL2TMQP?st1LaNALoCwJ)GR7HVH%gb+<}GIaWLew%;YcC zN0<~g^7vM>)K4-PlRrlAb?ZDGYp5d6NTD>54gbv5(J2qP`2BZI3BXe7T9-RIYYx-o zwURp7St3V|uZ|s)D$)SEt@wX&^%YQ2s9o0x3eqalC4wLg(yfFbNOy}!cQ>d=mq>TV zFoXz0Ge~!rba!_Q@jrO)`+eX0yDqNlTDlmXI_K=Y&p!C2GhO4xXv6r4( zUQV6sArp&$P|PX5L=E4?ruw-fJSiThUX+$=N^f-#MtG2d**?@jofNofc3QT@!J5@a z+#mnASs=B|WmDr`72ifX^x`;RkgO!j(em!Wv+J3tb+IW^({9uUs)L%lAS#*=90Z9U z8$U%!KMmj8J2N#iGoxY__jm#&i3xPbnrt-7ZAkPutsmNmg*&f6yr$eNOZ`&~{rt@% zRTU?-UKB9b)tBggA?Ya=x3bVv0SkMa=!(PXm0Q(S-&LJzor_XV6we*?zJ*V=S6TM_ z5hyW~GSaOT*zK_#BX;jM!;$r+jI3$;4m>Ztz@o?OU43(#ee&vhRClQBOk+@M6rz$u zftYm1&RJ9mgtx}T#kuT(?4#C$EajK`iMjCgu`-ez|3)^B)zVH;E$`ll3QPU5(&_F@ zH#v_^=VfmUQ)*f-X1_>#IYjy4I_g}CJsEIDo8N?%Si2dnzTswRh?3NMxte8_cGTJS z#9T5}qH9&Msxtq}J<8hz;Ni-Mz0~fIZ~H=C_{M_b@>*m<$K!ckxO`Sa_k4&`gnhrr zX8iXQ37^*NiYwXJxrRUwZv-y)X!d@X@~e0DjGxn3=MaoCK5ncsH=xzCL5^mloABZU z4?1x^=a^HRB!f*t7r8(gQ|W>+W7XGrB0-cvS zy9iQI*vu;qHu26J&b%TH`p=+2l*}Y^U4$;#?d&M`dr;2y=Q&6ry~!;t2G{3{b28P4(tX3I zkuL*k4*J5L<|nr7w6o>9a4h?iH&jD=(E}7eOE! zzmPzN=%1LFh*Pu$a7V2Q^y}jzB;NI4m!=^QlREk_tR5kOyt%JtP=Qf(d7mr1lv>v*Ezcy2i;>C=1AK4Ly$(%5$ueh-rh>zbp^5*MVqj1v~1^7x;ol z5=XBTa;|Y*WkwoIShAR-1aY*c3lLGHrk?riE?OWj*7D_-x?LN#8o~gkv@)O_kY8Kh zXTFzY%}-?~gXp0n)Mz}2UU8LKV{0@?F~Rdx?b|X5jSmDL`Q$fY(e7<26Eky|jn|fT zC@D{0bxBoKJb)Qy+~oi4MHCb;)akJbrH?$Z$ZLAGq|=Wf=9Z|J_Nn`hP^N1cw&M^Ejp*2B|) z%~?PlT+vW^_BloMoS3(aI-F4s(sG}~D+TJ!R45h@atY<5m<*cGLi5s0~UTUXcNfdmJzToL;)x>ULr zrfQ!*gI*6;uioe%HUoNer*7_GcH!Yty({N#`jXMu?#G!u?1@|CD zN|0>upA_>V^$ImZG)A4PSX-8>_JufO!uJm#=N6qw_b=ZK>kbp^A50l*V;&qUe%+gf zRZFMnJzQOwRz2&+RCQu+W4)3DG73Wv({irxQyTwh!y?&M;j!;Nm zRu;RZ<@e`%Bj?wyxa3Xa0|PV7PejQi>NEZJBGX@D)L36XF(5(}xmv(Y5b+Vl6*_(d zYyfneRy<#Ea44$A*mxf$Sy?iLrBZ^PyeCKGPO4&0Wcko|k>zpacvRdV0?;LLQ3 zSG=Xa7`vA&O~z*M{IlGxB1#aHw4FGWgHH~9f8%iOXt64Z{^CG08^T7lMd+Da|G5F~ z!FMKmkEqGW<@$$3gA+2t2U^|6%DoG`E$1GCn?Unfx9hq0wdZm}$#d9Ts1YeW?|co< z_rNE9FPG(b0b>?!XT7{mk(7b={y1Y<>v{U14R@vD_Wf#OT&2Uot+=q-b>B5{NU>1F zd;FeI3(ec*-ohDslqh*@%96%DmnJ>mWxnaNd2Aimy5LCXdnQ+>PR=Sx@4J#)vcDS+ zA2_`IADHFMwsks#to{TK(t|C$mlx9)`M;Wn!5#tdpopQMEp4XP`ix|Hh_G;fXMBj80fUL5LG#@)b|5Q!$Zeng8upSB&d4am6h`U0j@Dv70*G*waGpOrp8VlI4 zjg8~w*4On`aLf`c)U8n~Pl`;j6sTcGFyPlCOXzjKNRrsyd@XP`AUfyg& zTuPE-TOaXTrXsejKV?VC<%1ho6_`?Zax@ml26}TaN(YSBWMXJ^0zPvu+fzDo;$}L1 zEh-PLvtMD1xmB$fXE4VxRbG-I{!ljfZk7jO$yi=VC=+-5RBSJUTH@*_wM)zzD^x*f zus$g?_th9;{LFfo;8L$AqI{pI$UsgYk}IM~-ASEl$R(teBI@=ufV zHc?@%+?CA#Dad-OS<5^F9qI*-900WLxjpg695EfcU1v)-`7um)lf`6q1dD@u@z*K* z+qZld)O|((a0o3|z3!$e0IwJ*fX5De?1=r=^rcrh5|F5lGA>Q}C7Gw5I(4t47Q(9K z1Q>_nNZmKd+Pq{xN@JK&zb)tMhmdEFkqI*y6g;ZeC_z^cAWcR7WNd8T&0M+v8wFR~ z^C~yV`s4XNH+%*^cSQsji$T9G%*_IL(6mv9lBXZ_4W#4;|3?e(V~u{GnLv3_io#Pc zYtJ+G%qKzYc3wpMxc{66@8&3m&{rk#w#&%hviVPG8VMeBb7;?K&N>E92~FJE07}EY zvdEZU>%}Y~=KPCgO>~!JNVZ(R(v~2|b%a8{YdGGIj%nfNoM2Kkcl=rv&`pT$4V|>28qI$#6<81v|GC0gLgkIF zZJ@a;7PzlL-C-6aVhUX5&4>QqrAPJ)hNYhWEph0RFBtNyQ`^4vE+uacANKUq_fLxf z_%}4+ZO7%{fRMY?)`waKm=c7h^ZoN6njgKN09ySD2UjtJolUP$)5=qb|3*SB-JCK) z>JFlneE&Nh!Lp*C+I)FF*k{3U2LZpE_^e7#R=e$Q$S;m(nU9F}*`A9v9XBfE9SWNNEDnZ-Z}Z5Xc%qM7VO8LF!;j%(Km8u*W~<-NmwYY= zo3U#r2Yde3)3Ps_Z_q|+qyP7k?)Jnre!v#mmnW1JpBu+VYxgN#1R?C$+jAA+Ul&Pu zsXfI==+cf1*x8d{cK0Jr*N(<^+K3KAp7Fy0nEi2DV%bpKIP&aR|aBFck0Ab$WCZ^0rs&rdGFCr+Tu*`0|ZX zZB@1v2aXa*-jFfYjoR2c6|m3#KGxXl{qvwS-=$!kZ!Gy|@pD4qh|$?U`$Uf;!phPh z;|6S$vlr-o2j4eJoLK-W{!`R?{1@rebY3cLozY%oA%ECdq~!@Ce@QO;dzjBJL&=V% zg?msheI;oOxIbz*ZjJs!yKOVBCjx4Yw1OuWo>xGLW^YYLL&FA!LI97gF5|eH9r|YV zCka>A+V8aO2!bGarB&Iqg{yzW_uaVC$lnt%>G?_7-x0|>&a1*~;lJ*|jN6I@BiPZGD zdT6vAao$|UadB=E#cQztki}cruU2igFEm=s`|-$Ihut%IgK_vovWS&!5}k|=V}AyX z+=|c573o`eWIGQkuJLxnxLp^X&&S4=`_ZxCF}ECtC22kAVr}dVw$FWB56#=!T~0}% z=4FOUTgwD@UDbmEx~>a;I^e5s2a~1hGx$m;mAu0mk1a7Uq*IVjG>%fZkxtUjpN`BP zJXT4&;|RuzwCU;TLAJP=?u7)-ae6v_ZdvZqF_V1jE7cSg)8P z!T`MHfP*7=B2q47?_FUQG4z~&bN%RGsK}^_?Dplmk=7D}Jr|~q$!liJEm7 z5{DfDF!ya)wK{d_6uKl7B#h6?zB-BMw678;0g3qHK3;$#!_)HCM7-FqT!aNaipsX; zbCf*|0}(!vX@3|idCw-k&~y4tBfT9HKQ2U9jDXQe$;e;fljT+#BwvvLV;{_`KAhfi>Yq zY~=i-)Hda?ilX_5@{-jvZhBL<=JxRb$IBOOl8WBjOHnIxOTUKFe%(YmNQH6NTAuJ> zZCc>GxfNe*I&0)pV^9dcBdMg zp}^SqFnwzE@BwkbOvDRXTI6p%Ig|Kcz0U~*DeU!aW%QqY(o;dQ>J83clYlk9F`4ae zRm0S;jj^)znDaNnzJG{Z)aOgW@}2N^4_iX1H!26FiPlm|Y3gB*&?j#H+z+seYulzN zS;T;-5&itPs=@Ha9yYPDQeWLO1|I1grx_gao$C@I9T`h&rsC)7%0Ed|f=CWs6<|Nf zEm5K^AXFJHS37))VU@KKiF=$PA`RetyQ2t1+muLBxMgF$rT(@as5jVD$pOE)v?#9G zWZ13QV&S%$YysfFfvX@5Ev=H4R&f8?5|9rpEl0^4&%wQj{2KuY^rzl~2T1R&Q1hjG zkWeeeoW@2Y+U7)uX55qgQ`S_Hz-yvT}d3W@BOplnrOV=x^u~xlC zLy?rO&(;?n&FSt_BznyD4ztQW^B!~SE+ecCc|2R&XG%L45xkEzy1QNN$;HAG->j^Qcy0yyRT^c|jT zhRMa4vsv|Gcw*9OA&5k1mz^L3sEWloi)liXFiT~XqY>wT`Plkr3y^hUFa|DLx9pM7 zH%3<0z1c`=N#`?OcTNG$oz4BHuY-glhgq*E;=H%8{OR6~$1Zg!zoUo|+vPK{?;7~l zQ4~-cEqc2Erkl3eUUn0z`SBW)3A%n?US8g%@P8!g_@^&LfLPemwRQ}=IiS1(?UG{> zS>{tiIWqs;&WBVrKgjEdsSDGKMM>|^_rT0<%l9hdLTG=M`AQ4PqqUmbOaXYQ;C(N< zXu+G&h$3@U*f07HPLB6ISRBj3NdFMjtp&nG9fc3w>V%8KgL{Yeg#{Y6UO# zwouq>GdY!v3IOk@|3RqO`_qG(;^%Q?)*(OM6#YzXCa(QRjt0)(dmb^->G>tR_d@#* z1{`}bHcq6t%`e#cFlc+D@oXFP2QK5of0dVW5-@4JR#N)m06fZtK^xLeo1#-#X%yYj z=vtb~8QWzx;0oKqNXK_iDl8}LM;LB^#w2Qj@-CSD%QN!&)8uCJ#+5&&PVWBG8I>Y4 z8TfccsE1lqyY}lJBOcyL%%%2kJ!N-QCoya)dFp23=m3EBGZk^BR55V}=m$VD#U|*_ zft%lp^JpjiN#R({sZQ1hzdVX&l-H3;;*nY-iw-`38vzz&Y#unO+O8*%1cN6Xn2$Oz z(^X!|S>IlIhM#h`F!jk@lANc8A&J=(%Sp3ME_TQ#Z(T9)UY0pS*(^LFC z`}~aTFIuZpIc+~IBYcY`v&`GW`)~^bey&Lr>F>vL?5%cXTduklIYT8gQ%X1pO$T=7 z)!@=OqZH#flsnHxt+zbJy2|#q%bSKVa=t!Se+;${c;&v6Fg9yJI7Nj2DCX@)ku7rH zK}4&jSWFR2ckyuZjF~NM=`U9@=nK6q8>|1zkNV41<$&sa$e6F}fGa_reD4;drJ$Lm%({d*QGF?8V@qCgW+~uTwIn@6-7G_ zKo1!h@?$LPg8SxfXY1p2*)eu-#iyXgw>K;^-Y$XK&W2Db^W26>h}@28U;zQ7&#D%A z7+$2pAeWQdi=*U#%-2_!CsCZ+r7YlRMK2!Kf}=YFo$mD=c2-HOxFFl0mCpGJ=ow1J z*J>dn#t3ZL_LqX-KoqR7V`0zf4qrm%^MZfR3FBZ`U*E0(;~0@bFMFUtp@Awl0>b(7)8 z&%DI&Y*}r~WF7=L(Os!(2ab|L;O3yvhs7R`8s!<{R}uNp4vA-35G(8Qn&-UO1Ra>X zh#cmzz4 zRH+eTcau<%VAL4|QLhKWju8~EM9g;MrK@5fVW^0`I2gG}Nu zDCNC87;Cu*_&>HCX%LZL2vbq~MpxwM;z)K19?3MGLdRA5;;bHp+W%z|B*phk(zZX0 z6vK;H^CPO{Tmv^5rpOMp?l<5#<1;)uu^1qpn3%}U%M+*!2?^=!@83II+p)fbF0{Nz zET@+{pJaknBmHj^#w7C2XRyl3eQW}XOpvehJ*P6)u};Rz6jeqt??>UkfOX3G8Tu(L zsHDAJWU$Y;zj+hLK|P71G%X9+2_veaj<%C>EupL?qy5 zPZ$bNN_RALa3TIDWUL$99Vc_dsWTeH3v$V+p$$Cobdtf-d{s7ybFgju$aeMqs1QF` z@(;+lqctwg``A_L)!NhHe;@vI565Zf^cYzdc|0zRQB(y`wAKoC_|>8nHvQKC8Ci3e zDf$M^A3)6q9RO2H2D8LNTG856go=heO+7umkh9t`n;~VPe<8u32o~wVe=ib>>dv2q z`;biVm)5q@ghVzUjTVaoihe$QSES(*7s)AYgiD);mlwvUutNX`IdH%~vK{br1KkvZ zJ>S`b;)lFTWsC}UC|d}Z34A!VWu=Xes$j=dCF68u|LNph4bRZ!-y`Gj-{0F823lUu zet*eg%S?q9J>n8<0m9?aSko$QjW3HmCmcm%^%_SOlMz!#{+kp~rC~S)MKY?z#?2TR zgyD``?O;z-?E@5cnHt=`-CV%3a??sy$C?bwYYttp8LHr`O)u%NJvFq}JWTz_)BS93 z@95V0j;;8wPhp1@NGr7iW%l$1@PV&bo!e}#8#~bZNrK*Y?aav7RDU3ocX|1(rv$=0 zs1TwOO4f`{n+4`QK}E8hXhc=OL#RDfsZE3cq(s5U<=0EKO7b|;fK87sbVYSqBY_AY z@pCG6slb4h1mpoJN=kw7$?jZ#tjpY8E!fpS3gYdX4)stVXzl}?m#mYMlS`OnV17<+ z?vLnbaWyqHXm_U@bNCB;y^z_reP)BC5*~VgpDIWETA0oGbbucE8?s3)#@8^h8h~`m zf%50ckTvU;_C9ZExAkw;it14-W1*x6CR*d;{TdN-J1zyBK>kfc;R|G1SP@@*B1H<2 zR3QoqJQ|G_<=blTogzKh1_gPJs2Nusw$9_<*U6;nk=+>nq+m(U#^Dt2z#5;(+cbf* z1`v`v8RNo+piK~7!KF#BiyriJeQSZJU9vmfT zg-zTCn$SB5mvsBQo5FZ|1WrO0$IWRnK_wp9pQ5zt)TRW#dcbvf(Oy%w4MvL zby&!_cSW=O2lR0`7kte^FY$fnDqY4ZU*0-Jlqj9EG3c~aR9WGX0wDYEo6dlDw7Wy} z&X849RBYRbO&pJGznP|iQeHtzs|!%O&xKjmV7vriBi%{)@+53V#@xI(nRRQ*YXk0_ zLjtYUhIxH5&VJwXbaI*zOiXRXSq*)RcW=LDF=4)}iCdrtI)HjF9blq}>#u=R2?8#~ z4niU#ltTR&&%xaXy9l&*?%}Ev5H+m~NQHQr)@3-40;4vVgLS|_w3JmM`T+Vw_4?%{ z@njDc-Ze7$PSE;Sb;CLX)pYLgnTCAG<_O?Dd?M#2<_LCDKdFx6cv0>VQmp-P8jGRQcV-g^IH!}E+J7> zS2s-DLBvKq5_)5?L$Ojv(9XbDB4I@t|g_Cc6fTL+1BVQfX%S+#u< zgB+}t1a1W9*1n_&Q-c@vdQ3j4jVY-R2Mph!P>r%86#OInbI?C!RoXSie;Q%X;}v(f zahvYh%bOQw53)SIUH7qX+)#xVf-v#n8g&NX#+-R1>dw^>5SPhwcPQWfd;9)L5yaJl zwVkN}ZtWmCBIRH|X`pvrm)w|fXADl$*t2-Q`;uy3N zB`a`hfgTGLhoZL}duBAo{y_=WT8KfS_%^y0(8mRpu#22z;>5`VLLk;HyF1-Yg5RfN zVzl1?7>}NE$mmOrU}UPopQgXFm?QIsLWimjj^J2p1=ms z4vq#DgNBtS=wg$5!2mqAOr!*dGh_5w23F5fvXAwzwiU+_s73g zm(2@iLlwf@v$ZdP!0v7M!nevD1NA1n~H~Dkb3~AR%nmVTvmE==TaHg|!a-7cCzC9uzDfBDxbfpLP z7aU}oHQ2h`2hb$H(U@HUf&weeI)JNuUjNw$O%2VWTVhPE9hzV3`%x7Lh2642ZbK?0gyi?U4BpYCstPfhGovKkt{U;GwNeN6V8!Rw$7#{hNz;);m& zWpGkFudMqJ<m8r9?e{y5M*4J3*a z&Y3A^>SLP}0h34so+M6%O z@voq^xG=AaGDEv>=We%y=vZXD032B&c0APVsdahrqIQcq)nf zq1NY=rqv_Mh7qqv@SN(_)1BGqrXmjid3-72MKP(+&jUfqo}bEn3v{>*9b>-a0)&3+ z&hGU6IzReAY$T5NMD{JCwOi=-ZYQ0>rTpSk`)?k(0Ej8kRdK+Ofr=4B!^+5HES5jw z8WGKBW!;a1mBP@|O5)$1erjvgag`DI704$M7G>HO6#In$^LJSo|DcAtd2k`G+gF^iO=vU=x=j@qB`DUGMvBz}s#Y}X- zoHn9_xw}q9VaV$pCPSVVC0@VRmGLy{cN=tsypio9V>uf6%g5Ncn<>h}J(dg)pO7hf z?bTJBI<1G@X75+f=c6&Y-tILRHzvz#UY?=FJ9*NT$;#^^D#kDrcBDt{ zM2)K1R^XKkePam3m3vHci>F^1IY_7eOrEu_wrQ!Ryeaau0_A~uj`TCu`RNKD=kl16 zNW*zO{7Zun-5e68x}kEe$4~{3{3(pgrs~F+SDs_f`Z)9S`AM%I;1r8q-$b+boq|p( z#C9^co>Vn)_w!Re0VVw{;@s0(*Bv=xwk-9Qg*PTBjM9D+t#W_p7hR{%7N!!dEY0cb zVRmj=%G%)6m7qL*11P&c2M0X;OVE>a=PzJQwAa2fR*1aoq^H4pzc9sf8(cGFbGSdZ zwphJOs!{}xqXUC#X4F&rkXq+Md_=lzg!xmnZQ|dUw{}n8_IS&ssmOH7Se&=;CSVrB zztnBx1== zlK%ZiuLlvE8w<~@EwLdkyzj>g==q2K@vGBV){Cikai#m0mWzzz2iuhDhnIP_LvBYG z8+F83AyJ%6I&%UgVw#BJ$8#c)*`EmCb#^9u^nIdm_eS$LvAj$g^*rxiVM2JIBT$VT zCY;6(Q|vl_9vSW4%Ak}rXm%&YupYvFkdLhE!yyR$1^NEErZFPi@tZ|=;~eeV@1**1 zNfbfG#& zz+(#>AlapclG1}98d_{|S(1+9>51g40Nj@X=^Ur$NFKA^U+8YHUQv?Ct!-24^s81= zZ|u!A9l6|wWXsV0I)f3qT17?JsZY1{#)Z9jhi>~po2sPliZ%GAEC$8b;e4TY+^#YI z<|X!+dk|rS$(c<5;U?X6NA)WAYQ$uteq71N-o7`cq^T4uAE+q_>YU=s#M3JK@1{Pe1WHTi1tbt_7eiN;Q}K zIcnu0j2>U@CGqS~C3TS}irc*rF#FnX$ljDBqlxn_PrgpBHKS0ESWwBD`~o4TKvQ4h zM=0OL_$Y_EZrI3oKGU7kP5@FC^$LNh8KRCk-<8U9ZRJ@8bsY<&^;UcnOzbCHAjw%J z#@Dg@TkLZtfvVn(!B zMREU>7;X*4?o#NV=`@{clQ*>x=P9aPvDZ39HP>ReRXd8@w6$-YSud_cz*|fb;{#k2 ztF|e;)u+=Y#^>6}*DS8QX0Zh;d&gbtdUKDC_gT2>>cXzQ@yaqn8|FOOWh%mG_jX&S z9Z!*P$o35{8$K8|=3yOQ1q#GX`GI?jl2k3-8Q3s=FMcHdng1?ih8%5%2S01 zZoja<3==%;=;t*&Yt}g%2^b-n@e+)K>>5_IroLWmi+y!U6KAUZ6Q@e_0A#M6f zoC<-3H(Z%=Mar^rz)I(^gL39@@@?koawzSn-<~Lu{kyD>YrWTi96;=?KHE6g836NjzGp_RsfNd~WtXcIt_d0I5 z7+96!N0U%cXNR$Bv^UPW2q-vFV49~`qK$m!z-5-Y%Ox`r?}mH&*qlobV7R;%yVO{r zA#?)c?L}Lazvj!|y`(H!4GOECMvSezr_BES$F24miHq& z@y(1Vg|(NkI~D(%jJeNG|C~8F9&OX=cF9(*vU8|@QC6-xyzN`uz&5)2Fp^H74!K>I zpkNgY@w4eQTz&R{Ho55&5-P{qjmPhOyZNIOG9r#21x@nji*16m5&hZvIzoBxllsbe zQ-(~6*G{%ATpdm|e&7>b)`z%W`ac)ewq;ma(PwJVR_7LzFtPmqk0 zGkPui*hhDD39VnRFZ!`{N6ojr6g!p@ub&YU#IJ{pm}(H_eZ+-}%J9yaTkUpcmwv-G zq`mV=5B)IC7FRow_XsI)(#!6$0rI=lXHVM3d}j>5}h@nVXhp^Yq|rv*y!={Y|P z;atkGMKeU{6ESox^2zbZ?`OsEEtcYV3fxh&gwkbl|Jl;-e0YXzZ@u~w8m>tNP7~hC zP5xQ*knXeiTWJkyn_8&Zw&5;{70BPqWB3L7BHoU*IKvK4@XwJLKY)x;F0cR~*XdkU zF(u5Pk^Qv%kc;DeG)9hcOm5>)@A3Dk&4hx{iZj;v+NQPbfY{uOTumRUbHa-S)-Z&F zA0y}eQ}v~}3IghG^A!vA3{*w|GXk@r8g<9W^73*DgdphYvtk{QInMFgVGJMh*fNbI zfTw&=sqban!d3KMS1Z2K_p2%JwS?;T$6C;`Z6Bqmd3K%-?KsR5%aP-6sqe36-DZFM^Hh!0|``L+ldE_T@maRR7yPMk#iXwGqpLXLuT zI6wP0KFRfv^z5d1qaXze0rxBQ$DlAqBA1sW5-ixJlkTm<)BS76}Q~afz0P ze5czC-f^smf_t}jU@;YCF-Tiq9QsVMGcgIm03c_Dp+<-EHK?+pz6jA|Jq4Y{eEHi- z!w2nLTf@g=;1?3(*J4R1)LWAhqsOWa{_DVmn62=@JLjN+*uYJa+*P}n?fQ*5d5=}a zk4N=-T3U%$BG1KfsqUEv5Ua%2bs9MQ*pd}ZS^v1IV^%$zyiIUk(R5NXaHqB z>|TL^#+);juv%_C`4WB7wZ9M~9MM>R6jj>W}!NgV4>9 z#eTKzhb@RzodmEtTrb_WS2xtgq9+32yFOF@o)2YtKfVO0(J}`-vHl57+qB=4iqUv>> zT+xRcvz$Rq%yENNTx~@@r&kw>&EeCj*@+_6%bN<_y*#@ub6Go3e0mDZ*f?rsa2{5F zAC`UoCfq(mCkS2PjbdY2Md?TUhys`hjKRDWdWt#uaR)*Gm0+$Itf)}6Fl@w_pgnp0 z2Is-D)UW3*qEDXu*xv2gi|BlB%v0NmD#{|<-)=~0?QCLVLfdRSbLK5f>FvB=)`*|x zw3mev>~`gN#DPJ+vmPMm(f!JtprLDO4d-|1nv=ELkt}E|IOaX-W|!4pHNUKUqt91T zTO)Y!;oV*I%iJ17#}UL&M3y)bMpzXUt+`^n%hJ3JdR58lC~)$y8~mNX4#t?Xl+40H zrtO{H#E+>%lzJ5s>Cw0KC+K{0uE`rqXvCDpn-}0I8&E)OB10!)3L|e*8WCozZP2leIaT&v5_B`zkTKx!|qe>{1^!>xpryj}Z&8x>s10?-u=JQX|$H z6?}U*ZTQL4aPmJrKC`-#*c)wo+42lxD3qmp`|ReI=ATkMu$vpMks13byS@fN*3l|{ z)dSqcq=j<)md;V#Uaztb%O{i-orZnqvNnNz58b==l#C*YJ>lXg_HcNvp*Op>&(Kr{ z`$f{(54Hu1>`8`vtGRm*FD9xeM0Szk9P?^=H%Ahm^df`c*Ias@*I31FW}NIb;XhJ) zbEv&LS!1)6ybcUQ!%$vuA3B_g_(AhmlEXy@2q8~VlRX$+Zp?&5ye^*5&ai)RDDGM9 zoNEwYSWoIC*?=d?yO2}oM z=0s?YD=Mwj;m}PU0r*245s4e^UJ<2eMZNaE|H(#k?J%IjsuxWf& z&sp}$cB{rK)&GiW^6w!Ci2{57hjO=TCJG; z0Mk9}8kMJ?w0k2gjZeV8Z#C9t+2Kg@8h!c3fAj+L{9@Rf;?{u0#Ik^f#fxD4b{+j~ zTI8FOaDLlNZF?-?h`qUl{#FqLN}L?rSMyAye^6hjOV!Z&_m<43tC+K+^9aevNq;8> zbQ6be4jH%ANYaG5{HL#27yI(Odry`~P`o5b)^uK_qFK-N?%;;M(7P8s{9M@O_7l3c zIO%cM@-G3K7q^>fN0pfR^8#^Klno*kp#dx%%gtgesPAhN1H4}ab8tK_5q+1~_01g$VCHpY0JF~$|>^$v~j=Prq67h zbZuq*{A6ULIUW)m{L(H*Nn}+Usqg^>-*K*!4+NTqzgxX1Sq}U&)t7yVAKBiw?Qxvf zGRGtg$*?vi4^L<-R6>L*3+d8*$9tG)f}v367Me$_il=s<2?hutjr&u{Prdm{ zw9^s!e4Es?RKn{?Pron&c&bQuTDvM*M;+VUQ~#sy?9n9zQrMa>5EuV5qv5UYsN%Yn zNAhl7MGcOLD5X0WqEP5}X_tBVxww06bgmV&pgH0DqXj;9ZoZN!`Sjx8EG?EyW?wc481#MDegf#w@$Pc3Ospz%(coph!nI`RK)E{+2e+JJgDG&nD??U zPA1#jQeG6R=t)~*=orS%g&U6h6O8L?D~DJFVa|P|WOqmk2my8t`8jR3w*Hv1F+=k% zbMV$k)I9$+oej&1@Y9cKlAVJCZcPsdnW#QbE} zM@DfkdiHLNf~CD~A^Is6em%|%$VDPkNxNuZA1#N1Ja-OZy$7D%+jwd?uHCD-gDMFJ zc$XV_P}I3_pYd9*T|TFyZiaf={ltDsr$=)<(>t_&@!tjzCoM0d) z;0^f8Ww*q1C7v(z6wZJN3C4k&No9}P4+XS5!{e*j&j}C;LJR;denVycj1K9u&lgHl zECKZjGUoz61}*Dj{nyyb_ibZSlQ+Xa-{Z?1=>cI;<*h}9QU}8X=UdKcGwXpc9}^3@ zKD5w+;n22p_qRLT(mjTP9tO}Dc;?nCvEi|T_uyjDu;Gh3(mzQLww4u+w()Vd;n8mp z^ncn8A=Yz#0Jx0QJ5m;}^8ys7qK>i|_bg1;Ct^>3XLK8zn8+BZ;C@nTo`A~B7OOJm zH@H0?All{X6YJe4HwNDh?A&Wo{?gIU{R?*USrGG)%0B^y#gEe`QB>zpgbia&&AP9R z$tcj=Ybcz+kim)5Vo~rjDRiqazC2lIR$PDfo%CnZ$bk72NG5)vOvE!=0X9GpFHido zY@%zt4#WcVPjbIuHM%^y$)Ae+a#y$VfN^SI@q3bX463iZLu>YPSt<4ZGfGn&fr%|F z236mQfi4K2<6^6VpFXij(vdQX3VE{wk}jHMGq@`L&^5Fb8I!1Ul8YN<3{alaAa0BUkz#y@ijF!E1F&{ z=_9jb8G}-9IuS|paNBPZa=n_}7a9b#`8W{KQGYoaHb+rt(GQ6=3*eYEpz?5VM(RPq z`WWzZKNkQ0mi<`p)Rs%>r@5ak zLiaI{Tl!``*I3kpSsky|GDIEkK9?yoCs%{%^O6woGPhwUL`6jna$-v;4wSEZtYZ#p zs;Ei~bN+~mqGq86WRW$1@`S>YhcoGdSO0=~;{A_F3KPGWo5mCfnQ}F&K;G}vY>(y{ z|HcdQqSy>7KXhVtdfb7XzGA9oYkosklML6f;S%2oWf%b?)<~K)weiip-Uz{4g|})p z6+6+FHM)~_e(1J_75Px^FLc=yh{6I!j7jw&qC4)H=yG>v@Qxc7t}9vhZJ)*9Ob4KY#EwlDm9!Nq0=i3cZ+NC}NOVt2Br^+g!L{t6j zJAC+~%)C-$mCwL&;49Frf?xa&N#6pc?d@L$1qBs(+tPy#k^A2bIj!4$`Hv<%RhYz)M#Ld0ZTymS3(q6OrOZ6TA(B#si&7Z>dcwAsa#u= zmtrz9#Q2#oy_^@k0>+wi%Cv zQvNeN!qM>G#nI13LZ*@0F>TlOGB=0B>_uGmRu;F<#Z4W$lb|%8&mO#1CeQ&!}+z`7pR8==m4nz5@TKfjI1yU5lg&#~OSPrf>=Q3kIX4FA>9au z*H#v;80mDI`AI56(`G#-rWn!shz*N#!gEDw{E=5&+lHgB@SmJ!>YhBdOp(u_PDMXy zYY3t#8so3nEI!G{M`TV?3_4p^CSkJHeP=gpyFa6+qS68_fisjSiv}wD|NpB#BdMwy zgP)81B-{Dtz~=ChP@j3L@LhC_LQ~w_Z10)eL838hf9Z6x6i7|M?C=r#CQYeeU|$EN zpgsTL=&;k$kFlq=fPZ#Rd>l?2cWStthsU?m)94CyR?yU+EiZ0Mhsh!yQ+0e>!j!)! zg$z?!iQTCD{B^LV@<4+z2Ls*;4=f67d>Da(hngO75loG+@7O1&eJ4QRXn7L-g;#{d zv^h1{G``Wy*_j*MuCbjvOGi1?$Xn@u&+^{`Ef)-25M!CO-zq994(tG_8xzQv5;GX& z!tt!$Y-){i1`H?nqq6~HAEy}}6N8W~TUWAt3jDc`Y54K{7~~+3>d6Y(vA5B;WFrRYoX7SRFpSX~4S`!^k37X_2Kmu51&$0XV3NMnAhKTUC1tyL9Skp70i5S zpy35Wu@1A5!QkndKwy_S2r_RxILqIqzr)PUAkS3`6y=lae-+pN0oO3*N4u_{*7{Ft z2WC4(b%p;&)q6lw;lF?2Mhh7!vQ?6mojs!n*)G{3du3ef8b!!1LiWnKR^ncp?CiZa znb+pp-2a=tpa1{=>(o6?=iK8xp7%3e&+B=f)|I{}hpNEq5MMggb|A)yY)LKagDqA= zNX?M(JUzvw#C|Y4674*7OPN~turRLT1{PRiAtMJ)May1uXIOn%c{J-Fgl)EQtHD%2 zJyI2ig4e9ey=1-#L?`|Qf?Yj5OcD}?wWUD20V59lBuelH>l)6-yOm&(^MjAba)8!* z(L-8zwN5<)1G={wDM&5TByDZDsgjMRKfcP^T41v1Ev(i;!aE}w-&n7aUz5aUmz756 z{HPvFDLL&*9oc@9p;l_}TzT*zIe#uaMMRzkc+5C^VLdpV!Adae8FI$!T4_i=QSd5C z9jJ5)W!`#!NZh62k>|xaDmtw5+-@Y!_i`$9p5La}2!gS1`1^d6uo$*3fie+4<~qAE z${WrHCqC%2$NkB*c&_Oe)x$*|An+PE+HWy zlc)awwAhP7t*eeX-YPHQow8!$OnYt>nt?@9Nx+w?q_ZW1$C#APK&t||%{t%xbNV!l zbl{$M_TOY`)FYZq*++)kRh^~^{IktqMnH5fu6tW6ydeSXuKSu}&o zVn&KhNnb&)%dF-GZInK>ifcijSQLm4sUQWV1(jOY2(+LePp_N?AyY}qhNFsOMg%K}je$7<`Mw@2(Teo%wI(D%2xQFO39=$TJx zx3*e2L^rA@qfI%ZD}u&jpz=Jk>1l>9De!M$O`5e{r&(OPcndoo zmElgA1NiJ+?aIsYOwBL1W({W}%4wIpRLgdnbBqyzg=TNz->BGqbrTBW@BZO7OELbG zO&8dzQ?y6M^fB?WoofzV24%W+PzSy-3V+Sl8@VSo+vqwacr@Y2;~7|i>_3`%3485d zZ3awS&=>OBe{7mXIjbzDh zH5SPGLg!zw7R|hLUee`uqyWvci9O(Q=kW|CYLCZkmuj#e8q}R?NG8)qtG{=)PpE)s z6Dvoe>iTc|*U!g~WEwYIqGDt3J72(R3_$q6C<<8T%yM8Z*QGc($dA|gNB~YMjo|xK z#R$|)odoD8u)j5fd2AbZ>8ZSU2i6HH_ijRBK#56IQWAT~ZRt@z)6=J8QT2&qxr9lt z0MtdQrQR`id&USzkj0hGeVAkHxWCf&_(>L)j0&8ySCs&QBZQrpsYpLXMV1DK6k8HM zloryWf~4r!{WXoZ^|@zcDQM<~f6YJp35?oM{ei#->)Z|xgAvmEU^`9SVT@nya*dym z3%_TFrV;5sKkt$;Ej<4o{HFnu)NbuZB31gIJ2U^S#0TT8rlwZD-9Qk5+Oe-Y=f6or z^MwTH&QBysptmsv@GpSB1=R%~rOTzOIcw@s))4j4GJfxClws`V=7V+_KZ;q01k4|X zFS_=Y+2fnEytYFUAyg2oQn*4NQ-_f-dd~VZ!AAkvX(b91kDmPulTrFjo(!jJ|MqJe z<<)H2B|=yrc^#}3c=#0Tu=}T<p1w3?TkA zBVz^C_r7-y;%vRSi_0}~gey)XlMsew` z#zS(t)tJZ@i07(WWFH8;g}h(O6qe8R)yYcFx0&|Vdij#!gunJOhNhkw2K5;ul!akM zNn6+^b)CaaX+zlu?FN<$pjK<+iHHa_a3H6iu*1OkrzYr|>+qs9Y@d}G>n>$!zZA(0 zI`MNik;U5ZajL7w@$e_BycYst0 zzm6Qn`j9NjHNUU{$$6_`tr;rv&Oemf$pnatUveS!oaLw9f$s@apzX7TE+zoE8Rk+` z$k;NeK9n)9YvW0xr=@aJa((iRo`Sw6qwQns1=%+vT_i&`3ozF9_V!1doIQXU7E^OM zxu+=z^%DziA7c0JxKcj;Vjo4ralt4cjtq|cWo+PiqKKpkx}aA5r=SvV!4#&^66Y-4 z5#o;!TAWrliL(mf!If}U&$zfBP0eZ5hjb{P-Kf;o%Z*Dp^NFQp7HNB}(ebZ;^3zCF z_kBFFMy5G2Hv4;v4dwB`$+)R?!cRF4+Sod(t$fkz<0=4kgpv@TDr7V_4 zn6Z1#c%ay8FVIDI>FMpKH1+kn;E+6KHa6?wwcC;q2nZd%^O_Uk;o%vjSWNEMp6w4L z4Zao+5ywx}DmH0+67U*xgOXw3%|T+o01Jcmm7u<8{dqGjP^)NZzuqs`*5bFr@uHwi zL`x=fQ?eI-bVtnBAIvr$3xxZD^qYSRt_VC9`sJXp@I=)w_^u;sM~B>NIqc8}Lt-`* z)3hS#b{p24MI)$7}%@K)OVfQO&1u}*O67TEexVk#oJaBqmM%IFgJ zdfy4X#=fvExXrn}phxMgmO$AeBeF1PLrEj2o2UG+Jgi6vcjz6la{VY1y|^dwk?$sN zM7EIb0XQA&BH`-{q8mh*T0n6Yv5a|RH&dGwYv2(Cipq7%3Um;`k&%%<=U6^uS%Lza zpH@Tg&&uDp#Y4&?_=``!@01vngeanJa(V5Oe5+|bn>+R?MzkDB7mj!w&ln~zVd&hx zGa2eN593Q5)!eJy)}0t zv(GlS=w}PQwrgHJtUFJ0;xz_t4GyMmjr)V@_NMOd&(A<#q^_Rj(cyx@kzwB+rYn!} z(+aq-lmqe6r5X)84jlWOqpW#>%dl z4xDcU<7EtMtB{5Z{8+dw!mJ{|k=?Q)dMkIbWn{yp#G)_VY)|RR6dv3^;M@WY4&4CX z|MFi>K|$C_f(|?T{RHmh)o|i5Jso06{Wi1V%-80fBupMt5BbSqxkOkOHTmuyEL+@R zdG@CqdrC9iyEBDGMUhg5;`2$0ux(r@BmJICeVulVDLuBcmHe>kPp0s9%ly+P&4xn! ziyoWRXr7j4+6<+L+L5|TL;FdP4^TOww8kc@d}g<6Xo!q8qQ&nrrK8tgHh#pl7#jK) zq^Ik0FF%a0RQPPAnHDe*GhCZQ%Q|MB76Z~kulnI~_!_uxAUR(_<|zCz?UOGio#KS| z1zAml`FQ!%W=CU$a!7<;h$XM7t3P1+0PvTOdM4CeUU+3)m#~>?!NiZSBEGG`$9n)D znEz{4Y+k4xMs@3jfMj*^;(YhpvwbXj8MAw~=-As1#EjMa>AWrAw zE>t-~zfW-~N}o3$=zX>#HmZaVkE1IC2~GC@wsrYxz)q*T&4|y|0T*!mp}d~ghv7UG zU;t%M1`)VJ8ERT8_g#dp5R=yvr0D?!e4yM@6P+uIF0D8jye)0A+>-90p{JntyeyDs z;&8l-QSX5lymTkp9eC7zJHqc*EJWk(W~rX`Ew2k5Fs2kaMe;ofn?2K5UYRQrtX?qP ztTh(jTkbKxSajXny|7xNO5LJdpnxFbrUDOsdP(D(m?;_QwVAm<)=ihQv7dxd`10D_ zi=EuFB^8yJ8>ScSrWa$RiN?YH_gDh772}`5_{p#m1WLBXt%Z*E2iEm#6WO&4s*CKz*PXO;jU`sqg-h`djy%OdLFHCfDoP?@8BR;@4|=?xu!90ZaCrq|Y{Qk(pT~8`;B7!X zZyGgH@OoE6b+z!mcf#dv5uKX>=Wj6jcQ$vf#=b(tkz2{`pv?lo*F65NFFbk=+#lI` z0$KTiYT=JzJd3lzg2x2PvsYuP(5c-xT7Q;x)q_xItT3L_R-7)Gl5Xzc3f_3Xq%G&RiwSj|jJxf4z-ZzuoGfwnl`um#s!#X1$S;3P{&Auo zlqj-a=8MqJWcc{D&!;Pc)|A^p7a(kGLg_wXJ7{KJq6lFL3d?-TA48fQwMNNHaXRbQ z^q5KE!)1!&vmK}2XQ~ZzAKC(VHO*EyttxxMXq7;aS17VP0rY!%XQ!D^s^O3SzNs$+ z?I*K<=ATh68oBi)p$nJYc@~zsYM%MJ7)LF0uzb^S)*e|KBQ^MgA@?z@9AnKp!3BZW z=Akfrp>hAP*sQT^(=~BY?t?V7Aiak)fAC2D;LQSnK6!+$Jsx;%i;Z};i!fHi4wz?u z>!Gk#3D!`)Fs-;}IdmdX$m!3YKa!9}(C!~DFC%lqX{polcRLq~y@13+7s%ByfQt~*GIz+RYhrJ&li1v;%q14dr`OGaX zr}kiWBjk=T zB~Z4g6c2nYDXEghtMjhR>m?bY>v!hs(@ZveEwYP6NeFXUA-&pVHp2tUq|KI^Zw^@E%>k;7qWu1{Q zC1azUaHJI^Hp>#XU{N93OLfB@=!$>vE&F)f_--`de{OZ(bx%{!j8e<)1%) ze*b(QRLtpy)M<%2bR%0+DvM&Md^kN?g)YtDr6c#;WoudyATz<~sg^n@;-9JzGW`)y z9lRXM+l}>hZ7`R~gg1ld-JdT?FuP05ify?mP76nv<0=mH8%db0VFHXqlWh^YV+CFHCL}S`Xpt z+?rv{XZ$Gn z!F9$f_UPy+>Zj?|nb9(plJc>!T&|YbN zeVy>ip&&`mAOs~XptaD>xOI`kN^cs!7}BuLyQ#I6_xHhb0A+y))HOOK#U7F#U$3Zj z+ooE?HPQ_SJIA$^2(EL>NSVL2Fl(&~vBU7kB0n(^G-ZfvX_uQx^cSScQ(@?Hd}i&P zb7c)YG$Mi<7k+~zr!sM&6ciwAhO=eks{tHNk5{>5BZ&m^q!fiCC1u*)qLz911SQ3c z6MU=!vgdRT0y45!nN5Qc=KxP3itsy0%tFn9u)t`0%KS_GR?F6?LeOwvQdTBj&%go&>-v<&g`ceaU2w&~RwIa=@RE#O zTpl_6nj?;&LgURua4T}-Tw*K89}J4Trn+!(Tgz!ng$M_bP9*<^L~;^E;G(JV$G?j) zlfl|v(Y=W5e>-JQoKZ!6Im#v-wc7B{1YIo^d@$**oL!EovgWtaBIUSdTi|7{g{NHq z-N{OaTB4y+{0b^hj2e%Z4CfARKn$9m(-ekrQq*Ut!Qb$zNyl>MsVGu1`sJ?;^#85t zf`e~<^bno1WFE@UDS+uKB#hsaHJJVwlb3cR!HulZ@`cK&QGK5q?QlbLNq1N6mLs!y zucTZ*>c5P{RWO%051R45eED*?$4qyouqj_E%nj3*@m#_+bNgN>f34YPD&e|;#JSak z5)icl5b}5-+kE>~ znIEfqm2aT|l ztL0gOpOsHFpbvyCL6Q%^m&dXhDPgL48sFqI8Z?v#`v#z_Y#j{UtYHB$g>%eKZ%UNw zbJF=5-uZ>3skGFCGakVbV21CV8AQ%PF{6_uU8RTV~bY_d^$ zt1mhTXPz9s>Nnz%zo9J=`_A(^1zE=1Pub&wCg-hplL4R##d~^7MN35%1jkqiJ_LYd zGZrlhGy&?9&a>8KR%SlvN#^1XY_{$6bX41h3$O{`DlfzT7x(}3uKz8sK}}E3#$N~| zYVINva&)tDEYLC1Cmv}j%M{81Ie7@e;=Re z*d-)VKsFj%=JOibqw2MPqPBm$pdAfXbXbXUm9YwWc#T+5O<0k>f~}_)#lu|iqkD>G zPTC?;&)=%+4q@(#q++uh%payTyzpffbA5d)RbMI(=Kc|U{Xpz3Buh#?8h%`z27$M? zFHK~`z?n_)pFXq*$g7C>x`fc_AcG&>zxH5`Er-ia0f;VAPfLX9@gZzTpaE zioc%s4=@EyTGfe{a*HRoER(9I7PKy zM~osMzr;=ecaXGzn9*YogrAITY#qY(H3mgs6u_;%X6P|_tqACcQCS(^7)V@J`;%n; zTWoy1ys_~k=|G~5bw$u4-A;Pi9uam{a5X$3_XlVO4ytM|;}y$AYt8MCs?8%)4eEkB z{Iysh#~D^!R>_Ae3!F+;nKbth{k=-}s+yC1`qQ}xpZcfe!Kvqy9RNcU~ za?RS*iQsoOF5$0b43fz#vhS9n>Dao38EyI9cbgI+)din@<_BTdl4jRX?a{|hE~~ZI`GzczKy)}kShZ@rW(q?xd#E%09C2?_tE`| z7hZ9K4v#?QD(Rf`3D}`;^-N?P-<5C_6qoJ#cc%nW4c3-Xmp!+Q0LuN#n(jJ7t*hux z%>tmJDF9>GJs{xYW&|YkRpE~z zwVxi+H!kmiBK@#$0XIza*=ZWXjlGYtsMxYZDts?rwsWQP2alueIVH^d*Bp*t6%MOk zQOg6;bol?bvOZ=G4y12NcVeKGj{z)ag4Q3oL&yZ!LPxFqn(qJ_JomjUuv-L?fZlzI zs?-J#`uf_}AG3#59+lIZ8!&`3!&8LT_ZyB0OUc5bGNx85PX{HHurN4vcW&GBH4Ff6 z0*|Smd;M10vb8JG89+KT1~PFqQU@d`qC)ik_KR_X^GP2WD;k?ZKf2WB4sg5zsSTC_ zXOXB%YcWZ1*H3^C^pzf^iud=%dv-qG{@yRDEb1Vm4M+kE_L2nl)_{kBev!nmF<3jI zW3DrB<1#0^4#@!;6PO_}{nm>9pvDEs+);wxUk&hvP1aj~mW(bZd(;?QJ>rDb-Ty%$ z|CDw5o_o!7>Ty_7U%LQ1dspT3U7XyzwhPwCDu|esN}g_%PEI;G+(>#bQIbeVhX`a= z<2PW6b8r2 zNbG?8S=T|Mfi`uaezD22$C){Cx`sVmk`H&Kn{>RgEIY9XoIUI6E?G{}RQ!fU?KK>o zYEqq>Lflb6wZE$Cm{3rw$mc}T<`pLnI(Sz`FJGjuD!3vFG5T=GBucJRR>PX(Zr zm34$e{&d7}9DR!=T4QrY_PF@BgDBE>-f*U+#%Jmy=31F_-pPmTLj9K0AzK1f1f28D z-WGJdz&>IjP4%>GZ_=fe{&;d`yjH7taVW6ds+(pv`Ay@;1w8zToui~sbn<91;m<9@ zL&t^Sf{HM2W_4ReKYH+biZPc5|+DR)r00@KD zp9nCWG`A^$M+x$_AlTI8io0upuPg><@-($#0G?FvPN2?25|>k|1=s4H_#FoHPZiI7mmm}zgm`KWXC1m$RVNNo1k#KaeBGv0|`qg%Z? zW=ypdZ+dfO(Pz9Hih9~fr{tj{EFGvc-!6O6zC6TkETugOV>WeB zd3TZ`jFTXyWNCdYbYm*!z*!gy8t2W4_$c&U90X0_4rQLfHVmwEk0BPO_IpQuBHwp> zdUi)4CURnh<7;0QM%It$iVluy5?6{Ls}hSiH)?<3C|7vSf|}U$C<}uNkA-cst%V!P z=Zq=OoDW*AdUAY5-YSsd(?un}J~+-6W054ZU7%L_fu(}ZdG4elEiD7=R)Z=4_<T+gA$aBPYr`dfkiGuGgg z`4$oJzt$2Sfwnh^i!)XP63dqHYWI34JjrrTcz(tn`jq%86Hny5m`Dq5I=r5@*HPit zZ82}rVe;@GU*rwCjaSdRvOj!?wt#a%0*qBzd({$3+0Nz4)9xUVvT@`uR=e?YdcpH7 zh)y>$>wRBEbM@xf2z#FAxc4Os?6YQIjX0ZM9Ht{8?9kEF^qZ}FQdM{RY$S}+BtLHt zbj^Z_8b-T z`x4aMC4$U2Mf( z>Ot3?%?;;ilsuR+`-@WiOcM5vcR26ulKX`872~V)4A(tnG^~g}ePX+8?vpc{Ut;Bs z33DBTNBnI-*)L2C+~_6vZP?x7Q~jHu2ooWFp0yXYHQm&l5%vCv_~%7ZL~plvgdA=> z@dc9L;)DFdEPGb&51T6riH&{bNnurU5}nx?x8!BadVK=d$K#obIQtYQ;o{(yTFhBu ziVt_Fb|K-}`39OsF{KMyHuJk;)j?+TMpM%vBX_1m8%s$A+99cbjJS9=LrC;X^oMy) zbCVJ%aaz`jW%71n8|`6I&ni5H*5~w2PfYhx?Sy%+VS#xEJ^e$8gBx_oT0JTB7Xm@C z%I`1|m?nvl5#FUWSOqE}LvFBx`DkNn6*__P#7y!AVXufKp~z=m&aE5n9HM#_WBOW; zwkul4xb{hvCbsc?PMja82ih!$(N;N#IWVOVCpI<6a=y4Z2)8{$#YLYj&ZI2FyD%JL z>If*Qim(XRPiG;?x;w<;qMlR(oK+ta3Plqx9@gR5_ApgzaYxbLhNh#i56+jD&*t;w z^x)*X4Ku{MXcW`ls?Plx_kGq{a$J?x7>SF|66nhC<|yP&6YpvHN`1ojqao|37q;B! z;dmJL>Pc(4nJ3L1ln&aXcE7rFfU~-d-1ge?kFAW4L1D|-7DE&6r^n{U3qI{DVykL) zCkAxpr})RmMKen(6%mHhPM>TAM4Os-P;RI&p9Oax0NcJ)ndbEVjFaH-rffwk91Xu(5XGXcu_HK^@QAD%jo6B)ZTxh!txGq0enY~$II)Cj zNbM{F;#nAGe4$uY^1%8*jq`*DG^tXN&3)UHi6C}qhc9+#v^81i&skv6^7^%$F+?z# zGNzPo^5%bBfMg%LU2eCg)qPd6lkO8A(P!QS3RDpr-^$s~xciTPSkR1}3HOL6MVQ+^ zT3FVrhY~FDJmL=T)2{H`?&;F#rj}IG4Gs}$1Ngl*(uQ(zaj|PtK~B!7Fa6~YFo4MY z2e7lqm2%16=Xz?a4p<(9)Q0-qDCww7JZEL!?MPsMYLoeE&peGveD{#2Rqp~tHLF`h{(S|PoTRQ_h zj3N9rdw%$1Q0WBdv;P<+?3yZYIzZ=Cr`Dqv#{v9{sdH%uH(l6!qkh9h0c8M;y^)TkGn@n_^CakH-C|10Fx5kqbN-9HQ^dXlaXsXe z%)bZo-8|%!>vT9!+u4Zo!lhBa`s5|<3g8OtoK998JgYtKjS@ZUdN*Bhj(LMHl%6o` z+@(MJV2*!?6gEUO+n-P5os?$Scy7wnCKYj?7BY%@La695ToJ9BTTH2_!3|Jk#n9oF zVMHY$e)eF7?(f_Ib;{yG##|nO9F=Uh5Ly1TiqwPoO5!iQbpj$6+vF*9w^L6$+$4Oi zbBb&I&XOmbs!KS;>=QjcY`v3XJVLEdK6fF|S5mY*ty|lYb(4PHUIYxy(ACzWk?sC5 zCo?+irWzQ^V17h&QD(}CUGs6*)@L!0fPV2DJJw-@nB(#CWZS!@Y@VHJw({LyZMQ*y ze{@vF<|g4lR5l6Y!_{Or9)s6ha}L|ZaG2B|&M+MB-hAVMVch2^k3)GMKa7s|n&AuI zobHTqFy|TVqd3|y>`B=y4`Ol+H?E%&h~j;i^nIvjr#r@^#l%WruiKFrZ*#z5*i&wf zdV=|IH78pUl$I6!ZD->&bzJwjxX{LLoa83iafLgSZ{rmnU+5^E4mY07=sU?3ux1Pk z-sz=w*%?nF_@l+~H&B^P!44o>sk2Vs#7kacKEPglg# zIV88P+iakZ8O$$y`u+Ew8Rq%C_?8)1YOp@WGbFM_yC{r_ta9O5OShG`Cqr@spW!c; zV}`TJ9AYQC(>sSfPCK#I_RG<>=z7!;^eno{Z6SqG!&)(d-P1&bOq{l0jUoAb8dJ=) zd?(pw?v5E-v*)Bph{BV7>0(;ln#{e`71^hl>7tytQwn9ys<6aq+1x(Kk%t%icM^~L zmcP;VgpMkegZ{=In#fHtrD}h>(V+yh(R-;E} z?2`x6mU`%wp5s19+ZhTLq4HDU?OBr7iPEOq&aDCa%E0R4n$gLIQ$TkizCx|~s-x{? zSAxiLz5>>mNb5i%E!7{q(l`F`S=k?nRz2RkS#`g%4e}zlg5mwW7AonS88uo_T)<&( zmyukkJI8X3zD`Z6Zo3Ccx}3VSxTrmn2?c{|_iq;{1#5UjEc;f!xVYF-&goC{*1dzt zulpWnG9Sj;(A06{^AXATf zsIhK@KH%Zr(dsy#C{$YqMNPt3vx~c%GS

cqXx=NZ0X6o1kJDdHdqzbm$vD@;oBx z+-tLDRrE<%Qqv@LZ3m;N&pd#UD9SUN`k3$zw1#KxjiwBf#eF*R8oFp}Ul@;p555l^dlq1%K;qZg3;J`+}t{a)b7ZYs?*A zpNSJso)bD|hnl^@ln7$_O{$9zoYp>=q>$}qd0a1PZ2>$zcy41{a#Gi~efeoa+8$ep zT7Szn_UbzWwZ>iT(M?kx^fOg&NllnK=M%I#9~AFwRsv%tkYd<#w->~gi zcV_-vUf^zP)?I3p+4}yfr>!LEU3>eH`xCJM%|#7;L6R-lfZ<~ZUbkoI#V>tlalrUT!jMSSbCBg|SxdeY%p#H*HG zjT##P5-HC5(gSNbLRo#SVjl?#Ya)Zf7PI7~@Nwb9>W~>P@qI-_#l>XUW-+Uxw9h4Y zbH37wjKnNtt88g^mdP}wzpajiLEXhhJhxc0-c?cxA3GK%YQCyx3Jm3(Y&LgVo}Y+| z6^pyWol<&It9%tII^QlDvA!N}Mz+@Wme?F-`~iP%;z)+KbpX+H)Z1?3W38DSU!oHI zD@!@LAK{ET+3DsP8bIGo_PZ(vp@0;FbWJC*#74m<1P!}Iavq41e!|9w&C1G#ZydkF zOMp^Zl)bp_bEu-&?2oO~`o}VTt7*;l7ZaPrH2c501VTeUn)zq6TV@jn zDl3d`@y5I?hTLvqillP=gi9vdmtS{?gjx^L2wmI!cFn?aO8$v?Pxzcfip}!xB}_33 zN~-oN-)BC0+vVP6`rW=Jo0cD}VGw+xL?YP*VVZK|xi?9~^LK?5&m;Y!YiG{~;DXgR zZ!jJrlLeqE_&Wz1r4W9q`|m4g!gwVii5yI5G~p5MDa#b-n}4!kp*K7xk#xsXW~_de zRj;lNTOX3J^ckn{`MKPt=><(s`B*IIIY1?zSFl)uu%E5Ad14sCmn>nCKqc?Kw<9~| zHDu!H>S#+)G~5XmovI+!y8)4sd&{5Q#L>wO1sz)q$Mz%KXw=B= z5h@{*K(TW0 zWPKa;YAwBVhMphLDVV;MuP!E9P(pcQY9rp%xR5L-MF)(}SDH|8oAM7~KnePcPl~0v zPuQIWr(S}YMEk-?S5?;h{jFNwh8W>#8K86Id>glmX^s)=>>#7~s8<`$L0@OSLt zL`{8S!c)l-`q*C6&gI7+2c5%;h_tjjZn6^ZkYz`WGr1-0c&VqYF(Y)g_eNubsGT@s zMW)l=H+tY>#u7Tr!b``AsbQHJD8g@N3l83AiwIGV1?{khZwcW>HL!vFlk2LvINqKHsv?sC)iPKdOYzMv;Eu%#+?F$kGOT#yd%$yT#FRY~S{Z0%zov0(8 zohKDdHxpz*3iV$B)e>8g`z=h3U7t zIND9HVJk{o>oC69-=%t@&li;jFAgoT5lgWVc?Dgh6F(YIsD>^LC5rS99btc$Q9Kr} zJ#iFBsly0MRGdEN*Y}i|p}HRkBr~liC-<-28DED1efKxjpmI=&>UyaD)T^(pGiX(_ znF+ap@E(Rbn_`vNozUU+h&3o*)F$`i-aOtdft;OuO>vloPn28aG~&1Y^s%@<5Ib1A zxIX3c$piwS8EANFqA3Em{HrGv)#c;n@9L_hrd|;ODXMPh7K-Ju{b?*x_=W2og|s-Q zkBJB;Ps_uJZ02S#tXWyy_d@Aiu?h5iX8r4I=HDiz1hlJ(j~y|h z(^^YvBmHjPT}>IM-dLd%*FL99ShKjzeDjO=d*T$kak=BKobH%KFlW+xk49Yua_i{) z2=NMN%j-E4-L3Rn>1QiBSBvh>CJVZegm&{7H)Wy%&A4H!D?5^#xjg6Pv z0iu_EO>#X{A%y`GovrQJ<$U8XeXQ7a)f1nF`3a_nepYPl$INyKMS`k=J47tLaA13g z0~y})E_K|2p2M{T^cH(D0sUj`+-P@k(WJ)T)y*I>hs9XsS^_(?bBSHgc;e2pw;cU* z{?NXpCY{blUr1!w)~K%Tc;>go^kLio(4p`lRY;B)!i)1ovY*v`%kXUN0?I$O`1~8# zKXl+X5L?$XSRw2h1tbUrWln2{%}8E03Lr+h1^4o!KttJbP1?k>!{d3gcwJJ1Nd*$yN;HU?y^>0L*2!F)q$BK8@C0`D_hQwmcFE1c zD7yypQjC}XGPxV6a-2UpkMZyd3)$*6?c&RLm9i^+agG_Q+B$l&CK0|+)Uoo)Re>e1 z@z;w0n|I$>d>;kp-13!Z`Z%wt5fi*{)9$=Ng+%Yeyp+QOW@eS(TaTC@{aJrYt|L6~ z_3!4PY(iv~92i)Sb1q6BA^xq09c*q4 zm?ujT4nm5F$fAfj6|^aXphhcuH8 z(nhW$MhtY_Q=POQisd&kn2$aPdcD>k$uDiTn@~(voVlRxTj{twp?r65AZh=zrBsQM ziMz>=cVad_L<+{WImb*+9Kuw&{37OWYj2^I1XDo$#wH^C4`A6W9&`(;_pFST~u z2eRE~`+=5yb%D~Ng4#acU0h&7pXCj$C4&%jBwKOB25+VY|XRY>-*_R+vv2nAy zmpM{ihFacNjQURZ+QWyzQi!Ab!*uo5<)q$EB<32nnrXv<$DsBAlI8(e;@(NMQXRSr zHYVCwxj$I5#}9FWPMRW5g%G`H{ugK$It^W4LX;re$%~o}xcV}bw)Gm>#8KA9gw{co z6B*nDYlC^%aeh#I@>*}U0vr%q=Fc(`Mcw=J^kh2D{Fw?p6PC6(mzIVZE#o#)-1Wpg zBq9pqUixy=cijt33E?Ce!*}|lu6Qls_Nek#Wcs6LhK8bwew9{3tYA`hFkF*dFPfS~ z(}}}B-~o=;I!s;ec%3|;fTCsBUF)tLa{m6i29-rlNX58|qB=`^hxDGS*HirnmOxLO zc3Q)T!=Hbnbk`MBK2)JYj;yIAWmqq)X zM6GvD>!Bl8_PmoSw+xBNd5pE})^Z=TWEHiGxxTyszqh=Y5%0UrM(rze5rg4gL%%oh z-t$N&qvls2r#7Ig5B**CD&8XqH9TgQ^RnWvju#%$Hp{Wd{f)QNVVtD<{WvXp@6DD< zbJ&EF!pYb)--CIZ!|2QLJ^5NShq{Q4A(-q)cN2_vq&v$=aUe?(<#Frko+ahp3w!Ka zq&{BJ`}IyP%;xZ`EFHGI6nw9yy=Xgpq@9(~Jo$*6Ij(1~@k^v;apk%0P6Euw|8$Jh z=3W6a&hL9~S*xaarhE&E!eYwGo}NxTUL)JG5)M z@>{z6GB9i1=2wzmb_Q)B8V(bDiuFtnKEp$mx9DGUCB}Ckcy8Q%enS~``o0fxmunis zsLNRu+l|fV`dqDROm=?vMYvYEjCJZU8Fy1av>x+N0?v*r?DoA-?0SlwGgqz~*DCa7 zcL<<nA0?Ieg9(!tL*1?DXpot600MQVBNebFN{LDXMSdIinAqrVD+!AM{#^g*D_m z_Y>Ss>{PFK&>*=Jgu6bDQpW5QGw!8UdX3_(D-+V!VIN)34gwUj1~dOHU*rJoYln+cef-;I9)!mV-9EP#0NH-com#mBadO z6Z)V#QgzW?)D{oWBQmz>KtiEc4R$`K=gN&ms#-EGVGUY&2JdxdR;Y;QcC<=v zZRd>V{guA)gfb zCKu>sIaWa|ZFl;G>E?^H#HC`qRSza7Vg5(?@rHDQv439L0)-b}!Y(Ox|IZHTrEr53 zJ0Id{en@zDVP8xYx}d#>8!NQr-4~nC_aYJ5Cgm$M%xk33{mlXDQ-8+RHTBk0U9&g6 z?7QNUL&kiso?`5QKC6TZ7v(8UIoR}|CR@rTJuP!AW_XITf( z#0j)!=GtH!d%Y&8hPrqo3W>upwe?0zqcffUC}F`3>vbtxmw#MRaU3q-&EtLX56J-G z1|B(b8=NYYdmRMoSbfD%n{)zIV#1J|a9i`J$Ve+IH*>M6i-Me;q;?#2=3GgA-L~_6 z)P4>gtCg=#;bKAA#<%Eu*GacoMG+<8CF#vpE5oaL$k75K7zOI6D(~%Rw_wK`eoUT7 zG-TVOqv8bcQJRiX`9vy>4Gk&~vX`nVkV7W9ho629tUBkw<=?z{qfZQ6zHYo-@4U6Y zdY1&7TXWiKYNQ#m5jT{I@DW){s$wI8$TTSAr6r{(_W9%~+hkAiP=QIa+17OC28`^D z&wH^Zk5SijI_rFd`~oyz7)n+P=gt;4FW1@hOxRmcxvSwEBwV(ax^@@M2+0{>U!h61 z3MZ@PdwFTM(k}$_a0kD9A#vH9Z1cZw@Ht(h4($j2TLluGB;ra+N~$&@4UWzUP-fu5 zLL-;PRLU(TCPvc)lH-DA$#=AoM*T5(xf-7LzK{Ep!GJxXr`qvFjqMyk=3cV!wZg*j zL*eNqtI+oJ-9zqfejJtZ^q=`~PBXZq+UW<6+}x-v%Qc zMo-4u>7uf)mZa<3WlHd_Rp?#bm0eHw7Rtlb_yAfu45R-IN$j@X^;Wn#hQVj8!2@fh zI|W61DdS_(lCtNWm`EBmwdMj93U%#1K2z+u<6=@Od8lr7!3g|E{JFQVaHa^}DV8}6lCu0T>17ZWE_=0h@5ui{z*AjF zoH){a>6L^TBx_}rhkafv4DK(kvBeDu^aB@7#09!qe0t(t{`B#Bi{dRF8*mi>9-ECG?yZh6?ud+O)ITJ!x^YPepUW zS*;g3(l{6~ww0NBM|#?5J5w4qI4Ffk#QdKjVp4;_mtwP3pUYOb^c;Hs8kIR^$GHeQ z!gD+O2kXjRbhKug2X*?e%yoFSy9%4_LY0rM+~>8ymNK{pdJS@rs3y2%}rl-`6Dk9TUe=tXP`>z#@TP@@nYVi=m3$}6{ zJggS13zCUR!Ikn%5M=nIy&AWA}T}~fkW9&m5rc- zie04mp8Cio%-nk{-M`#rpEM9C_(Wx>*ShW1t zXbN#w)Sx*UJTn$7d@?Un=Eb-3Sz!c*S|(*>JBZh1Z&B9LiYnl>%?k_`+0b^p%pNWa z>~V;>J?v58(<gp$T~Wb?JY+do9Sb;_E!r}#v7dyNbi~G2TKVYN z!J=tIPA9W1EiKU(?#!P^(9!>g$NpJoaRUfuhq}7DHT3l|Yiot5zC-@3Vz?p)p4{E` zz#o<0B0Cy@_-kS3M5Yh^wor~RG0iuv^lu>Z2N%)4Bm;#Ap~6iF-sw6WI;FNdsQ^Ov ztE>0n_LA59D@0GgsqS-Ss@j)m#jj^=S7kq+a_)pb|CUXH`1Ju%%My2!tc)FIyF=zD zdCL7dTtOU>^g>^IF^ktLeR_k(UV1RTP!fs|(>2u9&NEoB$!KkTCt){xF z9$@IMfq}W3bMCp%bN3H^3_Q%gyw-uGi?8= z_lZ!N-489AMPbc1hmp#d$s|Z6V8-6r`b~vsI}#nLOGOq_94R^O zXQjI@Yn?4wx83a;!KC!xF841iHSqXs&AkqG=NA^h*VI&0E_{y&eP|{--e2{oYS{f9 z(R9|w5p^v|cg+{eh;yM?QU+d1(6tOD;<|CkHC9!F+QRvbtoBc6^8CPP}7E7 zQROy4w8(YTtuI8ranc4}xP@9qW?%sUjg9A2m85$UeFO=2+0E3gso;{gfmOmnNqJwb0`)?ij)_!<)r)#-s%my>zQI`!naW8$~D;^a``o|y6ODlz62K8 zS07ls#>*&Ok#@|*Df6~CUhNaGdw74_bo%1R1sSVoAz&arWiWZnb8QSSz!=FCV^z=w z)k&~ESwH{n4?>%ba`GE2|NVy@Q6nOxwM9W-0~$6tI&)6`aT_{qy$NfPC8UKnT*N1l@%;cm@Md92pnMz}IaPtKtC0HHiV zTq7;0&p29*j8V@OdSn?6Q1Y$1?yV}b^S}s}wD%P;2S(@}Rm*Jjj@4Te5dwwZR3z~g z+-|k-pC-{SG)!r_R^G6HXDz6*Pk%D)PlRa*ElUjsLK_(-Pe=T}ez(L9aM0?Y^8Yk; z^U7`)4*-J))svCS(&LFfA``mI z%zhlPtBF?`!fi#;yQ5~tvtE;~o+$k-qPg8f^~{bn!xg=+3Smbb)f9!}SZ@fICa>6O zF?zGS!@a%48&9K5T6&XM^WL@^v%-WY$NV;vYExH{sbKjR4hD`>*{r{98vgS#P4Qp`qoHH>N^Vq+Zx{lp+{D$d8@+TrJKW< zf+Mm&eU-c@V~&%pDu6Sk^|7x3^ASfzxK|I(p!?-*SEi_oA)L+ZcW!L@)NEc8#r&T< z8S1}z1d%HX3@MGAsd46VexG>iYzD%o)q|AOiHg;3wY3rWI-pwV5X-`45&9GKh)g4Q zyIzK+FO$IUYg-fQ357-+(jdlmhUuVz_38KY3^azsPsk^Is*rEU7G?&K8AW#t9 z475Du2sQ0F0Zf{wzQF4BOypQcoUG6JbkI0!QE*7yjkEBTWRPcK-VD9p;`*1l00WWzARc&UVuGW{mz zts32)PfvJARMys89XnB!p;bE~(q;d;DK82MzpPcA%@}GMO&%}8o?HmgClBoMRe{8? zWUlvl(6d!h_?u{o3a9KSpb&vA+ z`@S^sAV`h2rp;V7LHzv>u^N1}>zVkd^R;kBGUAD(#K26B$h~gaaw?l)3{~!PcQ7sB z9$kULgQH#FOUW4o#(2o$GZJULIGEpZ{Hedd=H-kug69{K`QA-J2!xUg$7FJ>&S{Bz z93k=bUXX?`_(GkTU{_YQ@qN4PH{&a)_3KlJAcYu;MlXS&`w5%6cmUoCOH6+OZC2Js z)=K{A?Zn>5T41S;ll z0PVYCYta90;GA7r!KQ6mMRL-gMz>6$^MSLo&2UnHURModO2FA_l)f!|Dej-Z`dO+fInB$tuup?i__I7P@SKqSZ@xZ^{a@2Tf^naHBjgHc8NWGl-r%4h2|eYz)$h%)%syIwNCD%1zsjW!`2Fqa8v+yE<2}X? z8k}bjusCvd${n5>)QP5;)7%t`0`K^iXv95~Hyu`whclKmG~A)qEO4qTxS*e-G$*(d zb)erBDKd}ouysw26O&#Qa_L1b!Z<%P%NbPZa4fvP#ttSBL9=PCs6bSszTvT9l5pei zw?n*@{&OkE>N;FqGBS>YZ}#vdMo@J)vH_j{YTWvXXIhU14uf7o*yIr#8FI@2L21{%tBw;Rn4RT-^P9o&p?nQ8V!)L~$E3JRG_%xBym2ESI z=pfD3L*vp=68w^_&T1pW9$%4Uo6_ri$pfd7%l^~#5;!W1`OW79$@ck>XuM-+yk*1? z9Zq$?#Y0XG_fBU|I=2AF~YT$9}rI@S3Gg|ArB7 zXJS4mTu4w~;e;ix`HTSP1zWZKZCZ0utir20!kjmi^n2?d;0cmETs@)VTm{u!KZ$yq} zwJ6I(tpu^kxKumd8*zN!IY=n+Dq2OfS{JXe%HUn-o^|u-g049G zDCh&KhL)ZRNQ`-K8Zi~*3Y+*l7srG3Y7oRQjG0{UdT(ZE{}dQ9{0YJ1^uDB>EOwFp zTMLdHGRH6v4J}6sS{PbKTN4!gTTn*p1U>2!T_iJDr|oI*&+!s5cXt&xnc2f;mxVb} zGq%Vi6^GmiD`XUOJJ?ZJ?SXSMAyxj0Ds@Y3A|W%@FNsaw){5Y9HP9jqlBaWA_K zN4rO`2ka)qT3zM)JLs*Aztp}nWduitQ+b_7k)9t9Zj#yTEGQjS8h-HTOkKsg@O1z1 zbdlS4+@}U%j7`r?uIDZ+cgx}a=TgJbE(?O}$@7d_fve3N9`vX5`efgR@~vBK_C!)r zoHDQsD-SmA8dt5~xihRbpFQg$QGc^j@8{{%(zns=wxh6^M6I_2X};a?GA=uyfoCX% z>)c_H#L%!*bUw#_B9ij+Co|1C#&-qJtuDET_a|pj&L*?6-Sm_uu}$$487+NsI1G71 zfAdZTUF(j8zC7ezZYIfCuMyTAW_-S=lYK23nI$c))Bo{ppZ7vDVnvi`SnJ#NM3b87sa(G@{Q=rP3O+>B(%tjfVVUQ^c7ytY!e5IDlq4Vi0(V2S!~j~4S{%kM`&PB z9_t60FR}~kx;lnc39UWME;cgh_iPHUo_yRf+?xAR?Yti*yEJKnbah;9jKcG4Q}~xC zi{RF%J~osBW!g`LwPyW?rzR+37*}Av&JcegT7|vF?b)DVp9qOCv{GTmTvmTq0CRxd z5&A$#wmunnB!{$@>EM0^V+t40hV~F1<@&Kk6lkr+Tu?gmBjD*n{v^k1gXIJ#uz|3~ zs|SfU6OuuW>ln%esXtd&!3)Vtq=;M+wQDE3x|J27t=P41;Ys#b^n?uS)*!P6r$sDL zHwWynUz31Jq0V2TktyF zdU5>n>lKBHlkKJ8J5)~Lrwp5hgd3}SyoOBX;y-td9I4*nIF|SFXDNKsD%LDbdi6d?LVSE6)Ayj{zwrUFx1t_u zBsxF=LMwE1tGS@=8A;%4kw$QHA=9PfTerC4mdOiyppv6n5i5{4*saEj5BL z(aOtE7Dc9t0`ieCkTav7B@ScM>3@z1#WN6&n zLp{bHzPi>~kEScJMIL0fr*@o~bnVRMVlIpG4Y}m$};C!0XzDfrTz#x$vplY zZFQcO==R=7$(F!&U4L(MUc{Pmga2Al$7g>6V= zvh2aK9DCOQhr zYQJIkUCMxz;Gk5WNY-M7u4wruuL3>?vM1x5yFE%>!u@bv0k5|YVclDOA*8IaN4RBz zFVrPrdnS1d{GC150%M!V(PVP{rrWrVTRw#bFRw#+m zfF0(@j{81?x#OpB&`Jl$?)W{g&GW9?8p`$f`h`@rTlm!OxNb+**L$F(`SjtepoHum{zLSE}pvTNmu9sg>n@ebv0*GazA~RJ<^*+rP<#4sy(gW zR{&*+V(`2vF>4PHbn`8gB`-7AdvCW3Es~#G294+>=)Ejehr!<~qc%~2*q*{j{0w$nQ3AK&=b&}s&)tlV)U_~z4-iz>w?A1b@VrKbsyy6j; z+oslN?98mL)ZktEa`xnjd+^U2l9W&8ojHqk))yt%B@PC2f}E`RONoMDFHu6`6OMHrG{3*DN$*AMbE``@pTSLcXJLI zz1!n}bR{sQP0=edt=0!OrHO{SE8bVZ%OE_vd} ztsFrWZwsfubM0QLx1nmM1HztCoRgUp+@6q1*rA8)8b}Tlg+cga%{6dn3H-17RXsaLD^K;Gx2NBtxJ}@WpZ0Scjc?J`b9Y}~$^@*du zpy?$KRharX5U*rzp!2e56Ar0iyd1YRTt4RqzuG?Oi;QrGZCVQt#S@>Pv-zlp_he<_ zrwnkqePZ6fAiD5YDisgYh)B&IARXkw#l;h=IA>)cI%W4RtsqKy4qzl24ZM(ai0co9 z_y4}LMQC>{{?T&Y4jW6HWFFSX)J*`=#&B03gOvJ{DfR@rvoI6>i&N|pZ^Kcl;`xl; zOk}0ivVYyLlgi5PJG#7_4JS?!L^J(Lxn}e{V{b0b{e8_PBf?~sOqjR+gb}>TtJT;j zU;Kk=kEnSOe4!4sSoJsoWPmnG{#KpJV(%Q#C1~-TjRtYG-g-kyTYXA||~)=N`0=+Q&f!oj9&+THk0njK+IOq+!tWhHl0 zM+WC+br0Q{v+uaX6LhN7SD24k_F?9W24!nAmnbz&yU%aM_Gw|R(zswDFCU57+;i~R zu@o;^PvRU6drcvB8dvaXHq%DXwITcEfcfqI?D=RFzq*zeWySyFpNxvrjMyu??<{!^Lgz5wD9K}M^tt-e3VJHI?($jyW3{{3ms=imVxl!~_k?HSuF&-*xIu39c*e`KCD zZ`h7(5uW@LWcYJuWoHketnX%~oENdM3PgOVMUj25=ii zq{+(SvhqU_EkzdYLv?tog_>c%`2IuGuFXH|ClWVP6VC8oW*IFE8VdK?ekF6OsU~R`o6X&W8SV&+G}*@KhhH~h@`8S^siKo?d0bE zp50AwW_e_URhF*y3(*KFV`+@2Za$)*iX z7a}NGOZ)EwBN&P9&roIF4+OSe}UUNns_&H}~|rJa=*3 zPSxk!HO%J2xz~a{{SAI4&ih)PW*i~VBlCd5i$s_Xzb|T_xXnQ^PszN(v%JypluINJ z^Huh9AeFmu0)>}(0FAR?aF+zhKt(+8<%+= zf&IBoSBZuMi|sA3`VwCdVVRW=8A+iRmF+v@cUl@LIZtZSX=!PHb_HU=Z}-d1ml`S$ zpg?U{AHbxUFV=*Nq;Q`DGd>dT%@?Y2%Yq(N+JOZ2^!3q##?9AD6PGf&j}V4825rTs zX`0INi^W`N;1%AwQwKuxMW`^!I8Z>In2i7V*f)sD`k87_a(Xfi08BEoX5XsBfg<}x zqW!Od*eCTPy>iJoFuTS!(9x(TH7<;R=&N_fdUqi~^dJ46*TmL~RF%myGRl$o3dSt0 zO6VUr>0vb0v{#r^!}d+t@*f8WI?d6jr+@tpD-#Z$ib+kC(bNR=@y+7-tIn|e{cqzu zqyZqgf90~(Ce$Zv;bI+47~{3C2)y``k+_&AOq22Vxc8!mheDWbKhqT@M}Obl{X9lL zubMaOhj66qgzL%B{sFp9?(TaR;P9g0zH(13xaK;&tq80=Y2d_|s;lrcGVGz#>PgsP z@-V?G^ERYl1|jK7va~Xxt{=iAa%pK&^xEWo-Ra75)ocftE~vU^D(jPZl9a-|oM}CC z`=l8MsoCWu{!*j~aUD~ZclwRv&NoxKFQu)>wJS*RB~G>m>$Sb~9lTHD2(@Dym_flK zGZy^<03Rb3UdmKJ$n$rYSBSWNtAN{vaB%Fq`wS`RPk92D;V2fX4{_v2<_bO6c*H%8 zNt^q==vXZA{Dwnhf(@BCauQzcc?hj({Ku zPC3_6o@~nO0w6>Tn5u}5mp6GLTjFWOuYnj_-CfEk{wJ}`%zx?KpCm^AwY6lQZ@RvOcghp=vEARHWM<1f z|LO|VtJYh!+LEb}U;G2#I2SC0;&(u1NjNtUI}1aYmq z%7;G-bX{z$hmr%|rE58-5dNiMIif>U^{E1^6c#w%PB>k|$&hj_=tk#W#x-u*X{V`l z%Z!Dx`d6OtPUQqW@?GcpYM{5gZ`$mndB7%AeP9WWM?YK4!Tzi25d2}7P;;OG`EN6-pLJ%0Z#MYZ*; ze#l~k@6{hIq}cM6TGXT_QLRRx0%hSIr`TiQjj;vj?B@2E&Q~Zkl+s;ace8c*CjV77 zo-3A{R*03~R3g!FL$aVb&j9cN)>|)7AKQp~zOR-7_l?FNlNDiuW5*wxvqi_f&Js$L zQYMNBIu+#6j)fwq?#=YUMv+XepT@knmPUTifAooBw<4=Cwso}*pdK6D`dtP$n-3n$1tI0kAD`KSf|xy9eg1|$$@%l|asATBTi=_G(VZSzhF{7T z|Aq=bHS*B?aHg+4ssrW#F!mPxJ(LL^Ut~lVcRYKVJyaMrW2rjHYQy%<>1rQlJ z?ps-zgE`iN!;YWH&)%x0I{|N;RLSU;?-9lFn0-F}C;;LXRtEw9>Ue#sTuQg!rZ`WE zYh>MiFV5M8X#;SDeVCltAAQ>WvL{Lz1g6mM&n z&Km;*a1X)_|6i+aBit_adiq-tl2$dUPgz58fxThUcR>bD0PU6ID%7^SAevBMr)FYm z1=$bLUn}7fQfi_9*TX*ie;K9G28Q^)IoRDQ=)&7gbm6_AbcY3qx` zKd*aHhq$2hGH`Z^shcVhdrk0KUS2g=tn`LjWN4v_ncfR3IbkC71OVrJuHLkTJ7dRx z75prE8HZTP^!j7Fe_QDW)gXAHSwE8{T9~uEsT9RbRQYKESY; ztP~(GOt}x;t>H*wf!*N|d*UXnaD`E6OjgD+G2dL%8!nww?@ukaWlmJpo%S@7FF+fm z0XjfxUUc>SQ)JV*3YIcZmO3Z zb~2=|#{v{o?0&rZKk-DP-*%F8_ywHVRVNEdU=0X^ewuRl>~o+j^5lXYp>YLz_Rr~` z=7vm%r2OFO#D&QPP0t)G6n126PT60rwT4J|S+g9|B0L?KS$W>P=E3@mPTqYmqTzfs ziB@#m!r&2vsNxdv+iYvw-jzOwt=(2OH?v}5p(xY`se$wb=OjRgKZS1qD9a2MX{q{Y z@yiX;tR%$G6_4`}R~t-#kpwB-Cbv80OBt|pWvn_->!g&!KWV@9T0o5bcwPqJ20TY; zT}Eo~^-nE?-NOr+$bA1>Z0qsQ)XH3na%xomHWg*n)bG|_I(T%*XB0?;&Cp?ecPL!Z z5x>gIy0l-=xKyqio>{6aqjTJH0XhJk3p~Vs#clR)l-lfUPVH6DSf(sl~PRIR3j7{xVE*%MkZfVJ_n4c>~mbgX+Z8L1$xkTCQ zD;8@xjqBR!2y=P~C$BCAIj{bB%GL8T4=0;dvyjw&q5fWGZAc|wxqkongiLz9Pd33| zFDJ~e7XGkxzQk=xtFj8C6C!7*6Vk)LDbw%JueZJYUEJug9c0e0zWLCAK{1-RktTF* zvZ55eGxgGs!dJSinfP!@=O$m%&58u|Rokz=@n}tANElOrK!VOxs+G#am-y#jB{i7H z?I^pNI7^Cy{#$**NB|V_pUvRN2U z)G1tNa)E({g8j+mPBA7ZLqg;>V2m+e!WVNv12-2S|UPM5rKKa z*BD3c$v)|^^g`QxkN5)fcrC6r$v79HZhvjTUr(QIMk5C`T}EBHn{}J_Kja||UHvf9wtd)~)eKVVDxIMlC zM57_^KO>LhPJAG9kYMW@ZC9N5zq5$O$m}QnE3$9a&d#~}X}c%We~JPN%7BWyWtTXp z$iKv>imCzx!1i=2^{q`2$VmtQ%Ij|y*hKc(0e@GW#dL3kq3I55_QH)c8&J$8+lIo( z#}CSs!VjijzqJV`o=GiMx$lW>^>}j!_xi&4;d~sK4P5i#5c-x>8DxX(UC10YoH`sF z9~mT;&BFc1UH_>sy!hIJ0YQPoqCdISz56*VtvlI?OmAlOdZIKaqwj84rbBd*ZGe@p zWp`ZBoPgc1ID}e@$pGF%#VujqjPyr`g78}EZ$0^E_H`rYnGRPI zZ}g zQzZ|zkPsl0X(H%|tLB38+QbmM#5DrM)D~MQ$Mkb6qwiz?pb$Ro4M(=$Z5RG+NbB?v^pxld#6& zaOd+Wt;f>|b_T-!G&Uh>WjyXk>T>X{CpA@PlZnWm-cHJrM6~|a2o|GXJ84ZL0{2eM zvr1gqYZlwH0AmZfnBP6~C`+n3+7dIgMW_0^bj=Ds!I}OOr=xnstMF^oFZgp2OyK2z z+e6l@sD#Aa<;y`jIr?JZT9u6Fs4Cip>VKNipDd#kJjTMSfaHNIUTS*8dJzai@nor& zd)79qE)bAv+2FT1dR~Ck6!@aaiEd=YEltkpE|#B&DzP6kEAe84)jT;+`S#D%-b-Ic zkM0~PzFi?J{2{{T{@4jE^beL>LmhQJJu<23(Ia=U0z79!I}zarzQ3wk6J=HGf!RN`VY zLqo|&)E(C5AG$V;k+>$O9(u+p(#4@y#jXE)#08)G7grpco8%HNFFAy*?CfldO4NVq z$}Xh+2bjKBbK-!{>pImtr%}7yIVb4pp(jNVe%=7^%rI15XHgeykrjg=j$Dd@kNxSp z)boVN2pg62lVuo#Mxyc$wZf=uL}F`6I>?*zW20&bO3v~8aM>T?*#o>B6t4GlsuEvr zb>J5e>a&*lpjWdg8u|8m3*jaVl1n4&;V-Z)@54>zxT$yk6HAY!q^R3Hx{G^o~ypQ9kLfnK$c`itB z>DC;~2F%vs{US7`?TD_C$Fbqa_J%LHSFvI1g@nKF%ugKlQmK6Zu`f(wUnHdiVsdw> zxuTIGQ^yljv)ZaV^U!-?XQvtP(kQa>@^h~!qrm{qUH^dWdj44aD-Oe#7Ve6Xh&u0t zmF0F;B{}m>$)<;fL<6sk568x@q=jUmO_^zEKR80Gqik+Ya3hTf^@sR6qPv2m#wrzC z?f%bW1Jkf(@{uTXb@M%)6arki{PU0Iq1PqhHu1O`I&=61Mz%+jdlf2^ypcKy1pusj zNLazHwK1pkn1M1639olS-2SfKb*b#17+;eIC_KH!JM07GSjetCtDozYdxS)l%NaSg ziTej~Y{#GyocHOnx29RH75XcMn-YlcSB22W&+ zudSQo=-VylY-ZF^_xQY=i}PrCqSo?qRS=bvQ}%a=ql_vzgy(qa8>&K2l`MEwjy*?~ z&sF;p>G;s13$i+Dq!)yg|5b@ZtnSH!%Q-KT>0)ADT1MaP4MUk(p~R{l?RCV;kXET| zcO>jZSDZql$@MY^PL#p;uI~aOAUPd&^uxy z09sW?w@E)W>+|Q%gPhO4Bj(=g!i-0CKEH}ge2p2z&AdJmYZCzQvwQzkLx8j^`1}t*sBLku z(kfy=tLbsF2Mt%gn$iM;2Zg7LYEDWIS!UyZ(iijB4p+ot%H9Xw#wq1DDWnZ*0hYZC ztJ3Siu;~9y;UEyHo~btS3rhbi;3iwhffB}pLgedrQu=LQZRD$`C57M@AELKMoUUxz35%9riu2+N zt{yFSx3#*_nZ4UGGgN!yG<%gY%;;Z-mRr9?m6l_*WqMj3TM1bLe1={lE82Pnpdb}P zCEc8?ul$H6*tj)!PM3c{Ei6K}B>7o#eAhhId#xRVdmrwL?%+f&D>4Op`T8Ks!s-&$ zS5BT5zrLXFHSzX|oR@D);_Wn58uJ&5R{ZOOy~nVXp(o)pG~s;@s!%?{06#nAoz>T| z|ML&_9domky($B%FoK*zu#>W4Mmmt=do&g)xY27G0ZcBgQID+xCZ!OxI!&g z;3WWys_j@YF30X9LC;)XIZb`nadvk(Fw&??vp~Hh5U4l+91H*q@wLd;CVs*qu8`@w z%IxSIejfzTl@@lEelo3|n?2!;>hj=&%n?KRPr>&)GyLK1_~vH%7Zmq#KMKBGH!uE* zVhnENYo$gskv*4(kru>Ns$@15e?|e!AP^X>eN3Nc8do%$SqPvEb)%8H-aiG3dl+`f zv)x3QADkbDt!YN9{;S~>Ogs&Y!EO3Cx9V0qHpi3}(X2Va!p5fg@FDegf9TM`&=@s9 z#?e}_#F4S^kQSEk$Wo97baxVh1(g2IPN(KMrVA@jiG2iT5I`E=&wd)(aR4xn1HEYF z^iF^srkVfaTYdKn4GRP2`(3%-hlhu&lSVwAb={5Y=9r4eaQIg`Igh9Cv1B?$&{P^| zN&yT`HiqmUJ*))g#o4^@riZ9D(%S(d{Qf8L|CLIn{{m}#q`!Y{Mn$J|3-@0s*&+;V z?7q2cMdQ6PjM}nK_35PpKP&PUZ-k|O?$L1o^$ukoj)0gom4pKN;=J0ZdODvXcBeQH za4UPQX7obm5XGchto?Ck6SufKz7 z@jB2ywrvDp9{*zcq|jCLxy=h~vb@UrtERqX24@DOd2LTGk6Z#NF|H&AJPxo)Re_-f z5?__dH1Am4UWj7$<5O*tV#;%x_lUg))1|lL_jpHTRE~Z%A%=7q1M;`E&t=zmkfO7$r6S8yv+)LfevrL-b;bTKpU41?n;IEasXjRrD079}kK;%B% znNuPK*~C|BYUoHr#(`cXKfcDa)!JtS4&89yO_ai*G)kQg+`l z6DfrypVEYB3w(wkG{x=od$w*Ji zF4nU^u~%RS7z=FdN@rDvmEH-nNegNH6IfuXsrlWM?L-o6vv?NxW4^!L?T@eCwJc4#aXcZ zkdSaJ4V|jfPjp#*lq)%*9juLltR^kU3cI4Uq}*Q zb|+6LN{?;idsX@97__V`@8)3pC%$O@>A!zfvmcXFQ20NKc`3;S^C&Z8s+VzboHI%o z7P$84!%gCoUni6iohecrxi8Br-&n4+LqA@PmCcZ$sXR*KUxlKrjwKIe^%T#mK=drh z?D!Hmu{$JndO-SZ?+?xh;Fr7hhUM5f=N9^JW{m~Nn;)?4xRr8`6Hmi;o1?36HgNPf% zHS6|tlV9ImpI-E6WDmQu!=e#9`IT%v$?-46a`loF!SpC$@zZXl2pg~$>-9iBta3qs ze~FuT2o$0g)jYT|l(CiKq0q_A#ufuQZq@jrh>MFGon2=ER$df&$5CVJvyi`Fdo4VI zQD@121Y>{u^4s-?r!Th_6iN20vnVot>){_wuC zfnN*z^|p64;=?U%_z#6%m1|pliM1v#{)h`nLd3B#saN}Je$zNR7~;hUc?FvZ3MC|n zb5SwaQLi#j-piA8>{u>K-7Ts>Mo za6~4$2@-#`NBV2Z==yx4b6qCcnHz_rU?}}qXXDtlrJ-~Vi&XtnK(xMK)&L@KqMN5b zZ;T8&vnqaia04O&Uuap9Os3)RVsCeVjy4`RtynhFxf_2zh}2-o019>~Zz`J!$G*A7 z6}h!;6|O_jQ!g<*%x;wp3~@hxs3xxDtY>lEepLo?epf4#(w5-fKD|k%iI+4`#91v_ z5wx*ZaUAqf^KRTTP~e<_8-?n$4PC^UcN0@woOJWg8|gPTF8X>`@ZJ)ymQJJP4Wbpk zWOXmZpb`1o%_@y2)(;QKl`5^m^9?l4COI8N^~Xjx(`bS%E!b{z?!z89h~9pqUK_8m zThX-UuergJ0oCRUY>V|)UW1=akKPpp1J|!Yje4fHy!NzLbw(mB!GS#WZkK!R%8^Ns z_82@eIvKUaCFH(?pE*g!8*iWkO+r`Q77Pq*4}cOh>1>{w9+oeg;Q_~CwSw8MV?oR*xtwA(?t;-1%@U!^F4NTjBvxZ$|-;Km-Qwm5*?qxvm&SyGRJNYkXp z&7a}Kw!o)vfRtzo#IF?PvN-L91%06o-tE}T(fqt6bm zZ4C*2A5Ew(0z)O$e$9p%{p=HSueGO1@?zc^>PfIx3nK3GN&+J)Twp@O4S9k-$jHy0 zDP}#?vd??npryMKPS!rWkAJ94;grTRp1CAuvP@}@D*mGeGN-6zZuE8q(4yv=U4evd z3Igx;K`aHZQh3E3i-|T;7+r1A%bc~sV98cCHZ}~UUT%$Fn}zJpMIW!P$#IGJ{ujM2 zn3~XrH50+>vAP49#e=ghn1ITrho!pbBIFfr^jZGWGkF2C6@!Z%PWyDOsPYx}K-A}2 zqViwpQ=&Qcr_=pb+lF_(bUB-tsXVa5*!B{ici_&TnOwi8XCozr?o@dpXOE4`BfNt%+2`-f6>-mfSV7GsFY~Ih$ z^$kicNTgT}cQ1Hv`@WjX<|*HwPuCL4@EcAc$76}RJr~0k+^;iJ3JF*R1Y99HG-qaW{YUalda$ zx#gRf=r@yvDuWwXVQV9>ee@T`2DIkmOF7OOS}uI)W5*?89Qe`ptws1l{fG3MTj2eL z7B6)#vf&))YFJ|x1tpU%T=K1Y+_8T|DK)pESKz^vBo)DHp{*k;!Tzmr-ME``cBGW4*%in<3$MO-CJSWJ+}BsL{#do2E- zI$r&x%#nuLcYZ(3t(ItyCI|RP=|h0fHIFxW1o&$0WLm1(vU{SrE~SZ)50ZREG-kQ; z6>Rqei5qI)mPAe7*1;!q_>OZ*Wbg_f-o%>QzAqsvx|x_2dx8&~uDCp4Tcgx%Ld8pb zSOi#xLoWGy%4V4@bZLX-@9j*tSthLnFTSN@AQ*moNXTVx$aRiu~TZ z45IGv@lh-y6+h&fJK5xx`sH7@9=WR!eCvt^6$`{&Ik8Po0r~tQDS0l?s6YPP(u7oU zdM(MELA+uzc&A+!VtR7bGZSL$_>>)6!cNzxu!=@kIUC${Y?rWVf7>VeQW?f?nOv7x zii*GT^5b!M(cuo*jS^jhIol}(?OU_>wAl34*jYy$C~>Lq`MNHriQC*Ayp9qd)$gwz zc*^hIU&ofBlF6F8A=r`vbn0j}*4UxuhWY7QT-&SqDgAL{aFOo1sDqck9AZ8IYTl-b zi%YIJ{i^l-c3rpuW0)sR!mV zn=Q$dP2u8+V%De&zd8hG)V?!4T&x`%wE1V>P+x9xc*9}*5{caNh5}q?!FR;^F*U#^ zLiP1Lk#{@l#<>=a#Zl!e=Od{j$dliN9}90HPUsZ}w5(DI`C6^t6qgAX$Y%V91$a~T ziXQ7AdA)PqbS>gMMvyzL{qN_=?Yy)T^=2DwehB}w3;tFk^}X0=spSm%6I|RvBDziHbhUhPx#k5Q2RSXV zlsv{=)&sS8PWRL#9LEpB-zEQ9Fj#c!^p6f=p!9{xO`1-DgB!H6a9nCib!#c70)&wo znz;hrKXet}?`?eN_c*0ZXF9BW3}gPiVqaZ<;C`dPZas36rqHwU$?6-I#foPE5Vl^r zqhCnj<3@)LIeFqg-lOQ~Utq#nwGE^fLS{z_jjjLZ!$Ds9j==%`%bpjqe1pA1{s_q*4FfmF(gM(iOJSlj*zxSW5tyzGf?0q(=sYoVQhw%6VC?T`9W^xz7<8yqh zf%}FkX9eIXHDEp)6D?egQI`J+1W7rxbiZ&O18>}D1s=7NX&X{=@O9Y|;o}FP^nB+W zpl%CG!z{I(cc!{=7Y}E21*?U(e*w!$$v^)mT>IxaW8a7so>W?Z>)1cV#3=lL$fU&} zeXgNNqCkz0?HBZr(j7W0!U6s~m1!00uj|x&y_=Aus?vLUd_>SV=mGD@%Mmp}uF>ym z-JtDRKrq^8!$Gnu(n8U={&$)#txcq3x>p~JUTT)I#hn$i|8$ca>i>}Mk)gYGhS_f6 zdniRoIYj{_{@&Fo)GoJ$@%SnMi0X0;@A3t zhi^XVu-m{!Rc;ycXi1jOH6&7QTL z-W#t}ydmTW+1lV+F}ln=ur}fa6AFy289Ep{Ycot7il5F7-fuD{Le#DpMkt@6zu<40 zZcKIJcJ`5(ZJkLV_UTJ6wp|ZnU|yLk4i1*PgP)JR0fJos_^3Z$p$qWyQgJE8S@gQm zwuh4x7Q65sP4kh9e*NO>|FHFzL2)fz8z>0`La+eAEx`%y4iQ{~y9En6zyx=P5FCO_ z(BN*t-95MrFu>r0yWCCAIq!FG)$JcpMX~qpUfoNcXRYpD{2@W1n!j8y_{1IB`oKD)`*k*()#u z(vG_>R^8+>FDgOayIMc4t6JzOACb#uKCHf z2HNFn-F`rILxek=OfD?M1ILatR_ngss_A?jYp--Zy1fq4gEve$Hd+!AC*uE>jAA`L zV(wyhve1($vP5Am3b(swZgST3t_a;0KXk!IVBcLC7U0R3Lp~o&G!^~JQmr8Q#%fF& zcIYejIpt5b_Eh2ZGH&#XGT`=GzKB>{F*U&80BwMis=qDNL58Wbni{cEA-@T8QKSSL3aVePM72}quNF;nr1-uu5IOPOc0Sxna!Kmq z+O$IM>0%lp# z??w@t?3ZyXEdb*t<2U;36MKh+^MiL1WQ{pJ%|Vzz=ugzoNRjT#HzlZgN2sH$djnLh zi$gSO81dTa!oRDfA>4kXgRi z(fH3he?G4iK0VMGCLrngCdL1w!h#2Mci~}sy-B)wE`YhWI5-r_s$#zOX`WYe5QVDD z=x#UT;`NsC`*>9*XDtnFxvTtsgwjD0+_Qa^I-j5{ zCK>V>&Ke46)ydy%8Ds8=cGtgn@ne%bpS`mUz_875_xwt6u`cJU&9Vrh51r}G9A_~k z_2%P^axLyJjXw~u%{BX`IqJMjyAW%Q9oU3F40DcpbZiRPSRCwa_T9glI7vmUat3XT zE681hfp=|&JZV!4Dj&Zs&6NOeuZ*2-0cU9W7kp`6-n%dXVRo)GQc zB}9Sj>F9mft4C7>xD6cB-Z{-sEgDcWFw=eofeei#UI=eNA|ju($M%~5^&V(1HHV7v z^Y?PZR6fnwRL3=z7-w0j#bKU+PJ~s5hlEHOUFsuDNz-u;iyP9QEn;&W2z=8)Zta}|;2yG_9D1?>m_%ISFaNkfePnRx=O@|IT-&79(+7iII8<(S7(o%L3b}c?<;JL zR{H+zQ!G`Z7pxKFO-tjRkQYe8s$b@>RYQh|V!Z~L+$?u8Ku+3r*Lpa4dw=v}(+VG( zzlXm%D9IQZygRQiM>>a73;H~{**cqm-SzCQ6nc2WnfRbVobLb7dkf+nFMzrR*!!qa z2=^A9#7IG^LZqqaj=GbDbMo@bq4`*@@WCKmG6LBhP?_ECM~Vs$n9+oa^T`bz{8)O* zYRkbkcfxD#(UJo#MmEk|v4BkQ_MJLH4V!GqRxy(X<9LT~f4Ef;+6=meLV0by!-d`O zNFJaB4ALU_@3@~^IFaFkFiqQy5iN-Hk`fhg=ceJp>5Y`g&YCC(UKh`ZM;oK_xC?P6 zclo{MU0>#RPYL1kMi%XejnzL4S{F?Fxk(x{sMXO3XN#=0%y>~x6-(3wLtree+ozGC zuZxde7rAWMb+C3`&|x#6H5I415;!;2e%FJD$iU6cLQ4!Xu5I9}gJdr!c6joZ)B8^d zW`0`kaZ^{P4;Xt|8PB_4-c5S5d#;)(caG$0co2gOCIbqeOnnjXKqY8m4__Vje{MS# zfAG_Q~C{dIF!V9`TCh^kzWQR-KAd5W9->PIW6>au)U{4P7*kc=Q; z$c&mOA6+5{?~M=fWt!uByE32~6NUho&=`M@9nG<~((WG+6!hbq4Tx5#=c_GLEPG4! z8l4KrbROfEuYXE(65jhGKRH|trlI>Boa5A)<_ODttm*dTPu-B$i(_4FXq}qEc}K#mdMZXh4L3iYa!ET9@)p?9cu;KH zR_-+28ps+A9H(19#_tG1#=;2obd6}byf>a<=hU3*Z8({B@DyNVx}_6Bb5#GVgU6rw zql?u|ZLrEJ`F*~W>IMtCMP$1je*P!2qkM|KH-)DS?^R<|ej!+X%K7-I(ANUof%Chs z<5+p+Gx;58I0HjB>2O=ZS>ZKdrC*17R=lI&vik%A5Ftt_H7GO#VeNnIQh;;33s_)e z=El8q^>k!t0@pQ_M}r88=B&Qn$(s7luc#PZwg-?B2#V$Syjwr2Dx3X$`b%TUXndZl zd=KiM%`!Uv&Jx>_Y8uRM&9cI6nm`N0!wd{BfEf0_ruq^HjN`wo0(4^k3R3;&_>X9j z!#{cDi}&P|%3^VExon<;UoYDK(&=+CE#5HPn7lvrQL0Y=WfbvyEHtEVF88tH|2C;- zQF;Re5oWfVZ~Yso<}zE-@McfR^^OG$-zj~_FpB7WGRbuB1CG!+R4Ne*JFP#R6bS-G zZJYnFOY?uiHT{vK>5%Um`z=w}t=0vq+M@xu%ZPsi{lEXV#yKQ*5@0=__3e0%q5lnl zQ~ANVs1OVi9=olvH^2#gvQ|Qr%07L4QXL%~A>rY|+iuCdl%^@0l_7A(J)wUvL0IMB zxi%`kQ>v#f#h=QNgr2vQlr7A3KEI7RkQ ziwH?Eg)Gy-A57ZSzuI8jk>VcykG&BD6#mg~@axppQ;lA;$D;fHQoc=@0(iq7cd%dU z1_L1z0KYyeAaL{ZYtdPXd$jcrxLT5jU1AQKVngzA79It%Hdy>uoSbgo>3iQCeJB5E zHzYq;0R;Mw`qdRoI)kW2XC>~Du~{K?mDvEi@v+5-f|}|y7vd#qOG82~X;1zDA^HDW z+28?Q@~|A&Q4by~p=+)9oRjaUR%mZ43!ul78v{2!9QtAdES+pGYSMw1&gC^Qt=+s3 zjQr~})`$974R^v%KGSIDvJnFd4x~W8S`=GD*&=_Und330`*+CL(ThzL%p-kX`+N&9 zzX(@Oi#LoZ>VQOZ=zVs;q(Z^5(h6sEm6p$KX+)*SlY4Xf`l*GN{P%r~>JQQEiWGjo zO4)R?2J{t-UY;6V8-5yxnLA_>r1sZ>aV6?Fl@nqt^>_O?LASRSym`-%a-t` z*a1V?u-i&yKq}v4iGGQ6n!$Ku8%z~E^{;Fg$*7w5G|w3xmK>twddH>p`hU9Wx{>y_ zqi(f_iMDi4DPdaN@ElJ~QW0LusI`#I_(oM;)CI;FB@gCy+56a)y5FFrA7F>_awkn? z$Qf?g;8&T2Zwft3kZ1m#M5*o{dWAD`T#>u3mVcM0L!}ka4~5{TkNtq3JLb%MQItD- zy@)U7SRd^!h`={nuyAF1z|^8&o@lD0o4W9Tf6&r`@zc9y)R;nZ@o>v9`5G~&;@ZDA zaod>+%K-c1aU`cJv}Eq~hjOHBX=}WZFv-i}*O7{oLM*~s@Wzz3l}{ZV%pDz_+vCl6 zDk8IeqRZzbYa#}t{y<_ z8)`h8~vranv^TWF7?UklR?? zNxDsgfbwAvmn*9vRFc^k@0Qg5guzLE`20-+tPqUK$uU>wgbgE* zQW(C}=m+w$w_nY?NfK(Im`15Pap(}a-I?n4Ugm1i@}#y}`ttxyDF_YtQ!@Osd(;6M zAo_*FnqxGw`PJy@s?bBH$eyxyiMB#*s*FWs*=JT#y~=|H$@{gL+*aIWrl7Yuhd16p zLA+lfy4UG5auU+^nL444#nxs%2Jeckngv2m&Uh!@NF%8wv4h{0f^{CYV-}aq=;+sR z?)Nnz!nOXfExuUrdcOqcn$M@WxJ1jJ1xNMmDKcz*=asOTylr?|$;<6YQAUFTo9>AI z6rdEn5O6AJHOF%v*FBH!b`J?}z3mG61rB-P-~8;($qlR0;+#52gbyXZb9hm-kfEqY zait0)iSHbnht8uH;^@wH94)=*wrtrWa*DdkL7JMq5bkC|?z;rqxPNl*AymwoAX1&! zr(b8UG1J*}-1hYcS*`tEtVd+r`HkxPM}h|%+dwsaaPbFhhL)1jJi#sV`eo~uuaGFr zvlL5ur9z)z!nJSGqnW*kE=8?~07@60ITOgP8WECZlzqpfS%U}adv?0z9WWO*9feGK zMdi!Cx$#x_0s$31lzAQ!tvgMb?1llYzda`095N_LFQm-xJi%p+B!1VroG@0a}axIysoAaAL3&HLb z;|D>$_tKoDtKluSE%JlyCLeFlBNT~A+4`nUjUfZC zm%(y8%t;@W;pw_x?mdo;!=%U=JUD@E^%sqCEF~$E`v!IwvHtuscf4T=*9%&KN|C}N z@=Nn$zuhU^y6*euOM>mb8){>^$J~@fz*3WqRKsmPG^-72*73R{s~cSgpz1C(aFe-R zb&ynkLcpRqm#f7Vm%|ju>5s@s?_7@>&n9S>XS$}dwK&6{LAfD^De{CD!ECR zSvX^M!)NM!V^FqsaI-%9XE z{!!fRPdG!8E5a>^RbttBhc>4ZTC;i??+WmglahblCDtD5A@`C(O2!)J`{$PJD-pBj zXec8O5{i%8-mj|JJyfN5TJR`jK2dmk<4lLE%>7-a{uhO4)HR4{WyWjV<7(7&af#zO zRql#$cBX7nZiB82DGEyL;XKCUk&D>}2Jhg~D$-lGd<4P4uWlETYG0wSRf_Tk?&ejG+QI9-wCwkquzEP+2kwM_gPC%uwWg+9_Y2-$ zikmPqFr6Umep5l~AzaHO%7obGqMk{cvAsiB>%9tK#a&CAu(nKWh&JxR=8Q{Wt>YK= zqds9Fn4>1Ueu2fs)89yn+JCOM9*U{cbi}tWJED5joxZLXa66uQAY~z68QoWuZ^vx@ zZh^7HXC^G5Kj&)>aSILrOHQ=>2)iRuuPW<##`S_%=4MLf33|3&M);=vb{}SdiK$=U zv28Hu`2gvAe zve`Xl+g~Ed&Z67$cZ0jo;+w=e(eTx4=aFuRJzJK*SnH8&6CXp&$2)S^t&AbkD~~-( zbzfG=k=Mf;97FvrhHn@Vo33fH8?4L>(!DM?SemND+gsC~G_VHPML-mM2#{FlV;oEIND02HCsZF;*!T<4g&y}xy>Raz&QalRav>E{Sg_~m|3s;;&>yG z60F+ja%ReP>rBT2cPGmT?oQOSs-HY%B?IXn1SmX8jjxN5J!vQ}TRix=ue+5X7=}vl zN;;RK2ix@KY7s|E-jx^>5wndEssTf6hBxXZ2a8S`To0ZH!d|i^9o<;>!8*5QY?n>H z{}j#yjZY?2?i-GqrD8i^XX~fP?KK%ye+$n&D+x`#xn*2jWO|9%Rw&s!m|V3(hjsTm zRWb8PqMGdbEG1ryfhY1JH!*kz&7)SNO0zXh!iA)?u}lDd5s_=#i0zT69Esmu5MTCh z&|vP9^d)^vrJB0=N{{x0&IOF`!-C8FTdtaLeySVS%QnafyuqYLtKCIS$Pd^6DGN3r z0R}@DO5u$J3WYysbkCnD3q{Zc`dhGk_;4E;>Ek}hm-wRn%@gr&-vyHjNaeUuF)`lF z*u>l9S#UTX=>B%vPllf)_qMdBI7M|jz5eOT^6kOgM}Ge2tLHD?WIo4jF^OQ#mj%yV z;N8_tzJVUT5qk0lsX@W}+=3;cMFp@m1y1|(xxz?~GyD0mro|r_Qr6x4g+PoB|?QDcS*d(LLpxG@lD z{%18xt{lRJel3l}s{&Wu^Q8MX0UZ`2{D==LhTrC^>i-#h11WtEC|{5siI+wtSqt27 zYT@-4R+sfJ33Bl=j#CP=kO__qnw5cdL-qJ7hHT~h>`$Fm@8y9a9gc^!Vw;l%&||+T z_|$s{LblD=y!{fo`1HO2@XQ>D(kVs6-V;P0zXxk|UHtQADc8@m$<~A!p}kHK@b@z6 zha3wP2w#q#COzA)qc29<{r-a#Kvup&PyVK~9<>UvNUg<4Xo4dmr2%E`F)8%DKNWh5 zaa!h@WvVuYKRiohYqjeQ(=r*`2%ZFyn$c>z(79CL{0Wc)hz6k_ogUlSp1YjKC*D200%l>W!84tKx4CMEID9ac)d2kf}EH!YPfT{7c94JXh zio$&d(3)+vHt3ygwQ92ZImPVqxC^zRAtCg3WW&bMm5Pr;#4{uR>%HReoKnMim&202 zY{s=ZDmp;Z_e5-)CG=VCuStOX0a72{I}9{5m zuRh`tkLLfyqn!WX(SdJ!J{C?rKwhxv$sbOd0edMX-#blITBlUHd?X-W*_RZD`_5)8 z^U3Z^nfcZ6#@<3*8CNegi_4pfH=CG$z~91fSUwzxiJB20gwzE zkFfr4iwoe4uShZ>6ysM2h1byoX&@k#%sBpb${tYAE8}#xzg+o0vvlOR>;kgDTCGkD zH4AMH`l9F%3LJbTHbD36(_bg_D0#7gf~NP9j7q{{k1(#A8?-FscDm(jlQ2plKgo5q znF0bnOTYi~@#9kbj;nzLKh9tN^I*;d%LxE{l}Srg%9KUAy1G`5Tx8q{m7m+zr2vPE z?26_5?eXIegea3_O;r4J``!#_4b=MV9iSpO8b(il{V-kKvZTu})VfCbH=YANBVGQN zw`RwctxeI1F^ZFMDtMf?*R?ob$(4XLgihdNL`WEJ`2bE<*Rum;uYc z+51Q^xQ=RXn#Dn*RG-3bA9)@0KON;frEL*5uJgSFfP!Y5unOY*_YA-t(g|8sH68W1 z%ep@Y#)Qe>0}wa=Hsy%;uUE^JSxqefPr=}cmlsg>zmbKMy|tqGQkP6SYtCE5?c8q! zO65=#7h4}1rxEz?d4L?Co{#mIzu`-v@!U<@cvl3hj%{TGZVCl6z(#&vT)x2{^6TEk@>vXnQhCE5bWQ>nfZ^s4kvNjRM_;=*YsB#rTW$E9ED!Y8A@ z1rN0t!$MxS^OHxFOX;vEBqAHKpW)EqsJpu4ay{v7@2YBl?;G9!GY3gsdnV)Xve5g& za0R^JgYcBnYO?qvR%w&P^Sfj<{_`hkj+hoH_#9R$WY>BVQSUn6cuv*{-E1M-rXRg( zwq!VG`LDAMwTUS|5P9Rz*%U0jO-x3-!4L%wbW+ZltFHAm^ReX6&5Cz+S>kTGZbv8{ zabycPR+HZ*mx1LGMlFEf!cuZ<{CR=%ojdwYYaB@nS@2N?d()p4 zh==`!IMTHV(p1h)H#F&H@S`DoeL*tlL@#B=wNR0aN$%-~(V;0V?x6c%MNl(B>-Ud) zm#)Z>i)TXZoEe$!XA>_}1xS}qg+X@!Po2O;{nFpZtTXW{Jba<#pVZvn=`Ul$RrC}o zONYL)$j~9?{w%IZXvbuy9c5=|ReIC2+$=8e1DNMI^=gDdY>AVRW@&e8RI3BqUh#MY z>)N|>Vei`AQSq7`W!Of>mg)8CdH;$9evvX^JmV85;`S%_UhS)@rMgMQV+9}Q&nd1T z-yhf?BDr>|cL%xs8^`(fz7T!yOwqg?M;DP@44BKrMJ#RnrZE0Kf2gPC*8e#w2G!Ve zsw^EW0a0h(qS%S;nDjo`hm)5x=dVvhbpv*fLl-BPhvz|}EB^eV6;zkHzxC{e5w&N! zAPDejkn0ijjtk@zU<#owU$&5{v$EYh4l7(m-s>bu5e{=UmsXMJk zZ^RxyX8e?N!s|Lo&--CGP7?o9-5|Y0Pw85&v(w~Rsnr+k&+j%x?k}%B%{;Eq+!^b# z;21NLRnmm&J(xedxY90QchY7{(_cyK@S0hFMYLi)h`#x6y(s^1-K}dA268FMp|k)A zzZkoe?>MCLOkwcbZKX5#BAR)?osNA|t%A%QWmmNl-&ZPT( zm%QYc4f%S)Hm=KY5%X-2uaV1a!>KSii7QQlo;NG&=#tdia_9b57sCN(YiD%y&cPn7 zNVd%lq;o#xpy+lAiinM9Et0;WS%tOgU_u8igVKf*29e8c5C{F9W+XFB|8k8FLw356 z%_-jE$qL(iu6M^4il~uiGGaQlnW&H-??ts?AL0dg$yG2(;4`JcL%ddwvB|-*g0h=U zp?E!e#NK+ZGx_GKBBsM?P4*V#Peu*JVsA;tLRYv)i2L=7(Nt`<>uRv@EP|xdG4#8+ z>u$npfu*k$b&ifF8);Z4bF^44wH&Z)H{k)PT@$U~(ilGd+cD zh*6Xn@-T$2Pib1-)AvNDG2PiB-f%vFJ@+2*h^mmK-1deWFV2X5e}*MI+M$=UcX_VW zbFUnkLY~qke3#WH*Wac3Pfq^P{O2sPO_#CW_jJ>*HlA&{F30Rak_AHmn;D}Mtz%6b zuj3#cnbvfDA|b&eilT8WgX3lWeiUWburkuq3RXT#^ptN;=a`gN)Xj$^BXP*_z0Q@# z+H)ZF5QkC}TyEc!a4S;H==c@{&5wj^rl}>JlH-haztOq0*yObX4($|%>D%f|Bzw2A z#f+u39uBU`$?%bDi|O->dMAKLFg9Wt7nBAA^3Eix&c7Xb9Jw1vpm+@HwCW8dYI!!$ zFZ$4O6IL{dmU-7j*z!*EZKtaM2Yk007z8<*&@sYjR&+1W6Q-Tp-7=M}f*|a1w&N_R z{$WYS=Paczw)9KdsvVhcvd?e(YB+Hl^6n5U5d+T6x|kCtSvq|3u+h`K`8gA4$6<#T zat6)}xa1Zei$y=xP^3XTVhx;6voU)qP@0fRF*_fmsI;qphYTRQ%#f3mfwy=?yjjy2 z^$!%o=+Uy=#$g@p9<7$F7&ffu(W)Ga(OtC%lAWAqfSdofslIG*|7vS5iO+CpPLrNg zYl3oqKvV3nK?!m$#A!)^Rt=zn4os@}m*3E~w}Go)RPZjN`Ix7oV5JxLt~JqlhUf2q zEPHF2_Qrs`f*-vD0$w%;f$l{7FmQRm_9m^WR(xMpo^V66emVvH4G6#aM5HEo^ru1C zyyhR{l{U>%{qp2Sc&iUfjs9AKsLIy3A)YAt@1SThf|JR4s;(KW;YgjeEpG+35m9|$ zWB=N~-b#9xhs#VA5X262q}}knERVnAPEn>>{}MOz zJX_)`wP4-;W;ys6p%72s-)+1C2}SSSqEF)&92Nc|YF3{{9%-!Yc}9 zG;5_?b*9@R0(Xx77nz%8NZ9&QpBI+>_ZE`6M2ke%3h`M<-9>URBF!(fMjcaCDu8D{ zI#5o!W%N?&^afy*#Bukf&B7YL z%4|!N>GZbL+9)>YCql~^mPZ;|w+^6;=QamlKR-+*iuaDtj${}b)0&xP{7ngk#~W^( zIx*Y&@C{Va!J1EcYWYkvfmHWfOoC5c9Ci3=EIU2j7v3G91(Z+b{T{@pzmvWs_^uL4 za*AP~oAc^u+;;}UGe(0OYD+yAUJKn5O#IeCF#b_yuG*t~U-pqgzci%_vDMb_%K(R0 zLnalLhNB9oEmm&nf;#fzOQb=Dpvy`r$(CmR7vFju=2fdpY+|C&wCapbOjRDAA^*L* z-W*F8w)gkZ^-gr)*PXsH$b1&0i;a<)eV^W@eI|Tzwg40pOe3X#7N+9!+u8dJdBduO zmuQ0thalFZ;KUg4E%NuJlj&zI1mfc0OMei0FFBEPDEwNYqjS-3nMT6heHLzvgi+dYWTTHUq1JmK4bqUt@m_h zcm!d%0n$HmafKOq@J5KgL8|#vU21}yoL~DbYVUax8Ph%o`>v3&T*nceG~|{gmQ3+? z1r9S%9+Ntw64zGHU~z>CR|1OY!~>W8fdnkISp`p_+nc2|Z{v2XlS?CgW)>TgPE=7f ziRaPdQ$*+eW|+A-Q4U|VcymdxB@pDbouOk`q9;=m6c!6Ry2;fc!2!7*ReLB|&=jRX zq+82z`#+2xXD8M@f3(^T1a1I_w)|nY0 zrMaVOsNKaVZWh1c=Z+VC;0=y!E$)p^OIe8wweX$U?H&=O)uK0Be+FbV*)qJ2$w)3J z-fX~4hpt`NhmoCL3*3B^TIecN)8UVDi?RuO==Dx8=ri5l!FD*H(Otb~B-bTG(w1$$;)P2y`K>^qSs&YwwFzKdIi5Gec`As3ZuJSMBm^1{Dqf*9kmCweR2=# z+Oy$}4}igSIeLACOszEar3LUPBG#HMSCFFd$y_*|{H+?9>*lbt6d#C-%u;Jl=K`%ECmW0f zgp6WFDG&JaJp?73TvibYiB?dQ%$R>_zI#dT;)GPviGiNXX)>UhC+dl{M6rN8u19n= zYf@^VjoNugRclIeE_yFu;OHJYxbuq92}8nEVDVfiI8UT|4AXd)Y(8Mn)-xjbMjX2N zrQaapus7Iw+~!oEX{dHuE7l?j^sXT8g+ORlh{ zCFXs`;;<=9SUNj+8R}oZs3KA@Xyo*xKoelCx4&sWJ6wu90yCu zL2AMgI^<-7{9fJe4gZ^<7@Ah5fwdn$G00?=FqaMwQ4cU^Z%W1(z063}{l)YL zA8pmgNZB<#u;Ttyc52SvDVpQc5=5TPb3K&k7ynI|O~GR!cT6@RjmHxv%i4pHZlbEI zB1L!NYa+?P9b&C8BSS)#EM%d6K?@ba8LDJPr^bTi12=NlJce+}r|d;sbSxs_5Bue8JkoqS}A%iZ7%o~Z3&-w6= z_=ygF%%`@O#XY=-5Fy3nHyGQF5brIoU84!TcBF=rrXHUYLM{tZ*54}jZv$UOalZ4H zafA|GeUP-3;g`!ZcT(Ua-KM&ib0p_^jTkzEltQsM54;SwUZt^c(Ypqd3w>r>F^vI`{;dl%b(t2@G}st zp8c)A1fHA71D$XcTqnA^>A<3e^pqY&1>LXnEg2e5vSa<)Fm=TK8^2POdumsi^En$%mBq0!vZbmk-Ya z2sqHrzIHKj%-VAq1DWb|Il((^)Ih`fr>JO*=RHXH?$8(XYa_fpS z6-l4-`~(wTe{zia<0<=+f@eg{C#_%I^pKQc;kj^U53>ryUr|#Zc|Z)!Kq1f^&NMl_ zHWtuZ21r~!{r@yd`TeZDlRE1k7m$L15>P>-YclR?wCb1pj9(3ZXWJwLVChoj@o0T4 z7kKh4J};Q(&DFYE}QDS&=yaQh45kBoFm{pFAw#e0)U=G zU}R?;td=#~9FJ)VOo+?BHn^1Lkn8ld5ud*~8WKYjWTB$l(jlGh!5ga_u=xG~h#tPB zB3QbzIyPF(uoS8l1r4eheeMzIueEvPO8>8nM(T~2`wL8MH=xLQRKB-0-&^73lyH9< zE|)MBRI4t6Ih;8D(kt6K#WB=O0oCA@;I(4=dSpOrMy7Em?WJ-Vm zw2PGN4R;7=0YW={_pBVJ7+Pr|D+4%X=7YZ2^Mpt8v>Oi}zh@wx(PFuY|C1MoQd;%~ zt$L}hw5Dd_Q-}W(_7#aUL-v`js~AcFK%ITr_x8!D)^?*t;?b@on&87#kEWm2hUwQG)ZeW3 z_y4IHwWZxFV0vNg(P8XlJ?H`X2<*$yd<770|F-BV+rKp|0S;6HRr!Cb%@p&Uzu23Y z|J+nhB`8s$`aKeNQ;>5 zUse{dEbC@8nn0D)$m~7Zi>%F&M=7vGqyGWm9{DE^FCR>>Q zoqs%8r%md0id#;Agduj>mFAFElw8*T)g5neSi{z=ra=K21-3M zveA7KP4^>B7>{#Yh^k%1rz8*6sr`nffayN6zn}G0WC}YJG?9p#tqMf2{2<$uT zfWCz?QXW6-ExEd=1~&8_!Bb=VO=w77zU=Q=>%sq1xPl~BU0?HUdfrkNuVlYwaR0MA zW0rb=zE#4)^0IcxG;l@5yjn>XrEH#I&D#)?EE7cPcORZdMfDHy!|vIW`sFyJX-SN( zJk#k$t+W1>eZub})(flw_A^=+=C7n4OG5fuo1gdxBLeceH(1nJYBgQ- zah^qRW>#r0v5Evd^e7iDx~evu(7*WO4BYg)d~x<gP=Qo=rVbJ$4Q`sSts zKs%pX+?i*1{s5{u8N~iBW}?^8mXlhT-B!9oTA!75$zRBVY%sd?%wOx^1S6_`0ReKO z>@5w@zC>mgJorm4_eKB8%?(6jsYmFwzdi-GKO?X^TxtI)g7J5#of27UzXBDk1(ydn zf>8|6D;+AjQ)y_OX&SX$^p&ZFp3&>$7JeZ6GH&BhwA4v;5xj6YPm^m2e8%DXPQ}x+ z@WQ*>y}-ydk@KmO2x#@%&=XPmzb|gD1}yU)W>tb83RdN+r0D0FqAhDtA<_k zMSa&m{G$zzc&)Gy{IT61#TB;fe$;fwlWW|IBV>m_io!_~cpXmSdPC5<5|?88E#Oz_ zlhnq))bs?2SvT@Zp_fhP+bTO&a2@14s8EoREErmHfcR%X>qrpS)_#Szj;_|baVXD0 z-NhXfYvcuOb-GbCtNG>kCl;$D>HfsbLTG9>fL=!EEg}CJ1ub@#dLG>jBJM2{tX$Qd z+Z|PR8Auf;Z!F%I1Rr`FnJ>EOfBvbvTdSc}!JPpfc}rab>&AK$oHsCadq0D9G(^() z8qB03dT$}(yumNmx7h2>XwaGL#1eb_TT~X-hJUZM+;@4B&-r@+64L3*OR)wVY7r>V z2JJUJ?ayc5?YPqAs0#W1M3IjpSDl&=cD*k@PVm@J^71Eb zVpEkHxMPq8ud67$sr#M$Tdhdbdj%nXDSd_R!(Ss7%)VeXx%h_^oUzLJd=`_@U9+x8 zW_*pCMe0zci`4_tJzZNke(+W?TkQwG(AP%!fu^{=3X+z4@7Kh(P^*NvO4@y-Z^Sd* zLgcnkk{6{w)D)Rv*$f2>&DqX!QFyS?hf?b7szQGW0}ux~dGX{NivKD5Yac>dYZOHZ}Kt#`y3%cClfSD6P#leC^pH_=4sY zzt_3{!Wwr+<{mN{Lf*?!bZCJDA;+`PR?%un@O*r42~ zp8V1TBd^qBS$5lDNL{ccSKv?q}dWqD&; z(!jVYcgAj-9`R{>vCHAJAvAoBnpKd{@sQ4+nf=XngWD7(bNzm`{K(hkU_{1rS6^=% z3mWfvYnB!}WO1SrkNR7q=^VW-f`N$M>Rp$8EX8B}Bac!MPKwUu_TQ4}W)DMFiK}y6 zziY~lrW@n;Mw145MbD(oNHd7%FFuyVvS<5{wGgkOhWU&)EW zm07N536*cd_m-1B+;2sj(9*qkVCO8Q51M|fE_^CEP&X5EddXVQpVs#bttrR*l6AV} znilS%skjpguJ^dN{)W{wkR4gF;(u*+?*T&G2!z?4(a}Y_+A%)3oipgW8PhS~HtXK@ zgZbF=nQeH4b8^k2EX<<#t&urpDWG+DjaPE3EIh@YNoOEXR-PjlMdOx=E|({DzXC2? z_=J!mB1!yy+ClxUF(^lcWv%LD)TA2a^*hhh6TzlJ&qqUptp3&Kn~gCy_v+q!;7LMj z)HTI}Z!gpc(tP1yH%YrlMD+4`H7o0*0&xTkeZydLvL5mb^!@z?#IKXKf&qVB`1heOrlm1$|Bz8YmgvGGx zj+%C>2_5coTVvGjyDuT$9%``0ew{bfb)6>k13g4HQWWMLW|7oy?{HT9cnG0`h#(Nr zeR4Xo`|$vIIGh~_w_bpp?=x`*$4uZ7#dCZ=${$@Lg@>X$bC+*Vm6#|b^}=i~(N!*l z`+hKMxRT9b<6bt<^r&zGj?aW3Sb|A431q#o(t zdCxMUNPz`_roM3|(oBgDO1-{uuVU!rDd)J32$6|$b7%Yes}JS_o4vhZj=;JAT+lm2 zc0n#})1*#+R^)=z_{*F1mVjU2ABnU2?(eiOB*IFk^SmH;~|B!8whbHjBK8t*MC*-sAou5WTIGiCpEkaz zw1H|9k0#0~$q>`1C>Sry*R2KnDJh@OvEA3B$DF+2x1XS1; zlfZe(aS89w?Vo)w_Q13U682Wt;*7dk%NVU_A3LkClI}Br8-8;%AbiFkh7?7y4 z^`!CAK&JEDQTM7pq~1w*h)QW`3USZy&S*AKa`}wi8LL7heE*6zOP{aRtVTuOlvRGZ#TOJWu4L&aczGUL6J0CPgKRd&Oyy9L8R8j6fzVxW z>#@w_Q7XsvYx(ym-mghBX=4-Ov6Ja6c|YA4Au<{?@tFBs9}bStti1ci7!Flvj4O*z zAG{4`J?iolUGc4UzucUbq_Fs}7T`3ZcR%0h4lHzK!Y?S9Di%5^Wu<~vlGgHN!!Gll zYDZLeq>kl5?`FwDTkvLYw>B$U1BrPZEo~MrHNgdr~uMW#M#gU&P zhMXM~A*wO7G)Xp`${0h`u|A?9Q=M0T?xvcFp@)IMMZV_(N}d!dOg2486Q*N)0NmWwoXZ2?Wt@^h1iTgC zz8YA(hW^i*n)r)l_ei)0Ofb3^SSq5isi{ME7m$px2tOT&$$mPxelrE8vW}eUFL!+- zTt4pTXG4%XLmE6+8Jh2Pi-aQTj3O$;jbiM~FREY1a(|#}VG=&Dn)U3V zQ)6U^_MBM^!MiAwZVrJn7AniSwl=3&Wqrbf>Gb@QKR4qgx6#Od*i**f zEp&h>J={lomcx29=+2T$y~(?7mr347|MS$E6`BRX<-5^*=n`&9ym7RBfXDXb1bJI~ z1tzm(^dgOnTI^ZaJfblw^{L6v_0EiN&hQRW!&v3k%fTSQbael6dShYh zTaoXT8l&;!WTMfL)Ot?xY#!#?&mUYxYqrucd_h{{OPP>^}T$>xZ^raGg05yX7=N$}>y zLl0Tl0rV<-YR`6YbUAYQ^PLV*_e(DSjV`VD)bkJACab0)=?7x?p2F}O!KJp=x)@%4 zh+KU`DWeTx@0=soo>gw{T%`GJQfkJj(1WImv~iJmxhq{t-5%}i67F7gdF#)>;yorI zC(asp(?}25Qt3GK$``E@VX&493&`t(Y+KNi%Cr>GEN_7B=s`q@a7MfP!Qi>Db-mBsiyvsKr$&dJhgxQu~W=F?XaHTM|7 zdFonN;5D3AK*TTq7Z%Ac0Y`j$Tu){ka8NTdGRnG0l00bjZfk^7F*`(t?V(O4>7J01 zI1lCSC4*fy=y>giK|S^d@f5H{6_M{u34&Kp-OF3=lPOtv{?>Kl)i@sPXetF!=(ecL zPEDTCb&|z&wXV$2!ECFWKlji?0b16iCg7_?o7gLF;$}&;pdgaep=#Hluz6dgegcK- zc7Nycm6IyiS?iNOHeYV@zM_D&rjj`ga_O>gEKt z2*EU2^Ro5yz>K!!Ym9qXL?n2dm*DsUau-74-4gC!V9alIkKs|_!q=}S+}`s%&%lAb zg~B^Y@y>yIlI3>@Dz4BT{D^mQ_{uZ~d@HRo>kOx$7d>fBfe0P3G8yC1BT+T0xoSS=`ZZ>q%-qldL^vwEtLLbf%K4Uga&Ns$A--#+cA4PULGt3J?Z=0{N(wdnHVcvdx z_VeCs#XD;>2pp>w>A9M6-q+{XOl5)I4HTW`hCfm?P4O8{lm(b^HD6_pInlE?D>e0O zIofG&@#*5qWpa}Lw49QRbt^vFt{(Ac^qbWu85P3v75D8s6Pv#b%4jUnsXOk%Rs8DK zbami>fX`JLCRB!HKAbs_MsVR8j*s~XcLQ|9XabNTa*l3}ZriyDeZ#}1Q-x};@bN1x zCTW*FPUQ0xGe%lGZ~8_@>A1P^d?H1zpZD4W2c3|Ji;MF`bkZc~PQd)xVdbly_l2RZO~-S5~Don&e9%k<|d^W>261z-|dOON#p_ zF7%-L4eW8MllKlSgabscdQambLj52bK!PEY$wAmuQP?Lm(l4 zOMcN4mq*?OenNxT(OB|v)im=2jT+wSNqcxrtuENp{5}I2DjBxbfmDloSs22T{Qrf$ zh6!<>JzoSEdh zGBKA8eqCMN?eA#+yz=sL%{^?Ow@Pg-=gH|Q>dy9`-;sQ3(7!7Wz#7%9Z(gK@F!Eyc zKYCH}GP00|*$acBPzmglJ8M98p~~}7>d}zb-BAv4MdXpP>JJ8*cbxnvMWW+iT{a6{lsBj=XR9|)OfPZB` zp=N%6vai7cN%*MDy~%_@3RNfjKpE{HR8j_NjVk9!XcI3`(a%>TAx2#i_M>x8Kk$ls zWlVjg_)o_9_xiC?Vea)-5JS^$&Hyro*x*n=$4d*`tz&{h_)xi+^gy-=sgHrS%B3^7 z4UrC7N-Jk8vcSFG9}!FVBK`Fcf4_eD2YF^JPD5@xjnkW$y^l@P*gyQRd4Q1vd`3)WOs>p3=d<^Hgwc_= zU&w`Gjc0pkM8coc0HsY%-k%j%6fO4G?*AA+e1`*VtV!I3twb3z(bpjI*9~E1emtlX z81_D>I3}Om)-L*ZTHafv6|G%mEPCPg`h9I|T~#))KZ(X!QVj+AZ!?7bQ0ZexCUk+f zO;WhPkAsCtqcrRIa9xyrEmp+}rg!}}inQ&qXP71($qWOytmz~Vqszt5mo85gN2`L0 zXh4!tPtpHNWgMkE4z_5SNF5lmSv$U*X{;Vv=^_d&)th%=<5%WT7Jxc$Rq=yqkZMwS z`s+`Gj<)SKfPwy>JD>x1z%#!5B8EX(qF){aKOy8-EOhSxk{ZEAnjZjC8*i?dNNvMQ zjNNcdvCUV61Up=b*&C;Z>Z{5QMv9Pqy#qFuuSh-muUBNJ5xkgWI%=kId#Q7Y=pX1M z1hOQIEn1-DFd2Cf7asv;7;Mfco?Ey&lX4|n+GbFH7F@JaImbf(hD|db;6r4{P=N1$ zU;SSl;|sLyrIBG#FUlwn6dks*LUa+xOoFWV8OZpFEn2)h#cBjLmx7p?&y#oNV8C4m zd<~=Z41uauKCC&*N&mGZR+>kdIDk;(enI{(&ft|+4ltC+5y-^Ck4uKo^|6)V@F;J* zZbE)+U3)BP21Nk|z<25$etuH=J80DUrPtw&&boI$Zrz%oIz(?L;1KA45EAu2cU0GO zQ96h{>}lPW9rgsJK8E!*@KEm(9e$z82nnVtNh9cpuYeRoL>ZN-CkGl#!$`49BaqLT ztn`SynAk3K($Z8OH~T*a+{%9qlG%F#e0TrPr%whf`lY zs*mG9FEN`7I5L!!#7_S=k@ANK0F0$I)o9(Q`Q5+N+)J)-?|$Q6ad3fOwBKZDXY~&b zZkN4we7&lCdBs0A)9akg-Hr{nN0aPcw)*QW!y9lEzd?E>wAKoMv!hivMoiu2BrSLx zo-X5AFtfh)njzt=gzH?T5Rg5+C6<&lJN}*0~Cim@LjfVtpc%ZAz^9d0aW7B-?!~3aAR7hU#4Yb=!a43Hh5BXsQaCBxs~% z?=UV@J>;M9jr}2mgam$X6wbIetXOMhAF$n*zqYHOz)K2YR7K4NJnO%g26D*+E%Mh) zGZ#N^2v@~s_UAD2WN(Tr{w~^G_o)d%&kCWov4N3u)|DGas=FJ?Zwj4D;&QhA4sT|k ztSx5#pl$el`^(|j#n4wITH*g)rI``2@GDv^Ow{P#4BR*Ts9b|iKb*-6X1FVsNK>qL zIbJ-xZ60%aQSQU#L!051!Fxd#LsA^r>#{UWGd-P`E($b`0$hQb;K7XsAbNFP|8NUp zR303}@d=D5P%;__kK@}pyYe}z!kVNScnMqV?RYqb7%Yw>OzfwB?>gK^2xMLb1m1n1 zFT?RXgW@Hfz&dJ#c6~q9O!vpu$nl=~Pvh+$aHnhRE_#LITs-}U4*MrO8TT{syb?3* zHzEK`Fvh{p#_UL59WbDc-Oy$>vHdA{>y7cHJQVW$hj-bbh$jo+7WfAHY_(%-=8grY z9V1ML=NZ&%OeEyPuD@}8PVX9X;pTcnjHZ&FrlR#`;^_e|FmaaOAkeotPZ2#!%YB6| zSJ8A+HP&!Q>+LdV2FI}f;vSGhzN9h>(jV+Nx}k93s+EfEbJ9DRs1v-YQ~R(7Ps}#i zH#o<)Z3r<`ra-jTr*$}p%sgQIoACuw>sXtMW52Q`xL5W{XKmKOJG)$CPm3ACkD3;uy zig@OI+?hzdnpR`2`pFlAQPC1UnvtyZPSg>H?BV_;&i#h@Zb)V?fnn=MrLkJrUas z&(E5>7)|SYORJ}an|1j=wB=c$E5-gAE?&lH1^WFRi52GSd3eRP{dzhr5;0`XW3mXqACt6oY(0EPEIs9g zS)q9~hm}z@W3N?FFHBir8`up+a~G$K0_|8;FhCz!KZ|>3<=^BS0~tt8)9DClsGl3V zeZGOiw6f?%GIVzWp7$|+=dXXMaDOajTlDF?!Ei-n`pfb_ugGdWql@Rgt;g@xk^1w) z8}22)ycmx1o2QzJvW1(OjKvfXVIHRTIM&Qt$_S!|V4U>l@+rQg!Pb28LjJ;_c~5JY z+LZdBeFovK4;t<7*&h`CaH_UphxVy$&rtB@uvgE?k8q^{)BONr-swEOmE(}qzU`E8 z$j0lNZTrcyR2_1wyRRaCdo}YNTk`hT_cX#husnC&%idYzqrrzBtfi&zXwwV5LQCl~ z#~y~8mV2bIMWAENzpjvPkm8oXtSVqs&=hi61-y@Yjou0hvHE%H95`cHku7-+HvQ$| z`-6%CXZv`nmk4lT&aPdM{tUS@lgoy>@ty68rPmJVL-@`%XI)_zF458rE?YWXN~R};J3?ti*oap!~RW8`aF z_x!BX@@;VR_;>fUw_QMO&E>BD!gnbS#kHVYrUHErqNV%E*)(4Mh?O^VY>0H8nO4?B zJVk-zH9-=5C83C#5#E^R;WpTFOz#6UFR-^?8Rq3?U%sWetxICd%NBJJefxe z?yrc_yciZSww$~V1k?|#9h71Oy|^>kG75ZLFsRyYnP5bt`J6(c+Z!;G!IK-W&Aimh zJ}!d-dH(c>juWi%(#GhH*75IM4H=t@{+XlxetQ!`NrK_g`ks75iZ-^>M$@YIKaTk9 zSFn6cY^Y89N7t(dKYLl63ve=u{YOLdNR_x~&np{SK9j`yBYb?3chEy!d(+X@Hel76 z2xD}weaF}Ven~qwFwMjx0fzX}9_Ak^3oJ=}wC`E@Xwi<)%WHPcU82CtQ9Q4u3gjx^ z+FgE?PS?vZ8Tyju7b_Y{5xsVk8OpAeAnuLH#=e6QQSiEXtpn`|3XSGdzAIXo+s(5{ zu(`{Eti3P<^XlqqJvyZ`{(`%*gMP9P>4I3=EYy&f0^x9vDsp#{KlCuCbY*&Ffk4F` zTRmENd9W~P7Zi^2>XmQ!!WD}Ax==kVI9eb%FR%WwylkHYM%j2p`k~V|Uz#}oQok6k z!M#Q^M0lRGBI0Eo7u7PQNWyb);hrp+!uTaEgYaC>;vB}yg*lulPfs=ZESnoR>uR~C>X0g zBTs%$*45G8JYJ6I3erLJO{8+SBTYXE6k=Jc<45fX84Y_IN-}?T%m|RMe4?)AnLlAm z16vn~@>y1!iI=7mS_Q#3+q9WOy-R1+7G1ApM;e2PY;z6q75WUSgKk7%oez4RG^UEJ zNrs$;!@dn8rmm}3^u)Q1%ZJW>Zc@)F4Eu!W{6eT61_oOIN$dCD`926GzWLjd2Q!N( zjOpW9pVKYFtSf(3lauc?T9+;S(wXFb#+)QK;csrQfARbIj7y@UD=xPl3H?m1LtWFH z_|H;36I01*AKeSF40Xq+@C1t45p5IN$!eaAUEXXv8OW(gi4C6h2ANXhH7CEk5WY9M z%4wYVXpK<$w@$BV0EJRZ0!&Ek#Kp;Z#?s@0%z1#b{8Ro_v*?8Pg&#{J^wUwP!RP6P zpg8U?-*_uBH3o&TXRI;hcR6@FJn`EH^G zE+aDIhfQAjfg)j!-mDkll11|CouJc%HQmfmyG7s^WBT;zzmsAopWU<%C`tb$&u6oL z@yV$&U9Z(}x{yn&C~^*qAtRtGFp^*zS0IB2Wy7=(R?ys)a2nTRq)}hP9suO2u^&7k z9CF6Hc;~TR4=EP-)!ookOfo8{wC+B`{1NF7r;@-2D9{j4a|glTs0nlPosgOlWTUx3 z*8cg9$pecGlZaKWr|~u7kIY=dAV7$yJ*)iz9<+U~h2IIJ@+&)T7!{@fN*Z`#X|IJ~ zt9Gt7IRrRO<7h?{qtA4mliv_7QT9hIzgb(S)POYoS2s_YnF$OYE9G4M{>4mKPT zdiK9UdqWBj$jLDUlYjT9A#s=!YcGTpBC*7Bg!G~*NkqTNH+O5nN)$*p4kXAxCZ>G1 z8eF*2-~3GJk=_SuGx~p8to~U(Io?mDoE>xVE zhu{Bm^Ga#WOll(0Rk-`@Y<6-9PWdx^jf6KEWa|c-eaFEFw;}+ZO(q~?o3qHVKWp)- z$#2VCyV~(9@I;PDXva;7B-M`xwhBt*UOckV{Dr~maZkT~-oDZHx5D}RbtVDebX&oz z+r&jF8x}*Y%7eBmhKK#f=WXT=n*4xFG_=qdgh$sW*lrZx(|sD-$T&-Z=9DWjxyn_Z z6fk*~9OKAqZXo+wQfP7&fNTaPis{7)3Z7i)O?4%`BvAee;Eh2~_X&EK()vA)E(Iq- zv2+#+|MTxLU;a&k*&7}Kn9CD;G+bb;I7WM-s9xg?+z(;}wt0D_cdNa$C$Iq!#iB@u zB2u@F)$$Tq0MbJPEyyik8o;{`0RuR4O(JLG)^S^XSIJH zshaE~_k4d4E+9_>_}-~je?rUM#`@-JninnE+K@QbUO76K9e{xG$%(^x4mHZhyq(~N`$OXFwQv#dpwdJ}NY?aj16twvlpr%=Ozwy#{j26ifK!qUp z%XT#8Y|bU7smOR-%*IpNMvF!a8pmNX7HtTK-C`zBX{d*XhbLh$;}qIWB>#!`e?sZH zqlq?Qf;qd-rQ@$(ze27Z|HfBu^#e+5yTfzu6-4VtU1WfHu->uOGGKg>p<}>UjTr=0 z#t7{4qp)@LB-J=@X7AmZ|3oAXDgq{%YHicqEn%s%7KZ@0E3<*AvbF`gWq21*1+96o zy2xy1Nsr`${{Y$mtmonv`ne>Vum<>;Jl6Qhx$ksvkRWm38y=LerZ$&(gaf2iZ20m#FV}x2B0KfM@xNF4;Zl$lE-AWbv79jQ%~A zVf$<>K3-l3Yb5g?``jFgOam6M=_2C|pl5jVCMF>v1b%SnW&HOMU!@Ih|C}9~w2DK(ES1+z#C62>VSGe1Q^`E3KIMK>?CbMM^_P3OX2aizy zod%^WmNkAWibNf!UeB1&zhlV)a8b>C-XE;&*z;|WzmmRYe#oaul@Huk9}d9bxh1MS zVhpvK`O+Au#pOZ*G#B&$&#}X_f&>CX{z?{%gabQskPgkW zvxd)-0W1}6+h1Fa)zB7sp=CIC$=}oj_{^~ehRJvEf<88y8f`|)x(eNG-XVhn6E6GP z!8=YKF4McIPtY+hxM8IetDDSbc1UJikC-dS#vgtojWPNmG9z)$OT6@x#`Bn<$Lga0 zdXS{-3qafOhqqv3nCd}u`KTPGgI{zs;oi-mlq(?#x0RWjmtHcQ2)!667lJqn-PlEg ziu_ZtFf`oS(mko6)73?avN?^dr%qnr)ZLTU+>bK6D2Lc-@q;KaLVp4jnw9qAJF`>e zmWfP6d+r=m-8S$5)+@jqm#)^FU^I>oLI9;VOkjVI*~W!BdeB_r5_2qtvpX;;zw ziZ}Rg5Zn2Zt-&tr39#V)Am?+Y@68fYlQw7p*6n>5F-6+bXWwgoqg>DTO`mt6HVR*6 z4Zf@cV9_O~-#!SK+};;wvp|AS!4YOfWn7{ts} z1Md!uh3BSMWgB<>G&V{hc!fa@o~XYTFzsBF2GiF!d2g=W%62BSEL0r}EMHTTp;vpB zd}e%X5VzX{x9Ncfz>f~Rqbne-8*_SFOHuCyE<#GHAM;F|^@{>$|6X~AQztMEDpow) ze(yP3)#lKzUHtnsX|+41R?9E=GRPY}DSFYjL4aT4Z1HK2FIo+x4JWv_E$1Ja?C%0t ze~Y`&-2gaR4x+l;&4Nu9s#Der(^`;Si0;jtfq*l`vcyXx0VnvTJE!Fb53p0i*LXW+ zCv9x32^T&dn_1~Z3J*#f*!OU=>FGFqDtP&2iqThin7<$(3;>kC1nA1}Aoz=$#G5~J z&>jaNI2rRwx=(MZ4x%}~(cCODR62vSP=A5NOoaA9fwB6qsIkl1=PLcv%#+Qfxg*g9 zf%L<}!%;H_to3^Dk~yKV}G8dhAFy7#+qGV!piA?N{+xses(Lx%qb%*Cbr z-%_BvnJ{t)_`P+wmLKw}`UqqRG&Q2s_%DG9rJ3EA_OE-@kaydhH>v~}KY^RCnSx}? z)h$X-6s<(45+msK?K*5$B@5baoeOXLT|#?u+lWnffz*MahKAX9VQ~H~BXo}aCDu|@ zdq>A=NJ$xN|A%0CznhFyaP~NG25V699c-GUEwHU@5k7xPBNLvDZXasX@t7ov3M<1TbyXxd)CGkv{7^t!zT z6EVknLQ#?wg5baJ1F6{H=likS~BEBx$r4 zu;S;0Yy~4vy5c#~LaT?2H%wAnV&S@*&BB*R)2LL-@=2n@L1<=h{f3iB&EUUuI;K0e z%Jg@KqdkMoDD~y$#3qvS5|tTK@Rt%S+0xiY81H*Pxh?KTyVXJt9w4ZGNWopH9Tt_G zXM&AP-NF#pfeodNgd!SqF<&T?8Oi6$GB#z89~UIt_*(+C1Redrd4$ux4-{BFR`Ux> zcarz|+w_w{_z(4%vH>XY#!CxVJYDaeUR>x?O=v^bzWgmu$x}YDrVq*%e=B*eLnu6vSIy+tDd4_8^B$%6TsI;o zH9{Q6F56dQcUJV%m80e(Yo!|bHLz(`P!DX;j)y#NPURysPJn;2DuY~b>_?RG8s4I% zKbBOb>R%2Tu7HQ*_!Q8_IQb`2g>?P{)&NtfekZo zw#E|YJUfgWZ_#rNi-D05IGZ-=#*IADU|Aj z@H>`D3sfBCZH)wn5F>hoR@02d)UGx@i0D!F@fo1P_&kTZoFl}9W!OA-wAAdzh{VOk zC3%Gp2~IEG>n~=pwSz+qKw7ZHjK%`m7hl>tc6?u| zf7~-jnE6d9rw2qLvfSS2rdQmp2RoxihK-t-m$W!!8b8M=u&KZ+957FkU;CiDu#v?$Lj02d*%8FV9(6Y;bD*` zgL9Zxf|ROitd7MWD&zW|@9v~#kanM#p4297A3e-MKN2x6;l=6`1* zS{P_-D%KW*lD`Oi&P#<2G|-;wKJxr{5mle*FSW2m5&sl0iP(J8z<9PzV=NcHx_*PZ z{+92>t1rUpD_*U~^(CS_<74%vMWhrz5cze^m!5ybfGdp7r7Hj56wCQ699twu_cBCR z53I^wIA2eLSZ?E=;hw@5Zy@f)Njiyq# zCMPE=ZMwFc(9xYhnrbIA8uesP;Z$<39Oa4zxGUe{Hc?`KP{<626axj(=O+W>(Gg*< zNyRH{Q!85S_1`|j8Z`-dA_4ogf>f&CLinr>cd28OnwZ^WpbFI7ObT*1DCJOTf|&a`;6&m)ea}{9HvnjGn%?t#000QnO^(n8J}qzb zFA(q64uT)yPaENIKcpO6kAA{0k!bR3DAPbq6~zt}C*b4MYr931{ZlT!_a`RU6F|ua zHat8k7UlAJnlSzONpSu2(`_}frN!DqH+1yM*2S^&?(Ug>D;&iLDD-V9G^ePUpO!7M zAElAsM{u)_iBb;TSN+gnx36QKD&?Yi2w>Jk<%?|ol0GMTMWi6fr#isn0=h2IX%KWg z+xE=8JKM%nKqlh;X=5E&1Q%|?ckQJPENVAJR`K$Ch{xtVmab3+ ztcY?&H&zT#cFLa=5|I2H0Ct6n>o?6HZ&$ljs3`~NYlW#PkI}P5ZbHkSW;M2^jcTg9 zHtBifbRhJ$c|DmiGObOnhu#~J3opIb@|Ht_+lC@f<=X?bmRe-W{etVIOeVIBWS;H{ zQY}xJ{~D+|L;@zElJEWcv!4OLo03c5XHh=g*U-`FI{46s*`e0(_)-@vA03+aqs1dt zRE{wU9tgMYrK;RHOLb{_FRR!^asR7eVxWBiORGovYh3IM51-T%N2X5+fyT7PwRaS* z`@H^JNO~+^igr!<(M^nF&D@K4-O2as{T=jK9uvI&OLP7(;%KnzWTB_1OfDSf4=Gt; zPzWm%Klso;)wWXKnlKFq8=+^9O`ctePxpWsK05bg4b?;3gmKXoh@K#SBYP@5@!b~g z2`0-lu52!oa^fY&jwqMK(##+geq1yEontic4y{FVG&JnJ;rZls15Z4Z{ZyR*D*YD7 z)cDNo>L1Pr)6O>-+V56te85mTSBK#^J;=SBUi-1hT@~G6owjjfsjAfTMW$I;@BJKV+te0@Iy04HIE)I?H0v$q`aqr^i!d!<7+#V=* z$#7n{A|-~?38khn5#0zwbNLiM?aB^sG_LF{FZE{#-S83DJ|YSch%cQde-|s^A6izx z@6K6U8(hhPIiVmcO*q@5I_97Ir%aPve~$-j^z#)EMCIbQ+Aohh0urz-LA@_(MrVA$ zw6zRDEF|J`dAA+Ax7K5oU>WF5y77`%$WC|6k5(RG_psDd4cdKimJox6k*mt=3c`Bg zk=0{N!x)r9liJeV9y|lX)h4dsP>&|#0Z!F`v5N2EcXvUo_EDV zN>)aWsPDQH02aXs+bJY|DZ-;|Y%yF@9-#w55#gR^!C%2?pO8!6v6}Yt4U33C%#^H{%Sq{w?D#pZCEo_}VOGClgF+Qvu^DG%1g=Z_2ZkmNtG znxh;9Vwh>Iy39-NkC;8Ek=IvNCup(vN1pJ!Cd&bYR1rBk*8sd-?dMZj(=IipX@9ICDlSl@xYWp9r1B?3sBw~3+BcSwpov6nF>H-8_y5M!(5 z>fVrYJuSDnJ5rX!#__ej6L8s-w-`zDQb#TRgZyEmK*%a?*RV#Kb}5}ze@EvJ!~(HOeMDEFrqSjA-mSjcAv`pkfr&(NYb~~|A~i~wKf-y zMlM6X?jLrt_6PrfI)Ut((Z-0RS#|>1_!@FOu8l7@`omdI3VvV8$AKDV=lx`s8lGdT zFeWCI>e*Et3lcRvLB5=WssUJK<$(Aj=m8cpe11~?+GC;$p`DKW%Q1-*TSel*Mbbr8 zYP}Ms52Qs!(x}DbgOpf*o4-~G)ASWT}@esxG488q3FT&$_-!_hHek!`v|`TBR}(hR^@)6qcLCgDcB{>5k}tp zfca;Cu_t8P+h1a`I?=BE2n$@(I8Ts#(ENg?MyUt6;mI=tydc9D%}?}TGWtPcD^2AQCuI>+SQDecCZY5>EFOjA=+qsC5i+PH-H;0`aIvip~w%}{)W z?ltyVkIG;Ty5RRCHVtE|s2(Axc$G*1Px3A_CTHyL(Snj8%79bl0#BF4TC=+OnqpLG2*(Jn z?D}D+UIDJT+JAXyZeK6OyagZ`KiFx+=mXTYjfjH8H39BIZ{l8X24I$&6PvkM0dXwv z-c(t{lVZ_CQ1N(tsSN2K??DWBk51_32C!uU(u>1uySrUKmC?&-;E5BV(KehYN9S@# zz|wx-xi&<4^`S3+-}tTv=Xn3;X;amYZMMhpGwAA?!dvslRJVv-cvFib+Vrp>WsUt~ zf4yr{ci&A*J#~{^U>B+$OTI-Y532u~;_fZInR$NPDtG0b!X@~zlCy_Hw4NtmpI?)m z8A7ytJ*ppQL|sfD59bw2{nPLklip?U>3-}lVa>FZ4WUr?`sqGfFM;9jB@CtAme)lL z&`%rLH$V}x%t3*ELt=vH8|dW*`X>}Kxo8PtKnE8*nM({^RH)Ts07OE)MQ@&eaHaf| z{N>~nk$72P9Hj!yCG6#gXxci>c#Q_3!tC)1_H3xyHtt&tq-+~d?tCXpjT5Nl**AK5 zf|wq|#$UB9P~b$b230jRm+zqbKQI-E+0>N(@1Z?Q$61^cxGtpmU9z6L@Qs6RFZ{uY zl%vCsD#Fj3Y&sobs2(G`lh1Qn0ude#TFrU=4qZuMtO`f^{Bvvw8A3&~g$VWWM4a?t zn4Rjmha#{V?=#zOqN8)OPDSohlI2fx!G2%sZ{H0^i$}a2TgKru=gC$bo~9~Vww|P{ zd#NEMC4>)t`z*h0?YMvCYVCOWlG1Kk+%C()0z@MEU)!D(nIGZ0n|h_d)pL(A~O@;e3PwZC$$QLji`hA`%}A zw{EV!xE^e;TjmKXJX}N9BGeb+o}yq7iljwZS$Alo3xQg6en*d@OeD)eb~1#qxDDBX zsDqLKQDpJ`OPGkjxs}Zk<0B}pOIYo3I;G9IOyk<`Xr$i+of}(r#+v&Rq4*scrxo{9 zi~hZju%qy+9J^Yz@}U)X<<2x)58F;7O05*>rc3V6ryoY?8WGE4`>U#-O*%pcFCf=H zTtrUkb)M(POMNpjP3Hbw5PNA^q^kOJPqweT1UMaly`Lqk`&|_Q7MHOUxXZ+#;iY9L zOAxO3GwL8*yj>V$G5a;}X@i$GUpwhuLa7NjtfHEPKrM^F@o-+omM!aAvQ@B&$ z%-4b{PD0^L9kAv}0DGSGKB(rjc-rlP4_0WeYdF1=&}+mx17pKyE8bQoR!#FSwxY&j zULTUKD*yg=^F`Fygw@1^ zxyqic9JvO*bTzLtot5?zW?T8MI`HDkQ*jK&B1i918g6p90~A*i!#XMHODToef$F&U zTqAP;UWxi$HdGyoPHpkYb?#P-{)tQub3 zP&kfYsaP!S+MI+HagXV$ajZDy4PvSK+reFX?FCM;;}IoH1CVT*QcqX|tRVTFyjzJ% zq()C_a0+n{6q2sdzMBr!Oi!8FoyJU>u?3@nf^j*dn?c3CzP|ME$*t5UMgMwIU^a+9 zW0xy}xEsS@bZxA#0~Y4IszZd^WbNelg~JiPgT1|;A`UiPh1$(aB-qUMkO)^Gt#rx9 zsZy0mJz#6h6R!0q!9t>;C>ovCc!DZ#(Q~P{cZb{2N4ZP`I}r+-NgI8paei5;xU zVej(+r^JgnMnu%&CXS;1JzueXk|he$7Y#a5w~7{6ArjyO48rEHC*7gya1EasKE+-u z{y83PJszb|tMtko<>_q4bFM?ZiT$FeVF=a*17_dcRfd<$$yA$py#mSdi0N)!TGp%x z84OFR?(1gViNZRL+MSEqLWOF5;0uVSG6`Imm<6 z%J?XQ)de?>K}j%mP;WI80HCU}sOjl_G1sy`j|5*oK znxnWdG`aVj7DCGbu&XM zWpWZ&eA$^*snBR*k;8^v{}QyIVN?3r)rLNPABUY!Y`tX|yF~ZXMSp zAhm;6+P20I2f=s*o94mIh$lrgY37~n5^Vm|L(#rjdtr|(VwWD{6QE;s z-WeL6;gTyGsi0l@-&HabQ##E7a14IIG=YSC&97go89pZ;6!|vrzj69$m}?7O zt;c;!NGQ-NXlzXC>Jl3m9Hf8y^??E-#ui|}d3oOgUiZ%wPjZ7op{op%bz78O(2~r` zRZdvi#8=Xs++tH#NR{Yh84F6QjT%oDhYl7iIZB}{%!;dZw(xpN%XTSp1Pmbv{tA7O z^oZ)juuVJHH}1oG#+Of?$j2EaL=SrLgIOgN=-#`<&vKimD|W&stWM`?Bjyx?Cw#$C z3*4Redxx6-FenKdiS}Ml?iwfou+3d;9j1FzJRmQOmhOA9SKK(5pA)>UU`1^qz(bx+ z4=O&1I$%QVD_-s@tt7IF&%U_4gczA39bS^!-QLV>lq}&W`4E>9EgSkj74gBm{>ZU} zIeqt-lhvsk)%3j?nWf~Tmce1LR-GFmaLsTi>8>Z(ZsllHrXP@2DCLsGFA z;{Iq)ZPDLk!i%%*{2O~$afiOccn5yI7TnnAOB;C2$_N_FiHSKBu!CYKH7q3w&oKbm zyr0lY$^Sh1v-arxbkq>bdZcQD<~@ob#BgbU!WHJu@a>{6s=>)sqjdV|O#E?L^9}L7 zdX`!by3V4hyY7X>3+3w)&9dcfXTMzje`^6;){;m zkw`T1HG&8j4jrK?@Cs+BimgDuVFMFkQ8V?PDC;-Po@9@rs+X{WLfCQ=%a&K^!IuiF z;Mbrs_CxcQxv11O{ukuNm$^Lwr@kJ6r{Uj&Yub-#tAfuw=Wp(^KhS=(HknDaxe={sDWA;<&z9+*gUDQ_YoTDF-P{0(fVb0_0PmaKaZB)qC*`;PX&FwX-f^sbe^hd$Z zF^?Tf6)GR@ze6<=HO1hM1BDLRc?~h_Q~PT)qmG+vWR~r=tzGJ~L)2Nv!hB_SIjvoW@LO)2UgEN$&j`YuL5+&y2OFi#$pfnC8Mg;M9$ny;u(VKg6Q<59vrt=PWY=YDEIK--bOvl;Q%AoLC?~b(ncwFxYxD-!R-M~ z6u+V6*l-t5>7&>xQb&<)ye3ndgEc|{4F@(78IJ@-#XGlmu%fjOm};m{uy=WNe@L;g zdAm^^(@J~aja~U|U~ezlK|JIWw@{>_*7%}@C)_>ocuvu6URm&vuW9t^mtVbX9k^o|z=Pj!03ABxFG>NjR-Y&&ddpFuVQl z2%~DUwyZBt#T#An|0m&+Z)h%Tz~e0sBFz;!L`21IxF(baNGWSwq&C{X*AQ^F%)n63=-QiSs)8*r6A z-0ZQW?z^dib?J}DTp*!GQBmQ6)fvm%%|MxRAlm6{z$#=&RhHp5K-7HQff{b?2rf)H zbML6k8MB8gz7>p}b!p?7-ODrGR~XGGL*}MSru9ccF8H7|yze91%u0QdRZ$TQ6cxRo z+;W|bA!!Aeeivp62}nmSfIou%H0w7x?+y5P>mhKk1E-g4MUAdN=TTH~KzpFkbE*(Z z-e)=_OpgAPBZ2w-;tPV$CVQ~tvP}+0N(ujyz?#f~Kp;K>zWC5CUct?K(p)MJ)wC)L zp*e*_1#5qePSOTdxh1IS)8WS1qD9{-uOj=F$*%<}>Bfvp2n9l-Oo8);M%xx?_;kT5 zLxSRR*B*5q$zf?On^kvP0fMJc@Kal(Y5vp`gVfKCgcmCqApLvgIyx(tjhLYlP>q{i zZXy?uE*d1I%KB{E^e!BRoQGHNRs7is zuJITpMuz5%G*zL%1CL7eF=BSc^dhu-(eE8*=)~-jo%z$Dv=N(;OZ1(YMYfhhT3sh2VcxQh!n-_j?9%%?g7LmOs%+Un!}Xo)=GVP7W?-XLRw$KDx2Y>Kl+wzkAs1n-yJHxH%hY$PYgQ{0 z#A=o_-`FpiZN5=Ye{ZtQAM?GF3tn-Q%rp_;*?Jxu++A)L(j)YW`ygSsH{`hoU$Xq; z)$dvE4d%IU?z#dJ4-#7J;4Rth7Sn!gKKnnZC#2*`PSoi^0uDd^3v>q_^PFac! zpTrO?w7R3a@I7u5zr3>km2+X$U^z;OO)2=^-~Zt| z1_m{4S#@)IDfTYMEtKTvVjXd?2J{ zrL{*2n!vI>NV#M)Iky-_+iy;5m>pD)&&Zc6p4}SCU>@yRx+#XLEqrwWrsCYl`l(zY zjgtYxGN}FfXf)WYYZs_&HCS(Sk+xcN+^SzZ)_hodF4It~fqV26xj?Ec|GR!jacK9w zV?%$n*GM&=huQa**7-Egkv(~IC%h7s#})yikbuLG!wN{ z*>3L>81mK|x`{_pSI4 znt;b)USVPA+}vE=#ULNOgw6(l=L2XoEt_?fh&v9{89-l_Rr^ z^FKN;6Q9>*N`<|mtqa+xbE9;aa-gNQYivnBwJ6LyC#;ZO<(ffCnyvb6aVpiU^ zn{ocpv&xBsxibSUbAg>mUnxK{Bq=w=c3rywRDMl0B=; zYP~AiT4Y`osQCMLJmC^wpY<&B+DOAU@qRyO_jg{flfBkR{{xjQEKm?-AX`Bw#TIH9 ztqGumS~Zjh1%tG1%03lwW*#;$PuczVvD>TJ~L!k^n58+k&(}sNoi&lookyrv?!UMh) zB*9?8*2Z0SO(!KMgQO6C3dI;UQP3!=UzcH6199 z<>yZ}?r5m1rO-m@8~0d-L_15Q>yRJq=gWTdlW zMifyHQAt5S3_y_XMi5atX6RJ9Yv>dSK|nyHyJzScV(5~V7;1o_8-{L%_v7PpzUTbj zx#ln6V&@%ut#$AHtn8y|_So;=91J1~!8(BizhN34a7OhE#US$GQrz|arh`Fwg={)SWJ&D9F!l>i&BLBB28+}e?0cI`MEmZWc$jdPtTE;cpZ*6!1kw&YUvXKsJ; zoXk#gDL8tCkq6jg&wPhP+5e6)-U3*Ud?<9k_~huQLoY3)iJ&UWSWqEqMxO<(-{80b z&Tkw;EYiw^GJ`PKFP5MakM~YLUCmI-&~Qs2@8N0Rw5Tl5i}6U?**oN!0wLlj#Q*>+ zLptov&A?vf0{7yyMbo*pD93b>3~jRHu_g}fszf($5!>YgaX**UoO4Xt*X-Dm2Qp~` zo%hx4?w5_;_bBq}vReO(65F62josl4_$B!2-|YLNNP+e-U=${x@Qt*t3QCu=u@TyY{c0f zO>gv5`CfqV$XpeCu0?rw9Xp=&;8UpZl}AqL=Qea;-uBFtVC~78tIuTG43UEAiCGzk z`e21Aasf{H?YmRlT=M-go-=!^l37ay8Q%F1mW^9$?!giZgg$%j_1-)vTiR20DR10DA805OrTms5NY1{ zs}6mccxz=d6VKc3QImgaYzviaK|CYadVY_Nb8$!G2kr{lI@hN+{{-thZ=|Gd!qkiY zS$Fq&3kGB!n=hGViT*k`{T!yu_$d=Q{MPb)$Aq~XGN;>|KD>2BlKm|nqoxhoxNNI# zx-n;afSaa>S%JL|x~=MV3bU{2%XKr~$8?bredfx3P^{ms)@!ZkW+;Y?x+Cj*9j{d? z6Oel!$3VxJrBS+^I`>=(xnTvy@a0vNNMA67A(OzC!bl4uikK=la>*y&m71ECovmt= zI^oQi!MpTt2Pj1@Q(}`FP4J`I(RSNyhqD(7VrpiXNkTo&k+;e zByqe={)sVA!S!soQ127_xH7l-xHO});p?swx&v>Ik?DS$)wF>)-xKD2mX!GV;EoY436PoOgE76*!MO(Z(c%GjEOad_-|}| zNhUK|rM#_gAn!Kx%tNCv-D&S*YiM-k=L7Rt0V`f}twNf|M%%yc6a}@U6_=Ni)nJ}X zjM}P@Q5t0R0CQ-1O;FvV6(Dm#W)8?aEe#juEIv z6uzrhl9K*06Q*vDSogY`WawD5hrQY>ijbddZ_^HVf{Zt5+y(1LL~;FFv81J))sXib|`9YrhIjcsJ0k>zF!D!hV6L zXW%I;-T6k}XO|DVPNJb)e&r&jZE}?u^i5&_XYdiKyeAV z@Y@rI;`YQ%ZrIWa2&z-8JUC4c>wtAKVu6c#;g_(74WstxypA#lo3E!k@)GUl<{Na% zwkgiGDcI-u{cWZXGb};US=sU(6E~-*`SvdA+2@JMh%H&PIZdG9h}VDJQhbtX)z(be zCmHqX60|2vXX2k6?gL;(Bc1#y)rhaX)RY$e3P^ZFP?4=PbZogWMu38sM)XY*Gu||x zkp?X%;uv8YHqpLY38W%3V#lX4WT_&e+ij1ZYv1pP4Bxr_(go5NnaRw*mj|t?iJyfs z|5#09EM)qV)XjOP^e4-X4VCDFt+pa6Yf!^VL zG4Bo7^hFz;q4)f%?p`CmQ16f8B`E{#b(=wt`N7Mb63j9SS}X#iJJW*ZOMc@`uV_g4 z;j<3s$S=VJxq-7hGPd-}%5P_~kI7c~4kGZxR|*;)7LHF&n3KlQN-bwfJFp5`k96iH z^N$CfnV1pNLG^=7uTsRX+1ktUno>1vs8Q8!+w(SFtNy&YGuVf-m2dHS1dc=va*s-` zBg5=A7w8%%`!YW^hnAPV&$7>`U}tsl3YbVA%tJUn47+TK>UL-OXOY^IdGvc{t%u;k zH<$&$`Mgq!9Ge4@RT~?eo9dllSgsUNfdyXXtb_6IV|adTh`A0aw|Sgj{FeW!YYNo~YW7>p8G`|0kZHlX1Ef?{IDV=ee27aQe%|aSyuIdn~Nq z`YA5A_BHNw>2AGydPTC6n789JSJvxum+Ah2+{lBHqgceqC8H4SH7U#BYbqkeml7#^ zOUZpX?ZCC$yCv6M*EAwA#L1dZgq0$8dq#-&C6+mv{K`v%V)JNaGHgDf4$SN30=CY< z_=ArUZ*#gBycTyO z+!Eeh-=|E3OycDFq7Pa^pBOe(#V@~ng$*f9UA^9!>=tC@S5^T@N*!<*th;?CGHd+0 zFfD$IK7#53n-@!r(G3wC?NVc>=@qv=W5d8yKGAqb?84FLPGT1_Tn@YCm(%te4vHQ8 z%5GDFUg?X>LN31F&Xi`PP7y?2k``^DIGS&R^!=oB`XVo=-)9&b37*eiJ$X`{;dUu* zTXZ#ZxfNWZoQq>Ah_NWjEA~1UhcNz~?q89>y~sb=^r$FO6(M5)rtWEH;wB}^QB6=) zVcd}oRi2ShLkl@bn=J^fgEH#qVUKwlylXO`)Y(w_SeLo%O=sNPSQn%@*VwvQ#=V`$ zz)~fXO545ftvD|G%%hr`(8Dg=&9>l%dH^QM4CLc*skXAo!wuiduors70-AXWNuSEi zrML@rdZBeHw39sc1v*isar0Yq8Uk-&M~SS{RQ2H|cw~wkSuLy9b*oDtVv;9DrPrdJ7y=#=S~FDt0ly7uew3&%3$GKcam5K z9PJ`#AnJ>E&~Q9;U{SY)K7*gU-n(+&uxcn`&)T~ptS!7ECKcazoju7>W7;VF)XVf* zAon&cdhkYXt}cz<^;|QIk}ytLd&w&@299)LgUN~aRKa~xxxD~iWc4@dht$&3v3kY~ z9g9R)5>&k^PXf+C%}Y?_A_>#&cQZIVG@b8m@@9X;d!1>cQs@^*r8)#(o86uRWr-1A zlHSShMxE#86h5jid}LK1{i*ANW*%|+y&Zgs$qV^?2s2AVScen=JA0%uid=dR9Iu#- z;6L)NN+A$tuS}2nCJ7SfSDu+%x>ZJI^s-op7ZnRFA*FEGnl~qhGd+d;PEf(w0FP+< zc?v?n+dnQ}9TNwPebK6#9GkkevuF-Z_Fnmd;q1^G@UQ7ws!xUpy2%%`9)Z!N1=~Db zx~b6iE4-ZmsGmZ!bM0({YX8jZU@ z`BffW)Y@*H5u#3#-yKj#O6%o2ssnd$xS^k0=lk}W2PT<(EFka}-dUM<)omeW_vR+V z`Q{|JS0O&v*u`&e+R!HYk*GI@AAHxLqf?Q~Q)^VYVAy?5R#QSSkG^G3nN-1LJ+=hqo z3p%HguMK14{Qm-lPO=}}5_^9(bf3bMXK={UJJ<3wO4^~YL32;-_q}fSEuoM;zk`)( z9j%R^EX(&frM15coM$q-!1b2&M4z(e``H+%z>^>0Q(SXWDze1FQ;qBx!bIE zdr`y5`^c0{`$(wLJ94*z6}^C=Ylu1-wV3EBOFk$Vbm;2hbI?OVyr5+ffkS4eSK;Wz zKw^ExqZ#45UTbOY7mvGyW1U=Br7(^DV;8im+-5&;$?^3kHB~z@A6XPc zvCAfI%K>pFc4!q@ZF87-P_s3hwmW2Z&5psAKwh(#KK4wNc(cBjthpkcoX=RefG~VG z6!a8=x6AM8oFtuR&`g1b+!)updd}Rq@1w{XHavp$E}WI4m25hib3t~<#&*HixmhL(n%fg1}9{(q-MKZhNU!)^G=p}=2W5ouy{ zTcM{Tbt zSat1QH(oRP>_^7!UL}Q{9>c}@1*ttK#r71u3}^Ujm(|{o7vK;O4xGL~*V~Bk`)qQ} zp4FO#Jn>~%)jK3B*1Wu>A?8I+ce(mW1{J|fD9C!Ms9(P!MvJzm-K7$5+Ir%%Gi%_* zJbtz3(`X-bIYHs{gDZ_&%teq6i|IW*sdfVVT5J44yQsMMijI1|o^?{|S@OsnpgH{3ASI$SVOO=I@oCtMY5_aL?T;v~^3gG_Va3 zn&x|=5x(K!c~1P*-!h52ZQZ*SSuFNghqsJ(l@lpe7wOM!&8+`b(s|*yVI6vhIFgHly3{8TyGxFV4?_>x5Cxbc%{5+#*F#Xl70hUc5G*m2+D-fP#%uUKLV1 zRu92696bvOs&;eP)3@DU6xk%)Ajv|e=hyzKzpwZ{QB!Y&SdL^|F1T#yuHlSJqlB)U z!L>e_BIAFw0FD4xiq7+B{S_gOsJm~hs%ISkb9DNHecRT(F0!$p z51()57^-ISqlmZE)7JG%ux$7iAx!==@y!UK%FJ0F_5uKEEJ01*p}E$Z!Vh5i$)Ta8 ztrAt+xALW5DuX^NSXW!}eC8SzU*8zz#wbs^XGpt4j{jKapUkAxDn-GD@ySW+n)keB zmF0v6(Gyusajjn)O?scz>EDV0X50ScnNj$Iv*&<-#b$B*7d-0Ve+p{ThX`+H3ee8S8Y9wtS zc#&NtYv@_>-G+g4TPt+?1MuT%Vvw=(>uyqFW`uK4|NOpY2!Y~D=5KeEW_tSNM_rh= zw9V9fJx%F142cAjGPF_appIjnsY?tiLzj30wys-Joszmz(rdy44JPL;TP-elj`aap zt=E7c@4qD1gJ->_9&Q^wE@T_o5k_Gn zKa?0#w#65oa6gMqyn+DUb@&L4(oi}{1bLH}n=Dygw*aeG%2;hJ!COXHwc7kH4YM#C zeEsg!sEf(T>2&GQn4N@@vOfa=#V($GUb@)Bhkhk1{(2&J%KQcAk4jK2drBeXGKv61 zZ%QkO{>O#9ZRFwMDYZm0W6nVP8I$wQaVt{s!4A&M*JyX%Zanzyg!WTZXF5 zr=Nh~`=j>+4m5&MA8kI{g|VhT&^X#4R+R(C{`Dn;;tI@E8B6OvF5XKI7_p|IDA^X9 zB-BW}JDycBAh-cGHSxu|>e}6i>yuRKn$`&djraP?8}O^h+Y}|Q(izQ-@K^_GUA9iR zIo)EPs)uC#Q497xBqJl!{27?Zr1{EJ_zr!!6d3%v7kE|#Qcowy82GEic|h(jjPE^t zmR`{^M4DO$B-M{<~VAjG!)= zx8+hUzNtUA^|t>!Iy`<`tHpfnr^Wq}JUcUjj!7UhvKp-L~(@tAcRbl@A{_A2- z=uN9aLkVQ%!SeD zbD$a_mh0&qxjs8B%HRjE3YVI$Q+5~PJl`XdMb5FV+r1s8fe+LwttZRZ#ct7mi3G;| z7ck}&ezHCPO2Eb|m|x&PQCRlp2Le}l6f_jmWOBvoL4 z;N#%ZuWz8d=0>bfifRsm%cP_();B#PZsH$b@THS*C|H9b^*6il@|GKveLXkq4b!Iz zo}@ql?`=rwqHpf7LQ`APC*M(|E9~`%R5bSDxS@88r1F3qps}V#ixc#K9XrBW$mGoP zM(F`Y>gIZUV_N3Fz5UCq{;;yJ_)4e*w?Vm#2Ik>RrOGIuY~k*jrr{P+PrU);Wtj8b zAk4?)dNKa42gAw$2W4nYJuP3I0kO~*M$511KnRiuZz$I%!v~7eJ7D~XzTy+i)9kAV z##A>BF_G}Q7F3Z1%rpv$erNAVo{Z#_pKHegA?9FAeH`uMBm{(9K|5}OGb=P<7P3;Z zk4!W?#%@w1#^n6X9l_22b;=(f{fCCJLsf@2Ha1#_WEKozXi}U!JPRT05^Bb-x*?W@ zT4@yzkSTIPIX3O42~^bF=m_#*%Ga3HX8#*5-Wh=I+jp*@WP7Rkw-3Oof3248vIgYN zfa>rM4Wfa1f@t#lEKInzIdaE>%1HWy;Kid~9-e5R!;kZ;ALkGFh9pMrk|slcdnMWc zuwndrF<7w~bAmsRxBhol9|L63N8sTEeYdIcaT!f7f z@zjy&GZj^l(lC6D6kGNEb7+}eEe4#je2fdIiUCWZt>5Z#2?RK&)?x_X5xmPzSZDil zj6>T9;#PjR%fJeE=Qd+}n#2T9A?h?Ff93c24_x!#p1)1}NB61(Bw-QfJ!;|r*#XEr zgk*nujwd~<*W%}yN}bTGNL>q}uJFC5l`jc_b0;J~)tiB^-9aE=^SVF%1EB2&4sex} z_amw)0d+laFefYJ7+0M3aC@&Z0fUOdip^uOKu@;-n%wQhRXnGXO1xES6Z!4HZ!&ucx`tv|;pq5?pj>CplmvV0&&3M4=cR~}wp4oQ$S{eKp@{njHEC09W8GB7M7ZZr7&hwj4{b@T541rLrbyHz^pzO(*HW}S`K z%mXJ`)YJw{a)x_vAE;O{=Pku02f7L5%}$^hL*#_H;cbP=;-RO5_Yx^tQaHeOS@QLm z)ql6P796Y9s}6nwpD40rJHb?DN<7CR(!Y>Z))TlrVNy$J9!h}=& z&LYQG*p2%%F7(ZO`Kqj5n3L{he|EL~#UxRcciIN}XP!f{0xx&|g4DX$guLd$A`yk$ zwcK8g0X+a>{>2|*}NNz_;%NVL{a}z z$E-`PhW~7lA%Gk=Yg3D(4vL`29HYFNEd+h)_vkZWc~!SwUa-yoC%I7)H6Q&aCj5Tn zd*O!6C80&D&%oXR*@4z>0N$>~s@TiI^uSN3yMhMO%E$)mTQWM=+D3#wxeAn#HYB?C zW;c3Bb&k(hVGIM>GfBoxTVO%wrcSGki8;ufKn>DZ<=2IJiSxlA7|BmN^wOpG&yqQ4 z-cXN~fCvRp$Z&XT8M9RoPgE3VRsTb?cjK~hA+@mb=4e#ZL*V6-Z#F2V(9hAG>6U*j zGlH)gz`Xf_iRny@jg0|)_&>`ep9Mgtz_TpNdT8KL7@*=}#O>_}qgDvj7{w5!dm>d< z8t{dkT>V7#Qmr9b%Kouk>3IbM3Dm)_?Bjxeaw095Bw)MVu=9Ks%jO_}WMDBAB+Gt$ zEAK19ay0z*3b87kRkmiwjL*WSs8G?og%kPo2pr0EnTi`R-=U^Y z?sRRlch`x&5w@$)JFuu0W8=KYxl)7dEp%+5;F0fNeEyk3=l0k9``!Yt*C#RnZ=t8| zNd2WNM_zD>Z13!(a?Y3-mm_giznL!{;JSGzOdjFS3aNaI{pndAdm@C3P&qw?H!RPnz=+R=AR$i91N*unM z49D7@z%3NF`wHQ>igAxQRO4oPedFW?%gadLtJ zH5|W3)zFvb3ZwWwDq(JZz+LPPg4-%TQBOX)nzv_?)>$pM)gjqO8gqAlb)6!2h0gJIpqIT|HWn)V9uO z{nyk(_NU-hSzT$U__wN`+5?D@xe$1xo=qOOXrovh$=77sEWcSsMoz}%6o zZ^ei>!eS0;o17JRnfOS}46ybBKeAeD^Mw}h+D!ewW@vwag~W7=Ab4vk(whlG)dE}B zsqC(eq+b>?eF2|%T%NqpiY*hUTWTr>NZJ2}5K|x`Gv8Gj`97cvy55c}==-|$9z`& zxw``>G-x+Mz9?iCp(6|!xf|Gp%Dq*;9)kn^-;Ub1j{N*dj;Z^Sw~^!02zmV!=wNDjK1RvX{Gw`lBOvTQNd#MIugDHWHCUIj)}9#x-6UuNyOi9mS3!V z3C==F+-3QseOdPg>RIn8$O$^a^tKl~1D`-0;7Z0q+9#48+nyEORwu9DM&yt@3I-vm zixObU6Ggydx#>7kWs@)_MEnB+#w4<2^Gu0Ta{_ySYWv^t_q}K2!*4h`w9bqIpmk?; zN3F;kA|X=3`JCq|zKyl{>UyF>MEscm>kDL;!&AZJ!yFu)MUqGOd4QCu=q&eKJuh?^ zP*KEHu*O)9f`HngsH*1%6C;ki__u>p#sRTU?ORy`+G;EigX}9N}1o(=OG>lbym9rw;#!1MixYwrS zi8|Tn3xD8T_@@Z$zgwgoI2sL0g27}sfZKYMY6^IyJKC+fqkyL}|0a@BnNtGR7~Bo= z01l`M^*MIse=HVYANtbQSz{~&3haP?h*Vx_F=d#xK_U4V*5S_qD^>rUIXCdRrg>No zO=Nb1J^ctxyhooO)cI>F>h8&AP!4t%$*U^r;(aYP-K*aG8T~D&`fC^4yAK_(2NBLF zKC?$FvtVTj5Y4d`Q|?W>HkfA{0ML>_d@FkAe2@(cu14tC`bVW!F%{Y{(V!2 zxsYicXJALavS#b^4xxIsZTY9e8YmKV0*0Uhm#XlG&edrG*Py#BAK-DXnILB6=cpSO zFRhk04b+JWX75eOpS8U`x!AhB%;7={B`Zbv7F5UF14QoTNxP#$eU8 zIbaM~&9S6sWdlLX>Y0s9oFlB>AFyrS6bfv5mAo5IBBkW3yfGVBBVV3AYR=nvD;H~% zQ-Nu}P{nJGl8SPG3v2CcqI~a>hz51r(%U|Es2IJ=!#`b{-$va?C_rzi zY0wVTl(0I64-FzOe0sM{hyb+%4uD_+UrMX7EVL&KPScdRlIgITt{4c2QS)mnoFjs76Z|BB4Urt>;nn>HKQ*u(>+uCqs9vq{>+ zDZbQ!tGlbYk>A;Ax|tyr4QMaWA(S48QWCmI>fv0jSl+j`@Dxpn&5dyvWdRV|bp_*p z*SJprINB{Z(|!Ik{`Ty%)reX9HX`>K*Ye%Uk`nfkE)Ft-vmOncwVj=T4aC^+@FzsC zi3yp*IPsGSB?Gk6W1B&73Npi)-}f!Q`CvSNaA;Vm${XcVLegpJN!xASRB+ma>DG6` zHnXYaEa&_H|1d$MQcKho*V%uA@hM-^wBJkAcbg}! z8Fr6&9{f!IyWr#5MTM*$q^Q_Qb-Q|(K4nq>NAJWM=sf2jS)NofhlF(5V}-q)Zq@oO zPRH~!K(6y&Hyk3E1B4585*`*OX*4W(&GHW>0zBH8rPI16SL)?;Qds%3RpS(L-TwT^WW}ajA^W}gX9)dvg z`ies+fOmwibxwp~`yr9H@`>adZVsw!0I#(o-XI2F4c3y-(E(JvxAk_)o(HG zi~~bl+Zb4YDCG7)m>H(V2MNJY}`xm-L; zpcF+05y;D=Fl`{7sBj5UlTni7o(GIN1AUe=ax&5-9M^RO5=gTji8r{-ibAg*wSnrV zI`2dT6#!Yf_0Hf-o_O;iKI|Q=#olnj$_y4XiU^tnk`q(Nd87lP85yg2ww^|}POP{1 z8L7EuSxH68rzFCzekV#i;p(tLA>tl&It8a4pSN2x-`6b+qqc50=gX1n=04G;g$-Zd zgcI*iH_c*~bHM@sV_8m7C@xA<8MpIJ{?r?<`?{-xgN_f{Nr+8NbiV#gtBz!aAHO~zcv>L@x=w6x;SI1 zgk-#CtbsG$jJIJsPgINK4kW?v^@O2wprK2}RXYFP;xi@U*iz_wb z1q0@EI#kI!ER`qOSxVOrh^(_-qh5|MC7H1Z!%8ZWf!RI={&t|Y2}m7OxSGBIE<)eU z@^*?JuOpKr0KWsZzZ3BdpZZMV*Kc=f|4OKW*&$zwkbS(}^HhRnzLw^M!+zt{R_*GI zR*S1A<$}9gm@^|8x}k1bqk#!T^`?y14tG=D$F>xa-O&RP$ThJ*le4(gbG3`KsH$rR zpX0Ws-OyX<|6_c8l-Sz5ikBjy_J)2L8Qt)4h1?R1*7)#cRb9YgLRQnrc>DbqfcyOtoSP&=Y8kJ{ z8=nsjd!NvYomR1gRL-_X%tk81<=bd43Hc3t*%^J#Hxc#PfzN$Ep^&bbMHjbQn$Ydy z*W>r~edh6s8!z>tNlm}Riv<1W8`*q34wTFut(RwZBcvZQ-N}TK!y}nGlm+Xp%dF2t}xq~H{xjx~)9VwbrWiZiPucYng zxMXKt?;>o15e%F)nCVDULj1sZ`@D>5y5zrhN6l=7zFtm_^iB+$t^Ia(ELVBG8d=JI z^(wAum53A6jT#T=XcR!{Dg5j%@a)`8=6&@Qy-*v<{r9cZ2R zv7e=FD`llsrIvVAC*=6rEuQ;cy^2J5efPbdf?a;>2(DSkO40Y zo?FQvlzA!sd|Z1YYmUZ+ z-8*nMV`XYCC`weSHR-*4h1oS4V&wSrdd(EQqZN{TS}NXIqg@U9^O~^2hfd~@yH>bR$j-^1H3*U^CbtM%sc>V845cu(23!K(0fiNu+sdXvrLAIY*K_~PyO zH<3SH2o^`-H@2Pk3JI=UX_TI^U`$%**q39_z9Fw%i2tW{PVxmOHB3nl|Nd5*BiY99 z-&jOYo{#PK4fPxbt36M^KWQXv#3_au_?lSeR(^j6R9d{-90lImyO9^oJF?5Or|GB_ zzA+${!c=oOHOK(+sf%=gawWV;3~ds%Ehlf57$$F)yfZIbfs34*+^L^DDP|FeSQCi6UvB~sWvo1OovP?=V76?aNZG)H@2B(jo@AzEhTpHQzeXNqheu;Kx0i%s+RzV3_~Gp;x6V9IkuT~3n$u(M-PrTrbHG#qop{DH>7 zQDkz&07r5~!r->gje`ceh5kGZHC4*x%8J(V31iIiMOJ#r!Js=yIyT-nRsVnHdyTj?4b3$_Qi+lPy zsY`%kU$pUX+SjOQtgR*3Wu#&CQ}T~)pw6icfjD`57z5ROav@mwJz~XUb{!-TTVOaQNWbC6>SJ`tfuzf> zdp7QxGqa%aZ%OXReDzkp>92K1xEWqi&1Ot26k^xeMM^c3S~m1_f8-8uEZ$!2n~3*1 zwqQHc!6Bso!cv5D^sD0J0Hwh;XNA51-haWL2sW=-AGvhta`L(qAtJgt(tBmC`p!?5 z-Xx6t)6qTq-$9ail!6l1a?EnftOpUWwkT)1&U$%U> zAK`g@js47y)bpq30T*q{nVR%bXz5#cH=@{#-&;)a=)`n$aj#xt%3JWx**}i-R1L>xC64pequV zTc!vOvthRzg*qsJA`er(=iGiA-IpQOkWNvMGxj}*+}#J~?zs#;(o5YRNJDRq z(4>{j7o=P?e{!UAvsO7!bq)M@psF^xnp1aQgsOfP+x6&z1a)5|H)Y!{H*ubATiEaW>Are-_SB0{)K5 zpw-D5uNeXa33`#BeO7mHn1d3kye={`R~Rw6I{SK)N>i`MY^O%S^+_!DO|)@-?);1O z-G@gJ5zy)VwI2uQVm0)>_tj~%8suz@K=k^6ZmnzOW!=2V5!VYFkpr*5V#Eiy&E@wg zrTq=*yp-oB6pi^hx^Zh`;mgDA=^l|t3x!Wrg;8xDhx|=Ql0{kc@mRyVRo&stq^5(L zqBY9|RfYTc*OQFArH=J{V?hsmRJuQ}i`qS{Tc@NuD!L+?1`RKZ{@SgBsw z&R|dMs!K^97K5&Qvx43kJ;7+_^)^;WFH@x)?QvPgS)`odA039jTH*$$o-@^tuO-X5 zY^-3g?@!VoRRhO#;{oEAQTKK2V+X{#U#8f1!}2p#O#~%S*^yb>J%0Ui zPysS?XcLY;E=6cGeY8Xw|AIE&jQ(M6Qvbt$$(mdzoT>!4*{mHgN{#sXI4dJcd7@z=g`>>6T8}tPL08wFWyU_n9a0nb^OPD z-=XVjH2C!@KlJzKt;NzcN%;zKG0O#6Dtf|gYl{@>HhtH4QPpcE6uz=ec8$6=sLds) zsGf$;RfYD+CJSV&GhFE6irBI@++avNRh`!?dtKkvzu4>GhMs39vyJz-lC%BPv^5;J zUOdYV>)q6NIn}S-a0WToUQ_j6jG?fMm2)ieDZsMrs$KQk5VI^T5#IW1PU%ZTL`N3( z_B-m0N+NsqZ-Vj)KC=2WWkDlTlgvA)U4PZfUqBUyt}UmF(CRj_eQ&E!WFGIvPiABC zwIQvqec_|tb*S{S9jQY~Iai%&SorSjjk{`k6;- z{KJ%ZCJmb^##iyYT}o?jD^(kriFxyZX^J1(K*F3FfEn|{v$C>MGb}fD#LPCxdF*^F z5u2$ni+u5l@*cFIL9}dU)#`UaUTVUzSU`aHd9MNOK+n13%NYcy-u0f#z~i5tI#*LV zSg}dQs$LZi zs>DDYKG703FFnm6rz|el_=Cha0-S`U{J;{D;!tg5UrmK>Il zAu*$zDy?V5iC8Ii!xWL4QNEEdu&OF;v+YH})Lqn5cV0WbT=bK@f72g^P=^rKF#p{W zI4@h(K1frf4lw8kYHN&tuWTS~RkPS}F9=5TKDx1C2jhELbs8RqQM#|K7I87Q>1@7D zZ&Av9Jb4|$e2wm)+L~l?mp^*DQr!7fBWnt#+RxL~&u`9~%Dv=1z`bfcDqp=5n;qIi zAalbK!9|9%-yMzjXO{nbz7qqIfk(jGBSMZf(bIQspD^O(2LjT|GS$_bcl_2d>WWp7 zGa8W4V{l4zd>mDrm_&;0c1BgSgRWItQ7pEarMk?+Ysz7d<0ym`wEeX%=D5Gp;x|>? z9k9&Htb@`%o0({jXy#8vMZq~F(VKVUUiYlEh?`oH`i37K{9i)^ptO$}3pb)fnf7P-uWBYgt0Tt+>(rInd0FG- ziL^=HtmDG8Mm|ilkG^p4!wW1OJ_IhAKl&!y5WEWi#j_RL6eh^9BWSl6oyxA090bpy z+<&zDjN}P^eunbBX$6m+(lRjYl^n(ptA|pgUQMu}j|F zbUy4ufS)S?y)A3c2~Q~B|X;KOj}GD~Hqhi;-9n?v%lLBbISSCYpwws7@x zv*|RpTh3Hp2G}|J3%%~UrQ9ycd9*8gMzTLZzBE8SJK!OXi+Z^%AaUd-0t_#De6xSa z18Bn!VMrMynW0=9_h%09|EO`qq!n-B`nPX~C-E_0g=v!q*y`ukbr0kt`%1+DrNf9* zg!=iB0n zVRTB?aP^OyI$bxIZ9IXtlr2wbC~yxPA z;KYLMFFBfW^V!!f6Z$pZUqd`+KHhOVcsU)*^>BB^z;k6%a>n|0Eq7qKlg1QVV_zin}y&Hxjg&M^T~0{lk4SjXqrChw_;1tMvM6P<;1hOg4T zd6pO1Kf=EuWtpGI7NW46i1_Jht-JgQopf+I*_Rh?>D*TRQq+L&!7kfYytP*15u3

dJ6`dkV|96b(NDU?Tr~&a!K3wOS1AKR|D&Osh7@09RlP+qyoZ zyeAu7S6BB4j<0kNI$!|*1zw?e{?bi>x_zLTmyhj)FpMx_RZV)O!A>Pk_K{vwrI9s# zP`#=TK0+}-J@1B{ShZQ|y7n36R417nwaHf;vcIiK_!Hd1{kqFSc~8|l^o75KL{U)@ zaI2eaVw4qHJjt2f;?hZ|(F6TVJ^0&LyB^#t4x-&MWb{)F5{fOP;*5Tl!7ah3bp6UD}f~L@NJuk{co!ZnW zx&O>o`qN1mL4g>n-n!%n=vbM@r*F2wleoY13=X;@${I!rzCF3xx~^3R*2en*2Aa|u71 zSw#w``MDHtXfcB8oWN^B4W@OQc~bxBInFQ7gS!eAZG=zhatJMiiRFE&A*!W=r;7Y- zle7Xm`yV#E#rE)@7tlO5g*B(JxB(X|ZMMt5S+xe&t*>+stT3gq?NNXPZ$fXtPHNQ{yp9nmS>&?-tcQJ8wkhpuXNOzqdfKO~W1Awpkf9!z#>v2N| zD{bPym}MN$oq_~bkOC2C+X$BZ7^YTX!fErPo>4rz;Hb-&I9>_0=$8MaDdqe;ifaE+ zI_}G7w5e1<8Sh_2Z!Y6V_iwwv8XNV2*12i9MMMfygk5{e3tt!CW3oZP?Zz9u4-$U= zabZt&?kLI z$&(;|o2B9|lB$I=p%eE>-X;BYL)-Kw4h|{))CoDhq#BN<_OYQu?gq%>r%MywWd$EE zC+b6EaYxP%k zbv46h(0`5ghJ~%I;xvOH%e^nTINv=B$PyK&uBKLl$UV}TbBMt@+S<{y0jD;9Hnd|1 zGw7-3y|!ORkAPv8zCZ4XlCF=7%hjasCo7K#Dl*x##Yom~5BHmTUEKae|YpFBGmYA1zK;UgGz#va$j- z1kaznN-ppJ4k`jG7SF@pOvWef%^p;+dbnHD?6Ubyfi@2#8 zc=Ri-+M??y_yrj1xXstlxSdkBFKUOJgs~X^0*#k64;xU)>pbWDydk#ZMoQq zVNGFJUFSgC6b*3;2UqQ&zB~QE) z)z7sFUrO$hE_*YLDpN>z*88Fq=44Ya`#?{&0fJ`ZD%T-XdqeTB&{cu(f^)_9=P9^K zMya~JoQUX1T6 zBFzutef{@d;)hofl@(-75H<#!wR4j}EW+3bvO;ls-+{0S9Vh?up3iia3l}_dX_B=Z zIdmp+sE9UneK-{FHAJ%R4-x@HoMBSkBGGL5qSX;GZ&u$sj8Df|fTTqMyNv6x3^hTq zINI%!cqau}Dg&c-O_S$p!%NA@E7Wn!l$?8slLQs(v& zm_Oxd;u&1z4VA8Mm&FD$ki|4L;=Zz1;+ZY?Zz{9EHS5|ImGd9msj+WgZv?x7e4}hA)!*@@Aj-8$c7c)p5;Y^Z~38 za%A!#zwFj9H5|pv;w;*!N~;T|m79z1PexLsKbQH>Z|4rN?y?i`tX51Hsim@$(p2enqKZ-9=Tr}Fk8pm?NwdUxOQMJM%W2h&h45b z=A2<22V~55ZaH)lD4jIdv?QX4SLoua%k)1{g66 zn^4t!LpLm{KX1{xA4*c8n3WViJXTwew?Ro_!PFH+k70Gpo2Hsa_MxSfO!B2yU;M;R6jpi@WjkCSrx zeQLEiP3Y8S$zTs9HFfL&P+IPy4(95HyLd*CL$xJLaP`abrWUS`bZ4jL$H>g{grKLa zoxn(kaUmp@5iEM2XxocoN4=*u-_NE=mKvq6jux0Wm`k`PK&B#^1E$%pPp?Ki97J|< z_ASDfOI4{TZ2ujMB z2y7-1x4yhC_xwQz#55A>Ug`7zS7bAfBWSf%g*$+$Ha)?nM#+%jU%#zn?Loz)VKFUr zB#LD=$H@I6xB)7&LrzF?$3|-Xb`H}?N02cS^*C_ozWc|?r{HpIsidpq71F!@^)`ud zs|GY8Nyp3lY&z5`pE(|{+2@S@NHoBw?Bm`Dv6>}F7?(@;He>pz!=J7%DORf4xm;k^ zz@GNbt1are2y^HM6jg6#Qv|Hm+^te%82-)jQ5enRV&&7+Qxv6gOjD?`^F5sLyIVNU z3R`XeTcCd{&ddzj*Pw$Eo6zfyuZBx~B2IO^VfLCV8|kTMywNjmmh=g(R?g z+kll)K6YZGP{}#4aRO6zk7S01A3IhOoB#q49UA5`%1w?tLffC89edi!k5-Tst?vVG z;}LWr)IemtsO4fHtW*ZSzT`F?5y$C6hAMBwiP5Ks9++m9oV|aahQ;!8sY`K{Zn|s@ zd&Fkhd`gke%ml(eya4UM(evlbpgm15h4wHG+578XmqUFM06_YzEwmA4$xU`rxJu1? zyL1LEeLnuHD;$w1nOj&8e+(N?fZ>RjBC8v5L~B{;#N!HYy6FVdK~>3|tL}A9z6dkS z9BPfoBh6@=L8@oO8Ds93iMR3@)LFBDIfh?Cc=U(dC6N1kTY3u3R z8svxqnC6xjn?+acN;v_8cAuhFY7$Le4x_L+*;)Q$JG~nRe(<(}D7Ap{yB_IC(&d%m z+?8fja=oo#^gHVX}H2C$a?V;+8)jHssN zucFL$5mb58x|hcKJ3G62{9SZg;@`iYir@w$Cz!vmu+Z+w-TcEi#}^WJvjp@kI2&x( zyIB9}D7ItH$SC{q0YQIo)_20KxllB|ZZ*8LFd_9FS;?fydN5luN0!RMs7R-gTgrNziWT>*=g^Uj9?o9(tas`-#O&RuVm0!UAJ5g$oIm zY1#kBpqut-TcIw@yV1%!Jo@W2+YC)yzT&wpV!UFf`Da%Uyn%Rd-~NfuofYIFeJtCn z-(3bW*SK?!u3%H+hw&3irW${l2!X@J+sVj`1nEb_bk(0RoN7PG{g(NeICplX~W**x#O1$nBTZgmf+v6eV z#<_srwZhsvdeDbs5u{f=3KJi^?>6vfF0KcWCnqaXPanMsoCY-)zOY-RjYF6=YVg-7$*UK}DdeJiW*CYO7a^Oa zO|P!G)qlJ%$DX-B>2o8G$JhZj!qP^P9nNiNDp2M~5>C4SSs3E#^YrC<9*3IbZAI@ZIFI8u9+>~38= zwb0>lI@&Ncy4aV1A1NGNxa+H#9OcWEk^Ma_wEj+qPtm0J$B7}%=_`{ebH`ot78DyG z;dL0yxNK;d$2{fliuA+}Xk^LgYQ;{`M4w>|f998m0Qkd$5K-#RU+;K3pSyPir0}4A z54*RZP}GqY{jlYHm~z{Cz4{Ka5&$sTbQ%|5S6v+9L{I8vWbAh_fLg3GT%wy^?eDKfs*h^ugv1oo}Qjd$?Gh(f~iH! zgD$0BS^Q~fQ@M1LV)vd^#$pH<7>SlcEKy$c#8Ir;G0L_3n{oK?)j!{f>i4~ONx521lQr&?@d9ymYo*K!A5V5YJCHVlTsrvpgv zEI76yZJ9>vSvQUcLJ*S~mG5AXII07c`}Ax+CLbgPP;?=HA`g82{7m1#;OB^uR#vzV z9}qHD8S0}eZ6YrudqJ)PS@;VSB0Wsnv(-Pz3Te|ht3i&D?Cyk=aWJz4wM ztVB)DVR|66MfF_Cu_{AgZ`DK2md!7sGWXM(K(8BSC?x<#U90_>>fi!>&Lj&cb8edA-N`Pt@_xyc4bC1J|OJjs_J2wV^p2n`ZG1KA;O3QTzzj|IpQoMsPj^)y t#pseoL~KPe;Qxh5NlER?LD`|#IGTF33y(Sl+z#~sGSa)Ni`RC1@qcxtM8E(5 literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/debug/mpt_traj_visualization.png b/planning/obstacle_avoidance_planner/media/debug/mpt_traj_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..8cdbe8a3f46de4d2b2a8ab42acfa0d977ee35625 GIT binary patch literal 184562 zcmd43WmsHGur-V%xCVj*g1fs*Nbm%AcL?q}xI4jJ5)$0qWsm^|3GVLhZtvurlOy-u zAK%Zfp9l8L(6e`US9R5@Rn>&a%Sxaky+MM4f@j0|yf*GaFlL6GlfP2NM$;$IrG-$FS`}kWTF8 z%IZ!Z983(H%x!H*l+CS8ARj_Ov9YkRZ#LGjux(|8vhi#s{~%#w-%9mo<=G4kW@p{b zkNXUqrGSDWfszsxQFhBXSakJNxqJkjPB+qXa|7PJe??-@kBx~TCg16&{<4Nny#!EW zp;gLL^jSsw^Q2z!dF+AG1cTwMB`pGmoz=v2k&=LjThcqHWu5^I9!2F#p|n8Sq}eex2q=NA~Xq!_#)R zSA10_A_{36pqRGF@)G#(%ZZ3z4BiJj79rg z4t2SeZfiPOq*A(Pb+Xbqn8ADQ8}aH_2lJ0Y*)gZw9Bw zZf|c>@)|*v`YNx%&u6%2!cTY%#Yc&5bLNDA?MxnE*Y#d5;QA<}%Ifzj^1iT&%Bq;P z_gJM)V@#r{qv%ts#W;{sBx=;X3#UUy|pp{IOY7u z5(={?nHXr`_zg&_3O#Zd(5tb1w^W1c0kP8vWf>_dAwI9ds|sCW`wa{GM87`@je`oF$K0xjEv0rOiaAqYe;RUcfNZ$NlUcEo|EmdT+xMW-LLL>-{VjUC(=^lkn?yeIm-j2#gO0>|=_G z1sC^~*{(!a(6DxI;EoKsPK54gDuX*?9JdV@y*>t33E2U2mhBv#Y_)S8OVzypqCzEIIPPU!^MP z)^TYa%=x;TnA4wi9mGaK8Zx4*8EI{YB(}_K=w6mCL@lR3*54Xh$K4RCAvIiNdviDc zx@3TfqUBiK+kJ`lf@O;3SZ_I&<{y07vl-MtfmLv~iPEBr%B7sUY_F+#RVwLK)N*_^rUXWTYY~K#1rN-F4Ho#{j zO8O-|Lg*{a=;^AC!(L815~k)%mh`AT(hn>;Ob?KaWMZNTRQpq9MK{cHMkzh_M;J;G zrDlyZ^zw^M;ffY*%F|Ql48`$QG3B*aEirsGQ%I59M`AED-?uC1SfbrSukjcSV9OpI z!?5w(N4|V8AGJV|h_+w}RqoYxr&aeJKysknPm_K+E5+8381qsH{V z46A8F6QOrT5mZ`neX8ElD-Hg-T!r=5Zr?3PLy;#q@|&~MQ?6ceE;Uq9I0_oh6a>fy zaT@YmsnyG$P0=qnAI_ujxgy1n@I@!IvS|`z?TFHxD4L7R5N#Lr>s()by(YKrua^m$$u%5B zYWuYZ-i{wZabDGo(>z^i3DB#>0d{}f)Y($MIJny(k6bf62n%xyMk#F8g)aIvSxA!v z)s9elUN;)sl7GCd;}du}_^p;fC${56s2>oNaFrsI;XQYXNqAFj>+px<2x& zS`&~AC$H+1^w$zz@29S3y+KEJe3ntOU!`repGIZLT<`6zW^sI7?DLScp%73oi^dtr z)Wy6p1$yqhI7NHnK7WaGIA>|E|7-Pjq4tWydN+Pn*Ryj0F|BeS&T;%Z*Ba&DeIu#qkiw%B*PM zd0Ft=S_#7fWQgAixUqc5m$Owd0}%lZyvqtUd}5Znrxom-_5mo=k&Qvk;@9L$XcNyU zba)iXas7_tPXkHP{Fskac8|`mq56y%->fzno*pcy_!k9v9>=sAjNJs_Fw%uWBhB=- zgg=Iy&l}0EPQyL}1C*9KN7u2bq7Ov!J?KmE5d(P5XOKO$c;ft|xJX1hN=)|`?%hwH z-hVQ~m2Ek2jg+1>>t*;gSc!&Uk%GlT(>}rL4#8^qrgkQid14-_etK<77 zlg`CzGJuWJ)xn`vXA&@E+EvBy^myzO9~%qZ5sFDZ_ifNrN=C-I9uV<|mWPHqiQX@E zI9={dwmd)G8=IL;zXe<`y563GhVRE?)B3z2?-P8lmDP83n#?oy*&%l!4wf)-6c8P=_eQON5O1GC8gW*?B|8G<%K_l zxJy$LSpL^CNrFaqP$nuWSdQACpFU{(UcEp6D%s5ETWj|lZ2W1z`EY)zvx9s>Qc|5O z;%~)uF5`$ibmU|bK6o03bwX_F)+<*|5_~uFtCcjx9Rx$a?a~%zr5XM zr0Vy*H%P`&{y=-NUZ3d%Y8jBnIp&*1|I#>2b66z#-#z~vg$3{29bC2P5E(taW%;^n zete-)eq2)0)D$ITSCS^BriM-LTPvieq~Hak5=@D|{=G(!d2z_4!xzx2l^H+WoTlW3 znWs75izOx`umG;CsAMzLT}w?gW~{iz#>OgUIe1k?HzYSNJ+ugeO-)Vf6gVN%G(B2q zgv#)`nmyG1`>upY)fuQtpC^td7S`#p!=wOa4i@^dS=D97^{J)4Z|KaeL}z zL6Qlr=sz}>M-`|(ApvC_guuD#+*{Dz=mRKLx z!=EEpTl)+qs2RFtim2XBR5C%{J|c)-{l)~3V}3W_X+=|-_l@Np!kZTbE6nAF{n1ci zDqGNt+a2l$4_pya#A<8Bf`;q|DEKLZ$HNB$p*OJZd1MYeh^aX3J}#t7(!zRz0*J{U z+A&DULbC5xX&){ke2^4=>k(fa7rOk1uNa;Bq3u4a`Gzq+i>WYbPDFIH;gU>X7aolI z_rJS@8xF%_T`g8_n)TmXrX=lBQ&DDV#av-5=yo6%pWQrK!j>m;J*TjVi)q@YM6nYt{l+)&zI!nJ`eZ^9G0 zAVJLe_Ex>A$e#{s9F)ILm%8xdR-|kfUEVK%W?Jr%8s!Mwl0~W=3y5C6fG?=xj8yU& zn{b0JdG`egEc@N^_?*Vg? zbLY$y(t%=BvN!IwFl|sG`SB;gF+jG$f+{<}0U&6YbNfSria+(Y*mJTfIbxLY4!Yr;4%}kAx}QDAWpBE7{101dDtu$k{gsW(Ci=1l@vFK3a?(C~{lhOSGR_t3u!A zl1r+$XPrN(_&)C}4K|a+BKUjq?*qK67ltp@P*=lcUwfVyaQSGc_Aniw@bX3RkH~)2 z3ltf>*2rL=|Cq1vnCfhba+MR)lU=f2CbqeO$8_fgGchDs3sds!J>Le3NX8}78*)5) zQ6_bMdUU;MRjHl9T}kYU9@BxSjEi%!)iU&8l$p(z9uV8bmSQhUZHRR4?mcCyyMWV; z;^^3!>eb*bO0fzMqz#zR)kzVU3t+^KaJ;7@0@G3!3k1yw5`D&Up8Md*PakjTgRott zU{Ip2*c~SwkQ;KfQNHa$R;kb5{&>%Ic1LAzs)AW=d|wzDx)%NM&fY)`9*)Z0vhJiW zLtBWcHZ(k9H4pjD&Y&rN?O4rm*k^!eeFJ;&HGj%s)ar5l^*V)Iu8+2u_Z34#Q~UFW zyq@@T@9x7I$DxKN8E$M$b80MVSz}-zqI%Ng&d0yv0a3m@s{BU|oH#CSfuQWGcQ28f zQN3plHbaJVy%!YEH5+@t1EoIzEmH?HUBIII3NO6@*Q8S~1R$W-@#1J@0AW4lDK=1x zO3${Cq@g)D+@dJ%Rik$WysH7GYg=umvq;1xa&>C#>y-wqCdX%5*6thBZ${)itUZ3H zp+|&6<~8kZl*eFH@W~kAZtUK#b4wO!UD{lY-6A5d=+!^ z5XcYG*eInpEhR=sI31cJ@!R2vmODM)vwxV^LZC{*Y4-yR z661;WERgs)vCCBfaY3jIdHvwW!t)ePlG?NoSU=R~*_Qt!@LQ^YKo-#vRS4->wTk@S zI=7rp|9Q6Yg!FqoJDgvE6w4{%sJ^WJD{ zAxqkDHWHN?5HDQL*+0n=aBsq*{^FpGcx=T)TBxV?#KZK4Utb0fIR9k9Wlg&o0z)00 zVbQjzDplb~TW3WLuBU#F!I zFX-lajP^e?G<|0^lI9*Oq$o6g>1xxr>C>pgQ~b1!oLIfmEKO%cWRp3Tj2y2Y)esi$B`uHsoEK%tO|A9xjqWpx4iTD{SX#Lpd+a=wS<9tu>S+n2UeDH-U+*O~z$f z1g7f-JazH2H)-Ly6-nx;b^9OCG09pt2vqjOAWu6SB1L4r6ymzKj>JnJWVN}mkJ(Qv za9la!pXYHMBQYghC)v;a)b_;I(F=r9weC3Fn+R&xjhD?H(3U1z?1OJi+(;LxY9BId z+%-P?A__-||2;8@#nqnmqXR?J^cCSKXOxfjV&Vmt9)i|J-zK7Cg{Kj8#MH(aI94z; z%+CC(@J}c5>o?(4+Uv&&^iRL!K15XD_YR5yIo)8zitHU~Fhdb673nz8ls#=mVuFNi zOsoMq(ZqXzF_aUEq2&kk!#juXSZaq$MO^6$SU>S)*U0=9pmeiEvPZq#I?{)_K60P$ z|Ior0YN2MQcA5jlRf%vJmu+9gg!cnQh+~2f6JCCL|3hdhW#!<2w03o?=rYAbXew=G zJ_$StiC*8Lqo+8FF#D?L4*Ew?y#Twd6n+8*kQSjt*s8vc_j!*53)dTarURXAOS5e( zJrfu~a3^NK3^vO|9CqVA<$}WPKZUcptgdz%(a2K$DJP4s?->8ex?_pIm5Wcem}##D zYn82|V$}gADMYT~&YU(W zZJ`F_^?MHl>Ir{7pI7**)yIWh23>H<@TE=XT=}i0%&N_(`Ov06DL%jKqvv8R#jqXL z>PmOsoI8E#y~o=K;Lv%U70%I*wWUAj4zk<-7~yVsgcQ9WuUvm!Xqx@oxkF&|YQgNO z+{b|N#rMBZ(h!Prws0USOKDmKhp|RVUXZ!Q3x7^MXhN3&i}u-W6lDath)rxYQpYOS zQxgMfDvG&^ht~}1sVv@v%3In?QQvDVc@CF*pztsajPXvo%IF*dFxCsq%`7W; zsxUFd(P8PD^G|y>zGs_e@DX-T6PWe~li|D|rKAiWMda$Bpq&SEYawfBjs@vC$!*{& zG`qQ5Go43T3^o{x|CpP@#FCjZY#C1BtQGiZOzCXC;O1v#1Gm7az1Q&G$g$b+=dyh(led=ckLQ;yPq!XJ zLa$@V#g(3M7QJ)z6dk3 z&xCsOWY_G+!sQ6@O_>~zUnZsJ7t7e6{86;6Z}EaSr|%pc-Pc;7yy&Fe8vDrF)Tm`Y zA;j?>OPC&nZ>hlws-wXYz^%##^ht8-p!Vsu#!oMpTpX%m-K8ZaGCaAk@3+x^g$ac^ zkP6dIsf<77-m<&56d9I6sxrtjPrbv{RtYz;nxr|cI#|N->>c$8Bi+i&oM+n8 z3kTm)N15m4(&hfv;}>}538#0e5jT+(y;KBWw2oJ2bMbilde|cdZs+;;`;INnHeJ2_ zogKYP#X<8N0o`qxsn{9=TFcfes$ei{!np}a7zjjduWL+e>)jl*O&Esa1h3vWIed%j zLhaK2cw{=ip1PH>FvoWd>Rd6%+`0ciWb0iOma=XbdahEzkkWT(7IfI&7<$lYinqXN zLK9DXi~SCe9o}b9+|rUE7J+kUU*i34Zsz*8GaIYq;OsokVUfXVUq(+7bCJal+MGLH)u+;j^t_-|> zTwEM>91D!!cKwP>Rd$2Gw|%_U)|h?^h9fYGKJ1?$ayc-kU2xFm$pRXhdN*Z`(5>GN z?I5fnMWo)ElTPASqRcL~4|Oq9U9T_s8Elk|Y>x)@Sh>z4-sFsYF&1xTYU+h@vsfwgPdAHRAu;lM z!FP`@LRlGPOfn-;`!Z(O<6f#vO*mc%zyfW{xM%go|eG&)z{S=?>Mpch)ixLcdFl3O>mG}I6wCgu*6 z4ia-Simkx^HUS??1PGXz`SxuvX4eICbAi3;QcXq4lrJ=@!UzP^!_S%9BrA$_Z~kf_ z{39=5#!gG;#_|ppTWvlxs%n~11@b!Kg;lrc%yp&bp&zo!J#BSHcSHJ|L|t(EfLzBW znPK_+E8(R)4P~_#1unc{OY4nO7h2}7udwQ#@2*Tn%sg_OkFIT$6JB;!mzzj}+!-&3(HnH76%?U>V95&W?;k0d_(Bf)@=okVB@bstS+QP?SJzx?y5s z!lk+XFYhcVF|qaWMl-1=?>$zRFEQ5!N3)JtPz?0$=}^lY3E9}>1tk~%XqNb#_#r?; zRm}|#@v_X(U7N!h7myOs5M1xfD`j`+#Q+Hhi4XuO#k1hGCLjU9_|vbQT7iHI5T1oS ztY2jpJbAiuRp$h(oRO^hGA2 zxgqE6te-AHVWE=gyjL?u^UW`QQ$`S?PSyMz%6Tq|o29hW_V?cW^Xh=XQD;=}ue(FM z-AFXd?{wpz_lVW}U!)W5yWjN4pIr(!KOe(rT1=H_7@L?JIxp-xu{rN4L)2^TD;*|g zAu~HWR{8Y&H!fCIRulrRk|+q*@^>@OB4>K1)966C4vGPB$b1^_u3~_amX=Nt1aLv3 zq>|>TDh4Yq0&{co8LKoadNPLsx7H<`kgut!sn*I-|BPMo{H;B-1q&Vp9!izvG}HU9 z@;aeS{3My&wz@h6Nb;JR11p^YzbMc2qZy>tOSlsQYOX0MbuF~_kW388|G@_RJ;K>` za*lVX7$|V8GLA7AoTQ}C_484n^-i05qw3kd{(eY$*Y^1>e7O5vm~)FXS^1~qF8kp+ z!l0fxX0`KAbs-V?#w>&5Ne~8;_aX38#IkTRhV75+a-yt2@K+U>-&+onRz9)oep&EU zK2)Ejd%68YNx^!O-v~;771q;Pf)NbYa0`l?mO8}l$$+P-Su4X)Q6VKhwwUX z9h@(Gmx@o}Fdy^2M}P~sdGsDAW;A^|a*CWAtny9>H#wXf{*$s8Dy!YOpUgPVW)mmQ z4s_HZa&!#}mHxQZ|Ivemf~~v0nyv9FgoO&ND!%bsq)bu(Yp#d=$nGhHV)yf6dy<;u zN~-YXs$26PLB7)KQ2_^|ha%jh-?adIuaC>to}zH%fl=(ZSYFELOYJ;i4W?V=ka@fT ze>*zf|6+c+(L!v`f2hq~=5voj^^Y=-b&#UUyTX4*{V=f=oPRP-RG@EA-+3mpl!nzy zq<6JaL10WFHsR&A%#bAJ%+d|e+h%RiW56P$99&8QDJ@fg1;uYwVUnJ?S5{Gw+ z(3rdjwP2zGRM?3mgrN5?V4y1)tb+ZZq{*j(ssPNW;l9!9a5{p|AX%aLiz|3*>K z4TW)>fSh0!6!>Q8;#rN2T)r76l-&w~gR?u$I(Uofl$PgyzHjw28m$u_gI3qVjSTJP zVVvZ+Dy+}W77i{wR~ffTkveqe2N7~D&0w_*c#nsc-+R})4GVLHR|M!}h4vYA`~!k~ zBS06U|5;wEw`YR#=n3X&kj+%VP~|v4!%&_#i2M0WMe{Yu^uFcft2P;SNtR-_M=%V| z&7!u0jULnfZU+kx-%%4+JSdexN2RZ-fWl_a?0(mPfJqiFy_fmhCme>^PQ5ld!;rjh z;gaxN|8?zu?}dhC0qZIkN|U2l>k&|C z+-;+dX+ePqh`&m<78(J`TWFg0POQ)U$KgEkt-&aRt7eox8$u$L;0)9H;(`-a62YgH zY1js!PQ#V`upLjR^&aBjXp?u4(Q?bTx&u6AA|V46=Kr&a!9+}EuFFT zE4?hetLJ+pnj4Q6u+S7=bH&B%0j*holIto-h>5=8``><#cMWF3oO`LG=86d>z$T!{ zaW?0Vtjs@85JjVs$;SR$S%1AK`~ju%uMUvflBECT5G59f3PSvaF&4J%la*rrCh&fJ z?K`;=*-Qs$*=D6Gl^9}Lk?S*hn4^!KL+K%U3&DM+Ymh9;1Qiukut8UFt%BI!aw8)f z%7v;W@?q%~EN8H~cxWwW+Nk-8AIN(cQbC6qOCAGBCW-}iVrA^b8u z;jC&S-m0uUI|B@u!skIo_L zwG-9zaO#iQ^6)SoNs!U^Q>Y(m;Rd`aV82-Cv`>iIVXY*qzY6S4zFp*wC@LcH^U6eo zqb+5t+|$uY&>DD%+O)bp^lF7x_aoVSszbFG6P+6i`B)#9xo)x+>ZBcwcG^z%k3@G# z_y&m}Ij9M#c&geWuNqL#iZZU!QCm8s5Q=qO4&DAzPiP|pbJ2ZsGr3`P0n@X_7*=rY zlehCDM-qd^n6Zy3BzJg!ZEbZ-G-7W;IXH}rnT0WO5#ezffz27O z6GeLqhUqG}6*ATofW)B-vi#GL`^#+*B=>jY`1v*Ok+AR61b~TP$hv+}+{A>kyyXlj z&y~PdHoNa5v(U&}*M-hN$Q*X|lv22?-=GU#$g_LYAOtaRnc`M+G5J}-1MF~d?6^47X-QoF%7>-1rpyi_Vq7yUW~NzVCC`(O?7nV$c?F8c5M>n}%F+BNu2P(IiI z11SiKMJE0uQ)3{QxjiG5-Aqwky-!6=SJuOWk1IW@(g?)Wtf%IHgs#01g)$HZzK^{> z3s;Yu&ioj?3toU0Ide&<;%oNbD6y!srUf~xqUTxBtpvR1S?$*S#6JK>%6tw@7`x!! zLoysyzLEJr+`wNSXZ-^Q)ErgkP6NqO_Cffa+g=!)(*Dh4asUR_>ezoQb%}EUl=Ikk zsZw1a?n@sev+QK-^oqUI zV_15xX@i|B=Tz$f;jIsc{&9rA*nq#)w$Grn>qSASijK|@uAXNnzF7wJJ5kXW$+{l2 zXdn>}4zz$n4R=pfXmdeDx19$jCwm~Tne&>D?eSWooC}NHJArj0qVJ7q-9rpY7Df{~%HMM14I-bODE)O-{Q&0^62OUuanMDq}=s z9EO#Pak>1Q9A8KeVD)L-c(KVDg^&khoTKsSZa@8Cd6G7ax=e;N@69)| z17}Mr*Ec`Y)s8>qa~M-oEd)agv@|P-G9*84@i5VxW7#!^qOz~l#cC@}Tk>F)3;Kmw zpF$=&*B4m`s{K!4!2M-4x;%Jbpkc45xM9DnS-s8*Ka=0p^kQdJR6?TKW|6O`xLBjz zTk!GjGB+m&YMcX~$Bu;Gd+$;>SaWlrskG2~l zri?VEpqI-POqn9|0IB6J2hqZ?Zq?7=`bHHFFSQ8&mp+?YBlq_A=P~w+r~Rd#j*LZ9 z-W}D)rQcdqx@rnE?}?9ER%vmzj)j4>(n;q>)!7xKKhpsJavzYig7#agcY;4LF28c) zoP&_XPtMNe*lp~{KHO8l+O0E(oOe6tkCi%dK-J6e`UN2q=xts5rt*58*Kcd+PK@2= zk|NcWQvJOC9DOvI9yx4K%Fyx6=}Pp{aI?&%%5C0IYJ6R%~89}Y2u<2(icvNO7_i|eb%EpaQmBz`j1L|;D( z1vDQ&(pM+rtnKpp>LME8L3O@YZMpYZaGZV=IA5isTZ=J#cTMBM=$6s^%ojo_Y+P-$ zY3R)Y$2xW;eDnk+8vx^+0b#FCr)R;1I|891i{C1=C_T>yGY9Fzjlulaj-c_z3xbNM ze4?kgP^{os(~^zJd0kV>Pn>!JUc^4$7mTWJBv`HFUk%GRHeR>+oEdCM*IDTdPZQ+w z+K9Reh+~bYh@xphIKA%PUYH8=aVigpf%(mNSTO(E(`~Z%YNG^>|eNBav6Mw79l)H z_LNZEaLw%MAl*s+a5Vcvc_tpubMDmG?G>KK6gE@Siko6490u8W;kE`LfQoy;9kHKy zx$ndC(5z9+_=ydO-9^$&z)N;(0a@;AK6^TMS$YSSJNeDxU`V6Q4wtEHL#!(od}on< z4|}r1(>|5i(iH-`cc$!C&3VIqypHGvPgp#>*z^Uv36j}WM9{z?gWDb2(=nK)cln0I zRmSP`O00dew$_{Eox;@or*ytdv3^{K{nGqV#){05ZDR%O5-+sp#uz=hbXaP=t_uRV z)2>6GwZ%&jEBi+tBW2qYl(iaU<~5)a+eyvd;y?HovaGy3goipEt3Vc%_g~YTjb+9+ z;yyC1o`IRowgywNac~?a6O-e!vZ9AfjUW|qLkFB;;NymXe)7c*l7-~9cjHp8UlGXh(or^4i?DIN&+*b6r`N~{8!9M6IrjFqpEuytHJ@if~&MExy zM#CW&|L-eBg;^&xohZAn1Hi&x)+OG4P~PeisNBI7NO8x^T|?#JOVnz|AO3J$YP|O2 z<-@)$ulCcN%qK!jzs`403H83LBTvc8ErN+(Ti5N>P&aNyb9ap2ok)C4vp3APxz9eX)sncjwY?rt1HJuJU8pH|BTjOWiSmABG(JW!T8VWwT>10bSM*Ewj z_andaG!i?|)tn9`Bb^=Y)u9ZOd~raLNAYTOXRMhkLlz+8*yRUCZQFad9`FzO0g<^m z^;=WKWmr@>=&|wf#@nrQ0zsc~8SdEF*wKNd57?VF!ADY}C0>ckPh1g7S&xzEdTt5x zc_`%HIwxg}3y1VE@Tc+3Y=nBA=CVrYq|aP2CwZeoQ(iPx#KYJYTzSNg0ktKMML+3$ zUlM((is(N7{z58R*bVW)4^{o22oJ(7=Is2R&@ZS}rDCu7c$RPFGnva%a?gjrS2murI?X@IHo)00W%sf?KiE)Qw1=TPYI1XqhZ1!j z>v~4&KDVYkW%9GHgug_&yLZ&)r-13&>E3mHjL;HbK94BNlp?aH-yimjYJV!?X0meP zy_GIIT^_0E!KKh3=1w$TPmkJ@DUJh?+at^f4CNrx{qgGN>0OJp3oyWM;x zdHHvcfC{2jc)=nrE?jx$RS-A{heimgTGaM=yu3e}x#qmSc;>A0Dcy=D^)9lC6%CpM z7nhQ}{-MJ2Ef-o7XKPcIOJPt1=K)fEu8V5_yoL5wQeTkl_9ziupVKbC$U~+{i zFGjIEyCUWDL2=f`cgLzm%Uz>LdsRa*Q7muy{IK8x2HKv;P|7iP{oL2FSJjZh&nEnb z^X-xC2_-peh5M-*h!sqMq+#U5#o<<0SBIK}u#pVXs5CS*BJo(iLA;Q*g@r});_pP% zck(?9NK6!3RmE1;v`2T;w9k~ps3pEVoQW^!!7(~ITB21S4XN~1_kM&pvknd! z$h7;S-}28iIa{tnTQDL+%9*hyPXbp-$V|&~o8{I*Ln*IFBGIiHa&rmVW6X$ap=TCE zL5hXYBR|m7xDt3YVTi0)liS z*UxhYC)gxbP`H8*b_6O;pJ&;JS4Y_Ao00x<#eZC4>s&YFV*XZdLI}BmM0$K-Z-G2> z!!)WS6KHuwMc~0~bt;d&;bJZ1=vMWt>)S@xn6NEM-++jnH{yaE#S zu(rg_mRqgB>QSgYHsO+!qYtaoaoMc()<^7mc<3Dw?sYCja`_cmgnQxO=;Lt#1!c)} z;Cef03yC74^vbt7O+?^g4o6TQGp+5=F?aiZ@nHh(rT|2pHNkE-?T~_h@kX(a{O@5W zpgQ#-QQtA!ARvJ{ru~9u4R-r>fP<$s#F7^CM6`i{N2#d zCA59tAO#`7eRz087JfZ>nIADV81t)sw*}#U)bFOX`7I8;BwydrO*iF>Tbx1Ua;Owj zF~I<41aeCX554KF)&fv;c?cTMJa+lAkgAnroH2R=5IHO8en4g<2-Q+HTgv#y;J z?qT<44pD3lc1Q$INk$$r2H%3;-`=2Ca?n{|)xsEWYcv3*qjXxX9-yMX7}cli65rMp zU37(qP7H#CsVW(HkTPA}@?^r8 zo`?2GAP*s4Qi}U@RW$GLetpX0L-;^MO^D-eL0yK5fC`Fn(o7FspULGOh3>sj{ITPw z!5j=K-O(^}FCaplK*_y;->jZVbr;8HdvWr-=t%u8cqxW6|3?0>k4MX0E64ygZjM;` zr*x@!(nWQruLRAzMqqS)_lt3kHgG*cMD$vjeP%;bZSKTHBV47uOykCZ{EqQSSFcV< z|Fsg7+t}ER-KOr+17*meE`mAX(81~3#+Dxe7tZbWv+%Phg8VpU?~y*D!G(UFjm)?G zERk*3q1RELO~rDbP8b(O!WVQWe_R+!h@R9F`>YH9DI!1l$scUKoj1C;SI6>?wTV@f zweZ!%{*r{IQ2ZtfILayC3A717Z?6@!SF!k+jDfxbq+F_b$cV`pd^gj4`9?3n+G>gMYPVx z-3qs7CS(?tAn`P;mGpA3cU){&8pdbaw5Hqt5KMmdOdfuWxU%2U)5J2-aC?9j(vAoE zmMLf-^{uowE4i8KFgy!!2X;?F>PPkj{Ec!Of3$W6UxrBj9LOhAL@v~Lxp2L8ePOvA zNFd?*QracESF~xb;r+i>CrLcSS3=&9-D0!_{}a#rb~p@4VrU z$^JJ5J+R}yX5Ii-G_nl~2AbmW&?Cq{LLl@H#V#jvL)w*P*&r40bF?z%j$I`Nv?g9rx zFVo2r>Z0h1C-hHt*xk1>Fdk-8Th6y|o^D6cJZg{oUk^Lsv{h%Cxx$CK@FQNqrntdK zFq84j$YSX8TFpcOeP_3?<1$cZv@+u1SG`uyT#-l7r(08-%Oxx2%Vkv;~0Kz`5z~JB>};?pjBN!XYZxs6|um zik^S_DUv@0&lQ8zMBoE{JC(z6%*z_Qg`mXit4%+mD?`WuKL=UvrKW255mY2fYTDHM z_FeDCDwz2@f)nT6 zJ?cB1*YB$g#m&5lRcdM7P(uR5nL5tm(zM*Xm5_77`|MAeMXYy6n=oy?8WZPrHB0}8 z*rebstg*}d-gK}K5)PhK9Lqx!`SeI-ciGsnROeV&=G?Kl?;b9zL$k+QxX2Yb+Kt%)))Y+{g#YYT>=LH#bg^7q(paR?wtOE>8 zq~F+<*X)dz@tP&mu*E5u1y$&ap`9!6w^FdXh_FpJKV@K zIUmJAmQW^#;~R*f`dtga&CTLd1r^a62Jhwr;IsX%A%AyLHA9Z)X^Ju86W`UoB)9U8 zK3+xG?bH%g8MBZw-GBw)Dcmb~hY!_GJSz1cu?`efqfMl-$v{d_kdu1qHmt@R1dMTS z=vquR?`N_#iJU!Vz21wJ^>f_81|X?2vF4b3_@vU2`1(z=GfHbjnOIzdLleRKS7>wdtB~s#fc!x?Bms4J;&2zp311` zuBNjwcN;@=laum9T83*LJ2w~;my)B!#NO&rOB!(2V%f$aW&1kpMfu*f;t6B3|!EF0C`D7ltw}{=AWKzjK)XlQ8eb}!e z#Kc|idt@JF;e3?yQ$IRdpPZrPVQDz$i@yJW+rpO9*o?-hJ4$oF&dD1bME!a!m5B9# z_x=MVI-=i;zUAg>R2qua#{6T$F$*m(ncfLjk3cQmGs0BN#5?5-fH=dQ?7@ivvf2ia zgMFgQZC?9L|E{BYQ|Jo47dfBLmRlC_`yl$C&>XJtf%o(8166-QGgohNkPF)(}^7=w+#F{Ac$T66sAuLZeJemz9mj>_67=7 z$LW+ZaJ2!@jU*yh_CnOYRO})Pg~|15fsv42&YTT%*m#p>Y410nxVg=6c;8+qc}pP^ zf<(l=3pq3|PB#6E#Lhr^BkJ4acDkk+V^1QOET(5`uuji?))z${EwDsJ46D(K+T z&#hHiGDjJmRTJe|#acT?GVw{XcR^zwPw04Az|#vJ&C?EDDO&>)g?Cyes&5?Lhs(XH zMojP!@BvG-T&#*aSlFei-tpK~sjX__Dij}q< zYN_mw+z^>1_*K?}C+;mL&s->e54rGDU&}dx5#jaRZ*2d^Rkj2UGw1!`hl#$QBp$U0 zYftyb+e?6BlOy7gQOLx>aCHW&mgQ`h15c4Vi@`3VRFLDi1!F0uQ>H?mR&;7HZ3&3i zZN09vZMg*JuWk-*0V!^~L6MnP*x3|Y$vZO~*Pa9Ga*UfRUt`?Y>gL^UK@4@?cEap> zQPiON^yi`GD0txoKimojt_r)YPr6#!Q9&VImbzP6h{hK2xgl0d? z<;l65EWQ2I;Dntl=bh4{RfW8NZN0IW%Icj*QvSCIdslZpJYnBrt=;=L z@(@6qxz@N|=Q`uf^I=Hul69FqL5nyIjA~Y5I1rd0#$1P2h&dZ;(AA9f#)E1*rZu=) zi?4saI<7~H?Sx;`VYrW7ozs%&W8B$H-3}&^%;88Vdsn}@VD`S5_4oS(ko%S&_=Gv7 zBe$5XqJ(ft5CFTrRBONM6~hM5=5GNg((n>gh`2R7;=7nqe9a8D-@G~1p5a6~yQ(aC~-Ni?1bTe_6OQ%oDo6tIxhgc3r$A((?389UA_Bw7peaT-&lY3Lyc4 zCLy>6cXxNU;O_438a%kWySux)2Y2n@?sjL^-us-j&Ufzpo-QxVuOGT+&oM?-&H76b zNi0TtYV4!`Cs_U!gV>6(95uU&f!^{v-<~;Mptl@|X{7@o+hYL7wXTkl_|5c-t*tGf z=$+s=YZD)&SUktgSayMz;o?f0pw3#V*LdzjDwA$Wu=kCcZnQs(3k|OIoil>b?y!N% zd}9v>htLeT5p2l!o@CXa#%<%WfT=lo2T==2_Pt$G`G?+qcr1tmE6NTf4j zy6Mv0=632EBVE@U>?b#BXD%BOeRdqLVaW%m7w9Nw8{ zHGjPpRzObsx^ec*;{WLpQBzlpS?&ykmu{0nZh2Dc$6Og{c{snfuQ(8nb4KJjshX{I zh6QU2ISStJ01sDpyWbm6e5kq-POnD5c(xHk`HTa6pd5(HiM8rZK*+ z2VI_r(p(u%7Q!M2A*M6A4Q65i!4XlKu4eoN(z9I(n^*Xrj5}kvkJNJB7|J4Lfv`&Htxv_>jEP)gL|oucGgH1qEMFQAJ!_SOaydELWH%X9>T3^TpwE(@7z2Tz4}k zGN!#SFy4Z7Lc&oX$E)|)1)5+H(7oSt1H?v+AFhVRn1XGBbZDykWwa8Yj0MpqeomO8 zM8zKvEnJ#5rz?G}@uU$zhhVf^j>{GZ`ht!w#?Su_Co-s9y>X`ATp4h5pp%LPepi+AnO00p zOv$ILW$1|DoH5dAn=dG?7KpzubXfUA>=Nty`AiIuy^fhtqodGK$U=U4qKH*Y$(Cp(xuXoAaVWlmWe-X^a# z>vw5fKR%Jyw=3-xfx#f0&C3ROJtvdT#n}L^J@5E;R|qD%WvC*>?_X2MIm?5?=M%a6 zRubnOvH$a{|9WLAWaj&OKm*uT|Fge~Rq#L9iMzDrzG{$_liK?`e9~N+|M)!k_|_WB|t`*$j$B0xn%tK{k0 z03OnvpVAhT?Y%l1-gBIgR0CARM-m2x+GSl650B@MC4Z-D9@asc(a}(8%51-0aumeK z)wtLmw5VnD8*E%cHM^dY95a}+DFkp5zMX%hK&q*d-Zcd}4qHyGrH+4tN!gGYgTWjx zw)^XGc6i;WLp#=c29&LKqcKIWT-$^s-!H(Ox$VBjSU2dY)`t>unPNT|=##ID-`3JI zpJyg=8@5(LlF-Skyo@QFzML6d#{ZLzq9Eq?QPvzYXTtqS{j|vluae3oV!B=L_d+o` zSfe(R4~aFp*ik_=*eaLTr&8rap7FB_gMyd7R2i?{S6+C8hWh=KM3&3Fv07-R2zS$e z-fcNQXxZ%BZ)OH2pW4;l+rGWr*#lMq^mmcHCZCbI4Ix&l&g+$v-3+~judM`HO=1CF zj)JKqgE<2(H*qn2N{+tW!_AovajNV7NbR=5T$DWqLMVmkMjX-6&gW_sypn(_MB%r8_Js=Db;=hN0{l z*?#)KkX&m3#Wbw_&yrRIo|rdaIiScpl{K#QtRuCpjT41hBRIJ^)%mpbhqAUR;Ci## zy9cpCdp58I^h^B!L`RW3%bMd%5_@oEz;N|#j3;S^EQ7<7_E5^b?;dD(Bw*jX z6{aYee9m~$EJC25?x0MKHuIT(a`(AuEyL$VXL;PZT7Y8wtbh>}>oD_}{(NCaJ(?U|Yp2oCV>$u}!kO(p#wT~q#1 zyJOTrB44Gw zY_$Rx$T7n8T;xgv!64lEp{OVRf(|7nCiHtbXjW+|av7H6pfm3K~^ZiX{i zN&nkXn&H+}N^Q?oJmYWZ0B|)WdEJs*>MH=gL`@w5RDQLqC$ohzg_bJ~ifF@loGoOZ z{WA3Y7J6zBHt3b;^Pj4d>*F1LcAwEwSP*D9ZYix1v?$^yaa()?qMfS@`rSFNHZz;E z9Q_`m|AEA&Il$*Y+_?A`3K@;32x(|&B(DJCG3Ea6a6L~N1B9UQw)<1)eT~_0(lZ>d zW!*yKvz}(h_W!kNu!|cacA)Ll_g3R>wt`i5DV|kn&O4jTw>=wZdZ&8)e2UbudP>mX zmiUiC3O|S`39P;VaAwi=yg^3QumK0t)zy_uq6H7ib&?7H%ob%@IRQF&BA(ir{J87y zymfgHc_ld61ICn-o__BhNc&LxRZnDcvl-PY&)8)6Ro*=aHktWV%IY_kxK7`@4pk4= z;n+nr+t**}F5Yt1dIj}HyW`#k)^D;i=8DaKOBKOG2c>-Pi|Q{1Fs-NBT#~ldv@Wdwn2z+Am{3(s(*5qw0msgjKGZMb zRP~v`1@i3818K=ub~PJev!O>y2?HDni&^S`;_nelPO;F_CnY_7e0MlD8BkjtEmRho z&KAI7v&R84!7pFFoV##ZthK~fXtu_rr2I5Z0WQ(6-Tf{mE>3~ZN3BoTM(}I5p(TBq zzYseG+q$%gf(D(}T<&_c1+JyCt4N41gv>O3CdkRn!C_JJ4_eqX! zaRSmJupyyz05_pQi&ns76HueT_R>apaLqk9d5_y8dh>QydE4BH0(MJwmp3OXjTQf8 z0|>b=ylpoRm;~*YlGm-pby9WO+dGx>C$^Lbdg8rw< zjcx4v!Uu(g9HG!fz~_rDk|SNZqVv^Ft-(SS>JM~k`~R9!ne=samndm{z!u4Wi&ZaC zcJ}J~7r@Hj0FSTc z?Vl78$L6Xi000S~;Ci#EpFT&&691pcIL}D3H3ZqfH=O{yyTMdW+V!8HT5n z5$^nf(u3QNH*2@UX_oM}jmyZEF6=vS4`%f(U*H1dK!=(>hj&jGPcK-UE>XOAHiUvy zFrtannr?&&ABILoa+E8z{xB?%5iLFpja`4&LH8GdL{hp&fQ&tsq;Vzo_iqh$P%2al z#Wwfa*}Cy^OJ4{tUQ6418AnfAqEu^2kA&$-ehxx_L!e>)IVqwh?E|Kx^9k#akbY6= zRb_5hLegNl2JSc3AdiSpjr)!8>HWlJ;Du&$Nq+k!c!bvb6>|>@^k;6lTG+}~#@?+g zTYo?D%iRR&xN3rs&YhC|GMRENdvvAtWS zpF}XlPIQ*2#(YA?IWfZ6(}}ygQJ66oPjplRREx%qq7#k3w;|0Lsj{*@c9(r<0_$bG zST=ufO##k27U~Tn@6FcT6P;A8VDNI2t-b~|YIb(^;)xR=RU953&dbYF;I5)c2W3cZ zI%cMuSDuU>Gr;yrGY|x@y)6!lfJ1pFbNZ++E7CMv@9)++RYoRx)NW%_#nwT%dZg|c zcob`nx3@NL<-Z(Ljs(E_B~W45UJ2Q1EKxTde$#U;yme9SWI;^%P(?c|c@>oeF4jzp za%<aVQC>7u3w5@<&5aG0Uqs~~kUOfYNWowtIL%aD9?-aT9QetVrENHFQ$?%G%A zAT9my<$V9?9E$BD6+t&+JNKpKo=7TqWu!+hUsLU&b?^_poaS^>eW;+#zoN%x;4<6csLCX0P*eUBL6zV6uRM^0D--lVP*VKdkCDrtUw7O6c)H7q( z1R=q?)Pn^FJ&QCXKd{z$OXJ%a1+VMH-_w13+@Id@`ke6ugZ6K1*3O>nl~FmA_^2s( zHYRq=?HAE$O;)HAhR5k$wp-t|b@ePPTq?=J(X7oPm=AC1SDpz!RWj4FEcI(!AM`J( zKwNcM6>zo&g`cckZsDeEZ^&tR23Uk+FnBrWSG9R$*hLW?I6)#O{-bG z5``6m*d7i?1)i7Nh$gQusx73*N9CVgsu&Dx-1oJ<3dq;EoD_#YGf?~pvO1gSpN4#Z zLa5UDj$e6vs}I@QwBIAW%0`>^sVg>NghK+!^;@^Z?N;Wj{}k7ln&M*$$IOnbYh@7F z2F*_zRsGq4F!rPY7-h=J_4Npb^r+h%VQTF(sf|##%gOHS!RMQ7Q32WK4R7$-?SuTz zO}pi0Q-{VDD#?Ex%{^g%1Gz-tehWcBOvqkrx6rJ*>Cm5dueH@U`u~R2^Gr! z0f>f*xAKgb_5$)0;bpddWBetMoeW8SPD>i5X@#-wJRR9x$SeEOIPP8x`-WczbH;=9 zSz7I(_QA!TyTi}aqYjFl$xg10KQlgcgrU*`^uXmr&Dx62!iZS4TRXn`qR6Zz=~T8p zrmX~u+8|6(hYUp8p}D0VCfDirX1-W}2M>fZ9d3WoJbw0qitGc)55Mmu`oKwuTSHro zgscbP$UBJVr>O2Km{`M2;Nd3GHK82qlKVly17jF#Y16lqudnOW%r1D|AnH?%xDhvX zv`!w9Kxt;4*XycJ|9$YIyCB{S2~9KO^|!9yT8{VB4$fniB3e&)6)I^)j_v# zhfo+@4m?KLC`Eoc-@m$vcqd7Ta4ZUf%IuCho%Sb=*Vc|#Mfs3HnW2*5yF~u;!Z=X> zguPFOFIp03J?vtfQpvkEJ(2kVW+N^In=8)@#qx)l2CS_BDKxS|+%*C0)5 z?J!>46-N*$XFMbcQ>hORPvg%InO5wVD&Ox8&O{vWiDwjp{-dypo1}$52M32~WqBvk z$x;@B%lPO4=?g|=Rq)Y^=l(^6=YkF%B2yQOArJQ)Be3OJ?ooUFPcq%38uOVTkyfPVvMNGh&AVhjPv`27rC?J;n*-P7ePJ2 zbe6MT>!Uwz1(vTiiN3Se_KJF2a7c7YZ8dgFJzNBF+F53gVQmCdS63}P5NvoJKy-21 zL^(Iy+t!&3g+lb}BADSPd{Z%FdE zRWnNlF(Tq@mP>hAgr{CD<~2BQ(8Gs>)KkPq&ge|BVJA&5LB9Vf4h}c*dnTzi5p;Qy zAUOlId~axvgCp{ufMfaLAQocpm+>@71-tcEcsKZy9tqUuj~^(tabG8obU_uAUeb=+ zqPOQSr<`LIM1!1lt~_T37!H_IaoOd5-xxES`~}KZ6DIq&hTEbMsGjOU#ibZXUb{uK z180=3J4t@*VzLNFD9g-PN^U4Lm5Yl355{_-!#%eGq>|Z!=vcC8f1xr#imvnUL?? z=mK%vUg2zPv3Z^(1cdkC&6%UUw|Ja&1H_l|Lg{6`YMiv?(k?Io0Nn4v{g>vu_6OJ; zZq@m{DhiZ&mPq#3tVp*_)l{;aF0QR7o1=y2k1B+XmwU!HJSoFOlYb6 zy0tgAbRrUWExPu%!-jH?aIw(YTYadAzaFnohSQw!T)G5L_9@3NQ=X?nj;o6>)ac7o zpJ7TdaA2{wHLIqIsv>PCTs2=p0G9EUZ$%ju0M!M&~zE2 zJD8yG_g6a+RR+DY!IdX?UvD;|I4+meNEe>DtnRTzhc;jPxq3t<9~=hWiFU`iJ^A6V zk+XT1Wa99vyTOUPHWv>q5#ho#$oj~M>s}RF>lX02 zjRH{A!gpLRv7U{YU@RRY|5Co{tYeUuciG-?Xvm!Y(I2aZ)N058>P*$z@A!VIbL?`! zP{$yXhUB!1+P!7B{X~Ywf#ZZjn&l(QUrj5O8)n|1`0Qr$-HFx;QNPcJ7DwAH7}P<_ zY7)8mW1>5yLm8uN1Kw=(h@#{jq-UTGCA>Xt8QwZzrznVG?bVnL zRc@kpn}3KxwEJ|nToiXSe)ZM#S8G_4tA*4212@LFxiBvDog zvoeZmBZy4M<**kDhHx$dSA8g3PU}6d?TIXFRr5q}yRqg^%#?Ql&89a^+97F1jkhkbOS~UQTo1kj2%AZCU|dKrlHmZSJ1(%AFOemQli(80nRA$Y_Lg$ z2V!dZAN;CPXDRCfQ$PUUU9*^wCZ!e;bo@>`ps~yY_lW_vQ^7Rs&DN&VUN8!~)^f8KGb3#L?JJFTuwF>B=h(x+&OXDYP}z~t5L0D4~G~hIMAmt##1Lv3_BW0!|6WWaPt{dDy$te98?CQdaT=O zV0MaWI0a=RKRvKrElMk>D-cizGgN_p#>SYXX}f$h8<}TKAQR{fmX2Hl+ZGD8n&$*u@it1*Fd>*LHAkFA(#q8}BKg~3D z-bSG2LYLT@TtwO>oH31ad0sTHxWAFrQ<&|!Ho6?SN_8PG{7kbpoopXr8H-#DSUmmj z+#-N71Bbx~Jz7)Z!2sv?2WkR%MeL=mfGwG$lhwZ)PSJry>rz`l1BGK&5)Q&^Jwsz} z$Ic%1H;%H~&!uHrXardD#!*^Q!lE8B7fU{AjQDB+Srgj9TJfsSDBqok8t_O?&B6>2 z5%3?AMBsby%@|Is9&YBs_+(9nLF=vhP@UdKVCt9ON(2}+1t``#?;C2o2Mjgs`zwQT zDV@CPeM@;pNpLw5wWfd8e$5bv_==4^{u7y^#53%_+lQi>r2xq&*%R`7-TJdne?}gJ zB6r32yioNDEQf8FSowrOl)feG)$0%k1|t;)y(5Pf4I~E67)(f^&kJ-3)0+IY^M-8r zB%=SH=e{{dWT9gRw5g1hqZYXTZpwZBOcq;S0s9Y%(`PnC(*I%l#3uPa zlm$b&H&*b!V!My75+7Wmb;0W=&F`#sGjT>|`m$p$!)h+!bRwgc(_c}Z_ zR_26;fs5zAY$XPisk~~qz+s@ov%~-QH%d<%2I`l zX5v)VqEp#mhrWPj;yxWdB@u# z>dFPThrESR+l8cf7ojBgSw|0H9{4Auf!U9o3|>|tQ&T0oX|O0u17}v{SdHl_JDS$ z*uHeNp{!a%7q=yUrfXMN-uCj$pKxZbKZ4TD!N`9)N1{b)R4G7-j3RsLtDZq_WJxCXTu#uc}eMVI|oAJvd>-v zyEZs~~(x|obmvNzt;+$KvgVsIz3Ej)yHzbd_6%8?{Y zV)5Fnb1TuT_hl{3c`g6Bfq4l7k+|AhxANPSGx7i||KZPh`tzqa4={?BY2o~M@xXjc zQ&w$y;U!ZTLx4FBu?YzSyF5|=KL#One83fy4q#oWw1yLYlB_InGc#;w-PWdTPv8}2 zsQyc)G$8Iv^6Ze1Tg?mZR)1pl+=h_-}=$N5#_o!cYTBwPSFWvjEK!2OOL^M z;#qjrRc3n)>-z(D|LWI(xy#|fmV*=cc*Wi}NrsNpz>UTV1481cNaZ(y->2j)HmJte z7`%-tsGUyeT~psItHEEncz-vq-gKph9jM&XAF#ij>7dw{oJk`%o(!GRFxLP#VP%=~ z;?HlCqbL;Q1-#*I*(U`IpO&31x*9w^EhS=*3;=$Kqvnq^JSI<> zvIW5xrE7Z{?sQ|#=cl6kBT_Q5;<3S_kz!dtQO~)5aj<@wVgLHS0G|4SmhYlLYyJ{Fn!Y;-NCw#mWpZM|%KVhI7jQGI4vD$gD^QCf5r;2-)NUmFM4)qKvnj^di^kx?`+Oj{P8w)UUL zn6ONso!IorH^dI(ym<0DLa*}Ulk_+y5|wgo>VGHYY=q=g3cX>M&Yy`#PE6@z$=aPL zmba4I>CFY*^~re(>6#p5T?+>0i36kDC@sNxIGqvrrvf(e; zuT>~(l|>EucVb279<6C~$n(|>M}A8clUwew5u93_DqMEjTP4A1MkBByp*%|JFakn( z%mA(S|DbwtP=iR-sWH7(MC9%={7;_zm9=HIem+6Yt{UkuT7kRAij9x<2E+!_8nfx6 z`QJ5%iA|)sUaWl{Yc9b2zRvYr*DF1_j{Gb$2u;F1FMYZ0w~Nx}^I2N7So1l#_!z-j z*dj0d8G`3(sc<7!qIJjduU!c2LxBeD6zV!^WW=7lDSz&{GhS~3D*rVx#WygHsSf9A zn@g4aRA(!o=EMjfhB_xd)QdV?w$p)IrNvzitqp}cPZgMPHp;Shn)w*-+A2 zZ6#u3?$4YV(O%@|?Z3iz9^#r%-o$lt>2eS&k2|t46Zf@~m)G@EPVsgq|1j@U%-yKm z_d9Y09-Zs zakv16zPfdL{jJc~vMuYiSD%ydji$oLL||^x=kEL&v09%pNt*6cQE_YX)DRL5SnaCR zbG%$}LzQ(4`pYyy;pP!7=ef(+)c8mO`X8Hm0*~IVfu9pCch((c>~wQW(j^2jGWz=Z z2(X`lIY2tQL(y~W9mD|Z3QOh>H*6}4PbEQdFI5)}FbWCug@Bq@U87Q~E2^~z?pfSk zMQaIeRtG=o2;e0RTTV78366sJs$xx+lh4dv4+yh z4vbAvXTIr$or&O_tHo-xQ#WRk3fExmw|iyp7L`g`YQy3H;s^W))^k;MHQ3_p}~d>5L1Nq_?` zuT#w`9Unh`F0ZwY6i>6(NGjwB$R2B^xLHa<-%Z^3d*ppKPc@!~2uO^Mk%s5}b)BgU zR5TapZI-+*6}lURQHtcwkkxDZ z`ED+!5=KENk1-%0A0JuX=RY2%g>gkiq-oM5)XH0O%+*q<+gDE?;oJW6zKsXX8>sjJU4(_ z4P1%Bcf(l-)J%*f@@{g4^?EfA^$Xsc(J5)(CHYqrM1|0K8LBd6-;$w&JitNjPlTC+ zkzhiu3{I=~FRtE@7|0HgHjWb#68ismM7_$pql?xZ(PeHMN|8jBsYQ)|M5F)1?gugT*N-KAzvk<|`lHhxhM@ zo157dPp13&`Q+rFwJK3Z$>HeMPJ7OoNQe3uAy|R&gQqt;S8Tw@h+f)rH|)H^CukV* zvi<`HyLr_I6(#C#-##J52F)Jy*1%9i1p8EWHtaY(NpPZqGBC5e-!{%4T54?diCtaO zp+^)p*K`e-6e zqi`gS=7J*-2)PoIl0*UW(4VI&IsN}j6c`F&axl5+smT@?C-|n~`b}A=1al(Z@pZ(7 zb1N^ePVdc&#+Mh3TO0qwhw$o^x6F2iNbB6TtGB1*X)4v49ad+HAYOjFZ*jcMdL&a* zm$_4R^=VutOE_^260l#t^h`5?!>pX#=A2k%V_7DiG~{>jXYmG0&GM6pkSRlloDll6 zUVKwea2)6C!a7OLQNs&{ZVj)_ueW|nmrwy?BLW_azLQ0HFY?aDeu?E_kO?T z1AXp71iwgTaE6r4j>*|Tk@1P+;@Pj{%aOUcb2aCcnupg z%_M&c5yZq!|1M_=(R-XlVl}+363L`aA5A#Fga0KY*Zf`OpdT?v7ROWs$&^^qq~}Zq zOsu7qL6mIRAVxtMwxzZEWF9)GoiG-o1*eZu)BndexY_W@1qs3#-xbUD0)B@ryZ#F| zefMh&#K4zV_xNPPVA1t@jUpTeepR6?0 zd!WnP<{17hKb+Spno4ZgjYrcy!>8`fA#n)bV2wDtqCOCIU}a`Lx>&_GwXy>1V_E*KhCtw- z_ON4T(>@%xTTiz8Lol#>de0Zzp)_B@g@fv42)}GC>PG^@qvZZtSUQD30^A^q4 z?gY6J@+nQpmQ*N_pkhM>l8yU+I%LL_Nx5)3I6D*M_wCtbo6eh4 z`139}5^i3(iRRC^wBrB)UCTO9R+I#*p`pAunh=SvKzi6)NdF8KCSb^bG9-D}V6l!Y za79y$5|YE2n5x;4=MRg^ z_%087aL~TrNWN=*_a!EJCx#!L)!3N$0e0DCC!9sJaCT{-^K4Szvz;!h4j0DJk+{A- zUjlYz`&Y(bMs25UU@z}r8&AIG31iVyu{(@hNk9KwLUuoYebZ{Cd=-0uneCf``Ljo| zcD%SE=`Akgk@2BqGP!99a5Q^GJ}N*JhjowNaW9-bs-L3Q+c299n3YtvP)=w)BB~=H?V@ zYipkG$$ct%)vc2)R*c%2&pOQ8l~P$i0Y#oicFjd4CHOdzz!57g4V{>fhRZ!So@$N^ zAKlyb!yP-Hkx1CRe(-Q`AWY(10%*JmJ~wXdKx%*I3&tz`2UaB~CkHkWFCMSEJ4bta zJ9H$bl*#Xw2#JMqxlYs4vyuha5dUPPwl5(S`O#k(r8b?^L5j}JNsNZ%9|bONIWXA{ zi*jv0is9oF)|Lhq%cIWx`X$Jo4v=b5AKNCv!!an7^6Ys;7BqG^5$DS_VVZ}85XCjq z*?ynVgU;~O8|LSdn++ViUsR!5bqxA{UVAOA)YImtpqAu|zwY~+-8$K1r<`RTN){}8 z%AY8da5eI0FS^6!XBNj405O-&jnwyW6BOAdIs5cNQlRGKbWtm!wQUZW0A_wEaFgc^8 z9m5%+;3t$n_z~0I>@2EOwk#%Axez*dL=-PR0~~&Hb91NK9wEioz(>n}}QiP%08faU` z%hSDQ7#sUHt#1J$uQee@ulCqrvm^<&GtcPHw@WPGE-t+s9ye+FPjP4H9E9z_Q0*7% zIlGI&2tozM@}*1C(u$S7nYUM&1S!Ya$5PlPyB!wS{ZkoQ``vi^8hMh%n@Ezyd*9Tk z%}+&;DIcn0FZwBPafQk?}^VErIt>zP#fp0pB|{YP^wip*lc0{HytgnjSu?a>7i605w?iLJ(#W1Ycb=Y)TnBBZ zgCaH`SQ=($mirs2Iio=t?h!35Ez|7Jd{GYVFSKv3zXsVr`XXP*)y$7A_Rp3%D>Ph4 z?Vo8uEs$C)TrLAM5+m=WCOsl~#?%K$f~aIabnjH=UpOM&CE?`#SCxl$ree3#72V^M zJo}PgxUKSMb%ApB4=3H$oV`6Mipt(Rh1k;4k`4T0f~X{MY@Qq$P?rG`umfc`dQK(F*s^LvX-No>!TF0UTlaM3>Ue)kbFZepn~ zSf1DZ8fQvA85uahcv~Rx-(hiZaM<5z15U%h8-Rh3C}Gccz>jU{TM(Xq*Urt4I4tjN zr*#*3J$$iiV$thcdTXtpEbF59{*D!Z<50oiSUUm`GTsu#4GLsHQ|Jt)OAQdcCwuK{ zCl1$r2hxQ1QzG2_K*j>>e^+W*hH<7cO*A_=)72|VG2JGA)tgh1sZkmO&eagwS#laM zO`S2lo*%5TgSlQD&XS%dM(jQ?9AGYhh zil>kRk$8O%2nJQ4FHBhHRW>a_u-0wS3)aa_cve?l^PR!_Ul^<&TFH~;C)hje49%l$t8t51|kh2GfWaVK9 zUb%*KrhByW9?10Qe(6l@;dgqY{qgPF&Rt~rPIF>|ywh{O z$5kq-twTUy^WNu<7u>UpY4wi2kJ0V%yNZ9+xPP8uc0#gm6%~&=6%-Y#0SP8KzhP1f z-drk>v5-RhO{}da^Cdzh4#mmrixo5xbC0NrC858oQ}~FFjFuA`PT^MFl4Rz`$^BrA zo{6bDkX$B*Poonphyl7AZ8(U?$jH3h#cJ{pS0GG}^C>vn%t(UBUk4{Adqufr9Sp+; zS`H5{Uc{1B2FA|LEJ(zXybI-brJCGLXo;f%gZkl2wmF--vF^&i0`Qw)eyxNyuT zfXu{+LxK}IJ3lW>i9*53a@*;^9B5{ixX(|~?O}>WtFS6|b0{$ru&8Nz$S|>`{V}!o9qIT~uh{i^LhK~!PpzVQ zS)n9A8F^M8DtyU5*Fr_4umH7R!`<3O`0B(*K8I2&Ky^_nSi(Qe)4)g-q!`KKD) zuAxcUFO6?HacI$j|$Mk@k~oZ~cI!{=f<*%XjZzk`<4a#(xwz zP`I*A)endp`yw=+Asp8C$_co(xXNDpz0YnJLK=6KZzJ{AuW>XUJE&M!V>fA8&eadu z>JNJZ)^<;h3)KT2@$MDvKISiz=VzgZsx_O9oER!SY^WK1amjnleTC4t12Op`m%YaD z37(foX|%mk&&`gUb&lvPG8$t+ko;s2=a=ZK z&5t4qCtfituX~X15MQEdi7mE$X}r_kQrs9yt+j)X)`A{RE9E39UG%t(yv`L+xUM@L zu-#EmJq;k`NlXc~Jd&X*?&;1nJV}%_o!GPJoYDBmAWf~szp zcg_bkcAA6Mcl+Xdy^{a+L=F@VwxMOGg%=wp;o1bzM*KZnQDKo{TT*;$F6zLe4 zmbU|(MoLp*dm6WkM)iX8qHuxC3pVSSM&W&B2?o@|Unx0~QImtrvqOinKXZ!loTZHW z7X<@4;zY-E<89rB>q%oV1j3|W)*I2=rm{X#f^kcGiy#Vn{7D^P9g;# zL$J)XErliV6b|wvMe0lRXVF9=j29~&fL;{tIwgmpSWAM8RZ4R3?NhWQwG6#8KV~ZN z(X|;_8-u6lT2=##Unk3OgFxZltymP;N2^tZpW;!#G~*|v)*Urn^-n83Ofc_3kHI9A zVlDL)f!~cTWw;{XL`w;)WP0A4OOk~S#OsJ7^&0B^E-^pIw0Lq2t@a?DJOJ@u8)ogwX1q()fpm)eGXrW5L z>z-LPXZ?I?Gh=hQl4do2x;rJ0$SWJGVd=~LYg~mh%-nU&=wsZYCT>!z2$9!pVeywv z7$Lfs5cz+X0k{aHzAYq+FG^i4;y1IIuZ)SBPUwvrUK~KW)p&gvEh;Yu(x^1o&983} zYW<1U56qdxi2UkMg60HFLyPSI1E(#()>(myTRSBn6xBYDrnj`Yo*SX_p19*-%5~M_ z1h%d5!QSJoRb=zTEk*lcyW$YH1F&qs1_ z*moY!9opxhA4q%p%RM`+dNq;WI9^zep~l&|H6NxTn}4QOwE75nna@gCy&)uhTyC_^ z_FUJs@Z5J?XNc6F57s97>p}IezJ=Z|bT%^9<)pbUxf6s812In6=Yr{C`!i!%E2m^N z%U{rp*4B&F^l#=i&mBLmfGqihY|jrEiwUmqAOqqPWN6VfHAGsjZ*Qz?@g!0aV{ zCSR4)1n*edE{8D-%Hq+#t32OMKPHM6jS?^TofBFki(ZR5VWeh)Az$DFCrzMFk4&Ii_gb%R_4UQ%d*Qbv#NKS1p12@ zXaipCH{K?LUl?|uJ&j@KF{znMEPl}*!qpjBE^Z^k?3sDCM@z*Y5{-g$1egl=NelR8 zAmuqa8dep%a+&vl$=7nJ5z}x?{M0K`T}Lu65%DA#-vNmuNytSA`cRHhqWHFNTro7O_3bdIz zxrFA9?00!&Jo4Shl*VXCmN*iatt%+mO2q`hw=gcm^%^6C!Irk0`^yJ>fB0RB1|jUv-nzsezU)-P3?%k@o>v#dE*NIp zqFD;QnM=w^S-D@Ba@y1M@F7P|pKJs6zAaXdcf&l>-5<+0EQ9A~mF_JTZM0$WAN+(3~Q`T7G&GVct`{|U%)dzl+A zlpBu|95teCH9zX?`_MaOFB&ftceG6?o2T@Y<;d|?WmGMvL( z@4Y8C$2X7=87G;o_#epiKi5j+YjBulPl6nR!p4k@Ttqs{Dh-!KwOzgH2NRDp!X+r< zV!3#0(fWk43}G})+L`mKgBh@4YPij;zTJ{xn(%4l*Dn#`cO$N=XrheAXpIcUp-S3* zBE`Q2hK{}uyD}8yg_r*vbIIAxGY7lTZjM>#iY~HUT!xB%D&TAm5Ym!gR4kW}m0`6+ zJ-$i=9S`8$p`~-j)12AM`&rTQq4Ggzxzg*XlJT4d##8*1gIj3hO&lwRKIE-0GOij; zxnf93XnMhyFT=c71d0p=F)@EXv%(a-_J<}<#?1W4g+WP%)F1-nuMtK&KMGwbyzIkN zx0}^zH6qjp0z*(sfoI^n>GTVBE>6$FFzyfgs?L&viTbHYERbtf17AQei}FZ()^CMk7?Ft&e;e&BFWCL|#Uog!tY7 zvaw6D&L43^YlWf~IK%;W=n7o+nbBG6SizDfV$t~}rFosUW=1-Dx#>S;d#J?|GrtBP z-Kh&2t0(@dv3j=r%`_6(cp3RF`@)-=y+Rvbj$K3jAHW}m5++1=4ehM^-M>UJd!#1d z)i##@O8TD`J&;U?fKG1kY^@z!RYidgPZDB0TcVIwG7N}6qzeTIme^b+*Z3CS{OU?< z1(ZWp4Zi3M5-5yb-BV=`#Bt?XtjR!xfZqpewEY7j4H?AKx!%K@%lIRX3H_t!3TQgw zodWr9vwjA>urp%%zj|fV-M`&ukGigW!qo5SJJ*lz^!RvC^+aaH6gOiJ9r4j%X;P1o zGW!C<|FL=Ux{pxg=U9{^*kv%NF4Slf;H~$^?Kt%A3Azy$9ik3lcJ*<;3+3#+R~-#t zF!s^?a-hj%L1MMGe(qw3`!77@Ec{dGrb8W{KS?&5H(qqc_9j7|DxJj-I#V@MSlGkE z!|;lSJl|jhi~h0PwoM~J(^_2}J%e9FWq6}gzH9aT0&qB-VF7&Ob>;h*qfe+=7s=FN zRi=&`HZ}Ksa+eR}Ggud`=GQ6b6G^cVAvclkI&a!|No^uxPhJiUJC(e)jEm!{4G22A z-P!gMQOufbInOCK#szb~D6pAUMoHhD7113lqzD-MHSW{H*)j2{RZQem47{pmi`HxB zRU4j`bgffU54C@_@6xZSNB_xI%lr9NW;vd94z;`SkP|f1jxh4Xt3s;5vaY=S4;e(Z zL-r0_URxXAOEsDRbl$xl_fpdV2M%|4_mDmlPKQ+h>)g%uST_NdLQmE^@n+foo$^Yv zV`*`5aX=t1B>Co5I1OE+>h+guY=4{Nz^T_SBhTp-mAfM7r2H1@i0VkvEwGYVP&f^p z&%Anuk5qbA6K0_Frv%`NRtA@qZ622965a{^zlrlX@(C9#enU+XAHq)}J|`Q0XD!fQ z=#1F+yO{nHWJ3p{+Z)2M$&4;;+^87$36%HHTV7OXai{)E3U(LQ_!pP(zcRPGsBIGo zosU}t!|ES!7Y62eY;=y&@QW-2HPV=6OBFMplhTifw&VvP;n)JT?t`E+8dUqj6$GM* zF_J9wLukdO*lsSR5<6en^m7#ok=aYx8hL-H+uO~7E96iS_w~pzQeUfpA#?%yZ+lxu ztt@JHO3l+}#nvNzt_(!=?dD+vnZ))wC0cjpc+i+2?(3RXlC;JN*8lrzp}=$scLEg$ zgf_7Ioa_G20O^~%gw>sxSOA6F9jwa4s**q88~Mw2HRJT<`u=?o#i-i!kpPP=0JcgW z7^pn#rkTb5ccKE!Z_Eb^P7bn7Ox5jz~1zBq>D6j{uY_P`3%g(t<26f1q% zoh@B5FP_{JYx$U#2Zv;!WNJR--X;4;{+D@4$q-~h<@9APrO$Ew@B1&84YA$ccAdu( z8)+JZ1n_``Z>aRR#mX_qk_4+}0`qajOC! zAr3;V>z0(zy=mo^%~y^#0-~4~{RD;1j8y4Ehm^~-eRItCpJy~(47uvoREp;(?*CrR zK%lW$K8*Obs5y+hSdib6_kKPBt$pG~EuCP(B1m93flFjn10bO$&gUMigja%IX7T*n zwIB!*goz>Hh`H^VRze)QSNLe;73IzxQ|6o<7ELcj;GFmh>mNULa@x$)t8J z|BIr=6`xbd-&o^5LqSU7foybqFa>i=zW|C8Mcd(k)0O(mmQs}KW!-#*Rx@g7#Q z%cRq%j{&PgA3fca&bBS$&U)S?RS}1-Fx1!$=n3$=g4|K!9U@K|y;JvPul6+)n5OB5 z?*&2=wl!f*?8(f(ddSdYnqBPZeQ-tQp?;o2czjlE;l!6hx$Gm ze_L@x`RQaL<**v~REZpd3Vue`gQfkTo$+drMd-B~@8<6QB}Ve_=xDig$c5PqMCmzP zs+9eX;Uio^A$kUr%m$n=VgASR|K3}`j}IGrvJ~-)Sv|I48u(*EwHnq}ANzV@QNLV7 zuO23}Lp6sd8fEi40u?9euLbW+(r&ew?M3&ZB=VUcVQS$r`jGD^%!}AR>(={ssBQTcqVLXsL>&vutQYZqScFWIT>xQT&@8BozLUYhO zjaifmsr$KER1aWDx^KSOl@jy}_1w%VD_gtNc^FD%7 zusj11T7T%ZCdXYn`#wN#$o!umgZV@jAI)j$uIV%uUrL-WO0y$?6(K2nQ zBE$(dp$5S?ext*9%xKoUs_>IXn)-8ZnmI8Y`E(BTzBt;f*{~X4Ajs@%x~G|;cq;Lh z+-C0X5W^a~6uD$N#d`+9hO%U#3Tb@h7yROLs>~0hn{iKGH9Sxpe#cXoHzW+9^j&la zM5zn-<2J{b;~82}+N`Q6qxxQ}f_pv^hehSDX_V|^vS>Vf-Qx(V+jNP)4-+W!;EZbz zu}RzQ*@a48TmCjsP85e0iw}}}{w65=4ktg`&sykV4{&FBx57;96If;u&!Cm@=T;tNA zP1Q9oJ@=|#spoTlR))lQD0m_5-c2nMj|5HvZ7*V#;cVXtd1EoWoupX7f)bko8_lCR#qwR?QhBSP(EY`m zSpMTYl$X@*;P9q?tM{t6=^;h(PE*%ryC|I;zGDXyKQ%CtjqZmKgLm~~@L4KK29+w~ z$RT>Rcmyhj*fT$idM&r^NySwsnat9%fciLZq8>z*irFiOOUY91@s3J~WCN1vAwPB3hOh*)(cOA#6u5t|2;Hh zpfp?sN_p(LE``Y}^$yt& zQ$9~dsap*%>dUmB)QOvV(yKU-Bk_x%B(XTn%m&&eYF>%Kq%MXM39$%BMsC5WpE6Ki zcm8)5Ap5Im4f$r046*Ux=s8-FJ-dbp7MIe%aajc(DQW55Yi{mm%v>}qN;)GK1ofngN&ZeOE_@o6d_J3P8uI9 z`~BRWU98@_%XX%Yp7MLNFx#C%oE`AopYU%W-Dd;rg9eD>JZ_AQJWXPjCFDJQRl)yWYIE7W4FlB{$kTt9eDdUkvzF8vExubwZv> z8u->4pD`gT8uZBExVP%>|7~mWTd;e7%8s|eGo%aua4G%_Tk&32c$1x7WS9GAf_{U( zx7tausV&$cf&6)F2R(fZB6W*2ThRbRPB+eEu`v)juY%;oPoTLd>oXlQR)M( zVbg)+NpJIR%mk2#<_^o4Or`*xgE6)$mZN&CDR%Qc2e~Lo*N6j?jQO!#$Ki!7S$qoB zdlY1JoW)%3HKOONSkCgf^FMhwxY)$As>O;Jkx)MXxJmG4N-WFoZi#H!qs@cYQQ!`< z13@3L+RnX0j~kPfJEwa@=Gp;oBiIZ9-nbikef}8~gGZa-V=U*19jxm=Mw+$cmHs_+ z|1Dc~(w}hQVxFG>u#&%ZrslW)@VfqGsa>3s6^;=EnMqz~gT5*Y_&&LGfV`1hhC${G z>W+iRpp*-hBwiSdck;A2P9_OcUc&a>pL9u;{<^}s3f5S2bn8K3sD-BLVI1!yDl z*cOAe*bzd+HfTASY>+@Q5re+FM)W{H;aBL!`bjHvg^La;e;c&U`%PR^# z?yfqo-~)D==)n2>E!+i*Ivf9+=NgNnx(5XW-IDAeZ9WUbz^48j*)VTCenZ0Napa7` zTu2!HHcDZ=Ha}1p@WdzdI!FT*yYaMpZeuN&D`%-QFtzgbME%}wpY&WB4Y70ysr0hp z7MuGZmE(J;dz2bBU*q-PI@vUG*r5H^!5vyEmXcDChgIHaoGkM7jI8Q5 zU)hF*KjowOw}rJTY&E2@mI!c+gU-2WJV-!O(aXxqA+uze5+cJk6TzDxb2n}P6MT0n zy?Z1`v!U1R;nNY6tmud7*`(tH^|M^W%%-y^62r#Oi(;S;Melus|KeNJkzGM!v4q(z z==h+UaizVjdLobV-us5(nJ+1(<+Edx*l-~X@T6mmZcLDp=qFK7Bs~2Fxkp+Mr=o~4nuBVv{`chNoHwzQH*Bc{K zt#ak&hi1a7gSa}nfm|eK6-)M9h%-EajxcnR^IRASiLw`)@-d5jrDI#Q} zB@XW#%h!9plzW8f8+pyUH^se8YVA?47vj_>iT_*hK{&Q=>|4h||6`e4nRW{oEHh3i zmOx5h;JxW5%z2qyf8*xD3tBm1^5eziK7dar@%FB~YP$148Sqoirdd*Rw+SFSO@Lcu-ZwmHzIBF@`5a!mFlV|sj&1XJQ=~ah_&!{B7m_Hu6O$VF- zE!gV6Hx)ZwymK!}Zz^QaesWDxl#-iMAVNy@K-qonfFv8bITOx=3sz)ypJ4TQw}1)MVGPgt{&$h zad7J?+}m4Kah5LQk4yW?=N<dnNn7=EW)tjBed@ckMK~;2(1r3^DrQHeVK)_F6vg6i9)bS<0#I={-=PR(eptb$F|0RTP%m&l1be|Wz-bmvDwiQH{1 zAz7ED;8d61d`9jYG=0w*R6>7eE+PRWW7=H(NBb_{L3DQEGykk1BB99HZb5>{Xf$rK zL4r!ZOI}5t6ovq_vV)AwuHmKdR)|D~Z~kK%t8Qzb=&zvYH&gh8OA0y`lPu4+vR`)R zEu$@>9{!Zlwd}sX4K6D3etO3{_M&zdY$hU5emD4Ehyz%s7XM8k>KS6tm?#@SaefWp zan_@1KT(sGT)J625aSMO7i6UGi%7DF7E{VBf322U_)7(e&#bLww=;zZqv>{O+1=6F zlYA0IYjypx5$Nl^=#^%iPM0@jh>4JE^t3t2A%In?SyUC>4PiI57}eHo$?jjYW06Yi3f@tFcNJ%K(l5(6$0 zgR+r*ggRfu@+y5<4HrSN&$B7QyfyoXfrn17<)h27pZ8ueG>V}0%%8I9DdX%!4qIp; zm}2pApgj00UO1fUp5SEHY5~-Dw#RwNl~MkOSH0E>k)Id4G##m|={QQ3i%0TV zobkpz=gZmrE<34z9#pA_1Q|lKzO`0_Hh&f9AwUrGrD$FwXXF)(H@IW*Q}wzFQX4+Q zB0PxWd^Jv+(h`*>i?t>7^v**Y;ge<-(D%L zhA2P=2=d2Vq9&XX4FZKeryuAYjrILeg;Wl{XPQ=n?=y$6YXp2!{_m;T(t)8RGVdvN z1}dS`o6|fcs>LVvT-!f0}w-h;|V`P#%+nf%gD#tLvn1%P3f%5^ji5H zsI2ouTxn5GtGCDRFUOeiawREN@XA3P7pgmW$lU(95o{d!jPhdXoN`7Goh4nxViOAw zs$<3YU95JRQx+!(>g19wUbT|}Z7hp63apCcGp-zGJyS>M;_9`W zI@X;QB`R+3CMq#{%16x3oYd58c}mQZXQa%-X_I2m$CumeoX|3bimD|1oAXETfBNIJ zXfP&tB@M!22$F~1a+#iA9@zjS+131?)Eu5>@FyyB$E3PmAdNc9Qt-N*sM|P`l&E;? z6?syJgw+IuOgp=F7K)0o>9!CLJ7qe8#J(({zj&T?J-*$?<9FL0mUy3%{ zQ#VG$ZiRNxwq#4fCim74-ouq98J~7IRc^wAR>u+IgeG2&1AZ}-Do8>|UgKA{IWPq1 zbw#Ve_z6-n1hk|~@@q_rDXsRzTR<~aK62RBYhkooW)D(O1*A&hO&FhK(d4+pnTpi79*xU+>!Cqs1_8f1!=|!5NmIGh+w8bo#>P#?)oTo?*6+ z-EXB6#Zu|)>cWD>*~vLSEb= z&Cht6#IMb6p7}}rh?*^a*29!%v%3TQs@xOl8OD_*{Z6kbHBNjxm7}DR;xhXTG5gu9 zPD<5mbm{p@_PIJ#=OUVUzidH*v(*W4T8;#YrK?VW(B*q-yWq1uh{vbX*`}OyCsnHq z3~tIQ>L=`#l<`WT}CNKNI&a@A$(g%GFjhFiTKm!H_e2)d46VGRRL*JLnAWo8~*zZ4mUTyja^>S4v zTT7q*R`Df^tzEQrir!6K`lBREX>GH${kdAC^1NGPPlUm@$9=zwnRK1Gq;Yt7Ie#3p zk8`;~QQTj3b=c<<3JBS$;R{|0#MU!hQ}mn;5;PkIgo_@QTeGhJ+R$fY`aQ<|$Z~xS zt$bZ^QB3FjQ_phfup-$8VolCLKXt4zJI!t13^@VW)5DGjJvaL>i6VBXMW^ zFJ_Ew1RPR|I#4vmDUN{HacpSDiHxN$9nqIeo7Hq|QyLrcxkj3#4L zajVlP+*6ppj0Y8?=lC!beu4e;eZZ$|M13pn@$m3a z67tDK(XdOVsRnE`;*&#Geg1^I6(N!-qq>AY;RgWRJCk%j%+}p1>Oa*=acWZMS|7ic z6*f5DX(r-k$ceeZiAxG|3izBr5-D*}l|^VjJKBF~<#E};6ewM- zSe~?RV+oa^Odz3lD`Me|z~i$3F`TW*9J@SB?pE)%=t=l2$GM3hCAWCd#Wk zvmRfYD)>S%64%6e-JJ_E1Ky`w5Eno-b$9;>3}NOg)&LAMoL=n%F5Ybxxk3G)0kQgG zwSr~yH23Sx%f0eh>6ysN3+v%5V;}!6)He#%%r!I})PT(8hFd}%+zn~_wwT+%*4A}! zljl5VcXZcd@|WDW%Rx_?V_jPJC%^|N9SM)~q>yYm0Gp|1D^QpciZE{eXmYG6I0Y3E zN?r{|J#<@m^V^p)pGcqHj~{;)f+O7T*X5M7urk(8+?1wEE^CQ8dZkt^T27#uA(rJ+ z47@&dcb-^N`d4M3_+853yV`w=4TKR}bpLEY|MVg&csX6;GL)OMx#94FQOj3zaH5ks zl@NOo80E0Lah^808}v{*T-_}=VHTb>pk>Kt=)J*@nM<%=F!Vm?o{M)f+>-WOd;Bm* z#AJ0Bg6=xe7Nj(8B>tvkAo3V-;8gpSODWrj_PPTK@&DU~8RXE73bXtAJ(onfXG>bj zs?M1{q;On&RFX;#r~LqExXmoGKg5`^zWg}+L7*N%%Wsl>zp_rHl1_|`SeLmbO~XGhgjCz!y7Qevj^rfiS-0P_C*rER6ELme zR{|=hszXf=Nt*Nx%GHp8!omL1%>09HmQOz&-Y=B)*K#A=(NS~|dwJI*#!aqYCvnX3Zgmlj zi>e4NFx!;0cN5EHr^SD;nY&b9&?r`XuIr`>MKPCGBTH|1Q)*T#RTX80JG}X8^btT* z?*xIZ3<4xdMm@=)Fr>etQ?v8Q&oNy2)eh!RZTpwSLY>*&c(7JVO;Mpn0XZHgUP^5l z8*e)ZZg?L^KVV(lt_oVc{ET4BGJ8_o-yeTuk&qDJa`fczafJW>Z&bu7Q@LL6`#xsL zSiPo=TVW8{ecP#d=34-C5c7vy70nhXP-fgBcEIBguoZ+Wzc~bgl>dZ7`}VcUkxEJ( zc{1vAqUVz^?F*x;fp<1WGY1#6s;+5$e+B<+KiJRDYk{QZ3iA)$+iy5RuCou|vg(>@shB zF0hm%5YxkzW*cw4a1O7Eh2M3w z)>esXsh9eQ+dE12LS4Y@Zem#p_#d8?_iw7i)4U3qG1%U`7M3pkElEAw8G1k@13=#vNQPLZKF}2&tv1}2*B5$bAW}s9RH_7 zlk@+9+W}PP-R@|)pJuOg>h!EuG8S0q`@~%iBH4kovr@%yZ~I5ES#Ls)P(3a zw&^LEpp*?cZ_>_WBV_thx?uZ{Ix#bgE8JY2^3pdo6bbm$gf7kr@d^f4y3S;Bp9I)| zq?9U}k}B3=re)auuHm!)UNrf6&HOkV%6t3++5~X1r)+{><;y<;K&p{KORI{S90K7^=rogV-hF+y~AI}VZ7N-*#f2Tws z>oQ-G^!+5_ewUo(4~0)XT)*9+VY__I^_#FOw@;dPNU5=3XftG=^`|^aRqdtLmdQiq ziz6=_hx3i4m57y7OIz2VtH`P(96lRsOfuB6zMeC{K`72VnFDn;z6n3hrLkqVCPg7E zwnW~Yb#A6pEWT8@N$abPj;)+7Uvis^1aGqgz__pOI0ryPU_BF%Z2)-pP$TL-?fH2# zWjip*yaYH~7avLE;kdKdrpqW)?elSCzM`*c0gb1GQIaqNX`S_#($n?M8Wb~q(%vDb zrBm6A|I?KA$OBI*;w{4NY*{|JG=Y^(8lWTPE5mNM5xspCN*tk#XGSHD7FR?qF^4Dl zRK=&~JhbM?jzZ9bjH#Yd?`0Kqh$BOdZGPRvP2%x=IB*#DV}9Ld#zVj|=?lD05L>*= zk70ACR`~9_zvJ2pz=8?DzF+oPzVzhsrk-h;7{=`PRals^#) zqObrf`-ItSmb|~H!D+?iSZ`Hyd8T32XKUS1Rkwon;<^u=njw^N^};qYgtzLME-*<$ zVS8{v9QlKo{PvIWD9oV>a$E9o>y-MJH*Qx+D@nGQ=&wt;r9|G=>}&^FHI|ZB*6RSZ zINEL#w=4%X!!L}Wq^5?=Vcu!%dpy1@YtEdFLu{SpIGpiYyUG%qSX6gW z@eQqY=RltZG2TzcRHu2w%%#bR7xhM^>_pB30+L`UWXF;PT*`8KyR>bG^OY~05#s81 zCo)!g&tJbTJ0|?jP0t`I3G0&_{!rcrCma*QW#;e)@{b6pra9vDQp-ke<+RA7->8s5 z;P=+1rFTcnuVl5DHg%c#!_|r^``?cz$XY$f+G{4|>NP1+jXu|AkY%bGli5}Q zT_PXc7BN^ZDL*Txw+70{knDlXEk=X=h+Qj*9Tk%wt?*Ggvf9{-jUf;Tt^0`TF9IM4 z02YsI({NYU)U;fg=2YiYcD;f`N)5xl(PZUTAAb1FO_i)$jf1=yh1Mw3w%I{3(XoPDV2fkbB>Sl2kCo|8 z^9GG=b7C4+ekHG}e#7(NElpe1C_}224%hR{7P#-!8<~k5n7j*aS&tQG3tfC3(0}Tw z6s)X*{GL0+NtcV#!SUZ^sm<$Lt+qh7;6L+ayXu8^o_L4gwG_3O*KA2KqrrMw39#zrKbm0hhG*%sZbA@)lhOj=_|n?B;I^7Qxf(9fgkFvg=s z{Ox~^TS(I^;mzFoa}G&EK5M}tAShWN(N(fQH@HT1;**4=)pob~)oKy<=IrBkW=qcO)7%2{BtJEG5H!cFKJZT59U@pvcG)8|uiQ zEtc=c&iv~T!*aBTNid_4TbG^yo$=$#hjQ8qmtOJiNyqS?B@qsPixOxgXUG6Df@v+b zZcJD{ZZvB~)e*k_&X%YKlC2)b0xdKal%OUTm6t!U%+7`nT!TOlQAWe$7>zRB;_^vEDH_ZF2J-#b z59?v3Hq=X?A8vVHRdF6rk-~`*WBqoNC{9-F$rz;mEb#FwuZQ ze|e`TJ>m#izpo1Ow3@iFLawl$Ej>H+NIi$w1Vn9)8nq;Z^>wOzzsWO4lE&U|jZO7h z@9Bx?g?brmMnR+`PpMJrN`>3W5AJp2j0~-q{`;A!^QN$sZ;Ex7L*XU;LcQ;eNgYak zmYk;WL#Xy$5u`gZPN9mg!ZD@~jwo#HrfTp(p6WV3aLhnL9M4e5Yx$M!V;5|_yP zLkRK?yqF4;fBBHoD8rk&?h2g)u0M6^*b*wXjY%;#88QGHZyX!t-W(0fhkKsUe zL9~Gj!MFfBdpcfaP;$t++|Kk5zT~32Vm7~oBl?YQ6ap5A@>6YzNdY;ATb!bW1qC4e z_U8}xp(iG0XR1$x6k3@qg^Xjuh%izL&cQYw7K?kL=gW;7O1g!WV=6C=c4)Cd6|Y8G z1`&w2%BOqbw&cXCk$pnvyKZFc4-xJfitF|7DQKq6R+dF)D+d(#O??Y5JY|YMap7@7 zL@Beghff~&Lcod~V6=i>aqXj=n2e1XF0c1g3&taQ^m1MSr_FC4OXbwrdBp?XWx%41 z^!zEIFzxMKYJufH;8Yk8)XJ4ZwHL^R8GhA`1s%|h%$+-_qq~oIfZ$2`lVx*|ft~En zraXMBrOOz~@rN~Zb_Ns;AU~crR>ztEJ|Xy*?`*a84OO~*kM##rw2;;rgCkAJfcDWK z+76(YGMIShs~UGGqICSAAS755XU-}@3uh*SvhRdAT30qji_JAig`5KDV5Hv>?S+|a zYQ3hVL?mcpD@D6*twOwwKe-kqCbr_Il>BPP!S?WK{0bM z!Q_Q~;!F}U4``K!e$a-Q@2!q2R#UiNs}-=yc}ez7M^V&J_6*J%&c?Om$QTyfZ)j>J z|F&#tR_uPAATUX6j~uHX&y73!2+sc@!)=Fdw}cmAy~NqghNKpyQP^fx*i;N-6GgbC z?3CDWlO4LhZ~66fIoZ`PAV3HP8DF~yBLaMLpPSeHzH7>4HtZy-R(g~)wg>_J$M1%%RL=JV~g7SpEhOdpov zokD=bzYCeZ&8dRIWQRUPuPOoZ_ukp=gUrJ7f~(rB!pp^KoQ{e!mhF+2i~lZU#^lg& zA{88TFrY*SoXBZwHfD5eY{J59(FCOo9*try=M;>FcL(xx23mWi7CL#~ViiZ^;}>Sr z1QVyXR1jy8$&%A-B-Pu&|zu5xS< zm*Si)_)!*+8nYwS!<~#8Y9b_h9J&WJqZ6V8aiB|o|mMrNEi=L z{^b?rItCjf#eZP2wu80HMPqd2ma)Zg)XI?Nu2%C5sytg9-=O9~XTETbf-p{yHL@d> z$YwLX(x`(oOcFgHM;r)>wYJoL%(ihERk#!UiWXIG2Q(QsoR!WNmR5=teGEK|t0f!k zFhKN}RvUs$r>8bw&u)~K9hyu){v4qErLqYtkMAJ6j`Ux_M45Nb-OGSvHC?Fzll1(d ze){okLF<1iX4wgs}!}ZHLUaBU2s9%c#^yL&A1XILCd0BDE89LQTq$&!eND z?g@tGRn-MfsW`$<>|V@`FCb4>Rk^ru-MNTjN^Rrd zxHK{lSg+rGraPhE@y)}616+$uGwP6-NvL2(4LxiQABtVF)wpt{iz(QhD=bWwEN^02 zuAniWlb#`4e9}EUk1jbvT)g6{gw!2jnr@u_O@L{zLLJ!6-%R75oO0vT*k`u8`m@T#gJciuWbuLA*YE~T&>O^!In#Pn0Gl%TAx3_bP zi)Q4AZW4eLftfC4Dx+aWlxvWn*?ZEcPAkEhyxaSTpdL$E z#^Vt&Vq2kI`iXh5s_y_!c?-OE@?a5$N`{>xqc%^A?wa+m=X}#J;Q`&N*<^vongRi!eTo*ZGKZzq|ewM*TTQcc364s$WGe>@I_7I4EBnW#~}shAJke zj-Ccn*8#TczUB1~s2{2AtGRp>3@)CwlZ36!nqOE@^m?ST3e%bWT*OJ85B^tX_vcwX?Uum97eLIN-?69!9rjL zMnXhx7xroemVh5Prs!dxf{UWrOKgmBp-U_P!=VzBAk#@vBw7(vUDRm5|sHegUjI6$c z%s-PO@rJZd96VgUCBa zj4WLGlj>KEwlvLr;ajCX%G@&zOn&7mJclvDS!)huZ;Yg}*R2JRfmD)6f$Sm4h?~Y; z=zdNLZFg0TfkgStdQM5FfPt!oO+GURK4;xZ-!3!9#pV!v)6J{#4Xkl^8Q*pd5DzxH zlf0+r=cNEkx?C~!Go0dRqNWD3LPtt+m9PR0d|SgA#&)EW#K*Gf9fP@b?3{T)d4tjs z>5BuR_Hd#um)M%uAp{8aIdvyLTeLN%<@fl-3>nA|G4cJo9%RcD&({|rT5wm-_e~eB zPsB$4+o(+Y1igBT{iOk25#?R}gxt7fJi%h@a}Q-#Vrs>&;n^>TWFgd2t=(*hv)hG6 zeqq-961(;1eFyO#dvO2ChPuAa5slfiuZ+7JigMujtH&F!3A%$G7^HRRIoagoCt2if z=d_qcJTH@rPYL9J4BN+BVvy>zUG!^)0lg-O>#$h1f|QrA(JD1I(-Q*)PARCi2m2sw zB5+c45lLN4;+F1(-LkF#HOH@SRJgZ#?$)dGFBz}ls2D&XNR~yjuKXpR-cJjqudAm7 zlnl;j-cpk$<(tzSv~;-Ir?#fSbqVKj0hv_WO6Eoy%jc~Hte z71bk*B`sPF#{DjtSqGp?J+#P)yK@JZ4 zv3zI0ZI)I5Qdc~g6sEI=R#SZZ6|FJ_cXn$-dBWFEWvut=-|2=h(DESb;Z=50p&u@Q zLBJ;3hS~Gosas9O!7g6vW3m0>7k^uXnmZI$X8eQh&TD8xZs*7YnkypZo`Wm+TM?8l z^9+Ra)yAe?D7b9vz++oO6kCnpH}ic_$8RxoL6tEv$|}Zy*-S~o@lh~ySw1Fzm#k}Y z?*L1%x#jz~Venf^vJHdrMGTeEuGBm&RH3RLZAexA&(9ru*^5Mz-{up+?@6OTgV$({)f$2WtttSW+-atTttQVGi+WN zd}M*DfxU`au`-}p%9VY-G&bSIq2QyNX_JOsA|hswhLmiJ6CKA|8D~mE>&-e0vd3U} z2c2FD>S}$x-wrO3_FGyby}s#DefMm|jn4dr2wqa=K&;H$-1m^5rU4nua72U%dzSq>v4u-=4guapYt6dR9-CuL&H867n zPE<5sd*A8nsGeo20_JrIUqUrLG9g~ob;st~-sF*+@xLaH&N=9gr%0m6`i9haFH|C-_HVv`1>d&QQlA5C2o}BR%M1pn0&G8F8F|NSJd0$J|1_QD z@ZBSD|A>K5z4mL7>*(bIyz?UWO4)VM1R+p^l-E#cTqrbnpG#mieyh;Yx*ny}_#FxP zqLFIyqDti<*=N1iu}aJHwRPvE$JxMt3xQ-m$wHyy!z44q+tUgY>ILZKOn{62toJ|2 zSAPMn)*y*>u74m_9xA^e3LUMcGK*@UiiOjCJ34Q7X`MsiMEaNS&me7;T1c~1WE}>2 zei^B^5RjPb)YrW|d12N*yd4pPg+Vc4m zjx1Tq+AE)n7HWQQ&L%Ej>1tCqHljy{pVXGpD#pH$Di^D5?Zj@ALP3u3aEk3t@=1EE&9;Rlb;ZA?H4P9I%4z}jI}9n8JwzyMreVs zhDCCx1Dgyh++~@l@FELRqBv_{&KwJ~vihePcnog}I>=*|K?ZNdY?9E}oCOt(Pjop2 zq}HqjIfc(R0T<_~?*tU@?I;#q3RJ85d{}X@`UE6qB37{BKo4@@I^p&X^h?xv-`mW5t`S>^Hp}Z`g^55>F@!#FnTqnbH zk7TZBUfdf!(t-XTroI9y%JutNKw3fxFQ6cxfOL0BDlz2HAuU4;HFQfOA|l<*3?0Kr zcPJ?^bc%p93}w;-gW5>eih{+fu! z@bwNJTPI6@&O5@_`>wlpBUIkzW0i>L~&FPEKT7lFMiIk~x*v4v*Iwm3LABQUJa+I`RF52*^gDP4KC z0A!)Ys`)7M^hpfsqq_lFLp#Fus23{$c+uO-^A!i~+!*S_PKm{2U0ta8y7cJutiTKW zs3K^YZ@aEH4<~hven&Zvg&@h#BzTMb8jCf*jbB9^pJc@XUuFKK9$3C$jo!~_Mbn#9 zqO8Un&DykrQ&^r`^cCm^>785QeEe7A^6Kh<-1D_|&CAuRl@322bdG_&D}m&DL1WuvMS+#zxv4F`Y#Lmxp^eSqoH!Z1V|^v3w1 zT$=8}c2i6?$-0`M9QE32GQ+|S=$Fzh%fZ= zl}sGP?wPzZ-hL8r<|#E_lIG>PPJpnxsbv{*XR4s{ONec?tlS)&JY1@yHki=!U9Rt+ z+m9~Mf807SdAq_cDZW z+xtxfD@xW1PcR(ymUD7n_gPzcjy3>~FCH2IeRxCrIfHtsk8S-T!GWf@?D*XY5FSL7 zBnrkRs1SNR!uDC1lX*tC&02avoSCtSxRCsO<$2`AUZAGGzh~Q$K%E*B6O&NcEcTDG zm0Fpx-4kLOH<;~p?46m@m@0Lg?ZP*1QAof8PjQnr26A3oTj%mPugp?!b@Fav_n<AD+fSp>AXCDZGrAhG#Kat zhSC6eq;=)c1cLGWEdRz5@}Wl^r+J-{L$9-z}6UO zrk*Ir5R}XE*CJ0YPXlNsTLj85|M21R>9lOl^jVdrH%0C3?^a#+>oAaRMeqz_X}V$= zc0*ikz&@bEw{DlcJ%J*eZt)O&v!l{Eo)S`Y0WsLrr)dehZ6On}b7td@_2OL1T$^1m zr%aFA38@7P@X(ND-QoE2VA1u?V^_`j^u@=-ds^RKu<${c}6o(aF;@Ohf@ut)|^qlJxCx~!Q;yhNlp26c_Oa>He@X*+a$b_BF^w&C(Q z?R%^}*m-H1x$E%F>rH+RpQB!O+CPamC&^|(aTf;Irh>J#>#@mtk7A478dCaKC^hps zdo6#-9a%ly=vrct0?n=)kJW`q`S%h`T(S3%F-dk~sEy~N{#K%SititbcF{0M^IHNA#+G{In(K z%a5Uq`hb2&(dWn4a^C@;7CY{U)izfd`sc>5{Ci@{1&7bo)s+Y^^^l?b?gs7G*Nrm>ck?Qu_tJZ>%hlq&O`ea1`k3F zw>QK1Ox0ie`yx~4Q5El-Dc5~sTZiuYSz8X3?exI*M8GzGe(evvKAf;SpJ~_iIv&{) z2RgCCCGUZ!u4t_3wjNHN#j5hWoaWE|=RI|yxwkt`jIfm0 z6c>cPPiMtydX|*f1b+0oMP{krtm@5Zq1fA)?$PN*s@;p?p%n+fn);mP*MLhx$srrF zTMoZJYBV}H75S<8agBhn;T1URv#&a) zu1EZahI%RF?Ww<{5@Lj)@An`dksNQd*#@g7!$qVtJ70C0gRMCB0&uVAXr7+87L5uA z&>BZDMHnV%m+QCRc`1I;4RHT#5r0a=^8PioLz>PJa|yLR9Ml3DIsq)7Wp{vGag*}u#kov_a0)Uh)9 zd#xE@Qb>4|A%x`?qQdZ)0tw9pS2hNtAywAk`UZ7};0*2)t+uhU(^L{OTzDt!$!;_da=#&*ny5JQf-@PYJ+W>CbYXVx!W ziw|0kd}~lqrqD9$*)&$$Cf~TMwY}MYR;#ie)m+qxmbdz2|2kqk?zXdyBhaSr!t}g? zv0b!%-a2n*d-|U>NmlIcP(ala&?=YNyA8Y~Pe+W}aI!vrWlyf$z7i|d@}YO=j*8`& zPs6})Y;KXw5S7@P2v~x$!GRDRGO6L+tP`iH7vJ!Oj{>-0Fja|~y7UngV2Y-*{I<<0 zO8M}0#5&eG2K9-k+(J}|_s&Lw+UKt%{-I|q>aG|IL!ow%RN$hPlPMj4@1vSWlSG*A z@0F)4eM&;7A*w+CY{95ODUKd|SAaVfuQy~~gUs3u%c)kn+PwcM0tbL-R<@60wEb7# z<`adS?~=HM>@f&X$FMA@f5HWsdU;(t`6Lilj z^tWN`sd2hlon)o$D$M)nGA1v0?13wDv0fuSBTpEr0i$~b7kiWu>-`(=KMXAm=m+CQ ztsIRNZpRFnsfARfGOLpdeq?k8BwUInf5!Z%(QtB`L+db4KNCS6y>yyik(8bw6SCtP z9aUHF0d`TZ?!BXGlQ9tqN1g+>=}zc%hvE4Nl8Nh?caT~WCq4oQ2QK>_*dfFpeQ?LV zd+PYvbv?r)5gGdtm*nukV(gBGHH7qN73wH7-2h`tv`V%A0&tJG5d^+%ha{WK}!nI}AjbafX z?WmBrLqg!&OgMWKqqI@A^!9 z8~kNCx4TQx!zDG6jL&J-EM%eIO zk!mdyF0yZHrjz(4Vjb3}Rlm>$R%{y2LGlnA8_Z;X5Tr%MRf7aq$mZjC-SG>DUyS0K zjWM)P#)*h(p8;uy%P~OO1(!fu3#X@UL$JB!4^@8aC`B%J ziL;gg%BzzspWU-T?>dO2hm{>1om!w>AWDF|x_4tm*fQEeNac)pQslRv^G+q*T8*&X znZ15lS#tog&_}7szjWMdSP9&BM~k!q|XH<=n-ys!IyW`3HIpQDA#s?sy!7B6W#FMJ<3=? zp^9oKKJA{=`SscVpB7-%6*U1H*5VLQ=NPXRoP#7#WQz8B%v^OGgW&}sg^t!!U60aS zb>cR496bqAxCJdomK$P^W-r!UXRbtDH8Z$jh!;q8Wz!clxuRJaNAYI?UhhJRdG~-o zvJ2gZwSRp#-7vKUJYChm$?@^X#6;axKX8<&wsv<-wqN}lZDRZx{^X8XaqU$CVzGwi z0oO#x<`%&yB@VMLS<`KDcV{XjGMN7+iCqSD$rc4SE&@Bdz=>S4;)|nmOw>v+h)Q_~ zzh{q6pO)jNyz|_gqWL8}S2X&V*OSRrs@vQ-@ZB;hP3$eKE`{~2u_HZVKn#ezoRR;X z!25Lr9?u!=Dl>460DE*p{8^|8Ql^j6b;DXW!Ot+wcj&b*@agG#SzaSG*e6bAwZ)F4w+%YyS zVkLU|xmv|Hd@CmVaV7ULCMrx@@k#*0w(Jh%@wvY~=+BN%Ot|!Opa#aG{yTrbbtVVo zN3~EGZpQBB_}mUUy%KFaootG|B^hSuKhn^QF1O$5BQzj6W5vemt=}J#Oeo_1)i7R9 zqFMA|%aG-T9|SeDzzG9=TmgW4nrzX8V(tscw4ZJ}eo5vLtVcjTE`v8)O{gAACp850 zrga2*uJEg}_h(*ki;E8kwHy#FTrHegR{&GX0Z7IF##a8aYb4Eo*dh%6qrnmpE zHEB@qdC_A);i)!*|$YIoZMU70s#w<@95u7 za-EH)DPt2Y7wF=PBcrUjvZv`+qPpo(IzLfJ%m$QHda{G@2tzhbjg7J5-+`QHhI zq$(A^7qIZXTLc~CLn#7|TM|msKbF&1O{yLJkmYgonk3qWB(NILca5UQ#$|dm!D(>ZM}=#3eciPo zKdm8(e)y#?(@vk2bm>m=jActl`{=yIl(or%t=o0cD>Rl)Rim*kNUG^|guiuQfaeA# z-3@bSz-1qfB=45 zL+9;W8^;u~osYUEQI4G6=x(RKBVD%4a*Zp*!oHrr`2%fd)>SFi>Ira}UsLxDR=(B7 z@b+$du77&mmcQF9G2j(A^U==;yDhcpbLbMW>O6f(u1dNo2yb)21kc&(>lf{aRogdM zG>F+{j3+6&qs--v$Q<>`l`?4k@O7~PJ@Lo-`yJy zpmKdMM=@aF&c7S@3#YT^^MdholJ4KGvcgRlZv+>{?l9>j(_dhVA0pR1$0xgV&y0F! zi|EQ;gpevnU6H7C)}C)cTi>>o95kNIRemQV1A>S)EE4g`Ddl7n?U~kl8e7Y`^&6P| zEt~d+9*b|k6cq8kd=AoEEh}krSA&P^Gvgh#Yq*h-HSX+FBCng(p)C}fJ2hFuerUj| zrcL8r|))5>mdZYzze1m$mTXg0LcP9xMuWeu~c-pJ$%3h-A5V@`u{#fI$~8 zq1)RmQast_7Fa^qd^W89jx9M+QCadEyD>RJL1ua{Ro5@F1P+kBy(g0o^$yI_l_}mV z_{hFWOXdHTEUzi#d3nwv7U1}bu0gnK(nPEiOHKO#dRIW*U;Fl-i7qnUeg?BZvo~NZ zBGlxoi`^GZwib+rG$kLt$Z*hi@$zziT~a%}`+{;XY7gJ5r|m0~bU@&<9}?Uhqv#t_$gm^vV;Q`?$=rT4ZeCvB zlg(&<*h90hZ8S#W_u+So%Me$0ri5)n<8n>bpwV65<0oeUuf=fBx%b=u#-(RPDnd|J zs52a)BmpwmY#lHjXcU+c{Icn>?!&W{8Ik$XQO*6s`Y(5`D-S&{pz1909v-OcX9QIt z?4E>+*QChwee&%G0vR9x`cFk<+m5x4v6rRk6-wkGxTEDX6>$-mv~wBWA1SD5Uu2HI zzSXAq_FkgZTldqQFFdwiRrPu|K!4bqBFx|3bisEP>3b>x^9=iFbRIqCdsjeja@V~H zKYe?YNVF{~(dL0`w)K4S@L=$3CINk7QubnJl@``BuT}BZY6mQ2g5*7L79lb*Ki@p1 z+{b#_>wkF5#kH^0C8N)Y@rl&@LNxshX6Vgbw0fa}HF2NWq!8l|?eU)N)tW%Zj$2m* z7ZZ-^M+U$<<5e<-iQB&vnI*;OA-CJ(b%G!4wD3a#+(v*VVs}jnX8WL zN5I$fXQWij*MOAq-xcM`^VdcQ+Ppzf3G#HVrQ^VtRk(g{bZAvVW1AnxFnesdh3&lX zS_fSv$glfHb^pfRi+)_zv5#=XJLizc1wKKjI6GM1vTH30OM#L*i4eRU%tT7kh|Jr01 zj@eeSYsyk>gakMBp^qP zXu)r=zY%Z|u_nX$^R!-717R>W-lc@^brN)qgw8vW%YUnAuE91zI}31C&%|6TH&DGX z%6)*0&iwPSCyi_HpeE+TMhCise!EM2;@X0ePNRhYJ9M#kFin zj(W_-7Qtn-T{|g(TVVT>6x^XzH9lw~z3E>%{F0nP#>klRm2~LgN3C$PfBrTY2c^EH zDh{-rHiMh#Cl`j=>gU6*_@+2~<6pZ*5oj0dnf4MdzKG5GE;qSE;17S-t<>##dBO8F zDm-gZFSJnpfbIPz6HYcWk@>C}9wJz=>Z!K9La@l!?A`}zF|evMle>C2 z=3*ki;5SykeE`Mj>RJ-Yq;rzELmg&}aw1sx7hJr>#6n*IlGs$(C$dXaqs|LFd?0 zoQw4$4#&C5uvxyOliU38VXYYF%_sAP9c8G}B?HyY#*Xk|rTsEy6GpJWkcWvoZZQE{ z8s>R~^ZB&NL{|X&`2I{x=wCL>$SODs4@d}rOom-+ z7oxhSRi8vfp-jaVldTq61=`N&H!2$I8%tl`7|Ql>PI8cx%S zA#hKAO7P0nI%^Hr=N=k2D@~*P<;nCLvPYBZ^*}TU4XnF-gM`FNV#{jn9udkw94RIw z-Qv?44oKg_*;sbARV;yZ*8nuHK0c{Ge=dFN?I+R5Xj{P7nB`3<21TT{Y_+8K#)lM{ zR|yCS*_0^t6Ddby=O6w4TUp z_qjGHPqhPG<4)g|3t_}$|8o@o5$;*JRWpvZVD;5*^s|dyyhTZCm*MAj=WS}khtMI; zYuNQnGm-e!AU&-=D`=~Z+EL%mG#?@=<#{U3{3xajW!is7hUg)*|Beh@^xk-Ax#FX304O_EsC~_*p0R(tYddr89`Xo~@s{(YP1uHRJIU;t*JwmL z56fX!@A$S8Z)T(vKWIIMp)^m)ADPOdoKT}|B8z4e$rH5meXa&rmb@kWwMFy3C}dQLvI!E z?1{wM2CW@w>h3#HqZ7tTi)N(I6oB)22d@A$ckLgopg^MaFMvZ>kWMfG?*M!BFSxMk zWVH3eHDQ=&nHueR3dAOS{TGOqO+*EzD~>7BUVK$cwp5QLS%h6l)*@OKl);L=mKG>_ zzW3;1+{-ydj@Jq+$KZz}~h8(*KrsCp$E~v~557FmEPhjD89{) z!}Nye?y~04)Dl{ZzaJWFzs^CEx@HFM?jBBGuSz02Pt!dpfg+@Pk_hO_wRi84QoYal znBaS;s(?j6kE078tPI!AU{!|=)bgU?zMtf_brI=-DEq{H~ego6s$)d^*xYsCf} zl-4EsI$sQm8(hl~8byTnSP=JP-v*H*(3v|Nn=1=IDWnJO<4ql?qq|)Zn*C*O2P@Vj1>;e$IR0d=>vY02|fY{ZB>TWk2vz zZ=N=QBDv)R3QDkxlSTu)Hy^R)+0N0Lb{?jPtH{pJcLBdnn?bXt9wqN>u9_bs^GT6< zc5~W3)Qgf8#%NL8BaLX}F$|%6gr!+T0nPC$Dqtng6(tBAD;UUv{RuD5dUozUvsw9f*IUV z5^B$z?nSifREi4to%vaz&S9uC7-|!SDd`bvYhzRW!OHSw?&C<6hyI{!f-ilwH}kVr zx{b8ETFlsS-5p~9`nWs*%h>!i9ah|JaOue9G=uJ!@_)Nb zNbi?q%%P{0fFLUd4Jc=9t2>Q-1H;w5qZhA5;2_U+ZTT>nwS2+Wf}hYUpYOUq!oG%f zXtB)cOhS+&9$Qw=8%aGP4E_ptvufIO;%hWE)P6NQNt~JRIDy{0&Ox^aCkz0Tc)t$! zaK5I#(X>*E%_gvh$%!BUoY%YkcRzWU??146+~X9$o#XjNQ%p&yRg{)u;OMmW&_f#J znG_)TjjmAi%1e<6Z$1;w55ojA*QT>}rAH^W08FJM=-=RCz{_*f$pCX*_ZkGF5nbk! zewj;YUvLfNoq)IF$ja!A8ta*)r$>Alak~YMQ`aFghcDsV0>akl!S#eR<^SN>d*?9l zoVm|s=2kQa;Zt6);^f2!#3F<`g`!18b_a$KFrqP`)JGCQc8o-+X)B19SzBBsl)RcZ-w0Mk6Lgr5xn$7&guG4?NjTuJqhZ~DC^ z#bnYLnQj_+FH4=SZ|>JuRh2zG?&}+2D7V~5;pB$}YvQY}X9AB^bq&tj~pqo`2 zzUbh(M3o}w4+|FC_A;(cp9434t{!U~U=0(Whuyz6vArhOf6HqM;vW2KrId|dn{BEX zTn{n5#r7%RxR3qq^gWWPBa5fMP`n`L{SWX9&}5sDc>{s3RTu2}Dj|ywtQ>`Gm{?UF z0@Uk9FiN#Wy>AH+WVi9l>ghP{fBiT7>BG%atj6&1&u)1ptIf>q;JAP%?cjiQbHn_1 zPpUq--$1jF0Q8FA_#fchR$bdRdhFefBPW%>uiA8PZ@TWl`euEx%$y7r@virz|gFe%Sd@n9F_7<9`--am_C{m03Y2xpR{Scors&PD%H%4 z&~KVKd2+W!r{>BpStIaDvG-znm7kew>z^^xW^TTov%3@d+oiOp^}>xHCV-%``Cp}m z$IXVv+l?BZ@XG(91@jGccET*%-$IX?3h@iY7qhq)if9>t5|n+Z^IzLWTH$Th7-~j3_$Cn2*=j+GR{=>wF zhF)f5M82EE_Njvx_05fKe0WT>C&>kw956lP?_|1k^y`^bD`2#D5#~ytr};INrVj-+ z^sQV$H7}m}{wc;(odb=>oHOo&L~Oc?zE%v<=Vu`HkKQfw$SA<16{T|8~^PAwf*~v zNrhl7C-H}#3iB1enwrz~sz#<{7DGa7kS({Uqvo|*N|V4nuyC;udnN45`O^n#*STKL zaLabjo&yXlVx31dxG-|Dy7&QRqWnnp$V<5lU4X#eCo^lL*yA@t%-Vk(zdzhoR@}^Q ziNa&jUkpDcNCEg`cbXzA2O!c9gXawRsu!rWUr}*EEUg2$Adek%=n-g0oTJ*XcR9lF zo}x)IaBA6Hi0Cm+8JV(;-L4hi1rjmn(>@|K4B}_PUz%IUnnY1WXYg=!H3<@x%zy^Q zTZ1}k^jxKthU~aZkge+x5*tek^}#LTUhafh=CWby=x9AzZY;jvh9we&kSiU(55$FPNVN_bbiMu5x3GMhXw@UGLM2Klt&r2}_ZTHlD{sbbE#p19!JaN#`?P zp6r0+IQ+CO&5AHltr2;OAXhj5j5Q*M`lf`ne%>xpq65T?-(buR!3~j#d zXyb~*MLNkJHd+23_cBMPeT|>n-4G<(n%peElROyN^4*kLT*~t2RdV<^)Oxe>n)s99 zUq%h$XWk#5`V!4G4*lu2F$E zOiCPom&0huC4Mg6tsY$uEk8uf&GgNrG{08Ia}NChUEXr+wbReGyj5^RsI9!qXuW7A zebZXBBnWt%k^E3Vgn-8*hB4NK`ynv+rreK+8$(uu>6V4`h^e)^!hKV(E{5$--T5GN zPb_Vs1tiZZZC4@>yb0S|cS-|1lX7$dz9u2+;$~A`1A?wF)2qSKS#N0-nN|b3ftYb5J771H9;w?wsK1}i(CF8@7}vdm0=_Cp zTK>n?_teg@jhSQ7GVcQUz289T5ocrQUSD5C?LLJ$etqswe`~GCOE^jBc^9)JFll-{ zPLa0#)9Ddcz@Z84WpAs^aHhods6*NHbhyXKl%j zraNjW$?gtr_Rn+@ow}SC_3LG9-<#djKXPr&IUPYHTac;fHfY5EX#v2pNf%?iLoPE9 z*`xE#;;Px(a?kqMe9xs6_8m<6vlgb?Hid=`+B`U&r>p?hW+6bh}@D3L^V&;D3kIdc>w9a~^1OcFcn;i$+km+xd+vSJDpDGzg6nrp2&VjwPFXnPyHc-6>xdmEWlvo3-zYFw<3EKCIy zn}B@vKEmhG)gBvY>C11Be9$x%gwWFijQCHu3M_3nO1r3<|A|JV+%_Qjrhs?PT z&(2v0T<=!0rj@H7_N@hDgcyCtGhhggQu^zt{w5D>Cy}W%tF2_G?BG*dw*WFnIH;6* zLt;;-7_|$=i;pMM48#@MWvZDbyfGdl!hqDb>g_C zem8|@Z7uy2xXE0}i%U-K2*y@sU{%Q&`sUB3a>YyAsg?J;wpFkhFs5N)B9CE-&er#DhGu1*V~d>8ApgH6-Caa_it zv4qSYfnHe;*vZn#1J+%Q(n}w(+AN4>3=<r#YyQkpD4x$|dZ!kuEQ^_@{!kel zZm@}6LNU3l>#n=L`x+(Yh+9%8bkHlY!@k3M8#SfK(Y9PqxBv4N#{`~wDPlUMJ;4sI+{gl_ zTA{#BnDG$@3tkvFd(+w5%xvTlR*Y3%sBU3{5xo&-LQ+E_S9z_v23;eOBb2nI^hm5q+o1B4Ebz3zGms-Rh7@KuY3JT}a>f>LHH!{3>AU&K)*N26{Andk zY(VxOQI59wY!cy)aoU{2AsLtK)r{Zb6`&x3eJO-!XQ4?3T!3NLi!x zd3Ze!fl!hGK(v3DELf$R4}Y@N1MjikH&?rjv4d$sz?k};#=VyQGSmV@^0Y|m20y&B zUFz;)*kWP$`!_idY_s)mXlmNj`LRFkY3N(`naI6|>i8iHcYjAPF^Fj~1g2yTdMZx| z-4j0R-0(zm1nIx_yTgQIWBPhNWUuoq1mUPBe|;94@BlW5;aUzkm(1;|Io^H=LfD%3 z`wY5mI~2LPP}fr_-YMsin)|+uKsg_QqrbyCORf*=Q6e@A+NXYh)*GTh@&5+|_K*_c z<+lDJXQ=+IjV+VNgMPRZ0>q}t;4lR}!7ne+dYrxz7HL&-xNy!S$dJ+wmz+Qsffgz( z6fWHg&e&CnDZ9uhWvMayp{_BnC=@@bxA#G2oB^d|^lq<$&!9jz=liIPh8byWZwEBs zifD9fOoO~qPuza`P)JE>+mBXE7Px+qWMq}q@#n>)0&G+77hDX_6w*zVcRthGt#2Le z&{aQxo$XHA+S)$*>JVeC;ACKGx|lap+tT7MjnM!oC@lD_{e2`R_Q_wcu|?C}0TWdv z{l`>=cz~N1{T1hDI9c11q%JN; zakAkZn+;UjdNu#M02Lyn#^M}B5W;xaPNVYm<(a{xd!gC`Bwt&rS0x*WdU#8r?` zW+?R23)t_jhnyxQt*=*y#{aTB+T?IC&Y|7<=d6OIMq>k9>0PRaqlZr&y{UuW?U~s^ zUN3`HE{T03;P7Mb;d}X%81+7Rg)rJ|^yHOZi?5iM*TMJs9RFCuH*ZG7hq8x-h@=*2 zGDOCwwJ-*b?6`v`az;i+BNhX;bJjia)beJJISuO`Mc9wA-50$+qq6`6pe!9)oja&S zkdBVdKyP{dT51sVZ6vdVYWwIu)o{!9>ewgp^3-Wp9*K!@VZF200aJ@zWJJ_mmoL&d z;-ZICmk!GOX&0_BZpWUv`ERa|>AQZn)nH&7PHD^I3g~H8YwGVM{C)9Z@9~;3GVuB} zSuzF5tfcJ{+<|(!rl{IwLyp!D9*Qg2JdC@MVei8cD9V#kLaEX=y3oHB>FRQzPfR;I z@iR^7nGnZYxkD}bE@?gT&|I*M^Pr#M1IyEU8VJ}D3++Dh95A>l54DXZ56#Z~yW`hg zOl~Y8`Xx&HR z0#Qcv5-KoU#ttQq!k(YSRK+^633Dnj4vHd^Zj}kecU9aewc&=BrlbQ)wNn-aqa{lO z^~FzCYicgw6g4(a>(bT9D^@s=!ohaB4d(d98 zWoIq!AI-F!zInFg_-v%*Y+bKJ-LJ*ZLQ;J2#}6JXt&g=E0CgK@F*rQjYPUOA&)7`Y z`)6EBO=1&<74!hGgNw<0HpCB{ot@c@zJIA1mQ3Rt7U%m-`BW&PPrZuQf#8|%@USwH zqiNy;Gc>4!?e4>J-aC*Ehx6BbJz?9Zn6PG5@z#pav)Ug<=@adotr-c*V|^bayY^0N z$+G;POb)5NS5kOlGdtsXvV(Jbotf1tq@R+tVfjM^cZ~O|h_dbK;Mw)H>CR(cXMFaw zq=Df0CwWjeOBTxcB3}fkx0!OcgA5aEH_X_$8d{a5``AKQ+{Y`3uQ~} z8X#O*N@G3jhJffBW_j$i8rsC4A~Grap~FJ`bt@YiqSD*7ogCtG6sp6ucm`7xg!4T>i&_m(t?OTUYh zSmWUzQakq&99qu}B&qNt7@T-m`)A{EKV7u6bgTPkCb^S~)8(TbsWrcU%3NGrfB~Qs zR8&-t&uGwv92{7LOWl9JW@av|q@Mz#RYT_+JxIoA@#%5wRJ5~cqnR^3gEz*Cj)0?9 z^}Zd`#AipK&SAC(7}zS}_Lo#&UtcAaA75T$3I(M@AT+hKWZm5b5s1T^y@1w92eo9L z_$$XWP`eHNHrYz@hfu}6&%Rni{-gZ6m%rX!SE^bZzNFDv5`4ff3CGXL<+ch2L(A-7 zPHPugE3vzv>oRKm`0XyLfbgkj>CNUC!|99fTxnD?E&0@T2l&)h?=oof;Y3Vo6O;OG zx0tuvyIqUrUxa@_PF-|HM}4*#KNKT+a!91|Otgf3e!NTP-K}^=-}Rm%U?)9p0sFs@ zCWO@QZw&**0A+>3E6Dk$@%@YYkmdNa&2K;v+gm%YVV<4|q{3}DMk_KpvsbE?_e2{8 z|IT-^RQtV}O=YKm7uivg?Mboy${mPO2BqD&FA;KsBOrP$u~0T%8EsFBbOQqa0-KZk z#u9Hz?%79JkC$J!kxlR>vY8MN3INV>?a_3TxWt!JPxi+_wZ9rr6)V<@4M8L6^2Iez zwQSU^^7z8h{>=jRj$0<1=^||-L$bhT#wRE97L&r*!;2K67ygns>wv-U(oBHx1-r-Z zk^A|+S$X5GXjD|xRFwrT;9|cUaXujTS*y^cQzZUR$77k}*CHY*Nv8f@BU}H2qI(F4 zzHE+>B|P>ufOupNnLK-(Pi>AoB?_3+E2QyUWF1o6pqGP2B7~e3sRF9fyt`eS@e|t59J4lKg%2d*+3@Uw( zRbS@ADC4|^S9|!pWZ4$l4(D0FS7ZOp{+5(v2aNnXc)QnITxd%jm79F`+#SM}uqs)1 z!7*Sg{ITTeOH!%p;hC%5a~e-?AI5Mp<{IB0+MtY=0T1x$y%8lPTd=TNQkir-pki6C z!R>WwA<=mu3jr7mPWRcZXRKS~vmW@TYW<#r%zYgdHD7L46NHdq$tQip`Zn47H(|M+ zMObdwUn;n?oB$%H0;2uGT#z-e*J9&wE_HubYP^9uY1a;MT+;fBKLj}qIE$%5e+W{7 z{=U~|zh^p7ldc?Iy*7K;3)UU+CKLRGZC8Fq~uIY#J46rIN`f|DY{0lm+*Rs|3c0X%TdR~X%k)}2oS@dZDj7_HKiJ&vemEg1=Ok}Q zQIbcmngueMG0m!|bn zi6wml;NjE23Zjbyed-s=RRbgcKjM+D{&PRrRoI zulz%GM#bTW;hJf0Zl3EE4Hz{HVB>&Cfv?r`8(dK5vVDowQC4P@Tx>~>jY017Gc$)9 zI@Z6+ee$cAcdpiUEE@s35(PqT`mlRS1+Z;T?m0f;U+=L0Jt6G;&xi*ffnw5fYP8;f z3rf(DOgubs^{(qKKVKJpNla7#dR7z^VB770YBKCRS95tCznZ}i1)5pUgb)7 z)1$XsDpEHboMqCe{)!F%cCq~3_1X=Ih2t=VONy&nb5zn`-JsvDg;jItz$2o9h2UO` z)h*M#myEKVTS&Ru9lxs`OU@=IPN^$>-oZiru3j~PVKe@M4GS3?)7-s}egyjMIA6yF ztAmL=ceFm#F=Ye2sLiub?GRgA1__BniH$1C%yI){)b{pv#1&viJeNbC;utwYt{)W^ z6vP3_^#fNH1tFlY>UWpW=)Bp#!peVh_bz-jdh*frOoL9*Fi5ID88c2^HHUp5l}QgeO!*2?-Olt`aeO%E~+BZ77($Ucg`` zsecQ3aDR-wiUGe|IllYPSJL~$@yCz}X5iwYuyw~6xI_m-&R4hwfrtWFC;!Rk+r!!a z_hm9yU+lRV%LFX4P5w{H;t+M1~EuXG#d$i z!}Kl&1iTL64A4=l-@%1%bKNtda=o#lMYuenUX`(fW&lrga{l)ajL7bPmTgnYK6w}Tw_U9dji0Yr#RDN>e$oG<>nnhw?E1b55k(ql0TBfyM5J3u zMY?n8ZjeqD1Vuyv>5}g5TFI4emTp*jfu(D|!+k%`JKsC=eKV{x>WEzDI`OOj|Ky-% zT%Y;%i@4QEXtN)IA6vHR`3PVWqm$km&ZlPufLIO1n}U|ji9UZWCS!5#9b$l94)72& zAEsxbqO7u_bTKYO+9xm{3JqZR2GAu0?}T@iWE0o0ZQb71Rs>kp$sH9iGcAB-z13hpV_>mt z$z>67{G^_AEHMlE`9o0dG-gMh@&3tm(&AzsY>C>*b8|Gw%qE_PArLn;S>7SL({(_{ z$z#XTkue`;`h;JLC@WkiZwPR)%%eHEv;sWdeQ%LqJWZ0@+N19$J$uGft0fWo`!S|X-1mNB4}0G%I4t12K}*|t zoPBAhDIgLU^tVp0u3v}z21C~QVki9H?SAQ0`Oa9Zcq9;pLI~O+-2d9O;$gd5KtsMBh^^ zimw;B!`~>_q>fm4ojUuou8IrHZE|zh^v3`saDP^U>3x*fV!FRj=6yaBLy{o$MI=Dy zEh_{nVUhhAUa;U^U}j+x{j0-&x~8!AbGr63PNKN6#-XME$ZTe8hD?{m6*=ks5P7GL zggAul3&q1d9#PR`^PZTa>0&KiRLbeOPzY%f9v7bu3WY)@2y5lDVqTw2)_4|s8| zMBKWOw05oAW|zw4zZHrWUJAfzlril6k8G=Gd5zyuQQ;Hz)Ou_U9*KZS! zK#q_faOwX8vrN>KHLkK@nkJ7QGc%JiFbvGpxeBgEtG#*mu5EFBa@YNZuCA_?we^OF zAUH_4wbc;oJ4Q{%&n&d-pYCB|fV~>UWjYDK`otVNvP>ZY_7!Hz$gP%9T3WH?!{$&U zl-B(&LN+yZvww7An7nb#!bW}k#E{PZR+?@$#9(&Usx5UiFhdkm)<*ylOm3ub0!_+0}J@h=g|4;rrfjZNh6thp@~;$HlQ)$QJfEl>6)7gBwRm0W}13=LoApZLYf z(l;mHC)0NLmgC@`&zHo zHI|k9jGz%)W-&yI@Ef{54=D5`LjS~o)?Q1970xPHSXj){j!t=A?DLBJ*6)LI$kVSN zI5?8tukq>!^i9eO=ex*-cW&aI?v7jgUPY?K3FtE%kBTjh!59{!lJw4Y4<;XX(yfxw zjg(=PzA)d9t@9s?#C%Y){N65zDkPmv8COq%6$IZxe;#+zIu1@u{KaMPC3Y6}+)MMi z0L@yM9Ds340&4zm03NYK(9nH?zVzQZygV9`KUqhOV^dNT-QBBo=y>mIIFvn5SWN`F zjgATpBz&_<$ynu8Dp7o9b^MNBTY*aWQ3f@6luW3ut_^IttkmBx#LLieEH_Q-ledVb z|EAX8oqX2Wb2m|`oq|VWs*a5OY8lV-E}E6HH^wRf4QMLP;Y<@p3fhM`6XU*$FT#f| z;Xah?`SXFvBFmb67r)7^gx{`nb2{~@*^}36qr3UT>vE&(uIu~SU4I9kf^Bi0Haa`v zMlx!)mlgVdBDtKh+>-no>)`?64Kr`6CsO?&s(bq`SwqQ~yY6QAxNF?57+i>jcbW*Ubst9wFdt^Tc-M89Eo;fm9Qt=y< z>-=~opKSEukMQMg_57lO)mpIOeJ8Xq;S!sFANP*s4{pnscxnFi;f6E&_$?LvPi)h% zblDum_sOnpN5oGNABghu!VvG_&nC8fya->}Pxh>Zgq?LMF{}(Y^8I*WiRr2~bt=mV z+w4D3+L+mYd~$v0pW=H&{3R#3CF!xS+~M_ZO3Tu?LiDxZpPPrvy}Bn2^~DWY=J5A9 zNuEJX!>#&+!aBHF_V(xL7g&g77-(}YpRu$P{{Xox=k%Mo>fA8fno%!v=hT;IO326z$W#Kcheilv?%IcYS~y>l`xn*EaH z9zy+>SC6bWrdh^kLYu=c+${qzC3p!EW1)-XD6DTsQ{}!%bv8lHDLFgj-gML>$&u!d zqmQ&gVFQDJVUaNALksY#pv1ft_B12)G5gvgjiz2XKD1vMpi4QBJbtLsqi1XGGt{hg z@ia<}Bd8FHnym*kumeC#z6m%i7Wracj^E-wgaFAC;V4ph zprE9L0E`q!L(`2V08~>#JX=IkI?ImEd_gBNtPg)mFWKb+g?zmM|G%q90Fq+POSEc! zuoSPg_zVYx51e2BrsYLtb#=M(vWz-3A_sZ;h?YJe`r}8eVgddrpXR2dM91cMpn2q^ z774x)M_~0Q#JoBm?m6q$DmGC`2tHPFS3YhUyYw~Wo3FjXO`<&E<7@zbkp{^?p~f!X1r(q%F(`wB!^gdhNC7{XI*Ib}X5GTaZ1Z?#BT4-HFhC z4*okNq|KU+;Aw^aN=nL`)<*s2N*i*ooF~8iPDN@Ab^ZvWn!9FCW_xjVB3#F6=uMRp zZ|mNx3aI;K8*s{g+?ZIq^X{Dv&xK)OfF11-YhZUyiG#^3%gA53oqDtT!XpFs6`Ugf zn+4Es@zOcBy*zl5%Cw&$mXcx0pyY?d^FQmVyM#4~BYZ5+YEQm09E1qzmB2Q;KKghv z*M37%pugEF6|bC+L6^drxQDIcb{2Cgv-jp{pQ3c#^@NV!SVX6D<(yK7IGRFbBZ@C45T11`Y z78mnD=@kmAgx}Wog@ZE@)eI(KhF*L1oZefj<8=CIlxLxQQd}Sq1=1eAvCd15jNBzr zll@+KJUOnFr&aoEqs6uiCI`Os;pcS0uPd5Lgw;#|u>-atxj7%?S%q{Z3TMw^OgUC# zWXsijOo63f*US&<6Ypb_tF@V@wF#!|wyOK0M&s$eEW6rb_|^9qc*$Oa!Fi!}EL#xF zlulXLFhlgE6ezd{2|7!qZ~?8wqF9&<+k8^e1I;2`Y43Wmi!lVM%z7kS?9+3mpaSqr z0rXe?0VO?QLqNpFSz0nWFw_0``ZCo|CN0A>)8pM8=LeHA-ncUNq*d+&A1cM=<#$)X zAw3DawzVLDXKiJ*Q14j8$i{XrtfLi&Qh#uu^FfktC#e|!Sj( zKt8IU+If8hZ8^WPJll`$|AWb{i%)Da{H#l0s$6j3$V*XG$jk8xy%)R9pmNoRdRy}+ zeG=UzENFXnwPm=NgTRnS^hk>@pTEm7#^gc3Pg|3r#?#lf+T1xG0vh-DV<29*8*9kV z?!y%9i=&kS*It{X`tOGGbOQWJ2KH0QuK#itKwoXp8ZM%q;jt&R6a^TziVo~7ccVl7 z3YqmUCGkq2LG1Ue;^7rnKN-s0P6*fqnY;ru2rrp7A3Qc_Q$p5#V9VB39^phZqWwQy z5zttgCwJ(Oz}D7FsQ;^^O9XMbu-%(wnAF0=xuSdOHGfw7vQ;g0Ko%%K5b3d_`JWc^ z`M9|<>lW%SY3zN0BU;*6^*Ox%f$OmakQOIu>|VeLVq+0$jg85ztwvIT0DxfuZVYs) ztju;r>%1mdy-X;LOYmU*)ESMj%}=(>fw$5?`7JFkyeLw))%umaxqIytSi|%B(yutB^xY{MH7^|i+GsQx>=M0ru;uUo+=T(6#0PVzp*?K%W~ zc(aS!GF31G_eBiBt?^BbTtG$v%ZjU+8E;a5+$)>h6u0n|muq0)3+ulGC%)y`x<-zy z8Y9)U@oiI|#c4YHyCxxq=ShN@vTi$ef-XTZOtKhnk_1RF5Sedbe)B=Zuz@%{pe!E9 z6*nGqXF$-+7rUmYwZ6)#s{P#tq{~)OO+v)ghEhQ5qSM|$z%?rFn9HG4U3IykdE+#6 zbN-4_JmAtk36TObGo)3Z-jVWUR{O zM>=&=Ec?mXgAgnE2_?yM6ANbdCoys_xs~F(ajO`dwS}J@^R=}qn47#*W9C6QkB}T1 znlqi$+)HbQmIkC$|b0!+VL{ zU--LpU}{EB?rDnwY=`kst!KL|Y3`$T$12|9(Nr(I(ZL`P>CZoE>0@e|UC2dQRr#I; zxWte8H8i!3HUMR4Jbnhu^t;9SpR(Lxad9CDQBiH><~_YgKQRV?*dc_Ss_M0_4|6DJZkdwQ)XpeZ^N=j;~6)9R4bbJZqq=6 z&fZDDnabNNM2VZnRPrT=Ur|PlM7~u%7uHOx^6i$jR}&C)8z!!r`6WJc z^CE{DEK~hrz=vW`?~H~=VY$5L`OSwm&wvcPW|#E*YbOx>1Nk8$` zcJz+E4j)$$rT34sJ>VB|{cArNvRVyuCJ|%!N^R7ySuuW5uuEyC^Re(Mm-%vAZtHiaCr?@&SsRRp zjGFsNsk*Xmy7-;71m#K>69e(XHT7HmsCO29&RYAIsK*?4S-gKa19i4AIDfLcrg`oo zyZ|=?WG4JR=gRo3eEevn<+DO?Vo(WEK>6g-yqp)_;Fl;4{- z-#=`%bohAfDxk~S0n3Q#lsV?%OPFVI$I0toS^0}>!y4av!7KLsyJrKPtp0<2XJ?pg zO)znrnf$F>Ns<&A2k4c1d3m{sn0p^D9N$;6`*CEB?%DbRRA5*PCpst>N1c%0_tjoz zUS_A;V66x3ss@J>io?4rf}9O&Oh4b|Vvq>hG-K^xqG|un4uO zy*%it+b-{UB%yJ$F|0@b_&7d!gnq*|_=P^r9c!4}W)zP|&Dad<0j!?(E)Y^J-^~MC z4(!8u|7uJ|J4_Dz&-E2age-1hr(b{ceJnaUd4dMRJI+fR+@!)P58ipw+_~kskrmsEWKm4| zyE#^HHeS;_w#;Y!!u(Y3(Yt2vdmFUGILo>MjNRf z>$IPf|1Ddfy+oS!cwWd_x<+z;=?&Xm89-k~KjgCrIKxcoc3f&kjl}cp$d6xd_+5tZ zW+VK=knd;uCZiNBI?%fkI(r2ER}HI;sJ4o@7`_m;RJq?)%l0eThx>PxFGQYSZ*KTH zSv`s6P}n*#aX#FCAh!fy>oU}6H|)&!IY&6o{7mNt5&Cmg7)$!0d*Mf9#m2?EI6l!t zUh=TBBc^!^D!*2F}s>I^jCA^yt>H>5{N&+9>TPJUB{$}?6{b)X% zsUbwNJH}4ht^4ez%N)7R0I8M%MG9D^Kv0Kqh?L)`H}5=b=WhJ1?R=YCfARQArwkQ< zDUNFXGZk_N%o9_+tgPcuom`->i_#DDjNqD3lgG$h%r`cA`ul&uej>AKT?+ylzs##c z-J6HDRy0>O4WE{}swlLZ#v8b*YSh?N6YRco_&jBBB!qD!C#s_Z(F|}FzFsj{S)(^X ztqnY7t61FEe)_CT4MP8C^{Yb&Jj%IoW|w$>%i#r*A4_eWunu!{GVE?2glEBz?j{t+ z#Hu9wNF?0i@=`-ftHS4Gmt>ZbMDLv`6GwRX=`oVu(FYQcyh&+jcCu9xag(zA{!0rnMni2J`d74Zyl6*tP%ImNa#O=!JHj%aag7x$ZXf&g*kSBG1MawVxirh(~9&qVyWBumS{r*&5?tKs_Ut99qELd@9j{I7# zVMaq_^;!&7W2_|qSZwp;3CAfl#|HsYmJTjx6x^hQWO3Jwv2MWLuN)XW)(HiV#4b zeU$*gT?D8e4&6EVM$Ij=U3bH4=Bx}Dn6y4y5l2vY0n-J8q(VJJ((3pTa0kBDayDjh z5_3_K|GDuA>T+>#er64nO&!O?)-1c^0VC_+-~mZQ@PHIuZojWz^2|;hdx>^2(s9>) zvs~;^0UHlaQy+3V46@@-(4-#oaju@Sp3UfDxqtN0cpfk|yO8awB|l;je^&A0D@<^8 zzt}wJ8CLa?swyS1!v=tWNdg%(J%c?p|C7RYZX;VEQN}5vUE3(=;FBBr>V&9m4h%qN zoYkTaJ0XKuuN&MzRz-zG*nRsU2M0lHkF<%&BVJx!P#iTEfc8@q-r*sn6AH@DH?y>K z-CKCQxwUmcp!}=0>+#8$+qlq&;(2j5UGBMATu)cHKXdBKPoY>U9sQY^6HxhQ$8QBP z7|I3S$h%9;QVy(0o&Vm~*%9}&_aKM*34EtbaUat9ZA0WI7J?&dvW?pip`q14rXX3- z&L!wfb>0CJ;*$tvj7m!Cz3E@J?gnb`cJA;w}3 zLAgM1^QN7D++2_@|8}ON=u^+T8mQ1&sTYlqa6s zn*}AeUliQ?h9+d$skn+3f6qC+1nvAJE)d(rba3)nu5FIP?s%ehWylbPOigr}L2t)9 z9eC-x&UL+Mf7bqGqnCT&!G^)V)(i+IU~zw}`HiQ-##RJ^mZ7DC%Vo;iRPF!fO3ZtD zrt=C%p$vAR`JUu4NWJg-7P_9En|=8$siS{@m42+P)H8agPC|6;H$|PqeJ$Nbt%FW7 zRn{OY7OZ6~9nY~={tFVkBzI5Rpu+f_+_nKn7~RThMYcsi8-W=A3UlS!F_i%4iK|Z+~k1e`N+U5=asVJv{N! z+EaTcwJwFV487?qNO8wwOxJbZ2z4mTNv9$XsmV-h=;<}_qAWPfSG_9Y9y4f@F9i+F z%*d;%4!=Qu21&arY+S+@AdCCD=>O-f1W_r<>}B^4eG&qRv_L`Ik<$`qXqoZrQfp=R!C8;D+0q)ovkWBPndlHAzRz(rZ5yO;ltZcwa2;`z%edF8`RHOCnK zrG0l<+POlS3aq0jYlgT8>v)6eKd7eY&bu}%g=j2Cjk;9 zuTHo^c2Pews}HIriI}URt%1SAFjyuG0lT_RgFA;}&Pb!arpH=Kvf%ck)mS6 zEc@Re*M5{b&c3>=r|m_uk*>-1PU_F;O5PlB7obStmR8|LS@N)|@Dl@98BzKxj-i7C zcK~|8g3~wPmJBx!|JuVOtNZNfo#QD8e-hhDYgYXsLRrL{mcOcJJ+t z7I^M!i)xE%R>~K_kD+sg32`SO`i%Ywzr`a+JZXx&!!I;r=nST-}=; zj1{dsoCB}Dyc*8pxK1khZ+PAmyQN!l)D7x)!8tmpx-_&QZWl}~WxJhXlB0!2pLCLieh^oc58L#k-`A;wkT6#PNBG6=Q~Y!d-Ckwx zB$5;?&%)VXIn^)qq%<~OS;f=XWPi@-9cL1tv&ynI)Qp(~k@2NGEvLFs`bForUuKiY zrx`BBZ#c}$fw#$`V}-9k>_yp9iMK#m)`eozGtq;_;DbX@9%(wgxM^9wPUyajwT(?= zMBlxC=BV?>1TNFgH%QRN@DAhcmOFgkUYQD<($Y?%&bQjCuYOtt<$fN!wy7{LBq^i; zF^$7JDz6=t^t7omGcy~y)rm-#eR?mxRY9D!f6#!?&C-`U%CCu}gi*q{S3&`s8h_2# zKaM!bytt5qZ;$N3{Xj|1lPBJ`%gwr{G!hk*B-$6mX*Eb*iJd)HWxSl(X6I;<1$IcZa&wnAauT<0VRrijQAng92)qFZ^?!pK5Ds zO|NzTt3Ir+PD2f$JJbAj16&jZN^PJARwz*7&#q)F727WrnEqflkyiQbd=jlT?v)xV zPy#`>)m2Q_+g9wIzUpBxIa%W$!WRC`1AF&h?XzMh{HEFI2Wn>nTxsR@3`w6G2ti`5Z?4@6?r92+3Bn6cDxi;?dnf1o+)3tq zrq0wttejW^pMMJk?)~9!kTq=)T#_m9g9o}AC-@V(JLo>zDg zYaZq9_78%ClfjPD2ze*fkq0yFSXFhd8x@NP89wCtUBNk2W1DKypLLV5LcC6{5U}9g za|%uIunEcmb<42TGg&#Hid|j%EXluZnIDx(E7}p*89OESCm~WmWm;)2DP^4 ztbiH*Ce-`E8_;jzi-PXyzZD?=EFP{_--{EqtEDi>;VF;8nmq!`f0KFnoq)Mm+|vn7 ziU3>ZjHU4W!2w2~Ae!vZE3Hg-;bbm}rl*kPJ>@37XCMdUWqsH($lO z>Km{IPImJrsQjAJ5}x1N90uQw#Qs;?z-zDxo6he;s1O}i(|Q^j(r#{U;+B~czIz&$OiO`E|>j?rBpID zE|qnnnx&^WeBmOk^-6aIZ}B^x=zk6j_xmMf+)&ihaT+R9dYfRan?dAsjHsIllo-uL z8NK)}zV2!rBKdxLP9c#mJazBzX{)lO9NxVccIwYfpl?^%>;KiJSB852`s(y}hxYvs zp_F{3wj;`PP&@V|_alDsI`z`(s$lQU)+lFuQ)<)=VvDaloZ_OQOpDb(Qma4-YNHvW z=}lgd?`rFxL!Ifcab7=M;H2_}?%nFbd<@-p;<4Nqj^fH6v=pbu6p_c2=~Fche^eW= z1BHAxoeLzw$x~=rjxS$1PK1MPNd=2AnoSdASug`PLE(6-G7kMx}bN`scR?!S}3f){okWh z)>3(N#Lr6?B1+SAeorMsvT>bwY`F|%eu&mxUxS!lZGAq^O*D_vFfctZeSIuv5#$pn zBA%o#y$1zCwWPwoARUbZMr;)XLQ-_yte}+3ruxC>U9Vgahy@{Zk`mDblJriS6WgNM zNn3IoPqtNU%wwbQi@o=EJ}L#6F4v+xB=0bq{HH&~zq2Wn?9Z!@qx(~>{Q8B&ydv#- zJIItUYW=!wSz(Vnp zlME|~sKRq=47oX$Vd{RHj&?Uhx&md~F*W zR>hnsfZ9&#lJwzAQjg$ORJJP#6sAM3N^Jjm<%=ej$Kfe{>#@Y`X27oSlzCGFl5^F2 zysV7j$K@ZYh)AHjw}E@scNC8I?vI^igP%{m*F0N^dYP}62TnGq3;9PRSl-tLA-)Aw zrsFQFUwSKeLn>66tpy+_+=7+6``7%!1O&|Oj`CZQe5N#YAX| z1QZG(LhFk5r{ z)CMXy+9%R^czLbUpw4+u@hpKY`vw_BjD0+==ZN_tC)SW^rJjQ25$IH`%>=Kc3OjEo zj>w_rw)l4V{AS{t1W~`vcbpfyE0YdD=a<~~_^F@jMU5ft-}(XF6CLN|bj&Fq?k+bM zR99!09XT9t0@bx36559c;!nd&X4{v#mZ{wDX5$ldFsI_@Ps+5LCjI6P27@ncZ0W})Hq-gB1WuF}T-;+N~w z1_`x19?|B14|~(gi$_6JUgOh_(5vSdpu@HoBALInfvJ5#K2_}I_C#RG)1#chBYt^P zY|AzNmzSe6{knK-dE+Mf^)Hiazhk?RV7TsR^Js9KuhoaUo~k8DNVX*CP>)Re{$Lv) zQ!i>N2jix=6`ZalTd}_;LBONbd6^%>?-;OqDDI)oZ*z0L=XLF`{ry>}scBM5^A&r9 zDJt;^B2AEq@OgvR`KRQg!Pq4dI8CHu<+e^_Q`P>W?QV(oB%nzg6gU{gJ(414r4SW> zowoPSTfIayU%uo)#RY}AZAXo2&bhCXH|cg)(!-kgNmDk<2Lvr&^_&45R^!9ZuszR- z=KB`7XX}>c3(!Pkb}&_VFS?D7hbPTCVP?g>b@trm2o}uht5%DuVC{=ht5soTz#)8kMRydyrUo*U<={RRAdu`3F5)H5({T7Q z=a=apmJy{&)B4Y3AO<@hE#^5qEb=jLzNs{92#vtDo>~ZrxyLot<;KzZ-x+xWJHa#* z00`}-HbcddGrK>9#+BJJS(F^WD0){xSC@LphSeT6P#BP==4egZ4xAfM(m_!JJZe={ zlbp)Y@2Vw6``XF|S6Z>UqT{ba(v#1UC%Wyf`X#~E0x}d_h?Gv%4Gpl#D96orJu&Bt z_709D6$Xf}qRNqdmRqGEw&I3l7eRt`0qbFh&ZY3wxN*95vXA~l2+H7BKljw(T3Zn7 z5zsG7($smy{Q%PC)0^+Ja~IW%bk#daFvQg=W~`M+O-zW& z!1YbIO%cXo;scz{n|h!J>Vw$rK(w6M{h^a*bEJJiAV7d!q)kA%nZbI$9+5)GBf?A7 z6Ceg9i)EAg=U^n=_crDF4pO7aB;{~w^ltc zl+`L2dEafwa&=;zGk17Rpm92iopn(HXjFO zV17PpegV4wV3h(?Y=Z%N9!ukXFJ2>_KH^uS2pf2S?w;wc9#^9y?Ty~;Z4U;JXv_Cm zKq-gkkIhL;f!esQ<@Ao&Cq1(ocP~`6oM`$z4Vs1`UN`D|sc(v99bGNrUGoan2xeWh zu2~;%Qgs$O2PF}Ja?5)21MHh8d(Y4drTUH6#UQNgzYF^YF9VWEZxWo_Dbl}A49*+6 z`nC6(T3a6sL68s7WDu=h0YHLP?dsw$-oScHb4S}mHzhnAR7To1 z7~U#syWA@`+ASygkPl+Y{*!St(JpV+xLO&+TNAjID?SofT&xUkOKaPDVEtUo10{w) z0>JhrFjeu~g4|qpw{-dg!|iDGNQ_AvE|^<5Nr?iA(S!T@0f4yViw+pvaY15)QCT`lTYsdVtf;xem+Xhh1amTu?|Z zr5}>3dQbcnxQ81y8SKbnnE)3-ZGYP%rg^CS(qo~OI%$ikAQ8;zX!#?xe$fwuV(Mf0@8SsT) z%o>+x$~I-0Mcg+iU+MOoCUesGC0~HQ9b1)OL_a9?JX)ymb%eOU-BLPxM>v;+Pp*PR z`(!;h@VJ&FcrTCh@gt+6-YO=@Ol?=xE`>msI{aimFU;SRiGm3w#RC{L3AYLuu-?fe zfHeS{G8H?n87cXq4ZnjEK3G{fI%i5@b9g|;vRM=uc6%ZL4)#N;d_CT_$?LTgU{P1E zc$7bZj^HbWiE09puB~GcmaENMZQLjp0sGiP{?f3bAeFk1K7t(lHp^YMq(V8oR2Sq6 zsOz-ec+yC(C4%NY`z++SFgejTM<_=w(OK$R-luuccJ&6IAoZ}D_J<;X9gQmRb=K+QH2C1EHn*u1A>c%XS z2(|B6kzdPGs8o+<@C`h{M_Xa@E1>j~jmHayh^zH@W{Q211 zM)lfnT`v>%g1F~OtgiyD->#sK$#)wBekt2x`&=ux*Z3QOG;lGCuz#k9^39F{06(l* zgGf0Xz?l3uZO1`gxoT@<`emK^^oPoWcZg93hk>P~FD5MYror3;8;B6zC!mR*7vYOe zX*N?DW&JH8)grB9xY9^C&H_CLfGnK$km|Ue&cZE^gczm@nNu{+f;8EPQ~6NXc#>~w z4a7SZ10KZdUPKHGw(Aq=j;VD zTqRW}+^a=K6gc@IT~AZ$!ej~kex~|v*)g-RGN5;2FHPW+GcJ+S$$BDxw2VHL0y7R>O zm2NxXqp<;$ofpoSu(-)Vq{fVATddCDC016JdE?QL@%05P^&mtID&KPA`X+b26M5~y z#My|O11bN^P}pytEje6jwT!I)o(Xjqz8gjA%&gsV(XELs(uK{dK1tK3TK=eMXgN!N#}WF> zPt$B2{i7hn_UU|SN>0tVk>C-yh3lABpNA!7%2LjA#n3Qqz5dB#)>rEo1HVKh+RUYW zO^pK$xKi}$D^Bbi4M*NzUC^Zdc$3ae9mXAR?!_j!19w!JzHibpswn1tWKHjNDL5w- z*%EAs7K5+$nX5YSD}gq!Nm?9hQHa#FGdj$2s5_hZ`2kjv9E*Yv+v%1o=i=D~eZugJ z{zV4T`RrMgve4lXX^H;d7RvzGng`3m^=?t2pt(5I(6BQGTdj5_d%DiSI>CR(z4JOg za_e8cC}|y3q5$akH>s}}^Q{cfB8Ox`*@*j^0t3-6i(&;(Eva zNbkHAFyNNz12?kt+5+z*ZHbX}x34oc;E;05ir{|SJZ&kUYpKs_Xgc*)>Gfn35J#K#BPDz3%1iUd%?$Wt&w%KEEUFp ztrLgA2J&hv^~s7CE%OWEEgse$@x^x~a&466h132R9@9I0KK$hlC^21i@~Xvq-QzQD zjyr5NPV}KfQSA zXneG(7k{$Kc{ZfRFtWadT%J4$OM)A4RB~LW`Y9OhEjA>+O>!nRwKhVj!CjZ9Va{hw z5l-`~rk+=_C(7m1TjEd#=oj+Ur@ivlI&Uzkm98*!1Lr zYinM*e}n${oaDAITGU-zu_F=#x0_)p1P8qwZL77vcYty#Y5E>ApVxsX%5gDZgwGtk zv{@UQalYa|UD?IDE^GU=X=@VO6g|7ag-1 zDTP|9qI8-Y=za@%Pge6>q}LIt--8?Cm)or9pL2d8aD;mF&++&9a~yBYdXc##2Vw4; zF;)$1>#;apbLPNVhf&0*&&y6!Uxaxn(j;rCH{a-<&Asypn=76|9ZSWl{qD{Ck%}Cj zKK&?uzj`{H-H?8!)$`27L)kO`u3d5=&S;=m2*qO&FyV*LnbvDVdwwlGCI0O?bp_O9 zWU?}f_j>s3%r~rEmHE(7u(_VaIgjTou7y}?%L3?ufjtI{c`duAtdEXA$DR&(jfBdq zX1?n=HTR;7U}+~&3#I#Y>w?J5vEQN9TOB;!FzRmBMxmU*If?S}m40u2Yr7TbB32Mg^G1tjNl-iQ( zjmueRz1WR-j!4{4`Qd&ywof=#OMFVH8t2U^{TW;Fa+33H-Dt(`mtux{Rgk3G%sRzBT_=3Wv!Ox~WyV zg4yJ8@HX-(>f{FU?e1PHOtyaZ`O%QQ{Xk>1jQK#%UN< zWLzC0n($v>WoE(nwptIO+<(7)O88_}bk0eJ)a^g9jQHbmpp|sC1ub`lcFzQzJi1ow z^5Xb+I^n5p=&l)1Q>y#nt!w-=cUIfW>f25K<;X)Af*I0=elDo0!5pYsq+HuA<*)Z{ zJ~;VSqNx39fv$RY65cUWE)M~Vv;yWr-OFECi9`)buk$oPlq5I*AS5H;JSsqDlU$3c zY?@%gPE1wx(p9x@?T7Gt_`+N@yhi)vci$h1Nr23b7tPDY6&$4c{)ljP9N{XnhN{ofqLN3S^G>%If#%6Fw9r6qlcGl+^7J zTV(Q6wRNCaX{Gg&R=_oh1o_=Y?7~|#BFXuI_)v|&cVzP1jJv>;a*wdA%##}yaX_d2f zA!dZC4$Y7(;(j5>DMYi2s6?-Xu72zAaD_M0Kx)qvhy5FqIx0w2L^Raxr`|aa@qESR zi}y5r&S4{B^tju~&S#d-N(9%8+AaX^gTERKe3PE zCgrup&(3Gs{@U9vUMO&Jo#sT&+$CdaU5%|lKk)P^WzG%LH}*DnQM07I$7L4ZXK^O{ zs2zh5bCU$6Vz7_LkmARpG~+46ggJ9B{xk#T<M9R$GgV@yjNsT@=w^Qe*1gQ>JF)wr6eV4T5eW2OZ zlOZ%Yfm455N^Ggz^s&mMemXP+9nM4hLMXEjHs``lyS6=}KmU!Gy_TjS>30&(xk7|| z01?c%m!|aa`F+0m=lY-gTCS3Q34Ar{@hs->3^U{qdS1I!ab}?YYUq3F*Xt~*`9<_W z`%!`Q-+&MBe)@?0p4i&!)mZHQljEIAPFQ6?e8H8+ry&;z(fhiCmdJmI8&pk0IeHKN zOb)@A@2=-DzC(iJeL>(;i=eg^1%yO&IkNl0U&X+H?)aQgfh*)FBvy3M?I2Z4to3{r zH%{F3Bf3rg=2skm;*dDS==?~Y z{rjgd*rnruh+s%si6^84N)n?&eg}GP0TrLk_;i^_sHNiD=mw~t0uLGif zc4d0aTPi7#5oGvfrusdJ3fSY3Mr8lw7p8Wbx3qJ7YdQYbS@bM&HH`(~2Cv+Mp`Uz^ zS~Iv(EAJ2ZF&~@Ub*1B4w{WR(c@R;;g{XFY6K0=g)8io1cYeDIlYA6&9`nxGWPqSU zrhvLj>xVKHUGAfdr^Y#7q8?aaGo$9m`2cc zYK*!ldPojZ=H2g1^~0{YUd8f1o00CVGpDeG#B@mp_)=VqW|<`sceK#y<%wSNFvD*7 zKYK;coEjt447!+)u6X)}Kv$NJ98qt%%{)%a&5Eeb5NP zkl#Isd)I_yi~c7C@?Gljk(e(u9a>AdFMX$ezk=jkR-zsb3zEnQJN$%DuGAij31*uJ zMCN^z{k!EIt0gA#2`TcTxrtPYy5s${-~-)#KD~fLGXL`lA{}Qv!ueX~TO-fwBe}CX zm5E;Q8i2~ek`N6Gh*knceUW;bzFQw!U(>ViDWjiZiT+Zhr&2BAY_r#kDaP8+?jQr|5hf0upp$G*h1ZcM2nt^_%T`{IoolrFF+BB!pm%nv_ALA{u9 zcRfP`e0@0P2___{MI#c&MgBM<>r(1G8jO~(irH$3Z2Pm=Qvi=V1&;VOG^GxBwIN_2NHrogfi=e+ZNf1?$1kKB=l(Tvm0s7 zpuL+pZwr>-)-NqB6>E{UCHPJNO~FoLn$rCQ`^f18dr{oVqfYLe=moB5i+?K)J#_>W8&Y&?tBs9!E^tU+=sDu#wz!5?#=jKOgno! zHQM|V=i%V=s4xlUU&7bE<1oY^gj>b#@HGIvO!Fnrvry~A5Fg*7LI=GhVOg^Op=9x3 ziX&+Kot(XW5nd^{+!K_5A8Mwg$DZm6%-nHi%GijD$oHfn9H9~YD)6N|BDBRQEi*GH z_#WlwCWHPh#ass(!iF#On#>*tDdi0h3CG3>h8Y z;mMGG0M!z9wVEgoy$!R?=o^{$r-ifc)Mgn$bGY`z=wrVENASnFcOtkdyS!$78vBkO z9CvUDJ>PtqALqxzU=w(%(tfz$yPXW9r&&qb70u82c`k#^BnumCig=~2OT^Gh$Nlv* zH$$9kwb21S<~1A3te7-0-v9zR5{J|~lE-s*w0WP$z9Z6FZ97}Eo_vXx9|13imG#n9 zaQ0s80%#s`TA)l>)3;Ul@(IdL!e@b|Y0cu>uf)UDB2CV-vmK4x518p=n^~EePe70_ zJJ)Qb;aREo(N;M-tGQzEcKQMl;VkCKJe`WP%G3TiKU~8EgmG5eUs3yCW$q0sL`uBB zf7_(Z%;;a8xJ%BMbuVR?))q?;siZ3W9sIOeD{S9Xk4#6uXWr|ySi!%z(hH{*I?(B{av z%KNBvbn!)G6dB$9^v}18#im#lrm+UF3Sx&vl$1klN@@2d>(MysC1dZRD?AGLHHE%i zYqk+Gc_6%6tG5iQx~1N}t?<{00=;e286kWZSbq%N5~e8BEqNU>xmb zk>IXjt_y)Y|By#)@(LK$_%;W>eUWO*eZE_fR*~P@xEmkbS!tw@3{M&{c^Zkjarvp@ zB(TQ^2P;^1K1jm*dV8b0a~a~z?| znE{6Nacj=N7FTUDdU%S{Gj|)wPn1rh8s;p#FfZNn?Ded;*S+q=Vd_k-#tJUiI|FYVo0Gz(b3dbuK)67;OwW*G zmO{1lo}UVfih%CclW=0+@Z(4|d5J(rbkD#F(Tq>+&RG;UJRzepw5v>j)rh^~26Syc z4DxF|c+_IqIp6Df;mLkiYXRRvW}Z-Z1!)yvY2^o9%!zSpva+-9*o&F&hG=@jIJInF zc=Ys?vUrm`$p4|=Uty3Eyxwc*pXO+$dOKffxqmPXJczt}{E=2&S8R3Bcn$E&JT0SO z*E%)d?@hJB6*4>W!9R<^7?@h@n5P&Dq!l^XeaLdSDuy0@tN>|oo@flaTQFo44w^Q% zVBaK4mi(P6n2Cdm<)yTn$V**d#>(#X*LbKDNE86<@CcPqg2lI}zFa|)gBKIYq<$tA z0BBfCKQVc}ERGgNb4o)>mY|D0&gIEB5`Ri&J`*N`Fd6(FLe=J0v_X zj5k5-Q+Fqz!$ZsidyS)#%wQ?DsT^oy5hW&#JR?`LlR3HWWp~8C7e;JU-SS4du zYc#4NR{b1Sy|fYQ$K709N46Gz&*O_6iG%)xdyv9p6M}K5BMQj*t8kQ%?C~8N=|rZ5 zoHGD*`vm=VdGqC7d&cWfuV*i@FasKa-WZkerys=1{LeQ99Sy@8WqYkThdTsVgVMJX zN4?kPgK4*S?l{CjrRV1!A|wbXv|-6nOf& z5fF1LH8m36goyO?*DyFfgcQb#=CKPMW`r^_y>y*=;)$#eFDOg4lRdFWgFR#l>Iur% z-jp`}gfo|?@#!3$oh(e=B<(A6!J(?=aM2)Y1NrOMFaPu}cCmTG+l`**?&p1gNE3JX zQYt5bOZR=eXiCoEZ2{QTliGG0-V)1!7jL+@0t|5*X=CcH&o?wRHC2s_RJ^^t#kR75 zrmw(NfsUjkdWz3EV@{$YPUxWL)oviamX|0k@LN{FV*P%=6%7ba95sdhbkfC>nHDGj z$X^dQoiT%Q`)9Ct3**(`y0jlAm1v&*(d}MPG2-J|JRF89`*kCx8>_qE$(fT(vp}>5kC_oC|}WEUn)-6q%9@; z*RbL~;4vGFo>x||N+WKAkzR)dbn2bryAEyj!Mr{pNC7X;s*@VVXvt)_N630*`UY7o zOlGTpyPONF`kvXlu<7kW9nFyy_xJBfNJ-++J@ib1o5g`Q`0E$h--QJ<-?^BC1bBg- zzJ53D^{zl*U^W55Cn5G4%P3wf(@6A;YV8eak!yVNw?${wgG0&n^DaNoFtf- z(A%d5{7IwC9UaNkcwPB76DaqJj*m|}WwgTMXq^T^$+$R4#1{wn#?SS-s8Sz9T{!Q? zFfGNo-fT`Z+kVe&$?;ai;xTFo5mg^o_Xi0%N@grV*Xn^BnG1_i3KLA1lv2z~M zNpx^i+irqIH%1gkngA*lf#5$zueT?9=MQN7s^;|F?##M<96ZrGmglYa*1G~9@bUm? zj>qfg_oQb#J35RfO0C34OH`U4CZcpKzL{x-`Ce$ch0~;-4_aUcdZAF)WwmE#wlQqs zSkKt|W_z`(l{7R-WPIupqDZ3M3^`>J1LITaA4##W%4E+g6qbapT<2|w|VW!`orvo7auNINEE6d7a zb?lfP{Ko~TtgNIqtp3y0jrxBcvk;$^f*IqH-Z75&`bBnx??324#&lL z`SRVC9+1X~T>}(E$%t}3;1;S@KH6DZap+&Q(}080va765`P=deD96Af^Bkrn?s9T! zI>B-$BF7%W53HMajCzex#9_lvV#-oYT6d^;pzQX6i zC5)Nqg2NjY3JH=2a^jVqdK#H~GGD#&s0rv88JV=;Dq>jExsssB?+okBzi33X2Y6Wd z0k84$`E!YS!&`H*N7WkQ|1+n5CT^&qrq&1y7n+AJF;o#= zG^P1~$EkYc4E8GPZ5|mECS=|UvIUGk8q&AZTfKZQ74{<Rfq37e{vovHqt?wxEI0DC^SiX>#{o5M{n9J=aNKbk9 zV}h^S+)4FlZQu=1cmg)^87Ol>^uC30>-htE=RvsVIJipGl0(0K#e_tZfTJJ6=$#_Z z63$&*hQG|_*p@EgXX*|Yj>ay#7YdPz5N)wlYs_D-^!hU;_)G^7)+zYZRYxK&B^>5B zABvPwY*k3M+v^_cTQpiZIB>SMwgP?VTU7t{sY34k4ImUXZV7qx)?4T9e1V8QH>C4} z>G}EqE?$U-LZ*CYK1>z)XQ)Y%m>}2>`2Oluj|r{W`fz1bw337a)0p}tC<7Zq_XKNQ z4wLCKpW@QS&!C*SlsMS-KA?b!E}MY?N7eWFk!H^?E=p^t52go0{n~l;`B}dMmrgdP zF}HLB@E38nib5E&0P7FUu;2vB22k9|4gYD3a+ZEc_{nsj7GVf%51A_v-9p4jO}XOD5zJKk--FR*xku<7QP17qfK9i-8vB9%*iePS4k9N)?&kpjZ8)z znm^#D0@S_kBX_p8%tlXfh2{!==yXI@gtI03J9UD z)j!3q)=0XS<)~@iDybG396go)d#o&_?DmA!34>8N5Sk8UYt~4RdBxnia#J9am4}!B z=@}tPO^$Sqj{0;R#lq?yDFFXaU?6>-7A2kssBLTx+!8 zePUgt{^s>Tw^t~kr)z&{I|Sk-(`Q+tjNwaI>RS64U>-<+ke8GD`fo!Wz%(0e$sn3*nSx3IXtbR%>H0~%7$9`MY*GYWTsoT^ z6KuYpwqz7F*Lkq&XYQ(|8SJ7N7Rt~!wB=pjmwRfFR|bkjk3wQ*d_-Yw8r(0|Dgf9P z)L7UA83BO92?7TKR||-DK*dt1TN@QsN<>RLx+EGM#a%MrC6G6EbDv0mdUBkTv~iIK zAozYy{O^%(1MLIO2bL(PpOb191=6X#>RglfJ!>xVH)aQTD%;4_g8kuyEL;)+i|u)-T}N{h?*N_ zYCUh4M9tQDi%i%~RXDV?wY>p;G%K~Z^MyY_K-LKiS8D3S#Kp;(o6`f{Nn(E8{s}ot zaGAt5q)py;Y(*hKDVi}3@Q^?*?VbDP)q+AoI3Fa&kaNwRe7w|3l-5_6ceO52IWUSu zra&71qdobqj(46jIb(x@RdSBhE7*WZi`kkX={lBiTJu;&KZtm&N*h-NV`-(@fgkTZ z!tgdWq-$RYP(jExVIX=%D{CvA^@2@&;p`X1_Mn{o2>`4Rx!t;XcUxVLx2F}<)gJ>P zRWN$c`?U0vvQlVOBpZQ07VcTy3G1p3eH)_%MDz=mY2 z12tS+C5d^fRZi49%GvLddcZVrtimV2N4}K+mUZ4fSxaFFKzH`4o3m^7jE^5X?3dbP zX1oVN#TMZ{an$t@RVyl@-flK6I$W~78<6^v1=7YUJ5-XBTjOAN;o!*0S(vCifbQfJ zz*TrSt!>lxp17u(wSIWYQBoPy5~ub0N`F=sE{JLxY#1p6uE^q&`#Z(F=RBw|)Vj5` z-$q9FxG14Z7DlnU*Ex#@8U~h^a~@i_G!i;(yD$mbFoe`MC}{n*=Vf3B3JPi~JFdH4 zi2|^cGK8J+$AZ$mtqvRB$hf$#<2EA&kukSKyTkK5bky`jD8u0nvQNqyj%~LP>vcKr zN>I^k`!6`OaHfHxssJkS{^^3W-FTBtN!*&8oT7@n=}61h7TcNbnAs}=H?xeoy1N4s z2XdoFnhU2q-!TlB;g>= zY;7PWmMY8f9#TxkbPoZMkgv5{MP0ylVh)6tlVds~qm>n|irI@^X?#sGKAHNwK&UR| z?EGswx&Yu_hzO%}kAcnVz{@S@Lm&2KsgB{H9Ui!Lh?G}qwW~P3R)@iuKP?xg4} zzCKR^1Fy@<;97BqsRQKn_WEla#f7g!kKAc&$appde?rNSdI+y-4R4AL)h$AGDLoQv zzryL6Gf}LvJ$&w|$GZ;{8ZU>Vc|dG>P_qJIgp*Y8SHl?MXpLDvq#d&sO=(e^Z^A{Htl5!CP9U^PSe6 zvmf9?59p6S+7Q_LLTqURY5mmsiabZTHS={#qK}{pTsso_+N;=>dOei%s^%YE*Z_BQ zkZJqLw0cD)q0(=mV{VaDS|dv`8$x9_A!g zZKsM*ug30&sfu_A83FwhY&a=tbj`tcF>zK#D|!Y7EVQf%BNGY=kBOvEn)Da}(rrv$ zXQ%pFEq1lu4vpC=J#U!K8i%^^k@~V`N1q!o4ulu)ru*J9Ju?$CxVhg76Xq(694~IJ z4YxB!F`hOLHSS&jJcIzb;1)+fD?#{Tv&3e$&Y(WOv@{A(JT3&}>F*Xmg$@FHaR{RX zxdO&c#7wj!Z!C~$zf^d?TU-x+eO=9bI;2r>pc8NtQ9H5vSIpP*TMD~Tqf}qiz77Ig zm~B(#CYjHb`(jj}G}>2W4|~S-ygoORW~?L3`nog5gErW0-2M8eXT`?0(SERRT`*jN zN$<}6NEfDp)l&%Vq%goAU#%;!KZ=Z&(Rbwy4hyq7-{bX*FrCUtdvGRn_PTqWTuM?h-*rqOPrrpu;HY{!yU(qfKWsni0ijRS(Q1OGmHK zAQ2$KM}aWGDsUAfZ`}@wj0y7meccq`#&87$20VBmCTVg7vRmKhr`kpVAjf9BnBYM9 z6~NR1(8RLElHA;{w>EeC)z;Q#>#G4TIWkqZcr$xyRK~A|W|=?Hge`Xv$IFR>bQeot z)~DJ>PoB28;~IKw@KPxS0DVZZ*-^9}jyo^yofZu+3= z(Y;qjZExtolm(aPJKWv}VB6Yxq3#e!y3UqQf$zV3MA-R(6o}N+l$;YnLHA8I9Un`! zH#yv{<$>h`%$_FNpXYybk6~Nu8qqCmo{AX$fKH1yk_XgRK;}Ji+u-z$d1;6 zm0!nJoDFd#_-k8Fug$&6i4N;cX#Bd+7MWc1xe|3_vQbB_p40QUp*?!@pz_RglA*hT zBOzPGReizfU}=RmlHc?30x4-qLG-c~ZP9}A@;9d^_WSSdrXqnJCr3(O4m(%@mzyW; zD4OL>b-&7W#h$KQ$(sz`4AOOAS z=DAg^qg?Z><`C4x^|gRL+z=6MXVHW?*qjw!&@BX*P2Fg))Z2x3DLfHvCt^!o+3cr> z0k7X=XAvc)z^L-iLgT6X_J$PL=lpTm=KK|W{y2FO4ou->sKhtsqV&d)HwtBT@}?91 zc5gDkxY5Y!@w1{>0S)@cq@GMqrmrz%1$-Lu#oRxyP=lyq(C^)u$D<%ErT7Z_=SVcY zvOk9`PS*mR=8-P8jHQeS)wdD!z2NA7E7I`ffrJVL*WNG*8@Hj^eGaw&6sx{u zzP$N1eCXW0wuX`IT|i$5e#3pJVVU)Z`>{*+msH4QiR#ss=d620|lvXU+Qsz0Zam4iTV-6nfR4O;B;F1!7EA9GU z|Hk#nhtZiwu%tpJK%}rXz*+#u{+rh++hY=*5^_-mmIcK&(XENTyy7D zN|FcH`0vbV%}nev8u3xeDaJ{j@39W^x%xh+{FjQ;pf{_UDdOc!eWDAGi?iV(hlYMl z6QmD&i7f8q#B7r^PJZC{G@ISoU+hzaQ$jP`}TgnSZn)lJI_rF{2 zM74#zjw z?M;26bQdLkzX289-?HKBh5vF(V^WHAtRQX-B{x8wpgb@KEhF+*2mi?w!GYR^f-xzK z>|DZgDf6z)s0P5_&P*RZLWZQ;dL>&yaK$kjLmZpB!g6dJ$U?#=j<~plxo;uZfkeyFYDZgs1vtJ4@CO3G3Aum2NR%UX(`CyAU4f0PozOUt8=f#1ad+D%?adfO-3TqxUzBH zoGp$Oa1R7xWMf;-j8sOS`^MGFPgXt7O3a|VS>ArT)Td>R?7cUD>%L}V+g=gD=}S!h z?mn2QJldJaDOImu=kC-G$)^^oqHdvK?osd!06sL@$)>MP{dHZ@6EtI>DbO9ShsKdG zq*Ibj8Zdv5x;t#kw+^wD0;+kZl%Z7Yn4c9={$00+@QFiUvnr?u%LdzgLrmx!kRG@U z7mn{521Dd0b&rFz62avkbu_(wtbw3Us3^t5&3)URJ$BuC4}i(<^;ZZ=t|ka3@yTv)W=li=8s6}AmT_p9SURAEz}d>FetTrVc|4M}v0<^RJEJ$WI~_4e z+ViNbIa^Ku5>)B{ky~ZJFRMan(NLhDbyf3rzS4C&b6b4TwP<;7;iwDcdE#2*J^1oX zuSo2GTvFeraLfx(S`a+ZxzcsN0R!|NA)2Rk6MF@q7%$59F@2-g&xHwj6;_aM(jZ<* zxs!DH32&;dDqKO{0GN{$l=IoAmMqzI1g4FvBNeVJZ@L+LgZ`p??GxB9B3 z8%2jRQ`EA12OG{!k)0(b6F{&a=IbG>V%symP#o`tsUY2R3<7ifs)!$0m&Znx&H)}U zxd5mHvRwIc&FFtXOV>xSg9ZY^zW@mp=Pusdf1)vW?03hrHV+>13H|o8`q(+uA{l&zGEw^lts+?3=y7Ma#33G`rTJ`;$(kPfJPcDcU zkP=$?JxvW$X%xc%;i{B)5+#EnUKmny?;u~P3Cvow>f4g8&D`xUO@_HqTBA z`nsY&g1CD6;Fh=^;`e{f=HCJvGVbn`*Cit(ZqEi_s&q3xr}q7Q7>vT0zLZ9+()dZU zxjnni7VHC~5yKNBwCTKWy%GV24{sO+r!-GcRn(VVE>KEUgYWE5CIh;GiBlkR zb*(NM(t+w;%)EOJr!P8Ey+|)zce3N^6&am9E~j0Yb(OufVe*RfTWs-q2K(+3{`)2^ zHZ*Yz_EQFg{Z&7%ixUar@)Ua88AwT8cwn#y|Km0c8-1kU$3^{}DZqx!1OK5PUB4Bx z5u|Mm=eWY>JG~o2BV%k|gn4iIW+G!K&Ubn!zQv$vSjtYbfR1m@n znWTlI-bzW);p2z%Qw1r*RgtjCrLKTcHL#o8dp_hmyzpdxq9|h$*zI!LO8IolC%IjV zipTL^YwO>`I+K!;di(}p7lAoRO;#!(fZ`+CmxxKK~N4i3r$5NLoZ@(+PNa&2O! zmKE{p>HOL@&!PI>5(id@{}x__#LUZ~+69UiE>$V_p{sU>XUW7sPw|dpJH^OU*0n}Mp**+Z63Z(DjL}Hh_SRsLS!|?04%2} zr!?JHV1B+M21f`Y^R})xm1TSZ^A;>697%EOI0BkGOI_3F-9z?3^J!{VgPqpy=*9** z9Ud_*vGKBuX1#D)T!`WBVm1DU$lXQPFGSS$d&Tf=_ymbw{+1t=w*h`BF>T8ZC~D)Q2{H_+DM}6Bg;b{6`1uGFo|80~s&#_(N-zEg zad{L-UmTX+!4_%?R4%oMK>N&H%}G(Q+3;!G7VwdbjT}|SJcs(0rXUr@Zl46o@;OY< zyy>&`bOIm*Gj4GE4+6Xo?l-)40M(Y5sJHqFDTxHsG6*8ZKE3IKoN`@UHPLY@!Xc*@bX=3k`tNuqSe!O@Aj zAzr;7=}M!apge%+0Pm%6MlZB5k_y z9OgxL4mDXvyo`hH#iS`5fd%*EGe+J?=wVR|bG1TOTUMygsSu z9o~9r8$YYi$1Pl~k=C$GsDkX*ObCpRBo-A{dMA&5*-ppa7vQaMdZDGO*GMvjQ(13m zB>K55bj>G!4#;5#L@)%!5xKcP2@e32ReC}dXmy=*Tp;Kee68=&h{XG4`>5r#Zfk0$BAAV-FhXH24y|FX8*;sYw4DtB<{63nSFaNO0noI$hOZNmz z_fQojv8%Db{JTZKgw0H93KB;dAqdLd=C{x+88m4zSL-a6_A%N}oTfP}iBEMbjGZ`< zJQaX`HVmZr-kSa^c4YwAvjuj;XmnD=h%oVenCJ;)_;-Fn!n^_de;73XT=DgaW2HaP z(JmX@Vg@)X=Syis@8aY~*JF`HAnOI(FOUUmpeP`#+G5(iG?ss8POBm)Ps-B|YTK(qmpY|1W_kfn_NAAZUn-ZWzjJc3pJ~|aRcSo$t^jb?DJUoadjs0y^LP&f!-cLu zHOk0ZbP#Upg@WbAOqydIP%qfOnZp>qzP7gkgenUPW=|wyX7p=5)n3&SdY1!_uv&NR z(?gR7JlE|-C!P3HUT{B19Z;0dhSL-@4hMMygA@OjJ!<+fj@&siY^vC{``q9VhcqNm6E zGY5TY*U`taol?`iz6Xsn%NbKoX^o=tOq$nl<7jBldNkfL^-PWy{T-Rrs4I6fb=!H) zaKkpKWcK8Sq;7rm)7&=ohpWqn+x1?8oo_Yus2wi_sb=X=ls9Z|J#Fy6T`ap(-K-$_ z2|BQEMJCU`_O;FyBu&kGPd&7_42sab@LajeC!|%rXr&#?FwZue9vE1=4%AA6#mrpTbZ%?9tahwUrmZRHgJzfEFlVSoLKGG2>^K2YqLk0Z0}B6T!0$(S?IPv6aYr_T{J!qg{bz z|GKrlcgwR!Y=C)d`l`1ei7gyeI@y4>&G_~HV`WY%B}|DI?tM1PUF@PuTMYSam)8dR z9v8FYDCX!W16ENmGtKgZ-gOt>wr2puXvgC1*$)3o7j`9Vj;AhE(|c{Yr@CIRtDVOW zlwPYU^Y=ROs1>_{!;`7#@Pl56z!sUjm`9?5vZhB-RmO&k@CEF&-yUZuJBzbZ7;7nn zmVNFtP^7NbzW!~+)c}p&zWljY?a2~4OG5_-vH;ZVb~L_G;)wp_a#`xevvM5_ zE3a#T`B z_+Yzc4i?$Ju8|7Z>s)~(KAxJVhK^o?p8B99z{3Lw3jzY1;-d%p212fA##7@olGs{% z;F`7eI&_dOaNI5ZkFyLyo+c^crOJlWkC4lFnZ7Y=r?8q(@BU-NytwR}lFNzH-(=yd zCsX8z>DD{mTX3z}WtGFTzg@+5rYI69qdnU}xEyYA|MLo3!p#x4O8p`2aYRy|+s%$3 zTVj03KuJWnT}{N!q0?_JQO6yRXNwq2fvW?Z(ikuY?jl*UNuM$id=-4!n+?X~b2!E* zR7c+)rS4-gDU~D#`P*Ky zE(T$1CgS40_7F>0dYYjsj6F6rU&k=0dQDC!sJt8_)VCxZ5KMhj5y6m%TY0d|()Lt$ z?EF%Mq+P!`^g!=)Bh)w2zSHKo?)-`2^jK3V^Y&cXj?ya$ME2r|?}wIfc88&H24Z|7 zu@u_n*&y%vjLU=dl1d*i@s0QXJ>D#X7KeoEZX;3AWG;GJi|OwMziDcsRU%TFe|bJh zLk~KK)Legh@ph~ai z#o6QQ_WEUiQf;U6*OpM0k6UKGizt<;M2;nCSqc)_lp`}7bK9)KtuY@iSLVLAf+-}l z*yS}X#1W(mV@VC&n+j(ph6EaqP2=KC7HYN2Ro$*XJ@!=BpHcyo-QU-G@L&^At=j7W z6p^kNRyqLzf$kW<-Fc+%pi9sdeeG;PhvM7#nBcQ#O}Eyw$u(!fpve@XK5KF#mk9qW zGp^H_2-`WKp~ohpf?8zA;(o1mYhN!6jTyVj6&7N>rn;StfSiA|Et;?A;9Z$eQbz^1 zcY^kc{RbGl()r(#Pd8|4sjm0f)^-2TEcz&ASr5=ayyYAN3ESADzdXDzRKvkkjnx34 zco5K!{OBi3^*|V=C#o6P40r?Fk{B7(3E!@Jp6(K%YO{#g=y&Q0*X{eIXcM$=tlJ4g zK3#ewjN8PF0DK0{7UzLg&F9OR&X522_Q7fS&ZSagAT>wrZ)D>cOu?5p7aGj&>83An z?cO&Q%g~*+^OWy3tsqi)iq?UeiQ?OXq()E$&9*hZ4tWfvr1CJnk7bZyE4gww$ z*w!6C6cwhbtNPLM^nG96$E$3nnnydHv>9!!B?~GAyL+RCnkqayWCcrc3<{^2y}|3_ zt<}En7;WF0SN~t~4F$(sqR^05L5pHB8*4p0VhiJ>nt&Ud>2PhxQbSq&LCLF={q55o z`$-it6A@3gT!+qX(G_*Ji(Y+t>3g5fc2BI``JN|i>{R&gWp%wbsG=-bUuY15cUG@K z+VqPPL2d@pUY+VbrwKReE4W_Uq69k=O(RbkocxPecPFcV)=xQ76K)Ad*QBtu3U)~z zo-??cSx5RNw6WF{wKcvz_$tlg<>x)kOHcvAYw!8{_utMJbK7p&>$Cco^l=%_|JLV5 zP+SD)yK6jc_x8mUt7i>fJO@);F`$F3U$M``zbz^bNfD_D-JtgdHfYtq`>05vwUOJ> zs!l5|~P+$ddj{W{cin{kpF4GGWIeCBrIcdkh$e61)ssQ={Og6;T`G%hi6e2?| zXv05__p#A=e+gZ;{(p&y+z4HaA*S}bC66+moneI@}XZ@q6bz>`AXN~uulGQM=nW{DTWvrky>;uqnyrJZXaKm`=CM&Ws1&cm_i z<)c&P7hE4XctqeFse3}x8nH9~XVSO(%qfR!Bk$Fej~Np%kLZyIf$W=+&9qRDCN(Fn zIdxPn-&8=)*=vsKA7GS6y_cnLnyJDPPMSJ-!q7W^GhV&3oBih`Vqxc{(%ULaTtEpq ziq*5rl2JkR{v#5J-7w-t1oU+X^fENGf;4(Q{WaUvgEyJ1&r%=wZ=zzR2Wt}+6K83y zB;)A~qP*+#nPamA1XcucI2i;|rcSt?eGt(*UN%#nZfu)!Pz;@Di17~mt+Hjh@Kf}# zqAjQNZ!ue>q1V@HtfSNm7rrx0&GQhso^WS} z@2EudCaq3n;D-x)TMp*()q0k(Azq>ekBee|bMgjlkIr=T-_zyY68bJD&{@?d*3Pjf zw@o|z)inv5>nzt(m8_*mv`4f}tFucu;PGNa#Iz^9K~C^*-X*g1>hd(Tt6n@BwGNd% z&)4WUZVbC6t|SYB z$%M;h`>LAv9(!%IW&24@xy4JuDN?1d!UuwQ_0f%p`uf`vJgCI-A)yr+l(j?H5N zjXf58g5bGRg6nscF+KyV53Qzx>aK($BX^`e{Z5I58Lad%fPks|7yG!RUXntNS6}qj zG<9uZd-yN;`H~XM9(r2gTs5XKwM)J1J4`A^m<@yMGjRWvKS~>c9!bS zp}&P_$Q4eq)1+M~I}xMwg@04HV%VpidK`=$zO5*7^bN+a!qPr7<1vNDWi;wY4UT8V`o8(1b7{)KsdMOc|fUu4By)j~Rs zG0yhobDieYiV{>_ufMuNAY^>QV`QZEn8`Z8tB$|dlL>W8`}hcz^jVXDOPE<+ci~+3 zvY6fk8F3Koyw$7L%BI+eprA$fcX^r8+4yPs^+jLaQm$zD0|Em23JE7!-yd?eKAdww zM$JT*@cy;5CcEp&X**@1KcZ$_FDTwKQz3_~r_isJ{+13Dvrtrr-U|?uFx1I3UrrnA zJ#pR8a_khuNb{>x9jM|_S`+LKK;CRJ9My}Bk8fbvuAzRo_-?IqC$nCna`_+u+*u$T z!71meL6_BjPf3%XkMORChiK?nC*Ql?L{SY!NHwF`O}Yk9V3`)u<`{g;SiEAOdB^6su50>G#)a5s;P=yW#!=b z!KjhlpDu%&tr(|nvXrZd`S7{)k-^yL(TihWk%ZCk2u^PsW?_XszvWVr<7~w89?cQU z%2~q$*}7N>Tc4jxR8Tu<5nsq!adgd2wK$+zdkb^0uzet1kJg{oPI4DUY5}3Jp zd&5x+O45w32PuN3I|v(^;Rzz@{0W#cc3UMU+&N*dlR{5*o%}unz3#F{5^qnj?=iyD zpomZnvAOaSp)^>f{or}NB8UkM6?n2RLSwB{>A;nsm5aACNugqa3mea*<{K*Yp`P-> zu$mM4Mp%~goQtdEuq*{LgF+j=UYg$Ur;e4W&X0TXrA4t~)=5HVCqJf%%N|N6R;*g| z6+?Jrpak~=?)M`ml|!!eYr{r)-|aeFlA8OqDr^aLU1{HKpDVGQluQ*%BN1H<2o5u8hU-S)|P04}ZANSgjmjM6|f5mKrtv{pyV&1e-(s1oz=&`OjTA zA76WEF_N}yGddI&^W$)#t6PxQ@5%O-J_Wj#ee-7{x_5oO%q1#W)t}vxs!pAKqr;z8 zE-uH+d}m*o(VBSEhyBV9msZguJaHhU@UpAieZDcR^pJ(RUMq}%j@~*I3XOr0<+S&8 z?jaUmz`)aQUqueJlf+|=N^BGwB7ncdWj;wx(!2eE%j0m*cq6CJaiv9jY~=i-VKqW0 zPFx2WnA@A80>i08$Z~jh3i8(YVm!5*Zk{@ICIQJXc03=NrlpMt8_3_Avi0-x6W(hf z2H~hIrI!&&YW4+siLi?vQnUAUe%yCjuw3}acLTF~hJO{r<@B0F6v({Ebh7ShF&3gk8xOV`035Sdf*y1O$?)uH$sazc$#b{N5V zS^nvv_4f~vDc-+93NiMU{SWf-2gazicOk>yWIccJL&|93Qm?Y#TAxpEHWq6eE(z5q ztWN6tx_-;Lc<*)UX=*gl(|=+6?Bxx2j&c&cNZ;b6T`mkdp;~1y8~P<{ws_ByS0K0g z^r}33F*e9Q=y;UNu>QBq?Dk7UhqRpQo10C3*`kF#mR@?+o|JQmnb+>^XBJ1an=I+v zsd)4?jSkn-?jhgu%xuoR?ir<&iMDfFB8_?DI2iN47r-f1OH&YfgpogETYrlE4Vm;} z&B$mT5X{roW{=`+^F4EOqZrR|+eJ0;AIIeDbzUYI#mLyNY@V?g?28WVtjdK5Eq#Z` z^f5TC%f|SW#AUeK4nqdwTpwY6SR~1SGQDCTC@GiHps-}0YF!F*0E|-2`^h3t)#3xO znl}ka814O&e9@V7Z}}Y;AH4mg{FAmn+=P#Qud}^tJVobQ?(2X6-<`juxt9WkOgk5g z`nP?n2M#6%P^Mu()s?*>85@-hcUMjO%cKb@j>)8ZL~2`KETC%rr*3^%M9YYcAJZlp z`tYIP6Nncp2)JynlYmmK2G%GR?o842*oILrS`pow6)kIlZdj%i=FoZ2EIW#*TUjOTY2QTGuPnD1^@ywNu zj~HlRVEB=s7g?CB#ctbCk5&IA)=W=*KwzJdN=Wm$i^XN{34$@G$c33}Vm>`*M(E+?;CTf2p+$v}N&H!r4NBZ@mM-+THqZLoi z9DGrAHfY8yY8}&;Omsq}nd3aoXW0V^!n_>htg^pcFXaNZ5xGWsk%YHX9VlbbT_Idw zCDWZI&()zck*&$t8Qas(kU*EUlWs{G`v^0eNma=v500})C8{0=N36U*|D~A{NqtPi zaFc5dW`IJPzr0tfWv#n{jez2SBGaGCf0YEW4iyQM?I2mTTZxdcgVf%TH(YdoY~X^3 zZzX5S2vf78!>!8EC9^FIOV9Z>uCf%wJ!eSdovrR$0>kw1s4nPJ-`&e_+Wy1HS5xDI zzhdIt`c}?4gWWw0Sk%tFGy`apm35aA!W=s^@J^pj6(;-lw6;QNXf&NC^a0>VDhN+P zjR`mZ&o>ec2{swqy3-21^6Vd%N7Hx)oKZ^$b}tGWzT_0#D+l}L{u!^bPLOmkq=CgA zn5}s!3M?)dET3wfJ}?uld_{BWQLS6|oBBYOtDy0sn^LDXrYqXEdX5B}AV*DqTPLSA zM-4ar{`x&q4Ii3UGOq7o$X`;MGd7xP>DJE^)cdxx!)owT})f3n0E!XttgX5u>f z*cy693A+qN7B;^Aa{XZ@u#^%;;Z0fM;rD7ehc$S93y8=X^5#&^4sy?PeasU$1EtoIxGCa3q^*k)QUCykoj zwqLaI3fws9>MQCZVn~^_IPB*d!bC^_kFbc^yc#)M+N{lRdh)k6&M9`VG8+)GdE)s1 z$kx6PeSXDH&1H^f{7^8K%|MrV!+Sk92TkFfOP2N->GVw*LfvsWF6CaAS8~dko^C6c z(60F)uwASV z!ROr>zYu9>{HZ_A$Sm?~R(8#IPf!Y=SsGaWo)yHzq$})orJpakvKCywup=y-$hHBc zhYUI!)_sZ<9pRO=w$=-$u`{|Fp9N{0xs3ASZ_m_eT6hVvi(Srb>gPv0aLsLK4eW30 zb6v6>M)0b9o2uEU<&u*oj7=Ot@<`ETz@t=)~8eOBpG9}#kD%+ypE#gupA)fLq!Tw-Ty zp)gTiO^Ycv(DuVJBlkncjK%Ip$25m8%q1&6(rCtd>Ls^LV~e@T-}ExAZPd@@xVr7@ zR2+xeiG0f1Ngl3TB1W3a|Lj0|Z#=nH*s>O0-Gz_bLanqBbIf(ro15Hd9~1-0 ztldMj$U_Nf@*#uXg{PEoi`LM;Z|Y0#hqb*qNJsy84eY~n&T}_>E-JH8nq&)NG{LD_ zES4~LuK4q95NFI!d07DQ&a1eMELm65coY(vG`-T{aoHPuFrE!)jDJA5K88z!MrJhfqRS?~_oCm$wc*-rbkOgH@Q^R# zY$aU_(t}|0MJ_~{(F8U|+IgbIj_||!6E@8ays%w(e_#9Y*F6VwUS5QDPHVQPkR{+k z=1NfYc4dqF&+2Tdi-`qOmB1q)l+MOCE2+hSJRq=iB*=df?${GZ_s7@Ixd@&L2tReu z$R-SQu(B8mCSk{_gS#vp_V^UK6)KLQI7x;^LXC4(74i-G(n^Sg^*;X2&I(SW-lq6c zH-*2Xxv8GNmxn)DUIv~RszAEUeFVTOW$JN`Mzi-0+AHvtoKEMw#P}2_4x0jrk6mvE zCr&zQc?zKTM_HtcuAOg5PnAWC1Tz+Rp$T~96os{Km^YpF_#9zKZPFW{(c=3fpQM%5 z_K&r)P$kzEg4^Dd%?{;%y{vz(7B%$~Z6R~fOG&gSz=*}K& z&Lt}weChX|D& zpK67Iv4wG>lpLgY1-BIPPy0E4!E83W>=CuuwE`4?lQ&CRj{SF`uRMz%cbq@|olAq^ zdf%OTk<6)2I|45A%-jXF%To8U3^B*zJKhRk?@OupTBtCw#$dT8#rm?P@8e=Km98y^ zsj3g$ENea2xt%7Gb13+pU=N3NTEBvCekRjDHVcXsTjLZm+2v%RtsGbtK|mg|!B%4m z(v+7MA~-8!(pVDsm`eszqU7scDb zMj!zRWXN?zA_z)rDddZbzn4_iWVRNsoR=!ZfI%^&Gx!JJ^{JX%xnn{!;TPAWk`w~IPhjydDSigC*<2{l^RmKXnHjj0X~5RL$O*r_y&;}oUQFgn z7XN?dY715%|VQ zaw26#WN`yh1{4aVR8~~zNdyqS{{E8%D8`Hc9o>h$kxQr!#xi%-jyC1#>x(Ja-3^%AU1f29VbRRgs>fmQP5bBbSF z%Ss>%DXWc+gMxnr2D7U<6m!VGJV;U!{|ojxME`$VgTcxk<1ODS_Rq4v6*2%jJ%>D7 z*-9gW^EEwfe#Z5a0=nUdve{EB^Wp=kj+yv6piWAH6jQ0ULq99t8c@b)W3H$cnK~GN z2eJDV+W}oLM72%fUIzCcfs6T1A=`fyS>SaSPL^UmX?gAH`DC_8`BE^?6GrvmV^bZd zJIu(OCxwKHFGJ5w?a5SvRgLNJ-pvSb=;yMc()GIFMgOzBL8G%&PuWi9@EPyF4*iJDd(P_`_4sf?n3@ zt3OIQ*~P-X^f_6P*-?C0mufmMPOFdGy{y2so}!2$0MNdH!=V3X{#j%e?&aW(8Em8L z3}8n97fo&BKsn6i=0H|0&Qv~j5eSuq7vW^hIYJj@7u8(WBB`7fJB0^6b9wgT}1iNL+GADC{JUrx?fVq#)yFs(20R&c%HD9+>UaX?W~ zLD4RM)UA;b%kc{sGxy&v3ii6*osCZAic_lhaW{P46~dYxh6Z9THxwmmnA=yCb6;#V zO4_EZV2WtxRI73y3-X9gv&?P8w(=BU|K1_w(;}woH{)DSnw*J1{AM_!k@h z-nzr9Ry;5iu~ysgyAhcV+>-}lduXL)OO~5v2-2r&SE_0^!a_+Zm05v+p!M_}U4ofu z-Rjy#*i&nH>h_&a@KpA>xm<4!6y7+|0Bs!i{|HwR;8ZQGgQBBtHT&%wt3bokNfQ$? z^5~2>`$YEUCFzITl5v*#b^AX{!=1^Or9>wxb%iRaSn+{(Q*=>72UA6kN@|S%rWoe~ zX8+|MA%iTbDIbOkDW>NcrcLEHG(!WqA6~Zq-j>MJ&jVROHc(Zi!?m_@#3y*Tk#jW4 z$fv^>N<1+!6%UeEP%wJBeN~(9w3n`#>q-AZ~T=n%|dUH9EDC992j0FpRGvB zT1&uU?Qx=B>4iA7^4Eg6ZOVWw`jy&y`TmJDTG6}ls+WdakKiz0+J>Dfe*{`S_e;!l zzEn)Ii|?*9Qr>zR{6aj5lCmH2ehNR|o{3Z%yTYp@dswQSsB5UpVJf#nuw1@$Onj2~ zW$&3-AzGBn34|L``j=vVA6cm%Mt!ICHcz3ucs%njveys$-D(G%UBV)eb{bh zE{y3LrzLlX5>mu&9mif3_p$m|VXaMz!c~1sUq*P$!=7mE+r}2$&9pSnB>;`mI??&h zDVsZ?Br3*<7CV;T2dEcLNrCH5EV$x@gOjsR0$#n};K^U3$-=!fD+?_vd(;tN5=nU4 z3HEr>Q|cc}uk|?hN5Cy&Q3iHLDHa|zBYEonI7S3(q68&Ot%jJMIP~nzEySTen9}RS zB|rM@PK48Wz5B@=Bw9=2wn*Iq}Zypb~-Nd)HCED$3PH{yMKKSftTq zz5^;$teNVM4rU8}gQ+Q9P32zO>kL8#5MuN^JYGC8nkwCg08exXTlF?en`Q$47#l&3 z9nTt0%d$p)X;l05UUd6F+_|X6tmoq)`LZPczuLXPe=qVfO@thp% z<#F-&RP9ImeL@^Pz1xw%vS*(aKg(@g{IV+3mY_CA9dq-NHANd7;C^Y82A}Lllp+>- z19)K_hu8P=wce{B?ty^-jLPy^u9iy^Jb0tf4zqQXs@WrpwOEj3nZT3aY@&$c>tgy# zQK5ILI|+5U1BKAeUfjZJx$T}d=Q{Os99jTn4vqlFBO;PdXq@?yoQ!MbJ=8L4UDTR2 z^8D>VFPGLSk;`_my3+XTs4u^bC87{!^B-|o8^6mh<{Q@|DJ&6pMxmL0kbiUu^v7CU zM%;Ei*`edw@{-{P2C4dP#UqotR@_5(HNU+aK5QJ1csb#)z*uayx&_daF{d*i4u2PF z+?g4IPYtHyNqE<6q7)j?t}}EX0wfj0$wppc8zO)-m(S=(vk~5SIje#vXhzqz8lJA0 z?W@&8I5ZFbmti`(Y2yjj#koZXtif>`N6r$o@Uo}ib8&zABCBtfy9AnGPWg2I49GVT z-6_kql!Xs>aPcLnz?)F_Qp@p??-P=Sd8pk*pYjAg<+b;mxHWGVL(0$rk#{@l-9A$C zhr43dwsi;pXj5)^szH*wRFDWoUyB6&aOxc;+uH6LOzdkDYr>DGb+=lBjnXvH@TVxM z#pn#p(h{KFdYtF&$A7qHde{nvI13aIl*%!h1Qd|o;V&1^s!Y>`&G!dPb3EKX_}ffX^}2z0RaORpO>F6AFte@ZXS@%Zb86~m2t^E_X?cUp7F zpI%1dd6vmVC@`A4+&s}5giRUfYG843?_xc3*%RIbftI&HFghmagTYk2?OK08&qO0!K^f6hk|m(;yl zT!D|4*YqhRvpG0~OLzFfu;eP020WzR$(Mw}aaIx;pEi*xpk(w=+(sTuf&tPZqKP18zgPsiE$dw(n?D$oA zx|8ip)xP;QWSO*>aNTf|0X5(~%UK^MeUz4Q8|Y?()1pUxPV_1rDz_;5j*}xH1urrmy_>?>Du7Yeeqw34+ub_A?LNFM#wI9>no} zYah}R)n-O=bp)Z|Dt|y9g7HEF0!jK?xP}VcP!wrs*r&XQ7ar?hklS9@SZFx>DJEW# z+5DI5wFy(yGoj2tk?6gBQH_vYfX8F z$(3|1@MPTenXII7WE|BXVy$hr-3fw&a@xE+h_la(G`B9V>@N_G52vnhK8!yh#Y7K{BQcS)vM!v> z`771QKO?Bx^)YjMG|-IVFn%c+Uv;k`9rui+9^)}7aW_Pheu;)z)UuJzpX03Df^|!1 zA4er&M^$V`MDXFT>0icWwRk7tb!nQS{bzYZR}ZD`+S+=!UwqsS9AJPx-WRHKR{8EK zepNc(KT6`BBKOZm+f9Q|_-2v{YLF$4gwKWL%1fu=RO-(7UMoB{4vxfdf4rS=Eq8!V z5Z)WlqYLa*m2;G=TooK)~Hx0r7Mei^^~@p4dDL_uV4}qzE9=yM6Yd0i_0kfg>I@ao8wo`#F~a;Kt`nE<5rTcg2-3l(ObxL zUup?d>;pa~+<5{Rz~2#-P<)aR3B~FRL?J19e!7ysaM4`nb|(~T%Nxsfw3=a)M^>pJ0$5rYD1 z(d{Q6Ez|E22f@FF`l-}tXCt}vYm)qxI?Nqy0=G{q1`3a>&_Qn zK)1mh=c4;`&ZF0OSIG)y|BgR%@2ERbp?IHfr8iwBkG6}}&c%~#Q+|^3&|013;l+X2 z^2%eG1V$ytsmoU~rX!zw>F(rbAb0#)wY~5&TJfd#^)o}iqt%wSBZSA2$c7?2P_*lr zPE*xP=gH6G?$}Sa-R(S<7*WOW3JcB0h3#&EH7C_bK;_EN5XN)JQD4EK0NE?iIr!$h z8$}*i&JY?va3&sL_B5GGka6BK5ENnSRPSFm)P0i1Q(2iIvS?9A0nLGFyFMCGE#H`q zeLkX}_zIKW^kB)o5U*9oJ{jAU?)&L^NqDN_rlgQPJ-{+l_X44HQ_>{;UL_DYdW=bQnyS>)J3-;5D>^a{7fPZmUn=5Kk8TUKe}lXFQJ=2a;!M z57S-Sz|H1ntbSVS^6rCCyT9w{({wdThShLI^LdttfYa35Lo$`8K+yzu8( zC5i1!)W*t2B%IzeXSvBI2ogUv%&QJPEuE%Qhqjk{w#VbEi3itA$Qz>3Lw!+$r_LC3 zsO~K>hiOTcN`MU+gIax{%MV_qLL2gWf86Nx`QZ~T^NB8!^gmarNq%zG^_jxdB_*9=db?!F1D%Fm+69hVI)~sf2a1Os8WpQ2dC)-OO&e zH&C@{2RO+^^!9)4-;eXH$YLr!zs!0~X1nDe;{K#EprK>I!d~?k=k2S#adTE5h^HT; zdi(3XK0|*Agsil2zvSikl$X}xw2G99h&?{CsbO*|E2=Xi@_c2%*=%^zWqX8RboC_e zY>|P~d_;ONEdaCV^&_I!dpQ+8$0j+PFN2&plx`m1ue>VXmIyrh33@!Q^gQ+)v*+w0 z?C;bb*o%;C9yE9H=9#{+2LOE^Fbx$|iF)Gt8WOa49)n1JZ{Ht=?PDvh3wn)f+<0v0 z#ed}%1Wk=G@(CDT?3uk~7w*yiZdPI-dL?HjTNQeZ{UvI02EQGW$ik!{(ktQjk0-n&lx>#G|CgMCpi3fgF1czH>^&KSJH$DpOuPn{5WzkAJRs6RMKD6(}6fxhiAtxzvLVw zis|6F*ZZ_m-dPm%-In5TW|iR*L41a+kxycd9!bhEC568nOcdgS5S1(}e2hqsC_ag8 z$1oYoF-oa{=W4>N{zW-{ke|8%gUKJNW-u|9YC6MZbT&(IwID$6q)L&O=dGG}a7^Yp z;0F|8@HE+*hV#8Q)xi;o(3i8m@Hjh}^`q8!v|i7OLBk69R#^)@vt@Q6=<|Wa$!djG zPF~lROR4Bo=k|c!7#87ruJUlb^tly`T+*5t)p#qw;T3u^TbW%7!u(8FyG+w8G7|K*YeRQpL4_?h5| zkM(V!3U@;wWMpe@=QYT6bfO;C9kHcp21va(cK>L;0qrL;IOGHtGbY~NfrPsx&M6}_ z?Xz**`K_c6>rm@W78nUjBl;GhcjyXWy96_AXw>RU^@ed6vNc_U=+54%E6wB&AA?y)Q>TdQ_2Cb0u!7 zCnlEeRYTNT(+pA+>#Yn^8(hQ{|d|k^RxpZgRx$vE;DC3NmF)=x;SV_`%2!2!100l)nE4pLL&+^ACo2|1ZHEz@J^v%?+C zbDZqs^R(%tZcl;e3lNU~tJP~e+o;N`D`r$6zM1ZYb098zmK6YZ`9h(un+LX$=+G(h1!Hnj67?&ZB{@hqtfFN;ygX(Sn=_)ctls zBxln-ssYo-9~?$e;J0I>^!Bc-k1{Z_?-eVVt1}`%Iwm>UwDE;2ZLKX16j;lS^vOGm z-7PyKS7)B@=5}x+0otm{ygJCt|29jg5q<&Z-4RP?+86)UWzY8rK^qn7CY)U#( z-nfI~M;-Lfe44Z$;b;xQA=}A^XX)p@WYXdXs!{?He|z$Y!ANmLui=qG zt;o5Dk9(YJ2^nJHVSVJ0v^3v-{_KsWqD-{VLN3~Q-makDy|>jRbd5Wey}mb^Cu?)l z!E!LaYuY?BgUE%-mKCD<{-r+S&vlhzKnf!5cP3+-;%GaHpzXyEf4cr$+Hrocbmd&_ zP?!Is0u6vN8tZtxVGx$>Gjq#n8sAF4a96`ux4k46dc3DFCpwAkOPR~wzu4ANQ(-!G zrEm9$CvRKu`zQl%J4kVvrGtNdRQ}&s?54bekL*X8aa(4jB0x3HDb}>Q-3coY5fcX; z98`m}HELUCbCkIcm5XIG3Z-zho+#waYE1_1NhUWb-fyoIp{Fj{m9UnI;cBgBo}#Z= zNiY2^Z?v{wgC}5ec%pad6ZK4O3H;eTy}(*UxhC?qQEZUksB;NNV7e5a@#oh4VJ{>W z>U?w9uiu+&b~&((X?~q0u@T9=FEv3Rk+p&@uRDcxbyp=1vFJza3<};PI-#fGF6Q+| zj)m~VWj)yX=B*Nol{BK(R^`VRdPE%dYg^D-1vV zYQVCQ}=o7JYDQ>RO^99G2Nu1sKEgYQc*S zqj>3Jq6XJjT8ohwBMVM>v^h~2rR?4xv&%Q@BaE&`;1_$0=dU*-TxuF_Ez3e?GIO~+ z*j-WTx0J$b6Fc9Sto)56zAcV>j>8GK>55aHP$Dkg)Zj41{RFK`oQy0t8oXgW^4B!a z{|^f=!!ZW5g44}cL!;rcaF5p-s@qkN?1BwIlpSlk{@p z_-QlZ(zd?is#EQfs4eN?$2#8ciZQkl5KjO?0}9;^x3JTN9nQ>Qmn(gVm4{+U;_%Hr z{9*oj&!6>Qm8qc=9B-_@WJa{5mb)Jb_p6OA6LKJ5A(ph0?XUYUcAZ){h7)GVJvUlc zp^=SUauTfYIT3`ztyKHl^_HhdGw4QfaR#2Q-MF7hd=b;Ebe&=P!%@Pes_oC(bZ_Yr*h`Q!rzX!nT-x(qC9BT9ud*oWsQTKs!4b|6yIzA@043K{Ck*fC_PQ2E zMejNLUMPW(oix6y0CWCS$Yr6LUzL8dUR0AInVuHS*4{@t-=mg`4g@bBa-0tLBiJ_# zDB5pXziZB0#Y~12(i7UX93G)L|AqKv(K9nM4gO43R8)kpCW~t+6n%s2>W&$L3P-QK z^qZoX`6j-h5@S6b#l(7wTlN`LqN9xtOR|LGEll9E&#C6pQ$n&4_tl2*wj zVGJrxwE-s-N>8(5yP7k>+ZV9dZ zTRx}GSGiBd%BL0$(_3Jt2hX*)i^mrivUNumX)l-5t`-S6%JWI_Z6dk*_BX%l_5O&9 zj+$I^X*<@3qpn7Gq+$WO7Fv=XGzw$cdw`Uqpn#P0##7B1l9r{+;nf zdmcI6tG5?a>k_l@dIm!4(!=}Ln&a8BtD_&l!T%{;U1@dQ-O_xaaqGoN>p%pHUuY){&wC`x~L~UlEnDNa6_6ijjbXK6yEFNcY&oPIuX(`W(^pN*mIKt*7}GTlgML zvE}7QIoSv6)q=A4iI|}=9z;EJ#>9RtJdy4mB^Ujpc{HIgJsFSVGz9GXi;&Pz*1q67 z%!kA+5fgmUj`CAr*Xx3qv^AmvfT-jy^e6SdD)iIYTQb%&)is;rQD%sjp0w!^xWjhrpriU zEjIf|&WY$wpp{os9iu4pkwR8QMPwK*%hf)}tIA}WY}o>Uf&!$lepG687xP+Pmv`%4 z%a&^OmaPljK%5`Io|FKr!woItOI=Du(!;ijKe2Tr>R(C(9c@+lRO(JkuK_I4(Nr+d z^x?ZgyD=Mp8alcp`y9>G(0^p6ZUcvGRj<)sQ9}Xnxhb425wf^_UIX&9);TJbx_<1= z7aQ<3Y^cyGjRo8e7mn2&HWa-(JBhS2m)!f&%Cqvkis2sx@Oe0kP(_Q#t{AGnU6u%V zZ>o!A%B02!{Z1it_+)82sQ_yu1++2>3=Ax|x+#JV;NazwGTPkMHzj%co|Yk(Wr5=YHeJgzXq$ zX5HO&cOQN!a(xB5#|`H7R3o;X?I!#RYt+Yd**HI0NP!ywfb*0Ui0Qfg;@`)}NTfp| z)F|Gb9RgcyIWl|mO+@aqI9fpgm@Fr{rp>xyoG+JD*G|8_4-S4&Iu^-@AV8qVdp3t# zdA_KA+eSOzSj~KKsa}2O=~hB=X2_rtR8D&{W@U2S33_HObYNPSE{NSRj4Z#+4zFLU z8t;4W?y5$p3HK69Wu+ml!Iq?j4rIZ3$J4oF6=oGxOkWlkM_u25q}#z{cE1p=Q?_sz z^-|qG_pFGLkujD|uMeWa{&0$3=TJ_X3tD+C;V1frO5blM9RN)Pfm+4#`5(Tl$LKYF zLLNXgK4P3yk8VD6!PC5>)enRT3W{fTla)2h1M;Q%qKh=FDSb)i7EVfGEC8ZGiTXmm zTR~!5Qr?f5FNAv1h8}xAb+mbjMdG`i*ShuWT-m&*7sV1erJcS=@VQri)!HAA9<&pf zjozm2A9{cjHx8hgb{fe6BvH%tTGzadoj?0-%EzqRj&iBfk+(t{24rOAY?v*4Wz2I` zY(EU7c3yG|PoVw4^YnoSY{B-Hl!A~0gG~Q=?~B5QVZn9|mHFwk>phChD(0^=Oot;^ zg>yO_q-To7NVOQ;MCW<+zR|a&fU@R*_}#ruZYSsf#mbBB_HQ;V0%{Sml^(|U1@FTM zK|c~E}vMS@;T+P%E%ZD3q8kF@nK;B z;FdnD%g;)rUdQ$B6`A-*R1tl%GtFB=O0v$TtqOB{|FI$gtXkK+st3hTwfwKO-78N3 z=-_LB`7ZuwwMTFmQ-*3Yi`3eFwofT0s}j0kj$(#ykf~jNg+<-K(D|XFwmhbSaZSje zh^a$TbZ&x0os@mae3@K?$z~d_y_0_Nt!0_rnYIul+5}YVnX7qHo_&O=}>i?mg>C+ytb+)%D%Q6lc671Ak@%#`@Ewvye*zRkDpl1s}B z^PelZRb)UI?(gTvhEVdA*MSN^WioQsewYBrgT8)MUItU_>|@3juBCFXe$G%$nEYxc z)BR&MAL8R+JgtLbR+;$$+p2QzWiPpzb@66uK9fydtJUn%hh;fp4#)*n!r^NvKyP#X z-12m*raGo=)+U~x|Ipj{7wJ%d5u8w? z9byG>EjCU5qGP`?(A74H%xg6t%^EaiOk4;gNpXw4Kg6 zcz$u=boriLFNp^u|M&NSX8=7xq#pBsp|fl{7suU9Nfo@uRD5`iy26Zxo|hNhGZg3I z>lKq@uR0Haz|hA*oc~-v*gN`C)9|A>k?h6H4lDUX3ov71(^7RHgMZQr{=XV6@vAeA z{gIbt>)${dQp`}LU>Jr8kE?9~ggtibx9W?FP^M$C%(mQ^W?T4Q4EJfvR1E-Lu!u0z zhRC@Bnjs0gB`j8 z3*mf(rxXl_E~l0(X{8{p!3pLtla()jCg$cZ7qZ&f^xoATpm~*X3dUp4oSgP>vH3Mv zsLaBW0-zD8?8Z*-&fyUD-}AH=Ys&GKlD*2VUYl*_Nv{)bCDIP~pNmzN9~@uL@rqpg z0n!%(5mKZ5e2EiJgw>|n%xew!h4kGW2R^Eei7N6SlSRL?Q&k4jGuL0@T3=>c-j}@I zppzj6=FBpf4a7qI?e+OLHq!&WgB2|XZF&mSwAI>v!Y^LF0{_~g_*Oc|eM_}q^rZ5~ z4fw@y>UIcp2viP?5yMHXM$7`+qQKS=!ksy2VavB?!tmWR-Ss;p)c6>w%5Dh8-|rJ& z<`p#wumm026LQVoyn6EUVs6%vS{P|T(pLEW$0=1ZliCO1ub0gjwq^y#JW0{7G&WY2 zJMy<}ykx!&p#{)yv~N*oP;{A;FS<=KG8ZC{XHDaSXOgr6f;ylTQsLp!M zo)s-bkAC7huwcQ|okRciOO<@RYT|=zP##NE)ek*WhgVMNf;tGy5Cc8MY@^ zHla&M+)uwTA1xLd_xJA#=Nm{{`$l$d^SPYg!n8zxb+{jh7;?9IOD<9rJmB3sP$Pxo z^=vE??9GFtN7X23ANLAFf3Av24JQ@%^g();+s^^Cw0#~t-<^f^>AKUjlM2@n#wDkCbbT?8XR z&|^a*w9RQ4OQz>7O!IKf9kbonOAbc_?7gZk%vf{ig7?!!0pVSm%_j`ArM^4esxzNrvFW3e z7$)yJ0-lf3fF;Fhm-L|kj;NdLDv~~-u^rFBc)2*b@l~OZt2%@^X8&q!L?;nLN?VE_ zqv-Oh7xlV;_DE|Bs}nn&(cZm+grMMzCyw^i=#C=t%Bcc5IO8uqbXYG^G92J_&_DCo)Y3GFYYf5nfE@PWh2>v>A zU8kmCRqId(o)e;OsJ>Ou^#m%+0o}I18psh90q%MNs&21|d$e;R{C9RgJ$v5A^rYo` zi|X{V?fmPd5SDB;cOI)Aqm1})N}z+Ni-FbG>^zBWveSId=U3M%c^Rov?IlShR4psC z@lls_HJtru&Cug*RiE|@E2r|`>#^DI_neJuB zQ~9KRcc&mKbejLj=+OU?Gt5h7U-8UdpojV?UC90bRme)(yRYRQr+{=ZRg`|JN&(~g zRkDwAP|1d!DZQfD+zbe$XA@QVG zn#NC?sm4Uk(Li6mMZ%aNoPf*ux3IisH1`0;Yh!Xh0}-DH0E?B6Z5(kg0GBAFCF_s6 zeB?3{2g+s?52F9U#upB4$M|(tH&3M!{^AxW?2;5S-W7dlKfAjyUymDkz0nHh5_b|} z8;!Ea4{C1x{y|!rldIL3ojSavg+F-qU3iIS3QQT{Km#U5<<&YPT=muX2e`AaLc#*O zg~$&yZy9e!=WX37Kkj(K+d(-d;!fWUoGJuSP~`RVgbY6Z2}BjLf%sF<&&9j*1>+7} zU>%N&euF1uEiaf65E2UZuSiL3Dk_WVorjmGyqerxAAa2XmNH7rq;Wg)U8$x0 znDaZbmAKB|aK*yIvOm-r`Lj)Atav!?43v}`566~<70pPF0um(1EsWNBYLu3%@9XRi zId_QGUQCn@)BuRADQ3M<9W3-O%?Be+* z(iS~%A*1|zqPEGXsmtmDWaM2`Wzmbu9~p_Ww!~(W<&(Ztv_LeKXjigZxEKHOQ=Ja3 zC!)4m*;QDMC+)1w-}^vLOiWJth9Cp^1EKLCJiz#MZg}L8Vd6E$t2EFRv9f;+q@iqBZ#Gk(FMs z0D|#nRL2{~4nyW*43E(^c(*C;q8Y9*WK{&`$h$VJUM~@7`t2o{#MWHrCn*S|6dpHk zlxykzAgjI0SNNC)y6;(AkT`sT%z?eNBt9cs(&yjG%{-v#iOB=~9zPmQ9E?kze3Ov5 zcFMUndYS$i_#NzM2{rv(gLtyi5GH}zFOOHIK&ej zab-OmA!XK@W0tnGJCen?g#eUQA2ouLo_$n;J;{BL`S8HTc^u*OMcmz0FEf&I$%6H^ zW5UZY-)kQFk2gIQl_alf`@R(SHL&m_2wS-iAF0A^c|E6GZLr1Uj^Qlqk<(tuD>?rD zdlH`VCEYpIN(W??$@GKzQq!IFMr05Qin!UhqN6?@F$ZPJ3%1vGu!W$6Hn-dS7`cOu zA!)kB7o!{O&ZO%6OT{HJ#2x)AgGIbOD|3EZw({b@RMxsWO!|_^{E=tZ_em;;?oXHb zzDUi14DYy3G{I!!uWlbXxD-F12(VeL!MMMAJ+U_E(SgR6deL7vP%IO72p0zHES48N zz7XDZa+$B!g=r))y}`r)u^HeI6*}U-{m!dzf3tbLE1x;%cTvOHcFQ%qW#OjgSfIRi z>kvirg^B=i`4nIkWGO6c%*k_o+L25%rMzSv?u!#yEqf=Ag7Q6N9i{+_D3$4%$nt#a zm<5-&Yj^x=Gp;!?c_p!6fXu%2_`Ra}Fj2wutVG@Te$n1!4gM8<3XbE~wqNDE$QJ(X zU0&xFJh$)Cz{vp1zCK4 z%s;(Awm|qAelw!JHSD5+o*A6V+j-h}7zsKysJ1HI$SY}=<4Y1ix8Q}RN=(rx+3v^1M}#CyOtUBRfZrRj-9QU(%Nl8cOrU~vyh%AY z#wo}v$jUcs!exdLnHDFm?Tl5Y8*#T|7=2hKqF+#|ym7c$j^uCCiJ1@$enp=dw~?jc zjP=GbaWRVqIe4#hz!Lun&hN0a1siRB3?m*f^nOB4TKu4c(y1Ul%;lnQfG$ImwUapP zt|7G30Cadn4GIb(EoZ!DO++Bl;S1QWOOm#13)|4Ovdp6l@Hx}&@_BiCq9-QqUk3X0 z9L|-hP5y$8W5f3E{QD(PUQrs>tWs@QTW1BlR@BkaS}O-oqwvjUbtH+wtQ3c~Oo4Js zHKBxdwaSxAjoBO`!|jeF0z|EHHTn@dMf$9iX47QxqxVm@z4!(T*#VR1i`VwxIk8(s zgS}0ARbbH)XJ*v#5RXx2lN_5<0`hmKjf5f4ZI)M^DX{B4jKCIDGRcuItx8B-p(&(4 z@^8kXEu)O*|7e@1nvClVd@nAxQa6av4a|kIwyz{GFcq-#NREVgVP$g#xJkSx22B0) z+xkUfKS@LW=tL2WgOv`UlavtuvWdckp8gIC%3mZ7P8zbrS5U|eNJpD-5f`DRzf=AL z8^LKiV$fDbY^#gS=ZlUc4H??;8R(y;125}L@gGI%Af;iJqG~w2*2P;(Ee}#uI4l~C zMZ^91^NjvHMSajzc6blf&7J6b=MVPZEUdQ*$?R$IVx`xr>M9oD5p$2qf`U>O>_wib zvt~Oe(Ab0)%OahgxfueSFt2_lzG6nz#Y}pUSwhhblrsH=w z$8i|IKC+Si&}vKV=;&A?@c%3L>xE_tg%C#RcHDeKx2A4byuD@_@ro_{)yA!IPf-d5 z5#zAhy4drC@Y3$PsxSPDnTKfkaUE#59)?gG-^`)a6(QV9rYsOl-BXB(ZEa;rfE$&V z_?J(U)4Ardz~B41@cKwq8AnAJemyYoQBZh}oE|)|>|Q@ldZvg!+|pJuQNv2IS|E?R zo~$~JMnRbT&UpwcW!eO2TPA% zn6mkU>E)0{sSB{Dak&r*f7d_fgF>#K70}NdXhYs*LlE_MdE|kgc>MW;7?8KCkU1AW zRcaK0@kuf7_7p9@wr}~K|5jjn$eOhzP7~(Vc&K;<9VJRG<-aqf$MUzCiRt|XE}x3C z*gS@pzB^l0i|PKm375DIxkrpyq2Si2DAMv`c%Zf}tX=-_6)^zaJLjtv?U5N!3_etI zSsJ{Jl8iydO&#F{chDsxpYo!b)8XC;(B0RoN~HNX|oV` zPtl(#ELLTwL}=fwET#t*9#6#9UGHu68IzJ;Z=X`j5z3}juADSQnq+7C?u;Sxqby?= z)9Y(?pklr=ygOjXHVl_xO~b%Lr2P5QGEb@&UDK%7a=aMKjGhr3I52syn~wOBo_{|;?A8v@rT1I= zd$kS`Z$)r6D?dM`aZc}fU~oEf6N$+P2^RhM@go$2N>!#@bC&{s#gc^}B7n(kF1Eq* z;cD0ZeC?%x@962gz5GJ{@8*UFhK5tSuvMKv%qsaMC)gbbekvZ~q~eHcII&lSdq3T+ zkb)Rc4_9mN4HvL{5B|vm_DM21`~d04XYOKFOx91Rf}pnMar)6vR>;C;7rLt#y?kX= zKZIy9&Ss`EBrwps9lAgmii^BVd)`O;Olu$;lbi4Qu5D`$45qqaF%F`ca6O_W-_ zdM4j~pz%wmzAP!&j4W{nvrIbKF*bN^YPKxg-lt|%1bkg>4vvi7p{|Cuartd+5Qms9 zBq-Ri{!ab}lt|y_Pl=FGzRK@mL&8a!nISk;%-3}|}tOix?nSq-&^k6|*H>ADD zrP$fZokCV%sq!+W-lp%xXP<_x$EjNGr&>#}M;Oh<-qZQURNW@l-`{&y64YFaYUlAt zVJj9maCmYSPOl3`((+1}39J0n^oAmQXT0;$iLPI96*KQ_F?V+oemYpeVYwfSIElB9 zry^(?VuZWSdCS>${zhwD*vpzUt;YuEXU=kF^Sx1%LSv<|N zy?-M3xN?uw_sMt&WX01}azV%Gsi0<_-u}~L%Ou{hAwUF%RM){uADpAK==QL^GE+zp z!0ge#T;4K>*)Gt`m)&r@2OkK}-hosutz%G}*;D46fZgt3IK+|7N?A~+g@+Q=lub|N zuBWTp@O0LUo)runU9=+j<4j?}8JhaXnS5vTA{O&inJw@(KI}faqBL0pSpLukxD_Cj zWFeB$(&V6$>5!>O1`B9I&Mt^Ky4L65ll3Fi4fAw(-E>BBf zNVP^CZbn=miR8yzK6I-;JtVc*n{g1sGha-eDlz1DPjfz+60?bGZl-%FJD=}b-kdJ_ z*S9-NJ{9TM2U_rn9@6a)>aU-zo*+Wd!UhKtb&cq68zEh6Wy$79G^W6)^;hmUCoB-~ zcrU}O@XlrBH{8Ceq`tOCrCJ(RT~_xyJM?0ud+bp6)w@M3i`?vXr*}Ia0H&h$C~j!m zzT}w71+9jF?Y+a&Xs9New~?GCspB|jI^HcTQMHzi3~Ff;h3&5@#vFqf$p@?J?08d+8{ZD zr}oXRg-N9mboJXU9O$-^!Bm@Avi@zvsG7dkP~Zatf_;Wp_b=R`aD$KSOtU4el!RBvjLN$ zER1G+iz67eo9aO+T)($)MFJW%>x@GwoZZ}(!SeY@e~{+H_F?Xc&#t5ixP|7rvDpm5 z9TZ2RBLyYlBV5Q4n9@yK?VeOUUS(=Fqrm2-?(u=8nc7b|YfYDO*loJzwa{_E;r-BOF{Yby^uk)X9jWc2ZtOe+|fR|5`;yeQA@YtPjgAPW+E4X z6lA=&-b)(!43q4-?x;MQJB>ehcLb-)aZV*FHKF@Tn?d_`{Be7s`#iTLzqTgY+g+ym z91y2t+@bz*dcdpqL;_?ee+s5!lkaC#Z^{hOKTz1h0@+gjk{|OAGnWmx@{RHm-@vF6 zmw3}MQWEuFL>87y~)>0LXr{z$>1xVH3@pe{du- zOt=ViP1LgIjuygZBTxV5CNV>XCb}oBRvYc@&6Z?>(;A9+fp%F?AHf?)$8;~rE1`u0S&<)~*-O`kj&0%>Ps&W?;&H6dwTMMcsVf7EulkB30~% zkS^$Je5d})*V}fQI=WCO5VG6g|1!uN4Mn&bLgzOKQ(Swsn?Nm(8(6)ylvu)FZKb82 z2_+YXXK+~V;P)os4S#?x`6&e&L(eflAA{lLikoYSzBtp9To=p-#a zetg~lpLpTtkqz7N=ayh|;?y%XqrHUgAI^h=iY$mTNPg&;n6$56{q*6~(dGh?l`j5$ zk}&Pv)iDckTP=B!tRTT-`7tzzG*KLTW8oAfu-E)xz0-14K9!~*h_Zhi`}&U#zf%11 z;CQL}oGbeRMQq}!#FKIsat@afx%thN^9mNWznLw?Jh1aHla-2kW@*ch5xDzXGnqtK z@t*CRf&QYf>K>CPgp*|ixgt>#ae(-;a$4lQYO(VhTE&cw!FWQ_yt_>x>Yydc$J$N( zF%3tT7$&zm-G#jk?=W>o(UmZaX?vYcgtq5JkmoiP&D~WAt>r?s2&$V5arYJeo^3%v+0~{@LY%mf zDY1TyP5U&mi{38#KYlB8vJd%zD?JxIy^AHr@?O?Zd|-q2wdRf*@3(kj9-mbl^eXQa zO{I%>fz{0BZxyeyn%ld~L&)r;Rmo%SD0&m6O7*2Z`SxXrvrSjt@OPC=iottD3DL8x zr@bkY<2rT&QYw>XgLWrEe72+AUA$}?QVFnU_%jcOlkeaZO^sF*0w}B%wRat(6cvNF zcYyU!s>BkvJoF1~Z?x-z(&yj;*<6Tbw|Q-v2ij8zfP_Hk03uVAD=+5daLPlNo{}3lZ zIFlDtok0ifvV`O(BPd}(2X@F@xC{<9_1P7Y`sPw;l48pxZM9_Mw26IJ`}O8m2E3+k z7V!mU$;uZ;0QmFg^}Z&(e$9tHX8e0FuJh*`$djdLp3%u0(5HbfhkiRG|Nx(v{nK_S&Nx=^tJ^;m3lK}^{nzVY~T7W2d zI+>pfo!}!9tURI0-u<2cXTke>|DE;T>l@;!$TPR&nX_)czwXU+x-1QTl}HG}>&C{b zm_O*5%PxB6*Y`%d2+2SGDsCudkvXp9v`3M|*VwmyMlqIwY~=nv7#rsmofH89xE7Fi zJtZV8JXNcF9*8`Px)OO>recZAic8J^orTu-`TaHYlX%vrmg@r{jViNuKqbXD&fr>T zSnrzta3T+&^vT}30;U86kQx&b{|4&h?0w&pd;k?W-QC^x!#vXn?2elDvaqlThN)_dDB&VJ)g}w&FMHzSO4nG~ zPwZ#B_Q^N*HdCVKH4vvoMDNkvOGL?hDxKGdsmIw3}4#AN#jda5y zqJ}I_{QsjqXg;`M>fw`8tJ47#N3{;U0^l;Uupda2NgR1ZYzqB{U#w3k%pUzUo9Iw| zK*@4hJ5|}mHYf$gj{DTl%b*MXEWw{^P@VV-RQ&-kt(dBG{If3mQjZ!i6R@Z|k@lSP z@1;Id^~FsNQI9;vu}?1mj3K^Gn&)5oU@Q|vkDj(->fI>^@AS<(1^Js`EbbIJENSW7 z#l#W-_1q*!A-<6idCE%K387&znrxWlH@#2l=L3#KE*n>RAO#*T0eAYB^@G@?g9Yn< z(TtUoR9vZmXesje$;27LL%YRyeErbyD)c)8o=zv^sIRy`{uS7`7BryESH;S)hIfCr z{|KYHC-Q5ap2JZ(?v6ZxF+Nc8c_e<2zWe)+HG^DbAk3IjUa&#IOB>xLH+ySb&4;^Z zymi+1wg02%d0dFUZvh`&e8JJ34YUyNYnjQiy= zd1!g4bB=*0+!!{P))0N5P!08cFP>F_S#e$l`yxW#_5JCWo#H_!DkFIbQGJ|UrP3l% zWNMQ7OO$6UOQxhxo}e05`t-(r_WmY4<|>ZE^sfDzh3fN1e@M&N7004^!|*J2PHD;` zw}rP`SsQH_dQ0XWy{;USH|dupVL)cZ%$ zNpd=@OG$*0cLNGPG7%4MN7zX5{>md0{57FdU*z|xwe#HKRF7bu$;}uP5xRdsH%AD7 zd`hhQ!neb>{!hpX;O)NYs!JSh}>zWn~Tj!dJV*) ziI55;){1l6%x*)h3kw<0A=-BWaq-iTn~&l*Q`zx4m~MU(tEf2ST`%Lce9d=Ux8+=8A&!P- z@FcDK=k>^&h6P7E`F?N zIryrLrB82zu@pX6bT~@|jn;RaA0eXpJ=R+iG$HDTDnhdwo7ys1yfxqaGFmk^+L)nC zf5gc}>;6rrV3!_Oy8HPZx0nG1gMj*V8U0`S41MPE?j_V=VO;80=^NW{?$EHw>(rp+ zW1u!rsCnYY7X=-Uvs_^IVs4Qd&*c5^&0=zlp24@@JF|Ox$sNQk)W8cOeK7-ODbL6u z(pS0$EY&dc5#==rgL*KwD&E#R=#~FcqJy>3)IPG?%RR&#nflZ+mXJ$hTf_h+zyBXx z`@?pAXmi?}kIQ2NAyw8rc1GmH&0&J>`;fQ)JK38uXn9cb{E(j&w9db-tLJ+HRQ>wI zX6|%Ue|rcFKUpHyc!{?Xb&?e0nbt`!#N}6%mJ5#ojuADyE_Qd%{z;O6(f;V# zC|-04aK2j6(D^7b1QfJ6*r6GwTL`na4fy|xVdLw9J{p1N+b5==RxK>zX= zeJ`l#o;aY)d|N`n45+N+yKrFA@g&|C=qLdjV2rzienXM(jo!p`L7}E>lQ^^81nTGuP zfpRMZP=Vw$y%%0`n3*NB{oqXz35P1$uLJ_lm+!y&=RWwD)zT(wn__?1g5;A3X}AeM zqd`%TGs`g;W-!~>+mC#@|EAWuVU}{~gHfQL-e5~H5|`*EChJA1)b;EDy!C52yDSRQ zZPb%ewpSkW@S1+O=IgyLS-kZs+0AH0Ox)YM0p^XI3DsV zbOU)}&YpV@#THvHW6<*p|Ii<8>gXCwGRVdYhVchw!qd~>TG1^S+R!3Zq(j~7qDh2U>dAPaTq z@jHA#*-?VZ=L#H){b^80SMV(h8@qEBMV58VA5)2L-DOrL1b}+ZH@_oEPjp{jN5xkh z#jG)#JEQKj?$lY^NtTgCdkx_f|9!zs>l~d>nR*{a)BkrS|HgHF_B**xHb=2w02k=~T@(0+8aggc;D`EW zl-7m;-}F&*gA3d*nDrDknjhBwprAhK=db&Rf%TTtmZ@N~$jFDhp62N|6G^%R!> zqB%h8bW zM&nXDa%C+Ux;JcZ3Zp-_lBY*gW~tFzbD$j4!0cy&xi)&W&P3>DrWo5Yr1!wDLPpTu{N_$vQx&-}2k?NC9Xn6jznZ3_5H!%=f_J1bgM&$*!2wo4%*pLWxJ z^yT-nhi0ZS6N_CdYdi#0a?;(_$2=@t>H!?A?!0C&47VhBC5KwsTcTFI$hfs11*m$i0b*(fR zwy<7$7?56CR@QLKl6q911TNDG;FM_%YK4XPhwy7Xx%%(GCE>rZIP%**KWRx}1|A*~ zpSxSXa_EB0ujSw1`{k$S!1uz!ENP-#13K{Hi@9u}X&=h~^?c%%0|iu$eLP#ndbLsM(>CkxTvO;bp+XmK?=$-=H@lEDl>9c?H;t$hw>BK*?<r$y%UBZg!b02?P-jSnZctMqCc zBhVkrBYd(P?D2nffG&{Z`)KV|NZ0&hGLvUtt%nsrI_m$=3lPZV0woMToh=uyg}=m> zv)j*K83P<#f0j7b(&_GWbZqQL2?+`7FiG(N0z$$MMn?3&J|p3sTkeRDJG{fj1ox`5 z?tsDuxG(faZA~>)#Cu_9YP%}xr`DGpK`em5e=vp5nNI;GN?F0D!TZ(&yE9$2RHvGs z5=aXI<-UQ^ZKxX67RsCZiM_OU?;O>;?v;U?KlJd`j^B5| zBfi4cz;>Xau0$w#WMpK5Uzk?W!ly=*PSm=V%0N`e+Z5Oa!VG@yG|MaJ54A< zXo_P!xLw6gSx~*14?tHS`8N4S3c!M2zZl?rr78l{wm{1nAD;bqyySdq-~ZLEX`la`nqn%*XE|7JsuW_^6*i_O>)Kf!8$L`1pejIU!d4NVJ2YkyM zb&qtvYKD69L;ibI=-^uJ&r&rI_2fE9{YhK5H6HuS7d=sd6AXtZFIqku9lZ{ryrrg9 zWOS?X9&+!e_}pi`1@Ro zXiX6%aj?3J``fF4))Nu=^N{wG==L3X28Y3Y6_Ziw&)4a5)aegy2FOwmZvUM^e$5Vy z#F{K(!O~Hg>u%aQ&w*TsM8-_f&p&Gt2m6S6tNpVB^7)mQ9xDcMwwTL9FKX@2Pql+C z){q&%W*Y%u+)Qo!x2%O?$wQLg_>Q-TSo+ki2yB~p0*PkfT28n85@)uuzur@~<^WA^ zDs2q=S%yxVStKs;ajewVH1*03S!iJagNy6p6tXRIefac@duv1)DF0Y-rf@V(nbVXe zpN8dlakemeF*_MaaK0oF-|TpKF65|AWoEk9xdxohB5Nb84vxAya}rIwXN-efJM0%f zg!cFprnyHw2j65UXA{to?e4piWBB^&jA;2>`qpYW&#a3lRb|2@9P8trdB1-BirzP< z&x|>8?C;i6AeWA2dykjRh}GA&vkFlm?fc%qh!HvmGe#HhO9I`Jq0C!nJiAe4)2HUo z%51I49brSAmz@@8JTj{RAREIkN$jDXhikL}PI|krLwI+h2Yr~kPtu%~-qc?*&udj= z)|TrR5-yfoDWxdJtr5T!ei#fX_i$ptxqa$nx%;b--+OUgixzV`q9m?^;c9$$iiDjH zoVa)}aZ8I|wcuoTw11qJ1jKb%tbYI7^rbclQ;9?{7tgtM9a& z1?Tcoqw%&Iue7^;&(h+BG&eAwSHAx4{z%6a-`eUA6Pi@v$3wt_55@9iDqn^+ZfPYY!7ura6)Zrf~!vZV51<{8T@tV zPF<{NX+G7#UrODZDj$ zuD)|g1$}Sc@N#M3n&oHo*Q8DinO!rXCWVA6N64&Ko}&Cp{cy8!5w~xDTj#8Zxi(j7 za?_c1WZDv}eo@B}y-7IkN{OdM+|^5mW)JTS2_~}>ay=F8W5R10KK7%Q8C6)6w77N_ z{3!o8S?`8c%BaV1AE>ydD%1iR3>nIS6GyS-D?7AkwB*mF1o9`RsE3JGQ#r_P^v2xC zBi8S3x1P);*QEIu@~+{E1$uwLipSpj*dDPvd+=>uxzgQvwtF5l z8tWufSVeRj^*=2DvPemNAjpGdU03%eeC&Xh)%KVOOU1-Mv90H&qcqJ-nj?!Cwbv4@ z;wRpvtogQ|?IeyXm!=SyuH89dCqJYnr7F|gg;#HAy|*r3o@C?@gmJ5J*FHC_{!4;1 zMMAV4S(VXVB3jBoGga=UVB@BKnh%+R-C|X|WY<|#1QnNFfZNxShJ18VI;C8f(chviN?tO&6=?`{1Gbr)udL)FT1z=-U2iygI`!da3`e8q+j19LX+!!V5nVjZ$6%h%H2e7+V694 zv_Jh69cOJm{Tt(ai9OJs4g9fHHQ*0-lc+2$Dwo$72-{M@K?L{QqH+tKvyCO;#X^f! z8&WG`XZ97@O31a6ZQ75_z$c;eZh`E3uY_U*g2qdn>`4l&OLse3-Gio>Mj?L#qxe?a zXAKkTkLx8zIsRl3kF}7K@enc=*)L8U$q#cPb7x9ArXgx+`kp(BkSUZ-pyIABYa!f8D z9c$d;AhuUw@@LOdu8*88Sd zJq4%cOPwe-_b9$`k7G3lQ&erv*xaS7AC8CHp9ei=t*%=4zq?vV%INDUKFj&lvQN~y zCqgs6Vqjy&9d|BDCRI47segCLap*bcySpS3{T$LIwblN!h7E4;30vKdX06CW?@4^? zVZfD8rivNsw0_PZ7SkpxNDMo9!J{4Xfp;Xq6m~%>q%O7HwY>Z##- zIOY66=?O{28QWylz&PWltmVQv?v z_D;d*>BDUxvYI;`!LC}vKNB0@t9R9ysqnI_O9z8A>Z5x6_Nyuo)q-39+AoqKHW~vQ#n`0Mn;v)~w&y%Z+&65!oEz`y%Rv<-)Q}D=iX2+DTGB1|g~$SQ;(S z=4Q32Xt_+QF++5gE1gj$ulBfqH?ZHdNO-cBy|iDD;NlWW4WHbOEvrh5-C*C0B``w%0B?roC!Uc&zrsOyZ6Z9UT5a4(=9(X;lUF{>XmcUz7GLXb=SYyzcM$tK^(KX z;viiCbe=^h%5`@T0m##3nNdyjSu%2*0XKSrJ0s%h9o9u^_yI9CS65?+`Ts0Qh*EJn!z+^Y20I;aZ17PsQET zr&YT&B7%-AgyrPwfE8(Ytzq=(Gr1>}Ysp;bm{^$wmc-LTEgNd)tZ7dQ;IrmfIK2|X zRVGtfC0>bX4~yTbEgvUG`~S zod!`G{Fnc*+~;h+an4?W?oZ?Nt}BVfJ5vDM>(zbR?fM7||M>#m)I^@Nab0ur_@Ds5 z+s>7C;EsBUS&bqetsPhFUcPaIZV_vzSt-VzivO@x5*P2H$wN}^ipaB&U0+XsK!V(2 z59qin?Ly-ekZ9A{BneIiEF9pdu0@N?Fsd~1ZikAZ653If7q9g{tU0YfFZ60E_>fak z0h!@;c5EPv_YObb60j^ldAhZ=<#3qk&a8ND4nW}6fg!_(W=1v)*qq0xVNFuVXat@A zn$$@8EB;EmeaA_o9C~75&J7IJn^%}$=;-JGr9Dn=nzvwpf~zRy$F9LOco}d80xccg zU~|L+cFldnu3Z0OS6}#=HjwX(P~)2b#9qpoR|SH=2IaH0qnC?MAYJOnP=E~i@y7Up z%BcN~Q0=@sRis%P9?PU!VY}2aM;RRy^FmNCv9C``qt-_I!0Um85Pih_3ICE1B*5M6 z`GJZjGym8f&gWdY>dE82@Gv$hmX=h&X-UbxDMz(P;)UKX{W zA4n64KW#|qf0=|?mv-C=g#LEve4DUa517EjGp~V%W&WQl`TM6pKmg^RMSpMQ2M`99 zPJ6*6q2$mwz&Uz8dr&_8?}J&NO2H5LSR$-nVqnqRtJ6+LN@DaT2e zo;`HEfOHDzpuSq<$>TWCT}+`B4?DlNEEq0@=m?pTMm~+ zqpEGgVe*VU>!}ql1^D(f9#{OoCsWedE^nn-gF-&nx+T4y`l|utrfH1@jFG+;PX2I5 zBH@YOsnj^d`uV?x_QAg>v3NmnGJ6U>GYzVG?L-45NOrzLF{u22cOpkZ!0v2g51peP zv|j<~FrGLH&u+o~BQ+GcJd15Cm3+;kbo_d6qN3)3agh2{pk-X_+{xyq;Zjh38v@Ls zQAH^7zkA>wY;CP`yXvc;S<&u91Aq_Yo&gi@zl%{I7ozyLw6!F72ZRg!wio&u@=rql zfglp^(p9cSDSo6K3V}n-D!Y+V=PYsdKspZ}^=qm4Hv$HJT9pJu2+H0v)+K)Ax*y&Z zLbk0}G@+Ia06pI?k7z+Q}lvm+Rz*9l=y;cYQgz zbcdlwJ>P{FuDmx;y8kG&f9y6XAdioG%EKb+oK%dv1b{706f-m4#3+e>_-H@zN)>r zbn0xYdM1?mOW_oAuHs_K@l-iSB|g`fv4{ekAISkI@%u9@E|U}bS9_z~%N8k^-RdYZ z{4w%D3)fm)>u5H=_z>5`&QBC~!6)4dFoM;1i~|1|Eb14hxq`hW^8H>inTB2W4pEQfmM{yZJZ^zHxX|KN3!fL8#RqiM zb}EVEF+OT5-hZ-bkFRj|+iB8VF)Arv$@=91p>3k_+-43$ZY{n~YT3?CBlVS@WBFju zVzcs`s(rQcJ75rU;|c(!JH6>Sxzxe>%cA;53fLs_QJHbK>&=)oI*cbQ^Kx*IR1c$T zGkzsM9uSqB?jojYb@&!P3HYec>h0AumM?uUm3?E|bFX#;VjXV8S)J4OGNagTo^-UM z3o#j9=7LEu7f07yT`1Et2B@foS>j;66sC>Br;FMWz1=#UUnr6rUF#5LWV;>pZ? zGRYyZyL@)AZDY9Kgm-Coz**y;BAv!m0;@Pl!Z-2(oe1mPxQUs%@^>BEQWkMR|G?&w z>Tj9?W)Mc(ahNZ*L`1K>nO;z_ZZ;73ZO^oAdTEV$6Gtu`U^~R$_Lb~I-7Uu7ud-5h z7PF|r#~T~By{4<3u=&#UXj;Lyh+HiaTw4LV+h7m+sT=DX_FZeyU-xJz_Anr= zR7mP3N9TKUasT~)oa4$%`U)tVNu~z>t(wkNBmnzTk75`pIH-jtYdnx9{;h` z&bxJlyVB?w0wr``EtGY`M((sLUkf}>@Z62n^0;koN^bZ@sdpF!hA%5ERZMcTWAjm% z$gkeTQ|)o!VAG{7nTDH=@0~tdx9t|V)tAr`46?k3)6=j*;2hl4gME@CCfs_f@-I@d~}3_q&}6tT&Z%R1x8bBWYRkLtFlX8#m$> zSL==W@-pYTuDLdh?H>Lr&D!akC70v9J7XF}bG_lQTZtu{B0}s8WgEpmf@yA4jdeFw zJiaDl!g9>tJ06=h-}y;T2Gz~czQ-8}!sd&+i>((uY{B|{&C&I?QuJ6f-l-oOF=u!W z)qC!rjmkzV)tTBMq0FMF{hN7z7_emSQ0Lu(`(+1>3kLdx8O8>(J8Q&F7>Qom7Hflz zWBytbPkE{(93R*xlvVeJt=xR#u6IYr%*)Y~h+VPi6JKmv-s3n_i*^?_xwKKR-Q)7Y8H@c|0 z=bnUvqF1N~UO)F84>!(U!cGoJY+f4l%HKGZ`H+u%DC`^7#ac96G_O7Ck6kdc_~rsP zR0nm_dBUO3dr-l{noO+Ace8%{Yy&FdIk*7Iw=gxcY?IkevLFmG{ z1=;a}OKbiO!W81^i0MR1?H@)C1TIGo`R2+Hrqo7%QL0`2KLH$|IEMvExsrWvvS9>T zRL-lK!EIvew~b~2EOp5d-cqnAza{ut8VQ%ZB8dhnV!7Y;>1NVRlQsMB>v|eH!V1Bt z^bfgXcQo`T?3q^UgnS@`5@!K$u zupryW&fiqm{P;}?x3Y6%{7vi|JhbM?q@Cd`jRI!WB5$iDco;;>U+QPT^jh~={SSer;hf+^ePSSyP6&$6TZ&eu`2NJw3^?o!a)27-{2ztc3;j>(@1gxB-M(pdUJo zKrMrj&dh>Q-f-}!3{Du#C|m22~Chr({52_M5|aC!3Naj(dZnTnF=oucX-7WipH3PqeYS zD&9`HsEDu!D-(bs8uSTTvZ4i?bvXHoZ++NmTLz%HY|DI^g%=0+qU$>WJWU+?*fvy~ z&+k`h9M2DE9It09rL^qmmTr4U_}6AGeCrUcS1jo{>G|UICaKSoei|a&HSf*Y7^pLJG|5}7JXEi}{2_BIdM@#ihb zLVqIINIax-xOu{xGF{Jvm@J__i)f+45KpHcBjt{rsiL6@g4m!d*)w~yw{+jzozm&J zJi&Gobj?<>8Kx|@l9P=we;zo>&U;s<^B4&}d@;cPOk}JJUC=m@V!5pR(3^1V$+Ek% zW02@?;h(Ke=6odmid0*Gtp-%9yde>YK>B|Asl1Oxp&E2UyYhjX{*)+|HNCRU=(bl40YD- z!C({a0xuS2WSHa82;bu0W9YOs^(SPdI1$I=fRY1gydoNUBrKM^V*;s1VGze~MhpsG zp(jX)zGGbdzh)eA?au_RFQ+?4%iQG&ang!b#PEtujyoW)%e>KtiL7S6$a<~m)Rf#Y z-m8H)Nk)bk*Rm?>Cg8y7byjqZ8b}vs)`p#pY0DuV41Rz22+F+B8WWSu&GzbIS#pCa zVYbGTexsGyi<0Tic(Jz4^2MzQ!=rc6Bx3Wj&-c~j5`|NT8oanqy`Fvh&%ynT?uEc{ zO9qM1#p0OZH+pfI!Y1}aJtZ@1Ik)f>N4a5a3U`?M%I{%tJd zSqI4>r_jrnV}}L+c%el1!u(RcVLx!AE_~8?Xs_E-KlCb8QNxU_&1;sd=^~fNt>Ap^ zgs*(9`M%sd0)x~jnH%|Bvvo7~UN9UYH$-c{$8BPJDUf|WdpS|XLH|qE%ER-eymb-X z&jX`@seg@Z=j^; zl)vQ;@oZh|2{xk@a0XT=8 zpo?+`8>H-D+)sp5zySPN(YIDICN-Lzj8vY!7M>~~LOoUX+9g)o;Ar?ds=@WeaKml0 zg?04fNaQ3XAn*;I2qbPnaFIwAOykm|(TDn~hstx$&Fzq91nTRNV(_!waWEwwrmycI zu`X;sx7~zYwx=+1z7QgU{&`(DKYZgjx-CO(-fJS1sw8F%gUOF>#9&C1_UIrLYhGTf zjxHzuVA!LBIh>Swcf`=IEmt2^Q+4{LfzHq7+MZ8eK4Pet@YnGq3EZjj$+f-iGEIt3m2oI+{&0Tq zX7?Nt^;0e}6T-tFZ=_(3(dxi$kYn_dQYZc0fEln$=@`4jY9>OA!|$u*(kmE8h5Y8= zxp3#kwI{uCRk?yIwTFJoB7vwH)&?y2)LtslhqF})-UJ&UM*e}`hu z%EnxnAcWi2P)#5ex_&1gpx>ql8-p{ zM9Tlru<%+A72`G8!VQ9~j1_&ht1Bx-u=$6e{8tlk;u0o`5lJ)AT%_a1?ig9vGu8j` z3w;@F+q_WdMI5r&b1i@JLFS1Tjmyj@pKRa?TEbk#S6|Ph8g-bTt zqqA+Mx^QV1LpigDk6~D+yrg$}@_`PZJuUY?Tv?N9sWIEj99``>#65fSFbf_pqx4z6 z(p`=%EMnqQ@@FoL6<(zfsw+WGZk%BeoMAc~Tghut4&{uqaxXTYUQ1IBZ>^HE*<3iV z6;Zh;+mWexHtbL-K>!PV_~-uaHL$f*l6dmuM+IwJeG2aNiknpz zU^_#KT`c&5_WO!^aR5-aMz)mUoFU=H>9Ge5yG&>u=ntAy5@4fBfBsCdm;Imfq*Syb zvIKdGu)A1j^*Yug#l-SJ{`~1%eJZ9*oyo#2tGChg9d|Nk?5p$6UHs$+e{&TrrjU}V ziEmIU^>5_BuHWGTR)7|o`Ofqu;;%}rkjtLl#nB2qecsmD7h-JG*>c0ce>V9)QcI-I zE>V2Ht7(9~My z2~IeGMrN4l1j1;S#Fm8G zQZZREvp9cIAud=9NJgFxWet(kZJ;O)ikHybdt9*O9;YKF<=WO*?Stlw5BaN3gQX!q68r2hvq zpzjc%dThXXrvJN8CDQFI0uP&YgjiMa@s zAomx%51WW5D{OxK8h+}&)b|4d%nQ6O2OwlZ&j2b>tmBsh#4oU2>H4<%UyG)!2TWyc zF}G@BtTerxQDm4qtmyqdWzJb35xOgGz%{J{aRCqBB;VnHHw`d}acv)zX}AP{ijn+h z>Hi!9EznymXa=|z+(20m;4RRykg8i7EFX9^NxlcFFfeFpN<~9c^Z$CTcF}xw0~bNOKI!UDGd2&DnJ&VTc-j{ulVV=JI|%jM1V zvx%PC6XprvK!y~X=?Z{986pr8NK0sy-} zBx}D<>wv7wrXRPLIH(EjS3yug7!RH65L0HWgI2E%9l_19NW$@5Q1$Im^51bvs*4Li zQUJmqWokd*Q6FOSN}U$GpU)A*=Tb|)yB*A^zIvDh1!1K@eF}1qRTUn`3V2vh+ssz6 zDKPRnrN#TZTl=1%0{Z=kKFo<58()>eRVR3*cY!b}6YS-e4UFR6#vy84<;?BRK^CQI zfyD;a@i3rVu(&wFQ&bS*;~o9agd&BF_C`3K^fhw`sG@>^M#WD}pmIbQ$ zQEg|@i#gFZRax%PhzzV|TV9={U4%`7vV^v|Fs;wXb@8ZhX5c?{rZuOOsgX%CYC1EX z&n&K-w&;YcC0v`;mjr#1WQ`5i!t`|3p1YVkyz`jv1^iZL+CSb&V8?2yB_%nTazx~O zUUdJyi%`DIuou_=krsAPd;Ku4r#NQ@(JOr+z%mi*2xXGXgtJyE9V63pcLN7N7Z%jC z79kMLL4l2ZePc{H@+9Erq^E#R78n733mcowWXF+q?qN}p5dj!wVqzldHRt0@y6Rdh z$LrhsBUP@FAt=i=UoySTt1iHo@u6|iCgPBz4==G!i%RqI45mQ~955~r5Rg_ocY%r( zG6D4A`m0Gxl%1s5Ye0TQBk8qoc@nOF^(z!nH|D{-`o2{GZ{V9^!giUIsCHhNR-Rde zEyHy~D(K1z`SeLjN_yJ?I~U^49{(t(9%m`E;8ata*sZZ~O}ECiNdF)-Z_(Lio`~j< zfKWG&*fcmdy6aS%#szliU4qc*7S@o(#8zXgO`2!*@wP-hwr6X?&}RoPQTSqK#70;5 zbWSd3J$J3FmrF}HsC5z#BbXlh1~$KpUQ^NPE!JMe96(RK9D;dahV$LqoP95xf9aY( z;o2S63N~>*$ktjDWTw8YuovMp|Fm(Ye0q9+SLpo8 z&7zZ)SSIY&kN%5x4_=EGjkN9+Pwh|$ON`~hnc%3+@Y+yx8ihMZ?KJ?uVB=PjXVbyXI3%$LCuU;)PE`lf=RzMef99&RU&mbajr| zEWTxBQA(upr_91w*KZ(LQZz^3x!!j6TFw|X`XJxCnm(8oTKr@x3us!y#sI}xYr8G)WOo|Uz#pANkBgeI8J<%>Lws2N2EHu-$eV+N+)FM z+Dtd2w5+advm6R%HJHT1QHeX7qb%R`=JiuF)PvP&SbO^Ue~kIZEl}wI_7~u52_%g) zoUUIhFKwCbONuUDo>U884Fq}~MzA5UTbQ9%GEfh8vbCVKL3t2~85qXr=Eys@kvywb zjL*Vfx1A3NO?d8*hHsxn_{xyiG!L{+k1YQslT*aa7CW-lr$nxqd#N32%71(|_ z5yHOiyTyJ@7LTFAV)xSv{{mjWXC#dNX^x2uC2wD80Z{%qp^7 z-wAGPm2j5o)}M)jrh=Q!4kW)G&J0Ekj_UPpPWKNC?A%&?v$k@pPnZp1%e_p!ugKU` zqU0I~ufNx()~*lGCt)$!M5nl@IoeB0?eQL&l$pJyIRINBJ68)`LTs1xx43Ox<^{288)2pLM4nXLml05Xn7oY-12D=d= z)^SnK*vZn?ZXuefNQax;I-?cJo;`3%ES~TnnseCANy&m+vZ=$RKViSw+(4ncaEGI< z4Wqkn2ntDRKYZ4@6=5b?O7=5jXR2J!PxWM-zX;&`nSRq0A+_2oqN$eV$epRkWRJyM z0oysdr^Bd=pglxUN}i;qVrm_?%*5}}BWsRWrtF*;ZIaqCyFyh3UJn5Ps)~`%Cw8gy z3`ECX+#&F7NKC1BY*rTi*`hOvECt`HlssBmsTb(cMBW*ds-a~{y1I>Q7w%VYSQ&*t z&xq^xN0k#8F7I0IM>L7nuqW?E)Pc&OrSGdt=)THA`67YS%LVcxE5God0TIj=#2PZK z;9f677TZ@`yZA|38e^~|aX2r7EE${_O$4rwpkPfMNl;38W`cIPf(Isr^xr^v%RCO9 zy6uzf^kTG#<;X+_33%b{oE_Kabe3I;~B)-T+;0)9Ad=zv|ZFb$oVLOS2k&U0|2$ z$}+7h>i2eb)a_#b_NO=H0m_Hh*9)a?%a^BCP#9kEQmU-}7(7&px}#3X#4%^rEr7gn z_Tox~lY!*q(o$?NrWwz1I-2HB6h~sTJUL3g;VXxS5do5?9^L72E%z z>aD|~TEF*U1Oe&pk`e^z?i7)(0i==c?o?VzM7kS>?hZj1x?$)J>F#*mm{UDn8mno+&vwPt%9qFv+n zyGL&p+4y&>Unf%Uujlx@w*{70zcH4DuB!RgmFmksSj5sxE9BXqI@gshVG7|!eE-3d z?f}V+P2AhK4#P=er3#DI_X?aE4tkd?666p>XWv7cv8qb(6moi%(#M?od*+*4VF|{# z<^^+#Zbnb*jZNJ?%DCnO`4OI6Hmg9~$+l0}NIEdFb-}qRs?Y2?{%W>vK9e>0Le&Z-_`&wNPZK5fKKrI#h8PYtpuRzv)V)WtrPu|qd z*f)+Ut4cHboBAMTWOW8ehFWy$^-JzzWH5{DO4-{_Ktzvdu8PQ6mh_v=7OD> z&xJQBR%9pvzlnEe=G}NmB$bEyxULddD zxrQ%D@AZwo9c{O0)J8|h?-6NnW~_3@_LP>N{#kw+vOiwG`SkD_@80SZ%T2zuR77u<}cjv`OAEzeQ!<~Pm>ZR|N)V}GpVhx&bD@YoIgovvdvxA4wyoe+7&N{vRF06AFFQK3G}%A%0Jr+H8z4q~}XqRqO?Dc{1DQL5W!;i_3M zPiAoA_`#joQojg@aY7|`xkcd{wvw&f4{D+2Ha45BS4-<#DR$`Xmm_|UvA=&y9yV^L zCn{_#-{Kd$rS+}Z4Ha~}NR*emKT0cEI>tI1sW5~nzFs>kz1tra^EBoDrFc1JE}sA5 zCGm{58MT)*L$FW?5}n!cc@MN#OXLTRNSxy8W6b?sE0plGPHb$=sDj6CBPOFfd*`hF zWFoe@^5FdVEI~iYm!CRr5NkHot-HLzPzs;SFX(t|+>-9?7{VoL6cc|myc4;}O}-7M z3qb0f8aefQs*kJoyT@7ZK)-Ci`5=fPB}Dml=TmO#v5BwW_Iq5{Yow(8a=3AnxBOk* zGrdWFw)CdUnqtiy+lDcG9bt*o&aU&Jg@>0u5v#X@w@a7LWLQ4y_jPM&=Zit1)%pJS$`+#R6@Kd$G z=%*CK@$vlhZ%T$7#Lb^3LX43C}>E!-VPIoq;{b9qp{xmZBH z9<(@}j!+~KEPlYetF2{j9Xv*tA-`&6B6wxXBtPU;r1gM1l4Qp2B+ie39wqc>oSg3d z9TE{10SwN%Zs?my*X$D!PVYgw2}^84xZM9pExOu8b!WY3H-7!-*HF4)o35qbJ$&o4f8!2k#dFPTI4J!icDz?^UUo4ZL5qaM zVo85w_@{N%xOL6`Y-h^TeBhK0RGO@l?U$D8kxgD>Wl*jIM`Fe?ZghfORvVXpyMsUq z_tEd=2@-4WYCAWMq)$mS@PK*W_A7bHg$Q}J3bR(szQ#l~Cw~SMNFAuQljdS$`5tfg zECe5%m+EH=Q1-Qb?~hY=eEaT%PlOdYFl5qtw2h6n+w;|!`?{4 zA3*mpU=Y1Mj#BQoHr7xi#{SpUIN<#T+L*Tx*JQ)O^!va7>(>B)Pe?t_+K4<8w2C zNk64j3XI^BuO^Ihzo#1`!gBJ|d{>+M`9VurQ}d{3#_PehquV#SQ#@qSq9iu~|_j-`Qygf9b5hCWu!S|{fBfkDND9Hyu+ z1!=BxUo=hSfW9PL=G)IIYNtHKwh769s#xR9(T%z;H~f7#KAY#cd8QG{G6lL2#Ve4? z8#kQuxHztLNBFl)Xnzw^$~vi}zKeLTRxIzxW@|b9y(} zR_Mof-&WR}`aX}k9&&{@2REr%%UMrv3}`q>mm6nKz>@U#^{oaG=ymKkS2?UpEqU%S z<;$l4?tJdl{(Md7CyuA|oSl2?(k`cO!G#Ey<~?{ zr{dy@ix$3pl`#VOK;a|l>nnV5agmt+>@&Hzxa`kV=IH-}p!WV^{rvkCfcd-s$qFef zEseBV&XNcLnmNko=`Fp`N_%z?dVg&?!q0V1!kCyasl}1_*g{DZW%UXy0Qs=vRL29( zGN%+=XGeyYQ+q-thy3ZiB*KRT7?;(~AQ&BoZaiIX*G3&t^Q~Az!d1V&_%J#TwNwPm ztNPWyWz&45AiiMO6c_*|SKjG;UiY5w^uB6wB+E4nJ+ngRg}1j6b5ltlE5F(|^cwGp z2u-(8P!MvUSqnO@6}}~KL7;qv0b-QJp}ig9<-fd17&$@z>z)m4yQBNbvjTphQzpu5 z9g#}1o9*`^7itS3S|?T0cr6NIaZ>V1?k2WeBzaXXG&x?s?sQV2Q4;>_jmq-+(5nF3 zjGghw6-WS_@;^_E#McSvojbCXZQ%eOYDi?-MSY%ai;cI}niesTR(mV&yyBdabrdiL zrxy*00)9o`NS`mg5#!ZRLhYcfx5$01-C>-M@MYFJ;4BCC2ak=edsk5@_)^D=q(UgV zKA@XPPk%qAjyF)3+_3*?KW9;Zc1ipvrM)t!Ei zEaa)UGi=TK2#N%rP#zhZ?=HFzNI*Ukz~Y9*FNT`2wY#%S2r_}}#PJz`_A@~r^5?Iv%?rK(-BhsupW1l2_jO5;L68ZLVDtHf ziBQq1e(r|)NL^WpUuN6KxS9P%6^^#zyvMb3m*Ri4bjn`m<)IrGFeo#UHMS)3zwqaa zOyRFPO>;A@I|Xjee+kDQ0(-fuPyX0-n{tAJvCiJ96<7q%KWMEMxqZ6AD*^ENyNMW0Y27@G^|2qGlEsf|FK%7!hS?k(Fb~g7C7`5>>x};KDCcitd zG#gF!vIKsvqCSo4jH-609fbVd`6_a?Tp*+{Z95AAf`4%%2ndMze-lZLiMzIk78Mm& ztmRHY`4A(DWA3(-z`~nfe-7MpZ0ET-@Wi33Co^4?mUm}ameY@FS#yljE=bCy9Zek? z5WEYP5dE{ER%{M0$&3+NAWlU8&oQwVo}QfnNve>z-QC?6d{Lk*B=!0E%lU3l-Iqoe zQbiJdGfDcnl#)8X(hC;-Lvs{mZJ-%R9fR7PYS44)14u)3E|>SFPEkrmmPn!%A_M48 zXy!lt)c+BUSEIUImS#XY?XTeF0(qe<@#=O%BR^jG>Um7A3C<)^RCYeX-*~81uSb_W zdD$hIm|UD^MsC|gK!q?-W=DIN+3^MB1dpBy>-qMfmZs4iA`hv)X|e#Q^>3czuMUXG z37ndquJUfonb^zH?g8!wkaRF~^|tXQ$XGQy;UJ@+EfuyszTsP@Sn>9Qahva2uXOwL zbh?QS5Cvr8ozdj(NKiin7Xn_py74e_J9mMDDsKmO^#@EK0xov~h}$bNg!}N%+V`KQ zw*xsM?c4h7QazAiUbR#!X0LtrCvkq`?Gy9zFOD%vrd8*N=!0ziNv_2rQ2eki7naBy zrj07vT7&{iqhA>nqvp&DEZDl4AE;+q>O%D&vDf*VR^2a!VT}r~-@VHoj~NIr!bzNH zK=Mb~=Mqf&{@b-Z(mbXnF--|rf6)JBp@D>gW*#-q)@3Uun7vkOPHI@_nWSPC z467D5-^&v~cBPB&lMm=5A&sPXOfQthU4R$RWsV`czMu2wq^5ifELjT+N?;Ti@6Oa>Mlx2GYxUpBQy&hMc;bA3t8w<&0F5! zS!(hv1DdG(`)qWe)SjRzY3%|Tbm%r;VN(9bd<)=4Zrp3b@-DuK_RP^JlUnDLPu=QR z0NG%KN?f@MjQAf!=Qi7+`st>7>hLxU%f4dgD{5Vv25#mHfdU|EA+1C#Y$Midyh=&s zu@Q`o&iIW~@NVM{qa^3h0HNp?S?yQr$KVDO#9uARG@J_`nMTjfc(0ocOqZr#TimwrZv!Gb9B<5fsdu* zfVcc)249Nk9%J~6c&Xv8+b-v1Rv3xm8y6VibJw=xSH<;O6b)~hr+=O- zM*Y0A>8?4A@$-W^sI)l6YL^iZ2y`aTWlM*^_9#^40HbhRptUlo)aT?c zmWNtH{mXuxo9)dZX9|NIFu}M!$tkv;u}<+10kzvpzt86&HzyCxN!+C|8WbK;ky|IJ zUQ-v|wo>F_Fps(=Pe&Qo6YY9gu7Bj1AI58S>{am9gnOc&w$|k|gcM8N5g=wq8@FR5 z9&44`nh$f$`+Wid-8_1b#+>@ok#YUAqahIQVN2N62V944rtOK-6*57tQ~owTy%(-p zvyVL@4OivSRr$7r1-jSo%k+374bfjce?G-Ahn+3TW-<9{EkE71-^0B3>c&DHE?=w# z{FLCS3SI&)N+qI|M~*dD7ah5x&7FYQggOSs(j8AfH)rfoTVQdUJ2{`wTq zkN&xs)ASCf7(sDme`XE6dO}gMBb;<|LWPbiN$==Rx4SkfOzc-$PStWwk~a|NFrC|o zWI*RDU3)!;_)`HiY6|Sj#4>ndt?lo5YF&3{Be?ke_k9iiYus#GjG5WPdMr}yKpQu- zp2OrXe3gLUu(E+N>(pAh`-v#M|HlPzdYs_f40N6oDMNKsNdDF5vS~d-9M}_mvd|pS ztfydhsA0RA?}T%6HMP8UL{SsWp!wtow@gpbVbV;VBGdZcQssy(X7UcnrrFGL%c@ATzV%R^4LR7!Ox4H2&C$*eqzwBM~~+07#HWpd!K(+IS2=TTSgcCfzT@ zF@mZ1dAOTk{5mvb$oJKudmP=8Zb#l3N2Rc90GFcE{AT^x@J#oD;~m1e$OM5x)+{sBYw`W{z+YraJI>W!D)4IcE-o*JTiL49~{%l6pr8>HW^Q-1kR zH{$1b#!>p%UEEEax(njj^#?Oq>XBq<%}l&&G&`sO6wH=spI!@p}9Z$2m>5a%hZBiGp9&tP)p#b*8RlDuR(G)gKdCW07qR1 zRK67qe3Zjz_Y2h&7v5ZZRZx1dVr*blGakY`2q5h0*=R4`>y-_W{#ag~OCn6PLkIf2#u-&Hd z%+~OPtmkL+vVGi%NMesoDj*xF=)Ij?p>sd<^Z#kp*2m>kz+P!CtbaQlm+0sFJ;AE< z0vJwFuLt4dQ0Q^7WhSlhUC>R9K;~hJ|aJZ#!$30rJs(k2aB)oimX_m-kK~<3Mg|w|;Z3V?F`Q`Mq z%)7N~)oAc7c5Gc?do3JtJQIF2TKMws6q&y=gb+HRF@Gn8MWsFG`AkNF$;*qfXI$<} z6Youb=i8$g2l-QZ%DKedwpjb;8KwGU+66F5_zR%Zl#+kJDKfa3@$u0It-bHlEzmEY z_0NnOnw)*Yb0k9fX^S3ozEt`YqYJ0f(9)q@VoOTi(&oc(@o|L6=`&s23HWLz-MLo7 z(KYTIgdjb=h>1~fO-}>QwO(7+R~21)*zz0UdU$wjL=ujexE+}4OB6=Fh*Cx!s1oLt zzqIj8)%V?`!e6?UB|o+P3{0^YVrqTI-VnQc!Aj}p-oR2x&60uC0;$uoS`4G1sbONJ zjG;-kh`f(*j_CFgLx^s_M%^^2O%>U8R{@&GOUhp$^7cfU0?csYBI>tO;Du z%7yZ^dja=cR0pqc)CUjjWx?uQwtG5CJTb2F0wBrlW2d{C1{Io^3<=p1lm{wM?z;M! z+jt=Tve(w<@Ot^UvyJ-42OY*zaL8nIzX2?MPUi zo<;#rC?FUf7(ps!oI0XwWi<=5{+&0%@oU+bVMbvknYJIfXg7E&c>0}#asNZR-H{xJ z|DjT5vYn5eop2ZRxUbA-6&m2>c7g=?5sS4K;s~n%y+Li>Ha(oF_MgSUrjE*x+!{4} z>9+qSmHO^VoJdSyLmOiF!b zuB%$9^n1e@H{7o_51Z?~0+Jv6frYX20R3+t3kWmO|L)DoZ`@4cPe3-ZC+z;}!@#GD zTYT5aDWG}DRpovZPomd4t(=U-U5C}9f2~!0ML||NnBb`gu6$&L{fdxOLUHpRKJNa4 z#l*XzAWn3^miy^Q*H!XP$Fj7*)$C1IaK0h8_u$;N{>DMwt}3<1D~XW(eA5p?Lw8pb zq&JNgZjL>9)gIel5IwRiSt7maj~AB7b3Y#j4GO-gYySaTLE*%|-5i_f8I#f(*o)za z2=UoHlk?s!zkj%ho?UJTkBnX#Sq=a?H`G`Mr*3@yav*a5a1uFruq<(5rFeEPrT=@* zbhYuwS8uL~qP;ySjbwQvKxlUvAi@3nAWG@O@iQs`q{o$18&?u{{>3-p8Idf4LDzHF zu5I7y-JpVBxQ-_Cd(3!e&D}Qt2p_Nm+?UVX5h^qZ< zf=8htr)sHiQy5*m;Ojm9?lNZ~rc@qEuf<6Zn` zsh;$VuQo5Y7gkp>67WZFsCjp;M^4W~8r-k$oDx~fLPs8`Q&Jv}(G*6wS%ZgHwcBr~ zBA?vIW8VyJ?6yy{pGxipj1B)mi9dmaTi)Dw;Pj4&M0qUxCDvOeXKPISAG!Bj>`Qr> z{@sVVi&}AMBL(O|$+7e1LSRFu>MKy@rFu{kUA+;gbgCcP$|)UJu-A6;tISQSRga{* zJIkvE4J}f+*dl=i1C)jC%(%QHJ_*>R)&pQ)z0b;Mlz2ggKzL92dj^nDZ=&>_9K($0 z+z2%)6i&FKr7pg3hK8GN6`d%A!AVM*4>t>_oJS^ptZ|e@NX}1K7UNBR6m1)*+Tx2cH{ zrfJ;!$NV}Fb6HLruskE)xg)ksJ8xj>Y!~|hXcxhQDa>54!Okbrt zdQ8jhX5e2iAKjKiTR-d8Ln>k4Gtvi*%8ibzd}x?D_(3ZS*p2k+xg%4l;DWKvK}{fF zmN2o%b>T3BWxa^g;1@h<6mo`eX&Gpb@2&?<;)1Ea&h}bWmKmLGji`b^qAo6Xeoo99 z{s5|5*TL1O2!&&%v3iv>n?#n5f~!EwTldPp@1t-&O})O8v6p^$B@ov^>4Y8^&=D`1 z_hy^Tjtp2NfW@p84WY7;=A!Korq^+>RmS|p5)y>3pu?c7h8*K|yk_%}{&~!Kt|bmc z<`7m=3sgQOpqD&T*tz*?(S;Td@O{j8nf!lRIRDjMd@nr&FVUH7fYSv~fdT=wkaaEM zKW^^GSqy5?rF*)Qzyho2czEtZH_#EhN?dEfYSiVlj`>y&4vxHpQMk#G#9Fd;9Qx}f z&(uqsH@mm^h<04{S5B!J)14bM`VDz3fu=c9>cAwM-jz@h(E|l7VKXMdu!X=Sp8snK z8S_PTr}w}ohkoHOD$B?iWqI@}%YLku6Ej_8ZuywgdtU)imB*7Re1_r>GTZR8Yd!6R zJvi2(QI~``t`NA1@$pNBg#fH!+NT)G)>u_0n$o|Mmz9Oj%*w*@|ADRV z{$^h^q!7s}eIGNs%+BH1SwbaR%+ffKm{dC#tcDd6Ao*YP3@f`sgW!>$wa$)G+x*a? zaNOznP0`9gLHtUCsicEM9GVm+_+Z*4hRJSUzl7})tDV8*3*zMHRZuPLnS-sW&8#wJn#gk7pgK#^ebf}8`b@bxwp&;`8AVbpFW|;#$N-- zHTf~-)Qqk~XENPK%`;&v{k0gaU`JGV?(SN}!fqScgl!>m0RWT#3E-0l z*0Qo>KYv~q_H+PQ7`IQ$M_3<%3sx^k5MrB?^qc5-68e#F=w~K3n@$7j?>!h}6F_1O-0Acirrwtjb1fw+* zvqE-BN#4i{%bH`{xnd=bW+Y_+#6nEVP3<_$rf%I$w%!b~T(FJa-skp=O>{)^=(Hc$ z0GW6Uy5|Tl@Ul>}0eK2JvJ`V_uhwPO_4N$nbWniWYtnqJ)jxn3$Hsc=epTCBu206{ ze_1r$UN>Y_SzC(|WlaKH$ieMLr1;v<q@8w~0v>%#CPZ;iw+hoDay7UYaZhlZGYB=O6}D zr2ZZG08|uH@_K6K;^Q@6Pze>4ZZ~Nr*yitG3sReNfr{sCBxU9w5oL;Y5GjY^)6%2) zEb_5Nl=Mc_BTo(X?XU?3wSlsm_6eaW%Jd@Qw2y~xN~?ac-C(*Il;bHf4}Ma zQu>*Rl!xF|P$7I<(+h#RsWKiWrrNGE0MZ_*0#KAl-DcKw_iQM`q>$6=v!KK12^&Uz zRDcd-w@s$^5;`$P)rt9!u$4oHfeisV&A(-eL{&}!k2Rob|=A`%r#0+f(7-NxwmvqOlfR4rk?@bvd1B%}wC!od4jj8}Td z*|h}IWtjUH(mn0%;~3D0WxU2&?_9JRyzocG#Htc(86JK>#vo6r7KdD69L7Q#&#Zsg z0o)Ar>G3?v3(;L!ujS#V;Oj8spdufnPt@-bN~f=WrHcFOnV#qoK|P`*1Bj@uaBV5x zA&+e;{W~P|uO`@dg-0lW2dVa1Zg1VKYQ@Isu(B%`&r`*-eB8h67~YA({tkQ0e9XLA z9A%`q_7a9Y?ac)U!3zvSjT<3_!z8)MZT}`w&1K?akA+l`f(;HI3f>>gc;-)QIRJtT zTtvWMhcCReKeimw5F(@m(^fG|4H6Ndvk25*9SAaVC2LAd55KT-TSL>!tM|X@6>@8) z=8%l$Av}~#B)j6n#fQBA&+hhOy{-zf1Kh7JoykLY!As^B*%#g)!!V-h&XWPuFe{5q z$7fbKbKp@OWVwyszGUJI)-3HHwWD*=LXT~W>Ar2RgSY4IMMlUOmMBeS{qnc+hrfuUS4KQgckm?aQ4vsstL^C35H+( zGUwJLNH*XXTS?q&)Lq=qcAlBx#9FSgMqtOgSkHRb5i(L4T+<5Q(Mqt8uR)%x6v~h4 zlOr*NSH3RadF;)u`vd(tA*_iD5_r3l8hSgY_kdoDLn4E!=#qnfwx-}SWRngfhXVuo zG}Q44=$@6%=vuu~XeyvVH0=Dl!yj7O9cVzHtncpE6|1Wqob0>@<%O%3R(Ki4q!W8> z)Ks0Lz2C+(J0~BBdx=`%JW8%@c70;0e;dHp2e>SKL4`yIjtWd000)0daCu4GLGBNu z@!!KW98|BY8yK=GDCf>kxza07tErh}9%%;nV&;U6Hh*dj3O`R6K^g~t-^kHRMw;PU zhBz^yDQ&XNR9JIxbBAo_Op_o0`MKJ-qx1!x%Z)A9B5{{w(@D%)I=ylxQq&KAtv;7P z5`6pd4yEzwaWrCbEawB@Ty`A!BF4qRU#A#ai~VtU?LyFl9-YUpMuQ%Jr-q>?Dtx`_ zt{(txJA@{TUK@mTwZhjRQgwj-Qyt|P_!dYmFI~C-1y>6PSbr<7w$)n?s)Ye_hwBwv z#E#lBu%Crl6Adan%oCHrnGeuf2Re%gU&A=vyMrOoN0o7QH4Kx(lt9UY!HG2vQ0hof z#@R7@p+yZh4!mTDJ_#_`<>uz*ev<{5&SY*nXufQBwlxaZ!73hYi){Mk5#ueot1ZT8}#u%eux8xxhn)iXW-pmV?Kb0sfrrS}XV zYpnB?;pHL#v(7opj6nR?grzEo)k0PtM=7Li=oj`a9U9OAE~&et zZE55pucr8!vTDDqL(!KFKLGh4!~v3MZ%G$M(a8NZv%KMUl4_14fdu>$sWmma0S8>#m?^Jych?RKkKR|f zK>ti>tfaHt*->zj1VQ1e)-W(tHv14-9-+JNV3oipd#&s&?Bxaag!`far7NOj+p0 zlhF|#&?8q$z(C%lx|(kKqcMEQO#K>~2=hynK8q9A7n=%`Qkgi4;wK{$CsOEi-h;AM z)VI0rafOoHJigSI;;;@i*pvw-vQbR3b7@J-6xG!N&2zwfWZl{E?Hl($mCa5^Y(HF= z?{2(HQRE{tqzJ4+d<;^rKOwaSBi!PL&eBbR*P1y+Y~g($$&)oLWV;qOx-8) zCBO5xSm3xsiwswk;aFIH<{kLXzk`<_{m><10JfxheQ=bqM)AbPYSu72fnyKxvyo?> zm?eTYxDV`(FIA?(g4cC(GfpOs2^FWw?uNwGs#||&h*zhC-R3aVPmja*HA8Nph<;kw zNij{;MiONulq0g6UB>{m%BcGl@;jTGU$zloNf9s#j^HktqBx(S*-S`){9ZSIpYC5e zK}96a4JyYhj(k}t{)#dX^Y0hNXp#Hl`r`{NN&K%Q_wU(Ic_bf(Mik*}2Xt}<`iUa8 zCYpHGeYwzt@B@;FlF8luDcX1BBQ!K(OSft*+zI{Te~JA(qh0_X{Tg%mDIJ)w>E#;Isibg;go!lK3c+4KV3*&9k+E|W%<`=*{L zke6hWL>z-GOdq{btdIwvV}l56tBu$J(4b)I#eL5^n8NulgL*-fX^e?Oc(+?P`}t2k zXUoHrT6`LXyHE3PnY@GkS<&BReTENvIlWr@_559aXD{o1OZ=V($ba}L0vm}juxXzU zPObdbSvWOw-tP*lYlWjJ9UJIcTp-`oRr5P!>I7B|CRl8FeI@0q;k=|;99H+DjPO-` z0iCGd6K8Ad3x59WMAKcLldnn>lje5OS$pU)pl1V5J~>^!I&sEd>8NtIux>KO83E{oEbP2?vV~;ceV7a?8ti?blg|te}Hp zOOdDkR4v$Sk2OJ&5Gql-TFdr|&ZH5Zm-VNsi?h2}W*aDzu;+RgPVw{S?_!Cm-`9Dw z?gK8)4W(YK4yqhGdyHAFLipvv7vfr1Z02@~=zBSP3fb7T)f~yMKGDkIeZJ_!1=}vS zk@f23?PBOY%%6yZ>;xFQKf^81t%-b}`#k%^E8`C=dyO~hzjv%yQq}q0SkI{CQd6b_ z`ZhA|qI%5)Oawi$p=yvWZ4E`JNvSxR%k23<|9xc*4(jJUeg#%uM%D{eDlC{`jF86N z-WZQ%I%zaz7s#)QcXIO7q|=UdCqc$|U<>g1`QYNWnPSOMUwZQgOSpy-y9&&+kh0Vwb2R-Ov&N)+En- z>8Zu_=ME7`X-UM7-%r1|$BKwjMTuUR1@9CNm6$0g)4ye+TX6|odA?;7lcE~>2LGu0i1*Cn1KDeHx^$2)VfT>mYb3cl|j$qN;q zAa5jS_5eEk3l6;zGKdVsyIrHS^uz;0n|QEYmuWm~Jeax?IauL&IH%+$S`TZBUUq_I zdWXx0Dl!gv_rs)+iW&0r4QIH6ZJOb>gB;84lC`p7c{Jh*p=D5t?0ma{W=>QTUAJXL z&ji~%)e`er*MBlA4`O-miL)y zL`wsHf{xd9pGW~>Eh>hlrqo=Q&Xsq_XPw61zYZx_qb&IfhNst8mDQE!JLT5+M{hZB zBZY9Gb`2BH<<*}|8CCwobTJ-9lZ#{yUuph&elT89rlV<)90pJ+YQJMnwWrsUA-ta1 z*|1*UOBktY6jzI$C!bj~r8lOVyZuU%yW14YuG^_b8Mtjtrg$Mo`vQzv9IBSd%yGvS z?CZ*t!d$clLGudt5bo0Zs?4!#?v%{vSg5vC7}x z%^ve#wXa=WrFIU6mhz`r7cdlON?1=G0$EzEPLGnD-w7a$9^qM(o&N?)ue+tuV^id$_$+r9O{E@9Y;o^$STtD6)U|wH|c|F6=*|>~%<@c^Ov4eBn z;T^l=6j_Kud7fQ;@R-S1+dNtz&Qy_wI3*(+KG;x`v`ys7mkKM$e#WPTDyC5+9qK~2 ziD+OfnKpF_6~Y%VK?T{hVT$K!@4JIn>K-np^^0gk@jm0lz_{?uMxa0ZYu) z0Zr?(9(UZ$-gcgDoc+MhY$Djn0v{pTM?J+qk%2oJTygSFEMRtfm%^QX7J$m@~(7p_C zmHAGLoL9#31yEqIK{bzyK;0ZhMj;4r8f1}iCf8YjhC(`V=F041-v`0 zqL0^0?#RzwhX&3c){+8&Lg!{yd@X(@ZT+rfQ{dySOtQ$f#6z>Hs&B#m_afwBBbC6B zD)Ud#QeTdx40m8p-qR}KiEo&cDNRun-Ug^WRWW`6Hl&0~q` zN2S&CKfD<7XvZChdc7#1NElVQ4?ZK&TwUjHUzvloJ&=nMmM;3Wri=YncEaeR){8l6 z6{%x4z0 zeY1=EA?lC)KCcBFe|oCI`Bnt)pH0I3?zxfvNvw!msNX&_%izx1+S+)%hm4eOJXAzL z$oUVZmlndp%7qWH6oF(XvQ$FQtnSQ;!c(4vrYZp_tlum%EpdLFhdi11(Rxx97M~dN2Gr9$&`voq0UYb(GY#t)M6sv#jL_Zx!+2|Ermzs1Uh8dKZLOT5@X(+$YJU~zTfCBbzQfu%E{6hNSn5>z zXG>yOtA6|CM_3vE{$1jJTF!sB?p+R`wF6G})X%1Ws<)r5))rs5gQR!x3UYFC_UG#{ z{2%U&0-HfRyzo*8ps!4>ViIaO15^tK!Rgds8LxNoUU__h*7G)dBp51a^F0+db1dPN zS7&{cI&!M(E*kWInqpPhlEVqIhe4|;HbQo&lf%R2RMJ7ly~#SMWWMSH9y+DS*hm@Bmy?@3*Kr}#!}=-{K(m<>~MJfrC>%FbU||a z7vl9w9l>#bJ-yCVnqTf_Dv!O`4clSkfx!L!8c${YM|l#sxJhI+6SxHZGfLamQ-rom zx3hGz5h(#r7LolMY{k~~;+DEkvD@BB^xs;5XC?{~>p=Z7 z+qYNJStU)ur>YP>SGk4+ga9NY#mm9F79pEvHKDUA*_2AZtvFt6)snA531`U>PzpG81Ftjgn%SI2h0? zO5{P}*4T`t3zf(7Gm;;rLUERQn4Wke-nXwYy#Ku4Z#XpNZ$GtII?GmMmxG^Qx^`&u znV4^^a4utlqc55DL|eXA;M0E`M{Mvu%8|2c`N?y5L$&PV7wTeJb`hjmiYrsRS5)_g zm(BIZI(H^QVTtw!o3bCurQd4z$awB0R!6h8jaF9|XRfoSOszzl&ls0$A7hioG+AJ{b4FsJ@F28h|E zc=n>fd{FvTvC0uX-*(7*s2DC`JnD1wr}l!&I^{SAy*7&Dh(RrpEE^%fb!k4an3!w+ zbR{_J;DGHlm(JxS33_p$xT{PY*zc1apI-yRFThPpXlIyus_ztW-JP9W()cUU7OTyI zY7YnAM_=mUitsvI60Yo{d4%70J9$i?Jq?lwJA93;bOb|x_Ar8c4&34*TXyUyR^)dk zkSbP9j#g2g?rm)aJ+KS1gHNxYdQZJsC_MH@yuYa{$V>2X@y^5tWEbVO52-ScxVvud zyG)I9l`K{Sd(L+%b57Ra)pG55Tqb`dYx*}5-QXlO&wR@-1%y9rL$*tGnfPsykz!G# zv%^tj@^2@u4(1cEx03UdRo>5zt*Vy-P{ODKHmERWk@oz6`BN3<6pBpi0I-MW@$MHJ z2JEOCc;R#Mj(&(_ysv^SX?rB#XFktMBH-ykvAew0j7SreaNnHnt88K@6LeDK5(md= zWD)`H*hO5fTAt?w{ht zlCYB;8CvS{@z+#BoY8F0%}R<*;a{SCdOu|vRQAucc;%4)Ux(e#nvoOO)RvyENDtt*$aE1(e>j8RiS}+RI3Xwir`Rr zxHeCuHy|h~?MJ+U>kyB=bmIyX+dF-j#VW_(BEZXWb{$5i*fwgj@u@CFp_v|08{5Uu zqa-S9yI?xJ2b5CQ_c(XmTz%6eKg-@^Vckx3%3_7vd;a`cFtW<8KRGx+qxm|CNT-N%s2+yOK&XpP z9blQA%sFX-vsbK*!m(wpW z;4(i%vy+-9I^CRKe*3QFFtV(GhBjZg9iMO+K@+- ztGTuXEd9`e>Dp#gB!wH4E(+6C^=fvOk!oAkjkE!8*Ogz=5%peWk9SgBrdZ!jZmg{h z8@N~z5xjg5_Ox*5SDsd45cF)>whpXjr^nseYHL7@?zP%<$9r|92-hb%rOo`nk4Z7X zb#rfAY<^)Ua`zw|T)cx)@eAY-bunGB6a63#9x76eeLMA~uU{fEDvCZWZR{t*gtVrS zu~OcHXhfSX?HRiAwyIC^FiE?bTdJhXpC5$&n6B9-c9MNQ8O{(fC|OSkfU-~pARlOS zU-w;c^@J>%u!D-Xx+uPSu9pn+&&3e~tpw*j8k|oSeSGbdxvS6O zlkP|21S(0+m*Fj;)yom>ztH&wOb1iUKj!iwdOAU&tQx3qEw8t(l=g4xoK@!aLA~rYafe(q8)=2yn|m7Ptw(2qvd@PbEsKs$BsX!oBYa zbOWpW{VD=6Z>nul5GlOB1HH)p?j)qUGMDSD z)(Sz6yn9?`yZr?Zcw)bT&pUZpUID|SnWyD$=C0Ry@Axx-6Sii^y{;_BaX&7R#sU{h zuqRpg{30*#%*^NYD>XVedx33L1zqhweyn!y${AI(b+7F2=W}1}{dhu$16(o{IAz`2 zII@cDS;67%=QZ#HqI%ikigJBBcaU)Z?EXrsKp3^uo5h*5+r zxs>L$w{&rc==I?fD>esAcXV`gXm&QmCDCbsKZGvb`#Z3$^64VF9oa8FyFdyGGP1G) zfsf4okI4oqKVT23E_Yo(lh$KeA`|lUQLBmMFbm5s?Y8DCWpDbMtoLxxJu(@nHQ8Lv? zXU5Mo0)Biwg_TRw|0tf7Eqj?7a{^J-b$bTRiX>0etw^yFOneMtyXj+71ew_|`COhr zKz_tYl%-cO-H52|tzD)W;?hJhHNRv-zZpY2?aRpP2F1&igv~W{XCf==ZkjcHmgXPV zjC)R|j_av!fW)(i;8>4zZ7{O{|Zjtknazx3XiIhc!iZywd?!}2VM z;=p@xGS+^?ZLzE)BZ;!CrJv|?XIVi4Io*(B{`}LIYU_mFH2PDwkihjY$=-GCR-&h1g7NiO1Ym`@7vhITe|vJwm*KfttCK)8QhuIeQlYn7pID-n*@mWM4Q3 zMFbqe?ISpUvU0eppD2*d)8Pa*yu+OkwP9ei>744k@AN;J_;P;=CBCy+_l>&6yP!oz zW_g5(z4zoLvGr?W>zrKLo`KY$DRuoPz)lxza30{=_wy@iK8{;&O>bru;k>){%0pKr z*n$}PG|}E7*S5!`p)9GlT^>3aofj=-5k2&_}xvkq50LPximqHt%PLRy^h_I zyOnF0N~d3g=9gD6HHq5EsA_PjA>I1G80?8B=RS6>iu})&LNVLoi>&vq=a(5i&R{jN+hDVtqBzJA{RzTsyCh)Bj zvEDGrwYQ@hrSHa4P3huO%e;%!M!IeK)oPMpyC;YwCiBy?k*Q4)(?p2YZAsN_!W865 z6{yEFIo+mDy$s}dRXG({e)5&~evuizJLuxK4*97QZeLeZ!+c2EH=5_kdbzi-kkkP8 z3r|aX_kNm(ESTVaS%!ZR25a7y=`UJ7W9+}Z?%z`nlkxLf2na~U#N0_48=nwNXo^2t z1kG4^fQCtfSu`i4LF3Q-e5t*6?3NDITL}iiPL8Q?p4oeLYZx)W85Gbg*NcuZ+3s+KRIT;J^%;Tlg6*Q=>P-f`miJx3g0$*) z$u?5Sgt!99s4sEF)RyI)dc$YUQ$LfseyuX@N@9wr)ZMxp30)4&Ec3QzNjOrVVDhN)SOLq-Hdo@VI8&4(KSzeO23pBJ`YDN z64*lw-T9dgT_acueOe)If)kftMHaX~z#YP0q;)&oZfqy`mGsLMGW_n&0s>()vk~+V ztS_l<$#4Q;=I_tUNQr>z<||7|Ob!>V50MP=5CO*5W+SR-V8{DX89Jj0 z)>#0>00Jfkgu7P&gedEZN`Jp$B3LB7d!CCMI30|+n5CDGtVN#qxiEQGk~Yj^d$9%A z`D(28RDVAEn87CbIM=K& z7`(#QuoxXf*3q@$ym6yY%i;(`(|97FmY*~?~gJbY}l?`dXs zRM%{T#6hVbp)_O@lCf)_%N8o{zz*AK9d+^gfoW*B^=ooKFSC0eVma_Y){%?5}5Z=lq0Yq>!4VGi=W>18riLXO8*vN9iHJQjXe+ zifT}uBLJZ5)*s5|_2jHxB(sML_P4wlS;+J7w=?MFP)bRKKsifd&*j(VHRWB`J{st) zSVKDKT|9LR&rXlPX#Ydu0YON-oRLws_O}sx(yV;5e!KAKC7^M{oDcVO{{+GLqbhc} zsBiKn9SGuRP*YTrI;Aamq`pul+@ z1fqeF_fZg=eRsG-I&ULC0Ihbi37Rbv6hTw*@YyEWs%H0|w7aGUxudEZxW>7_)-3O> zHPm`&zdj2gV)XIDu$b|J+Bc%6P^>!Ybruq3@$m2rkB{>d2tmd1AOvrRn9-Tx1~4QCk!_Fn<)XNH-|Z*q z%mu5vi#tvM{1)MOEX+F+q_yu$8vkL)wOi)Rogke$y-@nw;6YPyadAv6tbT~33x&pk zEA2boOiIl5F?i4*j1*cD^t*d;@rC_Vy;JSfoHN4?iNC@fW`kSHQ&d~gXZmbGejWkU z8^SXb{ElB@=@dA4c;dYbsXGF>xwwE(SX@PAB&GK^KZC^KikBYx-<@;dv9z+1i9|-V zwGux*{N#I{v^|Fwmu!(_&*Y%>hU#;jtKcIbJq&~%qAVLdS>v78$zvSt@Yeq|4ihCT z<6++Go-wVJG&gnq_}Oyrwg?2G#CmEWuoW$=tsZ%PjhulnwmxnA(S&>YT^RdYYp&Jy zc7k5qwC_vk24vLx9JQCI;41e^k*-=6dW|A_vrokZ`f>&W+^Sb(lAPh@^DVRd-VF>l zsdk&wZ%uX~GgAyr){ANY8vKe}Pf-B9i_0y6#9X}qL;netAd>zi;m>SE2a%gquf^up z`Uw?C=CRgA7ra$lU=fFrm@Q}@PNk=+lww2#c3AoKToq&jsF{0x=*5cB-4=X!f!-_h z>*;>JU6+pX=t|!812X??Yd~@nlz#^WZ+$51u$}J$*s-N|?Zu3v8+%1)ng+NPq{RvQMur1a}K|K5e++OIdefiyu=;`5=iMMtdsj;*e) zUSuw(4aEKI3$>Z)T3j?3|9|g_E6~2$$l008L9qOuFz?(J*??V!z%p~@g0$&pIOkFurVWN+S)EvRQuex7$=FtZ+5%Q zOyz`dw_7FX;7swTm)(B(cr8otK{QeP25iyL6eUH2@QYrKvqF>55rh_QFnz^#A z?=gL)obqz4@kBkhw0g0xsG3lWSx04romTWBfGnk}NXe$X1?}k{*%v0pueTeRsw`^% z!#N+8x*VCH_m-h@1{l>_e85GeN5BZM&eU&(o6&2&VjB6{h&2xpETYoV{Rkl-?aA~LN2rWc;VYa0?nU}N4mI8r= zRjfhTcm+< z6z21@Lag(;=iYHY&nwmL4z75+MQ%2weY2*#u6xx!hICGMQjR4^O|JIVo@(MbsDFyk zy`l-X`Ky?&>s?s{$}?zjaePOjmR|ZsQjY8YXaROl2t#0V(tp})E1a9kN2#)=g99v+ z82+-s#jo(j@zaGlJ28=Zq`5inA{P7Xmp2g_+}nk0gGc?`-Jg#pmE_fnvokq%(|x>x z3rU{+h|8jNHF%Ml)Qa{)2~tw*C#y!vPlwT)miT$v@exW1*R8kxV5~+DVxMIl7x*n@ z83s0xSqZ0?fJT0d!-+A2)kFz3?n2ayWK#i4&TSGkd}--k1_#rhX%)(AOwwq%t4Jh9 z|E27$Kr{)A5s_Lx+t@IFC6uagTG*`*79cnOsG4zAq=?bU1rp1=MAh0vlCMD?EC zZ%#7gosM&xPJ{2eg9a~%QkG&uY}Xpb*Z-W5r>+aF)9!K5HJMmbUQgguGF;GkBVd~= zmgDWSS9vVnJL?KG_uoUudWG+|wzmt*%8c4Q2A5Xtu3s;_y>Iy;ej|j|weBT4n7zID zMBaNouUT{%2NwH_glaLED7|~UZ1w|}NWXw9&cc1~MAZlQqvncl5qgL3VGh?+iLGlf z_pU6-%229%3tysZ%BZ&v}cFv-`A6FIT6$Gflln&1`qtV@}jRER-xIe!>(@iis(# zSiAdRtsk>gA4p%&^;$J$H;qbyt&`6*B7r{x=3IveIZkG#)o$&DL9$xtSAv*M%caI) z2oDC!`5#UGrQT+VdK!0I%`F)3d)-IKzz@XtZu3nc^1^*=XSZzKX4d3V zDF0ve6XimBW5UU8IA>H!EOnnhae@}r<>4K~L1wf8y8XkwTxr@dInU}rNdRF0lLWo-Bb>`g9r9|_b zxxM9&OAD4V?O(}GdEVrA>W|W2EnUtkZ-i`HoxUF|T+rJ_e^&Moo zZ0S^}y4POlxcdb^2%8XH(9JVtvb#Jk3EQ2DnQI-~_oJY?KdSd$4My^&>?Ej@*P zrLH3|dvIUBh3~5Y#nb4ha_*=yyeLk+^il*)k=Wr24GNO{(62>0ULs@hdr1Qu+oh?1 zzYUHp(xZKXF|?Ckhgg3@1{F%kr$Ftl@K`JL@m?L6n?2~Qb=u@-RP606yCqINzen3| z=I+ymPxdsRx1?n?=wug9&m|Cw!W_t-sVYsBN4wnJ|5|DKM@oGLB^87@z)366ApxYBIdv`jsL5dL^T_ zPV_5g&MQM&5k)$ZnX4-T&lH(K35m?6afj~rr?T>Gnag^2iySjRM@w;Bq=)*?#=eH*FJ0#Pv$F$L_i^`9pC(5@D)}`SDxz_j~LADbFfcQc7-Gl(e~v!N z{o=%E9&D@+k zX5>Z_)GM1^l45XflA76?euTFzpimExO5NAT*3Rihalh@cqgrUu_JVb7C#%jP1)5#- z`_1<7?lT}~IB#>$Iv>{CcJeBo1@?L%TJlNUFH%)+&&(uBCwm*?e0M%QO8y(< zV%WF9XDr%&mLk&i+X9tw&9~i%O0WY5e)_rwJ!AZEdccNjqJMv8@*nvcS~UUO?`Thh z7?w6acMJ5>{+C0Us%K)W*|GxBx&?%U>624gKGGk}ZPMTmW@cO_Q}cr;&-Tv1`T$UK zZ3K}1z&#(TTlg+kkZE)^+5xzl|A=D)+4$>X13M1}?#%3)>!?RD%o{M%6>zT6Vav2S zs9}kK$3^ZSrjmDkNM zjMhiKyGwx31b8sJVr*V^za3bTwFNVGh?(bwnI=8Nh)Ex7v@0%|`n}^a;%bW3?^{M* zD7i7K#P|eObT2ktG5+Y$A|37KKa*v4A+h`O|Eo5OkoLJwKp*8ydblrOXIAs7r*vuSf_RWuJ1<*Jb8cEJHphR-4qWd6ZJZmfmxird+oygC`Jb8t~BM9iE9GVI8>*=ec zIZ|g$hF#C*T3z8>q)1kbm-BnPl6Bf908D_87k&h-AbHcJ*cF465qZOUjKss0Ge3}x zQl_u_0+3<=(djiz{pY(L3{~-cS0-mGHvtJ-6}+)R8QsDw;}85~@@!36YR2&_8!76K zEN5UDJn>Z!*FX3R7u9{(;DkuO>v<83&Ka2B&79aIiC^?^85_`;StINE2e%HK`c9B{ zEk{p3C-VBb`1;&n{FG}mZt*2h`Je%MUCaP=$BmtruDyDt*TC7cfH^lPrRU8Mcet?q zhvvRLfQBvO^pZ@m2&C6=Oak*f&^xpBa;R+Uhn9oDe=^e@CzwQAYfF8eTRqBZoV>`i zb36!WZn95~4Df`01svDxFayrHhVNk#+hH>={6`F|fYhY4BJjmAS6~-G zv0s1pMsqver8-LEkY=n}0oJu*1qW>v$2_``|li%UVY)4W_6kqexnFPm&XAO1-mdaq?A&{?Qr#vbC?y=xqMNE`EVqol zr6lwHVY%-ES8i?S!YWR@&E>6lawN?5FNLJfS;bbMu0eMJa9Tk+s;9F&u=bi6q|m*F zq?Q2fcxQNC;p$iyuZopk*>H6gr$8BDOWqo*)meeFv*e$Vu6J_GL^v`);@*W*^rXyQ zd;-YlKf0eKbFqDtLsONJZvCw@$CaQZd`Sr%0u}hq!H8-o z`DwjYwhgJev}5L*3yLE=N7IA8IM-x;{p<6y{Y!LAQ`OtM-iuJSVQ68b_ayxGmEFu) z=gLF3yDCAumV)?7QW9MBrNqyUjRK&wIkIR|j@e+qQ)l$$4+etS9I$hvhu#=9SY z?4!9kpy_-aT+l3Bew&IOE!u4u(*D$z9c&E6LZLhpTiglTE( zMZN7VIvYMv{lxuj*rn&gg*XX9#Q}z7g{NlX>oU_NZ^qI&Fj~?NUafu#NmLocWh%>b zyc7QtYLW#3loq!-zL%>c>%IK-m3$SS(h{*1bqU^O4RWfN9&_k26CwcpL5kO2J&H(W z=Tw~o!jUTQFHsxl5wN_mLI04n?X@!$UMJr@fFg_pV9WkgA95LRx?h<}V6QT06($`knh+=G5|v%gLj z5uzWc(#Z2X{;4>Rr;KHsdEQGGotmFRl}&@`jzOcc0YI+z8lu=-q38ro!~hiu9->c- zA{HFuSg@SI%V~I5N=)LIqM? zHOCZ{bgelO#?`)KKPI5x~)w7vd@5ztTE7deO%w+Hz52@YH*zoZu1$mQYmXb-;$jKKcJwxbQDRklB&N zQ4sD`0yk*n75*7{p`l8^Sohx6?;d}Rn&4^60Z61FE`RS-YtE)ZdtyZ|J(NDIWk8#i zxN^!duD=~;QZ~x$8I2D?{@?GPtN4hskZ1p!((FTU{$gasRt&JlCrL<{y;+hVj{v(w z0Bm5-dkX1;DEeG1fbzz>X8NI%vce8Yo4?+^p%h5fU~}rUIGisU-LgH<2HH8T1m`DC zzh)zNP>`44J)qsGx4!NHOns&H;66~P?{0cHEhJi;I{6@~N_^>L5frFFJz)E=e(BMP z38NXF@GJvh=u#Z+=gk60xXldkpJuv}1D~kFnbME{q1nt-cHTpAi`M80!U4CnxN|-( z(ga%o)JRf1i}}uZV(ba_Y-OJmzqW#c|G)r!NeKqdhOA09pjCLDm6Rvh&xs&cA1gMp z%R_~ zCu8}(5A_zT-lwH^79p@s;7|8;^|O83Muh4PGXXhMAb340&g6> z;^d*sCa$2caH$oQY9%XzRZJ;-0Z$@ytOII82{a@D%K0l<|02e5ga3mVe@=}8`V%es zlVylm5(UK){FAX--d;ldm6E1hmhwX zMz)ib*#O0>ZTSX>bDUdg^sL!M&Nd^tFwl{~V@d!0`Ex4$8ap?%%+fX=eqEg0XpctX zZ_MdP9-xX$GV3d8nRm#nwU5~CCXUd}*4v8;D9{?qg8s^V%wi%qYJ>;WrEzx}(;TKg zJZ-%@3>)cY)RW#k&mOvF?D7q-DXU`GNqA5IXVupyN>O@z0i16LqC1A|eCb(5*4V^^ z3P3qJIXR7+tfb&))gAHwcl~QbR&fiR0;Ec-t!uZ~X|=3K2Y?(u$~*IoJL0rvR@F#i zR0Ya62L;)VIqu$p68R)c5QK>p43?xd7MXXCh9}pYr#1Bw_$aPo9g+KXW@q+99JRs&3BKZ( zRoXOJ3=Em}Zz8b51#u+j9trGTDRb&Qhf{@coqR>s9Zx|z`CRSy=I#O<7dTIMe@lPj z!_lxDqhBj|eYbMU^kpEC-Y4L@M85xJH9p&~W-71KKVsHu&ni9=>DaeE+(2zofKC60 zF_8?M9pD4O&WP9Cq5MByzz~R8!x&W?J;-A9pQ*SWODT8B>DmHi!(!A{e?SF`!3BFi z3siLceAZ0fyor7*aP^E%o?J#Av(700>7e?vt*WA;@0l8vl^C<{#)_VeY0vfsMoCRC zD<&^ZqSuuD%6MGHyyGjT%Oji{(6;wwxdsgzTHHsSHalclA0t+5`uqdZhYxlYq28?b zPMQEH_|MDzO;JAwOixcMciGR?+ED=#l3sTSjBJW}UM28@=qWW82f5trb7(-1T-c#v z{<&{d%boT>K|D+b81i8IQcy%s%*!hhCUTBAj?A>bjB;oUfc5@izPDh3Sk1ahL zy$4I$C@qTcw01gVRKRKnkUpQ|WV*WhI|q@YZ!;vMS19ni)3VCoe1MgaPfdD_U%9c1 z1vuds;ccOiqgeM3RuT?D!`6tv`E%j8gDA!jI~6>H#1;!SpfSYTW~mP3YPQ+GIB4R1 zyMIeS(=jYA-?a^%jJdzV=hPS$$EFFwTMAuODrSdk5DtfH4~YC{6@QogGXx-wejGSE zJD(KeC{SyH(b)kRLx!Wu=lMj+EKg8@%&PW6L&WtSSw7s45#illzOkSF3cu3ah6QkV zDfWEF-Me{(^~XsWw)r#ij$)tG5`#r-s#X~V->O*}D}IX1ME{M;C9K#_`xe_m=+OyO zpZ@M(w8Wi7_9g=$VvI-#8LRv88}J!57)=czwfOlg6}V=c7EAvX#QfV@kE1q~7^1XN z{JRRpW+>2)Mc+A!;o7no1FGzM?9%I0E@Dey>HMin?DXWU0b%9pEb(Fjt6lm@ zjj%8fVwxn8=53bVm$F9KYjkpPzgkcTPWEhS<07tpF(Q=6DA;@kpLf2$IXM_r`Sn(f zbGHl^C{sF|J}0agE16-`5R;=Gzz437|Fv@xlxm*t=)iXx+_OlyHIC&1DLYWhUt#w7 znLkhs#Y=vRRy$^E#y8|Y*A(@e?F&QWC5^e%p6-CS{&0n&@W1+eK+uZ@F7EIpBpq&e z4+(xK&hHMDz?W4qGJdj0b{H>ht35$snd*M6*V(*_QnE<^na|~&vzpPy1k`y;GvP1p zzzx=((#RjC622rw&>+5t>kOI;;0OTFL?p)v(eD)Yy-@Ja#UvszE ztY1&Ll$i~7;L81Z`{+y-^Q~e%gHo@ z&LOIvfvp#Ir+_vPiUu9pgMK=$(~h<+TcFZB^#a0hb&BmW+Y&2A*&=PAE=lXO@Q(=r z%MFw15Pjy_)T%5tvAV#2I_Lk6&#RD=o{>1xG*1BkP`(VqRq=v{&+R}@noC>-0X0o- z^$FOxNWaX|gR$Iz2mA$gMusW%dK+IGAz$8FzziKmH=d^DXpy zfjQWi$)K4*vnI*b+ugy&r}88i3-M@v|YyNE* zQ^3vsKid84`gmaDAQ6j+qPy5_@>G zw0nV~i^m$3xCEiK2OzYkyB_L;NqNDgf)cL|d0-958UXjFUb9t$c~<*)T>H^7B0=&y zC?tnj%$1Cgb9HnBUG;?^(-blKF*yy(>=vd+C(+m2r{j|CMRWAO_L zWH|%n)SGC=He=caxML-hseas$QbEAxl;eRW1kJmVkp*E}qbE@KT@N5me(CGgTWll~ zY(PW9c>X~Zvwa!%oZ#3sN{hQb6_Aq12R#4Ksu~+t*y`c?38bJ6`?>3tSy!SGLGi1k zLs2C(H{Q*kG@_Hw=ZY&DkwK3h{)+DB-#ymwAn$HEes5u7c$1fAaf2e!Pu1hfB_F?|po2NVZV zl9I}g9e`F608%!s70+46tQwjmbaoS{$|m%;@d95g5G1=c^^AO!$jqnvS_!jwqkVgo zpRb<>eI!riHHKx~oZ%{_G*t0Z4PVw~Q>;}*SE-iUX+NGvF0)tGXEvUoKYs4 z8u6XLX9?Gef8SyU$0r;G90~#Ft}pq$F605owYYrtGM{xum);?_TOhLb5{W+p-Z)Fz z#d9B+oCeR`VDZt`?&W{rxBDpHU3K&K)A7kI`1;+Crp)ML+9m6CnqP@jg7Xuh2r8yA z43pcLNQvrd7v=L8nA25as`nzXppruBm9jnOb_=)U!t0c>=xB54i{$=ak1^nq!yGu` z6=Ab_988aReq0<^bdY?aQ#zYhO2WeqQH_A%VR5np?O4&mZ>h`muXa24Fj_PYlEj$d zO~|7?J<@@#2GlYCDnb5Jg~aRT9RTfK%t>N4`W&H=5z{~pRmCZ7wY~F5TIpl;wyt@> zdJTG--9=KF^;p4WaQ^1Z5i3?ZaKWH~cT!3Mo5$Pq3M`4$q<;bh`wTXL&6}+m{UM^N zZM1Bm0}isb21MBTsC5w-+6iLx#;XLAtSD}?GnX}Q^kfxhr||sd^1&@K6zIqshvNgy zNaqzN>KN-rB1i#;PK5UxDHm}<7Bd_(U58dBq*`v`Z91T->r)N?KVWNEAfexX-qZj&e&O2T?^ zX0JaFS~d&nZ-NRN_Hw>tCj!hEhp0zl%Dyh_u7)#(I0g^fibR_tKZeTc;T002=g#wB z3Q}4_!Y=2XKR&IvGvID+;P&y&yPo>5yxt(imD)8{VJztU(;TtWXbnD^+RnDYNVSI52G{s002*}jc|o4y&@u^O3s zZ6i%Y->LTgWhREs5PD#x4w~`@T$bb>5aVOd_qa{7=&W@CFEc=|9G_1~6nta|yU7qU z$selj9}@P8{ms#PdHa@sgfsRN$EP<{tGC`lM?ZnWl9YX3&O}+keQyzcBv4v(pi_JE zB$-~PQxCY+MG3C%DL_;`!8tQReoR(kt7Ka!#Y@k6(1rtf;B=cau(rg;r<+kR&eObqvo0?6nl+4^#6Prx##%gfg47%&wdXv|u>%Y*xJ~(!RzI{DIm;zv<&nTu>Js7bgaiui}uep#E33;QQBuK{tUjJ3uW=Sjg#5bt-@dDJnzcQwR6u!xKCF9ZoN7s zX|4HW#2_TZ-Hm)TK^~?1(+zl%08rt(0}ibJtbO}Z4BwCk*iZ|5tm?=JZj6FgHdC(sICT5?wcC|0!e$y zK~Xy@mD5%8$77jo-K`Kc>S|hh1D4tO#rl%<>S&i<7WsyT*_E}mFDZ2PB%~?9wYVbA zH!c2Sq+60+RD36OUm{FzCqBl^9IcA**i=dtm)1P3qv8G|ri{}5BB-RMhTDY{JK~|! z<-X8^8?P}`{clLB_kx|CjKdEPlAyVI8OHmQ8Nl!zA+_5n`8zsSN zCUk&EFUs@1mvEJEf9uTPY9A_g%_-Kp_uBkB7t8ke=TU+`-BAkIp}5Xm=NO_=%z>)M zLgFZVYu^2bq-480vle7d{?lWtrel!4#hZ5RBe5Oiv4gjA?Vyr}!)f9iQ?KbDIC>*B zEXJoiNm{5pOm0_RV^FeAWeq=V3aZhB?FlH9Q#j@jwg#c-(_oqP*B5KW5jgm*IAKxw zVsocyUF3=We_ja+Fj2w;&`>rIR=)u-Uhc3?Q>MU@N?^W!Rg~DXA#py(r1c-7oCF*lH8@5 zJ_4#Qc_;%cFRt?cln)r?fQtS+DWFM}S#&hOFm%$+@por70>_w99ABLfBGS#19Bj&CI2ehk0BPgw3Hsm^BdCq$!U8i{`m*x~Z z?HUb=?yo@<{C>0(u`T}U?B%<^jyaI;o_u3f4Ij|o^NOcPQ%cJ)6J@*g5u~Wl_0#y< z{1^DkSWG72fQwS6^xTLv?J*xIz>1z88K4we7!5pz0aw#Gks8X(MUtsklIG@oEY zMcb`y`EA*6;PyHxy=2(aPVaU)0>3T-oJv6f`_tk^4JE@4S|RW|+Rfv^8BN%%=+0G4 zZ~UeE-R1L6)S!k{Lc02T{#JHqQE&glX$~-{vnr#|wzrzDW*8E29fK5qJxpLb|1-9_ z2ApoOHAA(Mt{{G1aQ>^`R!`tqP1Z$zf#WoU!v`G^JCTgDoEz@^y={{VwsY@%{f#Tiw@KoI)tWZ-jO? z%yXN4tan}7>vi@Kjy4gS{3R)5dr`zWNpX1#Ov0(_j%zs2RMZ=4gTE94$DR6GIA4bt zQ#tmnEEbMZ|AF(!8>!jAYPn?c)|ZD3+d|KSMooIXRaJ@KrjM}H@&y?}_+cb@T2bm> z`E@cNmWt0SdP1*0?q81z&vzy+z(~(s+?3%69maJ5_G!IkU{ejpX(#M0!4y~XS!Y+L zd_dH(dcD7b3NJLgD2fK%>*D+> z`O@hQ?7hx;{Oe%fw0&1}X_ba;UAw5q;llNx1IJfxn?&77Yuq%={bqmk7G7(f?E1I} z4h>ep>1`iBC#>PM%{ZtA@3^m=-#Cr0-s}{~*uzhxe0>%WO}z(z znFh0NnnjQEvG$jR&cw#`py5Zi3J%-%A}#UFsk4W>$U;qvGzOVA}bXd(){XpY5hHM1FeU#pw*PjdwFk(=}kP4(IANS2&f3GKI>jk(X|+1Y=Sw z-<&4Vytj6$_&j{6yXN!jmu|>Boc1hXP6&eH4b8zVCf{zsW=&ZZfnPK@HfzXK7s+@1 zvFEd$&3+zWAK!!hnKlFtRgQglR4SWL?|fy<@#_BkuUx67emD3v`@Yvzx9^Q7YyH}% z6gvH`35Dc{{Z1<2SDM=cBVdCKMe0kpySX;&;}%*LB#!LLx;B4?jq6qmlCiT?rYO}H>slmOVtjiSVS)E_} zfpKPO?TNjNzrxtr_9H}>+sf>6Rz}pFMy3_Mou91g+#L5uR(SpGC;zv%wZzxxvHZN~ z==itlnb6wW4sM|ujv&=4MsDSZg=>tWz_>!SKh+mCYI$#h9s=HkuxAP-eT&YgmUj0I zDX@Zxk5S+Qh^jxR=#}qhwpV!SN@^LN?(jW_BoPO0DdY7Kx3*7BerCd0>l9svLG#^` zdY5?ds)XOBn!g%Fi>CeNq1vBwBZ{H&<@eKWj>MTVJlwfo?vL>c3eo2eDI!vL8g0cXEJ{pi|y4x%}P9)M>DS>kS@^Ir!j^Rry%3tHW&f2efLbbQ1yHlX^Zi-FM&}!Rq zjo^{&dSA_i{U3&r^6T@14I4j$wFJr~pfsyPp2RGTKLnWP{6;@@?tMhr4-fut3(q{~ z-GAseojBZGQ<*vGRA3SIFK)A?ckC)O^%o}eJt1el+B(&7+Ee1&1i!Fb4liju@Y%{H z_fbXRPZVYrIdhNhf9$Dacs$*&Z+k5~MI`#Gla8$et?#}IJ56LCX>0KQS$^aWKmNZH z1N5M!&T%>|v|t7ScNfcB{e9=^K53;Yjxk<0w7Z_%)>|?s!Y4(_t;G_wD_7Fz;|4>d zdWl;OaE$ot*U}s{;WcX6YO2Jo{=D;j>>!EPBogPz<@>^V?kC&=O`-@m^!6!Y(N%!g zF1K{aiJa&Axp8)KbJYHlP;n%~ZA}?8g``iUI0CCtyTZpBjcI+hYt1d`=anOcjQadQ z<$SOEW-4L0o=*S?lW2Dc`BT(dk>7KoR|J0Be36JXXU8FmRk~=yT6}qvr*(DEcNZB`6@BY?u^zT0yF@*W>H4rJZ)KPy$CK2E`;^^Ggt9oHgG+ zj@cDVw!7c)#!i1itgAZbffh4nhq&P+=Q~)$So3`vB6M@r;rnR$Oq zDX0>0Ty7$}N<&9@c-^m{q{SOzB--fTY2$RUD&v>ElJ2VJ+lVJMVY=6F<2pMb)M7*@ z*IBXsoYm{*@O@Wre)VTYBA<1V@scDwQtPYpg9?Jw*@{DMSmlYiW4}C_FO_d&>TDK+ z@s3?q^MpS+8Sz{-FK?{6*2e*jM#jk_hLVHBviKn49|p)b6f8SS;;O4N8Ag%o|94ik z!DrR20%zBe%ewUsux-dXh|}q(L$ls<;owbyrHLyW>@+0D^lm96}z+9g+HOm6Z7U7HfpTe_s%$e z(>UqKEs}b_Wha{x^7d>wqA&?lPCTM-cI++@{8C5YPEGHFiG@R{d;Zy@Z?CLdnvCSz zn%8*t63?+L%>*uol;{>O(zWZ`eX-$531~jMTom*d5ztMUM0Kvz7jSQqZFT)YoF3bi<<+>A^QJ)+x0{qXv)i9` zlr`al3e72}_il_KsoX^OUO0y{A?xK=^B;_dg;x+Jz3F}A_oinxCyT5Hu_Sl&f{c7i zDFm~=3&=N!$zDEKT_Vxl!6Pg>{kB8SUHhTv7gQqYNUx!&u)pr{At?kdHwd~~`uNyb zuFYv-VRLg_W#vY+T-*Vdj(dbYF>#*l>vA4Ta6Us0;}|LAaj`v|OgYgKiVlTh1`oNY zgrI9$SP;+g0uz%z(K*&mv9k#^M5x5G)bcV{ zDwF;}_+SdWY-!TtnC~u}NaLhE-F``lzg;pZnxC#}ZRcsJfalW)_=%tO`G=nqo4gJa ze$fA?s;iEQs_XiMfOH9xf`F8YI0({+v12!OR@nVEsd$BXaInvfm69Mma6_?4%P@kxd8IPZ{&&irf@&&|;PjS6ul zB&)RlgvMBf>Y0nBIy6>nR^CS?XXg98v%f^nV_hS!S(fcOS!#|l>xDXgIv28vqk3_5tRGc z-wV33W*Ts(;(E@X?$87h6`M|T%e_ZETBKD$CV~a5I$F6fKR>;w+1MUY=k#2}rA{NY zM7N$2ExuO@sA|}Gh>PO_W%IW`E-GtkfD`bab((mGl9@NE7UEBD1ry5msW*>*Z5B$- z#;gu}Y-67Go%ftm_1)GS+@v>Ufv>){_y+W)s-}8mDCcNXl7&}lto0?$agpb5Yy?zJ zT=|!;wHsC@eP2gb0|smO$^&YFdqjdM;c~V9$peb&-q*5hclo=xp3r#f_3PjzkxKXd z%(c6h`QHfsZp;2X+4_A)c2f!qLqoZ)<4}^6*8Q#QT{}f0>^vYxBsND{f=+_5i!med ziM1=j)u(wb(Y6nW^uvwRGqnp@w9HDmVp5Ig}Z{V(IchixCW%W~wMCaMqJ%LyB>`NbNF(Y}}MjO9^ zol*x#%Wc_*u#0o{!DBQH+EZ1h3XB`wvnz3Ty5sSq86_!L(9`| znG_tZ^iRUVf53FZ%znwpyvS*`H;}Z1R+J@(GG3!HJi$}Xx^#1wxC+{&s^2b8Iuo1)<&E5% zTtoSQrm%;l7<$yi$~bv8H89`|e>x%@qF|#_q1$C-v8N6M53FTYR>mbIB}ppDpk|Pf zwF#lNmB1>7N@4MT#`m|jxmvW0{`xbd4r^DmG})Z`I_lHl!qJ>W%jRL;>!Ha{omA>W zMLe{9&x5V#uZ)?%aF3AJb7cgA;C0 z%CXyyquG7pIx&^IRMsSd<#0#OM-FgW>p?+f3_aPDD3?4&m%M%Ft_zN`@ccZ?(XcQA zfV;p>FnL*k0c9Gavj8RxyLv=uN)YNfNTwGQycx@lAp!8DmMws&4}Xr&e%j7s6R*>ATN5 zM!@JhgNr-soc1`yG4wgZ0Le%-@F*;1ZW%4f!>MW)hcU3RWZ>EHDy*)kb&z>=q zc~u@WOo}aeNg!~Tf)f{a0v-;k@UJ+>?F2&Pie|QQB;c?oi(FwcaG2)~G#JlmnRPUs!lG3zdMh5*Ra+tT$?u zfd7PHlEGd?kLgOOV`yF-C=8)XxaQGtgb_2Y>eD3~IcWFC zm>Z%efA$T!w=RKbNx4wPwN@Bv*v;^d=-Dgtu52 zW=#eAw8+Kcf|4$cH5?YU1I3|zOfB&aQdg;r{nvOg89hBc9~a|$S5=Pk1K1xw&aA6T z1X?_zcGI|9W-2W2sZQuf-t{My3x zLu^*ztAR_fgFUzFOhN_PT|zYgBZR&{WLFkr zda=MPGk=)A@p??iSD(B9Ot1uR%AsM5b6;<7oelt8Q2Xv#mWbq~y`z`li zq;2>wFoXrT7*iEsxO`vWO|+PKPeAENq?S!i0_b zy?gh#0fH7urCW>okK~RA8+Kq06Nt1{r(|L8#eqmaO@VZQI|QmtDx(SVNkA=lvG??9E-aklX>6X z$;kM42e6?&fzMj|hY`TURyMO!q*DuOiY14__1sn|s%_`{lLQ>dL~cngshO+x6l_i3 z3#u0Cq9!y%Kv58cQ!rjeK~*WptJg6s?WS>apDwZaY|l5kQiM;!ai+58(NURoY z>4v(OuC8uZGskUQz!LJWdPGMpwahK^zKa&EOSFnr+5vNQr(S&Z? zPK_v@;feQqma{i~^#*-AI%TdZr(N6L=Qy+FXGS_FJCFoJhMALFNrQ&8#J(#86I+fb zWEDUF{Q_V-6(>#t#BL1`_F2!twzjq?(sIJh{FDN$g{V&-XO{BpqF-ark{PC=3uEeV z_c(mc63UFP7P;6s)OtDH#hKC)C*1j7>C?bgi_wA1+}6Po@*GUZM%Lff>|GgPGO>qN z-ks7Iz+=(WmG~^R7gQ?H(E$v51_cxayDA=qAZ*qH& zH!A^#)wG;gX1`p4!=mXSo+mM2z9cLNd!I;L$K-YO3_$8_dfCa;p}%nPp2aYH=z}7=0t19urIgZorZf#Y4>CS zhYwu|qx8`Bf)zaLqtCFlJvct7&Wn7*>cR|;M-}f6aconG}joV@B5*1B)opHEm zW1T($m66tG({0qViv7*b)o&IJd!hbL#XEdDf>+I3sPQWNH>O zkwbg-S_nF>o1uZzJ%_cWjeXytzT>r2L!~J;O^2&K9q$#Gjz?eWiSK3U?Yd6!cRVj==lc0*goyuO zeb*{?1_IBLb65W48@_!>_Fgb###g8JLGyg%JVL6}0q>wttatHhCSLCn^XpO@;t+l2 z@qLx+kv=QyGmHa#^c-Yhm8HPi_a_FVTB$x!BMe^Ah}=|aki~$d&o49E)b^XXrld11 zc;(FsxmcsWkGCDy7l+X$ly8%ijDZy>N=X{?o3`gWg^#N0FsPwh2kq-^=Pm~He%xb>;985PgJoJ=xtKVu{aZMCj|Lx1ZuUeg=(Ai++Wk^8)b?JvpWR34 zjNrz2CZbPFUu^AoBpx&pF@P4FZP7#HGfhXd?Ye)4yLjUM{L<^ip7XnE!7h9uMKXDc z4@f}Anh6h_f>Qg(y(Y~lV}nUg>mRnkxvf+^&rQ9@ev8c>BA20#(;8>vU-TCOh!rvp z5NzMKs#6apBHZZ2a$|`i8C>?#*9MF1v1r{M@fc{3(|h|TE!28d?oM~?K0W#HJB*fC zq11p{Y;%0zBTAFHz{BYj1_k)~%S5vI#H~`2EZ$62M}ed6Vj8}JLyZb)JGAHqJ6K0LnJh(>&IetVK$UY=J|-}%0gQFxCqWZfqmuT!BU&Jw5Eh} zJp%n$C+Fvrhw@mta`NaF4R^Fp|Ix%4ZNlEXITrk^*c52a=Z_e7dXvnPcip4p+F&Yl zbmARcssn9dc427I=hBjyaPnE{zDWo&nrPGcJ!up?jfq*kaIlf>q|Y4Z^AUqUxWz%j zMw!Enq5jKxE|<}V$@1KDt=qa<=-V9+a(R@!0cqzqh!$XsIu2u61snK)Y5l;C>^rX> zfYG+uNYb>OFkyZc7+VF`v9G`u*r2&{CR;#YFIwa_uLIgI)oPjn|)UW);m`gm8%NfjsQFuKRT_J=(-v8*vnI=W0IJTpw|U z2Q$d+&JkW76JH1%z3T+^nU?k1;FRK|65B_dvlJ%lucZWk{eXZ5LniA#zjPMVtaMeE zrM01E;DdQ%qTr~kjNiY1FF0X2BPp8tInta^@5B#me3jVR;!@z@{ifuex39-=^-8#S zg7ua3{rrXD0#5)d?ee+?2IYE+DV@= z%S=p{_+6u_`*m`Dt$}qmbE~qUBJ|$y2%g-#W?v!ArzWk_M}=dm2(dt|&ymYnBhNC9 zQ${p(te7ipy%^^7?i1^MODeV6Yk9uRQc|}=8IhPM)uHCIG(5sto4!KTWVi9=>q>*u zx(&4qxbDWqb7Nf$X-nyF?XtTh#E=?6pI|S^E2HN@E_QR#sdW;XS-TSd(tb@L-fnwh zK9k2*G*|Zne$A7__QSF__P1dKwQP&7C(uTw41tiBKh+Xjpd^hRHEfCus5w&TU>qBt zo~BXT=$&iy;Naq7Wi~pEoRepZk8t~kOa^;UJPp{W+Zv|G2$L8qMr*p>3H)lUm-g5S z_CpQg0Qs@A*Kj~oVcOTab=2V|4dM(UPBrW_WLS|hKSfekqhAm<6Sw_>*9i>sQTqU7 zcH7fcp9AslOV8d!`ds>}6{;_uSQ<`e8M}UP`TlKfHFlL-Ul`jf83$>+8Ve&m!&=?j z`Jq7M1|5GfnpRrj-z0~%q5#@kBTlkZL9dNHTnf8ikLZUeiL{5ZrBIC_^-AN%$JKL` zQbqfDXkq`a>B|mi`a<|#jWa%*64g|Aaq#U=MAfm9M4ql&T6NAbJTR+y?;ZtMvxr!_ zSZ8Krc}-gKAD}g;N|#GRrC}|PL=Gc;!)|ZO4d8lZntjIn$sx3B--?J%!i1C0+IEgn2DKEkjAK_?8iSORVani@;fp*uMsLpf_aaA&7vo*)Hj^op9k zeq`?|UK4}3edW>LIXehl3Qs9EeG|aWSSc-M=47`rJL*>5U;LZ@aDt_lol!cJh@or7m5z;wy6RB3}}(!q3Rze_VKL6QA-Po za%C*}l6WeX78Xl1834m6l(D>`0@#O}31p681dWGM9kKI!xy8lSU1(KlX}&e{-Y`H> z{;8N+y1nt<$-(iAEd&gXTF<}r5O))bO@N)e$ngSHI7eR zcb+?Ksse{>$h><;i$DPIT7;~2@Beaj_qQe{k7lZ^m&Y{pvw>E@hzfFO!l%!lIoR3L z%F97RkU#Nv-hOom9+11UK&9}Mmyw;oi4kdhyf4E$&83XPaui@+fs8DqeYVzt{1);@ z!FeX?sc)>b+D7W?>hAQTWGuM&u)s|qY(ENX`*VTbjHB`DZ6#+5RqX;oRRx5~ z@H~>fBCc^#_mS-%^kHHChLtYQy3UuT}pB zp&Wa9d(qWWiP#dW{%L!6vibarYxmEdw}b;Ddj z3jUsfI&fTKMs8F&0BZqskDS85gdIV^iv9vzqCbGa;Fv*V)h-~Pta>D#vdq0SnxN;u z&~K3s6~F5p6yivxKmN6GW3b6(D8qILA_dlp^=>ZyUwoIBKO`mq|+4P){1@(+# zEDmiAP|Awr)%4J_^xd?tUE)nn(5hUg!o!ybjzyE}IvsaX(&dV81*9eC@r_8CCqra# z>u4B(2sfmfwBobko5{nuP2}a&Zy{bl5nLPR{(#HIt@2f9V+2a%a>X8iPhl!3E$v*j z2TUX;ox2!a9|M^beVQT^6bJy-voqnq1&p<( zW&<=*TGK6Pi#<4jR75R{q^i2wS#mAJo$!CqS+pzn#4Cj_o89H*wQ*nQDa(r+8+msR z%G6VHdW_hBdp#&p%LNifW<6rHzmP(fYyf(cR5H|zZiV;)9U*sq{vtu?36P@~Dx%;H zpEL@>zZ8cllUvg@kv)I%9O!2=76vpDs}yFvn~A(ZH&?tDBXCIEg$7)5Qi_r#uMIx_ EAEn-=c>n+a literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/debug/path_footprint_visualization.png b/planning/obstacle_avoidance_planner/media/debug/path_footprint_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..b7e2d64a9675735e853e7be5e0f892483402ccfd GIT binary patch literal 188692 zcma&O1yo#F6D|sY;10npkRZX`EjU3#aQ7gMy9aBWAi)|5!QI_m8VT+$9o&N3>@ z$-KMPeXrJn({lFNR=f6BU)Am~WkqRp6k-$@7#MU}8Hx8WFo?=9FmMD&2+&W0GW#u{ z7kH<)vLBG3;*De)3Vl!HEUD?NYG>~3X5?rFV_|CtFk^BuaWpftb^2)Md<@qv484iN z@`I+cxTBeov!$Ia!n;D||KzX(~xgB@PVzkF4FU1!CSdAz=S0vA&&FHZ~s+i~e&f(wZkE z-R+-yW3v}(EGKW9;D49nlPC4j^Z!o)8Ncedloess(-{s7WS|Dymu15e2LA-7`=gH`YF%0UvEStBqcFOy!fXkBL7QNWxJMB zDfM!FALT%WRL(H3qejT*2%KLx>?%NOnXk4miR3HTw;0P9p^g!BOfLTGJLuQ3kB03q zE*E>#_khRyR@w$#8)Az7I+YQFW?kkqMcS1ST*F1WG)0U3$3XOw0?=v9Y>bO&`Cb;T0iJ(c<;?4g4-D>=S*Rvxi_cp=n#{MZ&*6i6caYq*3> zBH0K{LgAm4c%F!DsF!YBXNjjIXN>mzbf$sq;5_Z-m)t%ahrvH9g+%-_C5Ar(m} zBuu^^#dE!t;dR+4^{dIh1R?Js@8r3C^YWei$RcTSs!!g@g}WeOO#X#eQgL_Ig6!6k zj&HvUEe%$|(lFxKeM+XyE&J0|>EwW`8T+Py--ao$c=Ov|kHW~V6Z<%AT^^ehFHT9? z=P~%2w?C#Ipyi$~-}zK*5NoAX;(f$7Oy>5}VfwcQO)T;czY!u=vZmW}=09y%Zdf+Y zG@L$kHCZ|$M<`gkr1_kXCgpe*Hr$9YWOvU{UJB}Zv59VN;2oDsPi9#R* zUfd^^6>%lD7!{7#jC!Iry*dv zSFI<8FM>ta5uv-(h4FDw+H|-vKo!VofT#IHrR1B?*_)(9rTtS7)j+?`c2=2Yj5kIr zKl)Yf!`xpAHno@^KUEjT#cezUWwc^a|9As~=m7RMZ~u_Zg|kqDKzHG^2%+S(c< zQU23i_OH&o!FJM<=SMt%^2O>^{sJMh*XWRj%{{HU!bn1uJvT-pH8UiWJlC3OF;zlVSh=M8h<^RK(XS~D-q$}nQ;~3vy;OQRM`0DaZW2>@1uRdAwnC$og?M4KGYwWR1F0Lzo z&E6JW#j0~lpZ{!xMHjrFBCP`kVpu;#%;6~(GfRJ2`7B=B?9d@%gYhAMa(*FY!9<<(6j^za(1yUD_#pWuDVoV^2&-$~_nl=Uf6h@5Pt0V$hyOEX z!DDpa8dG$&NsAhk&eYS2YXZ4Hiaqs zxwN>$0z;*V*xPYlb}5Rn#%`}inZM@2xdPD4g~XMG#mQxqo4-lKh4OUlE3L;lv}Rof zn;G+CXM_+4w`luVt`43snE$m*ehJzKJ%ob8Sy4bcbJ6lnOQ3P;$CK{0&Nd$%qf$J@ zhI_=R$9)Ier`z@v_ftV;fu~oFm*9_N*Kr(K6G|PTOTztc6MWBbltdo5%>w(_m#&d{ z5RgeuqJ)F1)7!H@PTp)uh^#+|aWrtvhJiiES6kb{X#Jj;G89CBEPB4k7G$7s^OIlJ zktq2RzMv42CO!hB*wCpBpD6bZUK>sC@efbZ?w;&ax4bS_t$I9Fk@g(=I8fn|2&bxp6b-@N{ji}zR&BrnAvD|>iPCAM$|`v$TT;0 z?nw6AqQT}TL|4|`=Ju^JlCtdy4ykp3PlvZ6KSR1(gnG64Hqdk|S?1iazyU4Alb+{k zCuWIzv3LJUuq!V7fd=uHv5bZNdg$DOYu6aOmSXWf>5F8V*}B5JZcto6b0xO*cS_<> zp(OhD$J)HVdicw_-k|+(M4!5}POHOI^%4e@D^#?F6otR9EA;@jKdrOaWUyscOCKx> z$kn997>*`DK9eFaeZNX*qgBm0P>0@|z{9Olzv-jzQ5vFZ9!b6Y4A>1@NmvKl zJgy|^Oy>3wTALFBceyI<5M3UadARjRhhP&NM5oBo3CAD9Vz5 zSvaVbhr6_O$#2xq$D9~VJJXo*`4eIb^jt!YHp<=9 zjGBS=duprZQi?#L>R%d8y1jsyrC6S{>36Goy{jZ3)Sg}byBDU0mHNIn+qMsvka>&D z?JOYqv$Z^s?M9l@=U2Y(}A7b15nDBC8 zN~R}Wv<3Xk7@nk?*XOihkww)^<81VS=e%>utKqap44~}*>PKq!zFtC6`c*B$Hzu7r zR=X8JMsQc1SDk5K_j(6mx5(3t5()|mOfok>+b&_Asj;!q$JOqa%0MOd(+_{tS5$oF7!$+=TRkPY>P7S#x19Eo zTzlU=%@+I`zF$K6z(0aaLPFwkF|9!);L2FP>`F2?ICw`|URY?<8~&mNigVIjX0+T} zSM*u%8Dd)|6$69Bf1q(iC6wKUZlh=4>|KqSM*1GVhOXVSl=$>?1xri%r^l=I!jh7M z@!FJ>lxuI{s;Vl_LjJ$I37ze>M%H5zW&uB=dZ;lQ-pzlMIXIye>X5R^yjnZ1^;OS6_akOPvCP@ z{0i5@g@?=LW!s&xOeKANeY;=VrL?As3bt>1yYy^MP7bTtP=bDu%ZE5`$3**eyoWW}Kqfcu6s!z}232ij;xMvF7aVK?p-UB0Su) zkQh5w{Cvr24Ay=CHSu!=?peTGzCY+Y1H@MoYT~BRj`RR?Bjuf{@Gbf02-(GnB(_D$S%ZsaW zU2blft&Oi8x|<)4 z*@V{S^$ahM^iQ=~Y)cdsTu#CcM_w5j`}nm5)sd`LRcyYh_wU~~3AWig&(*amg{H>Fewy9yg`BTD^E>d8CL|;% ztEoUA^8j<(jM=`86Z*L`$ZrZ~X*f}S zM0#tji_pgl!{VoVi`N(!r}^_df}eaYNbB~V-}Vhkd|dqKNdHafQOQ>9w3#%w%2TAF^^0wWtlCB#sTPmRjILE;Aa^AuN`ggThj-~d`N-|yBXBXA0`G_5X&$M?kx76sA zBH(reYljsjg$(TG3_`o|zSAv9{ArbGIB~G5Kp0JI>sL@Q>2NsYNPhPUEsW@Xuejea z9FtWG?P<}mt-3DFuVirZ$x+9upmfWkeWe$Xi(8gxcjH}0F4Ohqv~+0wK%7? zVl)Y8#H}CL=%w-+gmyAxmDjSrzBsFBYQC*V?o%I^1pXFe&u(&ybd;7pXh@rENNv|r z7j~D(UGdsng;fyL%q(Euo~ocK#3E=g%pzj>t#94F?aumc8=riuLDWw*4 z44(FHJM0JZMJiMjJi0Sw8vL;M9_he%t&1}H@$;3ze8=HCV!BGf$Vfy>UOQ}%vK_ACYAv|VOvAcsr_JDTN!>P(e7#O7*%{o<+WqFl=93wPXFrT=_8L7ymc73o zs?_D53JzA7Zvree7bGO@qsdy*FP-F$>!u#(?QC*+Kc;w&3J4*3^)ll_kwQ0Szhi3o zq@S*&@Ofm`#p)B=;z`HG7x!hwHg0R(S%UD;pRs&SJNDy}1V)j&&bYsA&8I?eUFPW9 zi6iJDbwmHa%1d^#t1gmhdr|GEb6#f!%2Zq2znq^rEb2GZ_M2ac4OzbMCJnsC-X*Q4 zZK&Ev7G#cfH#uLalltam^$~46;mhDfytjLCQR9Vyz&sY0jdy*rz^oMSZi3O0ixdjI zQN-31yyA$%I!qiQtPi zLxuuarWRPF%mlKBNwR{X>4f5}OC83k8#Ka16UJJ-f;9I zi$m1Kl7Xh|mrrYT0PiQe*WL*UotPHrMv2wY&5yNF+gXWjL{X<>vu;(K%qif!JdUNs zZIe)MbG4c0H+_M2=Sdnfbw`VnKAycP*@N;kPws#0%6@!ncx_$*6GG_)LdZ&4e4#DfI2ejv$ zpVjN)o*0VFE$7+ftrh1BP<7DK`2!F~T{aOM6^piaOKVM|$cC;gUT?w=OZJ~1+lMkO z?p@bRL>0g40SY{mK%70DTA+)Le0jgO_pGmWG={`P8q{=fhVob`9L~T4LY1bC{iu^x z^X-$y%*=Zsri@{s7^}D5RZX90G;mZy`q*eb%iM>1>Ms(S9{v04Z1`?c88-Lwj0*A0w=2_VKdJ93F7 z4BM!a!1%Z|m8-(v;0_A!te3-m7ZCD(&ASKsl+3GVeQOnrOM37H zWGWFo5}2p>@O#~ygfg`-Xpc=uMw9~MQTb*7HDI?D#t%jw%P>((c)#z)KZnQfm!QTy z39#*#2(Z|j!d`M3|B8{95LH$9ky^yNFr>DD@Q`Cp)Tf6=oxn65{isveagn8LAw-YD zv=zORELZnR#&ZAhI&_)%=dTjA*Dg1`yft7;i9b( z1@tsUCY_U$(n?w0eek?tpuqCGCb$l9*QV!--3Mih_25Z~?u02g3>LmY{Dbxh>-;fm z?QBI_WO7tSL~MZ zqD7A@G=iNh*`C_YdqQ-;(P1W3B5kUkfo5RTs$<}~U3Ll^B@UT4$w^pyO@SJ{c)xt|%R>pYL zxHs-LKJ*c#SgzXK9FAnXZ#D^c{a3-PcW~30g^l7cJg*@#p%9zcvkMNOm za(0_^68PRCiIFGpJtJviMDb1(WY5TpAyUa6OWWZ`J=P6l<5t463_9I0RXf|QLLQ!? zyAKl4#Ci|)KQcD8QUAqQyBCj*J6y^pnu!tNO<2vvfkEH&%Dr|SwLe@3>Xm)6dTrr2 zZTY(8R-3H;X;)R4m`uskjfo|Jm|bd{%`O48xaeld-je=Ggv7|%gegXiWI`HaV=9tP zGD5@ALXtg6>BLAEAA@mY89yvcKSW!(#hgdUbDzjb-sy)m;X5tuNfJbw;$hjm)JzajliCn zlY!HMgp^(w_3rWSot{jO#cVejjlk~ZkFl6M#v!cGVK_WanJQ+k?To#9;{i|TCdE&! zw??=m_$W={c3z!NEnmOqVb%Pyl`^8biir+zewHRHpZQ}w>oxlQ(Jp!dX069vHtYCI zhQZ|Sx$6j()3D(V&CF?e47Wq|DMt#zO0?-IXkJSqfQj$Ha9?95z6xP~ zte}y&Js~B(-oOem+>})^wD)-abhV^@w79kAWD#ZfXiq!ZLh5V(Ua+l*_{hVBw*2|T zP2Vv5M3GekWctn9=Y^#07T&-ZRAv(J7)_5#Q)QY#t4_CKdAtmk6h-EUeEIsO5`*R> z-q^vre*3FeJjF?e8#4s1XICg7QSlrXel6UB^}{Ic>-W4y0~r)ifw9!@2RcqJ_q2;5 z3iQ`2HEErtKIIDby=|3xtQ*g&siTHI!Z{>}QMnL>{jy25E-!+PqvH^4q9 z*zRbppCw5ZFM8eXV338P)MsUv|G0D3gA$qg%wz4$MlojUbTO&!e9~>N09pD}8guNL zDw9i98r}SnD4Q@gz2rz0d$%437Z=LB%v*p*MgYrD$6mWWOB@&%A1^K@CT5Vt^xKIC zrd*tXSwO!ij0Nye$#_|-8BxJi9*_r@mWPhq<%Wo?%9jD% zke6-MGIP-?1VIv+)p}MoA4@Pzyo6pgUPak-E4=3w>EsvHc4J#nW4y;nBa=7q`eB^KdeNs4USI5D3JL~wNeGhT zTrzBRj4g7B7qGn@*rf5uyjl>n?bxMxebjN`V!G<)S>Qr`V#_%r-8nlhfD>C+XS*!t z>njWs92}hHb2%^6^k`THrD)PnP*LgW=qQDS+jJoP#%wl==7$Tl@*wWgq~d*DXuKhF z`8OqFO1XDI?;XWvQ&?5WcoQEjm;VPHn>yr3-p z_?S+9>yFq!f-Kv5-Hk)^bz)+Ij*;=;l+9X+$$7Z>{xv#D3SWp1^JI6h`G=rptdU}+r2~3zd+;HD^i5?Qo`SS_}@j&QnF!w zo7}$kl=DzC;`>SQ?@G+;LH@{=1&>r(uWOIr} zL0$P@QBW){YHGOh*@!Vn_pbAXJue+SeHN60?0}QDazA-Q7Zjt3S>;ZRUuwO<3%Rf> zU(Yh8&=_Vg3@_(_a+ecNJvQBL#u+B@)rm&1It|Q;OLl-3yb;W@b{ZrAK9>dh60hcl1oZyo?lDi}e-d zKBpIKac5N?YeVa#nS}qi)4V(K&hKl!Wia*irf^7|O*%~u=A=Hk&3cm41_FIKQ{&Tp z$!|u8eOHr*TUWvP^XGI zVQ#?+_t*OM@#Q1Lv-QEhBT!I1u5prpgK~_PcUZN}>+}bDa4*ml5gAuE?1T*u&n+pK z^CiX9-|n*U=}Nv{3U z^7B&aeKm~}#9;(htU{rLq#C`GkPs|;$rctluL7cw;bvp0Vuv+ zN-*M6SCnfOMK%V=kC{I+Vu3X zjq^VfP4MU2OH6!$z5Ak#mw-o)Jq1MJlX;h^(J>~O!=M7_iTJfe-LUWasDin)As)zDM;EC)Ae>F`PipPT@zGOVW~ znGhYII-7W;#X8rj9vdq2WIss%Tu`MUBY$OS0E!ns{MUDq)+;tWCoW)P1WQWlg)UD+ zqnu?XGD(x)x+o6ji3^sE&+i#XWL9=eN7zN85`oq<`D-o`go%Llxedq|D$iMBdx#&` zv(ZFw32z8So&5){6PtDJp%__61nnzqw+1jS_AVl6V(;O(;#QTH!Sl6n4(VbjTK%8g zmQuGN>}6E}K=!<7eagD;mDI#TZw+(6rDgPQ3q{04dfTH^UyZ4Ai&}dK{D1Q@O(#G2X(H9^`PIdb=hKu0pw)g3_xP)ch+NgWy0JH*&?kM&;33#OUUFn(M@zZ5;+z}X@2kjjmbmpi=(Ktp1)P3(Yr5EW}W#Uxh5Yy6O+%UH@m=g z@($eN&dE+T@HSO#G0%a0T_R?a2s zZv?qKgU0?d4z@uAnU2Xt_Md$Yuxw>Nt?ycqy}-6S4#HLZv5)h=IgpUR7*Zkly7IHt z&Oz0H;8QOfF3@4Rr>#u6QAj|%H2HeCghaHkq@?8a!y~y~ zd|X^t0==qdA=Ph`4D~OMRQwmDc!@XjW7-#YPcwy1nIUPKqG^jB@X+KPzS~~~fmzTe zw0?;C-IUN!nJY{5DQ{Y<`s)3e_>^KUg1erU-s7s}#O2KNs>ZBMzDf|p5%DO~jNxY8DIC#@{<+mCh`BW!{3unlG_ z^euO`kjZ=3VdxI`dSX2GV?q-R$>h$`-UL4i4^IV0!_y7^FTTI4m1G0Tq2>`J0rDGq z#?mZr+;!nLo}h#MTTJ~4S*^bwAuB^h)4h~uY3~H(hb~x;qXjfuJ-OT-e-P-ptwwnJ zF0hjO9jLUqoO0@GH-)WRawi%1;l4{^K6Dgp_NINh1Ckw(CXUKp)G{(gU}wgT0u0Cp zpYtge)gSB>^2lj5@JXZq*t|_K+8dndj;@lNmUYCsIyRLUx9OE=Fjv_d%)Vol3%3W{ z&2m?bxHp)NY91x0`rm!c(3IF3U_)RmzS&O(xEr3zwb;@cfVj%+P=8awPzABH5UqV6 zm80ELDo-6`s$Y6biM4jxPtkvQyhc$!vOeDa7))79<1twC!O9t74GrRqG@#-poL6kBWQZm-|(@_DUeGr)eE&~m;; z8ei(LsU3wn?Z4Aq)ebxP$+LhFOobl-Yq-d*q3`ip!@!5@YRL&xO-)VrZn}7IY^;CX z-hM{Q!o^Eh$rVGSeS;9?BW0=0>n9EMk%=lJT|N)Av8b5$b;Z$Ky-}v+=#?fqa2e-7 z4!d`+Sw3{q=SOelnUG@DSsi=Sh{~uf% z+#At!Xrx9=X&u%6xb^Dn{(Nk5YN}_U*1GX#2c#3jq*(z|J_}Cevi9W6>o(%5ztOgx z!1*+R^hkMKf4nv7ceIo18DV6pXayr+?AD;Tr>}@3h_8tObw>!h#xsO-LkD6vBb*#2 zU&lAzj9)cAHNHsW+1{bXKp^IB99?pX4>Y7pduwH*sin^zYP@| z9`H}HfpbmfDt4{*aiTx&xzsgcA&-H%0P$x?3d@@fC!w=j|w-l{IL*I=8AS?*85z>IhddMr>>t zL*2ga5On!uR@lY5#>d3~@Q6IGnUnCmKv*k#Jhuk$mQzSFcw-J->Gx zlSD4my@-mxe(#eU+AnUE_PkymVqKcu#{t>TXU*r)hgxTrMyE$vAH9Ho4fX)6&ko$w z?X727>!r4B`-7|S%@!^KCi(Di3Wuzs;;&W&y?x1TyEHIYX#!1b=&1wH$R~G{={3)_ z`P{+6eLy1w#wP?lVDbstz87fyPW6)h2rE-jBF8Q#H&;bdb8gf6x9NjkZx<|tMO)WH zNML?tKwJr2_Oke5!+ZktH4V*_1Rx7y17%K7}&?prv8buYr+y$5%8r@JOJsHexQtM&}} zcJqH44E4os=|vCy*<68lOvU>|F-&0CJRYd8w!4a#{_kEsAeseJn{Mv|hc4je=FZ4w zhm?_%!(7HqC-x$Cj7EHs@FK6$sA}_@5OEgg)<#=xMz?O#zkQGyqZ0*m6M{rNB=h@8 zzzp`ZG{#zbKedT|rCrQBsN~6~Ok`V!hlj)bnTIh^kN33>yQHWSLz-X6wo4^odb-EL zl(e%5Mw)6h(+RD=8RWj3%XHt`wm%8nGCL0>(u!2{U)U(seM+QwiY=@WZ=?=!xGI#r z*09|{%!Eg}Fk+%|+=Aw8ID2?6k7|eH+{v8MbNQs?k(z{gl2D>}d1u8+3lbryn%gJBM)uNq~Y zN!P5TpBeBmf!M;hbIqb`N--wfE52x+dT$1pc(|+6;FbjXWx!{GOk*M=sD|D_*j_WJDCUmFH0qVRBqm1a1GCb0eW~?;O#}llf>6e26F0 zfhd!opOHW?z%gvgo#!+Q$&AeG1qQ8nYsiGZf;DE@A~;k`*pYZY^!THP23RbEKrZzl zabXdC*U=%8q3>2HqR}@3*UzV>8?t((wS0N1JNZa@~!`!*cV zL)*9i)zVm4V^R15`yVg&3dF+jOdGDJRh24z?p$~LPUU=`F2{jya)s(XP&Pfnda>DurM#p`Q=S4+ga?WDN-a~th@sBGpd0!3O3z^R05p_}Kl zm?n?O5^?Dv743-xEAyi!pU`}Tc#>k7;pnyQw^GFt%2ztd1H^B(!%jaW&TNt<3{&#J zzj<@LZ!O?a+1Z(!2^!D{fxof$Nl@vhiPzQ`I_9Q5FU9o^;875DuUp=MT3M zBu$##(Gm`^W+w0D+x6exjAK#Q`4+CXbgj!rg1MIuO=JmXtFXBF@&5sot~FYHzE9rV zRw0~TZ^mF_1iL?6yp{hNN1^M=Ufz0(q9l9@|7-9W#y|rGPq!NH6_b~5L`#>yL1}-S z3EV-O5|f)U$~vBu`TT9iI@Gkm!N{-}<(9^{Z&h?FKgD$UxPt8gaJdQyU_#=eJYbOE_%oEzT^H?Wvbj#~2p(sNowR3G7Dv2@&KsuyENM<6?FeDf71?_OB% zF{1S0on*(y%W&g!qiWp;BbF@n)`|`4j8w;b#%z})h*ksPX z+wpVy7g2XNbn7CMYj(u*>0Qe$;))7;Ufg7EZtUW`PZx{CbAS#bEzJWTma-naJo7p~ zd{EU8 z&c>iMjG{%m3pAd1dH_@2S``gVw~xxb;7;row{-;Fh3vaSlLplK4Bz@@___!%RB;gE zS|Hghk761u4>3J48Cj#TOPSgy@`RmBxjW3G-(O7|AGrgBVgMK>f?;Wi1Y4LCGs@Oz zG|Jt$Ps=^a`+;*zS5^y6Q6!Je!8$15IZKiaU=HhaE2I%%#bdXAH)gZe7qf@tmQd&X zlTlXe@pROdI|x0Q^4-dO52i?gnMNk9IP~Pl{z{#QL0ZH%h{0nm_{)b`;D0%f75|hj zg4FzDp#&FYjyzq_$>`d-aU=n^gSE$GF$LY0PKLH=VFjYye@B3V?B+f7lu( zk&N@_H7>j@$VoO);J`UyY5+Gm*ng60l>IJdys7si3Ky_=JQ)_;wQWVAdq852ChKfs zq^d#j%KzmI;kQ0+yoMz-IhXhyZbAVGEuZt7X5zPmy02&(?Oh0?IsE{U3TWbtSb3d< zjKFx)q?c2UEj2mORT!BjV^?}Y?`A(mhLQ?-J22ZenX>bU+zMZb)Ca^%S=5&K6#WN8 z#vsTe?q!AK!<6MX$2AjDd)!+##7ziLd@b%{v>?^er^L@{dKt!`NG_4V(Gd|LynU9$ zP!M`3G#fqMqE9*Vk~@e0`PgjOuC7x?{Jev#{FzuoQFs?hcQ8Jb<$L^LV+$TKtmv-M zuWn@yib^u++i`d&MQ!Ix*h#u(vWjx)Te7G;c#ACD2MxL&RjU>#DZE^@RIRNH;CY7r z0bpf(#!CUoQ0-W=qRl?n!zzTNqr*PyE&>r++>pn=dT9}z`n_$lD!KiBP?7Qq`186f_Zu^q!>nmLtUC)Qh*zF05x%@W> z_dft5)6Q-9Y%0*qm@U8z6gozP?!SHZnbQg-(dF|u^yub&O&vHn(K1!ea_9@uXnv?{k~?}R zk3UXN9O(%_V-y&QcG0D7RE=Enkg3WBHIy+;d>_r=h8RspeM9vjC!uC!bh9_rT4oDLi`ul z;Y94^U8)oa>$tsY2 zN8!?-i{}n-<(|8nLR!0QAi}nzD~yQay3zFIc>QTDPeJ$G)?Z#aVWhKL#o#U=4Nb{$ zVu~;?C(u(e$1iL~js4ZQWNvk1;8WWm?5ObF0eKV@%nvAleOgsALS^cgc=(`RAnfVs z=`z0veuU8?H#Ep%2DL-2x_S^tC#SoEmEXQM+_?V_sMV$+?&5J~oTg}(Z?Gc3u%lWj zS?3jW2zuBi6p*SZd*)_^Uug&v8AZzl`lu>Y8DjMj7aD64Tez>aTrQDGU|N4TCPN9H zpYkwExDEuK%NCYly70d!BMYmbpE#|Qp&M>W{J>Q_;w1Ujh?}AhW()M0M4IGEAATiWMw}KZty41W7{K)bLK^QG{d+6$RfUJN?m~o_c z&7rQ*eY{e(J6(1AcK7oA(aOrKTBuCBNsV&l|JFq)8XAf+Cbfm*8x=pb`sNRk5(w}n z_B3WN7e0D_gc1f`I>CB7Zqobc0e_|b{~bE?HAs3%<@nvR$@Q-j0l%J!CLi6#{6F92 zFTX3N{r?~kHwtv%Tsi}um*_RSwm;a`gKo|t@kvRuh-zV>GCKcvPLK~84N@ysXY;zW zu~~#BXGgNZOwG(x*{{Fd8BUq>EMtRa0*UGClVbo=0Z{r4uYGlOleMOxpdhK}Uo48f z+m_8N8YPu2k*)IP%^N5WU;1({!{7OIqqj8cji{a;Sv-xxMi(l}fu|vE_i+ps=iQO3 z`_jGN<&l735xdXk^;KGmERE17QBmz5YW!44�A~MUR!R|EbG3G>rOSUt5 z-d6dt(VNwdbRo=FaIF?vrhE6WQEow86-QQ5X#t)WfNLw_5Fg3d4b;*W{_ zP!f$$AbjsDl4$kyp?)&D+hw=#~0WjjpYb@Y_hxzD_wy3t)rBp&Ra{^6cZ4$-446EJFa1UyHT zTjsW!qLYduR$C|ZZKo)oeOK3SK58IsNQ#UWG16ka*iQzzSR8iu)#{bx?`kxaupWJr z`UZhL{LmNzsc_t8*4K&eOtnE}pbI)pax-)+XAJ;gT8k)|_GxI@)T5=QkNeAZQ)@o0 zGw*nHF0@8O9ItkFth!jJf5b`h`z)3%rkDKGOh=j+GqQTTHm;<4!#qaANR!&!=e$;w zIEpg~A@1qr+1aQT&kF3kB5|#HGo~cGCabWWz3t_34za28c$s5_24%t_RXd6kGmk^L z6y|K#2fVsrh??$nq7vscf<8VZp22XB-fa(@u|%t;@iy?|FQN|IX=6@ci+D}F<0 zvgr?tC1ymP=!5sof5t8o?B(F5y8LTQL$&8m@S;mUp>Sj1&K&dN*b?`);cYq-)cd(=KY+J;UG$92E*=ew_&6kQV{@j&@nS04Hcha9O{1KkPnqjymqE5N~eq z^1zSAQ1Hk}SLjl@;q6*-wmdZN9cv^-LEb)NHgXPiG2EJSf5z>L+F^d>2D+ZyU=&2B zYOIU_ZMAYU8I$Jf#*eI&4&L`4uXRM@sl%t~`l^ek5*pq(Y1NG@C1ofybj5c2wZGeZ zyt(5&FJ}s?0|-9CP?YkEwvUeM?#M#|m!aWQ0O^x3Pf*Sm(DnY1ZosB-LvCs3tqV|g zYAB!TJsf??&C=Bl@of#D2c22~uD4mqgnGGFH|t-UE#r{yjj|f|(n_sMl@3YSN0=hS zXpI$}G&&qkICHhD&L(o`Re`$jxyB*O^$L+}#A82V0lXyJ(acKZ$f()osQmkE^ftNC zb;tvLcl59~2xNynQA0n87=mLS@FEUOK;jyUPXdn8;LLAC2Kv#ln^VR=`K0$6aYSm( zx@{NrZO=AQpTcn9qPFp*ixHAj+%zCZS@)?lw{I1Of+qT=+L@mXS&CGnU2 zT<6}C@_4Jz;umg}{$LBbnqrxdtqyYoEr%3Y+^l_%G@U zi%upgc-%L+d#c-OFK!yyVI+?#Yx5Koybt_DJ+_tN^!CKU>|_)Kx`D(U{`|O@4%V|A z_Oc)uJHo)i-KLtuG+aj}Z4O;CL=^Ks4qH8T{F)DybvX^&GQn}2ib{=u_`r1U z*o*ye+RnpqJtl4XrQ)Alx1%D!=l1>!$!$o~wi3xd5mYoyROl z@6H8b9nT(eEbaz|FV;_=!;r+x7U?1uty8{vlRQ^oXq+8@M88cW_w+i<%WoimzC)3* zy`Bft*$IztMK<55>0~B-+1*x@ZoWCL@o8WFKJU{c3}f@u#|b19DrWc+QS#=Am;VTj_$S+nEfQX&D~{$+33TOszS0GapHLf&8;s)5ocXEoI zH%v^>U?FYCF=9=g4j7^3VjJJq%QE**CVHzzoq?=?OQizA3Z~oMk#4fPt^3CPew)@u z5!jg(c|TP8X%D=XTkmJq8S9fCMZ#ewfuxd!V7gOjtjaAENa?RIljSV@utE9G7tPS< z88>joZYRVHpCIFfI7fF+u$V+e7`0%~OlQTt=o>qh`rVm4dJ6&u_Bd>dU{*IRZl{&G zfyc7WS9YUW-N(&mK=WuE$%TWt3J?K1=~j+;rD=5(M-wa@h*(o(!GB~WC$OcRDT?Pk zfX>6+k`xc96gu_Ul5m)C5y%$fi_k$4;-dU#06MMC zsuZra33@JZ{~`cT&BYfnWrL}8)8=TG;vsx#v8BO`QsYyykT41)LA8x=^Eyq=LL9CfjN3`l(o}XB;Eb{}gjbY~C1H^aNhu3?bUb7v7bW`1|JK^A{?ct?4 zcD^Av*Ex9{o(l;+yu)}jrscL2$>Cs0Cy-oPcYdtBhj}NYn3f@0NLK9SmUni*1Jtad zxczB8XpOu0U7$xSMy#}fzt8x_&CA_ViIsYR_sxyC>-WujjNt{94$uz4KlzXVrfqwwyf1u!`vj9{R_U-Qb$fN}7gx-nQ*AzC zb-45!m|v)*gSuwx0IoUOgb4RFOpO!$+gn?cTy0`eqhxr*!N0-n5<|jcOSfVBim8QVKkr4_1d%R9{};;&xY=fs4E&|1jZzVkg+Wl-AqR zm2zzVkqkXV1|Qu(8J>DwwzaJn&|koizBpQLuKV-wWMLvd!B@pr9~@QdW~4u`EH-vw z(ojaA`d?`K_rEQkywQJ-OQxYg5w_3W{SN`1L@Z4vjo-?UdOt~{(2eT%SPVGLs9Pv>9Q@m@WFAOn8|t-Iim{r8#QEqGNb z&8`WqMM4n^*}_HrwtXsQ;pS!fG8u`SBUu?4N^0tCxqb;r$?N-^3^p={BWU_bQ zqvQn_%6I~T($aM;#!Duj&meQ3F5%(;y+e8K7B9?fAo^wzFe$d-6jfMOrcb9E1qFWY ze$>>~^W`VfyC5`o)4316k3Us?717f=#3XZ=p@EE|35DN-3H|v3XJwXWQ_$0-Q|^(0 zmVCoco*X3lji01#30;4lnpa}$3e}vC-=Vh82LNUn9e(E6uEnF%zd*>EDeE0hZTpf{ z{WQ`&Tf4aiykgx=`9fMi=U$2jTJkYCm3@!@2`2^u(C>Oj0ibLqPO{7|-M$bw-imVB zO&iet&!ldBDByv$QV^e-xAOy&X8Sefc*4{EK&Sl#cCP9-B zT!STOaCZw5+=9C`?k>SSxI=Ia?gV#tclXBKp@I8m?X%8Vd*5@vUtj;Ap9kpfs_I#@ zX3a6?nCIKHU8V~hXx>eINV+?NRr&Y4(XZj1F8mgfPIwn5vXrRdq;)z18&sw?bDyUz znAqvJ2gaOZRKjz@=TUhsx{!zY+CKHZDgVd3ftha?VZWl9<`E7@e4i~^{qax6^Q7fg z+vv#@VML##{xBE8fE9mME(Ff9>oYG}2Y(?@PQ(=UnRd}{9Q-0o}v zvLepl^+MjFzbD9{;P0UjckSU~E9K3&xKjw_aJU1d*B`TKKYxm)C0ZT(t%BZva}4&X zw%+Q9tlfe=I=UWCVGEy|HPqYETPsRzFkU7LYc@lRq+hiwiJf+inz=jyLC8oNE)o`o zUlw#WVRfS+J?KF63_GC1H?&eGqd(i%bZ+?=<#y^7S)S0=uQeC8nJ#-1)p)L;o#X+( zMTgsAh)!hG0WR@<@W69%USwH)zVDV|q50b<{CT#cnn{7eG{ee%wuI=Ov_4t^nT8~G zYeMB-tJQ{6J8cg`x<7b+;CLk3 z61N3+OcuEG?k6iEcs9t$_6e7|-gSA36hkd+`iI3>RF>A8_q?%}qB17%^UoVj^?;? zSbmgQ@$(ZFC-i%=pVyhw@60})X7`QR%yB194KDXV8p86O^`G3%3><-MW=BI_nbKaRnV$J4syK+%aWllP^R_|m!_WNYxO>l^G25zoxRx_9b z*S+{O$F-1xoi~!fdNUd+ECrn5cpMSSl>^InsAIervRK9r>#4PB1}>HtJTthe|Krzy z{eAV#I`6F1)a5M-5z$zh^Qs#7hEgGKywUMcBFq4VaO&reSF)9>=Ab1}tNo#dhQsru znl#s_?Pk?vHpFuGdei(W{nerQoIcdHby~ia9cYpmk}6(fy3znB9!%{IvShSmo6}&r{|?1 z-vLK@WFwrCoqNh}rLl|lkaw;I=LVYeS_A$;*b^@cLpa|@8h9X^L+%S6XnrZ2;!BWs zL1TN8`Q#qBj0V(WEj4kd&hI~g$EmQqDv3sUT5tLTM|7>3C>t8;ZBgazuw}X6kwvB& zZ8@B72+{bSQi(1%Iwh3<(uVrmU)VJkVFQuw8(CgLGd+sZi>~KGSH@JyxQ+9Iqnb2MBdY_Z5 z_(T30=C<8mZ7rgaP1d?!959}&QU_R52-l;@;7y!%wwgVz1qcZz{r3v;Qav6uN>&m> zk4<_`jmLI2yPNiwn%_J*B%@s8`{5s0{F)7#X9jRvPuxuf* z_SipgfrgJ7SgrmpHeuvuHzpc{f{N*zGmpjJkVL47s#ibAogXi26qvYPAm%FxWSX1R zlJ1tH{V@qXzu*xbUBHLcu`z+ZoCViopcazE#Kc56ozeeC1X!wG6Y>fg4qwAF3yr;t zK^0JVczV1ouW3wSHCHy@{X60*j6CSUXl0F#kMHRYMo(e{!5z+)=GboaA`1~(?xJ|&XEy23Q0*J4kgeQ zUoie{OTcr@F*{MFOcE399|aA9y5pkavez7oT5@+v5+M7JdW81cOG1x9gzHta*ZNK- zsD*i}EpBs8|15c!xky2lqt0PqQF2iyj7>=7>0U~lb^@e0{_&W}XA}6h*fJW>c=#U@ z$)9bCpYf9c2XtU*qE9DshohQH20pp7h**&=iHKL|>VqYI}LNjc5QaDXF}C8^Txm#)(r# z4=A2+lob&XiSHWs_xF$eH}>Za!2TrGR{tH5`()@Wb<7nt5E?o=dq#uxn84RBUCpPL zq12T%xbx}$QC2nmXRrs8ED5oEAdnuWTKR`pl!3n{{-RZ(D-hnt@iU$37w$Kbp!swG*P7~tmDT%({@;SNTd@+TB9s1NfccWZ!K@+vWz|*to0&;Pnu520Vx{SOR%2d5jgFU zZg)lnY&XVxYoqp}Jlv}HSs`D>@aAX%6M1i`mpiuitkxE&UA#oLI*Dp0sB5uz;970Q zB&rVVSbi9%DdPvhvPZfl`=^3Xi*Tos-oe!bjWct4U9pA{E+)&lcm83`X>Qi7Q7-65%Iudr@0`!>>0|fj*0khgrQAkO7Lw(h`FP>pgYnsQ ziC$;!gx_Aa-{}eCLQT2oR8K8LjOx)>TWQd#uyIq$#{P44#afihUr&F_5n(i& zE-)i{*~^Knayi!rO5En_ZAqr`q`4ab*~9z#6)VrD>p9@WkFIs5cAFbDl)DN8A&b7> zX@HPCWqzF{W9`)c@m}26OC5>LYEY+YTHpw`(w|^~GO97+Ha&Udk{a=Q>Xg5Sb|_Xu z`X?E=vsjr}7)_BL5*bR-jDLWne#>h{i8J*}xcCaJsH zSzf-r8(tjc5wp{#k;V&5By>w)g)dL*+(p(JYwqV(tv}*TcRi!m9Isl1i2Z&0{A=&Z zG<=`%`A*z9B{-EYO99lcO)@dTRD%n7PHmuzdG>}@&}Sb#`+K7f z!yZ}v+I5I{-PyB$dbf<#z*)+(;Av}C?o5H*KizipTG@Bh%-L={>t+GqOLl!cuG?R% zp)OV_H@d&r3BzIZjf=wo1UKIxBlj^N0&rf4p&BVU`DCdEJI&DMtcEo$$iQ!$t!?Y1 zj(+{7M9RJ6n?F3k8?kb?$dS2MH$ubx|2nOIH@Fdu;N17`9{o%Y#>A4YpUUi-64!Ka zfRCN`QE+|9#~XO-kA`^wV?{l0kdIc;ZfYi>^KSzkd>DZ*P*YQrO67>gWj3m?TH*S@ zZZ*8#;TIehM#{*D8rj#CK&!F0+`vppNvWFfwa#i~zR8)s$?2Gi;tQ<-5Hv{Jn5H0N z>qVEnjc`W!K%nr9>q`<$Ww$oE(3Mw;cV`+KO1H~i#Q$z3L@W*Uf6c`_0%K6flX|5) zTcXxy*>q4;3{_!?*ToRw$-8pz@YK#9$a@qN0f=ce5Rq&V zIyY!)IU_=v*rnWF$uQdD4(;F19fd7ugIv7(BZHP;2n1}kme5gv{3<+= zd;3nJj;DjpQZ1u&EO;aZbRZ49fHF2Z`r8fz%coBpq)H_JI{)Q)6S_K)syaF*pk^-A zeztD$n>%pPE}!_0QN4$D=flew`-t+nwY;kefeS6&&R`z$1uDZ73;#3l>Y6g(^8rMx zZEXyw!bO02Eh+>+K@LD=o+u!dH9Rc!{c5j+EKyVbx!uV-43X%*R=~x8K`-D`x1xXW zEXG_wtUg6dMX9J}q4hw8PPTB=Wc55#pzHHK)ko4*#M>k|FVolm|R z8U_m5Z(R;My2EGzq!dk089Wd=l?CE?!ABi9iN~wo;`Tf2a{>>7BSPRgoKP)_Zz_MC zJ&Fxb)t|&5=Enx2%20X0QAg50Hw9B52{T>FTJEDOS5FG(>i<8nSH<+6=rfidpzvIz z3IaCe_RilCusL*zUu`PFO?|sw)oMirBb+~z{LBY>+}|+rd)|qqt_J(_;5iXAwYWTXP&s79TPkfeu0aw&WADHr2a!b_&Lp~ z6kKC0|1{-?S4Phuc*)l?&s>#6b-xSME%rx7LD$+um9EP7+>2O+@b>qBCgVI>le(L; z{gdS5!ndFA@Zd&LSl9F3Z8c;|+w2H+SIHcoS6NxpvAod*MMoceq9kzIQJv=)L^QLn zJzDpnx8HLU!0xSO%6i+UETVf#_zcl!3cfjC>g4*Zw|__8t$YJho8j@udn7ePF=H;I zdQHXsocuMH>vh7&cA|1j^x@8-s0ixz^yz<{W~oMR6=a|zJfVy+m+Sm2`>Csnr+W8k z5T)M{G9y-$_@c~Iz2ytFQ^o2K4Wz!O*P~dkwzP1}0wUMxMj&kp_xcs&8EVXPhpbP5 zMUC18q!)|4P2@5Ce?i9;&=BhBOEeMQ+ha7BSJT>E zSS)8nZ28T4XV7Gb+f>4*UA6wkrWW~PU~&#MjdV9~kt_^kz~}K-GX|=TU0DXo@8+4} z6*5p!2UvwZ20;b$6X@$DcX$(qb5bm}PkfAvBBrQ#@~na&5wE}^KU{ijbEXPo@U=xC zJlmM-(48j>2Vpc(@wj>(>0+PAU!(xzE&IkHV>;(9|K4KYW&wscc2C@*_atK+Z)sq)c&6Zv(HASG zC21g4a*;%=ecd@fez3R*8LJXl^?`0~)}<&vy4tdbwO<%#lj39#RE1w3+g*}HPdb-o z8xTPu5cI&X{9JQcrCQ}e9a%C&GUC8gVa>x#Z#s+{@1nD91{D4ZC8K~~_BJ2W-|!n$ zIq7)wEwS0}2dQZ?Y$KKs-ChWYV2sI}iuGx6yE=4uCKxRWcMCJ_93X{7IP0P4?k-vm ztHyOA6UJJFr*6Oc1O=mdsrQ<_)X)57Jh6$3v*OZT_4%HSP$z99!du{w%~r}HW)yvG zXA2hG(wbc7tM9s>&Nlxp65mY=8<6DoQ5&#&K20DDi(sxmIst=?Z!5Aa&G{ZcAV|tk zQMva*<|mLS8_d$sE<92t!-&AkbLqXkdxtN&Ik+60m(lgpAw9Ibm1me?$v1(9So= z6fkGGd1s^9q}pOvF^=22EOZXYQz~)I;2Q^S&Dq0G?aB9Vddw}Bqfmq7)xZ&3GfPW0 zdGF-C=GzV5Rqc7`IX`nUT-CSnVH6^VJU`O^?{Ixw50@RYq9Irp+{l#DEW)@v$)Bp~740nU#5eTZ6#b$>q&uDoUS66TiC|rFCH)ln zmi&&EZvE4JMR&G#3a^6Kozn}t&Lh@uf;fQ^I>!``P_Q^J zI+eguS8qJaQmE_@R|dMeztZ1ExenzFe13i7PGf;&CA;O8(UDok=zl`h)GASJdBK~+ zQ^`V5{FMbXhS<02`jg0yIEmx;8&Jx83B(AG-tr2wnX<;>g0^XW#6*T_tfetN5vd86 zKby1eca@9R1lH=Bx!x`zI6wt0Db{47R22Prk=I}3y^zV|-ko{G0QKp$oJ2S;9&=GK zw5&Q6wG%895x?~yahlxdDNgp8;z3&6u>14H@>{TH6ey6`@|^dzZK{uQ8g`u zy1(iCr>!Te96)-kd^M8m~-nXm{y z=`y0b6GV?Q^HFUat6oGm}o7u<(_eRFFE)OB<5?bp%!V?!y{sz-~NQ@== z+zld~h29slj++Xs5!a1CtZwcn_ghc2Lt1Rm_Z~Z=RDsK32Q1H&-U9>vXUCv<6I@Mq zJ&L^B_q}xso7Hpj61@42dmpVWuRv@TgCKPEshvF*QmmU%jD*}yZ~H~Ynw&Qu*h_TM8@3U`)zQ_6Sj*E8pxsm(2$6enk+idG(E4ih z+9^Y~2qZjEu*?rU986Y9Ov1{VFilj7!ZCwOnnFLgHvBiOMKK>7)m8v z-ol#yv4aXrsjhY<8Sew+c^7xAS3|ul;e(|ErVX6=Djb(sr(36#ud=x_1lFRoc#yrN z)f?f7;Art+uuDD>eUQ4;J==BTh&%o-vW2U~lV6UI@lN%EFJ$GhVPoe>lnD7;?T$(z z<-O-nrs)t)V4d}_VGGD))4NNQjolPe{2hhvBS(~x-omR@wco+cZzI|9x7}LsCF&{= z;en4)x=U3}y0@rmpW%ozDtqfh*I_XqwN^7f5<*}Ki7~r4MhdN{eZNm|0y0#)zLywI z)coXka=wAlJ?2?UW})}+GCBVv7AXsMB~Oj-UDN#AVz!{Ei}M9G{?dg}NArkq$2|Hk zX6k%=OPN}+D1(tT)GoZ+LesXaf^wm~nhV=d)$F+!AdM7y9yp;!_K!06h0{U+OD6BR zm10W!DS-m}xnGT7GvXhVbj}rA91eFRiwv!!%1M~l;6>o~L3JreS8xXW&stxg9AH1v>gU;jrId4Ppe)&s!VjMo6U<54+ zvaUbuRIm54@`$UO6n4^K~D2x1s}XV5rD9xV#Mm$b6ZUi6adU z;v4(3EiUM(T8^mwzTN;!f;J0!Yz$iKpp-G-IlA}_osRBjn)o|3`osa zAC{vjM&EEhgswX@oju`%K_hb`fn#MqXU(f7d>dp<*=ZwOjw1}??!=j;59`Aw05{Mh zB5@MeXM!s7PUF8H-a@NiK2(kTp}DL+*oFT0{unJZFz=mcp>8Yg1S(CVr@ocK7R)I9 zC*!63tuY}aGWW&B%<1r-2p>3k`x?L>#<+= z{Slgko1|3J-ore~7K286Y8#?+TBTeRybo;IQ?l?byHf#p>*%-o}A~@MJ^3 z3)!u~d4O=0&mcPGxQk5)m*-=Ma&02nn|*v5e)KXq)g_no*4j5h?n#hKuco`Dxujgz zCxg3Bjplgi9Q3~A3u?n!NrN4E(N}hHj8V9QJs>XTY7K_RI{fX*c+(?W?z0`CYVFec z(s(~DfEhGi^#qBtb*Cu8UGaXm`CjT{wwBO?zlx@gW72y7iL=3BEHoXyr@@px++!*q z`eD)?2h6Ismyhqxj{TN~SIn3Fi%0~Jo%+d5{@X}UA+#Jl#`PkIM{t>~!E>wL{FxI) zWAre~LPS`I?#M#_1NrXtkF2Z@!Y>{|4$-r`?nE|R^v1wr=5Z2 z+&9y$zDQ$$MciCVmx{XU)Q9)k?O{PMP)`>JOUJ7z7*jTqPauBY#m@cC*AIdISL9sE zZVxtwuqy7W^quSI6XxKz_81yzQz?g^mTXYb^_5NaqpH-l4emc(-Ko=*N74+5$2Hj* zzjbLgP?yOLoiU1yRkA6a=$I+2KYA$Y>rFZALdOsmp2(2=m}X3PA8*V%!Qq~MvFI;(m_3DyyNS0fCF%BAXGU!I@LOHYhOl4lkh z{?1Y!^4D4YG+90y z24#-x${57!qG5gePG%GpT0j-HjetZ9t`~jZNo>Y+Y_)K$6e%EQa=yFTq$TCk zM&foa9B1!g;`S7LlKxRVvu{URawb+rgd*+!$RXnNwnr&t=SM0jfQ6ME|5JRV=ogUF zQLxVFo?fIAJc#>o2VO?iSyIBV8!yw*uqr=h`Um>B^?MA&}{ zaFHA=e<;ZJo!h0qKL41QPWR7TTl9leu|uNL&xksn~gD%)&I`=T}huc`d+e z8q_lp6zmi)`bQ~7?gd6B*7;<%Bk3`H6Uc1NM@n1scfvs1sq@=nE}tWSm2`{1tOLO^ z?|$Op_rM94X{V}pG9uRTOcBr5^DzCOczG_I>-htqA^mF^bANnENw3lBv`(JMQ?X2x zEC0DPw=v(^T08V7)gJx5NE@c$9Ttr)a0O@mu%)YxblJ8#9H?TYJ5i^R^nAJl#S$8> zt6K+de%TR$!t$&RXw#m+?qV?0bl#cYwtW7{&emgpY^e37yu-9qD>RAKgIZ|qiG7#d z@=I6FhN*X&PIG5nbepl%TA<=F23rFj|N09#8Pj!WgXYX83~AM$#gZ?-8_oEVS?Zh8 zDEKMz$Mk#j2v1`x9e8ih(!=I0X2qWzgBa@{{!GEQA6$>e)(u++&&_PNoPP@cS5L?N ziO_ECALF0uja;ymUm6p&;F%lTj-ZswGzWleu&m-eX2rmAa}))CTPii(p@hqOk+=Bs z1IR|k52q-LCHg2xWPA$qFpmNx0q$KxU_)o7qHqg8V^q>(QDa2);T@qayk^?`w(V}1j0?^ zsG)#P+cMtcu`wLJ7}mcV4~(Vs4JmH)W=rqPi59G=!&nlhHe%T0)%CZyY5 z6SFDcD?MKqUIqo~>@Ag5x;ugKeZu8m)T;SD^txZw_jy703KC-Kp)>^r&r@G7jJ z^ei(4L{6n-#ez=}`KQ_<8u4Z8BJzuC$kWJ6L4~r?PR*4YHOFMuV?x@vDd8ATK zHI27!Agv~`1O}`S?K~TA4m^QPPwGduuZ`iE4NO$hpPAb4bIQR-U;)uy+o{cx%f0IL zHiMg%ICBxUd{Yp*+ZbWOi#hqb+O-}bcG-N8Iel@)f|y?xdXj5thX1bhPC31!?*4C2 znB5c5j&C^P&u=^VT7NvBnaR<7<&G6U?K2gx;WtZ_zn!1F={41t(l=cUKo%TIHKFHv zPG`*j4f;=JW2C~uLMg~43;^N)sdzxkqC6&tZ4;b?%yhEMASS)l4Bz(aJ`BFTOcq5s zs3rAr-pzv7#NJ84n}Zx6sDa=beVA=!U4q_WxeN7Ts!Zg2Af7Z^rSiI7Mug7bp>GWLWgCc{(ny3ES_ih#l_R>cR7qGI zR2-6W)f^w-pjC5^R|Z#W>~S%)atT<>K9B7rI;DreS;=g{iH=(BR)H4UT#qVm7bYMU z-{*t+CC54x!u9^lZ@atj-OER$-}`FjyJf{2Upy+NFg4C)9V0h9(PF3SQRT>@rtw7$J=H+H9O3|^!bj=hAMbwBwl5oE$m`Q2x)u|AL zCHczcQpKKB{^AqlLjkPkW!K#_$kVA8z2msA8Ked~2X;G{@$)7gpMOY*({>Qi5$+tY7G}UMc z2H5Q`%P*1r0euwXQL4!WJY$OWD!1CGeg$@V*PMB}))2JG>No5z?T66Tc@|64m$0=& zET`C9oo9C(Ogz3-`3f+TOKg7cfmnYrC<>cp1Lqb6F%K<^$Abf4%91N=M#DeR?II?3 zDmET#jt&;nDm*gI4i4e#A+0_vtnb7ALBm1?Q-Kiu&a@MmIvmmITe-uMRGdF8HU$yY zaqq2Gr@rjtY;<>Ximkf+NQI~}biSdi4CN;YSlN*N5y~>aeTSam(HMxom|76}FG_T@ z8B?8kA5@%|th_3~JZWksK*|1H{r(mGr5#^1GbX+Q(ieABwRGMq@FQs$< zpb6+c^}u3lLVZzH#o6i&@7m{?k(KuD(s}WdBvKum9VZOSxaLCEp2k2o;o2Tsz8kE$ zdY>Ut*OySKZ${)hgwylmXlz?$_w34JYwspexT=fWb|J3MHQVjoAS6YMB*t@Y^=oKl z*N;?JIA?kpUFBe}!+N)HJ@ERQFso-A0p8w=xo^Ctrs?&?f2JP&Kz-LU@W*|}@Ht>d zt4|%4Q4wuE94Tok-Hk6@-&dZ#%MYPPB!jjLU89$FT`88k_O59@naSRzvQ}U3{62K3 zu2eupoS)Mv_nYA}FRJ-u!V#7d1Mr*VN{4-Ux9$Gu8ZFUMp!o-#bP5|835g#d-c$Ac z+AM)yXY>auiI}+fCqBOPvojmSE?t0X1%SNz`osV`psR|;s^xk%89TZyq|Nc31f0@l zCreN7YQ%xsK{hE)oiU6^-|;OvZdsA*ovbo>>-y(Tzc7h-J-2GHF-KI~V>*u&r6pMz zBf`;s1m94^{g->(K&{4jw>iFn(+`R#n#A%iq-10S$Ll(^7PwtO$mNsgGn^vA+rsJq zGYlFIvAyHKje;N3u-DnpHRM1yrk@iYg z7aE;v5^;PO8W2X2?N+llchRUabf{TsBC&pv2hGR!-bNs?=&)MlmGmPuF@^SqVlyzJ z5(m{rx7(APsY5D!%;?60{|684+MhXlpW{1=h$2A>`W)9VJrTq&e~xuCy|3(-hMHt` zNWZnr>1vC4(_aljqq(|{ou&#EC}zu5&K!#{1H%J!LIaECzTZ+QdVXKe-Y^@`1;!T> z5>y=ABe*pAT50V^=e}nsd{Nn$4sEpzYIID|l$JV9R2fjMFz*3G;wQkkltuJRzRPzi zc(0dfUiOnv7$3zBSae4h3A(08Wu@fU1yAE7J_o3^Wu*@nuWuQH}n9yR)c66kC7*CTpL!oh)sF7aJmlP+aS zeQ)^r{gZ!SpgvSt=0|rvqC8VTnm1Ap2WU^BhqLW=asCL&&ClODcd7Uz5ZymCM1q1a zeG(9_2Z-&B$KQF?C!w2TdbKGnVDEWdrM--^JCqKW_ILWVZr6M|8I7A#C0Ek^pUryCAn zK|aA))!{X*$Ph=jZ=Itc!0erzdF~X^!oLuFH^slT?!T7Y9XKn z!xSop*f_I81snJZ6Z?!983T&~^mpCuHsiq0Yi`C@QnEGpRYJ)aJ76HwYQ%)=phb}+ zrC+@uhXMQb+c-Tabs4Bwpeb#&1|EGCN?3W7CBSK+mn=RL)rE zH4o=*9q566{rF?(z(noqSOEx?~1gIl6Jf|jt$ffY2LX)DvzQbQ7C1Gi$+~VEn zKs7rSequxUb!(C*>)bDS$|EN?x_v7DKb~=VW@hK4Z_5^7kZYGG-rP8GH3^c+<8pCv ze`Cda-M>fdmj1?q4R68(Lt5btg~Mhc;tpo~-QXaK8g8l>saXD0!y~w%xF}?3M{q#G zC}kuN5Nx)pLyzp+KR6f+UOYLm%AWWfE#?mfn<^g+i&7KYaMBG{^5I0tw|cAS2zk)v<50PERd_ z?W;-y7bWSe4r|7gM2e3DjI?s;I9Hz1sitPbuHlC;aTqRhpaa)SLz`-PvM@2Kx273J z|FJP2`10OP5VL*Xf!O~eKGK#AS7C9nz&DH!cn7G0QBvgJFajL7!pjaDY`2188j+Bs zL4sW_{$I>f^Kfyjb*zqg=NMSOGiM%x7VKhGKrzyYu5O&*}79K z7HnIOVFw>D6REo(TSBC0s1B(5QfY$?yHrxiak+USS;f>oLzu=ZjVOkO_q#c91_Uyw zOVitW6WPtnymG&+WD94eeLK_h$n)e_hn~}Mw4mcoa?CJ`dWdI3YL?5NbR-R#l!zCQ z_sUs3cH&iXY2pDB^dt_~MU`#6LDhK};Fm0W+;W!LQn1fI+8~Jm{`wRdPpyK62nYXL z7Ldd&$cgxn_2>6!!3GXf)7uM6K@3#UV~1y%rV6$VW_w4PlI>fD!(JXSjZ6U%V(iHy zBBU$cWxi!9>keE4222)ftI{-JU^gOYBfIc$Sta_e5PtopM64%N7N1CsQ1x2Tn=Z_* zNzfa`iG@~(Sg&he0tJE8#PU6}o*+)S3OwRIF2cP15LC$Pfn3@|s*&&gzLu#n@P%>E z(wE~Cs2%$lckW0KPYtUm)!}(<1iV6n5bw2kyiSy|5W|Kj6BZ#Jt3E5|EYqY^hk(z) z{zMF|2$90_4!`q(J#Qe(A&siY>2n4?S3^;jlmdArfGJI?T`2H(PiM!#cj0P z8ARp!@R$F5Yif33^YVm#bE9{Jjwph}!s>dX%49*hTNS}OxyyoYe{D=u%yJO<<-=QG zxHM{$wM%x4@$u+|rD=nrL@ko>r@CN#TSNj&T8lSrk~VO(a(uz;J}xL7t9 zjQQ*lF~&h&4Que+VU}DnRT!QzJm7^CJE|I1n`c0IV!2BXcO3PXx)TctSk!UGWqCVD|1Xg0P&9V+KLoU z`lo0)Im~fKpK>Wtr5Fb%5mZ42*Qyj6&&@|K%Lt8#mV*q}Ue*%J?&&NtAW zl9l>j<0?Uyr*o^M28E72{GizkzfF(fYw%h+xFUV(%b4Lu7IqcnJ!c_3308VV$#}@f zo0%iaH9=OLleuIm)*(o8p`yK2uyEDxo-Drtr8ICD7~Dm@p6NU#((36Y;HAh@cM7~) z$+4bv2T!=26+C?LcRBT0s=s$G&(8SH%deeV@rfxdHnOOXak}z)gvV(M+4Uuk=prrF zd~eM$(}P6N{QkE16B6hB=Yt^kDB#_7dXDt|@}~o>f%gG-x~&*QpKsUreaIviMKn3s z*j1pzitNqIF2czCNtjx%c|;ykXG^*L0qYfkq?VleMSIF#sbms5Dv}5`1AS4~ zqeO^kHCDU!FE_7e+v)ZW4g{z49h~a`N6~K(_In3l`FSrLgF!^aBsuR^bqIP?;AD(( zPn(ytgSg)DOwpdBl zpCINhZ^0URqj*?bR5UrS`koXDI3qRKu9Nu*?H7{iSc$m7I6~V%`Y#R?!MJK)tXu<_ zMNyHwhDPYrKFnsrlO`Q@r7E^(TZY_c|Ec}$aCSbHhfJe@Vn8qZ18Yo?k9Wj~5onPm zJgxK%7q^2P2E-GdO?rGGX*fg+KI;UhP|?@L9X>g4!!eR1*=D>d2c0+e6T0O3WxeU4 zneM}HQ>kP8F%PfjORMr4B`743Oggp6+1fY}P%1wS%xIH-k|Ox`W__u~h^ zQA zs@#tvVTUf#OcviythBE)1{y?_-piG|%`SfFtw}81DcXHbss78f{yT14z{X{_!nX$x z>j5{C;Z(DJY(4hYz;VYkF;YPWoMG`PDe^zvbgk;PZXbbDA$Q6Y2r+;)b$IZBA&jJ$ zgT{R8_A_rQ&_PitUXki62R?bUm~Qn#L0MVv;dOSAS!Bk3c(+Mwv(@QR)S+RrY&%vN z{c3qRw7pIdM`nsbm&P=Q1{FpqGTawzdrLhG{a7y5 z8K(G6A9%vOb9a%q=3djQx%t<`0s3lYbhl1xA!?PG6nYv|_lrxFw+>z$lvqVZFVp&2 z>dWvoid-{`?AL4Qg;m|89+<6CPdt`fI{e zu0ZzLll6=02rwj)U@+viZgTR&X45Xg&=7swFy#I+=2lSndadN(fzAA zGdKHrAXnOuk+fbBUY_e;APNBQ?85Na!fIvN5Iy^E@l4t}VR5f8q=I#T!0WUu}ue!nmA>PzJDGGwkonDabxBz_C=eJ1t=>ED7 zR|tlNdTiFxXpudIcsW%dW5lm-cD^?^u2?w)rMnRT-r(f@p?D--U)=fo-xdopy(b15 z8t`e+pI6Q~0L~GGiKXSv{cZ-)#iIcSrIOtom6qF5xnjebe54xLehB7-=H!f2QrF48 ziaAxYOYApP?!dLfla-0U@xd7tW^*f6i_Xh-#_99clC-+nGbQ;s$=+u0hnQznH(Y1tN zQY&Ba>24C7w4B(!HYVsuXrtYUzU4`ESa8&2xfXi1o8#qaXbog;wdd90E<@7z^Pe|F z1r)M+kIY`X4ezxho{tRO51UEETJM;xnh(F$S}$}u(|e?f=X)idrp|sCRMF~|q=BnnPL7`g zS4#>6M#vjDcT+~BS&HP;)WlsI!oOq&YBlKtA$hY^WF`Mcnnz*>e+E)Zsx&4E=zM0< zm^Xl>$OQQT9dABnC@NtD;4;7daf8HHGX9f^>6gZYL2jV|N24 zTrO^Iz?T93clnZ$`opi@U7>FnPCfcz<#*%qVl}%a)q(`HUq+^SA63wn-G|kk>Zdiq98Z)a%dtnajxxM!UU5KVVCP#M_vbPj zj$JiGAu@-ND=%HSxQ5mypDRJi3zC?U7gtyqQv~kqH*`57nVsXL2huvpV?aXk3(JQc zpwsh4j3nJg`J7kaFXtEbKV8YqXUn$yyYT8aH|cE;OY3fUGZ8AEPx;qXtUdj>%i2;8 zky;XmTJLP1?I8D>_V+uQEf00>$4g$@{kvs`Wmx)8U3C}vH7Xae=4Bgw4@)#H51M68 z{C#7)sqMi*y#1hbbTx-no?e!?U9^ml7hM@1Q@A#Wb0BO6Z&1V5v9OM3dJsGPdfvg- z{au*OSz*faVDxQzZxDZ5u(Qz<@>=na^BXN4uz9h}Rs_*gNOEm{!*TK4mg`+&>bHgn zejNzzbJH`q=T)rQJl}W!jMa?XGjkm5_kF3IsX;H1O#gP)DV^n?GpOwt9HNGIb0_pqG)! z-p7`Z#6t#rn30r0sY=-23jL{tL(2|V_q#4vts2{Fh1Y=W72hQL2HtKC_4HSj=1?ac zZc{R8s`zZ~>F_>Kzg*;8{R;ld@OJV*H;}Q;7c|o6Oz}-Y@$BgRg7LbSM`k8T()oLf z(FnOuj4}$F5KH5+m4j9vu2Uwtk{S6N7Je~_-j5M)*_>|BY=^mlj4V)SDDP2j?JJckf6r9^P#wZAe@?S(Szg(bY#&6Y+(nlzE0* z9<~kBdw%~sI$pi}QVfI5cg6{psqBce=dfN4=BcU*kDPf5*P(gA;Q#(~nJSmlu1Cmc ze@f)~YdzSG(P?%9UwwCTMJU4P`8-x`VgbrTRJ$X5E_DdMu5y1f1A=nJL7>4t&iJIu z#(zt=bd{6DvZo^ccgAnQYhZZnBY8yF`fwN{&;Z?jzm=VkSl{;}Gr!QodUTp(7-Mc8 zpVwV(38unL@|H2!c-%Q`SQE_Sc99w~W=&erni0CTzcvng!;X1CfdDPd%+6zLn(>|vGOZM9h3Lp({XUnxwYv^Q_LV?TsX);2Yx zGVLSs1LpiteAy65 z*cbs5hr7(EZuetszjw=YEXiB>N@BA4_|={SOO1j_mTq|8nWd&T2tp4|d#D(ZF|t36 zZrOSY<*IVj(v5y;z9Q0PZk_t!jJNY+D~aRW!M*Mh8t2r$f>m?TiYrYfX6sjlDycyHMwiN;6Wt{NyZ^l;pK4t3v)PM)88^Om1CzQOh?oqC?Q^ zZwtm7;{>d@2U?k5$#uL#ifWrG#QVXmlX*<0R6tJd5i3U`lTNeVM$ALb>tQP6VjdKU z8rt)x?+XA(Ia;jikITriZiL-EE%}6OvC#>bsDZ$OD>$g{dyg;B-gpAj-R)d22?`pT?J3HgPHoUWk_@< zH8cZrHd)nsch&LR+sj=+c*XKb5mZ!UU>c|GjPwze0J4lvftG*p6wHj;*avs7$S{VS z{1f=4lv(4r0xYX*s;g=6Q4&AV0Qxd)kQjtpWAo}hoR>11g>WkMQ{wf}!Yp-k^2uaQ zATUh@Mmlo-=ps?BBzn&3=OoQA>>{UcrAmw(9+fI$`@mXf$Ek}YwXu%l+ni}K z6MfQ-;|~07$lmk(TJOX9I_^MdIvGan49rGy&EPwYrDAM^`Av*UKo1h4(f3Ns>x!6H zEo>@do3KgyU_qEL$CS?QVi8B}JF(K2de<~bnGkL2DWBEc*jVdvWlFF3H=7|fo9^&7;|WVM*d{jOxXzgUM!;~VLS(;g5w_USQV-#4k}knN(v2Fz%1m{-e=NEmc$R8V9E&u0?|D%1cAV$YH`C>2(6BOeA`DpM3U@j z{8bedCgb?je%_n4D)4+&`TI!y)XIWO{C)T%nt-jWi4-*s4vw>{Ya(KZy};V>@v`E5 zdeD0w2cl^vrdA!ofRty?7n#5@vxRzZuj1irqe41*ZG}j<3VaTBP5-oa6@YR>-cp?` zsaIdjL@Qr)Ie%PZc~YRAZP>Jqmb&@jf>8?cTU4y{A6@CyOdVlvGro*wLDva2CME`$ z4&im$Hoz`pLD6~pkkvTOOLW#;rsa92DD3nscnE?ku_UryQ`F&%L>4evSG^91#K3%U zno?L5IML2+cX=1*^D?{oCk?B0517QdTbOmXc}7}tkU5)vjM%VwQgydSBz;n;rd8~l z_W05rPhS>C-FfJc>nSo~OG=GHisM4C(sD}it_I%Zwt{lDkDL2(NO?~)qUj~fPw1Hd z6OAC%OzwY|lyOx!Y& zBVWdEqc{}pFg>G9M=Q~X5g=-q9;ZuA`bd;JQzM*p5wVP28!0a~LPz#JrwHS71mw3@ z4nyc?X2HfSi3uj{;=I9j0`Y}~ql`Q6ZWxuUm7ce5i&`t;7=e;nv_y_c)^VGEIxaw( zY6`U1Sw~AG8|!1ylw%bF{Xy$3TD6%a(-Ym*CGY;8qfZ%^eZSCoqv&~~l8Q_5xk?V7 zZ2Px;MtpcJv83Rb6Ar7lAJ*RlG; zY6*L22nZRSz+g@9r)|==y+_xVz@VABe3sE%a*1JiH^-qErTR&ZD3&!x77^Ym5}b08 z3r6pgQ)J#zHyjQ-zf`=M%%Fz2=`GTy6rC4?_nJZ;3||GgnOhH#NcgU3NO)hAyk9~e z5jPx|kZGApsc{T%?s?9yR?Jj28~m+a@3^YF|47p4|Nd3m&^_)D)`ozKUVX>+5P0^( zetqQ5j%3V@)GMY2$7UTb86GM)7a5B0xqVN#%O<*a8`>GJ_b zY}6K^T%A*j4hN>*LM}>@Qwp+XOZy7}e=Kv2ZoA@iy+Q2?rFm&WbU#k=gs&uBK2iI8 z$tOMn=QP)cBp9R30w+0ey&7)YG*2L4nk7Y-waLDkm{=gcfWTf=Yq-^HJaOQ+L^i_WIE?-JZ@wn;f~n$T0eISC1O<`%HOjHHKv8` zJ%5I9)@1PN)lp>1S8KQEb+(28(ywh64rAd5{Z*LXQq~TLU#zy8dgwK5o^{NRHVD)s z436qubbyt6WK_+R1BzAq#=w~?u;1{xRWUG_GI+Vf189^!Ac=Q>x!>cvo>Q~1vMQ>p z!_1osE2OK`X+hIl_}t;j#9=lmx!}Uw^=D@0O-Jl@>Gl0OshlBni=A$KkAW9_kG@~1 z11;LGyeZrc|${$c2$O7Z`NOZ z+*ND^roN<|e-BGDJ|iCe-0~C@vH*ARvkSJf`FM|su*r#KN2$gy#6TLm(?n5SE`>vb zF6)}>)bG*Tm$+%0#jW51iV#ny*`9cO>Gf>mX@QB&`h`6kDV@n=)-#lo;qYAd2jlVq2n7g68Tb+Effw6D4a{w5*g)-eQeHTUic|hRklcU^#347sz_7Cuf|H(noYy7Q zy?WL=))A`q1*mwh@Haa-S4H6nAeEFAYE4%0B3RMiX319{QY@IwuhP8#xOMFbZSRT9 z(nYe@&_JC{bncL4u4vP8*}u+!SD=?;ZMP(we`-jxLUX0ERU|gWhFzVmH{2F?mO)Yp z<#f~q7olnO(GXCLwTWYMD`+(6wX+4Aj7C)&G%M(3CjMB0PpVpWTYZpzp1#$pqgXbJ z*ceh5z*4h;Gx4dCO<-8sh~N5~@k;Z&?G!yZJ>4ygV%~b(conYDs48r3P6hhu0eSQ9 zVn#>?qKiDmAIz4`{`?tQee}0-T%`l3c{4K&qQtN;wQbMIDca!nbIsOJ8)m2p;{49A zwoy3}N%F{|Xe1ds!o_p=$~PwFulqvWo!87+gr#Z*G^h|sc5QHZ`L89jJmPcVe+wXq z&!hppd*=nPG1wN8F&L=QfV|q4ToMRlsSmIH`oJYZ&lNJT3shu6$k;C5+Tf&?q+ZeT zn0vdDCK!K{oo5)ejZpdOE{~`OrydH$Sf*Ik8SuH*R|_ zJ3o*i`ii&p#ZcE1!C)q!X7sI43puev>e-@G5~;w@@Ra7su?wM=F?SrN z%>ZgQ{-`51qMuJzpe<-?N9_|e+?@KJ`^E>?J=LV6beHNdry>TbPudHI@C4LRqWbs_ zoG~Jk@AD@W8=U9^^G|u?ckiY@Ub&{O0~}P#s^ggL5n$zS4YeIPc^np+E4Pn=Sdwj# z_xwT5FnOVMUcmj<&h2sx#HH)@2seH#!>9?!Zhnrx6J$6AN-QwF3`hq$Meyt5jVkd zZK|XV12dqfJ99KSCukY%aKU|GVwFul)o!C<*VVQwZAS^kds0=Ei$mb+YBjs97gj~r zwH_00;oyOKg=~|YvXdTor+b% zL~OK$Vcp(1{0GAL8#sTnPid>AJxOjGlQl<7j_$Aispn7aVEODgy>bPl>O>*Xc)*kb;>y{qeU*!G>oJ6?u z$I6ds4kML_&uPvT84aHt{QiAF>ohzh@W8Xks;aB#R@~<8YLj;`+h>S0pF0ED(AJu* zSp86{&hIi9Y2H^A@p-oeJTlPk5(X7gKc~xmdlIpQZRO;|HOwQ_t2fp7Tkh$GT9r`k zgtK&+kG?(C&#QD-k^v~=0C%+4JK%K{DzM`3Pe>`-ZBon>jbLm;dI$WquhK~B|B+z+ z2`dNs@fYy>GgwV5-yJosJBZFm=KbZphn{safpJU)O@M#5&enO?uiWi5( zJJ2N@p~Hd!*`)klxmvP@Y~yyWJqAv#8%fI84KH}$%i-bS2c4ZU(zq+W#hDx0 zAE#L|EqDQ?UZkOh8}*Z^RT>~=yU{5QOpr^V0M+yCf6SJ%U|_?9upUQRXw|>QBJ1`3 z(utM-dprL>@CgcXgneLgu6W!LLJJv(ytejE)_r>Q5pWPzzXE}lz;&0m z^gz_YDK!ObKZA^v3Lx0qIaHN+)@jdz0dF$+fX$;kHD%BDK*h(MA$H(QW}0XbM*yeL zXmR(5<@rE{U)htf&1dkKpJx4evUYL-FKw#YT;coNVhLo_m$^O7sE!CvTU2y)O`nLc{ilj&?h%5;*f_*B?P zC-YzV;-^8x*}rGYe)>fclc~Z;eOK*%H}Vque*;EDz3GT81;?~BNPiIdO}g1vEqJ=q z(YY!qAaMPRKSnu&nK5ue>2N%SKZEnh#9<1Mb%pWzQ%(>MVO7!;HWXNcKltmbi9^tS z3CN+7ILk$ELTzH~XX>|FlP5<0YPy{nZvLibky0Rz@TXOD5%%E=KLryYOzE4A7s1c3 z-e|O0%gI~OZveLsl|AgSI$Gr&I`yl6{#Nlnnmce%_{i`pjXBxmZE;!9 z7rc!MMbEflPcsr4|I$~O>I-EWr?XH1SXJqHpQN@{_6m8A#~l0NThi9d)OoErg`GjhTmmXm>qW<+!!}1k`*DDap1^E{SrzVo#u%5^%|TA zlI)E6W&5e*^(*kmaRy|{?a>iV7GKCQzCfcn4wnbxIP1ww;m;`I@k4v%r_q|<@}KIGj<`Ki@t6j>R!%!7Cl|$X-^--!`-L7T!AdR6Uu}D2?=F7) z!1%ht-M2Mp<@m_O<$-j=MQ!O|0E(w@vHOw&Hk56B!?pxSX@ao=r>$!wegKH0)oi__ z&s+FH8FHsjp<_u3MXcP=vh*0qyaSeGCy0l^xof}U_uEpUN}<|wAQ_JQ+NRT%CBX}f zg9QksgyXbI-8Oa|=E_%C80c93!*Wc1iho^RUQvDFGCqN^`ZW@68}$xk+d3^w@i8a- z2N@Qsu?a~r4~P$^V?`J;tI(6)5exSHvg6cERP8^m=w&z*GJJYd>o+4j=$umODqQeL zYTgc({YlTB8*N(Est!lyDkuaKWR@n>m&q=vQrWz*6V+JImT436r~PGmnTkMsO&G!d zaC*T@_Q6NeMNbA4GY8I4AE8#PdNyD}RB`OsODc~)3*o2xv}bYM@Zz0eLPpyyMdQU7 z&FLVnEPt+Ce za8=$jzfo=~RU3q5Bg?QfqEV+zU>AP5@Pyi(ysq_bySTcjFjz7-H~$szw)EmxkX5~- zGlzl#N$ID1GM?C`8VJ2+AA=gH$>0Xbubq0Qun(%x^eS(^2c%lBk`7wXVUHS!st1Eg zGbx@#vA4Wn;NYmi_&&;9(S94w+ck;mp+7tHfMwtyI)}Ob{wtvpsdDsH73&;w$uNsG zi#gfBKO1;CeqR^HaHhbSeC!L)?a#n_Dz1vKbWTGP&o9n<9AExEp zA}}BG%gwZvOq{B;#%_>Qv$IScjT^0tfVC?$v z{wC-1B!OxBC}Mq7^<@s7SV*ceG8B{C*soX**mRwpM9#y-_+KYxx0Iq4V%MO6gyuLli2CBN8nfW!GL5Z+o{xHlCReLo^#!O04SGI z(KvG&BJA(5jsLWLzMu%W zFN$~}6qBhElY0hX{SbvFr!6*-eE0VA-@^i|lFOQ3P0+R&=jVr-V`U69HE%Xq)6J4ax`7ECepaupl>UyYfl2l8`}MQ=)@25Wo27b zE~sI%`iD-bz&S*T$gK`f{&&z6tt*l3J|^ik&>+~B^5CB2Us4ZQ$FApLh{ z@W$@ch(^Z(8nyU$jf4^RS`%vkLUfiYu@nK6E=GQ+e|dpbzv56DVa>4n z&>j^;SVhJef&HzSvW|Kz@%GAB#JPX;q{m#FbItH~%X!`@k zQ47vQoN03svR+CwdUE$V{po#t+)%btY@zh7Y>r4;dmbZClgGoHe=PlI@^%X9*FiIw zmz!Mbki@X@du#5ugYLyW=hlQ0Um19=B5`<0x$kqpO@;)NyRSFHNKH5ULxPswvYm)X z1z(`OVRfN8(YINXMRFZJ@WkE|GoJCK zg;o||=S*F6wdHNTcHaqFRSUpBilS)*Tih=+v@#Q%TcqMwB$-v`3>4Bb|GLn$+m!5i zf@ArwtaOu7^8qJ;aVd-OCHdsSf@vE$KEh1d$C4SG{^MQz0rfNj)f_A$m)PkWSJE#( zYTq$q*W&WWMaO??RBbDXR>105QlD-RjL~R+nWN8?7&t3S^wvgwGEP*mD~(A#8a9_ zwW6JDQ|{MLm*#A8Rj!6&cIua|qK+vW9S@7tIp+AG@N${9?HoHh#<;sIXYI$16f#U|rBnr5Rny;*w5Q0ApVb|uN$M5A)_`WB=^7<@q$Bv;;&)zy zm)5|~mZ9XcE#UpNPg2*p?x|Wwi|hWA<$7lrKwFsG-k%ht*1@gWZ46iWS#BqvaW>?0 ze}}yF8?YmB&(Px(*5wfkK8r$}pZ8bSBOOhqj9^+S>%->ajq z$g3E$$02I9@P#o9lCkiE0MBaD?`>MQi^a3N-j|XMd$22u$jbkq9DFCk3v3t9VIIdB zY3@EnF&SpuS2@UWgRd`LtM+;Qc((U~VI4SReO`X|!nY7S$1#uDgXhdI|CNCqpHVr+62)4m((^?Y3Kkty+c)<&xVWP#KHdL?nc$H_ZI_ z3wwfZ2C>1BjL=-6tGQ`^>ORZQwANwz55>e-TdyMEv(HD;YfP*dwJjUe@voLRdu?AX zH4Wqn=jfb;fZk;3WhTu-v_YDdO=)J(jDu*AH7yNT^7Bg}U2}xn5OOClaXz2JQgZw~+&wWZ1E1l( zqSkq_mc(14D<;`;{*;*I;r{G)H$Aw(YNL%aVy1DiC+|BErn%OKvp_T|7TeP16_WE+ z_*O{R%3v(7=7C>CU?0vl%Zqh~#XBi%LojI|_Nstteea+nx8#_X2dz@Q?!QY(@&KC% zx?pfFQ)I<2uCGqCMOoSz=Z$gYONA{d#BUKta4x_C6}CF#K}rjc_$NOdylb1*!j4-} zb6k_1(YfF7RilcV5b3bf(9XrRW5f=iNbXE-svZ!d!6Kcu^BbLGf9jX|P@bPiql-l{ zeHPQvF$NANk#pPOK9^joq=wpO;2FJx9}8;Rc`>44E>NzlCuYBjiGr#|SvafHub|N! zuO>|3d!!7Ir#860=NHG@hbE>j|C8~H>#;!ik8&+piltr)Kq-fj$N{-ClHNvNjh~*v z=g*L3k7q&w*kwUq4LnhA zd5F-6%VxDSK;MmFGikzyLB*0OvNwLxDWb$5cygU7%anw2+|qQX;OgiXLtt)Kqs*-( zKX<0XIaPeVaixvaP<{320GuOaW9p!u06_V_+al;9uH<>b-TXd@g0#3d&dI{L8#g7uBh1>xH{WWDvKM& z^$vaXOZnCRR(N=oo;%$UZEr##K}Mtb0;~pocz=BB*E?7iBL*kAf+cwIZPWWwXWKqH zZ_HxbZf_)I!TvJP@vG_-qW9hq<7f9;)F1!FEb#PxS@jkOH;%Uh>dFB&9JBKaMY;881RO56qtXP85%a*%5+P{t)>)@hp zQd3IamSb|e-e=?1qmXaGY?AfWSuwn5`}dDo;i<-1Ahk>xR=wTY_?YAIwn6Zc6#0MO zHa-l1m#5fA*izLE4kU+ER6qj?Yf*4b$=h-a4+rxXkmSo%k?5az$STLKIwFI#(a%7Z zAFqEbE*zwj5g?GlB!xWF*%qH%#p-1{;RMT4#fe7axDwy6DE-)Ja-w4FfJ6r}^}bDq zkc8uRht8$ppcA7ao^MN=p899ZW$-gqv}{{&A4T1e_4~y^(bCTGrAG_WVCV$5te$~3u4`sHOb{AY#}S%G%LU>IP5S? zta+Y}T~@NBX)y4N1Hvh{)SxvCR|ixe$f=p8$49Ef#At#5eryk<+T-eubiuFiF;2Up z{4quin3gs>F~cO=zX9ue!XCDiS*7xAEWDl}9>8hmp+-SW?eXeB^6SiqnX222$*TAM zgrG-wP%yo+6yemst~JS7w~b-If}W(L?=V`MRnXC&A0cekGRnlrW_`;=Q~7 z!V#Ds;ygR|MUV<(768|Rj0NV+U9}@+|M60=uERu9r|%k!;=z@-v-XQGmx1>#EQ#-- zt7)={`^m81=EyNye_ow*^9I3vC{}?{2xLi`GRZ%A*9r?+cgT%j}I{JDUe(olAqM}8a4D@2`=TAoV!gb5u?j5go; zOxErEZD?Ae9PE z$bOQ4QPT_nSuIwU-Q~fC%bu4ddgS4dl$fdE)`+CLTi@sXoQO_k$xBJRh zqL$yhle*4WB2UjnoO(_KNkU(^JG*dRvjnzefpEBr4u z5gG;k5h==AeFZefj^py!8?5`WPAl>q(Cakn3u%biuB)mq7@sWN)Ic>LsK!6y(@L9f zj2zx0CyG%{s_p~y)(A;uBcw@N+6!mFyl!>TVpvIk>~HhDhz2lHpzr$`YpU54kHco9 zMx--+?Eaz=Q>QB@cM=5{`s5f(iG%&MNpLGCKey*p+wrNhqH)?%pvuLin!t4AaMV@) zn?m*qP6drr7QKDAX6&@eILS|~QhUh)xbmvJn)T%Ek%s{$p_|bfGL>$}6wPhj0GF7)&z$aw4@`>=8LSL1Lq7qKUl@m{*KGF@r+C#XZYxPMjGf}b}k6YW%-(=SaKDJ7NW%;x^gPL4`X!i zAXDjFL#K^Pof>AvK#tL_uROV!T;5jSz0?+xcot!q%FjJm2I|xfsTfXTaXOp{^%ZNN zdrZPkQNY2Sn5u(fkyugx^DWY>75>~6uG`=eo9TjW{~UuXwBVijZKG4U zz=%xmipk1b2h%s(i^XvQVZ2HXa!vVe<_THE)<}&aA2vu19M%lgYWgbcHj1q&%JIiY zI>Ql}|J?IGcoSb!HyP~20F>Mq^{0uMuAi6Pz=K$+!CrFP|X@q{+m z-oHhzL7u7dLUgxTic=nTn0@fRO<3meop|7gME@x<%VlTmmF%5pLRfXAPQ&Eu9}~q? z#{Gh|dU>bajiqvauUFpNQq}Qoz?mkC*RIdGSOn;a__wmnGD-utQkrnD1*XELq~;$r z*)}icSpTRVrD}V-Jpc`}b-=q5;0P3j>eNy67F0kuQYx-zQJK`K5n`Q2i*YR3NM{MK zR`i>MhiID);1C~!sH3M0AC-oZ*nm~nw!L8reT8Z5)i?7dPS6p3B;HeTIzKHSq0G+j zC}M{N0zxx2;dw{_P7$8l#$qI5W^%yoJ)?NY&KIAPx3i$1Xc6^dQ(Vfs)MLCW7hg6A z(fnZwmTe@{*t=0SstMk({>I)HeQ$oqB^$3WO7oSEQK4$Q>h|(5w)1^+r20Nzh*jz# z*I;>5V-3BkW@We|P>gj{o&VOJM{hLIla*;;GLk6sk*PIaK$FlQnz-D==T>u*My<@l zc+`1=JVmwPwQPh|#YJyaEyB2w49+qY%(H<48I@^S3nhsQ!kEi;C6E!h{2o44#sA#V zg#Z3Srhw=@Ys~zxvrA=8}8#5ScNQj#j*bl>zSm9C;g z6KkJ(bCEDB8Qnrf+i@oh8FoefUh29>y%8;Do8fu&b2G6^%7s)DNEVG&({;hA%~==1k!zd_hW~o571Nfux?H&UaE+E zFvZ8i`3as3|CkE<5dT1e|JR7II(tTUOA-JxlL9@~>7Ls$b2+~JH9lKdoW56CpW0qL zv2A|8Ch==yY%*1PU(yR_y5rpXY^q!C40694fgVecA!%zt7yI{Ybm-Mdbo<9et6t-j|^Qsi=?_%CoHD#K^pBp`cWZB0UFc#1 zuK`wo{k;T9%oX2@h}SI%sixkZ-;>LvE(b>&mj$zpQvuUXEG)yvAUF+CTQWr?ou*T)2J?mm0H^#UeG zG&WstUv>|$YsL!^zu_S9U}Qq#!t?Mr7!Fzt%~P`aZmEvHzvJ0|%Yj)v84NsL9~gY# z>OY#_S9GU$J32AYsQP4DxVJ;Tr6~twj(aPNL*|z4xsMj`>b>uE=x%YQ=Du9|=U za;f~9o>uoL*gqOK@A%Z8Gnc2^mz%V=X$@yqS$k7iE-ke7aUOt6et#h2af41Bf8Qg5 zTbvmH+3;i7^db+&DEjE1Np%~^*ji9w^+Y^KCpWoM=_M+T1^h@Hf&AN3ec4z4OjQ;y z0UAv{w`K_a$LH+pP%rv%hGK9{M93sey$j3p^Yfjz@M_eW@wKr^vfj6NZr}qO9dSS! ze^8ls+5<-BM}V43;m+-*7rkuK&w>7Yyu1aO**ZmUG}6IbBW!H%CE?>xVxYfr3J;k# ztWZL-NagtETbvMlQC$Hfv-C^D(mvv!Uykke@X)##NQJQ2th$mh-3}770kR*+nwTm;SjEa5u^%vuig;dkmhbJv8$;aDhQ0JS*X-D6;~U^ge49@AGvQ@3jWB3 zJAmk2S6ttf@QHwIK(uqaf^AjI-}+}`K!cSp(->`%7mTxbrNv$`m4D{>S5E2o3W#ZE zPtB^NxmNC(4PG<^C5622o>XjnhK)4Jq}M-)>fGR2d%v+ zYsG87KiGwv^57IOYRRFWFE3*R^XK@swIRP_uG(by2BTq>&M;qrRYU-f56|z<0Fn~V zrl%6c0aol^%N87s7kzxNB#}!Qr#So(H+Qs8Ws{O1Cb5Gm&CmewgNU59H{y_nu;E~% zp#0G#mQtY`XEs)`#pF|DNvS46LN+2#o3-C^?Kt3gz(+vIM~Q}&l~eDtM`?lm>8uMu zj++gtJ_-)&|BbT;^cioTnB%$Q#XA)z!O?p0ngs73Xdavq{Bl=Bqkf~4iCwZnEqzD=&kAdp_a?2&!+QmR@b%@f%7IWk^udq%OCev2;Jy+7wPIZ z`0db#=T~MKC5IR3T=|>h`aiG}D-3`<`g^DLo7KpypSv1?a`94=;>-MmeK`+Wv%v2f za^A9W(0RwGSp}+a0@bx!kTtmWT^vp<%3P~K6xXysG{F!omU;x*SJJRtMRp@W_0{yXx49>LXs% zH#k26!b>q#K(e_G%)#ky|Gj37{6C!hUB-S+vo7|+m@y|z`gT(D1z)owGvL~9eMfY* zG4?GB3@l_QFJH9g#+DLmu!1cT(^bSP(2p^%Bh(}P2H4Lah1qwk-gR~dvrg|g4~lE) z(L$sU!}|Y7Js^Y)0F;C^A2%ncDDTA`Wab9WQ8Yl)OfmT)!X8}FD>Y&iv=Dp4!Rwy5 z{f4s2;kq{VFfs&WJCCYDof}pdJ&rgpPQaZOqibesZ4=t}@%1CnDMDQRiA_T3O2kQ| zft{;+%D&dx_ALS$JXUuLn7dQh&O7J6+PiStymN~iE2Ht6cn%&BHAHy;ZT*ad%l;?wNxi%N0##sPUOisDo)NwW_JfsXNtASS7ZeBZw zKY?`~h52+DauH}Z9MV3oKt)Y<9V;B6s z)D*W^Sp2uAeEea=glHFyJL~%7LgQtmgtf4}d}m3`(dPAHrhd-xELl7Ra7MVzBLD&X z)z^?Q4!QmRumBale&~<4uf7k8oalVc#0&QBmXtR=%7poc{N(RZ>ArQ+LPP#unExEV zQjl4B5)c1|AsN5u*9EK2VJB+Zbv`kb&xmL>L4#=@c8$kAQcN%EPL?x90!bbNLm5oj zcUO~H33OyZ73?@UGbR53wI$;nGA$C%yAK!?lFQKo|IMEC&Iy`kQGemBI_B zl@nK(QQ5&9_VRBP(x?N5ONl0b_HG&$k9uu_?RkS1Ph3$3L_zZj8r`PCJgYN2^F(uB zhhsNg+anHDtRbjC>xQ3!$eZUk*q+D-^Ikx^4kw(B`5^+vCExkIx3lvQgnQ!aVP@<* z)$rva_bz>By|Vm#!?}AD6m7*Oj6diF4Eo}+82WB#p(MY*3DEv1;(vY~E~md1-=G)f-#TfaEs-{5Id@JJ!vyvIv)qz2Xt3z#r%!HIUbkm_xV(xc4)nysD|IGqK>sr~ z2$zkM^V_cuyGd zd!9L8$d^lm%cKn}YNyE(P#`Ke?$V~mTTf(8jtcb;XAdk0N=LxJsUa|H2-{eot$cAn z%#A!P^#P#MO(T{8rz1l{LnyrknSS-ql|S0cH<@t@r?p8YQ~d{ys#;pIDk_)|g%b9T zcTy_&k!W>|&h)fh&=C1fPG?v;=F6cxQvZSia%a7`F0`PaJ9u$yGGsZ>!-svYwWoSwY8NucA^SQy6 z>J1bwE6tbg*I*adLw68(WWF2&Sw)8^L>Eg?)}%NKcw$?lJaca=<5RoUlr=PlGP$hY z*;-jyeSN$+acZPUP}EuZvb-ESe$B2(Xlib$k;DEZEK7MD@+Y7 zH2jB{naE4O_`|3a0`EwIIqVvEc4H;3bhuxZ+K{ghMlS7LPqifjN!Z&BaZ>WQm=a4k zV3R6;7t_}#K^8{?I{!^}Oi)nK27|@|dhPQeag|fr36N!V<#5fI-L}iE2IaTnZ=$`6 z1%x+5!*^s9e_f$EZhb>s#x>q_?D&3TqLygTHzG=!(`SnUA_o$vLYE>Gy5H?i7W=kP zxJvua4(%K|W2U17kW8_>X8xP?@5OR1{1Bzt>6)M5)0^6oGOUTRx{KA#!&$Z)o(ff3 ztiqqkp2ImRk9P|4OEZfZ4j8%BRdy~-wCn8)1gV)I@XwVA8&+SCr6ZSRLy`aPs&@D9 zwTK4l=D5!(mZ&OCCTW|#ciqt>3rp4$nOuk`o?;NivN31PP&s@4=FPfa`_bz81ktb+ z;^FrSFzQkE>f2|e&ui%`JvXx(4$nAyzZ_*>9m#`bhtF=6cv03`>^4xUr2o0|$5Zg0 zSd_)!uMFLCBgT=o9bJQBG zy(*b%YypcfhYpJQ>!VAKpNR9xTvnJEK^>F&6(9%)QlII7>uL> zHIU7dIb>gJi4X6ZMNBN@KqxKP8T~eAVE89aPPZ(n&+wzNkK%f1o(R!J(gG-wW#i*Y z1OhTLUSXIsMFPV8{r&H~y&_Z#$rQRiLyWZ_d>&g=@bLdw$Kd9HArJzwKXNSUnEetX6i1y#HL4rYALG^Zk3`gv!VylZ_8=A#Ld2bWD~KPEUmN#3>qve zG95R-!Q}_mlajS!9UOEMo}auFy^&OEKwDPE9AH;RKiYu5PU3fpnxWb z_%uGdaSV`ww$yn5UP;Lre(|BR>)o>uqLVzWlb^+GR&D{EBsN?Y<`HHA>IMm%xPL+E zO9u#n%}>_f@**fFhSM!tk8OT=X?Q@u;LCGfrx&g!S5Tv^{>C-Ct^;uzwk+L;;B@`A zwl=3O*nggN2Lkhgka*f};$GyNvcaL-EYpO?C3RP*mSdJ4T^1sP)kepV99fNEHJ>tj zvo`3U4=scsm&6^|j*Lar!!l=uhK?(bsrh>D9kg6ad=9g!UmPEUtyoQhhp ziMZb`omvx-yuI)CrjYD~(y58mtJ_v-_idPkokfu61=%~wJ~wU1HzcRU+uK%MYt8m(ycfWyiY&EQJmGfC zK^uKUaxX1Q*n7;SJw}^)@UjHr^Ml$ti2HI}27~gmt{CDc;qCNVh3AsF(1x~;$Vogz zTb4Kka#4X>aXz0x_LlPIFU}il!zlsH_YV zQIVFW5R!kyi$bX%K%jwLIMc2f&e8uKGyin4E=b3&%SCRO*MXrosROVposm~z zvHAAfx^cEX$~@1IJlo~q`W+9F)^4(AyJe(*1&hHLNpqM7`4R_Ev>)t0h+admrJ~$7 zbMUlMJE9lb4Jajn$UT7ePz)8kuaaZP`kh{{sO4?HE03iHuKs-Jn(c7zPVbK6Q2+Px zA@GZudp5~a*%Qj4#9}7{$$XH&M$93ouHz&*HC5cgT49$+SxU{GKS#H7PX0B}cQxnD z2cfd~q+GRDc#7b8)}j1>LV6&%(1k>a-5OfQTB%^Z34jL7?W8adR*2Yk4F;dXPM3J*r^Cl?{kBvP2HlVj%@1gi*F4*Z&yc zhpx#=in<(e-Q_5kkoOa4N4hCTwfhMpmmTr}6zOhiPuqj`;yG6)*MMoA`_a0?h7N@E z0m`K%@-Pa-sNfoENn<&%^i;{1)wzBgyb=?+$O1#>3+MT73e(pDy(%{Q42g_Eut{!sP0I_xTZVixj0=;M&U61I3%{z1@ zqBkV+e9dgtp`2^fC8sA!{p{EHBZ}(S;E{yu`BdhjH;f z`=QvA-q_h)s%26sm6SykEp>oTLhE?bF&0}0nCwZb;9yHp3kYNpF-dBqzD?s0d`kan z6CJY&(PRC=MXa!(6|eIh=8U2}==qQIBO7*#Ih|xgRl1`l{a`FnF8@8U@A}J?g`a^j zq;xKeJv&R05E8jKv&csYDjxxM#xQBz=K{+Wn}KrHA7j_iyJe;j?(7Lu1A#|0W&$Tt z$_4+`X%H9-QN>EG>)6NCIcsOwPJi@7NvZ0Ra|!Z}RA*Tr!kaJAQ5cfKMaDItVuk$c zH+MG}qH5up0?#aAV;SA@hihQQncVVss7ot}eq7bTyoJxxm6+q0J|O)N`@YgAN{`3Z z<-wNCimRlz8Tep|kEd`@h=zc}%K1oW&$N$?CpMmmA8*h02n`-^^BzuTS5@`;ibOnu zr@UJ;%?M&^ISuw=dmaQ)QBe=j@jY|$eD5tB?K+~rzFr~pte$NyPkCo3Rl8@sKD`tP zt~AE$oWAM^`+(SPejGjhk?#?GF4}1nxpjIuD^GLt`@^x?vdiAj;u}}v`zo~@N4#D0 zdT23u-)nFM%$zTP(Vk_wUtS>H*}3uMt`X_m#`B4;S`l<|^2G<1xvoiYqR3Y6qsUm;8Y|`Zuu8`d zR-N$rwF1BdHEmf916&Deh6RJx@U+_pdWPE>l6_j<--cg)iZ}LYeYZ3;L|?Ku<(sDD zPbffurtB5v6(wWs-8`kdtN%Y#eFapNYqvEaNP{3s2#6@%-6$X+U7M6vkWF`obfY5D zEwMM<(kWdMo9>eCuK(ej@4NT@4kX54Fy8lxwdR_0g;%}Xu|j4By+jW|EH=}!g>BvJ z3cmx!1Bj)HP*on@d6&~9KQUGmwAaEgePu1@`t8cZgj%dtH|+BW*LBhW)~{_=Fm@^M+F{*&6cbX+oS zJ_;K7@1I_V!RY}2(56fgtxT!Sy6a_Ayzwi|`3+}blnqBQS$Ak{#eu4+=sdP$sZu#o z%hgG_EZ?bd!s~yw>5-m0?jg#pS)urQodks5vQ8<+gN^|R0NNZQq- zxV!ndywa0D70bHUD?_xD=Sxp7q;K$r4+Ez!#1VI;t6}*yYv1TxdmM17^ws3vY3pC7 zF+gw8>i0y}54&t$yubSsZMV_tuusCmeRGX1e14sKzQ)IUINsa)cj|;-XO-_LAxTW} z?g-y@?H5`_bd$*9y4*jYKjZ?QK}}+_$d~k8^tzR}*{@q}C;G0-A$kN?zO#*OskUBHGi_bVCHiTmYHspG zUN($R878VH?YQ|DC~dEoALzb_%nH}?EzO&1Gt?Hty_=9dxfFljto8$u)a@xczt613 zBO0SV!tE&XM10rH8J{;PQu9O;_|dpt;^OBgw-@56K8W{bh+q+@Fyl zP^mS&?2Vh$uh>os;N*)*#rLSJpaa|~k+Y*hr|1VWTSE*H`0~NU{?xYQT!|g$umU$> z_Rn7=o#{c8kkBBBU+-BHZ-OVPZK$lQtR^}y={GF)hl%_r$hU3p+6^40t;yk>mwS)0 zJYO~!F`Ot~H^&%OC8TU%jY3{EMod%c=Bv>WSJy$E$u*U-p>Gwylqd2k7Dir+3-7=VE$4MSdGXWm}; za*c-&g#MzW!2zD;-N^DYQ6ptFEakphHlKuPi`nK^zs7H#?oF#i-?dRKhB+MB;p@xy zZ=RJ59Xb?!^I_$QOY!d%X|J0rPt2cbR>oHDk#0J4x?Nf$RQDxLszHfd=;n=LZu%0& z!gio>CX$>c7O9l}FG6@x=t#8!T9Z*=^Ozkzv-6?!V6F;E5Q$SIyXqX24;)ytD{MKH zPhq;4FzYc9q`<|Apptr<_2>M=ke#H-`(hRCde_DO_!M2>?)sVc&6a2s1$K_0q^$GR z-)OC+v3xiML`7LWb`y%fx>_S#ou8Ck{~iSu{f{j%96mJb^bMS-si`SIYJ%wKpEjvk zTY`$YT!>9@Y`0FnrKJUD=7G`d_6`o+_H`=i#KE(Q{Dd9Lm5&5@LvkiVq<9<^Xb2+- zaL_p%Q;LdMU;Lp5;TsMv?(eCW_{X3p0caJ-&BOC&B<3P`+mvavTN#*0tBpH-m>$(u z_A~swVA54|_rTPB5q21&8X&^cDkYoP6|Hq35!hdGDIEB6sKsEa@!@_yw7+_>U#Vo> z(q`Xtr0sYjP*F*#s1+W2axtw8X$S7UT8yiq(8K80rDMc6quv*2iW?S9Y%XGf8xlg6 zFS;X(p*ufv$Dd?9-Mz+V6Z#Mqy@rSqdJ55XCXJdGwwJ0pR^Zul1Z323nM>5Wd#g(1 zB88S$J?FmleJ$O4U1)w0mYZs9Yx@QDA>Mu2MgaHwc+u~RLzoJEH_WA9bm8K+}0@) zlalBf(92adASM}`v6@fHO6dKBdI!n}qaK*m7ImU(>y4XRSw#kSf0g+#yq*@m=^b*D z>09Wut)xUtSOSP0t|F|Iu#Lpk#CP$vu%_=+Z`NgIUDJ#;M^}0!_~Ed2(_8|ie0mmIOyyXi=8Ws&hbt^_2-m1 zwAII6+||5QMcI&m-9o`-olDy4ZL9wfe!nuyljfV!<1&IxvAjl397*rT2n*m z1KnvKhqFN+(T3jt736+Ce*74;u(1LO_6&i!?8Cd`EB2Fan=q}dKMfwz!AYUSSv3qy zGBGwuvauWLuYz?GieAO|62C4Uf;G@50V#xjhfBA?stPkz5!N~i1V>9U`qio>3C|@g zI-f2mb#=9G{bF%9+)^L;b?+ER71uiK1HZ+^c{cjp9Q#97YjYm^#O?Ze1eTHlf?(`} zel>cw#duXzt<6%wD658d!H?yq9j&9%2KlS3J_S}*z{eLm?+BadUiQ?Fj11o1G^K65 z0(x-0v($sUkw>YCjpx7FRJFAe?5B4?F%-+X3`_Ive3SUr+qfl>+a}?|5k=AC>dNnM zEZG)g*W8pMLjpd$vIZI}=ywpkjh_ww5s`U5-kc)rOgq{eO5~QTw$etz-_d9w)=3q# zkVESE^1p~LCz|xh$J%0^4~bn~bUp6d34%)YhP>p_3>Ox(1IRRE)*>RBZ-xw4UYBRjxZuD>E@D(ThSiE5j@>k{} zND1j#BR&s~Hq&SzyD~94Mh}}9;b7l!P%7+u(v{!}{>-S$@lpETgU!v+Bb93Fov^`o zeDiAEdzA;4vr}(Z`cX9IN<*hwB}R)c2$SaP11x?QYleG=4=GdOEI`*^IS$OqFo zm30Moe@Wi9<3U~wF;<}KV&GHP`K!5y?NhTePUCtEW^sMYk*TvuHLLl9_7g{}ySE)m z7nl9nd9OEk(iTR<8vSD%2OSQ?c9wn*8ho}m*RNXj>AU2KJ~%iM{^WBku}LKcddu?v{4N7}t8S;TP>*;|_r??mlfQ|G_yqwNq^%1TMEvorIce>+LM=FCKNy+mZEk zIG81Fbbg0VeWKN(>Xa9w-P+)CbNUWSZk^d!lqE}qBgdew) z!B9xcRTdr?*lIOi7oK~L%HKus zr+Ng4fe0V>OtgIsRm^Y%O$bx7nK*(Xb5ky#r1mVs?P=zZ*w|7qkM#TuKoc-Xq`O`X za5-iVRzXV|9_#vpjvD>W`(CD zqhPz$wJ-IU++g)Zpof zRB_O-kgXT?J{mT+nNO1K6^UyfBubMOd|xVns8`PqRnJYN-aI(%Mb=Wk#6sE(FU2oa z4UAR$dhOa#mI23j{_#~ot&r0zcsGusNue9vnRm$hCf2zem$6oVeqAXri^xFO~cHs9@gFY~dQNqGv>-a%l8%}d-tb{W>5}uUoc}8+pvDn?K z;4RL*5+y>s=FzKL2$*im8n;HzucYc(0|_B?6+zwX`AVJNgxPo?U!aAGfybYrZ;!Ct z*``sOtVgk-n=`aLMmF4pe0!By?w>oghQ zjhrco5}_MJRVvs#PF#3XgiDzTfOK|Ks3Fd?iC1%|~>H7Jx zm_R&)YfhUg-FoKNBVQZOW%8^luN4|9wt zkl#A%?Y!I%F7}2$Zd>6;Bo;!gwyF|*qtHJTIVLW2DIzt zRQ%VgcBlN(X`SwU8%0tIAM5u=8Qsks`=FyiLCJrqH7wI$C#q@=Qm+Idj;Wm+Ds_5P6k)2_S1J0MGCzC7&QeY5Rs8!D&Jo zf9ttDJ)fFjlKWHj_Os1l8ddynwf{jq;(Zy8#6Q^um3i0-%L4}X7yg?I5K#Cz(MjxR z!X%}Qtg*vv#~L>(vGB5HlhF5Ecq~zMFVEyva6xy=Uw{KWrcn>vekSz%WE>k!8dtE< z=VNJ`_gQRaEaRb5ayFCLm{=bwMgYA_#Xx>u)J2#)Kdk0vV|2%Zjxe=jJl2$z@g@4g zTDAZcPt5Z%#4%%4@SfbKjU+%^^3U`W*F2nboL1y*a>GtiDktE9^y(+L{NpcZ|4%YP z0RL8`=I_KJG}}X7E_pf8wR?l-)qjzQxG5|+Qt$W0Cn1i|kw5@F9SXQBD}2Du^Bbj= zqI9Zr7RsVcj2iUBzSU!3QtITScmsuR&U6Rl9`FYkluaIw*>TMY^*l0vm{3EbDBi-*53$RZ*T4$K2nVS?^ck%^92w4UpL>*uNr95 z9h+xTc~ME(R$nnN%H5`J@daMNcz^|&w$>F^wxY*3Rwp^QDR{Hg;SmP(KLHpLN9>9% zmw=2O@oA}f`uAxpJQebu)cpfGqMwNGuF{aj*3nkA7!@Oe3;UOI!{Y_4ya~mBfFlEX z0ipQl$rkoxRiWn$bo4-6ece`jkJ7k$&`HSP-$k^1^?w(UAckGzcLr%hPGa5E5JAMl z90a1o)XC(Kqc9`Ca@D3@(D9d`lLX{XMNqDW2^uWvQf_kF!YtasP!$<^crdC#oc-zs zqfq_meJ+i#g4W=^gO1+nyNk;ry=gL^hCYHZ97Qhkt)zD$IzIMjI89FCXV$+DlBAc; zl5hc=T%cV}yI8d|T`kwEfA45;F_r&I=>i8GF9q`}Ujb<`+WpVR$Z~YftUh7T&e*6o z*D{5uSSx#|@SY6ZlDY}gZY7UiS?hJB9wPIaRilu@=NO!Oa8iJ% zIm}_cy*Qd>s7@*_<&osE8GI>2!6wPW)<4~UV@e~bfT#3v4hGCe`JZ}hzE;F-q$e;vFiIfEGUU%8`wMs^%!qTqGqu0@dTy;`pgGeIi_ zfDC>B4qkl2&gTHee(?D_mjs=K1msagvxJahW|79ofJ{o>!PMn{82b+t@;eNu61s(7}k-(t_+ENCHEs8zWJU-8-scPObqG= zfjdfx#dr~Ba0ZCamTR|)l0L^`QcIeGu2x!L)?tv*hwE&5EHFqyT~l*#vi2#PzOdQ) z6D}oP_sREcZ~7!Ihv7B)e(~s2WfxcLcT57Ew4P~qe+M!rRlqtj$R{MIeBClZ~!@=QszZ~rRU<qx0Az*{P&3Ww&HAAkcY+ zXGi|@$H;eN1dqFHcJ$B3dk`LieqqS`r+5}kIR7z&yiG1 zOPLPP)R5YPywE0s5>}(6sZrMsv;u^znhZrAt!BOsssL9ySH5P9gpgHb2QZ{l(8xqp zn`>`iAc-24AT3xW)ilk^d~BT&ZKa#lQBMg&1sSkrl+h2tq!l>4qPm(0FZiOJPLyM}G;#>3$$QhP z@#63~9q#MT!)3;er@8ATwe0>_8Y0bHO56wJW*i3fl_8nOTzg!Eu2=L1UZTxCXL?o#3t)Ko~ji&^G(NB0<1GWHs2C5?H(v z-qU^)Zn6#U?Uo@f83;it}lQc(cf5mDCbMtzF{#3Nrxs%al;Sp^f8DqNPn=D zrgh;2`DUCK24$dF-xeB?hd(tfUrwTu_cElBZ&R~5xbQNvf6B6e9p@fGxwRyHC8T{v zg>`ojCs#AUGq98?QE!)?HveS(NWlM(*h?}pR0*s(W}db*DqMHL%ZV{=neL%;4{Yjo z&x7OM!e`cJN8M+7z9Xzn&t3pb<)3gJ>_I;)V$umHPf4ljW1{jb)w!%(G&hO?>r$*b zi4l(>lyt+NI}Dnsd}~EVzkAuts?uihOgS>#((;RB-LK8VB%`U6e6F#iG_k3~QXM_G zM#$532DlJpAi8pVNev@78Yw`}6LQ`*?2MvdsGfD-Dx3lTmnlKgEFoSnDF&(V{v^3_ zkPkt*6pW-J?Gp(P4BLMW(Q|dTOH%3M$uPgqeUy=Q zrsiZvx!5K$infqU9PYND)LYX`%hdZxoYz+L4xI@+n99`Cc>!2^Zxefiyv`ubPt3!;41{m*68Aj`)f+!A>&#nyXneUP3`X z#K5WTq8CdGvS9N0F%*+}?Q2mZ_3deC+%MxvaZ#sbwAaQb=0;H-QJVDkV8w3DT#-Xs zHRQw5s+Tdk)QDcj%rE>-m zDqCBmAWl7hw(!&!Kw(TDTFU;yNUF9)0UL2H6_Dmeg!1zqOt{hvU?9#a-5S79@72?d zFW2iGIQ!px-cS<(?{&DY95T{XP`$5!rvkvJIP>dB$rnJ)Qh=09cHAkH%cyq_nQ*~X zxk#|yhN6g8Q&{BcEB(L~BEWeY`coiyse7Gf{NZ`iO<^)4^U4U7ek&odd(iaH?+~{2 zX{xTaxvdO`BbC(2`L^lm54l1wK0@TQ9V)`XX2A1*99 zJcRLN>w}zB^O+mUCUXW4LG+0&oc1=gtpe>Mx4Ei9;agAZX$?_ENge~#turLu>bW?A zOwmMLa(opgn%SAv;^^SKujGgfmO30j0Y%pBf~kN-oF2k7i?DcuKIJmtlREtVl!~it z?JVCUloqk50c?0^rULdUx$ku)dJYk$5;ZR>4`HaUQ92`56gM(doeSfwBlqlUNG$iP z_+w8|I&G{6S8X^XUviO1&aYksd?rjoT@TOzT>=>Me7~(4e#Ua=7x$@^)BsKf39SC$ zUH3=N#jhfk7pqji?BABEr(sdIbLSU}-Apf|zxn`VSq_Cn3N*|XQ`&!uBsK}0KTuj6 z3Up#=o@7G~(wR&tzK|3Qyv<8|mQ!S4zz?sqw8z%A_y~7v0xCdNkk)w(SYuFMLV&GC zM^<1;_EV>A1f&BUz$ZSeapcfQ&H_jNqhrACEIc^3jks2qOz0wxLgb|niaD;z=YXN9 z58i3-sc}jPc4?IxfZuc=OmA)X zSBuFpm&_`~8qFvP!ul)4%shqz`Z5gR`pa-TW0pQ?%qU6CK_M>tv0_(PobZC4g zE~=Gh9DsUVW#{|Fc)g+5bHdX5J=R|p3fzz&ZWM%FKHN_)l;zX$V+2WqO^7M(wg4+u z3YOmK#8A)|QzXI9Z%{30j3E$ZQa5I>X7ktGaEJ4aB7aMdTdOLOyQ=$j1?P8YV>I#5 z(zMW$s9f$Ar;ozoIgF)_nIZj|RSpV5eQ`6-A@UC)KZjOipy675PiV#a6g*RzIQZ{9 ztsU>e>Hj1?R|%R-gZdM|k|Ak9mP||_9ADh>py;VEadit<=+yEv4_26WWt57Mp^xR7 z*e-XQ+Vj$egA_xbzNq0uQAvff`lRuGt9x?-MjuXIlY>YJu#+{suJn|djSB+NrqXYw z2q3L$c7hzJDn}v$vA(08RC4r;0r83sPtp}NEYaaXnG*t&PnTQ=2{Jxi{-APBYJGR7 zJVlx(t4Qr)FgswAy0y%N-_)_E`QeekTyL=;4%UEPYof!>L{OR5qOYdz^yHz~%>(?i z{Y1rjPRPkeyC`h$>B)YdTg1XrcJ?TajfGow!rqrigyT0sy~UnbY;EiEMXkT><~Rqv z22?M$$yZ>g2qZ{G-cV!=65F=9(K~70{9=8X1jj>QR%qav`>{NlwpT9RsLd%p72JX}`Z1SBT>%oA z$SB+&a37E+b$!>lv@T%GS?Vm#ozYNRQuy?-9^TFe<+VH>_!}UuE`y^~Snvkg+q7eJ zloSX`6|mU}Cz7b4tG2J;q?uAh266k|-}cq}D#09dSICBB+i)q0svABwwdpVj&7Ab; zp5gf$E!%pC&7x*-){l2IePJ9 z0?7v1WzN>`(%_`@2$Dix%=mGKD(Wb}4MUT%dcNLQL~L)7ZV(NY*Kf3%IYB%2JNUDhlEHRjnuG95V#}sh2DDzs32AeFH#es}iBou% zTe-&yEx4=wgYG3@1xBp7@)baqPU*g5gaC{PS0#?khiRv_Z~a1KEV>O%dA`yQFlurD z<`-d7{+#3_A~xR3;ITlwe4s&?8kWHOXHykZCXgVP=Krw0(jB{vSJqGqi;H(z(d0#q z-%EJCEp*?iC_he_^_W}w?Q{DH-HZbRM^aftu}oFnLn`odxV1NZcm_D-@ zn4!X}5ksEIqg3MN2?$)HTrUHf(t_EZuauuJa==ECkN`#ZoPx4Y%k&3KqL74CBNe%v zc21ul>Ws&us|^M+hc#)hwYH-tRdhJ7g!|w30s)=SS_w}{ZHH^EMprHEpD=vgZf6P+ zf%w$O3j~f=`jOD8qd+ZXn*m9*U%3Yc%ZreI=PeS-hMMz%MLiPH($tLGze#v`@$@Mt zNYj+|^18t(l)>OoIVwT{^$}6dTl84<&Ob$#uh38=-mBLv{O6_5m5D`u{Up|?;(1bh)&4UrAiCY_KrIfGE*D!wts?-WnN?U*cc^J-@Gfo+ za|tkm7%^c@&)5CkSe@H-zh(1+mW8QU0TOeU-BBEsK92)7xqsa+->bQ;-;lLuxq&6% zdI_*LT^|C*;Xh29d?=4$Wl+8vrbfRqk6t=dKZ-aHgyP0rtTtMF%ds#RcwHlylPLV; zv@Lir_dda;-$LVCjtMS9%P`8XM~&6BG;`lv$~dhybU~ryr{1~@c*wmTX}+Co>q;he zwmG`ai~6a&Y}|d?l^R|%2n24U8+U&1>D73sawIbTO;A^|*OBT<2u8V^>0X<)1`~g17a`mkOhKZVbo_In3 zo@K?kLTW6u>Yy^n2cgjfXe3ZZh60&{A%yTC(;auXi_d635ZceJ0OFbi&r1K3n-M3|MJl&`cZHyGHC67{%?2&tix2ik zb-oJfjm|=^OX_BeO#a{4^y6t z4m@3-kLu_DO8_%-v@w;-f-^~0tW42ZPwQ%{9`A0ouRH};KeEs9a2qzk#+?8$Ra~Kqe^i-LwH;&$+OD- z0!beK5x`T+o{Of4F_8qwY{#4SnjJORE9^h-uc>VA@(>pvEl&!_0cTAVQ&|l|TJ`Qp z(g?Lu+>A)NqOlnC6PX%MQ_ zgQxV+?1U@!H#-6vlOP`hY`Nh-}7tXd~@ArOXRLpN<0W6udPP_mYDLo4cdsT1G!p z_P_<;=6*nws%D{OWksZ;soA+3^*qC)x}#b*|Ho67&9%Ax*#oPh;PKA&(*ZL90qmvm zt4sGa+gG`12jXg6^sz&Zm+!C*sMo|Wm04OFpJqy~Mu8zLB_ zeJDSy_*Wo5AgHXW;++c`BdeFZ2WXU_0)YyDqK$aJu$kq+>WD*<2X&;Z>?6|38f$vt z4!f0=^qRePZmeSqEFh;`0!1CX+H{J`+{IaMoE+p;^O?^9R#SnP@S3yF^MKBextD&E z7hf1{D*~^4T;rc^*SxQ54;5rGyH8u$*x7l-#)j{kB^_o#IO-@`{|hRmw@q&Lo> zuV!6eT;-2(SlE+gXR}3Tvv;mg6;K7(&o|!((bRiuZEbz+d?a$%L2jcAW)}gq;EjR7 z{IjCtzPOke2{*TkfZZ&5EE}Nn{|isd+LZ?>gq&@`I9J6D5;{dRSNpR!r+4RS+cOUF zY`0f7$Xf5?6?T5hxh`FxB3+l=T8UmQ#?psz4m`reYdoi&7u#MO;8`!RKc)|~3%q>j zcBCFqucpFHdttnRoa&YtI?o?|u~hi>ab&e6FhXdF)+M(Oo7$*w%CDxYmnwRTL+-Z> za8tC(IH>%#?@oC*YBBc$*I z;v68sxI#9;&15#X)u`_oPL9ReA2Oi}og-E7=yQ$l>DpGWlvwSCYh~}48hC7T)`_g% z6fSOn%y*Au)aI`D>Q^QsccmNmTBjho)U36}Yz|zKhsn8+#S1V^rPKLKSC;dQUZXdC zvH@E^$s}(p|HMdVAj9`0eYA)L1u!ncI&dy|9u`tKFG&o1p zF{o+xA~2OdGX&<%Uk-|R?keS9bmQN}f*}I_bQ<6H4>Rz1XHKm}oo55N>o4#M=`PQ= zc=FF@_q;nd$MQ$0hC+tiE28g2;I`pE>>r~0tBf)~WJP1=zVt`8E~e<*r^IFzNz485 zc1Q&8J;DR3g8qV0w7Mrxcyx#qWAj(T=|ng=#Zn~d&2<%j+92r{+lP8tVm}x9RXg*n z6?C!y9Tk&nV7+Qvm!{OXhw|TA3x0_SCyF?ubQIp#TsY5O%Z&edDVf57fRC!Pc*nGj z)?ld?9x3;~9ugdM0E*RlfqMDxJwS6*uy_^r)nw!Irl#k#%PGL(07=q0&6YbiIY_yV zbW-Gv#CsB_N1laK<}|9y=l?Lsac|`H5HR&VbN)O6Ckr% zP3xGcg&S6XxQl1B2Gr!yb~;3-v(!aI?um8yoFEQAShKiXnC!d(Wzm_xRbDDMGiKN8H@p5nk*f%~4c)>r{z2>2bLD+tlmz z+1H0&j~cIwt&ZQ<#wXpRc;1z?>`-aTYLD1adU*NL78M6_MNX?ysaAn&R+u@;BTMDi)IlFuo&Eot3lRUI1!=7ned3Fy^ZHpQd(7+y z2O7*85gUW69#a=HXJ=EwZtpX<)J4zhar-JBzfS#@ac{fih+@TMn1CtXYTV)9A|1TC z$5I{AN9DSmCG5ONC&zZ)$KUsOy`5?U$MJdD@76YiMVUy{V*Jf`z58tR{#-BSF2|FO zo)&>Cj|4$$u$|vgx#*Abf1ulUy->?^>D+d241h%tq1`t&gm)?+b3cSx?}=ea7XN7* zIBgxhCHT1siFG$jj8S{5p@CLY6WUR)?mNh$Y{ z%_Ld`aoh8lt28u2z5+=rUW_NqCIa(?vWi_D1aC)d;Lht&yOU;=VO3$OUK+RE?_;gq z1fq_vL>=$a9S6}PB)F`pIrh+xX68bQ;xm!dLAV7?sEA5;L$UXpLb&m~M}Uw% zY^lx2=z1ZMr16;%H8o>AQ^x}?6n5P5!;=d7H7Ta=>r{&mi^o-YIK#FDc%_oB{nA8r zTg3)ZD&{(h2gu$eZW@gT^LS?XU43A&8G}c}KmJWjn2JR`r2=vJOm%xIlInIuw9MOZ z={OnJK}1106RZpJiSGCDF9U6Kr)y02iW9P@IK=Ma6N@*WkscR*uWn<;g!R?~Z&EL! zJsmI9-)IBIl<+B|ikq>TCoG*8=N?k@(?s_6a1xRS@!tW6SQM_za0wY zlyS1;$PF3|a1rf$B5k!YdcozfQ3lIcE4~dfnU(Ovf2HtzqK4{nY1bJ;rn(dZn^WcS zHGNFtm3s9>NJPBcGY)=TUwdLj+bFg;r04Zh_dk zRhD1(f#r7}N{7APVSTG&TUV)HM;RTw=eaJ#Y|xn8N#&Egxe0B&Ygm0rM`yyBaDEuq zG}F@Km*8b3Oy%Pmguf|%UQOQNU`67pXmO{^g*GYb{&ToOa-a*Pst2OhUzA$6|6N~hwKYzT-4>C23XiqcFYByX# z1q0VqpJzqsyn=~T*Sf+7aQ|Ebf#|kp0}}J8%_om2*U+An9?$CN3wnMQV5pdrs{CAT z5`8piGPa!``BC;A%Wrt#s+uLvR*l5-0Fr=$H^|TE3o{qG-aRq+PxPsJfM~EWW?wMc4neE%khn_+NZ^4 z7shLC0G8j*YppMfoBMH0jM^&bxsXC()%R_zX|Nl%1WTrQkgfiw+VW-j zQ+bksYhkOY1(FIfGCLYtQ^Oe&5_H0`ybam^UTUuH?uMawB=LVX)Y-y(|#K>mMpp)0F9I0h>q}JsGqYoA`T6V6a zgQtd?Lys2h#typHYS)CADalf%ymFA3OkPainMhiFS~xl~#KJKCK;kQYy#Kt9TiH1W z`9`~;`q8Tp0nNAUnZJHiM^#~ z@7Xe+bKplgGuy!xsoSyxf;)$f!A%rYQUM%!*#}D3^nv-o8;d!iwp(s^_^8q4sbO4< zTv^2Xd9LzU@sCj+H)mz)zgL=J-{&VkUwUTfpU8##OGTy(t!h%0&huKv8aID2dQVeX zuaMK!`Ed-2P&G)Tl$b7b=-AKIlkWC9Q?sAHQNO3-?+qVG#N$BPw;3uB4hOr_jo)%v z>ZzwfEE0nQ4`6fk{#B`oUv;$pzGTX8HRFX3cvR&I49ep{Ec=A5Dvqu48OMZ#^$v9y zJd{#9)vY*Nhl*-P37jBPGT%~#Cf05)ovU#CMG`2BLYsmDTv=Y1g9=jH9L@O67T6q0 zP03LAM5(k+e+(LnWMzG2H~(Cc73s__{qsqP)iaZu3EqOPmReK&IDIo+V1;b?p|up5 zc!B#BAAiGcA#eo{VI7h`MusW{#+xzVFHTJ6{=#qqv-Z^!-#*cQ zOBam4*eA*Ji%>FuV(|cj!L#XgJPiJ@Inl|mR71pdzr3&JXf)9WBgWc52cw;>oxeXq ziRknX%Rm7vm?V7noQH?lx4HRsjzUrg2>X76+u+Ii`LkXK4l!5hAKRr6e?GY_`hwE^ zv2Lt8&!(szWpX*Q$q;4vh!DK=%TFvmY_R1JvJNMXNY9m$l23{_p=R*&kwxqWuOb$N zhzca>q--ItMLa|c)>dioP7#R-Up|;HzX#)1`*ZN3bym*0hzFj^j^X?tTE;$9U_}C;iKO6VKgo~*OF7)Oi zrw^y1-HMo3#!ZH_B9?#Im@E)nRjv%+Z zcW=fJ?azL={}alk+RO4sluMaL_yp-?9Xw&qkdG2I9WT1gYwV;$ur{k?XoDy_q$C5IbL)4tIB%yrRm*%b)#1B!L>6iuFmt02Ql&_ ziLCp96PZ|waBAJ${QTxEu$3!54lme#jM^*B*+r!}T+F0x47?nPG52h8SXTu4h9_m# zUi9y9tM*P^8Kr7ft-sujo77uVm3E@h00a#UtuU&NgoKcgP={h93gpMz{T<5C zpL#(psmV~>bX)5_>ok6H;(VN7mg*Mt>lZ(0k`P0ulv7gj#bwSd_-*(T6$s?5y*+0} zMh2L<{_Y(n053~R#sK;FbuKR!)$Ky>FomrLk{wJiF<<^H#LuajO@?V=V&m>Jib4b+ zt|431X*4IjF_UHVGryFa_!e#9S`sV|s?LQZo%rl>C|ku*J$u4MSf5s&5IjNDM{HWR z+P$F`ZkNB(&I{|zI(+-*(GN=p_BAH8i#ETZ7L`WkfWI6dT|f%$4iIC%PNyvDDz3Ac zX+V^~ASRY3;INhshvu?{WqwIZQ*w8APqR7$gwfS@%|GNje`WGlc+#FQR)zJ(RgqJ@ z(h%0MjIP1HfzgIuB-X-!<8t?CtMZ=nFW*0{)rHzHh2F%7*A@BldkNPXnY8d_8P!e> zA>IeR^J!Co66Qszqxp&rOePJLI7(^wu9RR(iSPTny^hs2S~6-b?rI6^3z9u$;tDJ^ zrLZTNv~}>B*^J7EtmTrWlRu1vS^sWqQziuqx*Zm<2Ilz-2wP1SX~w0cv2iIrMD`*6 zO<}HW&KmGnS3(q3$m5iG{_gh7ZNKFqCYJC*RuE#=y#&14cn9iQRmE7efoS zDzJ0esOLLFGQXW)SXfvTs(MU9$UdHqdwjoSfV)?*zTtYB*ixxdQXU`L!D=bBC~~eb z-t!lIckss!NNp0j^VVfrA!QZbmXb18N$BYa&4c{Pv_o;!2U5{5ub}s&zz(^nCx4yu z&gLQKKd~9W7~*I@FCEi|{gu?rAEkchPD3;b`V@LK?2X55Sckv|&qnhZPe@^NZ{Tyo zXLMUHbo&X%rmy_&v|-4D58vB|OqHb+D@4A0M-d!J-xQrjLEefWSDnIfKqefMOxx!k z{4O1+iu_JTd7G`IzX$$_IP=m&-r1QOM0--d$gYoPr9yN}Lo@pb-0IHWr7H=xY2*jvyldo_0iXKoP(Yp{`ip;chgu~SVJ&7xWaNbd-|4~ydj^?! z!Tp*itY^Ak-D}_~CkyK9dhcMt1t5A5uDQWRj3-+!7l{%+lUzVTDjkwj~{dg+HC{>VYq;DooXPRWZt* zr3w$qy{gh3L%UPn_pVq98Z!<7u$4 zN4Z$Xze;i1WXWd;$Eaw^zX{BpE6!iNhIkqLU0PXu-^5J!oNlk?YN5P8X@Wrr0g9ZwN*=}8`WBMV-hWB;Fo z{!D2Zkk?Q0_utl*wVlQX1SA;9$Wv&qRVvskVVLR=(eEN(0)vCO`n2Un=mLFh7IK0u z-CYy6;k@GfA|D{Zor{f|?!I!Vxo%4Vy%=au*${qtXxLGtMhl@ttXSA7QoknjN!+iK z!yD)Z%S-=qmoJOopOnj&EZY-AjzwzIG3sFSv~&)UXG_oTnGp@=ikL=Hy1AXmhMZmDYBB2atF&p&yh1`#7}6snh5z~zvMVNG;pFu6=Kx95 zvxrFl423Q+zw-pN0@y#aK=yfw`olq=0iD zrIV=}T^PM0;pOH&?pO<>dE z=X3|jMj0;y(CmL*qS$C8XBYjEU~l8kPTs$|PS}+<*)^|G9mq#6cK+3$YEDTbIW~Rh zUcIBBRBc=y$mOv1KvquToxJ?9K#*_gpuGc;+uez3kI7T$v|%VO$|x`{|Mk9=ULLT{ zeqB917EH{>y?6Lk`;HsK+42dTzt^h(m*BiRGr6&#en%P+8hYS?^Y-q(1OwH;z$N&9 z3TXofP*eS;3;RWQJR;51Av-V7gZB4rUwbUi*NuJBJti3Q;Du9Wx(`Z?6?=eBaW$hg zi2?$U$4>+!YtrV9L{BuT0s|GX4hNRHw`VLzzzHIUz<{X%(BaT+6$cThQN~(8I0RRW z>Fubli4w4*?lZ?RQd+%mHcQ#8Z&UM~@tsk$V*2Eui)vq4?Q)V(vbeaoJ;g&3)Wyj3 z6ufQlE4p?;V*S5tLBM|Jj>f*Lx;!n5%$UDgwXVe?(`7DL8cW`!gUWnn8=Ka{Q`+~~ zapW0)0cYf_OUFL%Hj1J2ls{a1fq6}D%aumPiDmc)rn}(PHj-IYZqMmF3svy7Ig%miuP6iA6;J^6=mDK3o0TZph!rnNQtxp z5`&oOigF@^B59T?q8HXtxNsM9 z+R?{R(J-cbh5oy|L7D(DPldU5_IK?a7ptxeIXU z^plO=;w1j*vOQoFR$@Bz0wQW$;u=*)x%(9!0%^84vcJTKo*c59bXZW!(Kw zWFO4gF3A!2Ir13C=GOgA{T?@~iZPU0rL|*`YjNm_D^X{7t!CW>7!S5jn|AG!vD%NM z`oNe5r^snUtxTSzlNxQzX@9!(3G_qzuN&e}m#m6PF=q@fC}xGd489QIA+ z!c^(n@YkL>UgGeOHp)r&3K-c(!=E^#vPQoW`~|V4eHic4EbkJ#RqAg~R|ObBI(dzb zL?)(n-~w}eJT&$nMET*S(Ql9~yM4S9^GNTDH z5fqH+VSv|FUwC*E@J9Y+yz%c5Cst!IpPVK=G&UTLs%SWa{`Sq@8Cj3foy>-#MofQi z7@)~04AqX_e32zl#&zz9{KfM;fWI@-(B&pDA-)#Xi!>C8vbC8+iOVLUqD3Vkm%cPQ zHK!6dIIF4?;gQD$2ek!cYOvR0_AP(_eWayDvF(?QXAolA!z6;^dVC#Q;OXJOu<cIbr8xV;x4RMM`TRMw2X}Z zekk6rkX@|$9(yjNEnUy18@rERu?5TI54S1bq7C0$l9|hxnO*V4jXF#BMjpfHR&~cy z>WCB_lcDg!Ma4Vf%Pxwu@bbWDSzTq9qo@kc_UXpO&hUo8zze6iBS89tbW>DHd8$5E z?)zfO(A7<&ehpH606X)6%FG00_aM&vQT$HZGo4UWS5BZ}9$`NXTp^-d0KTCMe4w+8 zV|g+w^KInP?t*sJ`OoBGk*5Iv0r9mnOzax~mrm(bv;cT|Wre-52!7ry-pH8T&O4Ou z(cX=##`?kRrkh0;6(o5bHa5Q>>{;a*k3ObQOrva2KxLd(?4Su1t#d=olg+23M!Bqg zv)s|p*tmTW3TPlAD=b(arYz>Do^Gahz5b=K;Pmto%HYiIa zZl$Ae^f}sWmf7bUu3U{HzRcwjltu4-Xwkdb!N%f+Z3k^d@ihsH+nwT0JT@E8STZv2 zQaJ?vNtvC}z`>QPGZK+;o|*h#k0wziOF>ylsVP~^W1`jtX3zfg>GH+#91^@t0X+;j z#JMU@P^LlaC&8n8-3W$aGyK9={DM!K+<-`Y2>zwc-4uwf6ubjU7fpnP4Z3Dp_-h|k z9<>C~3Sd13pTur&b$JV5i?i-K8abYl3XG&9~@y`BeQlN27v1ZD)2fqiEo*dri5@ z!`zhu`FzYW3l2l=Qg{f>pK=!c`KK(CfAq$6PDv<0ss}+SY&(kp?jrT~@22dd9Yt~P zG|T^-j@Nqc|Di6Aq|ExGzU>|RDrdE)B17lel2s@L{|O3$n^9S)Y}iZ{lx~4 z4w}eC6UX07G$T(=U+I`93WPe=3ZiNg4Nxc8hF)AGTVZ1K%k0V4E*F8lfeQCb(+slQ zY@r_KeT>ZIFMk1>^lYx59GNUeL`pbRS;w}<7v5sMu*=XX=RWigDw{oksAp^$fVgGVmMmy=!viKM(m{n(omUalO5wIiT zxJrEI&K(?2&>EVNk@4C5R8|X2^>qhBYP|dF+)x1kMXC;A5SywBp?Thoyh}ypKWoDZ zfi%D?JTA`A(4(0viGg_c>8n?t%(9@#_O*JuP z`PGLwnM03eH1tTD?w5|5&F1;rpN%^NtMhKWmFJJ%&TWz8e5zZgIZXx1KDMWy9Tt6v zaN1M%ygrEGG4$QE4092X^pbfI6Dkh+&CY}An|1>UQm z*eo`SXxU#Xm$sX7XmsTtO};UovLK6d@~#^uR7mY)&5c#5}9O(aYq=;g)v?u<7B*ALWx zwE#WW>FB)i!wc*ExeZ*ybQ+JJ`fsW!ZL(c#LOo4aI5Zn-f}Udq{MXqH_AsV%sV&#% z7Y>s-MWIikm$QSjLOwpU>5w#GwS?^_j2lR}8jHXOHCqh4Jo#zCZZO7hEU9?1IdVTi z+f-e~dcJW6z9Mx~@)ufo5V{+Dr z4e?k_S@c%7&CJ$+_{>;856a}-a@COC!lbc7ND%B_V zj<7XfL6I=&ctDpoBwdj!trthx3c#rerO(~53AvRhw0g3xoR))q!t_sFN*RYqw%^;; zSv7=zzJdRuDh!P5jLL(MF41s(TbV-Jx+$3Yz~YRumK?q*1S)YoUU-Jgr(@G zww9c+<4^~3jcvD(j*L}IoenqYs(Qn=T2h4+>B7~8r^xuX+E)u`9e$~)5xzz2Q^d2O z%SDIm9~@X~Y|*{NE2Q`S`$Y2_0C(G1f5`;stjOFcNly$na=()?tEMJ?*W30*S65f8 z981Ib3b#v9iJ`RKi(n4vn~r9SPx)Z?zY~zA;I7`!b6vY+?xnlQ6J-FwwMhRC@6nZu zb@iL`(o`6h+*OQuzP~=_-8u(5B|U(pe7hZB;Lg#AU9buAzSmkjhs8zd!HUl23LjI) zCf}TA`8;FyZ8M8U1VtmwCQo;Ifjt;!7ymOK#vNh!ZJk|w$*_a4Vh2OnSV!|9%ocKD zaK7fJDfh*qXVH@M;;Ty-=La{7=exV-_>MNGF9)}i|zz-txX@U0FOXbOU{V|D3eT#wTV|;TMS`61ry^nT1KkUpx-N zj2;zU;4zg|Gz0S7v#$MC*mypB`_hZIHa2O4{ZxB#{C#i?iEh_#O|$q^dH#nhw*!2+?!f^VEwD1GVeqG+Az2Y}>Vw&-g;&`E zzWfG0J_;D5izV%KnefL?))oarqwbxrkDtRG89&OV$j83`>l-L&T2=m}wh3 z{)YAm>U2U{@W$C891i?$Z$%}_UKL~=lrm{{u-;9l`r#My$oSmNnE@tIPxBylkoQi< zoM3l=Wz}|qII_4h{J>fVa2>z8#u@2mox#LCxUy6zntGJLyv^T0?rGFQTR3gk{?NPr zT&8o_FvpClq#wE17BQP34(dxeDO6aEP@uWHCzC96fHPfs21j@r}pK7AIwn;&J)YbA!} zJw+;h&+&P!M&$cz>vZg4ceX`Aw;Q9p_E)_}9Ujr_JFJgdN*srco1@9prK(j$n$}Wy|IcC8^4{z<~Q*Cn?xK(o0K* zRD^dxmH5i9PZJp5>!iwMm#i@xr6llTnhn*mT-liKx#TP#(_79fi`1-ip|X@{O9Tt| z4nHE!g`c#ee0aZl7I};HsnE@yuHg}ZT(aL^wBd2X24s}{z-tdSTr1ys7KI)R2_oE1 zjjlcLziJSFICa#`0owyF9BmGRq}<#Y*QL;_7qr~`DhI-@WS+vUNwvW^N4=Q)*%!es zUxs5odvF>M>QG@{^z1M{SogP-}D^dLe$~Y?L-Ejispn7LIQvdVJ|iRY5|}opuS)jc$n)_t6z1PJKVpQ zTum?q|KOc-k1=S&!a_(_#mJMB#z51LM9nuA1(#?-IiUv=XckS9k#Qj-yK}~{&b@sR8C)b&8()t z+DtWWzcQY@a%!vBb(}?-{;{+4TSo;H z;%4mNg6&KvLwua`0ZUBv<*uCntM2i}OD7xv7tewrD_3>`N&RO@(z75P3G12@>>K_8 zAIjeXxI+}Va|a|UskYY=0iWMdZs%6Z2?ctWtqO(T;Ha@Ohx$>N>yc~-6Dk96z7G3Q zY%@<$^1Y*B4IgJm_M2_10K)lz?8nvT9398TT~QtA0Dk4fI1RAb+(SLHy-eqJUgcT6 zQwN^Q_x_?cx@E7*~7}y^;!{6`3w1;=z1|NrztJ5$qkLq2D9xvYS`{#Bgki1(ZIsidvhQ%>#M)vj$QEf`y}LTO`oh>*vXuX>{*J*_l8w z`gaAOfqU8a&s`++g5x`JSY|xMvHG4=IT3GlF#{MMg}A^*Hg4Agm(xa5?4u9o zw+xtQTMuJOhZGL`oG#oTdbH$7mcXZ@->|(x(LPZvFaay(HE_bF;T!gG0SoovJFPuG zQX~?pa$qUu&6zofdBZSM=XV;h?Rjm4FL|>;ENV$DxXNBZ&YxA*P6VFnlZ9f07Z`2P z_EbG$@#}J_YaPkDYzitPi>x?`+El5Sc^*7b#r||Isl(RWg>^W8_M$B}XSBh5ZI$L< z(svf8A1#UGi+e+WAg!NNlYgMo4Io{FiH)xZ7e$3PBJl@Bi+dlfQjr)EUyV0L8GmF5M>Co*o}hVD(vJSwW8*XuxWBY8nt>SN#ldGEiv# z3-H{dq&(;s*)1{~e3YA;`$j>51*r7E&OUbb=B0flUESVDc9lI>(W{A&+l2n|hslrCdz`LUxq6Bp<2e;$gcQX%Qknk}sa7W*##8^SVr zuO2L^0NG+K9b5_wdr#JobB0EK!(+L$N;CLgVz#4|T6j z)kZiTkBC6VXr21*F5p~kMFr+haUz4p#DAT64ZQkfR;a-F^fQo~JQfs;C^ibmIZ-9r zY!-MK$K1_&SWy@^zG}Ilc-|*6TVgB=%$}O~P^lp=*>y2ce}d*=+aKzCoSwByTa%@p zSj-%<8J{sDJ3AmYmYR>BpMaD!tEws%42*NQbewE`+W1=C!*vpY@Q#SF#`;4BSLyGLv_u0wRp880iU^^o}610yUaH;Stw0_r_ zp?s|=M6dKh;|${Ke{i~_^7T{WkGCGaxdmkyI+ky(7ju(!Fs=#_Wi?fm2Ok#d2e=V) z4R<6DV;5TeOF>r3#SKcti$UPUtZslNIiO3XBT&FkL69gotqxt+9PiyM`U5-OK3l4} zo914L0{A@(kmi{gCnVd9wzTPH&5@~*@*&&&BxwM3ZF?hXRg~XRJYkbOc}Kr!T2r0$ zin}(q_GBu{1jAM{`c0xfXe}LAjUhpvcRyvk>eFc~IaU0#1*@rr?`X}-Nd07q6zZQFKfm*16BAve zZ@eLIJDFGc{HRa?uVAC{gH-$xO#!)Qm~1t3JfG}6psVJMqI5D>*j`zlEunfWN^$WD zxScXf%Cr<7Zk>v)1;7~}0fCaGyV=zA0{fS{&w}!7E^k)O@+9ys(3AeyrDu86(YKUm zQ04hm%Wwui5BRVSFS$(q4~akF{)#Y~oS!Ep^tx0Ygj130*zMeR-o5)*a46x3 zN^xf>X5=x2iZ4NXYW>3sK2E=S)`UErE0wK{{CoopU{nQ}Z{YPo^^DjJCXzsw&%Wf4il;LhT3a37zt260wZ_ z)w~9AtzX)%2?6pi&Ek)E0ttOp);-ajbP&%f(#l*Hx#Z`;+z@OXOwi~}$)wd4uh7#& zFZ_9}MD3jD;S}pI=&`#xA^*HlzXU}-SWwiZOJ+Rrgb>|ApKKxvC?7{x0Hs6ECE3>%pRtIp=Nkq9 z*_-k__a8o{-u9?p=T}9)8xEDyjdG1V+Yf(;6Hnnte-s2`EYCAbQ#+4aw+M%qE@l?#f&1-ub@za#xjNvxnkzM zv#S1`_8nG#X72VK-sC*o=z6DGKXkAXL!T(L@Ns)e2nXR^%AitB0Dp#!$_DZTKC!qd zXSS8|Egfby3PO)-a0y!PCnD!JvT<_dR}#?5Y;2xJGj+N`1`?0Nx9P0nqyUAjq)}4G#k)olH2x ztSS6z1VcdKAcr(AxI6V{x_GvAgL#{~98~I}fvi$QTR-(iXLihzwX{qE4{{WM_&7(F zU-=5{0@(+k;U58sN_I_ecP?O<^5>izNUIol3dI@sL@D0k0U3iPP@g-cM&%RbZ5^Uu z5ZcZSM|()+I={Nd`z91F8%2TmGfg0+jfMWJoK72s;1+zO@C@$)ssyG1gjEku?)&e_ z{X4^2*{`e->&sfD+81HPF_DJi&iUaLW@a^jA+4?Jjpo$3X)IMnc0J;~jt&P9Y5ZgD z*CYRtw6ry);b#-nPu%HOR%r!kj=S{*v`?hy`rJUFprq-(b}^sm0I#- zrIW4c_mLN&sre9E8EGSGoGYm?a=Ds;RH0tW%Xt430zPysG}n8Z?X^>uT-FCEl6hJS z4@M#&oNHE`o3(_c13d{rZ<5G3t0?^zu9~EUMM9&&8;q>QifK zYO*n)`p?-M^qvf-ALe3au0Nu4dj7n=V(0R~$$BmDtM@@$g>VJfD8{MX?@OWReEOm; zPZ2%&8)zbM4MC|X=QcH+OYfWYyHDmyV~)eE7H))|tWpoxf(nFLk1lnY5vK#zJ~%z7 z+NncXU?g$lpu$B;MI9xoy8CV#==%pVHBzAQQEDG<J14 z2ns1+W#0a2GVJUR*;OS~+;+zNxRo`9v6F5A+sRBIC1jF^0w_S9VeJe+b|rZWB!xGd zww+xzYk+yBO8u)vyRM>VU7$=bHoWb*X<>2mqV5$mGZW&C0>Um}X0Kg00{2ErK{p2o zDf}iJ8+$@CIm5Nj{84QLR6ry%Rv5YjzG79V3Yq5-o9*t_`N$Ku7`s!|ugN0#pt285 zFOEzDpK^cytF#9~OafUpUzYho2uMI87#w4lR;6Di_*MQrvk*NaXx$2>;$wkNxGzsP9o za5F@Q@8R?E);ZRSzi;Tu%fFjQJ9w``Nt~m5Us9xDe_V}4JR_)_w!ZOuwwepHyPN&n z>rFl3&h)07QAFTz%N_9HT>=QHw>`52Cu-@_zNs7Mz;6J)8_Ww72?(#;8-2^4oj;N* zfRb}ljeRnumy*-+`m#!RtX-qzOqY(9zDwG!hA)i{&sXd#@=9ptmKv~X>=A4l?_Vd= z`3pSEI+Fo?EC_QiiB!=%qXq%Ork?cRMlNZ-MA?Jr5^6L&YGlXG$H(_ZPOi;lxIzpl zZ-IdBXv6Ucf4h9gn%(5kj6j+DIvDRtJ(1xH#x(yoh>$^hy|$>Yd<9bh6yF1&A|QNx zaLcRCwFjM6gOZe<$aMGjLp3x1;G?Firhvl7!5oJpzmu}yC>2IxtY#AdmXMIZm%UA*mz4Lk01WI%gWml|4f)@b zrubR#jT3R|p6YlUkZ4gN|M+FQ(@xLKyiVyZ87!o^s?ux2fY#fp9^zXdm|^%tuvjQJ zb~+7Wtf$GmDakQO?i$vv+-}V^SC*gChpBlrw}XDps!XoqUk21&(nYy&iP2Y|c3+O( zQf58%%NB-WzYD}v2$oq**BbXkr;;b@OHx||hkQE7*Qzgi4n{l(U5OO`@BMu(ZY1tZ z?D6((%=eL0Rp>@RI+@eg(upj>q4FZjhsiEK%mf5Alva_*(hsfEv8Z0qYZV2q7SiK} zpM@i<&tcrv|DNzzK*OVuDDRVAEM;0nR@SQ#a4&lUZyOs8t~-yz{L|ezjKqZgtr?zO z8%+dr@oa7RBuDsUM~w3%(NxJ(+eZx0u*+PI0uP-MDd~62z^#@^{CkqY6@Td>zS0PO z+{?`?_)}OxxpwY3QWH;O6qlO0A~ymUMEZ4GmfTBfXk7mQ5=u$YCulQWto-?@9hNd|5)%JJPFn{Nz*X0D%lbuo>gNv+u_m2< zS6NjaDvWme#&4F~Sdz1`8K6uBRXg;i74TPOUu46vLB474L2Ldy+R5C-krV*@D|OdW`W>lKYydLU zicPp3@e2vH(fBputaG~YF!vJb>|AC)TYI-0^zq1|yk>I=M{A=TG>+@VUx|rsgGJUd z@_j$B_2BPc{y%2WhBFZNz$v?85539_bRYXRF3;fYpE&_)0z(79C>bcMhntb`D zo?5-)uZ_0>O3EZ{(04SG)9JQp69C{SKQKG$eu0NbtrwIeA9$Ox`)NC;AFpxuVV(oz zvqP9tC;?gL>_WMrM5+ilQSNFdZnNg~R47KM&Nk&70W4BH5{&&@Vv=HJW=<6Ihz1=F z4Kpkcg_)l`Ax!9#e)sNOZTK&gHt}Nz{orQlesf-Gr=z+CU1^Y9j3+#}N-iKn4o9i! zV2Lc|2)#gw<}UQ@flAg~A?qS@E(J@I)=7plREM9P{kJ{quh(W~KH90-6#DJ!3l36b zq};RB?>210QtmaQ*@spf`8VuLYxa9lpV!Ov-l3nEEwB&l9O1C75P~wNzy=O#Jh9n# z>gvAsp#Ad^aCKM6$jcY3SwTb`$)85Y!>+({FVva5v?~ys^GT`!JzP;;eaXHa=V0CV{I3ro7b|h8|KUumw4WZA{GlAY=*IMbw?&(UFnA*$DYfde=6s@1_l3 zqG8^+Kc=K>317h4Up_{bQ(G-3QhryKL84c#gtfrs96lJ;fB&fY4Ury!a)IS)c{Rgs z6BqEc-@aV~O?A*~uLg3J&=2gpEdNLcOzF3?nyIB&yx$zF-Y!0`{3H8cE&Ut!9m6aJ zM$jDlPHOXqfS}-Dwh-DS;TU2Mxn#&=-8SqGNZ*=>_^^fPs~}E)QpLYeE=ZuLgcl;54uKzf`bEtgHaxhiQ^w1 z`~*)`z(FCnIXfM7=AaFFaSUw#nc8%wIop2f8#bj)v$2VBwLGH|i$!H*;?DEv#36qB zTD!+;*bH712M{(WTV{9Nqq+1fbmzd)|8nQShP5>jQPNX=t0j;=XJqN*%&eOzUcAsh zPm7)e($+8{^XHDLSwiWQ&-@xF*8UpDpgqBi0L;IQ<>6ZQ>6Jji;qTw<{;uI0gxxUPJQah8?|l< z(5g~1(ybx?UisIELixcJV+{_s_01}4bATV2uWVijJ35kwsyDdfSpZYN62}(8Oz=QN@))vNtr$EVLq zVg$L{4X^AsWVw#=duZbDzriv9aSuqGbT#)g?xZyU7OZ!J-1=se)akmTALHu59;&2saY$G!hwO)vqK!O4wGce{LznGHuJwB2)#yl+?GC%NqU7l4YSOPk|b zfZpVZU3ZFH@w>?aD5_*(K+=@iGWs8H|N5t;TQsDo_a+uV z6nOlzS*z#OwUOj`^JPgU&2QIuE7d~gi&0Zd;f|l0Tl3=?XBSc0Pta0u`&|{QJ7dLm6=^08(55iD#;t+-*VePS}~Rf8O+89ty>Z7ZaeXOxRm>N-DB;= z>n!4S)Rh0!>sQ~2!U==!zBDY7avvhKdv%%E@qJU0Nj{e_DDX?ugQpJf|Gh_p9KC<= zuf(9^j|${>O>}NniVy;1-R5GRgu%(t}1ZPzdi5<`JB9IS{6TQc%a6~{>cIr97VmD<>kwm zf5G7o*PW_nd!6D)h3eEHzYm($TA4luzK!eZB3bgR6LU+d1I`5% z;iHr;7MP1gsKYJykpU4{`MB`ePRt~9ZZx((64fl*Xwv?ZDc^ftnKEpv1IfaboO0$y zBf4aRIE%rT{q67;Gog2JhkH5l4rbf({;h(;z-sSFLV{H^O05yX z>a`6-%u~X3c}k5?^bMog)6>&e&Z}2TJsOyCEd<>Zwie323p(tcX$puQaxucHewGE> zI@G}F7NfGfJEOgmA3K=PNR;Z{XowsdT)t=<+Cuo|ASDpj9;c0KjkQzw;IH>7XeS@!yo5QoATiTdBCHdIt`&{1pcX8#vK{#TMbiBXM;<#1V>!}6C712ub93@zU+I3yzI9LTdedJ?>E=E>-7%L!0LjWcCI%~^l_kw_u+%NIGS6mh=myJcw3#V*5v+% z&X#R*^U$dHqsuLU%VXHI(3V&*J{I|KRayw~cNLa*k>nc8*?#?JN4kvnh)0@yV2Yh*Oh%51U zPAI%b|19zR9j!`7nNrEIlfKsqJp>j$U$ZOLRxjAGIPMwHD2}$hW)r-0*r<;*s1B9W zJ76Q7d*O?tM-(OFQo5bwUCN5#iApy`UHE&qwGeo%#nZuQ?KeLMVNV4S7v27oq@vv= z1f7%TS>qG-k9tuA)l< z-3NVCo$(sVvHbK!?T|9ZTwPt)Q?2)}O+JK98>(8b=k*8Ic)`uXwNF_DPI320#XCjg zEdJ!wp2~4cn>wcEjtDfYuiw#*&F}kFvyAiNg*s(%klJu%aRE=4F^P6LluxKdMR7Ix zsvV6BFXnyOn4KaeoRT&=-{tf?KCk)_SMsK{ZRw`c_odc55obJ$tGW_i zs}e!hglJY5&?Hp)EXDhLW?dI?S`s2HC6OcEwG*m{!pMoQiXA#KG*13akX3mrKIMAp z&QY*bcKMjG(J`{LkMNxe#1`Vo0cS}1JF9pRA2oieqBR*Zr2DQPBXcVreLdOrNZBL` zwzQxD$$Dt`Xq>s@i#g#q!Wlo2T}-nx+L zaMB<`QguQ-THhX-dcU1N-1kv}$9Q{v@rTf~>%sGpNEf`~3mHX}S70A+gTWbZoHVI_^vF%Fv?+IF={e6;m zy@Gbw;l|a}9RJgG?D=;idBW~fq}bk}g50=xTl(Dn4%%a`PnXzFckAXm^J8^7cNwSK z8iYlH>VKu=G&Cqc>;B1v1DZdabgTdqoP|`3NdgvgXfMGp;e(G{kw>9Mc z$l%4BkJ*eIGGXgQQMMm{F$T(e)oJm5<)k2=e9s$E?!_Ep*}bi9iP%xfQ%YJ{*3^?! zEuT`qt(a8#Rx!M(%81+pF86Ua?(O+X4{GqCt6K&vO|`w*pht*3Fsz?ok&<`63c7#xByi+UQ2lMEEg_&*zg!M}r2b zsU6GHbynGGme=_Fnf4So>00MKS>w<3PJ597>;)_bA4*V>3jFR!psA^9+Ons zZ^1~5#ny2liGsc_=|gIlC@+83_``M^6W0%Hn5QiIA8vo$-Scx1%W8!9ZRh%HHF7av zyW@Fk z<^qk^MX>0*E!3XaiGcUtI5=Fq`g_|0dO7-@))c+Ico%F>-?3h2TG5|#Ru>A#!hL3O zOIlyS3!k_%MXl*(%egAUGC5JM8YMV><0Yi>@~zBlj?pq{LMOR*RWN(UU4$F@dB;Vg zOSN%_5b^6GGv%AXSjSj@(~YlW3@4}Dn$G3i!U^JnuN%7u)3hTeUM}uH!-T9fdlVfW zx%1sI#|SweVdRK$ZY?yhrhIx^LhvLv7PXZX;&Gn!Gz`@NS-7WRdxGEDLs3ZhcYW`F zJmAw15rK$3v0t)i_TOq!I|A}84D{nn1)eca*%x=$BQokdzttn0=po+wN1p0!p{w$Z z1W%uc`rXa>F|jQ3KD}|NQU3Ci+jz-XqfdQk*hM~?8`oQAActcsE=>QF>nZ0D1#<6Y$#H6CXxyetL0+AVJH z1Kr-C8V%h?{Yxc{^$M?FzaFQ(efQP6u742XY;uEhsO9+41gFPjMPAsqn$h#U+w`}i zpM)h(x2NKpka=y~ptv)9i&S*Z;=QuAPRdj_TeoiyrSAvTdm}OfPiW5eGH#}(3Kmkt z2-Jp6J8wKuOlPF^VI))wa%lK5!h5M(q0zr9K^yFKBXm&3E;F8z`Q*F?HLf~6CT+ZL zuaJ;+CpFA%+m429raTb6S^1v&Qa*DMZdaHa<~UWHBu-Kr_46F|7u#wbf_=3)3{6YP zNR^U^fJAUzg=nzYi#pQ|vtg?B+am?*_TYytc1xm=!MZ70qb-78M2k^8C~Asd+8!B& z><_o)CU)KjqM{g^1m;H$x@PEwuoW-QhAZ8YyTH65gl8~Ux2{K-V(8TFv}DZ8xc zjWkR4-}6o8eEJFR{DxIJ#3Cir7m29%_^A6EZE1N({QVsJ*n*O#(y@z*mIj|Z`fl9q z99JH;>YU2fx4eF{9D|I zk>+MpB@Dk4tFkt4jtu1*W!zl)5_yydnpEpk7EKaL_^8DhI)-sZwIWUNE9Y*V=-YkA z(BI0J{Wfe0gY^n`8Z6 z$*d0@hLljaw=5JR} zS|P8i*3Ry@W)7FXAGw&|cmW+!*h+kPh&;|>D=;9ovm(m;V(1r@oLSNwwm5xuyK|Lk z{i%Uh}2H~)Pc+v*7+V*7)r#kZddzq1tU)%wj2LpDVB_34Tip~qv$9D^|P3qFla_)Vryy2mc;2hBgP(yq3F zg~Dvrb;J5FS*kQpxUAVz=G5(yOG!!Dj8|F)y~q%++al3<=rMPZs8uO0v$*mhjFdlW zUzJ<46%G;Zy)J87s)W4&K*Re8jjpBPm!D4QXiJ9y7tDX&MTjN z?XiHYMm1jgJ1$g~g*7^MPBe30hqceq=%+4bh|9jCk4gtoR>F$Z;-h3a0C zml%8VF$#G|8(6bRdy?42T>3cZh5kz7A#ERoKzVtEnEN7(B(Iqr|^skAb7#@x8}w#t;k(dP0t z_ijTxm^&QgD=6NBg4K2Q`ombKvXZ~OVm^VN+-z2$7*UwRHFKP^pMC~~%rT-Kcw;){ z+nxqVyg0h)Ju95NTQBVUA?OMcC~|lFXy&M#Fg0H9uei>Hc;UJ3kj>J1i_2I$5O&p!mI4PT5H zMz($mIL2-?34j&uH9TWyQ8-1pTp=Jvfhbf1m2d5g*$H<>3N+;8JltNDP^(TLqNJl| znYq}aqW;d#Bm6|=_9^}Vql>usw&8f{8fkM#e7=-RfQpqXLfaM?3qFkoi_hoy+b+|Ry78lOr#eK-i3NRir@>3U6W|%o|7NSOQ#m({A$Zt=O5BI(^mF?{*t%h4^%LbK~U?j+k>Qo!&~fLq)j#v?~)?laH-_-=vJed_jVM zeeE#+XQsO+`yI%Wi(yi`QF2OZm)pl;r;aAGRRJk1kiSE3Y4?(yMULl0L-$ZAFKE+{ z2Tj}eXT00ZtV*#>{UNnl*pEc;3%FGWV}1wgf%eYnsckGDgm4#8WB2hTUr2p2Bkb?| zv?VrN2d3R$9*&KxDKo9I+#oG}hHrODAC8*g=5B==Jvjb+sd3OG3qKedK6V)0kPN5} zq}cR=iw(o^&-`u`Hmo>!#k+qSVa@z7gj=Ib-*B|{fI#Q9pljz|5(Vkc;!k3>oF_zc zjVl^;Lq&e9$j&|U>Ihx}S=WQg7~Y4uOL}Y9mZ~uk-h1=%gQENgPa3fE&wF_;DlwgD zG4``_VBps0`UvWwKH1@ZZ}^s9?RnCyB($7@8+(V? zk@jr*g@y`#g92PdyJ#%AwP%iW*Eywp+AO=U-G;DfJlj&NBHq#U6yvf-^F1MCGucQ) z<5kjZ+pS;YQmVY*XLU#$E{S(LT({!J8R$OA9n<}3e;2A2J{PdC1Cg~qCXU~*FlX2a zhmE&~zrH_SP(w3bZ$49H4~5JNoFKY&d3z}0@$VOMG6J};)n2A@) zN9^fdNJguhnm^nqo-ovhIp~@W89@MJ6=h39rG+pHOMvpQ~qmQ4$0E=t>-o33?8fH`1tpS#s1EJU*eoV z*&83CJKw;|-bCBazUu({jcyGJj*t!~iK}W{=Qd+3%B8SL!ppbj&`&auy&#*j5~!^U zqZUofQ%t(=V$(v&f8FCV9bSi_a~z99C_0uhGxwndKs2ZYxQTV%t$9VrJV60?IEzSD@?4f$Rlde671NFCZ%gqa z8Ugrye5loID%a&!MIgts(M3QX+Qz&yzDMO80|_j4*>i2skMI@)n@+CH#kDA@Q%k2RkzK-Z{mQ z*X;Jy$FisGM|jm}!9Z-mhS-rk4b;rctO^lHDIf$DgHY`daoL!#h9Bl)qNLPw@#I{^ zMwUE#2T>@m=^jl&(x0lZ#8mnWNDlMj5y^4S3$PGD*JB{7XFmMJN{ut?8Go@Ox zswar@F@&n!Vn+GHBP2mu1QUdi;Kn8@uo(sjj%AVRy<;;(c}hAv75>NxN^gLbczFBe zK7baf1Q)4{uR-$I7G!P|b-n|qjIGg^460+9oJ1{Yvwk;zYeZ1`*Cf*L;mcK8z5eG?DR0XPjaudwhDsAx!0 zVqv)b8S_Q)I2f-0fk3{{36G)qc#7I37?B_~&Xd#r_HTF1hT_^7Y;8^I3XkGcCM8jG zkoNcV{4y?8(bo@G%4NKNUjo5-|9(J7$n6}Z6nSasn~XAFzP6+@D9FqIUg|Mt5|SYi#yJ(RVmapxmQyp`eVZ(xySmUq5A@t)YA+lpljXhe5UPbRn^Nl8g!Lh>Nn;c)G0?mvARnUllJtepBqY25jI zE3ihL^yPd(ag*^xiBVfeN8OAJxTO~VI}0LI|FK>cN;a=^b7l`-vta1oxo8n5DnwrZtQduC0-Fb{g@T(SxRcf)b>m{^DF}*}rRbCvJ zVBC|XTRbVIg){+cXF&Msq2q{ZRi8mG_`(!zLFQpT+408g<_|o>+uRctn5-@1hW?6* ziiBY1nXl(-NsmX5ABO}41aOMi#5i)`+@rdZ3UG7aFe-Pt+W%AjEsKlbsxj#;167yY zRP(obtFDOWaD5qIOarV#pg}$uCue#=?pd++z~=)1U<^t)zJd!|*}VTq8uE}#XXC(! zQ~kWt3z#5!dm{bdT-M_8hN=F*Ix|IDQ&Z>4Q_%6_Y>8j!%7iV#R;SOKTj}X;wftUX z&rD(qsF#g>|6eV@Sb&b?NYgOHfpr%Q>A_))zY;56X`i@D{>hK_lv6+DzlojVfAi)| z#WA&LzL@KnYFBmd^KUcEva#8~f&#MJvq72nxuOEwIM!%Ig;S)|h=O+Ds-*|s1|SHF z_xloMLHAY`z*z6>FjwPC3PX2X@8lI1P4?0Bip3CDQV9Cbwos?Ed$_LW z$cJ1MXJKGHdWE*7(D8+?7RGMErO2(S6(jo(JkqQzpjDNM%ID2Y4h>WQ!4*u zyM^h8!fDT*DOe$yuPNi(AFX{!Z`oMH`oWODYtwY)gZV+Oi4l0T5(Qw4KfK;?Y zV1%U(51qy}nBzVO!fQoFieJ1oWcZH=Y~fd-Zgo*H(Tl64(J#?re`jiHRH_B0*D*hQ zDCx}(KJcIXh+6yoEV+Mbf3CsPxjL=5nEhp1S{S{+}yrkItWjuBS_Dhf*GXthDDRVB>+V7WIhd0s-#spba zZiousVtTW}BhmPEi&O$vWsqUSgfCgUCmI70L zQ5h*Bb{8{`FCk%Q`6%&rh3>I&O=6p>thPIfLgYXT7Z{TnA-;L4{W-hUk$lcI0BI*1 zJj)xD!6Fb`Zvc2>%9ela5^*A~4BBgKup6ef1-5}%dF^phHWH4co2N+B8P z_d`jTUQD~aBt(9If#zd3B8W%DW@a0AAOEh`_s_U8U0*3zJNq@~vS3MqyN^veHB|Jb z3j^DAt2N5O@`0Fa%FCg#3W7tT+D`_a;dTZ8731e$dk{HYyCQVZ$Vv89RFP0AIyxHn z_U*wj1qaXs5;}buNBTd1N-U|zqphtChB{oeVU6DhO%)0a8g-JTAbQjkhz}z*S*{Uk zu6{~au4oDkoTk@kQO<9J$gIu%~i6lt@#|t!psp-?ik9g_?9#v*)AMZgB`@cq}Kz@l44JseN zzi*>MM`q`z-y9f2l_4n*c_<`LUPY_AK!t(>Z_ti{g8ypO?qZhq5kxZ9SESyZ#o@%a z{+rb!Ql_vbcYBxVL0|m(?-M)CjMcEcWvH%{rgH1>Cl$kA=MCDzy?s-Y^9kn-as<03 zz8jWba*O`#4OvcACG*>lVa*?Tkj&4^V8HYp9UaRRtPS1AHDFsax?-PAHT_>{97~4= zDYjc*p3T&ro&zFg@*sX79&1j*Cz!Ej#WNhy+na#F^<;-H6L6*C-8?tL3xOk+b3U; zBCJ#y1(}nMlw_gl;Bv5xz=@5Fo$P{9;^w_^R_M}~VOS-UNm^(&GyEb}$L@8C6ab`p!(z9nYG$lJAmaR#4t3Vutz3fg zpTCy?Md4Vy*uL^-Xb@8Z?2gq!F8YzdK0$UNFH2-+o+nO2_@Y0e9cR}o7KxAD%9mr@ zCH`l-7O#^6H!3}UJbY-3IZ>9K6wQ*1se(o7w?o2ay(`94U(wV` z?ArgqIMUD>VoO=D`b#U#d&>6h6dyY_*u4(NIZK4^DNCJtnwYf@IkH?Pe%$GfN=D_5 zI-w$BAk1q~UvBzho3XIYhQ`mE77k)`Yv+O0U1zE$$J$Pm&`5VY4^W7B|Gygc^RGhU z(2D&=fq{&n?Au`@Zsq?19jmpJ))D8!%YiIk#Y88vG+#dX`pxMv4NVxb-xp$IK&&X4 zXJ7wEy|Ed}S2#TW%4Wv|JhQ#V>$ebnN)YQm3KCl43inw|AB)nQsh+BH-~C{r(GhNB zZ>e8zo6LojsFI_W+uCSdinAL!*5~>dmGgiEH9W_O~qIHeI%F1#r)|qD$G3QGL zV8QWNPzA9M+NXh5kh?wI-79M*S6CC=d5N&d$jyJqv+aIdY%G|b6Q_W!4cdGIQ}*V? z7&a=s)|Pli?f;~vXL989Ohj=6el_JS;o*JxIgy1dc?n-GSzHgf%a|y%&x!$CAiXa# z{mP?8RkwN(e(MPVZO0P!kaUyNSHfCTn^Xou#|R8pDLX1Q%6_P}(N&U0=Z0Fq4`%MfKx3`Vb(3m!_6{v^%#Hi$zb)s(CB_1FqPVp~12V1FwZDmdt zt(K$rQlh2H?XA-aftg}n2rcTA;oX?m4tTISexuI!`T$@hPg2@A{$HLMnZ)FuiUPKMA zz!@GGS9j^tAI)#z2UN`Ab+cu#NkQL-bCsVt{e4BwuI2Co?!Vc1_?V3?n)n)H`ZBYz z;fJ+L%FBmVfkLO3Q_eywFc6eGldXan9JW|kA1a56Yov25k|ZSJ=W(+EjRTX?as7Da zRKFz>FZF_YQ1a$@qFM{*n5!*luq2gJyeNd?gV~hT95d{627xoDc{R3cvk&!E>uski zw_V8@>>u*-O4p}dVd-6f*dMHQkJ+Xa=T~gI7TbD22VB9u$~+}-pYuI@=Ii_KW=Zbl zgofg6H0%!G`(1p(B{|v~R>mbDxOrbhq#^eX3^4}N9XBt&E}d(FsHq`;kBuKU-zc5x zqa~42G&PM}XM6HQuAaPcv`XDjJCwr=M_z^U|3)epDi#DUaPb&_!Q_NE)%Vb~vxB7Y*CUF~MpL^dsT>#XQbKAyOtvIo$07OEHkK3T`+ zD#Vd~i#8dplKZYD1w1r53A)>hGX?YEo*qioprQ&Lzc>^XJNU`U#1xpXmTPr*g%O*4 zy&331y95H8|Bguw`d(JXv+h>kTNf9EbEjbo%XG7uC^VDffiudf9S-D8k;?VH(lRm! zOGel7#u`v%Gr-}?`0ydlU!UNm1WNYKNW(opulf^pULT}WVe>hqg&}t>P0g7e_WOAF z2Rgc&iMHQGR&L*8QMP-;(upUaGs~$=7kDq@ikfkgYh;whz7j56!7B>sR_%#3{oKm! znKk|K73(M8LOX4J>aAwh8kF5_eNyt#KEuCz0CiXU-5fBon$7izk>B{5=p6ay@+;Os zzx1%&O|R(Gq3IFnu*QCQZ+t~Xj)}r{pVCW8^JMQei+@o8#?=VzK(m5asi%!?B~rm5 z&yo}QoE{C!M7-;$aXj)lW(vO8x|Iaeu=NJ^8MLbh$GtZjk~?X`%*51gNB$C5VQrvrTWy&&zp3%^lDlm=PuR@sxp#WHKphnO|pP^Tdl6s^tE@jx@mqQ_O|`jIkcI6(#gBUM*Zaa@;)a z?m9Z$bzN&%*j#u=`y2}|EX>~>dIkB?(vg{1%lb-HJ^fjhq}Qjjm_2B zVc_x=&v&?IqQ;p7guv;xf86EkZNonAS{Sk@^O;mrV8Jr7bh3{pX;2mDkwF*WOyh}N z722gaq|u@G^3$c=&fSZ0M{_p-Me<5H(ji|m9PF}sh7kPP?t*3GH*X%aGjuMLtwi+i z#<{Ku;C!swO#$TDwNDkz(+@b=sNXcMtgBMZgTYJzontdm^4@iAtWuZHW&*@8y7@4e zZM|^+UfbRE%LRe`)y=orK@B%=AHb(mtC@t9JhDQwP=JSoht1>9;?e>oH#}EbwL$i-TP3qPN%QE9%HB z_KkOf|HZcdao*t2p{8JRFAdGyl1g|=9SOtk;lA?j5ea;^*&g*aKfXuf>b%^Z?_naS zM3jz>XZ=NG+06882|9E2C(G)~;1J423|dr5I+yuS8DEo^}di zG}P1{hcoV#R_e;l`JAkAnK!_8xvVYXxZghB%lV3>S zZ43L)DyfVd6GLt=N!#iMt`-WD<@?gH3c>@S8j3hz01G5gM-5qX$7(AtDEuEd)3pkz z1F_Yb?`B=t9o45lPDt-R7>REdr^tsSacaN$QMnX27T0EFu}Vu^0C=ZDfBpu2wz-Uv z4$YKJb*9}EAR^BmwS?C8Hqvs^D2v~w`T_F*@8mX>==&p@BBKxg#u$K3lCd*(W zgU?LDVGhr%sHhQsi&!mnO7w^jsnJ_eX1e?G4pXFR;g<-4fn{ z*fO0BKlC9PI_wc^gH?EB7KEz!Gr@Tv_R!5ekl|xjmR%EfN2b7d9N)?3{_qhY?(O68uLdSde86)PJxuNQ`LsapB z=eOs)SmS5v8AS`EWS;&eqnUy1dNp4It6>ZFxz>W?HyJyWQDvD@-yc6+nt1>1b>mX< z>!$+Jex|sc%_ZEA^&OnL+Q%im;d-TdG1D3yRlJ!60gpLF<0A2hN8-kw9+R@gl^f*J3N-{Ti_aAm8~zqQkv1uB?t)TAmTxbwT` z(7P1&@Nr4?R{9&(=L*18k1u}D+hA2;j5%Ss!K4 ziVFb|p0S4nM#qVlOO}i(zdgNXkvk+D$^usPSV2B=XB&34r_Fl0 z9Yry;S{YO@(DigdH7oeP&3&7X63)U(CdU7Hi)JH;^LK!i+V#5 zh_RM6LWFwx!d|s+QwP?)fx0U8l|8*LK{YwQtJxOL45$DQi5$d@m3nwLA$l};Z)(`P zYXn+#iC+=%z_3+3!;)uLHe@W?Uy3xhz~uU3^o#8MdiT+-xD}GyyVNg6 zVqP7b&CLmNnc}H739UndkKskd0?q>xZ`&RjOVZ?*@_DvcnxI!q(tt#~HyT z%q-68#kp^f972PLa$9=CrUac64%$cv@bRMl5z;qO>xoB);TK-I{gdTdJ3Do=#J9Kh znOfj?@6n&E7ASaX&HUCTW0i>gnLJ(c1PxWpsPrv{+Tzavdc&4;sDC$0SR|-@bFm!U z!Ox0x!Flf?KW}PalW22&>m_=`GkT_IHc9c_PzNQ(@jL!r0FoB!y217dEU203G$qE> zaz3aga4?)))w6`ArcvK3K*gob>YQ6mmwv7^mF& z?*gj2{PwdVnVFe`YcmvutNUKy#{_Y3_NCY z_|yKKw(NDNc$*pjP-@`-3M4bUEmsFl7TxEO#q!9E+GtFMSuvbhHWseV~Y{dX-`uw9{hhzFC3O=gFuRQ`Wf6|=KT#l(2#-Wuf#(n5-2VN>f?L$6P1%pYk@a zAP%sJFCg;`+P=ROx+m#7BgO(~M6kN`H*>&+&V%iuek!B5&By!o{O(_^?>z|Dw-)GI zSl#nq^ia`U70s!|S~t>EXiP|il=}YJltu=0v}$0?ukvf+GhH_2Te>ucSMW1)b7j{5 z^4#xaB~r3{R6eX4m!Wv0Gfloc_JrKt$F~7=7P>x4oM4?_$jjpirQE5XnT4UiDwDo^ zz{vP<8`*h-n1R9n$(>=utLd)E#<}a)qxTJ06MgxV>YF&%iRw6}@K zI_O-f7ce?$YdYwXxi+TTB$(y_HL^#PGVp$?+J#cFiGnm0YxxWF*?$+v?&t^$z9|6>|nApQZ5QwSyj``MWVeBSwPoXo1a}nb7 zGz#E6a2dbrbapeaqJw1A6@0JIil`@4{#hA*m8AMkTQGKU;BKEbg!S5;?{C~UeVxrW zpHI$Ay}1!V-$wq9+nt8og`KWKPt*yO%N16I2_1#4kp)hgfp`(Sblgsl9-Lm{wyZ(q z&^ixqOc>+XVOt@#o-;B^U4tq{1AY64*HKs7pL^8Q@|KoQz=V68#l=N^@t<<9UfpJn z{>*J6bm1U>?ZMN*#tyQoj{eCJ2W|P0owzk27$Z^fvWhGZ*0asJ>|wLhwn@_Jl}Kth zu)BYJ7T;Z|7zQ*mysWyT9)cWIeILaY)TtkEJc)f*8o z8uwLD%0DhSRsACzmj@lIRRQ`P9nkcn{}z_}eEtdcEr8z|;SK;iiVu%p{RixhwEgbx zE+a@OIwCt}Kl3ylt<(NpNR$bo6zK5LrOTZCUS$3-amb ze9yUz|Go-3J*x1wNgCG64c82Y32qy2|K?qHe3)Kx;Hn zZdk~nEB(FW$4kYp$1tCy`Az@QyhbzsJ{q$6 z0Psra13(9&tAv!T%%?z9q&v+FLg#1`Q{RmhCD5S(&lOx+UQqGyi0@dHOzQ>YEq1am z>np1r^Rey6u#*a|ydV1ePXv}EW<(UB2Yl-sH}<!fXae2&BhHE0;z+ zHHz4uWQwpoj2qjouZE|y{kDv)2yhbvhL+R^IgN_fuRnL)aqNFDk0}5uVeXCE@I}YOjC9KW z?Wx79%sOa1=M@P&faI}OVv&h}`9^o>Qwmh#=Y;U|Ga^8m4V*fm;5_Sdd5>~qEXaE@ zX|hk2h%a=yVUtVY_a=1$uU-md-nu#S%>fhv%yiCHswL_FNoKXFh+n}Iux23qzf$u6 z8mwypeSF0X1x@n+%20pcg{a^D^a$&46(kSvDA6glra(O663c`hc&m1A_`h0!UX`&| zzw@%tW4b##Le1%oeLw*ADK{}O@oE;lv^a8f{MJ6B1-hyTZ7u^!6zrSbxFSQ0;c640;r^NP)!RZKwA+WIPw@v63KH?hNpS>?O4 z^<%9yze{PG50K@qo)uYz8SbBfsPoaIPjAK4UfeaB63Kh7SQ(IoH~NO5uRB4Y;lOq? z-sB;mnd?&$6DN!Pn!uX~Ts24g-}?ZWmGj!{-@kwTcp0ENfz*Fc79_g9ejCFVlrgo) z=~VY>%P54c&Cs*D=}4W@6}{}lIE{@ru22A8(5^p+toTcZA|aJVfOxse3;_EvpTb+d zzu!-$MGy{D#8zucW4zmu#RVQqEt)o693b;*pv(E`-aK{Y5@=3;tc*xCN4QQ-YTRSd zs79FEj&iZ@|I{jkAr7m#A6)r&0)qdiZ_$G(OPb6B7EGBexB9v!zm`wAtbp7^Y3b_1 z-Ezb25v(JCuK>%-{9r^g+5d_vgUu9;Sygx6l_=hSY6SDgJr%bnbUth&{ko_R&T%~dgu-)d207iK*$C_DE)`nh=M|KEhp@0mml8Fl-T{|kY*XhDkeHT+GGDKw z2!6|XFf03i3u)15T>3RJF&~l+zOxwL%qi#CSAlW$bl?rvlaN~ZALU4therMew+~7Ko1i^gxlX4a*;HX}?FbUP9@+JN zA}N5t^zxFfKUN*>86i5XD^jT2e(Vr41vScp1B;d2gGj@wXUGl}526=c#gC7P`4O%g z*8bbxFAh9v&G_bxk%k5lD{Jfgyu4*ElLu{IDQIb5OGsc04GsDFJ_b?S+pam?8OCPo zt2g70sYoFjH7TxF7;hJXzix9y#=b~DVHxj4@pKVE6x#Clt@cLna*S+x)qJS1NS;V|#JA;XfUi^3ozd&&AADtPHY{>Lq9mljXFrXJo ziLfrJ%_$~&3ED9ETpXil#r?h~BqTJ6ftHBNhkrL=`2Tx{cV=c*yL>>X`t{qlq1*>n z{z;Mh#-JLoRJOCy8mUYC^`^ko5j7v@rVGPBY|?;{6>w$6Ge%=r!yru#yXOjuwJ=-) zg}@)Pv;-L1Wc<7S`hF4e^On@>g4?ae7Fa-)0=&A*s1VfE-23lY?5pe4*4zjCv{MhJ;(%3Qvtl!Z7{Y^B ze>b^fRKMWenD{ZHA*BwY>_OOn#QV}STW}tj>(g{dYEcLcddCN~Iy^JJj+4%{nn0dv zATKYCdH^j4cPHmHLu=+sObnaJH;M>wXPoJBKuR$KY;m_c(p*Z$)i3C52Ejmo+}!qNAQ}*yVbLne1J-fH@ky% z?L-_-F``q%HfS@U)yk(Hw3V1yA zbhtQW^hwY}r;4gjTw%wMj2v6C)wh<}i1@wZS`75m5i|+KvF5}eC^+W! z!US-n`rjfz!cZTof(eU#iji`rtxM_Jx7c(qU1d}X?Oo|xmoMRZ=hII|F)Ql@4qYfN z5r3VCUs+9J;j`$YjtR9XA(Zum=694RklI~&lQxXu%^O!*mH!$I>A7+(cFtY?gO_Y` zKplxbczgSYS6O(mkbRyr5Oe0QOjl{zF4lYPh4+=gv1mtgtxgTD7&@dj+L+3FtNiQ5J^PfD(tNaggT zwKSt)!sb9s97o&BsniH~2kyPu|KDCfZNYC|pp_>hBio-^Gq4gJ>fq;qO*5c2L z-kX3n15sunTonB#5U<4F-})`0>O_6C3U7aX{h2;}Z@auA;m|<)@pttNs0#kN-@53t z&pBgQi*}mZ2c)R6MxM{65d%vjqrGCam{`$xDU(-u&70+c) zY_{v`(qtnT7H1V@1;(RMW06;9GIg!-(40mQHGRf0KIn1Rzq5Oj`ueEOj#c4}3Qnx| zn^3ZQLBosXZ5P*Q#q7E`OaMHBt-1hx!GYFp4Sa}fRcJcRnam1=iF9`E8NhD@tm$2) zJ1y6y9mSfX(|jc}7KmD=ipi}I(tOqQ1-Xz0(Vxc(*w+WNB^x`>+fOjMq@=`6VK3Z& zK}ErkK9eLnXhvD_!Q;nyGxyxk3bYM_$O<}SarH}LQqos{LWnz9vbQEWh`Nh6+le}2 zaPZt3TFU-@mX?veM<*IBoI3kUvoeMDwy_z*Xd>+1!dVg(sJrQd9Fc zea!*WB>PT(k;+_$jR|3q$^}y%<-^zOb_E=N=js(o+_sgCo_a;1QoBqBiZ8mJZY0TU zVUKE5*ZQH0HUn2b`^SehR(Z+zJBwwkBu_YNh;0FiWJq?MylPswbY{-c1nJ+2QuOt8 zxW0Iq!hm`?kO9K#W93_F0aGNlJ~REkK%!uJ49lu;7^#gd7CL;=5^2xL{GhM8)wdcZ z>B?`va&^ESh>A)kuZ?JHLh?X}J)^NLRK1Ocv5r*1ysx@j>*@5xl$@9}U7T1q%~pRl zHObvBcaPWtedL`Tdfzb9oNQp|H?2f6e2z3%Q&*QB`Z-?XKD{V%et`>Ys6dr1RrEfE z+6&^Y8UORBg=oX=A%@MLXOl>FuXp$?UO%GB3fh%S$AmWYFP_XD9p9oARZ}upVyI~X z?F%lu4+Tb5_p@Q2*2QfW!thY6L-ctMEiaN%sLYQK8lD^trl5XpvBi}mcjId~^u|Aq z(&^g|ztL#%JAap>6wW+G`)T8YA$;Yewy{aHWDeiwqTN6jtGQco+_cnHc_pB5XXT;> zSc&<318@JaaMStC1L2D}HrCALEe-mnhoQRk=XZv`_+Hja`Hf#gWsd>l(mgM>xu1NO z`Q@n=NcMaiv*;GVdSj1+fuQcqn z%8&unA9j|`9!R{f4jxTJb& zJ$QgaeaCdGmr&@9Usb}BR#yo|*;$`Bf|+~t$(~;-FEzW#G_|_@P*M?(qqQC2Qa=1f z1hW_%=Epl}{_{_D58u#7b)hde#hOH!h@}*$Y8iZj&U@Ap1v@5&N--;r1LQkP?*1gW zLE3uThahOT)AQoF4(riEn*S2~a^hpVKMp<^Ry)@y^nG4PIQvo?eo|~wJLVBkJ=dGf z>BK4i>iog@%M*cLd~XvhZ(=gal00|fBofP25jd1HIJKb{SKN^ucZz$8Kzq~fCqCUt z7A4WTm>~SLrrYJchB_;C;Ec>3Fsf+!*6Qz{^krWBZ+*|GgFYygKz3Y`%SYl%pueA#0T% z8;gIFCc!)N&s%$echkQ9{Dr?#$D6+|eWCNaDyXW(Ua`=W~Ve%evje&Lx9{w=j>+`3I% zX3@cKLZ${-=Znq9qA>pQGY(Z!y6t9;`HyULl=-v0tDDiwryeX9lUeiM#yf|9QU77> zZ1VhAsS&v?AFS3;&Yqf4tn~0tPj$nNoPcM$cU5L965pc+Mo6|)$?B;$bx5Y5X^%{3 zdNOmq(9M#*?2BJ^aN!f$d0qDn#Fw7zXy@D)(4p zX#!!+?r8^OMLDmy)66lf;rJyhov;P&+zvj=UO$zXB@U76ew#e^WO1g$eiyaDc~8`5 z`|zy5juP|-Q#pdPLjgLv`z$9EVumMF;`C2i>McdrM_Fl4MOv+GBTGvx?1T}t$mGyj zWmeG@S^iQVAOvm~9CB;1p!c>QR!p(6n5<;^CQi>}l5lH)SB|qu5h&cXDlG2i=jSiR z)z;PVm=DlSPfz#RJORLx*-l?#5R1l~-v%Rw_D-?kPv*<`37#H?@XU15oGo}xY~cj4 zk`ubLc~5IM$-f6(gB}cmMLAzzU!d!H z;x}FRXDMasa^%%+FY2!%_d7X*!5XsoEtuigU)bTgl{}B7B%^Q%_c;b8o||P1;BEam zAMt4U8aQ>hBVeq~4O+FVmrvZ<=3?vkIH_T9Q@Aa0#=XuNPw6G5x;_zI9Cw`Ac){mH zOxFamKR+kXLua)DM36+`pbiO#m!>{M>ta83oq26;S2BqR;c?we4Bx#qVsTLv92prI zvjG6O@N2R_CCG@?AaQPq^3gT}?7{6A_s}^p#K%Tu{pV9`>-zi5y{+gKaaVfhAg$8l z&nPW_W(HCY*=CQVMDJ;;-6`XxaL4&vs!L@2P0^E24jO$)?PZOQkONKFp6+Fiw(p6} zonoJ;TjMJ$m(!9<;fIUGwMeZJHq4Yv2i^yvuDcYayv_K^1KzQ>8V|UU-HT_jwqo_f zD89Yr)Q%!4ia|)trZny9gyX>)!x4*I@Eb~nwmSH+@uE`1yJb~8I7#UNi$ng$K+fo8 z7{2F1w(a8?dQ@Ppj>F&4@d=+QV&5sb3xetl*+zMKaiw;xTg*Sk#FiRqt4g}15MqojkJj=j5+v$R zm5g-r)7sSOR_=5nL|8=b42Sv(9F4T{pze8Br#`Hdc!8dc_(mksa)ap04>j21Ch-k< zMh5G=E#A@SvO_w0KQE#U6V!Gy3THl!Dr{^^Mxr}%36V%ts>J)LcC)$thm8O3!tUHX z{oXWs(IgXVM3h*T%uu%iJg~8u81?MylU)j)#!+sA)Kj|LU9y-nQY9Ngq`cD5T2b$# zlTL;jm65f|WyL__d8IY6MO5{#Lz4lfgTe&3tkD5M!UfJ#!r_wnA*xTQJ#3AJFEh9p zlVIWo_Z1Aw(6g{yIX0C+^NXK5mX}DU$m2pC(XlA-5BT~LPcaB#q@=!gf;C0k_vU7(E>G^wQf~f=u-u)b%6+D19zXDR^678f zq&*R&j;>=x6x_FZRpdGbkv@LYRQ)R@;k}M3)togNX-Oay^yyJNo`k{YXFhjll($XN zybQN@P28oQ2_wSNeNOQXEvNAJye-J@$pRV7&yDhkU-ZRI<*DuLSA>HV) zq30L}TRCgD=rb>z?GwubDJZrJZTUkG|DHZ6j7Nu9MYLMfh49mNXzBgC2Bf-9(gPGOGdQ6D76c1_i~Hx8Eq_< zYw-4L>P&-wn*HdFJZ2`wDA(Qv&!b~=%CUT2^vUbL$1D4jN0Xe!1ioGQqnDNj2`)r* zI__@=Nuq1{-8h=*iqq%gdT_kWUv+h5ltlR&LdW0x&7KN+@Z8d0F#1)_yrmw=btkpw zC58W&t=$=18zaNL^ZY51{SGYVJGX!AindZN`$wsjYA-vNziOwUIOVB~f*c5VOS~~t z-J;&|Ju@}%%X|7BePfw&BC4)(-I91P-0nqx7?0d&MN)0Rc*kLmbG#7&I+uB2#1wDe zas6VI&4xuB9)pQlVJH4I-#Jy{a)tVUCDBhpwM$7sW^?INV|RQLJ67t_;^g6QxwFFR zm?gaBTdmEE^M?Y7jqOGowa6TQYs8y56195X2YI^uLZ_z0rM+=0_F^w7;^lu!?rBam zni2A;8NQqPbEm>?JeWJndtSZbXm!5d$H$m-nEBubnA|!Q;Sunj#sB`p*5H6KzY*x7 z)LQy|9S;GLt-pu{t}2%P#_tY?_CcH9#067yKF(&4S6YruPM>M~TJbaM_Y9fEgsq4; z-BaHCvQXbRv<&rE--{>O^|qln*|Q0CZ;abpMWpu8dY}2w^}jvkoQ1;p3<60K&!==-_H2=U- zMeB@TTiSN#p(6CDe5nJ3zFV8mLvPiso1*5rgPu-Lx|uAoJ)<0hkto70i*}sTuH8@# zFQ-9+7VRK#EVBeTKPQE`1Mrr5kH&sP=GF$7y!$~8DGcRI4WiHW^J>Pc_P>8>6PxYx zbMVH#&T0ApL0;?0gA4Z0@^9B8mZN-6;^xvU1?S34eV(R@;>X+!xpBj`fc>LSc?{Z{ zb@EE!Y@R1`_B+Y!M#s=maLQStTkNorxC&P$5$v^mBJ_(mblq{gJgO5S6qI_0r^8se9$^C0{c4y2?=qLIy)lQacD_c{lcxTEr<{ zJ?1J5>v?3-GKR~a>~e3oY>2`zP4NH*e<(`jqequs=37AhyR@0N`P?_DE$f!RZ`a$0 z?)%1v47qY*j$g&G>V|q0Au-u+-)9HD91>$69QiO^fc&h3e@4mL(nZ82#Dab5ze^dlH%H&}$cAT}eAvPS$(sHJlkYf0W%3!_Zn)ZHPKM z!hXH+S6%KP|3jw2BR;$&{wEXYYwiTQF{yQe)YzmIR5YUJ~>*d>4c?(lKe?_=1q>QX~#XS-B?;12@4 zUUYRIcTCiFUW4w?uyB;<{LmwoRAw9a-K6T>&i6Z=d0Xf2#uM||4BAY0O>Q3e##Hmu zG4&@nLf@EVu%)MGHq~AJ4lXEQD>sMd$VD^vrHa=7?o+$A&`I@`{^P|?Cy46XoC)1* z$Yj-mW$HYI(8YJZInA)^Xo_}=_Nn$AS+xZ<3CATA^`}!tUao0u1Duo+c6~s(YGSqX z+@0L!!k3Yj)Y80oxN>G10k<$j_e4X}HU~>x9JqPj^kNpQTVbnO_vnq~KXJy?M%Kn~ zAicNOwK-FTHP5^!4T@EG{Pky)N&eaiz*i5x!Ja&s0gSbKjulgY&e8t-`&89D4DRA&%gro@J?l^FN3{U_Pe zg;z>X*>#E-pYhWBSR>yW={3LeKk0k4;54)4QpvmCT2kWSX>`W0K80)-Mf<91*4bMp zxos$qUEHpcl^)DC!B46}zc1tekajVxe4c8%^@i%BVNPdy%~R$({kPZkTZ-ppySSg^ zCNubc)gOYbO!Z{dC>LbL5FWgrbus8EG7(|EQ**ph8x^J9(8S4@$Trg2-?S%YOE+`> z84avy&++wmspV*-D!F*cp$e(De+9B>wm-C&h-N_kh3Zai$)fFS!`|a!@yVvgx3#)& z=+dr9%FDRrJF^O5uYb2TnLF11rB>e6!|J6sI}qJJl08dwvi_0X-|B9niJ1B66p^Rz ziAvHKD|NF@I5svZ^^H)k_OGMHZWn!h_GJ93WJtl);a4?3a=!&XTje>06pU)6OKFPW zh%&KEhO}&qo$a^l(I=nXQSF~I8=8>G#_ExGP?-g zggrx7hxT5_n`}h6@p`E8Ol{FRdMMBMBvkxxCMozo=W9|sFNey{oyP>nRJ-H8mEws< z5)N&+cAkl-4ym}N%HifhIyC=nu)v2MG#kevevnw+C`5J4Qk%>)gPNhknTIe{QjQ$D z6c6vU^J%_tg9j` zf>dqm7eRv`^(lwTF_WfJsKnN>41G(Z%U6zkWPlzZU`TA|H?&2nTir>F|D}C8YA5t%GrW1KMCpYMsehXMLpCJOH|yrV!5t*a z=H49nkeU0lLZ|;V2ubDU>q)hj{cG@=^<2Dn9`mStC*hl!$^%SF?b#;d<#Sf|s5K_uf*vED^ ze2|)v84-1Se=}u8tM{F;4u3A(cg)5MrOzict5DpL6va)RVq&moM$RcPFeoRrH6V9i zOzeHky5w$gc4m5>@AC5+D(`XI`)9^DiJv=YJY>Vbd z!f^DB9t56*E>&mVa@c?Fe@>=oDsA=C41jIQfA_rsgV}YEDvB4j=sxqgiH4glKGX<4z)W701(|uDf=dCk79+i|B zY@piJe6PQ|if~(ft}eN^8VOj=%q6?-x#hE6pUVMV+7h;0X7?v796*WHj$N}((>m3x`1?v6bNFP3FL)sk2Kd*n zfAP{7kV6eehaokzanejBekK0f&QMCJ#Gh}2YiObZbs%Gwiv0lG?>H|i4%D;CEG2WrtfFjBewUWUPR_@r7@oRC zYt>mjn&MR+%7rLku{6MImBO?|b6G0cykZM=xQyMD-NdJ9n+Kea1)ItyD_YFkk_+jh zdrm*nASXR;Gc1bqK|McibC&z#&++YbiFAE#>+uTG8LBw+6_9;7FPM3Yuy_AfKQe7| zcJXw%S&N4+pd*}SxWp#9Q;x58s>_?jL{=$ZI^` z>|oHsi!o&Ku@s4fVTO%bXYw|+g2YhSYHvfpHb zq4Kqug>6S)rqWhEi=6SOXamda;7~#llj06TOS!Z2>U7>xE1;F736}@X`k)L?9h^o< zTBt@hg22Evc@om3GXWhC6SxO(RD{RUBn&Y+Zv0skJq$ z^~XBvaZVgU>Q4rSkU!9oS5HRF97lg+db1&i_S$?-|39|gGAOPtSQmy6Ab5fX55a=F zdw}5X4#C~s0t9Cu!QI{6T?Th|cXx+xllPokw{Csw$3Sh0JxkjAS>5b{&d7$31Mard znDT=im=a1kT!lNW*33Mv^YhyJG5^J?g-96wdo57PlB zZ~IqD0+zZr3qr{Nvio7Bv5Kg40Hy@22x4g1r3QlMgc_}3tT$aDv(+7@mHyS+A|Ek% zhF{ubo!Z^`*`oNS~jVIa{XHS<%|3 z;SV=qqzw-}vT2zg%#^q{1^xq(Kz@Fg2l&HKh(060?V9C3&m##;u=MW>POhliiWGRM zN1~I{EIvGFjn$v$L}e%zb8?2LQ>B(T5N2ewzK2<0)cbB>yEcARGoQE8%Ny$Xi)ajc z%Txz%OYsREo{;jruAsQSFa8F*Zj9v(d#pKiXq7Uk(PaT64n`X_MmDQhK`9J=aBPAN z3h+^Y(3)ZAZ&jnAd?`_&XCiMI_;TfxK6VYQ%V*+}&BKKqHZl3rwWkUGwC?kAV!Zon!LKmfgH@oxTpY@8`4vt!#Wq-&HF&m^kI6MP^Nzs1 zI7U-UR^&MhOAYQH`lcE&FkG-w{q`)1UaM@0@Kju|W{kWDxFUEN*>UDd)Rwm8#TK4a z>S6IgJM$o+28_QJ@`3CpuSZ2J9(6rF?9|is;JggWaKJcIvVjN0u zd}b$PjMA*i+Ojpr>h_t6t0&wYwg?3|uKRNXfd%Px5(3Wx72Xm_zsNs{M6UyWAiF2d&fgEXVr)dU)d}ypFit7 z6rA2o_&Gn^!x43ZZmg*!ifWzmZ;X?YUgw9Jy(c~3-m-O18lS6VtqoufmM8vCc=Nq1 zoyk(Z&L8 zjOmHqPrGRDEDbSE1ET2#zYsB64iTS@d?wL#daQveskt zai-$_X?uGm><2}TTEosm%VFB8Gu-abveiAJWkj=st9bAskJT;vi=g7nROzm5lgN3R zZP$y=n9G>$)1U+1>jl!Bnkgo-V}WzmEszBNpIpD(SK#I>yXtI-M%^LprhA>?gPIT_ za%6&xs`enh&crehh|$3D-0h? z`S~#!O&RS^Oz0Fu1PxNq)|i_CL=3x8HQsapCr*KXw-i6oeN^$4+djlE4SXyW!vn+L z9Uj7@2=bJbs*>@sYf~ZNE`Xc#`Esl9QQ@MQ!H@0k&co)MlQpSdS%g#eOCSrV0Plz$qav*~_6a84MV4yf7*{q~EIZ&Glnlm)=z#f=B z+(k9pd*xfwk4tS1{VPze0qrK`f_MV=Hx`nn-^)Gm2nl4qek=2crI0PLP~3FOY4({% zl+*uMQ^}jJyXVZ=bkCaF#`sAerfk3Rh@_k&(i0#N=Ll~{i0S_RU^H^+v0^nQ zMM|Y<+z&)2Zf-59z@xRTEr+H+;5c64E?kRtw$y>P&j158gksUHlv68aHBqSMgonQ) zi*;X#7goauLmb3Vksb#6`&aCKM{FeEG}7zCWHE|Jgkiwo^PgAK-oBYt0Ri3RZ5@1m%c=ZNZ>@T)uFeU!NRITgr&lPaWpakZj}O+J|eBviiMxyIQ|+olUdeeL)IP6f*io;Upgm0 zHgkVW(|U5DZI99|V(%=e5=`7Q@CH4U?d zCtJctU;RO{>p4a5l|3SkqDry&F=mGfFKduqvU2=DSHa4b_kqAiu&q3jI|3ZYf za;qnh|EBUkA1B=4FNGCh)>2C)&oYCB`3BaGm9lKswG=N6<@AMj#!6vCP4;4n@2cK$ z4_MZbP0~)HO5ol|k%XTpZ)7EqXLXCSmDu-xT+aKq)(q|F;Jx zyr}#D7rkk#|8~HJjZ)#%3Q^V6>%RHU7$90N0r7MDMxf05QlROpf&%!W9tiXcb#IUL zOqNbv07j`?Z$8{WUD<4CN_Y1JIKul*rEFYRt;*3c`y6# zUhw~X8Jp%jV=Ieo-3=d0FEhgQXQ2{lm_pP0mHkONjMw6DiUv{-;!4@;))?ckl@Eqc z`C!J@o%aoCKLtm7hOAmaXW3-@!+xW=|E)v%|5*omuAxWKAaJ`2;10Xg(%UFU-9h z|0fhnDL$Cs+%dh!QAl9OVnrj1PLt8cJeb2D?-?!lsR$%38Mp>RAD2foC-11_SyeTj znpMUxA$8Y{H{9R8m5PPmwXQdUhI7OmyZDlL4`2%on53sV!^Y%Dey!i_x zr$b!aaR+8`pd!Hp`9A>01gAj)Dy5yk$k_E0K+I-IrLM@NZS~*lI>L=2wD8bbc(gUc z6Ij*(@8f(lr0lyvcCF(6%9!k`{9)j45-dI})JRP{yc3*!L$}c$2n+6|7_w{|nntH% zb2N{?TM!n7YyX(W*w&kw3z}re$+lzP_ucs_Jv@pYxB;$+4iJm3_CZ-ct z;9Ied59ev}DU7YTK2&n46>-MGl8A(#SSV7D%1DQF#^|58QlL>Mb14 zBA+7)r?Nc;7@aQ8)hzpVTK|)RZF^Pj0F3kSwIGX8=35kyV`qR+rH5I+k<&2mjR;+* z>f9mzlPgcSN|@YA=+G_NI@i+w_+JQAB?|H>YT|fA|EBbl^@l>!(naOA=P*Nxp#HCM zO?p(s7TG43`SG4AkJX8BtGtAiZKZWv^tKC9AM0p<%IuzHKphJDVAJ`vf}Vzf!AoTp zXYfiM7M*tU;c6g2T6K~C4{0&NWE39wnKg2=vfku|@3#$l6e-xfWrWI*PBi<{-cCwkRB~1JbV%( zjZd-pTxsX^7SFfeAK(4QcZ#8zQsg|ZJDyp}Pm6o~QlnpFwC(;A7gir8`4tTX0H3_r z8CQ^SD#YFO;As%{9o66(3k)9B#hU`5R-F7|RxYUNua?io2vrlBhkuxACY!8>^VvkB zaJ1mB=~(rV-Db1E@MC&nD{Rg!5Nlm(u`-2FN{buWX3Aqv%NBN~Lh&epuM`stA}6A# znnF@+VFmrZdyhIfQuXZbbLD!Zkjc1>T=a3nXfjJm0thR%J`ocI4;=~ z4mKcs_zmkGwzhqYWj%B)L)a@*#@9UutE2xIQz#=X_8Q1yA22b|6(}uJy!*s59Qgg= zMVEkpD>ZL6rQv+mb{Ttyk14eRh0e(P;aXF{y4!#ujz~XrH-Q zYuWTh=77e!lVL*IQDPIN%uyI-8qTI3)V#?y-CqF?%EzbH;ha(@ceW4EEs9Ejp@A!O zykXk=(D4G85o>Q!D;_|WB+wJpYGM{Ln5Zks&Q(9z8rmBhP_N=*Vk&2y1GQS}tCkWW z%=A#bJ$U`RKnL<=VoXnmj}!NQQRX};PGj*}?SQyJsqRCz@!f;!ep0shi(c&VW z%R8RwJIM4uljh*b394Tz-c3U>3L-%dyUb#*0SceKFU?0g+|cX=#l@-Ii%h!TUtHA$ zR9|T>FoIaMwOw4@f*9lhZ^EEZLQmQ6xAa7d7;9tqsnW>1g08IRg;rD0s;=bWcg-HBS6%w!l|QMgsNLb98(dC7n_|+?ydqPNr-} zv5MT~HI${;&60#QZzL*X>gdd$1KS{mA}t@?AnLDz>V`?MM%I4XEHgRRA)_yzx ztt$7q@&l2dgG)q8^R>CNA9O^YgM-i(GLw2#*sIw>(90l~(B@*uXVSiqJ!zfTvOUvh zkke5`71eS1Nqn#ktN_=&a>vqWfG1|bnEln#!8748|nagG+ra_8xk8)Vo);m zQqGG&awP2Rbcv4kEFaD%^F@!hc$8Dux$Ymzx>7DZJV$t9g;&|yNfcA6RhhY6R95yC z(Nmi2JY>miOzDvK+u*ckt6-kZM5WluLViQvG5F)kvk$(veX8<8N{S$j(&>_ld9tW1 zee}$h{gd)Tz2MLb<5KIyo_~DORV_P-*LpJK1?Bz6DkB6~CK6w_Iz||2P_5-6nZQ4! zd(fe53XnTODqW$W9?{bH@=<)J$>J9S3CX;Lm}XYc9Ufq7#AD0CI$G>M*1;B6!qp8h zY7D5HYFv76mJl9|0;%?%Hdxn%DiTVc3a-py7zwGEV|R7noj(krMt{h+zTJY9%lR|} z6mU=NC2$`)+I&21E1Q9g-dgs!n2E@KkT#l5Bpq^dcqh|*1;^#oG92W_apYD(LBQ*& z>X!YnkNBsa1UI+(MH`e##@Xk=$H%qTGuUF+*H6ArxQs7{`oC!`f<-2cRS6n@Juc4X z-B&FJQHgG+jd38Foq$yEy&I*}r41@e4bnhqy5o75*o*yyG7)5mI`x6?J&AgiK?Y-0 z8hvCw!d)I`CikqLz!vf`JeF=qy-Dm&1l&@*>DdIN7BXKQ-Btv9Imzz~RH+iHlZHpo zp=J9(^TKDuDQDMLnc9Qyu9kyp)em@`nD5t)mt%n1d{CtR_*ID;a^56qX)``A@JVDW z;HG(* zJ@?PX+>gRW1R$>%4qfL~15YM(j8F1e?_6dw_W!8dzZB1q{4tPvKDoW@o-8Z(xFlQI zgMEyn*?61`SWAy|4LMzHPOH7EPgp1m0hmjy&f`iQo5v@z8|_S65p{11@it9$$<- z*dOJ{Bt3!+(^@3>lDdlTZ4mO{G3346!gE(j5}G)pv0&>u^NuZ6JemokT1EY*Fv2W% z#3pyWJ5|}goIcU=dKBvH>qGvL(YzB+Jvo-a&*Qwijqj}Vj2padR+MM2v?gq%Z86y` z$h~X)>4u+p&Ot?R-P`5OogsW}d(Cj@GPjzvGkUysG=jA^Rt*gmho2*x)>oT{yScuu zcVW`c1xqDEI-T?5yoag9WNSaz`nFfimVVLU4~C|95^mVuFm^u@Y zEvE30+ArLVytR?-p5x8;5t}(|koR6Bfmk!%p>3 zo(R?+Swc@VMsRf+JIMCy@p|9PZcS1kv#CLmz z%c|Dnk=<8Ut}KoHFmX9Su8GEk=Ke{x@%c9JdxNsK??zr8u(04UDkBKjb`{xtVW2m% zSi|V#iUd)w9i?rTn!USEBp!%OO_AE49X$nR$N>KeXQdH(^s4?Jc_Zi$`#G zyx$RD;xFD?YPqJe^ur~e-0)dd6*<5yqWbc%s1}yk?0eU))_mCp=W^=pXS=y-Bop#( zk7B4nXbvj_uZZujN*ZqXvX4JEhdmPca5i!w-n-BA&Dhcuazc0#LS+%gz0C}gF1sH< zX&#|D#)jsXF2S&PZzLxmyVj81Re8;SdDcB z5r*UJUavL;s|F4m86uCm-X2J0o|SAbE!$9KTAtZki~U&#mA>|l~%vtnD9>;e2f^4m$YunGU*2&Q9md=#%6Ei}sZReg6wx2XHv%27z@t(Te*Q>Ix3cGh^Lv=(ulPz!223t32%Vw((~@>2dE=P6qXX^(ez_i-qR{bsnAJCf6M{!Skhl>@#8uA<$N` zDVp{s&kipA^b0xfQgfi7En46GrZK7oCnHxmFJ>~eV=0B6x!O%0>9RJiaN11j+EUz% z4$WpBAMK?{#Fxg|`}k+?6tae8SFbk2+FI-<0^8*3Tx0e>*%?~1$}TI3rPY8tE!83B zrCAYkS&BCI@WLH1OOb6|qJNcmgPrl1n(HoSh*Kv}R$(ws%&aK9>E?kIaWXG{=O27U zQzwXVGqR#;7h8Q)w5N}Jw!P3bhw>8AgFpz@VSyi=;|Y7bVe(4A77z4tTz`JX3zjC^ zUGu86v|N8W#S2Ld8qM(AYK+Jb)Hm;=#t})YyL+nYXC7RTKFB2m6zL@ix?5CCGJ>)d zd%QONR4sd>Mpp%Mr9J4?r7~w_kJO{;K;Wt5S0^ip#a$SU3K!E&Lj$6NTt)HKxVvoby1O*wg;0uk&3jlq6^A2-1m?B=an^pd1}W&85*ry}`ThN#0o@KGT5oP=+9Pfzc6_w8T~vleyej1> zI%%jOOC+dq>|>JDrz0Mm&{B=-RXfUF2(U~`M4EEhrg+h#i_wXyN1-EpvV5f1uLz$!9RS%mvFN~z4o)B2#vaUhe4DqSPFPR29tVXzff{JLdwf4zkjv3(j8 z<9HJVKcpJAN`9tn zsEtTJz5=S9G1&!gF|nS0o+`Op%m6g0aExxMEygWnt@PUl~kI&@&1i`WLcU{ zrht#5vax^`Z9NJ})x}FW$p7Y%7DGgAgiQi@EFh{HjgY9^^O>IoMsk>@ND>Iq-6(Fd z|1)ldVjvaM72B&HIusx$ zjT)ze)CTmm;$n+8oMWE8mqYS{{48k{^UJF%yHN2}E)l3sV$8Cg^16NrxOhGze0qHn z23zl@Umw0_q2zLOliwKmQzWJLxRha$X6~^95^%lGKd8+ymLRV^;pjg3rJsD|?&FX0 z)P9)ss%zcu8jf{$F4+V#?JfX>%@9f1f+ZNR=N29}wlm*R+my|Ir25L?P73Wg-j+wr zjH#Lr5d&44%KFFs?-icCHynZ(h)a-`)n(R6NUUXO-J<;bHn$e19qIIe^^aY&1O?6y z2ZCSb9d%C_HA!1Kj$zv65K=bu>)xk%^R0?U?l2QWVoG@YHRW|(VAS&J&VhIE)voCI zDK^%+D8@gU{Tt!-!y~SJ|58Ulvzr7=) zlTH=>p&jVvJ4ZZAV>)9e!dr1a`-drZX(K;NeVqf70h*Glhb&nmDB;0*LaehZd%}t| z%=h;O3ZjtvDpYht9-H|U)z$O>)#K9Q&{Py)o5bL}m!^MCVVGXVacD)r%30gy9YqWZ^D1+ zL#_aieaA%NdkEoeN~(2p58A1s3$H5hnh_Qq7qTqx80W$ar%pa6V)*X`aN&+fQi&@e(oh+bNC>ipVu}{Jz8#zsok6nOm=zMd!Gj4%y0j!uS6hA6`OmU07dEp+WZ_3 zIWmS@g?=_>7+8xhxn5M{WaLTQ^WFFdYjP(c+|Zmm(KIQpn+-)2-*e(L!;Ce7s4z>l ztE&T-;$0AF(iDOthN0_rT$)U6OtFQm9}#cLo)dM@l2GSv2^y>WjdvHy?s=32lS)fM z23M6uwIXgjp=<_&es11;t3-$3F@>$ISVwfZJ`upJ>Ja760Z&Yzj>(m%#tnRmaFd?f z0o!o^A(lUBcK!$rwR87wYZi8&V@il=XP`+8x6+Fop0wX15&BNX;6LFshT@BzgyBtL zt1t;3i~-4b*Ep4Ek8aoVHpKdSstRfzjJ2Eq)^9!T~AK7_=0 zB9I4El=}#TJGB}drD%f1^UD>12<%ifR-x&bJ&<3UK{kb4~i_xL^T%Ilsb zZ!L}>R}(rie&ucl8(|MLLZTDSFLx_?z8A&7akNB*HeuS9V$Abt*8Iz{cZpp6$7)2~ zEECnbebGeJZU^Q-i`u048|V4H;^~vq)zo_h&-JBmu|i{1`88&Rl3NUiZ*A?a}l)H@-BB{@i}3 z2>XaOXtRZ}mJ}p&rv~JuiF1bSdnjAJM-{d}S3_)Ms53BHgDQ4V$0SrT?G}gmB zze`pnS5CIndCy{$?^ur3Fh zH6KjA-Z_YT4G5J}noX;`+H*{o;Ouyzq2f5dR*!@rhp2%?;^fe4av~;d*>5kUTD?5C zrK!iMt+utvjkSb~BX+tRy;F9uDG<@8)2KwT*cqg|G+lhr{!vY%!H`+}eul;ifA=N) z>2iBl(+>XU%~XXzA9(+JoAn9E?i7sGbj@_2l|8 z-bkO`niqZAB2h44m>Q>38vpz*^hZ zYN0%zn}{1b9f>#W<1sb`{s@W{Xe$7qk?l&^|8PViw%%{KS75nFu+aSElmklLD@$6=8B5Ou#PAtPbeHQ_7 zlF}4E|9r5X=b3<2%hQdU#Jh6{$>eJ4gKM9*tkk8iI=sbcDV^LacUY9>X^)ZQW8Ls#|8-j&0gZXWa@0T# z7M*7mX5c*?8n-!j@ZI?1I0vHGtY02Z9;U#RlP?|1_5MO30nR9QW3AIh5xdE9jpOvZ z8i0-e7nyQ3b{Czn%3-&jRVQ3btOEBGQdjkAYj|DmKr zAJ1M`7xT*`$^AW9PKf-QY{%Q$y%(&G^XiH_<%?4#$CNJtARAH#XqPY?A#xRrXzVK9 z;}7m$AOVErrO!i4Ac*Vum5Wc{>Jr`F#2;Y@FTQiW*v*gYn#eG`;QDd=;QNd{3(BUK zDGDZVBUHjQ_g-X=QM|e@n|x?@UbrxINa+_JbCFX0MO0ah+2Xh# z7`%s3$?B?vb1rgj_0c{&xkBrdz4{pkE)8y4^Mb9T+H|MMvAMZ#X;O_@(;)JXOfZ?> zN1()AUIod7-dY^8_||zpCBjniv{K-6F8*++ypQ*n@!DM6RrMbywa(4W!Mms6q{SUgPEe2FQ%)bEi{D;MJ;IK4 zRc%1%3sX{VYOs#Ee&J1;_tM^emk%DAEWJkt09c5>8vPsDzb*6(hF@z3AWj9bU$#i2 zbQ{M#E<0$2dSd4PRLXgmnUN8|@RkmLwJ=Zz&;DuPs+hV68MqTa(*^)2YK19W&XiEF z$j!omR6s)%P;;6y3?x3Y7hbOy1p z77y|LQ=5kzs$;|17u5%(REWAA8~)1ym)$&w3$X5U#IkeDQjR1}_7)p{--W#|vHk|z zh8L_*3NJ#QWIj+xHI*BcGq-8sZ2#K2f63V2SLR>kr*s{WHAu=sg9VC0a7r|@%Gvsx zkQ!K{&@&6_+$(dX-(%tCO$S;!*2v(qXoq3*`ZS~@aCnMmiU4O1|0c0_}A z{}^F!5XS|_a)Y$k!IrYmin8*73mjT<*;lsxTd-hOjEIjZhPsBh^ae-qEkBW7URC>Gw6E`81RPcM}Z2naxl$q&MEAyC=iv|*mG!LH8E4~U4(mYby-btjfwwQsZ{ zBz1pxM{l*n4gu7`SD{qp1a8Q;pEXEULP(%rrHOVx2!1&m53>O<6*dB!;5g}k%Bn;i z-n_UQMO(O4;ZV$&#ojRN8UX*{bbh+y7KD?4;N)~(NxVc^r1_C$i8B;HWH}5we_5go z1wb`LG0$pR2cBlsH!)VyXgCKF2H7(oA!y;#S~cc@@qEK_*dM4IS({JW9R3f7$0i3#(yz0$4jx6e3gmGp`k6EttN6R zttn_e@OCVyaB^T#*Z~qKR=hD_0<2wlOiK8W9GVd&(p{C#iJ5sxwK-fF%i|yksnc2legRglXjlvWob7{bj1%_C>MjYvQ12Gdd`VW z>c7POTI>yB%TBIEKs8ws{)Yw3$ciqXB{Ve6;$C2D7Z!pSX42d0lW3^;b|v*1Kqidm z_&?B}bJIH)I_8JYl~g$z*NrZka#EPW4QJ#XRQmfVNv?!~vsrXU;b5lpc02%12QuJj68LRs20lU!IdhDk{6Pq$SB;m$=cZ)yjgrZ4?YbD%dBe|VWIB7ZpgC2LfJ&|PmMO$ zQ3#(=U6kjqd2-w&1rU>Obd=RJCeP7-=jmqlw?C?JpDE%sy~GQO(C=n_idjv(=minh{nvKB>H)^SU1 z?HKv-6EF&3Zy*cR?^0C_OH5?CXKq+22SV%X6*JEY%aKi8b9r(n1}04tX!f+$6x40a z5Tq@`Y@obKr^n2?l{w52B#xmJHE>sd$8R1co!DB!TX3!0DtS_V{mKdttY`!xw>>qi zHOE*GrK_OfeO;ctAWCOJ!$;mdGBV`CQ2m6nL-uH~2qZ&!ExeIWp>!Eqo-)(p!a~3p zQN39=QB{raY8Qtz+jeS#;XstJgmn1%GqdYaX{M5mmm}$J%OX>-IatQFS-N1@t&Z9a z>#lr-CbY=6cGl?5afFw@W;dV3*0t8r(6S`r`ZXmeXs&4Z!ujj}8IEMs)WsQrVkg}XT_Aa$ZYB}pv3|yo_ zND~&?8p?)HdYkUQaRAB^=hJ}BDTF9eo(QR>ehis9NahnEGILzGQx5#3eV>?<=lh&k zdNbNP1Fkc8RvjpIHIq3^3kec6L{AR^YEu3iqAgWAw^KiqeudBb@{3Rw zAr#|69s}pBts~vzocZBabfdgBwLkF6R;C~FfSzPBkcI#Ih9Kt8A_9fU@mXuth46}x zW>O-Bli)hegC=;4d|Oy`?Ee!R;_4P}3 zyS0xAP7ylI&-%H`H(w7YkiJRlU*4{s8>`!bkj>GzqvDbzth5RIXF|LUK4UMc-5tr1U2-rZYD=mTRS{jp_*+>~$v^%A2Y=6|> z|Img%Y+Dv{WB3ddRRKzoQZL18`^k2GdG1YcIJ@W^oQ(QKX3SvFiAMc${Kdc5YV>)R ziJ*Sda0aiKn}l_O?Y!UjbWY7>VpLfOhsG~#_|)d`-gvx7MP;O6|8*|pJ~I%F%6U2HxZA-MlJrKzk7q5?|U!yi(eyB9=e z9^$OO6o7tC=nyKk$Yx3~TTcpZS{*GxLD9P&kdzR@Pxsz37dvGM*NPl5y{o4(>j$q? zTMM^d#@5R4uO3e1df290ak#$<`gK#EuGvy?P=%!0;tcoC*^7{KD;~WiTpdJNPc`wo z?9cZ<$DbWIq7>COcT8u*ybctbdY9X*aLSu0KT&>_?(Vx!fv&I~dzxPb+NGeC33;@q zl)Z{8H_T>s9)~tKJJC9q+y`oTdk*-U=bjBkn34jSJ81OAx@;}gX-kX$<%A?(>RxIt zwisl44L9N5umnu}0THhD194qf^WF;+?vaWv25PpW%(OVnxyG zsgO`MH#w4QlKtRaxCgs2gZC~+BTw41`KrOr-QZ`pY5bvQJ9n{q-C={-LgAqn>vvhS zjnRjMn%%j?q}F>qTzs28fpO(#+a4$QY#|A&xw7hOZZ1gHyj4->GJN2gmd+1XH#x3# zgAMKnvg!@7-h0E;iM%N&tXL4rkt*E7%Vk~zDhLEyv4eDml1B(0Og zRwLUs8s-**JeZg7PGsdtR& zsn$>%-)kIAT$qt)JeSexiKd(IdmWEQu6>yJrzX4odUNcRA~iuCr2iQ3Q+oCT^FQea z$v>;zQrKc`V$w~4Cnmh3g-c~oBzCxRfmhSQBZs>RrlqC5{%z^8?gC-S2 zHPp5p{JFl&1euEJa=Iu2_h?-8QlpEzxVb-`nOoy2;p2X$_Y&ORIoO{$-0w~Im65Ro z)^$#8dzTl3-S!-{6F4IOEKy5JHQLy=A+JrR5b1*%jC3`)!!5Rw-m8qXoj|6hctXeC zT5sMf1u}$#%-5sgxSyT5N|RZm{_Z%}U&gRxX|IQ|FCI zn^k{;5zb~U#*<$7q5e4YzA47S7S2joXl9ipcfqr1vQKX{yyW+9mfpqpx@7r=T*Vqr z_UT@2?*Z-jHsl5Lk&2&^m^;eEqR>uMR@Y6H%+NAptv$`r(juiC5Uc|&JNT@DC4?5zLk>S4L~PKUZBle@4vZGJFfZKKOz zEBZ03t6W|)UQqfk7R@Mr=UtTqE9|vJXq*Uv@$I3E4$7~YAur4@->jomEz!J@{pN>W zf{=jsc(}8ELkYGlpD_KbL}1SE>=%JrR==Qhz~{D)?rJ=SpDne1RgFR)^1g5tU0fb4 z(;xPQCfmZ>Rkbgou`R-|p)~h@txF%$-rDso%X8n4<6Yuz{=$>@ebM$m3jZ5mpyRpl z*>`#@=tC_YujVyx#<7_Af}9L-p-G*&tm&Oflq2`??1vf@%q+oXiCKP-%t-0sdMY#V zPBAVCkYUeXl>vq5M%a_&7 zIfV*>wN((Ts*B}&Z2|%p7Z=n|Re!FEH7`JTFIwkc>vTAO$BV3NE%G7%O-l9TmbEdL zsv?WELow)_hRzJ|m(J^p{ z8y=*2bGj5_KI>FnKKi$avy6ok`>P!zck^?F!H(=g3pZb&UEtvFRAuvFcRd_zSg{dH@z5`6g^Q55^A<1rxZ#>}5mu1fH_Wb|7>;;X zG^!G0$Qmoo7WS#7Dy>)HbV<*v_QQ0>6Y^T0!*6$oH^2x_(%k$}TrX076p~`ZT`&7e zw%SR|Cv7Q0(!@rIznwGgYnQX}BxDifZ^}!=j63~~v`3@}s!!(ppqg%?^dQjf>GugW z-KvSZ8+5M!nXy7!%sc_MN%c}k@u%F-kebTob~aCPTh z)fNIq;%tG{y19-m4(?(!J{Kn%@ZZyf2=e+hkL6 z(R15dm+W*%()euntY4Zz&!(nF%Xgn{b$CE@w;CN59Wg&cLh)a1Wy>F(S)V+EhQeBk zb?(U0oE!g2G&XX~oqr3wIW-);0eP^!YUehu{Kj_H`aa0mM(UT<=H2a1z2?nd?G4CnlxIDKBYLJ4RgkC>~6oFAEP)Ns()=1D@NX)?&|)~6Xaw0 zPeO1&u>>3_K)klMZ_ZK`e78hgH#M|4bf5W6V^dwm?+=~_&yoSokZ@?Hco{j#)lm1Gd>PD7`-P(Ja9!b*fx1xj&$e!)jP%Yw?8?5`;WU%c%L^~p+c$0 zSN#5ACw7N=;_Ar55q_dwpVFh?_Guy$m#riOsQyMi(N*+w-st?5z|bVl>ZIgH3qL4j6Sz8T z=EfOq+zjZd|GwHx=xlOv{VCHd>3{U<$Ux`)r@hs~#?+lr1L?xHSnEF%}k|&XW10+swDGTudlz zI)s|XC)UG*U$W-VyscH5+9wCvLct7sgMW+NUMUl|&^PuEK@us|%`D&gxW!YG2)#~j zC~O!w_OVr4pw4Vr1Z-)s=gB;txXn^yH7@&ys5>Xij^goCRX%YTI-RaaC9zr#STSGp z55Uk7-fr42e*03^j)BsI#g;`MSo{;kgD3g*krB`^3kx;o`^!zv`|{A!4e^p>Go@M* zii(PUpeCgvWu%+AH|wEhI!}i1;pSMwXmO(_6t@_Mp82cq*o`5TWR%m<7t>v7h=;3! zyZik{$JLp^Ig1M`_fO_cq7X(oUUECNY0aFduP;nYE%U9 zYyKcuiQ8p+d*{y81$ASV)W)NZ`f^UCCBymghIT+ z*mY$sMYA-xt!t!A*#D36cbl49$mO({Uu@+O<8o#V zIhbrT&?$f;rEzx;ygPf>3pMq>(F2Z^k=bMuuv^H3ig2I{+Hz;o3K6eR-5D7WVQ|Go z`S>cux|24nib@%4O9BW1+{Nn7+5t*g{2Go@sY89hm1W8&*+;*$z#e89r#Uy-^ZAdQ zflpD;?;k?Ui8V4bToEc_u_!M$^*{$y=@K}N7$d;Xr2(H>1n=Ym__|RFc7Y z1}Yzv%sX+6dMfjNPMbIcIs5B60m@q`AV-PfRdZuQJ{V-FuIFwDOuOX530SE;1wY2y z>k9-uAFfRIh~8Gp>;|HtzIGn#oEOZ7yy9_?e-BEMHON$ituyd*rR3IM8zu-s?TP_u-uMM5T z$p@C~qkad-*`T1Q3}0Vg9Hq3}oSc--@wX@Jfnd!1cYvw&ZtdhaxGByUDk8Udp?FzM ziDd`a#XbBD1w9SR#k(7;^{z;X#fsgX6G@Q82=J%+okK0n%VApWIhXPojJ)j_>sfOh zS2GR5nryqe-!t5R5IK;C{^zKR;une`tX5Yu?+hpPZbtBFqY%HvF#aA~T$=kfJ)VzE z@zn=+0k)3(gqxGb{%DhyAAOW+k$z84PNj)leAlAc1h~%G2W65`V=S*d&QXdnq3!{~ zB6~*9)IqdgKM7t^HB)>6aH-Zj1bMkIOaM64aGPSv#$61t%ItnVY%?yrAP@GAa#|lm?M_Hb$Kg> z(nBa-!j-P?eB$izBd1$NRqQHEb60lqx7o7iLm{uT+~g-T`f~2lCV2 z971rlSyF8GoJhhU2w;Zf;s-t{CH4L#VB>s`)eld~NJ=DnUaJS*cgTQIZ9Qh{8x-aG zI-hdCM;`o3a4@=4_rtCKhi9Ql5$}*LS<0;5W{Qq$E>doyF&I5fanGFu)Yy zg~<+H1PwCMKFR3H16mm=PCI&}C=c_Aa1%o%HorV;CObN3PH&l^$}PuCv1?u`r_0K` zz-gtOn)2mwQS>KgRyWKo@!l~tstc)M%Zq6S(h4q0;)zfQQMSJVC(CLX}K1YnwB>GO80WMto(Ys zsJa5Udi8uFJz2vhMKizd!G6NMnGHI~99dfpb*yb`#OTW;P;4t2g4Z`!sc(9F3RCJ{ z)Zwb_&0T2{{z%c9Ujp>VVHPE#gY=_A++Ji3{hOno4NK2S6r6uxYIDzkeerVxS`&HO z4>x}O1Dg<+EYF=bjqIF z3j+nY$wfcTdy565YVw1VN>f*Rtk$3HCg=GF$9k>|BRy2+@1|S^qxO_P`>QN(NE$nH zbe>!B267(^=__@V)J&fp&D~I3Q|Gj^q*AA_Sxw9iQJ|A{4_z$u_bIid9rK?o3<5zI zKN&&d{+SkfEhOGh1qOH6Fj`gXz_CGROvA-n$Gy3hHDawVy}j{9>l5^L0tB#l7q5j* z4N)Y)9>JfHJOn!dZP_PSfmz}qAk+wB)bf62Z_i=NZ&nMDaK@UeZ@`sqakdd*e&D!XL{S+AWD?mDT-B| zW|5q-tJi(U96OMOG_X^Lj=^2X_-am5p3e66fi7{-(X{aMt^I}HjIvS% zMKd|fB?nU6=LA(DhXC}J+G9;TXnRqD`+Vr1XE4< zTHD3td*N3zRRvWW@ZX2!Sm}eI;%WMSt}dRaujRuLHco-Fc2` zstBhJF!W!XeGiDIFSNn^b7%WeJzHH)vjK1gbitBCXUkmOI zY5Pqe4QA8W=65_1bNdDooA*k2HGo1jLbbjQ9Cf?sY)xy4YFR`<4PLw0D-DG2eefhp)wZ%L0)6ju} z)ymBqvDO;ii28tTQQZ4shY_)kQ+e8_UUq+<)6tGLs27K^f5BFLFwF&0*4D55;pY`+ z{yUP|#u1}CkZ|nsR49vwyFr*DSZ9EnjV-z475mD{`;XIIoneK9#lyX-D5d_%!1gKU zkR^s#3X=W*h)()>hr}rXIZF3lXro^Xh49`z%Uyq`C@Vjrr;xSEW>(oxOwq2*FYR46p~90sy`8%2G=bxA^_J36p@MtbIGq z_OI46UM^r~FvtRsZ33j7*>LS#J_7HgFVhbWrEwjr>96@dRNJyy6v% zOsrwzfrdSIcUEJ)kY5S@!qXRU$y3b34hRGpw>?0lc9TQUhtW~dWJ@q2bXVl~__$BF zB^@*jULT{XwIy=iH77T>H~2NS8sU7@U95e%su@RQo|x$*97Re@jLCpNtOaxKocQ3X zoD@w?Wu9bYZ7lkwZ!x0H;@6BA{pzXp@F6iyQbM+tETg&<8J*iSO3Z$JRMo25tM_r6 zW#ACf8UBLZ=*BaIdqM5u0C%neh-@(eaUG%#+=^WpV!Hr7QpZ-5lFFL4d7ek)=pWyo zRL|wyiP08tqO(s9qDpR?$PD?*nTJa%-p%Q=`@~RzqKjNPt^hm}s%*^d2WsyqLPCZJ zc)m00U#s-&X-c;EZb_^^4|DPIg3ixl6Qfy8^(if_XXenZ&f@Acx{E2#^G31Zl4aSV^q%pGMVQUi3`k0 zsR(tdZ<<;jQ|~J#tGjHySoA*63SZ_5kw-^HW|1momRJ0>e*I32hUbDi33RC3cE3;j zdT-ik9=c60K5DgH#-el1StX7K@fp%bcrKPe*U*2)y1{;zBO4?& zZ#fD8~#^) zz<)q+4|J&^j#7=X{k6WU2YV|oOmKdv$ZyAWpFZSL5d;1<(-31g_>xuUhY`4 zRR#n!r!`kI5zp;v0~-cu#yU0 zaA_*^kxJWr{rWYAQkW>HCz=?zepB5tQ+-6)kWy!T0v(|W&Q{{OI6YkixFG1+*ud_3 z`ueY>Ii*RKQRUejw8-+p+rf=px6yE7v(^sX3YSJep{e0jGaza*elHSG4(!TAtQd4O zG!bcOQV+iYkC4#Vi=)hzcXGN~M5$#`FuVEVf$)%Z17O@~UJl)6cY)jHSwR0@3$%*i z@HZ~)8F_eP7_U(<(6gqVo>Ck-Lkl@#_X2O_GigL^3^F*;Qm>pV-K%^XqM355|iOfLEj$})ogOsL!gsuXRAgj3T@L~;BOryu6cS>yC z{NHOP@8o4XCx@avnQ#!dpL3f38mEf}AWqu?mzLEDZnvEQpPQjJdyp@ds+BaCdzU_+ zyZ0Adt5Z4^rh*5fob?2J_@GWC^p^fy`lC5dnww={6>ouEW>{!zP*NJ^WHATKuu@kU z)RHt2bZVYYR$}`78+&?}K3n&k@ZNyha~0ozJ#&B|D;Agin(sh44k$nZ6GA1)C?&uI zl#=#2f=%M%OaX)s|9gzQB<`EXWz5<4>zC=~aJEGqX}C+*&VwPOElvVhHy)U?I$W>% z<)mNmw^3sc-c$4iPYfAA$SG!i;G#eYijT(y#FS2sn9-nd&-p(+o^U|?BX@n&_-MhF zm?TpPI?Hu`i58>)aVpofrJ~A4d3AS5O9OK;G?e0+hZS8Jgm#ZCyW?g~OS@A3Zy1Sy ziiWpsbDBcz3G&N_eomPE2|f^=Ia7&!2;RwmE2uK#TM6)b3pRwFh`Z%q6Jv5><6q*+ zg*`%^;U|oRBdI@p>#^AI*p4pKF)?is#1-t1PYAeel%wV;nvku==lJ1Sm%(C;GGf8) zV0RGUv8=rEB?f4$+Yo=V(zT0HAut0?%`%aGn8{i_d*&)9*GB_P!P6^6pRaT~xE|lI zZLmdjfmK5^OrA%y>9VFGq1}WDtcxO<;W_0BY-{KbzT%;>BH25spqS~2Ip-7_^GQ-nZ8bA%p ze>om|o0istm5Hg}Mncs}z0H=JhNk$XpT4hOW`%{5nI76iFHzcTsl1t4W{McQp0#be zlSPHUL-`)9^1LzN^|lc-39@x|KS2}m96@e5pQn1dJ(!odZ*}fJG?GjIpY)tO~u)YOz!+jc-deg&OH1vRVYZ zWaB6#i~x@TJ45t`sd$nc>H?LYV6Vn{3^WwxcZxg3=3NvJ77he^XY)o(1S)LmGy2uz z;R}-H2Hpui{Jh!nEw0;1HSi<_esm-sAPB(JzCFdfiIL2@NI3|n9DJ2K;5d4HAQ1JL<3c|?iG95-e%Ne_HT%^ah{kK- zNIaY!`18Do;O8G1x2%2~$-**@mO_)k>_-EcQ@?wWj61nIkO&g9+j8sT@A{^anvz@I zrooQN{1e(EBge=DU0=SjiL~W5?S9JEy!(^u>!T(Y$?c~8RYz+lZ&KaHm~5tHZIfuB zo6+i|YZI;d#-8bU7Mm`C=0^MZ2w?FD1q@v>xr@iXQ?~#%LNkl)4X-OsVgodjZx4cg z>I?y52vjfJ*<0r`z)1&-KCxko_6)^CFDe^7X!Dz!6E07<#BP1*?E)4foW?yAGWp_i zf^jlF5EWJ*t!nvr^poMBT$sVKy__}T-+ZA4x`g{r?IM=pwiR6Pqakn`255kaE7sYQ zP4CUGGj{GuS-eUH>-o)Rx>^F^Z3Y!ih2ybrq=@BcLW~7X6-s@eY z;L1CU(DBs)N&kVa>g#uILYN>R=}CK6LCS4`v;kst8T!%YZo8uEYPQUl0^^KH^(#7= zHk(>as!dUhh~^+Hs=nK);2{+Vo|z)5UIsJ48uRD|iZ8n6@0Miv0tegE_4skj_Mfvq z&$^~mR`$cIDrD#U7N&_nkRa3BXL?`xQerN2$?WCHh*N~XP9nu5dqCLYdB!Iaj;MiQ zC)INgoRHlZ9JQiBELjRN2N z2+Jb-(ji3Okp58$*J{n}e40~YMjeirX6Wtm9LwjRKXDZtOqf(?IKX@LYong@;`N7Y zHN#94Mwk`5s7_3L-lYs`!jbAK^_qi*k z8N5ETL`BP7%BuN)Jpu*^m&ckO}+uV}Tl^Riz3>r2#{HKHhAN!Qeh zS=*jb?T`AyUh*|WmPZo5G?Iq_r8(tjl5xIqYmTi!x88+kor7A8NOlM6_*EGmc)3(( zH*+_;2_xRKA`Z$x-}j(XUYz<;;wJHG`kDr}8z!~!)8eMMn0;PGyf>tB(>b6aU34JF zcx4*7}qYTacSKKaq5i_c6#^T zs^NNuQ9Y!v)4QO+`Q;))>Z(&|nBJn<@md9}#T2C~v^nW+UexbYsz);O=A-p8e}>m{ zv6b+r6?crZu}KLvA@{>s9Uqq%ugtqty6e_j^eWdV9kq9I2!=CC1X~#5Nlo^JmO(s*}K*KPGGgDpPLkCZO17M6be0HLRS<9!GHHdQ-{UG+)vLe z^kf(qklPj#20!M{>73Ww6$XE=XsY$o-j?&2RC~ZG@=8Q`Waf_E34bnjEnvHI4JCH+ zu(3dko^8KxRq=Tip{?#NZGAX5A(FX+iqRrvySXBgY}msg>`VIvCro#Iz_%|?Ai z1(Z)LF)Inw^zDst_J{s5Q!O8%7~%1nk>DHZ+`yq?H^X~MZtLG^N1u|U>s>kbVk^wM zkUEXThWa;8Te#Bwu#g{ayb=0o$+8Ch%1yd_>RbK~pT|oKIq#3+F-LM6ex09o^s@r>i0TDw_tG=7TQc1nfrLY-0p$rq-rtXT z*Q$(fk8(xw058`zerEjaQmai~(&&|%3lKO9bR09#aT$kuE|l@}H?OM(sfJFC>JoMq z<9De2ayNnN+si=YMQ!}?n^v$soeKtuole-@Gt9ZgHmE}UsymjT-y;MOb;mJsZ7e0I& zb#%JpkShL*y`v}Z0hE2C$mx@wq+EG3%Q?UO;OR3em=EX59tr8 z$=Agr(tVafr7*arVoDV8jN4~^=Y=qAd&3O{&I`EiZ2*iB)=}#RGJOD{52Q^$_ZsjT zngV$mFR!k6PdNY@jG?Nk3b?faR%H7FN(7)zLDK)16^(b$+1|JUz|;86usGJ>3~ER7 zo&WS6*^{6tf8wk|lIm(jz*qSmejb?WI9Hv|?O=IZB~hlY7eto(;R7!j<;u_=CV1mN zu>i4mh7VwxWLf??P5~jY?Om_=o8I$sF1viO(f%;j07l}xj0)(awtp{p@cdsA1&EwL zq`|1e! z<&=OHVll}k3cocUy{~WOd4(-Nlz~e21ziO>BNb-J#MbC-6(Xm_eQ_&I{v#RuGt0L>NJ!vN`7EWX^6iS$a%X}PJx!Rx8S5>~m_F`rp$^p%C!@ay zA}(yjPkBOm*rdP&A@a-BzedSUWw6{hPb!w2-UON8>FT$d)zy$_Q<&$-D&vKwY&xln+knGL&Ud~&>>6MG zhcqN`YXddBodeYz4I~n^^+4IyDS6*2ep3#FES1dojjp;8G`xNRNF8chYm2S_H0t5s z?(fs}O@PObrl4LKykB1&K9LX9Y*_ApLfa#=h)SDrY`slvMPp(*j3=0s{j9BBiw+kO8HQ&D{7Ic~Z77@-Vjmx&Z|B)oK$={)Ut!ADh?! z6$M6>+?wZc`@mN5+MN#WH#c4C2*wtm!2kXWNJ}<6oGlD^TAjU{H>xAue(Mvt1TX^6 z{kN>Nyhk1%98^HXA_+1f!4{;#|1M!}{t`&*QhMq+WQM<)*T}MRqr?;cXwkO^9H;Vx z1eJi-()?K{=(fsrUKC|`z8rhHSU%yf%nXcn@+bl?E2|=qVNxKtbk@g~Dp~+{$O3<} zm}u_dl`Am-nF>mrtgqWCe&1knc*5i#x(&o6MS=~?C2=KzK9Ni3RXH=Mh&&k+Arcg| zW&>n4pvd{Zm+Si)$jhukF04mrdll4BS?U1_${zZKJ#6KT{ypJ1U00ux3H~+)3 zW*KD9b_%Ff@kjY9>{4%hn-&EIHSjs`WE&Vys&tl-$7c28_r}|Su!skWT_%BP`4P6sr1?=u_)s0#l%hm#WCU_6*deF-LomY!YL?n+y&z!fFJ4tYG@DtR~-{td- z`T_LViqu?u3YND+dSn3e(;y|f%u*B z?Tn-BC26ltEfG^1Uw z%r)FO(8OkKxFU06y$IS_(1CDEhP)bnXEp%Ebs3-}N@2@Z;J*l`%6lAu$gIdoFhe}%R^iwvp578j$_ zZiBqZA8o6Bv-%)j@jXvTAK4akRQRZ0PoOhxSH#N z!O`&%M7-l;;2Q)<_WhnLTu;}$23#>2vOvG4psU<+I5qs``?tYqj*St&PxSKGNi$gUxnrEd@`mGW6CeEL!e|`X0 z{Qk}0UGQn^8f{a{wQzGB!5G*Fzdvq481o*Ah8q}h|5pyj?~KOCVX#k>X$D~_*THHlZcYnL8UZh#XTDBBXhu32=YKuOPX=YLCnPbhg+H5$FQnGssjv*&9% z1Kv`{RtDCo3ShhHaP2&7Vu-o-*qV}~>&3eE#*9`67B3PE{BF)yAeoovTExSY!r6?} zEffQ2UeD^UpE{a+ZK%@jsMm9qKOefHUL3wBUHq+SUYR`*i+d}*iLQKnGbqpG2cjLR z68s46%q?TnFi($&Vf z4vR8dZ{NZ|sn)^L0gHkH^sc10KR%;h#$fUs>32Ns6cO}B9F+Z~Q+{TVa~b_KX1~ zSEga}%_{WWrw0-Z;uMv;tu+E61_L=uDWpcmr>*H*NyDZmA-G2~akN-=Z1kcRT3G9=o`bsU)JVcHTGAB30%YN6_Zi7^OnKP0_T<`=Y{b$Ruh3gzten>GN zu@awSZvE!WM#+56MCFbnDZ75$QCgu871Mob$7_^UW$rkYU)~0ysc^haOc2#Gp^0Ix z(jVj%cU<0Y^FPugES1|MV8G+w!Vq&E*yuQSAh>AC^cj&|&OG9l-`I4!1+5B*ccIM2 zZfyVk>URcuO&o@NXXd@M{7E0UxvXtVg6i&7sts)R8qV4$S+CFbtxpezhI+jyU?DBapL79;fwb0_og0!sh)|Aoqud_KBo>xC_t%?^lrQc= zh<)~3hb}LKsB>Ez3+jjSN!Wd{NEQG1iyuu@WOHb;Le`^vverF=CNgn;c$@GO%~7^b ze5qa|N7Xf*_pzbkr+{#Dj3$@u`zM+dt;58bf(EG56xuC`qP$)nUwkDTjK;9E-4gvs z>Sjn4j)=;pJxCAbXl_`RpdqRWHc9)@(9rouAEUg7Vx~U2R#Vh^%g&CJ;?02P(Da29 z7b#l^i9i!Cr?~yvz8I_aMUSD(%_fE42l29%YV3-yFgY7Gemvxkq>>|CE;^xD`s#~6 z`@`um2c$vYt@)do{SQu2SsJui=pBNvF)OJ)XKF>7X!qZ2G82hhU;z05^StI*xG*Z# z*5(4BL@btW{kOm!oINPfGw!>*J%nDauU`H5;8#*Qg%98jpa79vnO(K0{x?!Jq~(*g z2TquBU$;N=Sojl>Z&D%{(|xg_zp0r~_}FuV#K7w?1Hc4VT3{oOAMZgAYJBb~dEh5+9Svqudve8h zg%Sm%)+`lYkWAI>Qp0=nVn*TQ;jAQJaHNQ*{`*;E5E@U{Q4cGXYMhb?MQ(JH&>Wrz|tLEXzBcL)E+RFYk=}O!%Ski&bk{ zjue6eu^pTslHR(dTzr`M%+5d0{3hIoU7b>t2hi#K?j(dz$h4Qixh^Wabmq_au4~E5^xp(y12!HsM%{nZUPp(UW*Jq$$S0#o+dbf)pU zQrx4Ruk}jbRwmb@w=w@hYy+(%rofb&pR`EX->ehEyf70Fzk`xjaU4F+q9ylsOOb13gBx ztazS%Dpm=(>c!HQtPALrlvW>+B{bGAtKKzt{i{6PCH+M5#ve`*o?=W&q?X^ZA88p! zMvqPR8|*k!#V^G2eQzV)axc7K-pB9tXbvlo2pn$nMO7A^49g><7+V8TB^mlBYFR1f zO|^nvmc6cow%Jd>?Xa6d#A2N3&mt+Xz@OdHHdRKa-J@_v`|4{#{z71>?J+4}2 zkhykg51X_^uz-A!mH5`$U-j}$#XGRw^O|%y{{&S4-hA2uGQ6U8L=iGKtR>3-n9TEP z<-yA5$czyo_Vb?~sKaF$rlUji^Ar6AUK8y+igNAi<6K?c493tVS(gxwCF3X3}9#;bJcXt5yz7$TsHaG3+iMH3|DO&WTT?!q!ajFuI#xU z*C@L+E@xX)O%-ca=<=T8J?s*;^gKLYs?DHCKY%+bfE*7~fL;KLnmc=WUnhXjOKqUl zgtNU{M2Fyfd*`69)#Bf^`ruLJtNRX_OSJp_fxji=-g4fo@+Ktu%b8B$l;rO0-E0|) zIk-yffr~OQRF6XYoA;yvR}f-a@-+&AxQ~ZW z#yKD_ex}N%&rxcG%}R`{nTa<)#130(>0m%5RX~g5d9#E|RyFCltlPPO0&ym3_i)_h z-;#w0xRaTmXFP=0UZuO5SZj1{B8P=d_zv>aq<;~@5z`0*MEBwhfDdLxmQG4NvcO^G z6SarI%2IvMgus%kD<2U58tE(C+g92EpLT6x##RBYwX4>x0FFGA`{onaxDQ%#YnCMg zH+Q_h_yh3Gn}7Hwz`-BNcrKSlEznOMc|32}$lyZEw57Il*vl=(r0$JCvRN&`(1IpsJQog=IVPRp}f(-aB zbT40qE-e`YM>*!!#I6HbT(`&WEfU6Z8Snqm3zVee&RZ)T{FG&FY*L1)J_5tHygd{= zTV>QfOcoJY`}|g%NRa#QJ%CalihFHcXh}LMaq3hE{VRhB)r}lEtW>)^(Ys&zsjbF5tS9+y1Hdko4z&T$ld&}T z8e#`-`;QzfQsLNvD!q56KU512JV5YY>V9=w}b3@vrIG83-Pr`^gO) z3xYVw1NnpDxA#4axN!`5Y&77zQ!XvTrm)LI*!~F^wI>!B&roi z71a|x9J@de9W}ieB-iq+D-^$-tpZ(HndSJJ*n8)E`BFXE`Eo$(a?d~+zhT8oA@*;1 z-l&pIFSO;f$GpgJ9G4sQCLGog#mm>yN(jWK{9CddDI7rapQ`8d+$(Qy;WfMhBmz`f ze1*)P*N zX(p$g@LDWoyY!n7^fNSj!Y9}1hv>WSfiPO|pYPdGl9@gy$^2Jq5g5L)ZJ}jV8C`;% zU_FOIQop)w!aKMRYH!=~G`Ar?hHjLsA7oQ&1wr$cQf4NE=A3em!3^sv#_eU ztj~Sszsw5UE*#R%Cf>EyTxqHO8POKwYB@yR(C3~xEtHVX_{bK?x47zW8G7Ffm#+45?QEkA%J2U9 z_G0)1bP~gQphmQK%wIkQgU;973j6?qN3T0La|~QjZWVxR?}v&lR0&<*;F~6kXMD=@ zrvfRd0nnJ79Hab=J{m4&5En}~xug$HX6k)%JPxc|w7>qh@ItCV)xyvodBjmi1@36g zuAbrTYQ=8*CdxiJG0wW6J#dWI&+W<|<}-iK$!f=|e0yvX!+sxo^=GC9E{Cy$D$>BgLJ$Hx^{v8mQBRWwAVmO^2>Gl_>Y(j3~_p3rf~%^ z;0z)a;4zX9u%_X5DnE>Nt3XJjkyvL{+xw+YvQ_l2oS3&PcuD?uiMT#{K2(9BmfwYA z7E7h#l+8O^-05b7;1?9&k&BCZe*87C%Irz{Z5G_ZiK$G~>bc45Hz@-oscb`x^z>QX zQr!LhIt4|&wcAuHrI^zP^XGWlfVmZ6%`qLr%jl2>ZsLZgf*O7PHhL4r zkR5|OMK*J^m}-gec7oHxwl5Ib{e?e)?!D0In#hdbyyP!5`o&GXXZeerHdEAXhW~!` z%BrnbJqJ?fLH@(>+M9=wmLzy(%otRa9-I-F@}QnC6U0;zPdG$p)2Ih395*^**`w+B z^_OtWrE1OAlxjQ9f2?ytP3R6qHoO(Gt)WsUZTcUwvCQ`fueeD1D&fZUr%Rl!@s4geV=k=FtD5>R_{jus&QrKt`BH_Z z3VnS9%M>Xmik(}Kz=Dh!i{nJO&RuSRFg{b*gZMgJCESQ7-G88s)@>P~%gb;0I+)na zN+G22t;0;YQO^4j@))$}@$t;sA#)RexxR*#4!1 zmf$MLe`Mo!wc!-@X17t(K85RbYxAGLUB6+6;!HW9q<%Fq*o?H+%QiAi1PWrxQipP;6n(qx_H9aFqJJ zwb3^$;P@}X=0&`ds~@)Bg-}2^DON$Dj@&!+DlLcE@mp`&I-$j@S)J90Yz}JxebmTe z>RlqGJ*DOhdw0<~TpzLV+ir~UG`sq<06Q{j^Vdp=@u1Ft&~k^yas|r4_o?}y1sD2> zwoPu^DC&!%`)*bZy-UYkmJ}H)*L!|YL))%h8(9D%uGa~J51rS^>zW=2Nu>nul;M z(`x(r82jW=PZO1b^0s3B(;+-5ZT%KwQ#BJS({wLEgH+XCU9HG#I?X7I z_MMP$*o)XtcV$$yzi_<4^CdydrP6mESk%5<7lzI4s5#!OV+54ioQT#3^ZWM>ZNij| zRs$C|R5Sx(awpq*@9k^Sxn8CPov@h()L;1A&Qmk}(C)k6H!uW=hYv8~bP&_YJlC$! zwBP4`7f%8S=XUUAa%#Q92gN6=rQGt~gB<82H{$4rkK{}GjG=KXQ7k5?cR>1<8+1;1o7~@weq=uM?a(Fkpw`8JcHL@rX0SE+}!4o!e#k zaKU?KVCMFYxqL<^h?gVfD+CQM(MU>%5zVFTmTk3~F>(6r(q1Mut#8Q5Ydwz9(NbLt zIlSX5i}nq(DL-szJb^C#yu)(X=M-08^fz?~P2^>$RGjDuRv9jMnE~r-OzSF><8ffp z4m8eq9M-d&dH51{ByQDP)kaXfyd|26PS$NJmn;3WTXHb!tdw#w_n>$)9MtH2i5G6* zPR?%MSMYn!ImVsZLr_ceJ|q|W{Yr+G*9Q$JHxjc0{VoqNC+Cw;6RdY>!~V?e%g#3R zlckWBla3LRq%YlTiP;()_DoRdbJkGdu*zBCH08~>9ka_+fc&_)*J{mog0bLI z-{j)Tk9!U!uWis4s9Ei5hdrothC%=Zpi=iw7jcKwc*%E#Qs0P>n%>_dP?agoDHS*e z2?t3_WcG<{iWbYp)YwXzS9fOQpQ+=ycC3QHNK&&)mEPE@r6Dsj(q|T3))XBjn2I8e zo?LWrxG4vLS%pwX=^Wcqc#NxpYEt9DmN@75l=HFfB^iigryqN;w0<-qQWaDCW>P~$ z-x9*!H&S>#85B4u}?t)w5c(UX3fvhXP+)nzVrwiqZ=yFupri(*QVd{SEmT3E0I2*`y#Mvc5x_1*vIy| z;!Elmv!_qHM+#;h4^2OUY9)Fmrey>GRtaq4c|0kpG%0OvR3?v_Yt5|4mj!t)fBg9T zUj!UuuSmTF8MTx_@KbJdew&mdGjvH!fhY&K|h@4 z2j*Sz2Ry4&nmiY~K&Xr#GWiHTf?--SkBESW1?Fz9qG!B2Uqo~rNn=ucQiZG1K zA06Y|!IL=22+x2Fdj#{|vsvrE7QqH{DsOyZwD9U-YpeWDQx~T3O-F`q+TNY@Ri52j zL}*vntX)HF_w=6m_=#;*YH?NPUvrWm zZCAv!#rU<80dw5r#yaqDXjd{%gpX{%!m?4Y#hh5#aUo=TV}G^pku{_=p5XB^ ze_OZ)R_<9&F?+uUXm72GxxaLWFD-*iQa2+Ez>A}!EL0K2MXh=?G_ZVsAarDR150J( zRI}d4$H)C(fs(zdhJjm*b;h0#I0pDX%93}-n4k)IU7Lq<#hQEH!iSA>iv6zPx4gV( zlV|*a5XAci87L7c*6wsBbTXGqgv?2@T82)C;rY^?p@_}8-Jo1VDAU_N`)4hs+WJSP#-2e|d!-QC*Snu_Me-H?$IHX9us0b&M85& z22J~>_ki7E9g=WWR4miIyjItm0#OmA3SR?3lO0>vk;G9soOsW5eW@l)8@0ZDGQf6@7LV9LCSL9+4!j}L=WJ^%q7`)U(`8jA z&hwaD8-$6CO)nsj24wa4S9bg7J+lShjYpC&-pkJEDQ{vrL^sSg&j|Ut=bu%33a3-5 zbd0HkRyKAoDzUxE>)vRR17~c4n*>z|IsU72L}ty9)wMaqbAU}yUN=-p>;bjxTY&f2$+|H$;;qEG?TH zte#EKXI5g=_5==?0p>_OAIPY>MsRdCWwg4wI=1oXhkRIFZlv6!dj93j2w>ji%*u?+ zv2id4*d%RMbB_?Uc{pr44HxYD%VW>g5%{eCL#7fz=@?S(B7>Cwhf=YXN+iMz$5lYXv*Le`Jl{fnA*&SI;WXTS)37YM;c&YFdomNuhmYfx_#qQ=M_4<{P{<& zpt_FJRQ*GcoB!J14&RZQ9o=)GF7-TBXAJQ2_vSO!^`|P!-Vf_Q5adIUH>o{euW`ur z9U1VA024Ie_3PKb5)<-lZq(;-rRZyq6Zp)ruXWEi%*TE zoGzRqAN#xb|8VscP*rWw+LVekB3)vDf`D{`(nxoAcXu~PcXuDUySqV}L)W3Z^WW&b z|GV$)!BCMgIBV@S=Um_X=C|eoH8ruDAaALGzEJD$VTgxct@>-!vJtOFkQUziaKFnV<{8C(R zeO*sIznGV@o($A~Y;%E$TRmg+UL+;Lz^;Z!Ot_NXXb~J+(*+bAR0~2%fjquo4yw9G zPrp0%gQ%H$f}KwWji*DB5^a55NFoUD__TdbRQ^f>}EJK-gKKY&#!oGCI5Tz7i!3zero$wE9r zH94saF<4Z#5|6H=ozj;Mv^JAAVEt;FS3oXn;L4^2K%f!=>kQDJ`4rBHm<(TLZD7hX z)jtSYG8o$tn2x_FRwOe=20sms-lCNI|k2xO5#jLtXrSDl2bo zdOFO0-@)oeUgOmqPR#WfaD*V{5_kE#*`?)Hxx!eijw}ZpTW)b_qBoj4+*IGcaJnL0 zbnU{GQ+(IB1y>YJ_?WopD_d1k4|Jps=qngB16Fj${gF;h-IXss3^kUBBmXm1Zf0Hl zE~hK}#Z~X|PF^<9LF)+T&pV*w>-;$~9Uy{`Ze;WBh532bN{E{dF_Bn%(!&>^X_LNC+q zuU>^Z;dtRWQ?F2$Hn&qe-Qc4>-Lr>gKl;wtM}OXU3(OEWbMdW8W095Hl<}*qEDmI( z+qoTPXhv0Fg<(cwXPrmh+q21j38-s6dq|#dESy_OOi}{>sM8o9=?k=kw{7RLCnD;Y zqa8!-$yZ9m2uu4%MfA4FBCd>ajC0eqpDJpjBNS$OYCqJ;C5x5q?}h_uPTx*OKURym zOU$UNe8}c9^?g)fX-neFoxthvA;DpT$wzrr`tT}Zl!zGlq0&g|cjiZNHV5+;UGkMg zI=#6Fq$*J&-PY!nA0XUL=k%J?51#hwH;HC(YMtAHA7qZS7lVvxL|aoce4o}guk0kk z-F>j19x)??&g!jnm_XLG6^G5$CUeSsU1fnoi8Ow7ZRD3Ob;%c73HMqq)FL%5Eov96 zT$icBR#I^M%8W^BZgG+2Gv9jb$&wh|hC_)jCEw6S8^%2a(=^{3mp1R?!}NBAKinv_ z>@mhUZ(U^F--$awyhH9~(A$r{#L-&Ih~JY3F-PtR@XFYGxiq!qF==mI_<1CHxJIoDAKVhlw%>_sifjl?L-^WsBSM0&MHX>i z`2#M7SYvS4{`wlMa(^49Jv~ZF^R7$gjy2JR<`vu<9fXhhgE&2;*{4UrA5<^_j2Dt5 z^khb+C@UG9=*U9nZ{ORi))RJ=Q;`ROdyitWGErJ_%xX?5KPviu0MO#YFkL~G7mlQW zU2}t8o*KS-t}Hf2b9Autaa#F$*$%&@rR6Qx8PX=3{Td+-{L~bJ*mE%4hz5#H2;<`y z&uOc@;NVMyPZX(TC}x-!iW{N()9R%>+-0{=o;sZnV#!YB)Tjqp?K9}SQ}ocOUJUg zLd+0P0%*}L2s&m1F>ufcJ(}Nz#1Sd;^N$*Sty`t_lPz8?&*S`9IS?2A4l&KWCW;+@ zHt4eKX0g`sDQJK#q+nJ?v8285+ zy(a!4&ByK3NtY|Upg7$(Y-jvt;$j`Qs~Am>s$bwzJFgX2U9Q9OgdTL*UJ36y9Vc=J zh~s?ER>!^#O>WD!goS5%TX8lB3x`}EZ*1Q5E2F#gZ0Hr2B<|bc8^{G*>(a;Iw61HC zh-<~ln|)&U73oO9mIqS3i}~Tor`uo?d(6hE7dpgVY9!Dydai?)0}4GO&8fc9JU4bb zgV~#4PrRSNvip)fc3ydYNN~M)%iVH=P0>o#7Mc=CdMHke3gFkigd$0Xf<+WJw`(Lk zpRj(P(s4lzZWu;lV$kVnSxj_3%%4X5BRGfLy+En{3+D+llIBr zZ3OZ9%P0aZQll-=^G<%Q47bAYH<=DBPg0RzCK< zaP6c)Yrj5`WKV1fyYYTyeYlBw0=cekI+;(af5=HyaXH{FNpwLehh2leI>}RBKEs)8 ztg*8BeSz4f#wX;4@@br-ADqay+Vll!8zZn(9PyaypLq6XA2SyJR~P#w0rUYI!+sM;5;^376Xo zK>R25%h+hU#eyV$cv444g9)#E&IqFN4F@TO#pchZX%`XsMocSn?uHIX{jwLu05k-} znO{gBB7*QvQ_`pMmL4#VoiPKHiBVBfEn_402D{*4{@nh_H5#DIzwk0gwD>BT<^!R! z3wIV{%bj;GRJCb@s<#|~-zph!)3LCythUEU(l0x6(w^=iD)x)EU)7r8y}V$|>K<9w z*4CJ z;q&W^BD9Q9`*}X#5LJ5-(}j)OLQrnW7W&6_$!=&WebN`fuf^kk+Gi0CdQvtu?zU#f zT&y+aTMZcP%gC{{Tx{?tSiE})rA)%&jBvA&wRhd6`*ziuDsvvi?Ij%tzsk>_9ehKJ zk2Dl%47TteJk*hK2w#wJ9vJlZ$k6OfWin z{ehGkV=9J0LEOUqdEeHj74Vq1J=H;Iy?=9NzZ_Ai0gd?zRqI8l%Q3WH2e-)TYCOi9 zN$H4BI>!Ca%&20gJctthqcT6dZjuV)vk_<8`~ci)0PjzkE}&<5{3ZcEnyEd1_3&ItuaEV6X5b zV=}dJXYo#0=|j__a!6#0Y>;}&sxTri6uG{|X@ARG>XR^(cunO#>l%Lg652>~n)UIr z7FOhLJq?F=RdlCzv{KU-jJQTTi}_@2zMAGYwX~xus!Um{qF42 zdqiU2$H?W!9Tl&>wTDGR9fliLCkyw>ObkLwU;(V=txUVwt{;IeRY&f5Tb-z{`-XkP z(TW)H{VHgS78@j49ce!hxg0xm19!tbvj=@&I?ykx`8)0E0t5AOmvN_e$LP;Kx{g}_ zH54gnaILdiCu55xUv(NbKq8bavxz)|%Mn`95l;jlwQSdoQ=Q(pWU<~t!^Pbh_pPWg z-`L)!3FfS&26~I-n7952CZbD*Ro`C;H~);DakIY|Cn{vf$yMYSCXPrbfcMS*wf}wA zTUj}+0*~#pJoL0n65^+DaYsIy1pJxfa@RLmcdxYClGI>F@?0(umgtZ&#pAIT?@-$7 zZZVgb*^{lcUCQL+EcX?lNZQ>bQb)y?v!f)ZCMn*whYNYnHQe&lY{qI=%UOQ4#(wql zK*8=IOu+5ot8tCKRd&9Qw!eLNOID(_v%o3@|GUL^nistT`4tNJpDEV@+~HMWgJp=o zy|v5xxgD1NTU6&|o6-s@e7-qvmRp2GE|fa&_O2vlbaQ$l2M?PC3~FwCo4q1C5WE^+ zt{Yc|pFJ>{j9#Xz^3z?tdKt`LHeZy8`n->gFqfPqB;McSSlk^b^n~ihjrX~6aaG*k z&mL{^_4~X=a@!_x;o+u#1p?M4Ao&tc&N%l^0Z@N56*@cH=j?LAafC(Gx+c21Zf$Y` zt(w6)9j0sEWCWxre<0~=G$d$VW%f)*&fy*XAmaz(*av!LPXvo@OnG|T$WUUgrFBHp zr}t?Q@_?iU9Pe53;77;22V0{ru6NH6CFs0sSK?TJiangx!v{IAJj7;oz@wYK4`icu z4Xwk+I_qlsvfyaWF!*HqN?uPEopE2Pf^?n*fyEP)%g&_ z%xv+l{88f@lFn{S+R28id_~b96jckor<>bd5>9=``)|kIyc=7Xg8JZp~*sf$Gc3qF3?lGiIT_BF2(5~CT@+b9mc3X3cOKa+ZK8Z zzh_lD!MK@=cW9V;pw!%_i4-Pt>rgLA3$fjPpX#QA7q{ffVg3YpZKmcFZuMlqKiV9T ztaWbN(=ea>nR-#uES#q%3h1!vA= ziR#(GlnilvfCUtE*g$vKh#U z$zD*QoOU9>4DiSZ;4eQcX%-u;gL90ry?DF|it^#oGn+c2{O;unctvIUm(&3ABiwBw6a}WPZ2Zt8 zeG4Ccj4qZ*3-q-!i+Q+FkS`u_yaWk5@-p0|5vM5HbWC zuP*nM0NX%G!AUwDQS}t4)FGv;CvTjlKurxOkW4mW3$U%VxY{#1H?3E*S*$=&$d{N@ zEmk1Oootb*O) zLVt}Z7>Cn^xx2d?@Ya>1BhRlBY3>8E#X2P?-kjf)=r)ZuOGqsNE_yC@;oFX0#!^xMD$9`=ZS z2Iq|HZXby(oZU(9Vdj?}xt~)TnYE*%(OzQrp=_b3Z&k&b6#}CD}**{x=KWraxAYZxD4${N`X>rTvjwgWbWvO1n2r(l7z5O~CH15egwI zuZRc|A0OZBfgJ#JK7aoFj+(ku^zVV)zJ4Iw3yF!Llr~@D-Q3(zvNE!>695NBfJwXx z`NN%WYzT_bGbIXF6)XLYWSTZJm&IQW-6#n$*O&S`gcteNkdYS}0Gtl7BVsZmkYIyE zwQE>BK63@=EQ`GS{4mVmSef=q`kXfScS-G+P{tOhyv$3TWXp- zF#ekVUY2(R{=a;ER!=4i0&NeK7kbk&1tF%aTh^bS$m zcn1$}i(T@P6N;bP!2Rd6cOPzh^{|OPP#9x38^kxRW#btK1cSMyzsRg?-cffSY5?RV zKsy`Q1RDc(lh18CB8N1dRKo-sU--GUJlSGs*%AJz7iGC|F zqyK6FD(jD)_oVE`!@NU>Cmd`FD!TeF6dLDF1(l zskp`aBP(wzYuK=#J%2*}k`x#okZ!(v*lBVC|4tkEU}d9Gd6q$?nz+1c$=H1~r_LHT zlQdd@ok{h1egjFeFi#~9=;XP9^j!V;_t~JIPIQ#Of0=(ETfZ|9g;oPFesli*>%c&X zw~heaLjw2#&4_=g z*?eJ$xiyJVKZj)W0tVl#ZsThw+9aH$;d)A7iI-sC0mR6Je0P+EynW{G^e589l(5ie z?e1q@TexY#2*e(sftT193G3~YhwaJ8r zMJm~Lzsb+TK$tc_dcv6`oU#W^-V1k9U+y;1)%P-^u+fsaXGsQUfv9PQ64t^mAMgM) zd3jgX@d|v80|#x?z-+xP8{g+r63c(>P5+C)N_^xSHS^}I%*u@OPxYdyg_^TF4r)r+ zcCpjGc@oO5yDJSXIU)Y4h2p?vw$Jta&dJLyyv)NZ6l=Lm!1k0(LbBn@{CTxPi2c53 z8#jji05AZ`|N0P|zeW9rlaiR^63pCC3HrPer^%Q`TNFtlXt-(FM8;lw>DOQpQpj0m zLmDzfDy5v9D4+P8HC9@x11Mjxu2w5`Ixo@|x%z1aiEFgl%( zpev`%e^wv?jDJVyf0>m@tGztt*A&-}kW`^hu7`scA?H82d{#bd0|2ZMpAfTf2*3M^aF){&`Is*Jtg ztO=2C9-tq>t0uBz#w7uD0`~D7ZNB@&g%m)?jF>Wf$hF^Q2I8l774!G%ndpc#WsmN8 z^iIP9a;pihtuv19ssm>UMi2!>etrdmlKQ$`Gg%&cU*a;g)(+%_DFM*;(c1jKjl3TI&q*=P=4@{Vx9wlvx7MC&yzjab z9)Yv!e5|poYCg>4H3| zat}sSnNz*x94f5&3S-k$=u0uz$v_O`+r~&O%SL3(e3V4kkdJyO)DXWWP+N%dDDQ`VdzYj|S4V&Lnw^S$GACC_;?(plS&0t=(_7bZX>;0~KKmGLy z{;2S=<6xXk@nNagMC8s>8y(w1bYOTWfU_;B^@-wXF)8p${ZLn42L_R-!Dj$7ND;%9 z4s|5BlNYmIy}2Fn$uX`Ju_5BRQr+TVVb$jB<=*4fwYCwmG^u=r+a_B!W|vhz_0cK> z;y;zs*Nzl6xRydqTmO}jD2g(zlygDw>IW?IBjH!J%~yGC?Zo1cs=6W~=3SDc6M6xa)PEoO znrpbQD^Z|a2<~8-HOuP*KpC77tdtRiRTPNYBU@6OjqkHmdk)czYn^4PcjMI=7#RFE zHom6UR4{(}v~bh(!LhUuQDQXhyIDv?wQkFZqlEwMRJbuigtB(mG#RwECW>E2G72$p zKBy{005d-Z7kpi(_w~al^2Rkd#&hf}lDSobgAHZ2%_<(5ntg;W2`0g1uXBN|)Bj1$ zovF|b1S-~exFTGrZoxluKZ8RZMb#7?IJ*8^dswIc6!zp?AJF9+6wme9qllW5gv^PY z>2Zt3jPUwH>&>w8e!0E&SQmO%A`cF$E!7znp-^;KOvmC;;}86Jks4S8T==wL1esSywu8sFTd+`8#=$0q%xaDF z4C#^ZrStXcM*JeZL~k5__W%{!;&nw2B_*G39Bv73&ia?u*d2YjeNs%82FC=4O?O5; zsQ6udbBOh33vx@>TEq<9>L<5nF)FTSF8n=LnO6bA^#QwO%e+%4i)fHXSX*`I4A}bEjZ*C2)wbWzcUC zlVGVSaY!*r2tGge@?d6Q2{moK+1gxxoM9b@)&RIcPoe8RSl@9EOgmuTG)Si|x>@2} zqA|4cBRJ6#m+s|MwQ<>I+3KeJj^#th5D}iR&2srr!bH*)=N(bd8=z0vKaU|<`IP9W z;e7Z913=A9ujuPEG;9e7Bc8+R#`br$UyDD)RA1ziDFJnb3Aq-Frrk+PV$nru0UFl_ z&&mcH=N$WHG~0Y&E0~+_J={Z-_dV^$Du+jB9lX(di93`VU?mt}QNUK_Nv`eAp)E-^GRNAroT# zhgXVLdpSd*iXF!IcG6O+KlwIazcggyp0?X2o>-iVn`L|N_jupe?$TT5dVC7PPme=w zk&%!+utGWF3{E5Lx=VBIxyllqk;F4U0RH{^Ou@PnhF=2%;!F4C|L)`O-w#`0GcqEve~5yK z2Q(^x1kGjaS8Ow7!S@%VAPGVeW2M9#HHP935*!Ilcs}{{4AsP>0uFP@rmhDh5tG63 zZc@E~eNwJVdhB9wB^#vg;-kSIim}pDDF%&Q>gvO;C-pu zLAP`B77J^d!|v=}w;2z)P3@9lbn)?RPF!nWV}Y>4^>o6y`LQl$?J^5396FKlr#pi{ z>&D{i&vWPR>H8*_bg8v^Rk>>+huSCQiXz)b>sD^+UY(7agA`o}A7dcC57Bv(Km`@}J6z4%_H~mH5ZND9e+EbNMo)u$fq7)SJR{sHocE6wDe(K5R?+iAg z?^$%w%%2WXi|(z69bd5Q-)P~6Q9u6b{}M+t+j@vxx<>YU;>xn9C}3z*?bF5J$E~oV z5c})TR0-8U`Qnb}lAy3dNwIIq-0j`yVw^wdS0C3Kk=kRZeO-T{rwzK6!a`1lYg>{g zVGk2y z=;&7u&i0gP&JDU)rbj0xB82YW$EJlAxR?HmzXEK6V_(`FZXplT;^gBI_SwXNCSt4h zZS#O!7`mjOz_O7OK!yMehSD+rVja53fW$cm`~=CD#R2fVvzz&fbxdxa2cu*XP_ekz zGYpfC_V3T6c7;&u-CTIOSS%y?Arp-(^wyv`FSk1C=!u8gTh*4i-h>42+EZb3Cbv(z zKcuoWH@D%8bls&wu#RLR{d>?Cosnv(#n&~2)}hA77y>t(-#c7Hx^;y#`_2qx;%;qc z?a_rR+J|XBc>U-id;Aq${v&`gKxD3C#7}fqDVEy2J z8i=>;piPg?ac7y@N}ooie@RBVMUcyW%?h>}Sd@Qm`uWdO#jRrdqcGH3#+1>-F$pM| zb!5T=DP~QNo?fDpC$i7S-ra4-74Al zt2j~$F&@@+F?Zq;53w8TgQw~}9x)*21LRxW9L|^f`+u$|tD0}VT0(5|gngw@Z>38X zwslUUH-ys@N{HBYxU&tTFfhFI000c6CDf76UG~82uwpu>8k|)0b&=JH9;%bkyrlN=YH4X?(>K98W$-!w z*OY{Nx~hfIM{Cjtcm{os-MU_i(x%Am?QN7BrkTIg?p|?a4{9d>csxj2rjRb!+(t_d zTnPc�k}#xob`d{e=+pnNx1z`QWT!b?l_xG_3>1SdN>6Q!*hNzl-;Re;yQRD-|3Q z&}AJ5IBL2^%3i#)jxA$CZ4H&Dde6S=1+Ez^vUBT-vZbHtxQ0Mn>LbrD)nJyIA*$)6zw z`ImIH7|;hn+p433;Ccz@XIbI&a9~68?<7;q-a8gCcQT6G48jy{el4*w(fMmOYorsA5S{0T5Yp=fWEIL!;l@KPtxQ(5(nM+9U1W6I>x#twQz*bf|$Tzk^`V|rxx|rqk!AU zF%_ZQ)ju6#pN)gCZG0X(A3K>!ENQu;Aq-A;WPKfU;{PjjSvv7r{mD5Ih z)z?X%ws@iw^cGCnE(z9SuXL0um7(`6t82r)8eo!tpD#@ff|qpX*xGm^78A$Ip6`@d z@Az5p6O%i@@jWyMjT@fC=bt~mqHjW%+Oj!lo`w&rSt_Y7V@NvUQJW+mFt%(B#Kccc z-LsB-mD#j$<7`%MfpZVRmoG#;3S+bw$G|3Cc&rDr7JvpSO4K=edV1Oe$icput&5tz z`B1$*g!fKE{jJIU!T8xfoz+Qv6mZ_8BmDo5g(vB99N~nWBFZGqH_<(UH&E?SUJ?wur8@5|NgfiUu`86bNug`gM$xpNlV)r<8E9_w|c61CN3`gGe)T5 zF=nFL!ZOBc?!`$OLagh{XD2;rQ)Pz{RP15r>!p^!m-NfGN91tnt){aG5`!X9Pe)gc zH{IZ)Uk(I8pLl&G!a-?x-;db8muXS-_+lKy@*KF9cl;itB~3M#jRApVfn|g1IB;!8 z(7hOeJv$flLDMq)$?~1Uat)3s%pd4hNiWKil$EjicM-pSoS>%>jRKf<%eAi80|NtC zw~>F>Ha@bV?Vak#eKws07%Wg!Q!_5JGCL;m-PLupNKLuv_$?_&!n%V5gdk2we6?0; zduC@!bJPH0&?1&E3^Vih9#HjtTa7GG)adHMPWsu*gg^%}qUg$8$$iAG@uI*3GZ$oW zKBFyGll@A|OXlKc%Gwb92k3U+p%GS~PPMGrv;vM`27U!cW=ld`E9}xNo3880y=%`&4KLIFFqg%@z~t; z2HQ^wVb0^u57)+v+s)c_N-mbLlTs7eL-ah9E}gRZ5V^>!>G~0M zf&(GttgLLL&9U_#E46&l0!08>|KGL#8+ytew#|vlU}U<9GVw5D&`Bg+T~S3vbLbgS zl-dh2w|s~=o8}r8CuIh1FU)(AYu#L2luTV#8Q#^Tm`mC+b~DToIGw&_A&pLW`KW{n z*ulA4YxN?{>72ugu1YbdpB*-=gkGY_to!tQ?t1yU4ZB_Pvt_8HAp5|qN+2#vydV!h zKcQrtFg(J4VEI^KrQlmI@mld<|3_hic~KFRAZrlzVf=5$*i2ufh$vt186USzxq^@f z`M+WFc^1Ml#~sDYY2r<4zWL+|A!dulX@N#eDU2<4^BFt_{wRRqe!rZ;R$MJ8rS?EQ zmeG&EFk8ew$hSw{HX0jItH%~~S{Kt=d940)9j>bmlzg%);7T87_C8q# zGi7kGV_yK9%5Mt?x>0rvqg7?unC^?2IHh(=p3eJW9@SzCm^714m(6|=p9q%x84FXl}m=o&BOw2~ET&vME|*Oits*KM1Sci_Ebir!9)~VyFjwc4w(OL3XL?AzKGQw;WulqitVJL5 z%{Di3cw4nkTXeC#pGomO7I~d&{@I8gbIV)qBbiozk(R}wjwK=3Sr&MU|2z8ltjZ5t zaWlG}?S>DhE#;PD2qLnZJ1W&D4~xANI0hHvCkmgDCV?vqPf=6azs|N%a1BF?3gi4v z9T|n#JfhVv1)>d4(E{Bb7;9^h1$^@P7|Z~_bSyEA|BZ+|IX<~AIhA)pZo2;E%a_19 zRV5|7N|%yP2-@;_QiSAPZ@NLFjf zS=5!uDq1|Tv=de2k^l^;+)Bri)t}G@i&ay|)lNau?mte<>oLMg$uc~c zpN#46GAt{u+{mA(M6h;8dRr;2-=uFn&D>u-VR8F7aK&Ha+w1F-ai*b`%D2qDrinW} zJ5wyzda=2=DO8J(gQH<$5D z-6=0vBoBc>)4}P;i1m^{`yG3&44V!7!5E3tbSdOFB6Tp!$XGu9a=q;*C3_#0sZZlhN{S&n}^7FeClUTzh?IA4860yxX zazO?YPf&dYv(};xzpMVXdO7E&^~fZ5)lb#F%c48dWu1P7{Z$9YHnw8p;Hz83pCq;w zy^-_l$%^@G_|PRX=?LW_Hg`ai8hxuPI@IlT1mO1B6zb+T~D3`tzW( z$jCRTjy+4i>`&G6uP!fP#wI2(EY)4rA{xDto05gX=+bgA`i$~kLXCB%K?_Q?6Hv?8 zrs98iSh)HSE2>Lm4)Ve_OS#Y{rNy41Cas@?N4v8wLaCLBk%%qm}7 z>2V}}QZ9C}e7hqfD!xe&^aUz41WF!8h9veifQ)10)dE>UV#&D!3JQygbe3DX+)?v8 zq(vui(%PGFNO+BGRLPi_;(*J%sLyl$dH@a3T!WBz)V}h`Yc@YWSqf1-K3_yOW5=ZG zq`1l6cH#Ifcd;{I-@dovT&mRZ&8^oR`0iN36IdzwYl-d6=Sm#U7R zppMw3QLteIqSV#R%}Zqsl~vgL9il{!=m<+rJH*S5{r!>4q;r9=}Fu5iRJ)~E*EiV zR(mb(8?WC#uNxK`T4A;M^Z8pc0MG)0Ny7xnzmOqk#aB5GlfGa~MmA$4JH&jmIYX|( zvU9>>Z^>aVbJY4SgGa^o_}z1;EW5OVdfozRThqL$%`=U)Sp>qiI*Gj)``6h{OP>bv zo{E$2j*iO6jjs-ohkrCb-okL+j!WXVe&qVtNY`+= z6JNybRH0#4F~$_5!E}3<^x)PsJrLy!x;#n&Ch@<*Yq*&{H19B6%0Bk^$yOq0cLD_Z zI$i1>m76PNOlo9 z#dm^7eZv$|ezL6Ad-m`cU^=1fhcmAlTsZX#pXUy9rf&6{%9XI%cAY-xnx^aOLy=`gLp0t`?Z9x0{_SFs&GhLkoy%8`;0=aD0-OS z8|3qIo8Lv5eBNy=T)A|Fc{}=FHPFstCg^{w;4)9;1H$z=j6C=f1wJ+Y{d*J=UKqXb zlk`9y@lJF%)I|Q|D*}())iPP^q;^ZM?d%;%%--BU^v5f?2?D_%6@Qa>t&$yc;x-_5 zS#}p>!bo8zPS0E^U?v34Uz30F&ATeuiXqllkj?Ffk%srpb+WeJwyVqhSvc}i4tfQw zD)K1$3U^+Wpt7`Z%D;6QHcUh&H#ULP9S8n6vJ>5iq^U4`d11Pri4XCV!e@p!4Og%Ja=1hFp`NkW8OLf#eh0Fc; z$niD?TH%Ij$$lp71Us!Y!rt*?HTruR*rzd}CVhTfCTLMI4z{=^f{;pqSGa*u=|%|@ ziqhf8+WIVxRsrLduwxd?bp476{$NZe)K~tmcDQV*2s(_IZOCvB39RIG(nptJ-~LTY z0;0PM$z>0m4^m4rTxkb7ga9h{VsscGPe*LJqI zL1rW-X`?NYbnI|m?sFkFB76ajEQJndwuC2tuSO!%q91)i%A=@2Fd(nz3AuW!>(_n(s@gb&rqKn?tpPjC}$I z&(pe{Nx$C?Xd%!M#y_Hu-1g9%ge%L4plGDBb(c?sSF(nQyh`6;?(t{lWcG=O5nlZz z@_PvCgT9!R)A2_oP3XB@4oIJtt|k>O4%|a$GVA7Mwptg+#8LVm7Dq2Fs}i;j)`Lo) za}$~xV3Deq^7BPzJD6CRL)7v*cx+pnU43$Mf5($g;vXvdwvq=y%v`}ru_mDfDMo{Z zOiX0RBI`TT^Z=}k(!rN!*08Nc`r)V(bBNN}W{gu-7!EPp%O3fbPlx0dAFIc)^h_}Q zngk-|UcDsA?v>k0+HYG#k}j2`14q!{7YP8-2I%s_O#12)7;etZxP{#jQ)-QRQ=ftx zsk3Ma_l)1*rYB}-Own8FY=x)2#(^B`Y-c;mMXF1nfwbtH9PX2r+b`;g&je;n-VwfQ z^b6y%Af|3EjmSG{@)K8IQwr~;=*naw`WO&8foZmwbVy3g(KLd7i{5X;422<}glC8X z6=j|0cf4mN2hm&q4fWfybm+qvS6}$3xLv5zs3AZ;mF#RA5>>czjs(B>R%x5fsPYd0 zQ6GR+19m<*>V;otHw6cU7;+kO>3m0;v>yOKo=hDBV{uUry~JY^ zDxn(l0$}V6l=N|;6G=sDjASq~K@fh~wWX85Hy{xA4=Z(bj}HPc)A|4vS(H0*YY+4| zH33A-AM+q_}n zqn9+FU5m6@YANp21nh77bvI}pn3+o!qvU2~i}If3PHHl2>v^fHooB7_3aw@-QPsw< zMaqyWkW>zw?SC_51;N&Ff1+G1<7Dtd33q&N*%+6z?zK;wB$1w-Ptk zCp1`uD?0v3<+9ex=Mcp)B!B4J1Ry9pg#}$Tz8U@SkU>6m+`@+B9Y=t|xKEy~Jxa6d z_2YS?%fQY5c0$0w5OaD@Ewbb=D5S0q1q5uXk8NS@Ef(j6$L^fSlq~dP$tDBdQgcYr@e>S8%G2;!N}ScfCtm}= zSkcoAHCEa(JaZfS2KqHkHsBu1Ed|A8z9jNHHH^%STVD?&6(vtG_tw)`G)#U#f^rT&%UCoer*RZ&`uD~_=Mbo02HY(qG8DO$(7~Gch1YqiKQjA%fm(d zhO9lnn`C7bpE&?F-O}OX@h)uYXkdeMB0w=CCVs_D>GV)d9>SKHb0jf{ zb|`RbIBjdZWCU=EF^vcxQaka@hgOHZBc9S^rt*y%pRKRKHpA4c;mfP z4sR}7EjM?=EHrzBSX-V52@^VhrfTSfRUxx*lpw-yxJw+pwM;iPXW(lpc1VF z`V*~Q_qO!-liS=RQlp7RO`2HJ;j&o=x0fSXSyl8~uzu_D!=)q0Zj5|z$c{Kv{Lyp# zMJ#o)UpYbu51M}@SbLV&^_7cJwf0NrmTp+*M<#oYHg?)!s0@I(LZWDu#9Jjt*Y>%zGD>15gBF6;_DA>0ce0 zQN2y_sENE0T4oD8j8{%hSQPS`kzbBj{&8q_L7Cz8?R}`j_{y{C>FEk>0i7TX%w)Io ztSp!Ftg%^~`cdSoqD%l!M4gQ_FriQVzFK=*Q(b%V0;ljoVJcs{nuu|qD~K8=TXALw zNQ+wCn!NPQ_p$*j7MIH2?OZavlAC1Zuvi2-+PdHq4H~?+w`B$g^i`8BxlrPgVtma`gWu)mt_RFZ+LvmjIFC@N{*y+MPHhh5 zv9IK?uT;n4V#aKzywa)>W!$R*UP+SqQWxE*NoMv(tC1bxY>wlquZi8kZcaH3JvMy< zg9Q%{^xjOXP;;&%7!nqoqO^s-~ddP0=temPHUVg`Ffq)u4Y`7Yo>rSK+yx4z+|hoDfax|CXDQO=Vb zO|ltOWgBke2=eFx}H9K(+=HETGb9agxW^KZ61vgr_{=Nc7nsOgrT~5c+wfrh4ov z-o^NbtvrmsBtKFeMqDOFRFwvQYiWU+S%~b-AQNBRJDVWO|RWD&X@f+ z`c$J`3a=UY4|37P`!}+IOJgMVvzS5pv{Y0YJ6Y}Km;2kb5LUx5GMcT&kM;+q!$=Yk zy{n`BN0ESMd?^}4&PwUumoWGa9D_<_4x90qV}x3I9O2&R`ZdSs1x<4nsWrvI!pKjO zJ~b)ptv?}*lxEGmVqvwx6z}x(^2Qf(`;0e7Sen~Q@LG#araYs6W;KnS@+ShVR~Q%{ z{7Hf2=lE@uM8ooU>DP($`$gl?&#Uoi{bVE&knGyp+Itg2y}Tfs{r51gZ=i9oy_1Wf znp&$~W>k53c!BptJkc6H&9oe#ZC<%mJ%+zXDqG>oD>TPKae&qj`!nfLtBZ6!czO! z_5wAbwnK#anfaN3M-283la}~In}}@8`3RtouSaqJt~khlXoLBN*y5MJ5k@f6OVD#U2R`X@bwJcPoV!zGGof=Glpa7? zp0Gj27u1xcdeuq;b8a{{7&ewwWHaXXECFIXv!wU+1Y3@6a)pTc+8k{rz>3+1!bV#6 zWJJWPL+GNO;i&563G3>3g`z56SRE*v#icw(JxoPd6?C%8dwSgj2Puo^%c%3}Pj&%j z#^LG^KqGQEAQ&b6B>7e&0>o6q_gU@Xb$G-nR-$#HdU@spYl)v%);V?BV&INAwDeiB zgDsQ)*s);Hj0m^s^&nSh77dm^VR7f2z2T#~pfl6G@{X>qW;R@ait;s)u>rz%r7Fzm z(K|DTz_x{~PI#>qJ+F zBp30cBqiko0Ez&$Y22v#!F%w}VN7~<&NY+@MXBwVpZ;KeK%c`nYNm%N7MWsNCK7ZA z&f9lc!KGv1j(N2_Kspi}s)80)g zvvHLgdRdd$yVhN|bC&&LNG+!THhs1TKayTmQ^?`^w>>oV)W}PUYP}3G+ zU4K%f)UY9U7~QAY6|FXLhOj{c(Bf?Z(T4`3_QTgM%jg^DH?dk@gbq-CNxHiVWb;OR zIijKuN9(6z?}owy%`o_!WJb`(qCtRPXu+O_E#UFkO@~JP!DOaw?jj3lps=fH0JBx@ z+eXC3cB~9$c64_?W09|;!eJlz2ZO)PHGq8xdY1X~=Tl?-1c1PYe*XQ2NddCfyzElD zgYZ)OGBC>bh!Z(jr;lL*tQvSy14C+1|7;hbIH}?$(J9=^b|1q4l3dw;VhFA^fo?-c z8iJ?pbA4-~N=)3eK(i)1Fn2omq*$HdtRgx=XD>y7L&6#9$T755zDZC50*S=#0G(a? zK%J|lQN{bHgVoTCmOHtJy@$wNRmDW3DS^y`6uENef<(kSxGh}*!(#}N^o)Bn$1Y90 zfBEqcb@RB+qY0X~PTY2>6FXscBZfJ+NwSaQf0qs7!85H8;YI>&20>n##r1y8At9&J z#hM6}Mc%TvqjMUwikEoa?;pHZ7rzLc4RPM~W&K4O-ezlXNOattXGr<6-s@J~j@9<9 zXoH(R&N#Z&0uS<&F7d2SD3)&*=_(Zxxzv#gAKA9UuL32FiL$b?W;e=bGSbp~RWlV> z_7|}Ve*)6y`e;Cdu=}>f?f|=?desUJf{cnPu`P$#*zI>$*HbWY6qTd#zYIVoU;utm z-5WvHt~Ti&Bz3blSlZdKo*iw4W0^!=i&GE-uz3ukg99N-;TnG1x8uN0b0OwAAt1PQ zbNRgCu@J1$GM>8zj>5U&ab%t_0BB!Oscs#lAt_A$40{$OZMWw3x;J)K*#`-XufElM zgFq+)vJ%+AN9^L<+F_Oo&0W=Lg`K~Z>+b4dME4*Kf}>T>*bCHw%EFxL4BhTf^tPPpx>pe1LAz3PsxzV zgE9OC%Bmo+r{5qR=A+3T;W+NQ4~uLsrh4=o`#{x=niO_mlIk2C28_C)fbX)j{bo&kQt*zG^Qd2Nr`HHyq&zG@U2Dq0f%o+gd>hkYCTs%qpB0`izkE5{gW{45u{}hBWWXf*W zIwhhTW8CTKJ1wuzp{)|18*N;P{exB6`&QHVbU%{kX^rggQ>q1^VPPnDm86Nd=~a`T zPZJG;ai-L@5Ltu}WDk8Us?Fhv&c2kc$?^E-CeckNYS%CpCCEo-<%&}cDrA}|){y{d z`dR`^R(F_L9jjC*EFYQ}_O4iOV=nvD8u`6sYlM*dInT82^gBpaM-Ppc&XmT8BLGNa z99yb|#;R6i5BNHg(6Ir*s&34O=xJ(UMef(~t<)S76T!X1jTn=JhZ8|=9{4DDGcTFEGE)7})Fi~oTSkt#Qwehqpzd&$(&OPQL=X!82 zt?l_9kKE1~5bxB#dUg)Ot8v29CCsPyy26~B9+_K1Hg0A8n7Nt6teM>;%R32UKiA?t zZ;{+h{SWML?b=gD(eay|u_~~c4C8uTDe5$)867Pzs5Q0@7NEh2fzW7hU2|LE^~2)B#QHe` zC0$&3ged9^{1Uu{H5?^fP7g>$N7e$cXS9|V;{R+Bg`(bc9(fmjI2iNIO>ICQZIoF)RKWQRxo6IGj z%abzm8A5hnzq3Cw9+o;ZwfS^Q26-GF1Vwd>>KxHSxyOL_B+3U0K|)BkOG*51!J+w8 z>!f)9lT0=u!iUc+7I4ZKAwO(-*^^uZvT^Q?eHEL{(LM=7RlHFoJk0=8TBCk)*1as6 zvP)${jiAwe5tsZ(DfmOZM1=MWjZMbp5wv;MNH~!6AX&@CUCJcu6>@*@o>RI?Kpv1n z%vCc#?MBfepp)wM({>ZCKTy&>6KpN0v6L^|HS%9=&HxlH=`*q2rSCiUnD5kOWr1WU zP~7~WlJC*aA+Ef$Y?+6%>KMK^hWx{EQVd5)^rtss#_f)ubh~CD{z;THKFVAV-5Ti z^W;lz=XUw((>#(0NHO;U8g-oukL6DTVp;a0dd~!PvE5E5g{l8%v$1F;jGsMw20+rp zZ|BNbp{=>B1h6sEIx5%|)$&Z0`EPU(>5p-p{c*HpqePH4B+}GBYiB8iXHCE~!cQXd zC_gOgI36#8%I*hHLZXsz>?W=~q`Ryr6kKW`(TW&Ghfn<0xCi$8u7mGzg%KhzZwrJa z%XU;r(c3D)8j0Gv5pWMZ>KmKRd#)@I$}C@4z~#kgXeoO=dRcj`uQY@FBG+3HAkEb( zEkj*>;O?qn7~N?f5bgDw8M{ei z=O0D4-BEgvQIdPKh)lo-BX9;MzUgDuN}$0d`LqYi9}D}tk8!4tsI$KJsr~QO4Z<)- zHYx+aavj*(NIE-Z>TPWrkmH7ami1`J&m>sU!fI{+eZeH%M zMW9D#HL6XPlj4ZQZBHFe&Qc}d+{EGryxF6cQ|fx z&+FQ?QhJf!lVPF|R>P*^C8&BYaACuoz#lSeP2e9nh84JxVsCovwS|w_(EqWJ1NEUo zdhm&u(OKnM#v^Rj=)UswbpNQRsGu!hU;~DR!w7LRrY&jXfCC$%U~QlZob46Cio{@h ze@Fk(hnW|$(`K#b2uWt^^^Gi^yj-6$7fE*{pka#N1h{NW5K=XrZxF<@fbqm zrT&Dj+pZJKEaLHpU;ze^Y zh=4{|jiiPG%MB^X#qYOAgxFkxMIOQ!4zD}<;K^8Lj zM0E^~1V(DqvkuGg_Y&**-(h?Kv0`3q5#fZHYauz72F-2tXS=$|b}zJ`;cfcC`f3Yh z`n~;Y>lx&P(XnO{4Av~Xp)rK8j1>Fw46TOsQ+reUSfg1y*V{^tK502_bYX=-Vw20z zp+5A+`Kkt$pZ28!{CbxIm}cvW3(ypOlQ^-Yzmg~KB{Rs^B`bIc^x+{{MAEi$X7&&*Rs0C_08!wLT*i4 z@pkY+c%^A+FCJzFurGIKd-i?^K!Va0E?((C<0|ALfUM%Kw%713u=qTHv<`UMCd1tf zl$p3G*gCF{*(@VB)x<_OFV4uS=O2@Vb@I*EP{w3QZA{dQEG~Qi+ov9fX?uY+d1~~C z+&@&#UaGcLcP(Yls_@J#|5LBeeU}T?NBzGRLUof}UpVOrxQ@JB3g|^I{ANNnCz!px zL)$#0rmkLOH&f@g_Wy32?bdYd{^6naQKHDzOA}X(TLrA5Bv6En=SH#OLboVLJf{KfaPO8@t`cNZk-5q$cXJ2aZL6gHzbc?V@bA!=;T4%E9BMe&C*IK9dEQRe>C-<%AI#J8%{M2LjC}GBe;{NBPfw}W%Ahk8 zRH?02ixX*<=WHzS2^(6dGTfubOtBRQH`TWYgid04-kI&xKRK|ek;J_R)aoLGkxuoo zep%3~efuv0W;iz>gzUzR(7_+9o>xxC+UP-Rwak|iqnxBeT~o^i)-P}MR=U&ND;!&<^WqpC6h@&F-67d57H z*cy?G?QAei53=|dkd$!|4Tx!rUozAS=vqqk{WAce$!_CCT)Ml_&sDeXq`l!8l2aU^ z;iKS-5CCFuf3u|V#tPUTF637vLmww6aqnx@xj(UV3x5p0ha63jDo?uM5{TbB0*p7{ z1VA21Z*vj9|A^c6yfmreEa!D8?k_HrPeUErRz36{&IoK(q({w@66>4hnGXY-D1q)Pjp&Rre05M z=c-kl^xh>~-CNK?|4F#pmRNah>o9q2j2|m}K^&c$Q>G#o{-U1l8J?6L1@5tAWVt=k z6;J{-h-QXaW>0!**6Ls-b|K)7(o6F-3Hwn;Z$(o@GWz1mtNUa@wEja@jGA%3aOiKdo) zJN!U9ogn-66XO63;FUK9G?s^pIOAG%a@70lEQ$3nFo+=8#U!a9rrs7D2%lav|1*64 z6P1CxT|D6jo4PiP7vC_#{51X`uVc`*SYu2 z>%`TRpVFR_?N@4Q&9;&W!}*0ArS;-;8c@cWzOSHz#f~OIndf6!dPoO7i zV`C$SS^;~zvatcjQd2ce_8(vDDrZ#c{44QzL=vegY*uuGgx+osN1{v2Un%Gs%3wE# zSPqNVlV)>=GVfa}cVE~l{i6GqKa39pTzP{>&>D#>0cY4sdcnV&@QSO1=o z)ye`%EjG;d8#r{U*yA5m?ZU6EBm-o*p`Ko|wOT3u&s*1GJf#oON7kmD;w+&O&l#2& z^hB;0U9D$iv@FR;NG2*48!}-g?R6>1X=n8TeC#M`h(5Pq;Uks)2r4u>9rFiQT zjl6QVHZGqPt#e&?xao0tr}%2-9&Hb4%8`M-KDC=$<%5UF%%x%0?Tsbjo>;$`=jn3? zs|&_;`;BB>+f{Jas~F*l_;$gICj@oXF?k;P^o05k1;-ld&pQsRUsQi7`gWhE{)p4_ zB3gRK#D0H9q^&h*Ay93?)dQp}EXeV2;RmNw61q3xGHK zlXg30))5<(wy*{Ya7>6g2TsL4GPA8%4^^h#Qb*l~1sd6(9rKlkhwr_9Z0MC`dI%j} zMKGUE1em8IAYI7xM-she9_E%Sf*z^n7gFWSVM%Z(QYsP~$exL^UE=NL(AuS8B`hLS zy9~)SXo&D}>D4?F%BmmJV6ly0s`Khpu7K0yBjbMvzK%5*{_Y4+Cw$vXm? zKlO)~pH;nY4?2Bt@QX^WZEWoR!8Lncm0v+Jrn&? zF+8%HG`Fwzgj{^i6+7H7&pdOR?+Bh>mK*#*iYO806OP!s2^t>Wwm&~f?wjbr@#!nK`Mrbl2=vXmqg?`+Mh}0L{yDwRd$jp%2feWKMpMn?o~hg( zL+_*q@s)CUwB3|$fcRj?ZwJEVI~Vh;JCllA^YhzRk=#NNl!3uD|5R!DX(q|a$^yx~ zd2`Xl+0o#@00&c>>*aa%b%+5f;VK|mACG1}UgmjxqZS8E(l+QK)MLgcjx)63<3nno z+v$(i3EnF5QU+*J_Gx;hm+j&;Nu^Hn-CuiQJV)kiA^-rkSm9KeS*`Mb$GV491vL`g zzom}^GEu|4DP3|^va)@rr^}c9FL(f%C~H`PlHSDaNt|A#16ZRbJpQZB-WxkAv8{vN z*`Q)Y|DT5iLpq6g0S$`_3n^y-4bK)9DsFwOh|FVCo+7u?6I?ANq-yLc>(F;JK8fr7 zJe95ud8Jj6$IH90yh*RA5vZkp*YA_sKf2T0SUX}`8Hq2J``gJg=lJ=(7cnALX17-W zNa}h1@eH=&1sC)}b9ZGI2wW4xe%xQryua`%)Vo@)FO?nEU|6Bc&g@tuxJ-u(?Z zIJYqsroq}=Y8eq}8Sdny|D<|PiB!lI)P%?EMVrjcUbL#NXa5n z;x?BezYZ(olPOR;N~$rnuPl({{Z;%G(}=t>lS|DiU;#Ng`*?J*i#zS1al3%-Q8P(CO#Z2UK^(L7h67*j z5A~qM*B57%k9?iEuhbX;<86F1CQUry9UjG`@*WEpZ>7Ke{5n=^yOsiZ&S*@e;oX3K z>9bz_xz$91i0H498>J?bSMzoiXS+5pu3j@Yzh^uCb9?gibKq>O{`5NQpQu3c%DPEW zi`NCoGr~tgmnn2qH%5l5VaKVdN-ex!yjM_@+w)gTExz@Nhw&n5XHBkq4jUruQa5m= zdMH1BB6%l$P9sCt84=>R|Fn*sm?I)ErM2Tia0hPk$KnHBG=Y%P8%f)5W4!;wt3l7w z%gUk#1_pw*oid6Qo-drAxRO;@-w(bpc>_HZH_sSFBQ_R?NXD{Jl4yUF4@yYsKKk4p>=27psXG7em7EWdGn0)K-auZi@$6)A4gsOw^Ajn1Hu_xbi?J**^IA#pX&(JITO$$Qh)$DO^_^Kd(_&(b*}y~&dm!PYso zE<74jd#-|qDX6lCb!Ed7Jvf!Sbkv(CEk0k}X8A_8#^qW=%wQCFN59|0E}oj>Md-FQ zU)HHU$AYOBKcU;_4x3SbUt?bBsi1`HPWKjC-tE*lMt$3p)rg62H2TIiq0 zXGJ_WBQ#PN87Jk2TQ%}>5WhdiSV3n*^trPUf{@4@fUI9DTiV_}_zCdT?keFt=+H-X z8h|13A4>_CjorP`qyC3uJGnL{o&Sb~P~ZnX8_&HxI)W%Moavaoa=hZXD8auP0@Zj? z_vH@N2M|T-Ux)%L)8LQ`5%TBKgSjsC{dqp-+HiMfPT$6U#|S$W!Q+;fT@N>3|bo|H(VSxnpHpQ$ba=L-w!gx2+VJK}S(1vGZ;Y}+55 z^T&qmUX@+A?3*NH!@^ex8uz@+Cv=7BJt{Ui-C7WS1OoYg$VE_)O-RKHtNSW>T%CRs+`etsA>+c;)-BR}5risx6vV z;dfgN zN!pE@YFeR!{T5Z2<~wjXtQ3SWt59fpUBT$W2+38CWYo;_q2-Y4wmkSsfv?gAoy5_H zLkZ+nv#}EM3$+!SchFVy&UHUozqYZ@0M7c^9(fGwp^{HKPc*EZYljG1K(F}tExWTY z>zvC(0FeWQ80}6NY=(HAIpSIvEY%oy^1wYGK6v3&yB9|CJtL1{9`XOxTgv5q$q_k_ zKA%0RZ#IZLCrPd<0w|2Q;8AHkx?NgCaZJ%5Wpk-MW2tDqFMMwaBcXEBh#EHMEbKUj z{cCo;kh*G`jNVBba})LK!MhIYmXp-*wl~Kt4KdL_kqMd`LQMOC z?R7X`{@}1W@-SO!yi>biJ-56%prh`L0i<$MP zHb9W@?f=Psu_cm7$ejdhfGSL|#e%xvCRA2hUR}^<)Cq_BTEm6R)vW|KTNyT9kEN<7 z{QYjJO)iBn5QwmK`>_5QaRhZbZDF2g3JBJT#wZq@(V|60m#cLwt-lJ-x{qIJyyJ3M zD`OC+(r#x{K;gMHBl_|7>n5+U=O<@dUbsnBfdsl$v7N%_k6BD<%+ZLM?c(U13NxL# zW|8^0z_+fRA5t=bpj4Uo(Y*ALZnvpUBRa1t(npA^m}b_W4{153dw7t?JB_xxt6A3DIRT3z1o_~oM&1c8rJ zW=f__soie795(uFRrFEm2lQcn6EkxI^F&Z=M0jij0a>i7K*ogt$PP1Wwyf8a+sWij ze%QnSpmKSbOUkYjZI~AbWaj!PF7PMEf64NP$2YV`)kDUo5g+76-z?X{PSSGPP;%%O zmxZ6MOMF9Rs{2l&S{JJg7P~h2a^x6t>mrbXCk~g5=%y}RQ7OK}*kkha!qd+pvnf8+ ziI{$&kDKIlBe;}gj86`?*H1a$lRx@fj$|C}l-=9uC z8EWNKbBGJ`NaS2$Rsk~nBLNLqbrvIPQi;LleiGc>_D&Bx749#5yJCc&Y!&X~iTdp- zu%~2{df&M!GB=x&<_8}o2ja~9L*y?c6@J*7fQYNW$Kc_(^fJa-4xP8X+1n%T?Lb5c zRC(sRgen{~8@6rMdk}Q-HwX4^XA)!fe?+W}aV;`UksC(F)W)7Y%mh7e%7{XMc&sxt zDfoFv`>YzXz^*s(Uu%GKUHc6RFm>ksl@S^AZL294D^(|)3^S`8^e=Wj2W&}Sy|dzg zNfsMwy496_Vys*vB`b9)1u&_IsO&S~|J6y>-^Edd#gx?n`nY1|eIrE*S$f19{>iTP zPocT(uenW__xT$f2!PmgKF%6ni2nexLd}h@NmnS7E6KnN&>Ml;Hq~ky zmdN8_9vX^;$0}{GWyH<$;9)=1u#^!^2~&+I8!ezVgplwUqI6fsqGdv{{I! z@=`Ww2=$G~e1v3y5Eo>_cY_vM1XYWP2`48`t+NUh7a=H}rdow3`amXA4>@=t>A~Co zIoaxpP$R6m7Pj78nQMyAvoEdnYL1IQlwmw6djoXkCq;vAikpnOaRG9f;puhAQ}-s3 zLiE*eh)XWPhGsGl7IOq93HoO?N2+kIUs-KUF95pxGQ9p9msNaH`KH8(t&<4_u05nc z=dP{29U}uZ4*|+8WY3HwouOb{3u%5n2}A49 zLhiLNpVc>AA_Gjd-{@B&xoq5FA~fN`ak_z92l4~VeXb(Oc7iD%id{!_h z$)%lILy{x%<2&+cDA9&j?m3t?W!vQCH^L`2&gq##>|P}j8Ps?D#`Y1iEhjkT2*)fO zkxf`f!Jb6G8I>gIi6GU%q12EcpF@S*>#qkmwOcq;PvvSBKJl#2&ks92J;m)|5O#FV zuEciEN5RZBZGGgUqq zvdqHr&%#*jp=DB{6{VQ5wev~0TrVj3;fXEng0H6~ptLA(&Qk*!>831{ReNmQJseUm zg4v4<|EViPVZ)b_OBC8Ti>>i!QlVls^@-Wo#(9Yk-bncE`VQ=t7yT>&c>NHhdXAw- zG+Gg1uTGL?T=I;14YU-OyANRSJGX9H^H6-`quG7(joPI;@%7`^Z{EC_G}%vjK&GcY z9ev$s>>GdU=?~%t7`7r_PyJ-DU3WlGsgj1tsp&K^qp{aj*0=>}sL7&b5s4Mzoxs0w)t?wC}dS6=q42=?F{a(1+|_S4h&E|keg z{c>Bb+oTmARCA(UUHsn0pQ~QiD!7Ns|LniMk{PD`3`pL;|=g^GYSgWHrd@3KZm|#+IoB4 z67}mGdHCFm4~}PvbLzEAj6-g95Apdj=X4_YUdw014NPMQL*@8%xT{xOB6j zetA;ya|>;Hl)?$H^MJdorltx@T@LRJRB84DwWMT7sMMY7oWAp3M*C(YW-i03nsyhk zN*7BX9#eU(a+%lGKTU1qBx!X|2S56q^Q#7M4=cG`%<@&&54M}uBYz^UF73OtlW6d{ z+j4x_y)m8eQ-+(Qslv9a@~cn9$2&v4v{r)Ozbu{@i;R?XQGa-Ki?U?Gbxo|~KUx5{ z(ZH`F6^I^s!M=kK%YL5LFX_*$)C(1NWQ$sa|GHTaCbWVfjC zA5`94o`${Rchx06@}&Dg$tXuRm$$IUtR8VE3bM64==jMW) zG(W$Kv?R}eT{2csTCVZ{SLOXSWGTryV=rCSVvBanpz=AfA@vv;wlXoqh~BZgc-o*b z=coj35ri$S5k}A1(?m0w96*L=GrW7gonRi`=bj(nq|u{Y6;+vD=>LIPA7vv5>D;rl z*e>dvGmPqPRjU@NQLy2AP}V0q_PKN2#pNKdEBYX?NL_61U3bw$_9{U_&MC4u=Sm8Nw#*(V&kOTEd-D=&hAg25*K{fL`j1d6mE!ZtUts2yz6 z#nD=v>J&71TY=53q~(8<(biFy#$!CCR{Tz^e-5;{R8p#PbCm3|;^Bf_Kh*AcCe8Xf z_EeOee7DN)PI1~opv!wiw_p2#-_iI=rM|Y7Bpl5xAfS!OBam2Al?_^}X3a+0h3lU6 z^@!I}j*XGw3kR;DJjVIfE}nsZ#+EtDra|;x(LG?sbM!Px=;!dzqOO+OfD%uvo4PI3 zz1M6lw}<4dgd65Q(xtl|;q~tqH8eCN;g_jXW=-Y_-kQnP-sn-_6FQR()elS)Yg#K) z#C0>p4#agRio1#Rma4^z&Pr)HQmUqYS%op;L$E!LC0!jIa^d`{@s{yY$s3dce{PGV ztc0)%i+f!p!&cJGpEM169|=xLUQ#|kV|ov3utopqmO8^KndJJ^uGN(F8MhQ4AEO94 zJ=nUwc+y19nuM@2S8|@}D#`VUyGKXD*x63D0-ckKVFo3Nw=^#Q>xtVwuA&SwFVrI_5Vp|(u z*(9$TT5=4>cj^_cjt9fMb=_CibnP1)|Dfw1aB^`|H!XFOSWoMUsz!uo(9>-2P{3VY zvF?|%2mv;Ez?yF@oO;YHZme^!Nz{Td)XJ55)f8Md28QHshlJcz8v%HQpGLJh_ZBFH z1p9lNWb~xpF)OEU8~#@ZeTi>MfPf-Oau-Z;ph*&YN3wbo%|-3Vg1be*D8W7aT3#ww ziBn7Jn9PouP9iUl1@6(6A>U23;WvV``}0+L)$L?a>A2j@5##KT1wY(K4H4%%CLbSn z(nuQCOj+M=n^`C#N0p@@e?lA2D4mCyB<`OFb~$R8(0RB>&}GU+kOh?)y!1e?KkDU@ zgLKg?`{AM*A`jdrO+-1yPJ%LM5840P+`Zw6KGCj7aiiGtWVr!?fbHphzRTa~9}dcDRzN3? zP;g^|pJEGi&moDT;%=*&tRJjVG<}4M`|_p=I8RkQ>2yruYkrE(<$c{lr%`l;OL?IpvDp67YiRF^k$-0j|9w}+ zANd9Ia&qGB=dv3rFBFQlvhZd^W)oUR-Xdo|IBLTtA~y~I=I+5`J0BH|Y?q-hcvKa+ zr4*`O-w#1Zndb0sg9A@bX`slr<{rNyKO4?xNv#@})QWYC35WhL=GJc?@0)$*>gFvA z$=#`OSIm0P75Rn5CoJOHILMo{EP+RFX^CMS$zMPP|Dg-@oq5@+S!n$3U0%T(*3xj2PGcv*KHa9o|I|KjN! zDNx~#3k7>OR&M9OH%TdLV`Et{K2%}nm)`1PLb)es;@^yir(Y(rx;V7*@uJn$1UJXV zJ7PygmF7fV*o?I|Go|6J$jwcSwo)!fwsHF_xy`nFD;~#1-f%h-MX}+qSYP= zc(`4D$@>(c?7R`GY%^oUCKe?J3Hm+CW98=E+`9jlJR%fiQ$(M z8rSQ>UE)^!cu&WT{A~}_$gEE7&6zm7U#~UEnIxv%jEPWdy2t8vzbY?!MsLT(18$K^kn#Ytfv*yiNW=I4YrBz<8 zSYSHFLT9S1hLDWk1UqjcX0~WL-2S#t4&^_!GrW#_K!h8?Bgp;8$O4GilaT(^pC^Zs zHQO<0Tn5>EUI6#Z`Dav$1QGdb5IgO3DC;G6NIoSTU!mKeaLKaEd8V#q?rdoRCj{pO zW3XVa#ex++DDO;|J42yf;#2M3>>K)nL*uyog>~MW8N^4396c`XlYxg_akocY;^D1# zS=Fi=N%D7U4!SG3#;u(WG5auWc)}(&_G84xKR>;aakgcXK{<1t%v4^Qj}U=>8MB}jileQ=Euj1Xu%vzzN|NnSvstkbg&B?W->9yT;SuhA+`B8Q ztEosN>)_zuU*f+1H>~&RjADTaCV{Zt(bzu=Gci4Pf71wT0to(WEv8!q4RAIGYS(jX zZf(hjM|erIfam|5^3|BLYG9G2DknHPKPD;oVKrE6lGkvjW3PXh4sf)_K2EdbcGhXK z-0CtE-B_Y&O-hc72%-!r^*pICVkV`$d>4lquMP3Lc}=E*)1_7+qgACsOY9-hi`T#Y z0FUq+wgDN+;DY^6&na+4-jdf$E{E1et>2G_cWY^J?QdQ2ZO7*hsk0^S}2L8#zvL$CZ_}LP-419KQBkA{Nl90v;qaWDAvX7xjj!xWA4s!CE zx!+B`11%B>w_Qx2{X_)vdDOWRx zgD~{@>6U@yRqvZprW%&SRPkBO6#Lv8{E^#bRpTW1f#&>_y7(aM#l&b@sZfVpje^^Q z_$I8=daG1h;mK>~N?kQIwa`Dh*Ngk-<9MkK(>5?jZXkoRi06d}EI!V4+PG)O8x}&E zNhb6heFd7Ls zsS?@E#KIX$K1ocyC0SM9{@)`|4}CgZc{6$Sg_=?;bB9$Y_hC94=;vH&;0N#m6L*q) zE&8qUq%;b9VizbM6vegRXuu75-CwTod^726m(@77;byQc8H=$IaQP`d*LmiP4!Df! zH`tm<`m9Oo!1rJi`QYw1Y=2^m-UXIX`Qi0DHsKL^tQ!C2;jvP-OENO(Jq_k8jdzA6 zYm0>T6Y_R9O~KQn%9o_HS7<6XyM1}`wxe<(F36#a#o=R&k)_ik6Sa_5Z29ic10}c> zt|=ewDyt8wQ)fo_l_1i|&j;9-;XJ0#k9vVq)y26RnB7mC>+llSmV)xF(KqA{RWq#VLS06_qr5#EiK%?+~zgq}F`Hvuh96j1<1R)@J zID5mJDT~=E_%un^wq$R7&8@5S3s@lt8LpEbQs;B(qy1VUqwLDh5AJHj3=c=O=5fK> z_;_L;He?56wH^Q)Dk+$x2GOWyU~+s9tOJp#g%cb3)BvCQkGOTgE>MMRh1yY!t?VLXnF*j@N)!Ww%Ah%-ZN9yb!!j4pHr{A%Y z_XeKS3Vmfvr#PDsjNg)8r;!Tss02gS&5GIM=km5FSi2I(4YJStrh2|zwnb#2IGT~a zA^)}H2z_~ZJWzmm111OtSiP}d_n{87)Em-qF=#+X*(`wW+~F20Ye{v{ytS4Do6a8D zB87wurh}yuO$!p3QP}|*{h^FQp z_p)JEP12@PD%zq&=_Ud-JIv_VZe3Ha!alSI^&~^4pEzW^?+(7NqM+V-W|<}OvT(AD zUm->Z<#S1lkEwCsqgaY6y7j;FQeuZDZCxc`Ri>R$xV;vh*hsrmBi_vwkGYMBnD>N9 z9xqGqSHJsiQ-;81R(c5%RM}WOllohMxQ3gmq2u%bzCKYNLvuCiZg1iz41#Dg04DrI z8{tn6=i`;m!ELiCx?$@;FRZSWt-y_$tp13_5AN92V9YEPbGjR%kG)%U*Z=d<>mfti zIm&L&yk*26&GPPW-cy(TM}@5+-nuKAot$y}hM~OP9JFaDd)~1lRm2>E|2zyonYea1 zTc20p0X5XqggTq8l?QX8kTH7DVJcW{N`M-)DgGbh@uqXbMY?1Y0uvAf#($UDzBM?x z(DRhqB}ubcb|lIE8CaoxdT|nn5nfwdsDVHST=n_euEM?Op0TL1KCW@FP%u$kEXkwi zl)qIsRCY*h$@Gp)zg27;86>lnd+?dMGt{{>gx@hC3ZV+0w+|<+As-3T4;c{*U$$zE^CekoBil+SBus$&^FOuX zvl`JB;yp#rK>gq6S~b67t)ePL9S(KWnJux2oQ6~71~jT8<7NF_=*Py#$8)(KJiK1+ zSN6=@T;@SlFz=b@O>CvjW;gGQ;Oa;?$#sULoGi_lUw`RtxSo$%Me54-w#v_)fk+>; zap3O-YX|m;!YO}`HRbb=y`&Ynp6e8}s0i`lkM~k2Hyg2kmVb-?gUAPX{0dI?53MFF z*aE*vK@gP!&R}e8T%2bVf(rmwKeS^bDz$mkC#E$?;5!Iy6aV;~C0pGQtTr&20Sj|E z7@ao?NF*8ks*eRsUu$Em-#D5>5xnN)> zU3P&z^w>pN`AzdhSeUwC(g-tr;h&KESDW4w{i!t$b{RD&HghhwrrHO_blHkkQZtiX83X3K~5va;hw;a2g?`W_cio z+BRZa?Hl`0@3h6mO{vr`+$h;eiL-Bb&S@jF78L4FGr`^V+%j zOe^%PrhA+M5r z>LrX1)$)YHT`G;7xAF$}a%OoOW)EcsUx3#}A>DG@#JHI2CRauk$JMX%vn_N04fWz@ zq|MK&_NbMW{|r+Jl6%w|m&3;1IOy2xbz6z;iAi~R`R>5m-k+w-=tCtYeUpE}Kzjuf z@ZSf?+LKRekFpfFY0PEJLuS;(lpLQyInWfM??6(UikGiErKO`Iu)6jmu0?0YsV70n z!(hQ7uBlDaDidECBtI%v5426w-MRa{iDEt1J18g1k48K#I_?X5A9BlQ5&8zb1>RmJ&Ey`zY8uszsQ5y$ zs(`z8d_Q!n%NQ2<(;1aNJkq1G5)1&?2;DFNcT%Ss+V)O+?3a#NZHd;5r?-ZL^>eQ1 zY|zYRS2W4JBscnwc?P%UFvnp%cRxjL5Q;Zf2z6;Xt=trtqXz(qLYviAt8DvA|xS7 z^iI^M5oL6ucR@t2dG+3j(ZlGYkKTXo0v-k7t(u5pP z6ahlX*qKcNSL6-PM_`-`Q*{aWcAj6)U_LQtsOzYcc;wP$fr}qo27KM{`VnOCXGm3; z?a&2}Zu4il#&tb~%|6K`QP5?Kh2b=GX-?@d){CHTooWc-mTI_g&d_|=;qg&u*=TSX zR{^@a%+zv5E9uqb7k*EvgHfpeM7OyUDSB_oKsjK}$5(RRl~;+%@U@!<18VNr(fh!k zsp2e@^)pl?qbgUiZ2}n6?vx>Y)}{7(gYNPZi01kLzF94PrE7O_5;^M)9i;~itk0gQ zCfyZlXIc0ewZ3p{Vpk%Zu)M==O4Yxdy7dIU8Z-^ZQ*7$Z@b>0iXx?NKJB`-(3>8c1 zjb)$oLx>%Q+wbr7d`P~&l=MX9W*odWkyz){mogq@nLTO}J?kr-;}d9->evnhZ(gci zE?N7pJ0DCfI9`D4S8Er<2EQ~Xaq94;h~eWXi9z5VGg|u<0n`aM*#ZuLFK6mYUVxiR@AO@^diN=bQ=mQcu%^5k(gB#KotRwsY1o+N zM&6V+pVMgh(p&f`d;!qBd(anNUg7}60NB?b2I(z&m*yr)5CGp38<#SGhT+$0YBp+B z<@(MwdQ3JqjUKqlJ{Go!io4OUGqTdzd)3ALJ<0sIWQd^P5x`M`UZ3eB)Y3ni07zIf zs%dIzyVE0G(7v>sf+svA07x_nHpRog$B~@H(#;$InC?O&jk|=2W0) z(x*l*W*u!-H95^bnmwP=4{!K%_BnUz5`5m5vA;N#v82S*kSOdTWIyi=KAN~T+Fn?I zP(gLu&J4Z65_BY5$28O78OY`!l-L;sSB585sW|jtN4W27IRXprb*anQ8C{nXiX9*R z_&TGdst&=Ds(y<*9A$8ACedupdeTb9Sie@6x*vMs2BRBnRTM^gA(K2$D-upoZVc7u z^1^*E0aIS9Q*u92IS`Q+kK}IkV@GIX&-j8ejiM*WTEM=*2Uk%`fuJ zJr*c|C7<<_`o+tJ`pQP(GI!x|VW~PcD}&&(j;AR-SF3ZLpN~JJwzgjjwPr{jiEhDK zV)%QSg8t(qGROMPAV?NUi;DUd6=b6zhqSL=sj7<9H8t@gw$pNZ^8w7Og&a6_PS?2} zDGMtn{p_d-0gkJsOs9B|y=#Vp2k=eEl3%m@e8Q%6eGWU<@wRM;6;4(`J+j$Fz%%>r02(`Z1}D#2k3}p}Q$IPMhhJSbd;vI`I-Z6BuiGs{$SjtY%)`-Q-2A4p zgH>#Kaj~nn9G#8nrYD7@yb!Y0vH9TBGh4|uB?clb7jw2e z&lf*EBEn618>@xXbm)Wz+o+-(QOLsj8NNtfi7QM`w^!dpqDCe*@v~o!VIbrT@@jU( z%&AW5hHBzJ$*wt(Fp0@p?A^vl9V|xQHNe+aO+9k;It|sFuug{&&>H#%T3ZAdVyyQQ z-uo;WoUHEmU++9tk-Xu2?5ow<#_KYW2z^$s+MZ^RwAznHT(@z4XmkKpm=%EHyVg(F z7+<9E@wpb1JbfqJO&2;eY=n~s0DJ%{PFNP79G2Ctx{?@k8}QOi^h~NJJSfR3df)p_ zHzMEEGU!4QysOiz@-W&)>yhb)zUY=~mw3#p7vNxFOAq9b3Th#TX(ksR+Ta{Yv z*vec*v>_=UkpzBycx}(7b#=PAp0@MPn!T~b{Wf@fsJG4Tr_hOqBcdbRPCtt)ut5z! z{qJ_gQi$48^@mhN9~_*DW1BEYYILabLeM~xdJe6vD|ui6V9NF%)&!u+0Q@E%#D$+a ziWg}cu>$ZlNW?i^OC57q7JMD@IM zG&Kc{ist%5sWKi8Cp3>t_5yk!9oPK914KvE3gA@Y21M|VbI%5ulu5;+XYMo|kCzw*x0k!%0 zJG?8U!T$i{6?ctFH@9<+am09@bs^mKVUM{_UHdMT5eQaZjskk6h-vjl5LtRf_h?VbZt zx0&fM`AhE;tax?3J!8R^3v(hsCC#Hw*WElfL7P+c?DXIh{ZBN`=y*PJE@J>_xQv%4 z_} zLoemzxTXSe13>uh8#}kZ>L!X>;*MnDZX(12x$=C$oYq%P{$2(mV3z|T#}9g3uaTRo zM{5+zwAH*)sDjb2no?0Y^;3&^MOPGqU(fUNrX1Os<-HFyGh#e_V6V`Y;>HX;9aU@GhLkZW~p3Bh#?PTzx2Ub{QCp1Y~G z#U7WAfI*A#sN{nEEg-ZXTtaR zhJO}p8g$e&m83<*>69tTbg{`>XX+S3+3!p44%!fgSK-_CaVZ>I3FNL)@jOc6t<-|(vQCA2R|E{nHIy^83yk0btn!M2{ZTL5oJmCpJ>E$bfT zyU0lins!xc_of@RWeMZ>IZRr^4Mjq00$}1D!Fd&ghZ3U*w#6v6QlqS@z`(I!n8pBc z?Ql9J#-i4O6#w8L{8cNX1b3YTvkZTs%7A*o7wYJqw?nl0kyZhjJpsTGRvIGkt0O)x z$xc8MLp z$X5XN2*8iQ&++_TvKTQGzUPNKxcNtmPFMt&x+x57t}v)ZFAIxDns`H6n;&Qq>tLoo zRNL3lZA!>HxmRgpjE@rYVGXYIQl@b$o>N=X(VxqkXkun&{ToA(PAVSH!*itEG9^~} z5jY`_n>Rz8n?ZU@J%?8P9}H22i(RiiRMNUNK}q;|yOg|P(F2awestm3Xx@_~LO=%W zb36u%fC9O9SyntRii|A|nOy|9mK`nZv8C1XBd69$LcLN^>D25P9Rn+ zHl=^v|VWF8*zxbn&=`Y3(fr-m5S&w@Uq(2u2Z0;nbFKvJ+UdZZza=hl`nE~TX@d4-|4ht#{4)qPc|gE zyFU>ki&s)1J+aq}E~jkO{~3HvPV}-aFL;_XScgFF38-cffX)Fh{kdgE!!rMHt?T(` z`MtD#);Y)$HyyAShZR^iz#<=@M!!E=MtDyYG%-?Ig9Wex)-2(m7V_) zZsmQ#3i|MLOms0-_Kk&yOw9(7xPNp?5~WdYN3_Sef!O>M3X zh?V|ZuGRo;cv;=U<=G@{%)MYZy%opp3LPRyvQKdX$pr2|uxgSOj-$ug61|Dg2IsqN z*B_l$uA($A4RFCccRBI%4ayP#wv(O&pCs61gZ%et*~Q+n5WRrRtFER<=;J>kxY_wU ztoi3^vO3wB{EhW@EZ(Tp57^!>oU{G3wG(o$o)O8nE3p9wBm-Cr?(EK8Kw91^EHcWh zr5SPTwk=LoS7FGwA0Q=hG*5*Z_NvyNySH=kEjpIRc-652mGTvfo6WhTs-T#8P>jLD{Z`fa_;J~S- z4Pd28j4H06-_s%1VUuqqGGSYNN3qIEXiuJ=*D6o~Op&&>cD>%SRK@kzgK{?$WU2sU zgSs}&D=59Z`IYli;~XGE#P47y3F{^8r3=|l$&(uzpGj)cH;08Te!yPUh?r~I5y*wj zo7#T9a(U={G*pa};OI5*k%22|MRvNoAGCu9)@YwI?V@`ViZ%Uf$<~Up!J)`BIKMir z|4YdlhPtiCtDB)KhkdZafv1j;1cr3t4Zf*q2{5;}r_&38rh9U;TpUD{-2D7!c!+Rk zMSwqe8SDwf5wy>I2uvPE1UwjfFSP6(Vbay;R0m7Dg^AQ602x2Tny-MR3#;UdCcm%) zE4ysGomr|=uC0zL>HOaFU6(uW!E6nHzgo@w?!g=v^e39b)RS8?V`6-~;9Tu}?BLh2 zTSCzpLW~YGg#b%0G>2H}OdtpSDggNVOBuGt^k}hX6W2XL=QD(I<#)Jcf(wB-EXxzL zwQ!?H_inRw_X_!&+{i*7^hkA-AT7mSu1mk=8>pu$sq;$H$;zW@el52JZ6Etw`**Wh z?UVofMK;A${F9xH6%C2|ZY7m8ne8JBM4f%Gt7~7`#~7NNq;8(`E=ZXH;j-P5cK4$J6ll#=W z?UN*~C3qzo*z*;W>B93hT^}s16Cc}t1Hxwi11^R{r~>P-wAZ(?54pxLfMOHgoivmYX;)5G{2Vm|1-!l*4ez)iCCsDF?eU3Ie zo|VX4r?L!@)K8%FvPbk|r3WOE;C@p|yREDeW6!b}YexCMN0x_U6jxL{_vekNXutI? zat4m9ct{r;l^cYI%)Fz%RPYb)>^qBcq907VQSnA7Ak0a~b!JHiM<%Ec@JGJSU^0DD zTmg>I`xK{1*iEh`zltguys4A5lMGn?=Ak3x;f2!b8HxrK(xaAeaK ze;Y0x`kNhH0U}xcf(DUg{+!!&s52-f%YGt8`6hCF$mO4oxs}!!G&hQU z^d#IO5G|FRoy`nyQF<9zs6>C9n?oz8aVI5T+>Qqmp*&utQRoz0I8@_4paqM5_1Bbz zM7Z??)jQ9wI~8mH+YqKdHYZcDq+YbtWNXvUnpyx`K( zQkB%0?$x-I6nQ(lXT0Y9uU%(vs(=C;eTDKxBKnG<+Z>VYA?7GrdmE z_d>36C%sf9O9G2ADxEIyt?&*48=f)Zf5k{(9vRoB-i7O3W#yNfWB>)gMyxY`qU)9EjX*P=_z z94OW`iEz;<(c%9YN1pTxjYhQ`o^O{q!jmk_-G9RYJPK9|q7^h*AG0+Y3E#akt$agK zD2rbRFQ*LAO%u@x8kKD*xF*7b+h2mDcxgqd_G5v%LzcoFN4n=ZU$V2EYtRMcJ z8*kq^IzKU$P-b{$G7mo^r7V;U?!9v+CKFr-oSLkmrKQhu71IEY%#`Bv%Db|%@@{RP z-N%nAu1{hyt&(mcYI&XmQ~E1&NKNKp6F?J#x71z_?Skm9b?F!iNyZPTnKOccK%S86 z+}{BTu@C-p7{}(FG_A}iXBF)Cc?1HHY#k;wBF@D%7w-~GVKMp@A6^N)#{J7O>!o_#48uM>bsc49SV)NJ*Fxo2ve5(PeSh$3 z)5QLGmX)UQMVUN6PE(tzkzLqjgLUa(>g$ZQtzg+n;}Z%}uTLZ(Knv&LNj` zWEeG#M|P3h?JoD+F59HZO2ll*3vdj>DVXF~V-rbAgZ#tWoX$zt}| zG@PG2v_t9Mc>&XoMH&Cr_6nb6 z`ETD=19wl76>T{IQE|X~A=A~c;rucZy0YQY!l6-|sQjW3Ybb&B}-o*FB&dS=x3AxAxz0Sy<=rGZH$#?=Oo7HAh~b9)KOJA9lM!3jRF zLsv+Iv!5(x_U>l|litO#d2R?Dk~l|guKi)=Lvz94)a2yk5L?FR;HSE^rk1k6c8~2J zFW^2UwPbx;cdOHyyobU_#NTin=4*(RfC<7JXr=PCx{o1-DTZ^|;g8dM0;BDl4-WzIlUfOOAvNd$tg(PD)I*>}TJ; zQE+#Xv^Cp_C^?Ueul(TJxSy99urE_l6r8w- zG+s^St-e>*3*eBq@2!x*+_EIVO^Dj@3=7MP)#Ql>T|z*c(;n;#jdelcWd_pQKk6L& z4((SDVFv9A3lA8t*GSKNNYUgA;PCnnR}fdju3>?dr=CZWrSPz- zg9==K-{>FEc?b&W9l{XlrdPi^>Iuh|PuijePDu>@PgY!{SC?#;C&RJ_^GA#l&d$X4 z=~-Pfzg5u7q{l5^-vPzP$yLsHr|;HmtB)6ibg!xy8ZwnC@YfyjBblPB@4{q82zGF` zE?N{%>`_>fINl_e9Obdfucu#G&W#28ss~Jn+Oksk(Y8P(aWAW`PeIsBSSP>gPvTk= ze3h^Tj|{i>`6L8l9G(o#1j4q7y_`|UEj50pUgA#aHa}*TvdbTndMJt7rey_2V2kH% zk|;hX%MXb4#207N-Q+8Apx@YR%h10=sCOY^X(t{jdEVY;Fs;PrNK5r-H23}DPEJXK zzk!*v$y;u{`24b%>oE6bL{)*#nd}MdDvs6X>#j+o>*AS-6YdqC#GZO-sc0N@_Jjp} z;eWXAe0qPfb36JvkY&x@WQBME&btnDOZ7fu1p389%W?R)J26piOF#unn?m9wuWns8 zAnu@t0trTZ^pM`W%_l5275ak-_DwNLPftY+FE8i76QZ%v`i5|>n|GcjW2_lu14PsQ z$#HOYcD9=0VCD%Ohrt{V2L$Cj70a|L`~W;dV%gCXtc<%QGa~)?am}%h7xClW1yD2S8$&Z%@Jp5NPAX@_2bD(aCpoW#CvW-H`D++5y+{>0$bBwO>i0#$Q-Dpo z_L;i}_K;zwIh4cP>II2_(c5x-`=W$rK8&ggnj}sc*`paR->5K7xwIxJXoQpDJ^_WIfStqULFjhgYm{3Sim5~T9(T5gx+uHn@HlvM_b!6@j z#KSy~2YnwQOgO;>R=xB-)AS@er+fGzcQ&?Js5f%f%3;;xFTBSbVzmoH=$^KHItC57 zW{_o8A*fGy-*&T6pEqV1eKi{Dng#i!WYl^m*f%>1tIqEuJ(s4VKM$v}JMEsaNH(rP z#AY4t^+9+3>7Z(z;oYO9RWCJS@!7Jmw8~|<^NW&kMoD+nn%*0oP@H}h`DK&Rpx;*i zT>B;{iR_Ijb2Sz{G8SFRN{$mF+`4%q`Qp6y=#YL;%*LB=$m-qs^T? zj09QRI!p_!1*}r)q>o_=j9#gBwoBDN0+Ooqg*LJf-2|QvQ6%RVdn@-j3LiAi?P7Q^ zjzSaPMiDAPIC1lTJQ{0H$Yhs7%qd-EpnGD+1$jpAt(Lo`ybJ}luVF~H4MX!~%jsVAnOfp%d_0>aSXFebNu=_=03pFLQ8ckzXU=NN z8S55PL-Jwvckywk-*0=+#%du&yHJFZEJiJI{a6J!3Lnn3Zr|A@wPK+NV;vz`#SUzB zkj5<3rrP5y_Z#|IC`y2vBYS@o=F>!q3Bp*%HVc?|BaZ#}&Dn5>!mTz5!~82d$&`*z zUgLzp``$ixF1~TvoNgYc=d#^tFmleUOWAE^HyxFS6xi7aKUx(!7q!QKX?Q|U)le%S zBJ#86Nq-mF-Y}vnCT>Md6Y*R&Yszw?Oc-Ia)NM?9G68e5>O-9=LfFn0Km%+X^qzPR z7R{g?y28q5E*j5@7cUDtzg-%Nrs*S6g;ailKf2+Fq?|%dTK1uKTI3QaJ}$|+@UAN8 zBjkpQ_wme%9y-vFw()C@2V>6wvT#160jQ@V@Zfxd{*_UO_ET@>4#C z>&Ddq(!7g{vwV&XL`s|{$>UTga71pYXLWJ(Z{U2U$+yGZL)mlj*luGh%Gt)LjL(kH zJ6>>D9>F(?8%?3p1 z45xz3Ue~o;MFL+494wtg7X`wTCB)tbDA#?6G1$%T$R)i!K~>5?V@FUeGmo6>*+JF7 zN6WACgCy>G6tR+>LR@!ft=~RyQ$2#yKLs*-}@|Iz+?dx*QvhUU&Zjm z->!Z4LkbQt1|oGy;N59RoH^;zVd9^A3M={79|And|K3lMl9JN5P)W{jm}l74ZnWY1 z&4^Dv)Ewj1qtCaeD$V-x(I{UmwU{@|Kqqyn`@S7Ztw@x`jrW<{v2_2=t*aot>SgW}78kJh8yN*p$*0s59@~yI1Lfvb)D+5HVm**Etocpa|S{ zt`VfFrIq-vgMBw*qB1fvk|w?9*Ro4vM;&E)SV*^)nWuyqvy6HeGtZm;#OMAd5TL!# z>Kni>_L0@t~sV=O^s!S>@$ldwYBT zmH*+7>=|YNv;d}^QzJx#*5{I!8Pm#9{_yo}4(1L%M|i&izzr(=Cw=us(?@8_0>E#= z?*ug<-T|0|;!qNmNF)nQ_OzUh>CHj+`--7R!X6veLE2=iZW{oTQ?|9e&4S*u=nSJI z%dp=38+GsE!_Duou$$Z7ccr*_%6i`92ZeuQX9S8R0IF!pOkHvZ&~Croo8O`c|5@hX z4`wBk8xu|Lie}ZO>!ua}_r!x4DH~Gw7qZ_)&(W57dtmmb=Jw4HGS5f;-w-ra00_n_ z9_Ua6w3*6wE^7zYGwHP~kIdiT4-Xb0QJ(qHxef|Y)vP~b2vy<;mHpcm%eij!IiS!t zTD)$yg=|8D8B)e_q0zJ_kfx~_K#U}#t>yq!l6>lQK>l}ZwU!0RVxr%maD?EWq^+13 z$};gXVX0$Ru^;?t)!LP-(qUn_Bg4bVG21CHap2E{z>YI*mj{I;n;o|{H%kC(ehbfk z(ni2WK)09bcf>bMkzd>WHlwcq)&NvC0Cohh5HWA;!MORduE}qHOAx05gna>CSaLG0 z(c&R@yyU}5`b@?DW)hJEvuyq=7?pPmQ_BMMXmgZT{LkIx`j-kIRa`8N+?q3EBa!EfsM_rICza;PDdrUIEwVDvE!%0$}=#xL%5zx}9A{Xr{MI)kIDJ zw~Xm|q7iZveE&~ZIT-JMtJ-bJJt4)wH6FLNb_f*0x>Hfo)MPuhZd@wCzy(bMN;tgc z)=c}Jkigc&`1dBEiTksH4>}2zFoF1CUhWjk8;HcTl2_yZ54-G#J43=9QvMskD*b{{d*ypmP8K literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/debug/path_visualization.png b/planning/obstacle_avoidance_planner/media/debug/path_visualization.png new file mode 100644 index 0000000000000000000000000000000000000000..7c9ff28b683182e076dbd052eadc44e82626c16b GIT binary patch literal 151456 zcmd3OWmp_Z)GiX-g9nEM32uW!NN|F?I|O%kcL>2ff#B}$GC09q26uP8lif|Sd%y3; z{dwzopnIC0?y5Scj=b+FLS>~zQ4n7tLO?*Eh>HoyLqNdELO?*{!oz~E1Y`nDz=s$1 z@5L42!Oa8SFa-P=-$7W_LBZPC!CBAF2*Sk5+R}*L-oVbt$jbhcwZk!V8$b9aR#Qb) zhYxl}dJd-6R-}rimPX)<5D+X(EUcRi)l4i~X(23}TZuWOEUa6}e#{)3AwlfS+j(C& zdDfL6AV?v^g#;B{(hioKJ(MmVfu}PKv>Y7n@7}*8)$7N?Ko^$n@KuGWeydvSUTvmP z!ddu9N%PZ`PSMmfU*R;Qu#HjzBgX{#Mdz! zY3Gj_qt}{3#MkM^*XCHbxEdkrrL|r+hvfAZry^dH6gr)n?c>eew0im|HWq<#-HCCe|39% zo0QuCtk6}$9(+E-Jrj7sqboX!cbPXObl*orUHT93RA_gyAF`gsX>wUKy}b}zT>lYIZQB(H2ywg_z4DyJUuNN;PYi0hno{A&sY zSQCu&)Np(UB$W9d+4N{tSiYO9!1e%HsrfSuCpmZrF4o+R9zhAgL&dg)d>wH0(W>2i(&Eapd?I{ygb_Gpc6);7@ zJ1iMq3$mV)rGv`R=v$PRkj*sxDU&|01Jn=ngZgt6(W^H{JTEmF-YUqS#3!uL(!cpp zMRf`S;UVFaTWk&S&HvIUF<|w~%T@^KJp1SzS92%@^XNAoS`4@egG$#`T@|CHuR=C1 z7M^;iK2YS-&GvCTyG99E*N5C&afTX-l4pB8%S6?2U1`Prd|aQPq5wSo!vX8KynOz} zeMP1-@f9Sr%`4a=y{;4fJL-y{j%fRB{UuLl9u@ju!nL%_RLdFMEJPAMbmC#i!_1qQ zr%-j|PFIySL4sDaX`~1Vi=yCmqsA-?dPvpTsABJ`ckvOP4lb*Btw)|1ap0#^nQ&{r zygtZ|-A%&o$Gi??c}*5Ps;wSjX@e-d!l>_Bn#xZlqdVT;5>m@iAEPEdQfPg1w}4$d z!0@{HSk=pQndX9Nn(0_)C5Gu#U;03PBH!*XxcN#8YWvBIsblCm`SDcViM!EmD4!M2 zS)Wn=)zx2}7j5P<{*prZEex^v!J~Mt3ZdX|XR}{BtEzpa5 zG;uRbQmXG^O`zn}UijL1Or!asLzz3W_4D8;iBQiXoU5KKq;c2Cho0hFCjvRq%>J^n z){u^z7!#P z7S8(!m z6-`KDw2nxE3Jbu;sx6(8pl>UcnE$Ny-TV|}S%M?qc^e(Ys%6I#eI>c0z>#!5cj-WO zea(y7r0f7t%G)kwYjZF)uZH*QB%SS*N19ykNcSTf=5D8hx+VWY+z3(t)$t`eTT# zKi2@!#1RDhRrLh*)0GAr_6UY9 z#*JyJ!H~49?-axvlQc+1rKKV+8W-)GnMv;(suef2kMb%fo=`{1JI13^77F zom$}0A&BoPDd7bBpSixp|73?Y8RVV@KvvLbwI~ZMD^BXvYOqjy#I}BTbOl7E3>5HP zr}0QIWgZJ?h&jnYsJw^uWO+$bbTW0Mwr4QdXmLhcNWD~>B*Ra;6(IK*%F%9IB}g4$ z>Z=AaQgI=yzyK6V0!|;t9dGumbg7JXRNXvoUov_p4~6H@RK?R{9O8}s0$-=Q|?!ZRY>8u|)g+IN#o)aej zm$edrc9$X{;&oyAkSAlUWCA31KkzEe-|&uJ>7J3Zb=Y@Driy3?Y!bPqSVor7Bc;uwBXo!^J$jbKCf(D6870pWALrw^M!lg6FD!a0e@KLh&X#~= z@cDv)G-w9;xzk@^rDJRzi!$m!Fwc#)1Ruel%XAjWLxb~+uQ-5IsJ+;DfAQY+^y&Ra z6I|)$1Lp{dIg?(xpPd!04-(8@IyCO%yKd*ZW^;RNZN>dZ8Zl8lH#h6ish7K>?#C@a z)=^&Q_G;4!&co`7`D!MJj{@;ZIC>a*?2-?6DyL=U#69(wYPlDP@|FSXw$m%#1LUeo zg6;T%^<5C}Z{9x4@_{%BtQ3rJPNp#H&W2Bt7d_My-+muyI!<-P7Z-cWg`yWP1n(#eCL~vAC3!Wu1HYUs@g#;vjUt)b4P( zH`V<7bZ=;4GDGBkz2tm*3MApWKd9PWYI0ssGO-7R&fb^9%xV$yx~DVS1c*)(#1T0Q zx%ityVHuX`ug{kyDcMlA;ZGNIaQC9z|1`rfQIx#AX}9Owtj0rl$k`z4d3Jg%#0uRG zDBg^gXZGLWlW41meP>u0BLCxs!rkRQ@M3o&G%9L&-NV+FnO3=YwF^za@L;y0e(4Cn zh(qzEI#${*1Ud=dOzCse8BapuHE2K}>RTEA_0JIJc1~Pcnv#Pfv2MjH)z8llr$*}I z$L{sh&v9{+B2#~&DKiIzmAySPeqG>HMnc918_%bAYao}WIb{hGbM|0>qR?Nej(E7AN#(Gn3kZGuP^64pZ3eztVSz; zJ$r+60{O3KFUIrJTizNvqzSf#CZT^c4#N~0QTErJfA_+SYyJ+l%6OQZme#y%T{$)v*N)2fsjKHQup<%XK3 zINl4#$Hg(ZUs+H}r>Q!Z7^%%#0LI71%jej*l!Z3LHZR>Y2!o7`jceuD!NW8@T5Nzw z^Sqin)cpNaLPSgAudx1tejTJuPKV@Jh*N?2P0-`6=UY>Og%CM8ImpDk^}-~wFohlm z)X2Kwh*a#ozAabvYDt6s)|-`Y$dcU|KT`H^CQ&Sq#F7YT^<$drU8q4fG>Z;G>CvKp z{mL6)IvX14_|nN|O3`AmJJK3=;_{+(k!w=nI>PL@x3^5?e6^C)A9%GL^dybCn_WmH zt0Yx1+6jf68W{plg%PzhML5ff9rJ;fk}|jd+`KmN$D8F35kSX~w=XeF8yf7lr(yCF zjA(@Z*j!E_NHZT@rV!H<_ker^1cdq}D_&wWrzWD*VG(I*RB*sPyth!uupN6nbKXAw z)=A9=Qmc{D_80~~Lb_Uzx_v7>o{k;*h1n=a@a|HNLX{m2{ty3M3Uc)Zxnkk?x-UIE zUu9})o(Bo4hi@6etG446jF7gE2%EYt6gf(TXG zf?V2eS3P(Dgo~4?tQGO;vmPMhCk-8s91MiqK)dFW+i@Z!iYfU+sG?(oQ?A{76Bp3lbv``TR*t+FFU7Yn-Bc7 znH(y4wmN2(C~sgE?`Kh4X#k-TAtraiEjPkp(1p!IZXBtim4yXN2ZT$E$pXkH=c{Q@ z0M&NfBD~rkJ;$Z5x_A5zo2$!xqR;&l4NNBcGKTOn#Y}iqTM=0(K;m8Q~1Ja_e)Hr8Im=|;A< z?@0EncNKaKa_6J*pVZb$;+^-W#|pQFB1OQ!B-n)+fL*ax;$-<_kgoIN?T(kj55Rff{2i{D9JlpJry`uN>}sRlfE=f zeukQmuy9Z=(w&W7W9-_oiv5W90O$G!)(|#N(qSa%xbAxWwM@3Rrm)u)U3g>L^M~A? z*mJM$!)p8C`X?z4EDTdBOe$%^&Hx0}gsC0LfARq#?p(^eM>d=<01n>3%&T`WNKGhS zvj>~O!`fbp^5^OeJ%a-!IquEV2h?4ih4$y>q$>B0UDG# z)&->XO+jI1gtQ&z)}%WMhF>C8CC6Z|)?+r>KhrRG-=Jg}P;fH$_@aay z5e}C{MP{44z_Mb{52Q^gk`_0XsO;$!CU61J`WPvl-xe!9=*hu|%m`V%!j~NFvuR{Q zo}eQ+Um0GL8T=6OD!wPvGahu6>$!Ki6aoxeg0${>s0HTu!|dS zUZC1W39WGn34Gk?@I0yS4ri3i>G>{CQN!WAStF|0T9B`vg;qsi(aL~c9)c>)6j}IJ z1l>wo&?~RH^0Y!}TTKq~FWtH=XpoVVy^>Nlpe42TiG96|uhecDUdG?CnoAkoBDaqr_V>CaubmOw4N5%zQZ8W zLJ%PIz5sKubDME{u8dY}2NSphAG;}8$7E83pc?QV$J~3!Ad1m1)N?UFDekoU0Sb}+ z#B#2a5zZ7ZxAZPJ;8Ye+zhJR2u#QWKrN3t_3nU^<%_=qx??5s*jc5j_S z#=HMK({PGtf$#oejoDKyV%nScPxxTxGI#v4waI^ciB(SHWyX6cpI7iNn2@2HhTE-H zp0zW4zlIvA<3&>D z*l;uuk{S>xSoyktlELfRh)MO?P7~qSf`P0+N9Bo=;T4ar6kg}TlNrF0W-}OyDk{ya zbxB#g+@7Y)1g7GR188iJbw{U;-zvoNa*yTQ`E+ZZG-}dtqxr+i#zQ zI76F)&6KJvl(>|lsDm6)vaO9?gJ=hCELx()DGa!beEd~f&%ZQG7=D%;dLH;TBaU$K zcD~18|3iJ_cV+_#j`4!m1%@!rR(+e^4O*Nn{x_DR{HSk;t#dK7<{SMwTNL$wPR`f(8&Db3xhNr{u1MV#&@KT4Et!`|i_fzui zSC4oWIGx8yjS1ID_p?8?KC!g-c0wpywjb_I2DWL(N@oseN)Rvg!8OEhqzYEH4VyIV z8lHU?f_;PkJwAcS*_K(-j;?X$ig1iQ(pz&W{sN!_ud&g$iC|yuVE`FEy>T`e!xs{2 zV|rEaw-fpKn{YY>`*9NO<4?H{6X*NBgP=o7)myb7e}@u8R|ri>HqmL!nldXoNy;)V zTn`y<#oCEpr&h9&=%HeV$AXN_Y2fp+gx$h!`cBWwFn5Rp7>Ts7N$N7Ga z20ni?6)Tm)Jn&1UAi%J6`zkuDzf+JTIuIca=HvSu{^_LEg9EY}&{pAPk`e!O%IZSG z;1oD}B|<|>auj6rQPLjri==!p=(1YyvD2Td5INjh89UbdJt8!0Z_Jq%WTrLswxPsq zKsdpjupZ-}Njk!a3&$w{0=NGZ*5b0N%3)M3L-~h{G`_BV>`Tk`Wu6uQw{{W3UNt6& zrM(^Ki%4R&h=K zdZhJxH+ZT^KW^`r_{vqs1zmbwu!?Xcjpu;87Gp-`CX_r#;~%d-!SvArm`l*DM>M)p z9XIDsVZ8RZ8r<2murtEg`Z2e3=Uss|`;y_V`bUUS`>~33*9FFzznnWbj0WY;oyti1 zPb|Iv86^!PD`pA=pfHuBl(QMCCFKU1s=e@I*MTH-@;7Un>qb_DmkHm*QX#XibUroG zqoRC0U;cnir>ZPn1Jbn^6+4Jyr|tz_k+*NeIy;IJ zD*)`vkD-yMUDE8SXP!4;{JE2j3_yv@;}sOa9|n|($iMgBwrMIqo(k_+mGiva{v;D? z{*gp1U5X{mA&j{kAC)1M#b>bTSy9g=AaV~I&I>6fGxl7%Z*}U{-1YJNvia%OZI~ZB zhC)Q)8E45;+x^=wK{)VQ@_UyWqfMd*fpk?&*?Gb}6yZ{rugCQ`W;ZX{8{i5t()*04 zHcxg3uD%}D@PXR}p8dXKv$IWSFF!|n zuM!d90-Jw#YkD%4+JMH2<*M@FAamTg5ost8NM);SNMr5Q6u3)rh9^)F{OUctuRar~7@3bSnmEkW2x8b5GzD()6a zs#T&0YQxP_iVlRNn|Dp~=&I+z+jYY1u0}?JHOFbI$~~$R_g;PJyP*GaOO{RP;QDb< zQRs0@XY97~Hzdl^8+h*R$k%@ z@N0&w1+8>OS$V}U&u&I<@PUq?S1iZs!;KI`EY6?Ni! z>*){^9vDuI6D{6$I4#c_$*U3PYe-KQ(rpc1Qo87K)(#%k^@@~bFu&G4-7I{GNYCR5 z*FCWWVWF2c#fV7dL!V}gd$r!tAw6B%w;8&r~6Xo!SyboGpZQpafPqFX1dmzTeC$;r)~ZUN`^d)it}PH*1435Ua%ouajA5;$FaoN3QWDMW9h>hwcnfKN;#)A#gJDXZ#_qg2%9Ig)+7IuY5 z1q!b>@F0xi$swgQKbB9Eh8vr|X@W0M)k{8CfHhnV_ z$jSAewb9VJF~5VxQdtOztel}&0-wjdu;><=y{_;$^hHv-r>RQou1}p8tqp1$kZIo} z*Drg2C9s^Url|5F--#=9dA(u!Lc`SgC1&mO-IdX(iQ8AlqiZY0IGB#AGLzTjmzK-T z$rl$65L=^}qXl^x^I2CVrWE9MOv9N1nGq4lon2tR;7N_u$tG1C{yBk9QUmo!pYVQBUZ}eUI7YLju@fYtj-9jE3Aj9d4c{B_E%Wnz!VfjhQXI%U&y2*>$I4yKY4>tAd0@1q?$TdhI42v)E8Z*MU$ z3K&^gG0SEavH;A?%*X_Q;z%&o^1GR4P%ymHYOs5=4vYq}NqwB?uB3yIkdR2?a|eL4 zq~fOON;(SwfvKtKtVN0iExBF3OUp7&@VDgTWJ|@!KYbTFC$fb!W5Rolhg@ks!|?u_ ztX4=P4{17wwYFA1qO7|5z-ov8PslU%XciH4345YP1(+6B)j)j@W@1SH7c}U159it_ z*xsR_Bf~OF*+-+ZlaWEzEkpv>JFMyqs^d>9ia-;(bxvj(aYn%4HzlZFOAbscpV)N68|NA7b^S!BJMPmEtHVkr9GWui}f;J4iQk z)2S23hK`^tmJ|oPIq=gk&4jsrqSt7NR&RKKgGweB3NF7PS#t8=_z$nXjwG`NbJ=el zoG*SCk4<7T9rwD2hxNaC^cpClH-0*Dh?pO$^ok2JI-DB$8?qQKt=YMsN;}VF5h2M8 zu-78CcMc4ZklgB*bYptW(p^`@(r^{bM2T7%+mIC@mEg~u?Pfc=d-__w`+2D?K}Bpe zS>O`n()3r7uYf(qYiICKh@0@M7JwW3xOD9)5=XW(k`))zQxR>sjWe{~c&iLNj#qXghdbc9XJejU8o~Y*z<^ctVE1!b>MRqTrML?sJER#YdOH*H0RXzG z<;tkYb?)jE@r4xKMCT_tKXnRA7wf0n{p=(!bvilK;*oQVd>-?4ztG2q%Y)@bcV)tg zfScEYlCBCwudJd3*dr@qeE9tANB6oSv-Lwi*&2aGEFhEQze#}Pa^_D$^R{UEK;gGS zV{jeR3=-#~Ku;#X2flv+1zApK5#&3u>_YttSxph{o=@n2_G+`v@y|wjDLA=C81T~`fhli1iXM%NjK2a@Oe>axtn>5&W=q^e=C?cm}~bAAt7Hlj1QpINqjIXYwh-z+Ms zzTgYH`_~{QWVj}YqB*sVZ0=bH*(x=z{CkXNh z2VRW*XL>D&&iG`};!IP(i>aKh(td!Nt}J&5_tTk@IyULdzWLP4Rw-67rXrWeK`5M? zB~3dk9ftkgcBW2zdv#oqz+^ftrM}Ai*H(Kb_q%!o4AOY1y^L8Oap>kcbXwo)2j^ym ziNOK>>)L;>h2RFW{1awUzNgh0 z==x5r`YYQJ8_p2RJ%ojWZjpu5`gcMbecl6AS7J7Vcp zc$#}vE%b;sH5@HsqRL|fzC`bJS~CBj&{hx?7J9|~Km8up8q}mI$8vl16$6yNm4BoC z+}FQYnLlq3LZy_-#QLqQKTisBAe8=f1Gu&%;eR+p(M96?U_Sx$#ckU}h3MY^-p{Xn zr%)iDZ3nJctyU(JfK4k>U0M%g)Ujg-Em&{Cai8%Tm_?bSq@)be>k6uo6aFnXa`NG9 zh#F#Vrf$A6I*W^kmNJHo>Tmb~T!+EsZ!uyhqQOLtEnZ4;@|?)jAFmg}21W`?w&z?2 zXVVsLA__`ea~|xMuY=38)Q$10wADwjM-8j;AAYQ83w>wT*Vj++*o;$KMJ~Hn`!mK3 zn;&FQlVDFkXhU+_gFSR-Mqi}eoDy6{tl-Sc&K!m$y{mG4z9_t3LAUR7JQEjonVNL9 zDDl+NQ_Q8CjJ2gw>0-jZX`H&OF0}C({%_X7Wbu*z>FbmJuQCB}7}6ygj3A4~Cgiyj z+4FGfhtd4-FcCqJ*7t+IA7b%l5X5V{RN$~rh|+GUAgv4P>`lB~;s`G+B=z-7M}Va% zVX4^D(umU-c!=DzxIXl3fmHP+-F&J=u@x4Y9}kwS`;xwHv=-u^8HIY=Wg z1A`e3!t77&N}oD|NnAFk-ZURcY|Jfi&p4?M=N*@=h882%sxpkE&PF!{i>_Ksg$N6w z5)DFi<=^rfs`G;L&_!vUnTY+BR&XTuyRrTFmitK9_i@slfneCOZb`(*=uKJk8Dg$8 zfwgpIpClvyD3SAGM*w&XJ9`RA0Lxcsd>68;Zq@LCbO2-ADgcA8Ih?xmwp*Fc7mSIM0ucMX00%N-Y^Eu5IyT>R7R-Ct!!U*r;Fia#7V_g|d09l}z;36CwD zvEHu}(JcY#l)zFH7A%Nf;eC8F>itE@+2ZY5JH~;$6(Uo)!z2lP&(nCiK zgkX}2m1JlL7-VcqOJ+5ZS5@s(Qqh)nbK?f2MphUA0Zlq8c8F-2i;>6!p@a7^_h(_M zUuM!Jqjm=uAqCHz;wrhD{5FcsYAtDij>>4c7H?Pm-*bYxwLkI+bZLlVX;y7rKc zM3!x&KakY()P1qc!2vc!*1A%IS;{^zzH{3Pg;UbMnMmP|jtLt7kEJel%!hCs|1Msl z-HE#zBT5WR8uTcy9BDzPhKS>$f8(-7ivIQaO=p!r}omrQ0h{;54`;Fk(Ic{|Ck-^be;rm-lD= z+o|p`N!}2DazXr@kufsNv9h>xn`+e<3eL=?9f{8>THwnY#G|O!1*)9SVi;4By$MH} zY31?Eo_EKWz7?6Ol{6)S{nAD=CJWvyea4J{&L~NSR{nqAu#e6vizedIxNumv0+zrX z|EN?3Z$r=HEf^Q^koL)bEBO~LVnQYIrd>1_CO316*16KrfI%nFsg7wUZKqclMu%?s zy}A`vwv0oK8yL4f9RA}7f1&}u)wWNsr0Yd~iISGqFs_bA2fj%f7OSfGEHN3U_ ziEserlfJK|aCtZwF-|Q1_&@9EjsFWoMeD$2zmNZ#fqIU%~l$1P3<>T^t+h7c6i)!Gc!TT&EE?y!pCzEC?1uP7jWg8zbfl=*alyir76*L~q0UO30XwZO&j0B>Z|C6h zhbws4EUjD+b%lCZK-In5iGSn^7IYs7So{1R?`vhmVah=T~x+2wb0^Bsm{95EfaSk+#TaY)BmAN=-VvS^EpD@}Pt^ z%F!_~C$bWMD?fN@zJ7S|lN9D!Ny+4n(T{`VA@vx^aoc3z3 zIxfj-R_dzGSHCAYY6j8ZY#j@9)<`6rA5~?Rll@3>|Cjp!(+ZkIl<)X{pkIFDz&QsZ ziJY9B%dlG6kbk&;4Q;c|7<}ICm^WTx&jwK^#pN4_M4+>E?UT&qabCBrrad`+n@xsT zTSEEc`cu@=RBFVCUI|@$mcyZD#*GD%Qi+-MDn5TCqcYzpjMnutaF9;3qb);K=;$eT z=093M2z3?C*m{$p-Qrf`Oax~Lrpk-es$hLuJ@0D^qkD>KS-otawllr?!Q~W-PxrL9 z9=FQG^&YRSTTi*EA~>UT`!*7Rj%)MgWt)3NWmb({dnB%x)7v*=ZL!b%eE#>Dw;_(- zN(qK|Ub*?+d(nR8k@p<*_U&4<{<~{xCwiB(rf2TpHv)!L2Ald` zOt8%3R{}>*gX9B)IA@*E*QYacg9SUhA%aU;MV}jm+pJ#cza#YE58zDwvc@}B4yuj-Rga&w4Jr5d5+k>27p$@?E5E2{yTVK~MRMfHY~2`)3@j6`6d`tyI1{1q|dL~lOu}C{dpLlLavBF&(@t=^++9>E>yjyk}dWRY=Fhu?o zS5$w^=xis^LGf@jm!mivi{~+aYUuJ3&utoup>fqkJ{=aF{JdaWjnJKvW6>3%pJb)) z!}IW*LG;9l6_C|Q%!JoddTS9$=35?XDo1H*JEkke&C*bCgVheeSh_yO835N&sN2Ju zX!o>FX|j9;&+3&fy;Xf)zaOh5bio-K3nx5t!D@tPaupspa7gEJhx&9pNZq?~L+UK$ zaC#-&wpml-Mfy%|df{U#ce-#tuHAk~-WYv(`slWy99FR>>T^T1j!Y^vl}^_M0qkkl zq4(O-rJ#lFBd39)^$GG?H4@`mrvl4K_1@B-_!m5_T%3f5TJ4}tCgk_uQXCDXCN{oE zGJwto8BMl^lCf}b?55%qV>2?MhK&ut6>-A{?4g6l_5S@7OYNkKiEaJ(_N~UihS+58 zb1x=OtixF$xwd7C`<1s&(gf1a>u_JTqOuk$vhn!(Ag3AHN4{zhueIu+b%?W1<4-i` z4?FpNUo9-iIH~SH-o^GG6!^R@O7uZ-tBbc{2bVX=6(f5Mg_Ap8qYZ!L!*Pk>S`N&^ zzBQNT)4bG2LJZ%IcTaJ3KFp&}i7U-~@!wk3ZB$S;ZpN~A4BwrIk~*=}E!yH6V4~oC zX=gu|UY&y>sIQhGhgd3YNEOfl1SKua9Dl>);5}hd$t3i}hyWF9kH*&I5Z+yE-59W( z)O#Wmv!`G#!GR+GlZtUc5WRhu&Sv^DmQu>h@m`eJHQ;*1JF~FxEf}S(zns?C9~n+z zN2*&G-kU1Ym}`pM=~kT87BkKNBK7PZB}(EMEM*F0ot+m}5{H>mUN1?P79AdMnzd~t zR8+Y`cyH-5|5^Mr3I)rF=)JnbpEOj_)?UgQEETZ zI}Zcl18w!05OT7)kzTDg0b(x>Ugy4kIkq$21W1#1m$L8j9Ykr}d$;cY2mAob+?0yQ z7-0n(MFw(wVxr-8E0uuHdqRpMCMITVVEF^qrd809xKOcY{K^v`Tp{Bz0!_yyZXp+$ zBCBIc%CKNq7ae~F-^7Z)=V?Bp_^rg5GsYBGR7lc`#`0Jw>-;OX*zrzHv16f+THlw2 zV3ZMD7v5ipM+vwfJouuh{>kvb*y7in|26arY*8xTYdW6eUj0Pw^pu#WJ#4Uc5##XI z-Pbav|F!T!{=l=ZjKFOIq8o&60C1cp_j9_dw#P2Rm4tF?52;-rmu9jD7h@||48Ovi zZi#E`_R3K|wlzxUL<7}!x;NT{PFk0#bEdF*kG!_~DQi^I296sKGU7{lJyBGc`1pF; zm#DHe2}46DX*T-gZ^E^=a(bxj`XBkq6~VOT>--q5!OM6aUYagWY)iX8;t|>QRLH?#;lOn( zQF^*ETHc2x?Y;%~0HIj^FjsIPC1G?!KbQ8nxBl^H*Fwqia?U-y|2WUkeo2nFQRjk^ z;QhTd#qT%?d@`;a5iRgE`-;O#(|u;lD#QE96&%$1&FmYs`#{pERR+Ky;n>{m<|)X^ zz5^#zV6DOn5_EC`ntMFbPb<$cTu*fR>@>Y~7vzSCtoGHqUuU}x6OCIudL zUlb9~Y@?(3I;0sr61bchbLu1jL`rU4mfa+?783I2iZlYvqCPvDpe@>jqy}Kr)Qm22CWCgB$$DH3=?w?4G%YXdbp*x`j=G3m%Xka_oO(MUbIKxvtDsKKizIa z>#E@d=}mfC;!q@HGc==9Z1w59nG5-7vbbTxO>`61LVm_-dr$%VZ>4a_88{(GHE{kk ze{h0DY5{@E_h3VyZbp$lZy3mC9k1PJ`5L4^CArt){1Bt;U_WuxU|K9QNcXTR7 zFY1o_L;ioM8AeqC^GBXwUgamjQWF{)syAD%XQ>$TC#n@YCj1M#%@0$#kirur$A z2}Y2z^75Srb5+Tlw)#so;H_I#b7GQ`UB(lJ8sOBoXaBO66M1-O$RgY9U-l^FI0Q-7 zzk{?x_cNG(#6S$(dq24Zx!de|zV}|qXM9{97L9ml&Lnfm0jLaL#^EzMe_jsGdYGHP z%#~TJLhHO%d2Ga`pg#Ymlb#v1>BHZg(jsW-;nuU4d;OOE3I{Bo@wP1TY zXbOnKBX!EQI*bHiqYp<>9@8yt&@guUe&S)gZN}~hT5EjWE}Fsl|H6%89(mqFPeOF) zg0sSFcsb0MFKwEZTzH8OoOr;nMOqr++1c6EitX2=yi8SK(GwpU5ScHGal}zJNvD6! zj!I!j8OKWbWQ>R4b~3*EFqV5_4nik68YO2+5epVxkQGWXJblHOd3RmHqej#sC=$~1 zOTF!TXOUi#MYYE*A6iYBV* z^9nH#9`?h-Ba#62)MZ}y^icHA`rT&u|EqpCrPX(77=~hfM?2M+`^(ZS0>G|9Sjh;z zGcABaOknuk=gO~LMD+pf~?^5$p!>zRQjO~w<+(YTxp6S?6 zKHLs`f&1K?TuIHDdEOGBs~%$hyAQmPVe>+Vq;sx-qZ1Z`#9}^y5Y~gf!-P?pR<(35 zRg9SV+nrz{3+aBt@dhodj6W`;4`H(&HXn=w=yv$QY+4b3ZAi9gbg5m$J5ry~Z3>_{ z>oy|=Gb&6_j`4EMAw|?VjD<08UG*M05r!sPC4FAvM{NJ(9H$B-JGBaZxH7NAerGNm zWidQVhQmJkmM(;vmf|P6P<$QZswtLFwh|PS(IJM1_dH3*(B|8y49(WK{v-PxbTTZ7 zPaLt7{!J{;&7TMpG9y>4*JEVHZviWmynrAcpwmX!^a#tu_N#6xw#`mf-XCMD_l^r{ z$s}JPPIB|kJ1Uo&Pwi1PJkX~(6Y$r$ZNw$1;8dOmdX7z4HzHg##S7>bNnTePv1T;Z z617nHyn|fv_|hFwW-rG4erM-2dszX4>y<_7+OswseQF-gW5mMd>Ybd{ejU>va}&c7 zW$vSn^*I4Wu81I`6T~jt(W}=vZyDSvl|7j#pN8sRdkX3ySyu7#BgFA)j<2CywPC#} zR@hNDcIEFvE(dK}6a#EOhF0AiHL+=XdebhwY-II#MmoTz60H;BH2{{sO0`3k&)puvKGky)SZ7n09`92c)kzhpigL{uR=L|F zKI7VaZlsUg6r@VbSWYsARrTdfC`J2Gqr%Eyzj2mnjb^v(9(=ga&87NkMgG$m`ZqBF_a5 zP@|ld&-hZFt=y4YsqC*M2Zl?k*ZBjj=g?~?K{Qyf`QUA>T}(Dfu&AO_keLFydKv%` z$CrvlKDV^jI9|sQSyMg~(2DP~@V)IxdN(&JyxehinPGKuH_pzr!$HBut;4kC@aD^D zyZ*cZsk(uir?-tngc0HEcZ2HV;{nhDad@mrJBm=e|IDq7f}rdc$eg7h`PQMS9$+bGPN< ztfIlHU3n5WERcCg0oTq|5+BPz@BAw6#utC&S~_zwu5 zKn|B1^7kKz0w8K9y7jPNhn{?*<1E@8>?PvlMufvdCex@U`zKc}_2+3^|xR*0*t3;Le1x0)xi}6FX6GAzT({Y1>)*{AeF^S*mC#Zz>QZxsNPEQks;m~F?8jbS}R$wHW_+1rMow5rblZunm4k(9u(ky#%iN62WLBzSQ4qLJ5bOt zKa_$zqV`)k9ea9R!kmNkOd6{MHhxdvL|0N1TQFBynTd6stUO?A{M32r#uG_2ncT9r zWTF2&8P#s0>eePZk~J5@KLvSJKkHX50D-E&ywC8_hG%o#CTUsTg6!4F87DcugF5`E zXL?uLvZTHaZTRNOJ^UvWMT`Q938p0GQbq%CL7LAB+HwBTzo~A$DGfL?OSOc+(QW7j zV|xj}E|+#C(nI`m<=NxGFkQYj)~9>51~UKa8Qf)@;|mZwA2L3k6u|;8I27N7r$&Fi zfWgUne(*z)hr{tp=_E*9OytWS6Ul=}&yvRTGp^MK%VGC$!fWu6dIvC(JNnzFdnQdT zdx@G*Inoy6dY^E$d3jQ9pz$Bf)!s@rOQ$XCHV_px)#aTJ&D`JGFkT$4q^MBUWP`c- z4F3fiqvD=QYvM*`^jOgR%x0rWawz@ohBE;1*_b5%z3=qQ}oV?&1SD!hmAC~VZ*}S%AA|a>H3Q$Cs zp6`IbzeUFf6>EjtFo}t@N*M-JftfAQ>7y=^m+xIHQE_5ciZ?b4U%q?^q1xy`Lm?88 zKXzKfB_g!(Nge#za-sGO9bK{dJ)FNF-Jm`g=SIe3TE$aQslcIEpIm78wI}ISR;(4G z&O+^6f|VZL$wWe&8A)QQ#=E)z5l3$45URK?ilhKh#l;2umpBq)T+yivxRF}%nLr!P z(8zqF7zk82W=Br`*L2?(=Y@p|X#s$Q9LdD#8@zw{w>zhCnEbrUqtT`|5hy^D(?QXd zZDiKsqQhLffl5+H2-f~Yo{VSWzy7C#JS~-$5BFtl|HqPJ@;?&}KKm|M=z^;L=i%V9 zn3bg1Qs}>UpN(RH$=^J=h2G>RUK^kI`Oh5AH00D=)E!unvs(v$M znhtY#7*{)4rTIp{JO0u@Z$UJDd1 z+IPVT=aVE}4N@bi0v774@Ps=aFAgVxx*FEL<-9I=PK(A=IGL*OdoKuR^+e*}%@iy3 zRD|Vav)~r+K0^@5gNt7KN^Zvz78O-GCiQ2QH-vtWLQR5`-AUI7PdNMJ=P8lt77rpc z9ggOkQykkEO|D|e)5ky^>(1K!1Wvb!nbXt8>bL%~=0JU8sgGp%nAoLtbqnd@~70KWaMWKWf+}Hh#3Fre7m(aCt|t)pCaz%eW6b(YE}AYtHPr zH)$4WYGk?UFG^+KlOK-fJzC_Ex+l=g%or+@*_4Wan+{CU$k%<9yaOS9jJ9r*R7DG@`yGmD*cmURiNkX|gG~$oE7p zqQ#sH#IfdH6yI9`7P?-ufU@K?y(TQSo(ZYXp~}T>A8f(Vb6Ol@2B8=DO_hYL*1K}-O5%2W zTV*m@>h|s#XE}p6p)Ml4;ds~E#sDZ})pluFOE@5Vp6K1}j11a>GqF9S8Emk9PBL2PJ&jq#PDB#dwJ8DIHCRX!$q_b$Z0-7-VM^AQw1)0DR#{9azS`whY_fxu_16og zz@eNB0HH|v_)^6@lfDQFLggCUT+bUSacQh2k4J7qwT(X+i0g7YbHVap3t66 z_qrCK6KR)c6i1Nzd-EZ_q4WnDddvIJl`9KxF(|#B>Ya&E58VZ0&1DxV|Ddwv{w+gc z-7!?2v)9j-o&|>9eSVAL)`!gLVqA>*-N5slPnqcC{7 zP$Gpt5uF=G7hrM zQIAj^?ANK(uEH9uuqQDb?_)Fk^>Kc`+pL?sBFYyf=cQ+HzqbQ&`M?sp!{MAsxbCa* z2VJU0i&cNe0M?6v(ym*FvkgUfK9?GZwuI)SF4Ucg`kaLH6{jF{ZmCsY3({%AmF?95 z!+OuVJKpA7Y;{J>k*+{&=G8Sal8oHdZ^_^a`J&>mH7easTZl_p-lZ%&Q0*{P3PYg!4I)3r&%~s+) zy)=9IIPh5!F*k}`WO}Z?l!M-yY$sBfiQp7lz8{v zHI!qPRZn|&ydLv4mly>#HICycqef%wYx2)iySEF30NwsWiF!k{H#9u4rbi||M<CJ;L&>jeRI4`nYPs`Qq&NP7--QXXk4jA){!L6~)`K&hDb6&W%tgUt@ypMD7abja z>e6BcAejsrjgj&30s1O-C(EgTlSP$YZ@39eK2>HEb1VTRK0`-#_#q@8K1yET&)xG{ z&NE?!jb4CJ6I^1ZBj+30XM`rhZML!06oi^Qb6zwZh`bRoY#-FuPx{|hjMvHNvU!q; zP;CHk9X{vKjim&E>4<~r9(O+Xi)ut~q^N24boEJnqW04e8a-LfRGv)w{l6{3fHG0h z;{wve9@9S;NrqN$;yw%B`5^25w@bvouV2?wQ~+z~AD7LK|I9uV`p-RI!Ym-%uU)_o zxbt@96+e)NsvB6AHnTL=zzN$G|P-8G%F7lDEM5OGnskivk(zzs0fDtoob}mRaCe@}@8P&9!u7Zz zP{or_Jf!{$1MygZa~Y^(bMT(IS&3kwTU9cZyGB({RfXVob-Z7ld7rFj<$`7o*JlATc_lk+DniV@7j1hzT8E6F4|z!JzmgGl%RmzuhG&ToG4!s z-TAW1?m3DaOZCSuSR1zXFYui2zNbCf@xZcc8=fsK8V{-0$1Q9EjQW3Ets8(h{qrnKroOxH3!$y}`Me_~Ja7Kt0A$jwx zM}8LJvKG@5KN2dxcuKZxYl1A;1B@p>j~QK1(+wWir2S3s+nc6UKa+ibRhr>i+TPK<>v<@Ik|aQ zHCk%Z>{Iiy)^D$LzA4way9t-1(G43RFcM6pWR3lbeV_ff;mqxgWI1@T4`*~`#ISWy z@CEX?!$p_J>T_AG(<1C8A+I0nl2;3f*Uaon?-NDV&mcCn z^ZMp)X6K}TKhD5c_|GsO zyPDN1Vvg=^UrL^DabfV)Ga&Tfbip0PCftXouV5&6O)R0V4Cjizt-FzXPANgumHI~X zHZ#>{&(!Irf1bB)F=Hojcy6Q0C~k+|9qK=vMhoKMSp6+EI_1281v#$Y2uG@uNo4V_ zH3uu|QTYCt%N0g*i>~1(0Q1`oD))pfg%1@U6}$i1>>Y2m7QU-66tO*BFm}6Mtr-ew zO!b#o+1i7D9%?8d7>f8u=K)B#^``%qbpzH&$$^BX)Ovue@#4hbsAY2(d@9xHr@F|A zY+<%F`2)4<+?^N#^NsL#w)i{=zOKNJ6)_)cV}n6YKN)LpgUaS9|ASFaA1SbvOX$mH z2NSeB`WtrAkUu&(asCz-?G=ON^n_7Y1lo_8p0$hd9$V|$&NMRmOJ=SM!R zFZm{38q=I*=bj&4%#L@;HNH$)?>jHD9HW*VZIW`jF=#Q?|GE?#QcPjJqgqa$3#nIA zWnB*tn9NHL^tCTk|L1+*tSkBilW%`^e^55r>}RBrybA=qx7pIxX)1FixZG7e)x)xC&| zs`dTS)JEQuQ?Y;8rTzWPEOhYqvC`4LM*9Jz$+{)k#FDLXqF`a zrc>iN5;(uDfapSi5~9lW#sVk^zlwROc2Rs_2^c$P#{+V$x&q-z8wQ5j9iCwJ4+iU% zk)`f{;e%Ua-;mOs55}CxOTm3&dqceecC4;xamS7 zh1T8&2GAqGoh2Krc>{m{+lh1|1lucwR|qh3t)2qy+U1lH*GqYr%ze=Q-TfbqQltVaBr-2~@^Sk0*R*2SGC`>B%& zChN;w8feX)R!X=Kn}|qb?;5p<#b~)tsG53{^RLF&H+Ss7j>%VO9MRlu4s*(%kSDnb zLmSnxGc(z95z*l19CWZvlGvS{*(rIxN`ZU&*U$~j+fZ?VF7nsj(MezzZRT@|LCXsO z9u0$);{N$z1ROm_4jX4qR-A-CbH&8PkqQb56wnU^`l@6o&XQKz6_l=YdW`*b^5UWf zhCIzSIx}KgCHF_Aj!dxC?rqLhYQQq;Acec|T9JDYFR0&|xpb&><~UXTVO_HpYpWyR z(;#+O{n{f8gDH;c)2oUsIal}M`BeB}pE>34xvpX(UPKMp?BPhh3yV_V`j-&(`&4k8 zwYg+|d&TtY#g-6(mPo;9_s!bV@FQiGOg!spK5ruJQB6iLI(Fo76=}0W9Fg-d**Ahu zgWK^qN|A{>8%2Sl80%9fF@NUV6z$+|($K*IUR6jZ;7s<-gt=+s4LfZAT>l6>IAukh zA0{gP=^|WoA!9>dak>M@Z2MoDb}g76v9tWn1w>TJ%54`RCgK>W1>$_ zcdJ@AV%@!nvE&T0Qg}iA`bC|t?)pmGVC!`4W^eJuC2|+s$Wr+|CV_~82c35T4n2HxOgF+zpwyH56tcNr5)4{@z>qY!o$htF_e`dB+k!7|jt2a;8%21MMs`IcGDGJ%qui;cgP zoLBq*|4??wicGA@x9SKpmCHYoY*l*$^M%pEA*Yd$k)7lkuFZrrec#6^c}>;w)Py?t z(l4dlFPvzxYKb}ac?P^^q5 z1MjDuv^GuN4C)Idzcz*0+kZ(568K)>A`=NxW4Aebm`~xk#4ILpyjU4BN=sZ0lIE$s z=<{iz>#qz74Ko;sBf^VW?ReXFJ+1b$;$0X?Gu2WuXFq%g1j6~!L(pP5T z8$+M|yrG(tnF1Qv2hJSa&03%W7vZVqh5qwqfo2&cXrsFcti#A_cgUt;{IbPukW+tm zAjOA=VX1ut?hhM1)YW*Xbvq5rg<)5e*CMU@s@D@{f>IkX`t7FbG{YAXdf`0JuLG7E zl-wFj;DKg%KFoqZr|E7(^fDB@*$!^B z{#5+w8RR~cnm#nh1Ff8CQOa9J?uhc^Eee3wpIv8tPm?*1a^Kzguv`_gH#n$i3*ShR zzkBs+v*|7<$JA`$XVk-_%6|Ax9C*Px33Dt^`jRM$GxmM-`1cxW-MGsk;vf(ciVEIQlmLYOz}b(m1c8VGl!oVWHdF$ZjLlD#d@))M-{Tt1=TbFpadf7g zUe-eG#%UslMG4N&PGojEHO4BULb9;#4;MeAc{n4F9@$tO;|I!F4aTdbBcR-Nfo z*#7~l2R>3&EPiQG=;Q_E<~k#c zlcU=53$)Y6L9rpR%H8EEJkPz?pJRG-KA75Uvh{8&UAw%?>(P|LTN?Jh(dHg>gn<+g zudd;M(8jSj5A6L%=`<3Y=A-K)31;GJl6S#S8fJ=D+H7M_S3ssLsduue1eA znny@va3yo$8C=&iMf^qf4eLp-o#IyBg)eQ=fi(T9{|PdA&*hb?GY9ely2U6oPS5H9 z+RkdWn)0O-O)Hwo0Q$;Kl&Q;4_EJ{8bsgUWc+gV^x>t>*fTbnMs@ZsG2>0hVI(RA1 zdT8mzqpKeUWa4VJEWzDJqeqk{+K{cAb6s@;{ugR^k(%{<%?c90Zoxtvfmi`045_i9UeDy~Ce;B94{eDGgiF*@5TGTus?TxgBpn1yE|;Mf@t zGT&3>MGf+A;R{2b)LBi;W2uQjgb5LcM3LTG{K*=>c|P1DiH62>=PX35X-GlN&3Sva z;f^(BILVVqWr>OEg0?plvLm_yY36D9Ji4O~zNYgKw_TGwJ6{^%EoR8+s@r9?xRmYFXAIm=pExg8KG+PgzuR2Y=UXL5m)Gm@mqSsn0COt=F6 z&bLPUGQVBYr7^E6;Y|A5s(({fO1<}Q9@=Y}QK6M60TsH@#+4cjJ;CIM!aAzFt?i-Z z*F$Q}fvtJ4L3=hxPaO`Ygb?iTtj)K~MoaIitx%n1-q8z@%C72rhX0FTF|~Gu9vnEr zpq&j1%X4G1B;guDf_|ZPTO^l^3OShJe4zZ<&S-$rUDtTq3p$XU!xTe=mRkEkjL%4C z{?oE%wRc@eI0qr-t=r*fc{vJv34#AMSIEX+TmbpI6lE1yv+}m-DIsJfES>}%c8ekB z5{F7R@Fx#3jyr>75vPZq%b?S$tgQP-{cVZT=uZ)T2uK?{5NdBYn4di1RU%@-(>g3B z&0766O#Bs+q2ZB%@{uoj@fV*vR|JK$mBqt`*A1UH)%?`ZV{v@-;(D!hB9hC$S?g%%x9Cu%4Bs* zH0RMYrMHC$C*|{r^D$Aoo8F3{J}zd2EZfmweN z82@zg+3gzc?Scv?R;jU%G5$|NkF*Hhx#2y&PQ<0O;d3lFty`%Pe){;&x!KY8CNBvN zimEgbo_3M+dDYtOT{B&li)~ydgmjK8KX+vbZ+H2AVML_kX+DOm+BKcN;08l8g0Hb; zz2MQ=4;l*wSOG z&`Ck3;{(FyE6q0#sw#9Z%c84e$yB0l7(KNzYk|YA&bkG|`37+B)h>*<3NaD_xPq>6 zBjZNTQMpif__Caqrju+Zs1O2jmqxk(pAh4R-aTyC-U3^|EeU$LRX-el zj$ei25@e-!pUr2Ru3qNcBVt8MDV_TRNQQ9qa+9JMg6FBUTx$!#zO6ya+DRKr3ZW4b z`E4WLTWRZ*tuNapCurJ@S$N~5n9wu@jMXzrsO<5mikieLZV8eTH+Y*+YodpSuV%T@ zRz$v^T|0vB>R7{%Ed*K*t*p9#vfCXm#*V*MX?}RZ&Ye%ZBn#Ync1pvY-27omyqFg~ z>x=9`S10Xju(Z*zx) zJ2!1Gz|ExM>y>cuZk2+oybblJP7^O^4Xu9fKVsE7{j9_l;X+gvps zVga6L1FrcYji?dO_SZ`Xd8Wv{wT=pnpYwdNEy>qsyTQJPHaw>|A48VS>ubV%iIT6+ zS0`E?W1YWK7vfF+u*E=;e0x6Ca~YQ32wGqv=(XL5w9=hKXW5ywYc|)TX=Wg=M3j4; z3qMG{zdOOjf5f8+j%#nwDDKX;M8f*vDT%`NU{2Zq2V#&&H#GOnol#b|rIxF$Ll zD;a^U2M)$06IYWVU07VYIP`3*kX$L=jQ90$))Zjw^!G*mL9aiW@;d)(_I^{iNivfT zlrJ3W`ZU|?P~IYVkaqXvC^qvyNI*kh3%h!f4|+-P1%Xc127($i5| z#q8>{r}k4oyo_7{A#+SspD}#phsZd1AkxT9E8ILP>8Zz$_fy~RUPbA11-(~Dma=eI ztLgEZ$z2aVC?X=zN+YrSf)GXN$;aWT7POtRZU-A$2i;GZ=l(DJ0 zwG1eNokBE+EGUS`1$Ic9tX(46HVz19el{P9U}8@D&S{y2)P-lYDMXDBDnxlrUJC|Rqfz$yeFDJk`Dd^F$B&eE{}pxmPd*u&kuesiQyc9& z=&=t@KO|)Sp@s#fEePcbmxofWnCo<;pbsuxPo&~lt>NVn?*#t_lK`#3Z<^8W&)r=k zpsVH>`cH$X0%F*F%3G*U&+L{W{$N8;t&i<}E#=e}XE>l&NOAjbT3^3UMujqvCWwp- zszT?>!92MRzYNYgvZfc$o1S|s3bXr0beEdYSugx8%Revo+D-;eZoVt_F*T$->*i3g zBVLZ!CbcJ#5ylVL-QE2ch9{0td!VpF`IxJ6(ubGJ0D_8OK?|;Jps+=hTBz;^fCL zlC%2&m{QO$g4gz(B{h1?Rk@Z1b38BGDcfO2>V#=<^UrsKZWvcQJ=dm^!_qo2b9(1fN%Q?r0l*zQ1~767JdVgJcwqQzzT z-ZxIuio~u$fOFnum|!zcx%4By^Go~G(WAD5j?Jjt9LGv|pTS0FPRnk;Gu zyyQlaJ$C6U|3B&?8;X~{AcYfvc=k;~#Pinr7X736i)Zg*V=kvUJ*dp;>eo2X9S2r> z(=TTQ{q-Ha$x`E$HJ6Mpf^6n7sYxugUmCq2uH%aPZ^@5}XX>zhgnL&v07{)qEB$nv zhj^|tK|a!@F9kW%6e*Szx_vwuZFaa371mk~(Rgw9_dno8Np|Ci;kH;W+1al6Zi>MG zy3i~YU?tAGG1PoGfdAPkL%CITa|cX?cyf0? zlw>0!O@Z##2#;3rgvzGvq+uhxXcx;=7Z_{<{j%8U&-yZiH{M&s`o}bx%{tQdbWLD) zZr7aUO*VHkuMg)H(2Wc$uAbnXT&~ic50}C9O$Vlu#GVY6sG#7z zx}~1#t5MshBgXNai&mQe@{kf_gA0=hqM=0o)WBjAXZ;1`Tz~fw4EIspUE`CAIo8<0 z9@H$AqMzT0vS15Loi=g}=RRC9=SrT42ljxST+fxUubuoJ(xl&>9OTtMDaOpE;dKCf zET{dDw>zN?(X6Tgg!sKuMU$hsCq6Hc(H@KlXIQO1how9G@mOSAZ}ccMKKb1iT~>=+ zX?XuD`hBTk%ZI38K3>^y1M>A>d3mgRG8kfCz5tT55&nlmlkf#U z0z>|`+o}%Ir?-Xzr>OLXi=%ArLgn1Y+r^?Q`WO7ktVz&atY^nfcszZmDFLqQ;FP9S zQx?W19}tnQ^^W6CD5`~0)bpCjdj_m0ZVVb%lr3^n?sI*1Kyn_1a?MCrX zeL#^5#j3-@9+wl-(xM2?@pf$5(;oiGcEZRL9!otv)vGyJr;+uMhZAkPz>Wm51TIhb zA}{EsI_nGxcn1$qIG>{D!pv6C?=cur++3tk-vAWhJ!KO<5ZY>Ns+&|y&w1r*%JdFY zhv-fBRig>Xc^r?6Pu^_e796?iwopl1hzQ(7Pdd-^wnm79!heH7#~W8$!ug*zzfWgC zP5lNtjftlIceK-#DJy7luMNU1FXUB9J)wWh3I52d#m)6A@D?!+)-04mPK>^Hc5szn z^^ZL3cV7QSM#ZarKcjEV`<#!+O}Eh-FYJ!ZAMw`GKXF9x-xGsX(>}?#3f$o}IGHm4 z!QUk0qwW;=;d|sV4Q`N`vC1HwI}R>#p)OFme~OIJ@DXU4!UQ8eU#j{SiS%MVNn^Ux z-=8Rlc_=kH`W)+dPnedOEGb0k9ej6^p<`3R42VY+kI?_3dR-%r`6J$4y^Jd=psXFh z`T&V9z?A~fRi0Y_r_nsVelM3hR(o`|TZdw!ZOKyI5Q&RX37Ieb&G^-8aBQEq%y}!L zWlmnvrQ%9m9Erv}-s6GRMi0U4Meiv8Mk0IWcQ=-}7uRxp%HPC@KIW?to|7p@M1_H5 zTe&}o$-Q5t1cw@7?)po6a>8FKQ}BbKX0jgQrX4o<#p2Q|n`lcX?n@k6Di*Hz?JRZA zHYk0k*B_9SL^e5cv#hE&_3U$)P`$Ek!q2xVj~}KFcV~Q0`A9AXObgUq zPTnRZ!+qYsF6Z&DZsuLA|AFGDz!dOF_#`B8x6vDC8E<5Ww&~3VxI03P=yF$~|HUp8 zL3e}b*Wt2^#V11C*M4#Hl#z)&BR>qfL=!hp9)bX2ak%;dQAx<3BXy!wS?Ww0$L{4> z5Ml&3TxXl1pRO*M9FFs!;pf_~Tg3fhL}|cM_xg!PHG7(THtC&^rp`-6SpG#hz6$S< zltMfbrfX=(P(K0T-)OoJ3)r!nL#(58S56wSsSHXw`9BD0|3`S3cUeX%5?brYH{?XC z!$3xcYRDxFp1~*_@dL>{b*bl_$-RhV&O^3@3V#h_CRV8K{{$t|(mW=AArF35S`jO< z?hHzDMslQ={;rtlc~I{fp}!p&6l#3;j+C$WEMdIG$eg&P=#M8bfcDZ~ZNJHHg~EN8 zf$S>xCY6o9>uQg--sCj1?x3o31xE@?3sW2poB+~F8)#I@+=evOUn-&;RhX}C6S-2H zsVS6I5SA7e$u#;Z>+)gd7d@E1P+ML&oZ}xS0T))sWA!8sOKAfGD!}kY4;Udxr&b#p zMJ@^qjQI>uLxEU;8_*6=KPu=#e*L0obUX>yS6Ots7`A83(x&u0xQ8F&@Yp(D=06`s zAQKw=6{85LlE^QZo&BzYq8iZ5>tl_~?GilboKQiylQ4Daq;rtp~U@LA!= z?pU6XUALxnl8~I&xI=DrI2MVPe zjlX_u1oR5uZbXEo9a`@oYPf?1C-vR{AiTpyVIT=VyB>*z0Y<X_mX(p8fi^p@5x_?XHkPL#F?p z4(oM6%HM1_uFS5ku2q``t0v@x${@=HOwYGofGI14Iw>jOx+ppMR-hH4lc}5zxs&PL zDfX*V_`bfrwu38O73_HZsPuFhCfwo`}9kIvOkvSE%L04Yeh6r^X^nuPRVet_fR6)=F8TTC)yBnBuR>g#}I`n|0!U za|H+;E$RrswTQ^bom)0*S1xBxyZ{{_CN)(m`*Ro*YW6L2C)1Cxpmrvyww~JdH7m@B zotuXWGlH_&kd+f^Y90cJveA&)gYG@MsH7x-Q6Onuo)i-!Bq@oKYy8IMT`WBkvpc_* z^({UM96%6A9}S$`>taFyrh=_mtpdNu91xv%&qgIAz~f?KZf@K>K#J2N%WFn9*&ir! zI~;z|)FcMjk~;uNhHF~@nyXekpa=`LNY=MhK_>5;_kMZvuWt{;AT4g$r-{jeDUZNe z8Q`{?Jjq7|(B&x0eVx4*BsI|F;ux)CL(a4h)d-tX|xmI`NvVfKmakX+ku3 zfZGQ^y_lGRDI)E;qdULXTt4tt%0OTQtXZHRj2{zkoqPqUF{K7Qa)if>+C8joF%_js!K=BH4_5GXMbzn~Iv3HXt}6+crxbt=w>hlLRi&iAsKD(ltb zLGp14-^zc70Qu<`3=Elw|CcZGm){=_rPCWu4sLpf`1I8rIFb(yE}YN%^ahqnT@CsT zw%tAXmEK`y6%~b~E%UQ*B_F2|qfGk3nTg_zvikOJkS0p%Cc&MB3UM3CsVT|S=fY{A z__8LV+_`}+=lC2unNA;`@^$+T&zukfJC)-_xKnfM>gq73u5WH)B&ozG-ng!6VCmKH zC=_+V77En>!|oJr9A>=>s~@m*xvh#MmmY+o6q^MRDoo#GpphmIqTe;oMkh!hkovt6 z1YU59w3+&{0LkO$?8C*zxaDJu?V+^c@j#;Az6n!x)nhBOq9fM%i2l2W$GJsK1l3fS zNUu@g&YW9>O-!t+sp7;TV+(m`p{LB)C3uOcQ>6iJQiFPU_=q$x&L~LO2QcxA9!(Iq zK}V6%u$bFb41>x!THNVavwANJ3v~C4N`iVfoZR^hhKvN?iySOsSI>N}Qi=VxdErdh z`~HX{wSSd!l}&1UIMvsI5WAWoqpl9VlSv$_T>O1wW1|&e9%dwWc-U42!0{C(f9>WW zF#hEi6IIUXPby-WwFi`5>%J|UE?wp~K`?xLd~@NzFVS^(-@LdJyt3fs&ru_mG3-<* z*&ZoQo1EH$E3^Qw$VFR12#sc|;^m{E=+Y|GKGZy0MabtORiNXV8v)Tv98tpmm2ND> zYeMaA=z&esTBgTj?2&C71Kutl09TH}oZ1iDZT$H3G@H539i%m7C z1FWlr1aeu+HU4l-O^Wlrv6C&@QjmvaNq&Ll+tfjwdp8(&kYLfGZjLck3{^~jtm@VE z^>tP(8F2)(HV+ymv@B|lLzC*kH_BY&B#IcZ`}_OdgM-dmbHKvd*e%ys(f^k$f?%fl z8u!#Wpi`ec$Z2gQDX~}3F9t6wL3^Ypn6U?r?$9gLG}awAjzg9uHfeAYGWgftxurSr zO1r!BeSE)aXGTz^Y;Wqq`!m3s1tk`$lL>ia3||z-=UWbDJmA0!1JSp2k%7r(e>F8T ztz#6HB`cLIp0j&&v<0vd8U3eqZR)2pX7q046$;Q$N2v@^KNmn`+$elKbY5D;H% zlC=uNv2^$6rrmPm6ms7rA(3{?0R%D9BTcb7w5~2$`RK|E;6oJXFhZ~0x>r9W zO1?o0EGiUm=O+Qon-ShgVSsDTl(AJ!B{^`X8c*jwFa@t=j_y#;;E*RuM%S4yfWdnw zCnT5|jlFn5O^fC@i&Im=EQ!MJMYOcE6q*(@YpomNGGr~ zxG)0>Wge~Rjg8!rlYlCCVrfZ=CQi_q9z|a}i7HK3Ican&xGYc%G^aVYah5SY=iKDv z=C6;XsWiEf>1=>(taj0pY|8m~N`CfEiaYUpX{z4dL{4>0P1N9))0#g{&%NGTDrNgP z6E0bz!Y#}9vh>Tx+_Lm_4<*Ht_Ta}xg@WS>|5vV~M%%1$WAX^3RN*lBSfH1-!RjMi zkgmz(2tVkiO~P%zL+^S$-{I5E*}|yhPW%a9pzRE*+ZI%JKv#Q;gB|kn(o$VjBE04O zo3iw0%2NK4peO<9@U&yK&h)f{jf~0gT>U!u_kKSM7rBc6*wkImMIcbx)xqrK*w{xo zJ&dB+(rz3y=B5JKwQa>%2YdUd{_o}H$;-={&u0;y08K2vpa3$bZ=U^5*yjs{AXRdS z$-G))mx?KGcYKR%{+p|Nx9?SW-wH5~j*hyg3)QZVX?Th1!_2`7SidZsR2#xwTWwZU z4+>}6A^N|+c~_0hE``y_WMpB{!vvV^JV=1=o;-li@I#o)&fb3Q;tsGS5hC@Yhb#4H zC5h;j;|>5qZo(jx_B&rQb~U6Vb1(y3J><7N%ssoLv{Gq+0o(>#0@DG>?doEMImZ=f z#njh9DZ%N~|0bT$>8-$Xzl_6OQcz1Ts{B%XYc}wDC#PeT;bLNgnnyK@!ev=leT$`g zf+u0Bc>{VS_#=p!9%}00q&59wRKT+xKs2=aER%JRG)Ih=SJzBnjTtmW*Lz_TcA!qY{jA3WjA{N>v^&8B!c&+CM+%kXYv3216mGzCgep3RCXU&JSm$-d55Fnios;>Br*42iJ7)hjO)D}830)u;$4 zdcK8bSUCEG^sfZ)GuU7>Z5UuADmOXMOQ6&FF)q-Ib|-$J_|dI9R~z;X33y&yT7bku z@ut1j{QS->Q*hz~VqoX5Nn@XOZDTa~d^C=Wy$`ba$96mCL*H2d+Y@{O0z`koZlvi< zfqpa;-axfpjnUM>DO4(W1`?B%PS|?!_fXy+_uQ6D6aa|Fi5HlC2MkFByzC{ZI(=Y~ z#dr3ZrQG;QYHDh_HmuL@2!Y@vNflxDqs&pA}ivl%tATZ9jPa| z(~rhyv|XBSFA{MC9hp4I0b&*;o`q2)w>%<2My~dX!J0mr}S&h9ImdcIHM$_ zStE?Lg5so(+})0&H=MT<4V6J|cfzQiI3L_CAH&N8uF)87cZ3kpl}%0-`?NxR8`gh_ z5aN14m$?Ve5;89HB}(jnF!y}KZ{@m`T;|(`POuvTb9L{KhG3W_!SirlFyc1Mvn4QkN=*Gac2 zHWAH~WjwCUu!j=|bLqhq^dw;Jradu=J()bNjl(KqOUs=g>a@8Qk~bAfu{$#KybjRQ zI>38CLEObJAA;QY9f>&XRzb-WVD_dWY@Sfm??`uDYWzB*<2W!sDkC8wm@VWlE&#cK zYr|#_fipn$ufJ*p-_|t|uQ%)M*q%fjuLUEAZ>{ajT7OLK)K9Mu2FxTqHi-d2ZOJqQXH>P-EO<^oLD?JKnETn)(d2{0@no3 z^`u?QCm>M3qMt9)-(?1q;7ZWfw zDkKEx$O4%X0ii`x&|6!_^`nwmh{IUptBLLN20_!+W+|%V_LG~93zveTBItp*LW?#$ z$vm<9Cm_Jk#L*~tE5a3cfAqS)cd4Gayt$Fn(uy#~#z$;A@`XQl;sv~>CZ2@Jm^Wi_ z3gk0WEm#sM5+x_5r$u;)%UsMC1sc@Rz_tAbRhL&+6&{^%CI|cCWv|88&|$vd^d198 z4VM<6-kh1y1+xRyATSDeBBd%o$4Zz*OpY`3TX491Fc+&qMNL!SvwZOJv4xAP%SYM~ z?gP5${>{=>lGk$5T(b0wXju9Dcd9(alV=;?t2{zrI%9LbX4`PC zN3sgoW`eKK>`4whFGN6B6QT_V0iHYeLdP4yH?3hWTzlV2pKd&NlBQR-I@9k+MW4>N z!&x7cJzvZpjewDI8w;j)!51_)>bA_YFwcFn38_Qx1D~Sdee*J>E|yN#>$$M|4bxVihYf9PH^iEc#w<^-lV1|Dk9h()T0K}jdDacxKn&eQ zD|c^6JnjgO@6YRu_T6H^FGp}bH!svX(`8%KB(CrRMh%IKE7mY+_N^O50>cx^_PQS1 zpewuhr5DdjB6s41G`_%i1K-QSguDLUmk^G!#t_;vKELiT9_RB`B{|Ri!1}F9-XhQi zBLCeJw2JjG^KCTPY5RGa@Wr3GRqD?zcvyAWoC)@prXF!KoTUwVZ=B`Hj~-4Ox`Ti| zF7mZG5#k^v%+D}z@8}?hV@X1(KBRddW^ilw`GzN$?sv3*UaMQ zP4$XXbtX~=*KQvA)tpu3oS_O()UbzX%wwof@#*OB<)MwnjA9>xTGmx{INmxyEAd!v zT-<%x7yOd+g<>q6D(y$MZ{ygTxw1@9xl9TCp^|Slky%6-QSH}wvXxkB4qDOmF_?uS zW5gQF5&DyE={bd+gYe!8qAcOF9QP?Mdw+)k@IrsdvRH9JP-FH`OpH>gn0{($t7CfRYyi%qza3mN zfO9PR)4^7CZLKaYTwc1z{kxlmu3n2fvJ(L=7!AIZ=kA@K7yijkqb!Ug-fCQTBk5JO z8n)`lZ72+_&n^u7?dXI7FXt~?<~ITohdv?7we@J8ChvRc1%h&eM^R`hy|U3QyH7@~ zyTqui^94qWa&kP-8V{-XU0-+_?vilkYM*`G0KWO^fon>-2W{t;zza^e+NQV2$$B(~ z^qON4H%O8Ki;&Pfn z3}u&Y=9)4ZsAQDyyB^=Z;WTcnv&eW@?KXSfFg3Fc*J-a`q5QK}y4JY10USB+1M>wT zhVoO}O$^xrhq+MH$~gcYve}?Zej6nb#ioya;H)y_fG(mir4V5i7O&i z)>Lo@v<-}?+8aKZJhJ6Hft{1f8AC@e6>3IMouG0a63r^kCk~(o%w04*B3ey`=FQ@# z7M2SHZ&^_aDohutMG5aPo1>e)`bvJ}ZWn%k^>Mbt3C(ITZ9IXCW*jQJg|rBG~}4?^vqW z0VPa|F(NYwB@3;4%*dZIQ%hYy9FsgwOmWkZ-O|lx>M7+|3`_9h5kdAJ&DSh~F{j$M z)d^i(jW0PA6%q_sRr)^8^u^aP+R%!!C7H1!f7bCBcjDD7q+^Ty`h+i=&n+TnpE7_X z@93E3Upe4#D^U+J~s1_laOjnf+^1cEww^=!DRsfr^r^~Ay>8=A1MII_7}JG z`|9D5&`Rr(VnGfX(U^Yy-H4lun;OOmb&kO8k9^=to?WpXpt-YG&i#`paoDF6)(pW6 z_woJ&5}NTd-u`;5H)-)gej$_sA~53pRqisYS%}t+Lo>YxZ3KCj9s9SMy!Lz~O%My#|We^MDFi;#H?|tS;dUo?9 zRi}dsEaZLPDx2rMh4wMiv&{3E42k& zklOHb{=%^8n#7c=i^~u7Fcrd{_tH%Rt2&%Y8`hWv1p~aUNj^I6#`*T z)*&}rGpi|KYI+bk$N;)sN95`md((WqE@8%fX(b3IUQ2s$I1eX~&ghoS5122v=Sl6S z@Srmh6uN@P|44m%(86K65`6&7=z-d`HLah<%novK}>Cg>wI{pkr#7X&zMLE8O^6-fC>^qC%QI z(2#{(H`3&V*3;<{_6;EuX<6(a-A3RUNU0f^@mdB}5;PV5EG!p{?H^4hr z-MawAKNE%U=+!BV_;dk(1Uir;!3Ait54!Hc+2bwlCVJS{nEYRxAdAm&iY!8~a>cP0 zu4yz7q?VXeu%fprz44Z1rwhDFzi5a~_HYoQDZ$p{90fM$Hr6y?m9Qn&3pF!-tflp5 ze3Ma85oKhkcTH>Hq5n~12cyUe{UDkr|VbiDeOsE|g%N1i$LixrLEtI6JK zMA=^2nEunv7@70hx)xL~*>_z4aQj^7{Ph|w`8e;z_rgN8ePQ*r+v?22?K&4d?#IFR zF9U%mpwR42rHaduUg!Nn{ac5Mx=VrQ1hp3}RHYKmki<{u2}^F2txcx}9v%}BPA6dk zlpeG8DXpt~W&BtXG{VW-aJaL!y67w zwl!_=qtpz}8sN27JE0ZNTDNp9R6Mv&(rl@h$r;vSc1Zep^*S`^{&nJiB^RrM%NgED zXNrw4H9~VaHcV-IxpfaAPMSp!+xV$aUq!fOyu*DGupVcTHW*_bT6LmsN;K-cF`!Y1 zRzy(K;od7=R>xVuHZ55~{hD9cpiy+K=61Bm-WH1_R}@i`?FwHqTyo3z{As#^JUnro zA3h~1#yTH$7CZcC`olEWrVF8N5N?Peqd{&`e?V!0ns;N916Db{OhW4=Q+gVWK)P#q z!!y>H;fIa0GtOpuIDWLJ{@{Lxpc+4=}{rY=^-o)c7yg)`yj=wTpPi7$T z0MKI@#gO4`S20W#0S?b4B_)2HI2UES&+=({oAH!&HmxQ zW}FS`GTSG$%3q;OY#>PE?3n+LuD6Veb8DgoAqfzi1osdUoZzm(AviSdgy2r&65JsK zcelpf-2w#f#+~5q4)f%`_kJ_8)(k)TC%yWdsyZcm?wwrLBD<*i94>9|t z;>A)DTOgGE8g@gltH`^cU_1F3mpZRv#<~fsBx({Tf zqa2E3#A|73Ne?;^db-(2v+pM~p7-WocumnOrUi&u43PVHHnpwOJkjL;)wUQQ^Ek+h z^Z?*9vCdX3oVVA1g3}5WLUy-m6Q*9fi846hoh2mO8d^IuB2#|8PF<=USlE@jPSBbq zlAz#@q+b71%>(pMkl4w-uUu@L-+PeyHpR?SZk<{`t$FeFm1YZ{%I>sQ8^1%3lmOO+HlSAD9&Ofg8v+cdfNlvyP&kp1cJwvN2Bs znLK@gaZ~cv*0%&EefbY>4FRI@S60Gh&vQ8p!5af!K0bSrU_hp=8W>S=TFqG_fCYvPB>uy=+Okj}nIYIyTct#L0HNp*mpYZOQ~84&Z1@Cz_nrVUY{VIIOQiuZZ{ zEg&tXXa95^^G-Tu{@kDJaA0bw5%IlMp!8Sld=ypQ5b0S=Spr;$*I1evA$ zw#@a^)eb~na=o75)8Ul#2Ah|`_iWU)>-B^_D8hcFGTvGc^9Seq$|(sGpy^q~yCe#W z(R!%YM6cCE_lGFEfMP6|_}@A%(Z9_Lqx~%M_Z9FtxQ5@0SJy-CENfWiHJcO1*L|hf zoKtf)G>V*Wp?P-XlAANtI#4z>vf}ed{;)kPr{lA2!a&-mS}qdeHKim;$}uPUzpxzp zH7dn_?Ci~@xb#;Pb1in9kJ;E?53NApd}WAgU~ydc@o6qU3JG)EXNkmxYqg-rjdH>C z_nPs_DEXkKk>l4JbY7TBdnelE+%PS5PyvS3M(Su`RizXgw=84bKIx__eUGgRU&pQ_ zHT#I%2*D#Fk`oCttji(r!_6AW)vlymQC9ilzSwqnjU9N5QUJXKt#h@i=^mSid2f(DTmoeGdzp8e+nyXKfAP5}6)MNI0$`>$rPB2c;~@KdOz%X5_M=EMZpsHbMwm)rkLlfY`1Ft z6*kK2TO=CTluUTlOPYNPi3^VCq^w846Dj-a&_6^^IQ*56I@_btVIYus#J?&u;*Q$Q zYU=~U1*Qj~MYVL`A6Oy>3m=64Yqn7I1|;ofN-svK7(=rZ^P2?aI;6{)BqdCPN`C|N zZX8!RTUvvQlx2q>&3rJDmz?RpZ&m6*MFcSSkc8IwXpT)c1;byf)9CtjbfYR^RAkX? z#{ChKytE#E3*_pfgOK5YOFAaOj_4n6az@pWn$}z>By1ZkKpVT=_~%{O#YO<@BTdGPPG^2R(5X*OBdlYfE|-EY^d+{4ECI4&;J;7%YZeODQ#2mx z;8^EzcsZFu;m=ZmzkbkywA6xZj~t^me$>_EZ^tQf3!36fE;a;|D$){wpG(j_`#RV` zhNF=Xih$7xm>WoN%|7rNZd6#bp>aov@+MO4ps&|>Y7FJb&&bW5_Kq(y!!(Z$E}1#r zhK|q7G%Vc5yaS&#`ewcQE}FX6wF^81GWz=DRT@?zPx?3;8w40PH0qgZPjpv)qvmnT zTrG&NDTe+ZM}1{%6S#2Xu*CxnuzdaJWq^udM5C__bmvEZDa%BZ#0;*V@?ji3Jub>p z;RLYG_$v3YkLR;jC)zkiGo-C73WH^t#Z!{-LrBk!-<;SdrPrT>*?Pz6dKAkz*0-!^%9uee>S14P{%1Hy#8f#Fu%NBv@vVhp2T3KDi4eWwG^Da&Z1e1x@t3o&f-TsIOn})?{>e8NQ4(b3Ye6o8 zG(Hy_TC}tSMLW8ry)N^7pg)R%(p@-tbA=>R0`VC}%Zq& zNQ|fktc+&dqECfmK$9f<4#(UlMc5JUi}sEikuKZKqEQvWgjrR!gI`A`TJMWL9_N3y zFposFIWTt>FFJ#p@7&PEXd4ncSAQ) zNxs0&c^dTx44!t4%Nq_Nm^NDJl7(T}ggv^RjIpYH;0AZnJOe3{g`7@b2|>#c(BKyZ zzu#7f6nigBAr&c+i;cG~^@Ep(u1A%o)#u*WWCNKxtrKW3bMM^7)2p8WN-y%=ArcBN zPNkKt>M#LD>~)ihcPR<7LSPcc2Vn%k9HH*$n>U*An{Pj@xq9)tl(g`K_)~e90kd=k zEkHaAFtHhWHDGW~;&n0MVJ7zX=}2POK)&jK%N=F%tn%?|+Gwje)6Ed0-bOMvoF-d% zZn{H!uC|<}XLsy5mMlW?>CE`V@@Hlou|SYvDn(M=H*@``0CGxW10t#d^Pe>ifB1Q- zGpZDXrx%xHYbMYrDmgb@jkmu2T>g`E&6X49CPq5Y#f$e1?rNwHZ)jGOOS5MUL}z%13ErOWatY=ceJ$!);>ceINzj9R z0ahw-)Q@2sF}q;E+LY3Hl_*BV5Q~qVdUpJswvfzy=a~w!Ow}%~wyv0l zmH94NObdL&UqLV(%&F@qzKCj#Hk4;uw=^p5NFX4+m_8Eg!%4m4gs+sgCR#}nj~CEQ z-%AOB^oPDy&L;w2qv7_;B{GBc(c}j#a!Pvp41%n2wmi9qvYpaw&+R0fFudM1Z# zBC}27suSI)Bkx2W>^Q@47I8MqQ41m;m=shX{@wlg@!ApCml18bFxNi!u#xT4$-BzB z3LbyfW@ux&>&8^+RrYmABrP*vC~n-%;9q(C&CF!@gzoLSe7eYf?orx&ZM21lEwgkk zDd@Avchhk#)I~hgfosX&53}cdT(f^5CptIBsHz|%Yq253=l3MU6mX$06#K*E`d|Kl zT?oCy)ddFB7Eh{a8#UFDOyAS%S-K^Pm0652Fcgr62nbmvf+mp;baDLqL9M*s%f=m5 zU(nA*xdbPsmm$07^aK|IcGgIzfHWG;TX|VdC+n=`T}JTqMYExM#`>O5(}7pAHxw)4 z6|#vacJKe6*=tpW^Jt1(;5L9h*8@ZP>b9}nsr=Zr^6^W85^y^#Os0 zS~eUGx1T&G!>u!!zvWglE`MAgu*9ftnjy2JwN_pwJ-9IAkuSC0*=~6uYAq7H;C2%O zGB|>qS~J?}&h}S4)n*lcbF;!j=x1i(KP19tl^n8mXV1Y$AxHKp2s}}`)`gBi9Wa1?T_cC zJ7&D0UxeHc@JaQ8lW&Qybvyj#&oK=jnU2?Xn=;ojN}{N**HP3Mo?Y5I9uhqtVmjZZ91Kh~<7w*)S&H1~oy4;R*HbGnwo%?RgsX9GEG8`@R3~W{F&T-2Ewe z-og#oSJF02mZ2yuF^reVB8+2IzRZ`I970W%RBf84IjdZQC|m~&83(2_hl*vlmEAA( zbh;_hmpBEx>r`cVF2|Sspzf5qKec?$+Wtu=ok!7qb>R$Du-X>&c34PqzclF3ar2tB z7PP)J#2Z?CBksA@JZO4M)a)Y1P$>I3UXk&|M1 z+DH@gxJep>`m$e}hz}0$Sw=<^8kyfvPw{wn=)Za{B~n*5n*xpnVTdFvGx#!36o z(wKHDu<>}TrHtd@4%nb)ci8iKkn%D6_8>RsML&=Z!YiX;0!=UjglJ zsE)U0jsHOK`snhUxcKq7sMvuSQuO)X{E3chb8M{o0GT(}f_u)Xj^(^dir6s$+ zs4JIWV+qgAC*$V#O$Hx94^puW{fdS)SbJr{j{dgPVf;TVz^BiCuo&)P(%M}691OYw zs*6hi-jc6q$&fvw_}L;Arida_A`0z-6}^KMwG5+walv&zMt_?YHKyv0dCj3$;XkI{ zXiH$QKr{u-n?ih>gHm;zss_L3y5zJcm*%nB^zfL3Bv8m`lD(Sdr$D#F^DCxHYy+@QY{ z;hdCoQ)1BV;(B8LscYxfqq~h+0;CN zu8^(xS<~v8xMAIu)YdRLNasCL%$fHR77Up;c7Dr+pFQR2>1on9A18=)$gvNvVp2^j z8x7=+K18fozFgMI_(=tgG-r#yX#&G;W_ZbBCX9Z_dZFLaEqRI+$!A{3Ve{lwyJ=k; z+eu;W!$wv|brpCdNpxz0fKDS`5w{3ISKHMZag>h_&&G`RjW2NJklM>7$9`hhW9dX4 zhtOAr#>}`YJzkLm8>^RiekxP1251*w{5ekn0HqI)?|RwU%3eVKBDi$UvtE##rQd5N z=%7JPki{$`Ei5U46@80m00fJs@$m?pSA#*sy`4wpeLZ6A+-7|2oAxyNn%v`n!jGxW zv5O=4?TxWp)zT%a&~v}F=QeHM8|u-o+S7(MtSUMdliVdSim;VBKDX8W=<2O}y=7-L zg3K3%#@Nq0t^s_}ug^m#-A8oXt(sj|#tydT*AWU+M)AqE8u(^T`nOjGdL*Jqwd-r_ z`@(fx`Zb|&uG`}}`T`AsE>~zoVd_&qmPTu?m--G}I%FU;6pr6I?60?4A9UA2{?Gbb69%mjMnCCHR=5tj~- zm9Tabw9SW$tkt!d<%jMIX#1vI74DWDemrFI+*VpxkUgXysjVwFG~Q1UaJQNT7d2CF zp`;Hj&KR$f)QHXzgKTWzcq_}8;!2e0k6VW68e*`(X4r(T3VGP_+`d2)xN46FSw5H( z1l(%8p&42(0kz_5~4PH zcGw@&Vcw-4!(= zGs3Yp_bU0`F8s6NczWx}Ne@HYQRonasi67Jl+zxsIlwYawUW zYas{f;OW`cllW&t@l%M=m|ud__%A|&=~tKeOG}9sNykzfP23dps#;<3<2|6SM2$oz?9n=0*n$ z)rLu^F;2VI(8brC>7~-l2Jf303zEgGT2^*a8OsIV+IrH)89%5DD0^=(P!Z+|IXQ3Y zP%Ty)Wzi<2QILpFRn3);C|;fh7df}RO;Zc+GXfAm@iu*8D%??@5DHg=3O5x&ud8fR z@!3aFl*pejyQ^SvzF=>u0>%LcF>Om#Wz>VqFN=?WPfTVAP-@>|_gk9i51 zqwi7m9PxKv3GlsT2g=2jBjcV-@->Bhhu;MDwly~mV-NJyB&nN0K93y79gm;oAGShu zT)Rd*ckeOn4(hfmnF&mLO0+{6_^ig;owm>UTaA$M`Cajb6L40ZMA`8d?UCvAS~I4; z9qw6?+_lvIuuS>v&-LY+SfSF$gq%cO$EwzD@1yN@P>Ik$P2KTk@Rvu*Be{R4om4}v zqG6{tTnPsDIZ;ha%x8#Qc0XKMKdZEd3iAuUj}gwtY4;}I^=#JhDi+>m|L~n8FOogk z4$*|hYM^}H)Ot?(PcATUT*RdloVG{+riPnLNZA z>YMNLs={`Gb%Soe$^vS0F_nS#GctLkTL3f`Sp1Z>ele%zZ|%P!yW+ErTqTsu30Ok) z-o8@jRXt}$&$}CV7iZMz;okiVefHs)H!}@uv`<3ZPSHByZ5&8H`RC_ zUZ;m!Lo(h~e!;5B^|EX7-_qNXjTdY9O;`Rcyo8uvo^G|4?-wwuDg}pqx4qJ?Kj{X6 zw91PFo?d)nJKCy3RoFIIdEElEOa6NG!Bm7CqPwy930s(=U2FD+69!3PD%p}~tVK65 z%iKhrzmsT+B8?bzx*3pVsX#haWn#uQhv7-XR0YL5QL;$UX=QMWJbvpPR2SAs@HOMG zH-DyTesFIzo`mpILl*XCb$t|J7D~(n3`^IkEk2*mJ8xwllh;WK9|KwL7|54@BtoZg z)JBa=j%7-bO6}VUfc76L8y_MP@^N)e$uaQ8kDFtn9Vqkg*$N&E~xP$35lXx6d#d012GS>?8ReiI6 zR$`gF+&=X>IV(R(--rlCRbo)4MUU&RU-@YG)9_AA1!_MQ+p=yhx70LRS9?a|EipLd& zlv7>ZDS;2`Bl>pN#4e6rM|V~2I{emxV-j`6I1yJQ%SvP_;vTcR7W&Alm@XL9GI0bf zoRCO3SoZEG0tNhb@sv`>QZ!}V_|K3MRw=Mt;=9XnQA~uZwoW;SJnGhH`j-!HW9X)6 zd)Z0Ra&h2lyb3KLTxkDg)OZq_}w8GMk-+Rm*p=zs3^}DHDgQcxEpp~eDf#{pQ&6MLI0h`7JE|4T!qfk%ENSc>P&LDdVXg|g7gofpC*4t?uwP3 zKRj(Trmp4{D}1ew9rG5~W8PuR_5jI{Yl*^uaucsARHYB`X zVds~E0S$x8da%|>&a`WkD-NK5M%F27k z&7Fm%Ii$FaynuT+T^dyx{vc3to#X^B3+r!-gy-WeVp)?2-!5>@W+UL!uXf1RYA>0+ zAWDUF#k}dR6J}m8Ym-Kl!0&aevhjPcDwbNrGJ80*V!F3R%|GBk|K=Y7SlD|_N83ep z7IWs{aVU0I3OR5p*y-3G=Mp~v#{<)o)qVXXPMHS9Fb5l~C^MlkB_-Mj50Dldt=a4q zNZ0|gAHWmzYL0e&9~GAP@&f?CEt!2g>wH2e=(qe1m>J5M7N;wHp~0c6%Pqr%VQV(T z-bL9gm!iiu_~qRxCyh{{$_gzf$(@bk@w-C0HMp{@k?Y_BE7{U3%7eo z39HhAIDCrlTYZ&Kq)F2pO7!y~3r~AtcCZP9xNT)Hf`3;x_kdFNK9R=b9-CL-c9?a@ zx{w>KOTl)J_V@QcA>`-cMoz0+ zvsJo-x?yW>BuEw008!+RRce~y_mm`5odB#@$rq~s)nOvCMX;rkCeO7^{!I4_ciXtd zQEw48%CG4Rm*@ND`ZH0+iQC7jG;!I?%*=Aw`8f3hRLKfCZA7q=6R3yO)=z+#!#aoN zotbGzqk~Iz*V-=fdY}8xA^)6gLc0z*fHf6+?@P#1g`Vnt_XU)$%Sh%NM0t^dn33mS z(Ir_xCF;Q|CkhF+K6S9vq24#RK{1S9IT39)qEZ26P(w#&lLTXnxU>jTr=5CvnZrP| zQ5$h03W0Qi@ml*1jWXcMgHK3O1wTR2ay=h#Fyi|)w@WB9$1qXAlB_B9?X-O2ROwy6 zw5;U7Q{#(b${3N&>Wq!wgQM(z65>$^cdH`$)vYKFV}yU^2%4im+Q zbm6lJj+;V;B2B;sH-KhD+L{uOaf)e-+R>$S9N~4}A!oyIOMhrIivhrK9o%THEC@32u z?{ig?DQ(9q-e1i1ToO?AmmymEBu?*Rhm5Y86$B{$hw z6Tjd<@XXoI(Y#Y$J%$SL94_DKl<$P^ObUmP=f4TP-5D_96#$a{7od4EGBQF? z@Yzz1UWRt^mL0V$5VXB^G*ypkEL%9m9i`$*u1wo~iWX@uzI`B)uLR(HW2AuX1{}-0 z4>1zFQ@T(@;v!VU!Cv=JaIe(;q!mni;M}-cVIEYp7nBrhZIHwZO)HLHE2fuud46HU zS^uJ#nyh@3if6^>p{V*u&s=JCg{x9cTO>tmz1hZ`{b zt~%EI-%wn3K`d7(O7Lz+fc^bH!K`R$(lnX{M7uhK4!n26Vs;t&t%G^W)_SC)! zATRQl0GJT0NTZt6pd#wyBLpxR4(ic(_`-8Z(NN>^2R9vPL}S=V&_v_?Mnpapg@MS) z_=iOGHYcQoSa6Lc75J)TBZ6EhWy}#J^74md8;qQU$+gQkXnw^~?|&WKbmZ0xep>dn zD#Vh2i1m@-7RiH}ZD$cb(@QndMjXzv&u|#u$pRhgiFq0sT7Y=yxIOYQT_(|Q*focs zh&NCe_PD_+n@jhj>=Kr+B@$`6ZtUIxTvGUS9X3XxnXRpA^}ikPfu{6$uHcP6@aFu2vJ) z?DCFFBOQf;PF7D_-=MciX=wpSB=uZBJRN(vS47zBI}d(LRIS@b0Ad;qwk{!E*X~K! zl;4J8xiBowA4JjHF82b8GS@mXaxKVqaHf6a5yY0r*l8;L>;SO*rT;$&)EN;1gPvP# z18F^?wt`V*4kTR1uJe2i_9qA8R^}_AFdb3OjCUod)((!3JXR*LgI|?C0F3=r5VzLG zlZ%VKa_ig5T(RJL%>)0Hw0kCWqs5IRK#9Wfgb|kpQ+ZzqksSdgI6N zW>HB=Zh1KdpLMLd+t0xdQO-MN$HKXQL`G6Us3AeV5K!^#d4lsPk_(VUxn}7A^4HgD zLg%Ad=^`PyuO3L*;)dT+z0>AuPTe0~@hjEmyYI+f8(IeUpPO`TmE7yFtHSnP@_D_&?5HaZd}`&H$3k25W`kO%X;lHzF9X~kMU z4cmTac8n)^-AVLSubL7G&9;g;@eku{T6XJ{#p}m=N;#?di?n+4ri^GwGHJ){_G1Od zmB0_jIx_>?rfz)>^79LL(;1&cKI?nMTkyYvba|O#l1W^pWD^h+ZCXGF`n5w)bjkA& zOO!0P1;b;wFhZ6mxgNYJZAmf^$fdrlP)WheXY5*{#eZwhXI$pX*`CXacNNlT{O+77 zzqq@9{Ep8I+j*`>p>W4QR_x(_o<@|x`JX1* zITr+Ui-gQN@TM;by!yv+-yjXq^z5HZ4y1^uj}0_431v^J3K4%}FgRWo?-hqlBf2FU5|NbfAl79;=#c0!ex@f!vQ0^giz7IPlYadC zxyCGSR%M)oXm@b;=EN5{K?b+Ps4tu9r(SZ9z3_J9B|%tD*2j77BOW}+IC}ja3@n5@ z5S7itZoyxt!C+ywtU|f8YNw1snC!*P%AEcRChy0Ho_PO`<7NU(S_1Q%Dqv}(i*<>z zHUPsc_71@5UMQDDr#M9gpl?A}#oIf+L#i&TZ$Ax?M5UrE%6JCSbWOMGf+8*SUDcrp z?KMk%!tcb=x8`UWy|l;e%2g7F#g&v|RMY$4Aj>cG7eWjO%nAr0!euHr50lO6A$r;B zuZsRI?CXypB%SYH+kmyUJ0of9wMI4w&X2tG(L(6#EX6q+KwGbaEx@_fxZ(>nUOkLA z$na%Kk3{*LCLT8ZZgpoLM0d7Sv-xxR?2=^f_{q3vx}Omk`!PM=4A6{~e(TCl9`PDe z`!5SJYw&OPCsD=lLuai;gMNr_e`+tC>j=so&Gu9}MbK+CO9|>Z7QTcKc)yGu@E_RE zmM@`Xqr~=jd?;2c!L`hh5b5sCCSX81bly20OICq#O1dr;orMA+i$l^P5mijbkRmM_j5uMUR? z_hQXbB+5GQI{JL*#L7C(W^O3Erwo#a$RH3IuaD+GheGGE;at%$p}xCZO6&+DB{5dg z{kj_%uW~pLQ;hPbwT1`7EHFs;;5e~6^d(^+=&O(HcqIkd5W27&gDLh0kT?5OSi}4m z-E>TkZ|^12KZAd!Q<~<*8ht73|6Yxa#H?C*$N1snxABz(@r=nt7mMX}p^WE?p9=BK z3M#%9reoPDD!hKRL%&1rf2Vcg!{ao(h!<1M&oI{eh3`p{NMWI_o-6Y8%gR7?`?ArO zl@qXn`rO={Yz9A1j)|?3(wn}%z9nwRav20-ja&3Ktv*u$bQ*|I#Clwe)h1ctTHIna z$NC*3u;^U>F@)U9@jX-93DURGv_VVCyYsnG|A!M|?8eidH5v_Iq0Qiu#tyr;f5a-rGwqxC%I`wF(rY_~&b;kt$nnZZ61_5DEb-_8*G}Cv43V@CLFZ}}6 zGs*HGs@Z8TeW3bKo&OEhdt|IAPU)*VYjG_IAOVJb#IiC1E*c*2-+P72JQz4Vg$NTM z*Hmeo%-kv|RuXaoW8QD`Qu4A?0z5B2${BhrT?zB8GOyw0a`qs87ocEHE?h!Og|dCL z!z~g+@QKfaLRFPjR4CgG%4kr&c`fLHl#0)xhDxB)6x<53*I&^ORk^=G322(%T6|9X zBh}3=XK^{Na$bcP6c~h?+86X3KrRk?;nZ+JOZ{T*Eo7QnkgQkw5j46&*%K-R|Pri*Y3Nvy928M@E23cn%;jhTkTgP zuQK6sq`R=jtEc^vjg8PadGmQW8l1#phh+Pl zGW9aP1Q~VPkaljicq3dAUHeMre?fc7AZ(6`jJnHQmIfvL9)?dL=CXqePv^uhCI_D7 zcFBtDmLxL-yq*6v_IB~A#OL%fl!w9F{LM;-^ZVn{1yQ}`uHVN?J;0u@l$9(OY$l-_ zrnD7;;dUQ}^$|vl0d%cyE?@3WEPOno-_vc{ryh?`y1GACgXoc6 zHVv^BU-~N2P)uVr6nK5mqE=82Im@R>(|MO(;l}f!+#l+U{KP!6ZsmFvR`5lY5XByD{Fp+@49Kq zMh_aq=#jt2?)?vmiE*C;urCI&$2mrX-)TJ9(E~l}ec?^#qkOmfqBE5{efX|>#f7s~ zj$A6EgIh;@Hil0Rw~V&qr8$2h2W|nb6K03|PB6dg^suMTl}W4nL?r)754poi{qx2Z z`D60=@-s5N7KBEVGc(coDG33SzZ2lLYC5f;FDBjyjzwg4Lu>Snn~dpZ@V2Ie_!uuZ z#pTHROz_c7Cs4=}z4s+XciCPAYf20fU!N|(8cxrtkG7r+=SXyK8ITb52d^tyld((i znXi{S?6>wC9186H+HBiHpUMj7A3Xn^cFs%Cs`FmHTskU9C}tFr>Me8SH?JF>NJ2SDyhKN zq6)AT2;^rf8-ZkwKM)52*@PXv^yU=d8%BD<1EtiFXw$!O*nZNawF=(YTCQbHdUzlx8AZ0tsgP_pk{iSHh1j_^6 z6E71WZywj|QtkcduJZ|hdfGG2$#x++-J}cwWd3j*!oyvCS6#A=5{bVCD?UV5ag>o{ z*Y=u^TXoDxi|tQ3L!CXi%NtqPq0`lkL=g)pvLvBQKKw*AqyDC`FGU zsV^nCuA5==cICZFVbRgBd*ju;JVm$L(`0vmMRKJz+E(;^&^fCfji9rE%sY**{2&^I zd3`2Aa=@{-FT>C@=KMFcRmBa4X~Dn=^1o6l>?QPDrr7IFE@yuR@yM~45drO`UaOU^ zRSumZcTimp9ZDF{>(`8Us5E$rojG)}sjLVfP!YF#KuQV`aHc5*fQSn4QK!X%M#-#h zsY?p%UHtIzV@yUyP)^b8p>vu%b*M967$irt40^lAjLwF&s8x3J$Qx9?aefa-+av{b z0rIw|w~v6pu!W`NOIQ`P!m4u%F!9OF%L_0bXxu&2&=e^%s|;UZ0#+j7+`5&vW)f2Xe|Zp!C{z5~;^d z04HFwx*=8iFJ;ksrsM^bknNk385tB{>8ETCC#tBZ07794jmPcxBExzmEE%sTwMZffk3A#sq^e*OxF@P`X8HyBX6KNVx{FyB!6BW_CZ!&-e1a0HIq&7E=Eh zE5v`vFuX*W#DDSXh&PtVHkAwb&VSPdssN;#$Q@pH>~IH1$H9?7Kwn7UV5K7ySPAJI zO`$Y@pJNzLB7fvF{Ru&Yr-(BBUNp|yCv}8Ef8+~L-wC+ARZz1)^b734W+P9VG+x8^1 zeM$@m2x86~A@a61F7FurG2r>anO8-m=n51k1)BpxPb><8w_l-~fJ!)*Xb{@&xS*Eg z_H38(uck0|TzNQOZ@v*Tqbkj|sONOH%-HD1SWx2i!1|rf;#og&6>0f@q!)_$k8Et% ziNk?o+xv>HD24NnVNzwt8or9Z=2c!!Z*@b5YEh&q2ekGp()oe~ZD+}I{{A_>V3fB|t<-puz69y@=B6R~i z-b>fY+?bzvfz!&$_sqX3KZ4BPqOMSrm?pAAOcL&b1nIuzj%q zPs_Ph-r1QmmD4&0_-hGvm`53fUsU}?q}OGE!RaAZInOMM9uyL9j;mS#QdE0xOuKtm zD{$!L_(gKHd_}JZG6Vd=mYg!%9;`am;XhTS6%CO53a>TYbk>4VyfTxD0Dv`4;qI@8 zomHPWvu^^h{B)e>OoX$RMh@m`az}M1o1CJ`9y#=VE_9vwMmH0v^|nswk+NRAEbvZT z&`%q@9lU1VN~FJC%{cu4tuP_H0&U@bTHA`jxTt6qK3y4&n1%clOy&`Kq;K%dC&&CI z`=`Z4cjzWhPWPeZKZFd{`xKMm1n@PM7-|Z{;E=Wp0>sa0M4NpCcd=PQs~+uymKt4H z@wQD`@3yf}4lCmc!uO1~c_Q19avn_M2@TFiH3V)O-**_jdXBly`jz;u=g9DLzL}b; zXlM}J&22g;sj7ZB2O2v8JGgOxt}#i<_Gom zm?Yel3s;PQuZuYzw_Vq}r2}4e6*it<7yua=NhE?M>_JbkIMVJuuZorex6fDemV?Gq zPxW2STih485a5ZSg}v~t)2hxM2qGTgwcxo*!lW#@ow(M&Q5rtT|okGJayXQHOkHjZ(nNvV@IcG>g_ub{l z(Vj48$n&qS$x|14eV-@l8n0F91{OR|EZ#s>(rXTjR1tj+w_ES(J}u_|pSTwAIus8Q zB=Xy@KzrXgVOljG5d?U7vf5|O$FZ(GXxikP>?{r<<1k;AKH?UTdl$M6Cel479}u5G3t+fBwJ!1-4!`5m}M5Ny|#m+P5#C zEwuZze^_iK-H=^?-M{GX@K8Yh`RaA2kMNNH`^RC~mm3bRlv`ad;C`n2u2r5B2cE>y zvL2sf^jg5qv7pBboZd$PN^%@LJc-2yr(I?9Ilyw(YbpL;|3pC6rS{%>n7`QCM3#j) zB+~-wimK!vy&r~EXXr}zkJodPUN*vA0?L@C3-#8KM>Fh^sQ_B#vp*uZrwDMP0PPNM z0h@*vxqTo*7!`VckSB`y&nWelCXTo~GoVRG#rBiaGc?T1C}^c$N@+H$Dk35W{yh(h z7w$UWo88X8l{c=V`~xeIWjlFaSzY}TkeVXbaU9{u9!Mz&g+S1V*k6M{EtbE4Gn}_? zS+d3uovF}YkCTc>LA60PYhyv(Y?Z`+j zkYy3MZ7}D&DvHs6orGN_%Q*KA-jY5rIBlHA+MAD3Dzd>sbtg@DM!7mBAn;s-!lF1~ z5J;vHgNgvG3WeCr@aX8#5k<(ii*Yzu@XGN3b3_Oh2k^qTEJgLKbsAOu?KEPLtd3`k zmd)4i3Jm%r9ItO@!t8oq;Sl^-iXLd^3GgdbQ>`R|wVrDs(_1~d8c68h^=H*cUY57< zH#eu8Gx3FYlN9IRid~nbM3pHd|01A|q*hCD+1h zWMBKej=uLYINSa4a<89a&%n_xH@IOK(%JW$g(5-M7RgT;&&!|Zn>?BeGy-*>DSdNC zTkccJ)*KpD+)XV4g+y}Q| zimgZSH71uW7OL#Pu3KPsboi>|F8`b|wx8*(TzYIBigc(2y}nQi37Jnvr0;KAJM_pW()3_h) z+wY`_bxr_f0Dyak7x}4(f@QvP7r2g)&$k}_K!hE(jiCy4`BHPMG2meSLWa{Ai zDUH#2Ai4ZA^7n#sQily`ud!GApMpT7SuU&Bw#$o|7nJvn8`qx%kGVoRMruzd$*<0? zd6{)KbuNDio^`lmC~(U(ZAD^75XVX^9U0?*dVailsd+Ne6(N6Cbr(O@=+P3-*Up!* z;D|2h<|W|B)%ja<<2Gd<)ka(83u)!eCb-pTc>NYBnC-LWsrg%xkVd1FfTy-;^w^cQ zI^>pbYgfZ#d&|Da6k<$v$8G8AZdhzK=Fe0>I7v(JBcA}jlVTiUw02mK1LZk?tZO~g zNBP9WWP8feKW_iVF?;)t?tQyi^*qb__0##V`i65-epfrO$|;@rG^{o`{-BgIu37uC z+iOtB^xh;K;GdjmO4`I3-NihLUA;No{cT5`FFvl*`N49S^YoQ>dhX5Sz1{qt_kM7* z`#X|cy3ip<2+$|@mf3_2K~7D5%Trw=SNDa^p<`;qxk0nLHG@4dVn{P-@x37os4{h- zGZi%!=g95udipjzo)L*IM;pt}AI|6NXp@4Z%WN`GzRSgGkvd`jtWj=a9vNQ1wc8q( zr7{5|FaxzjLdgD@ffz9vZv#$6@9h>gbHD%En<`cH;EGoK+rrMdrj2Bc&ci~#j6458 zK+xAL(xf_!HbOn8*OkzjAVAzwDqv^XyZ6$yO*r~ir?@JO95*DqNeT9t&K|UG^nY>o z)=^b=&;KY5(jna--Q6J|h;$r4Iz$>ox;sQd1*BWz97?)dK)OL1qy(h9@8)?vpYQ$t z*8S(+dzNddi^coA_ujK-UNiHW8QU#M@>En$Ebe(DiX)+lUn$hy^_wKK1tJ z-vIJ?2tW!p^?-p)76${8aQ)^fnNFu`vM|lethP1TAk;Xb5Qa`4}t@3 zPYyFW5v0T1<|^&2WLuC;GP4R}5o3+9lt0a^BSW)RIsI5L;i2c%o0Q#P0oye*AW#y-EC>E+8}9a%^Y7K>Z3|hSY66%HiD05 z#97Py`~@g9Zz6@@#25wzmL>mBPU~B%%9V;|0CoM))6mfHz@hyH6}nk!7;!s#DW|*5 z0w0Z=yQM#|vSn!ULT=#X9Hpe875)9L*fXRD4vYt(Qsn{LtL6I7N%DpYX)aTml{|B) z62Sm259nifKR5k7sTT?bNaV#QTVMw25~|OMec+_poptYtD)-rxA$M~-*)y+ z>jQgyT*oX&vHevJhkPUF;_4(joCPGKon66!Nki@r*Va(5%=3i>J zyX3~kGk#-%W87z@c9VX1gJqB=Pu2%xEeiZn^f@P3V{1*$-h*ZO|sdy0EL>05$zF{@o~yB>pq zYy|HT_|vq8DIC^e%KOx}$L15+f}_XL$gzihL*6)v-LadfSq$!=36bMNrW%{PAM^y#rX;y>lSMG;-O*wKzq ztAl}JnD)Tb)PbcUSiUx@oh`y^!LU3XWbUIKMpJbo3;d->JqV$;>K!LAsuPAnHfUVs z3mt659!LEFbEZ3|N(%<)9lIS@JSE!4Xe$vE4YasKo~xzYnF8T@5|~-m>}gU5l=_ z)5n_u?wU!4UB?cq@GzNWb}>QN>k|#q5bOeV?tGlt@jhL&v5=yu&aSYvhShCCxWVgw zG^ix#Y%>wPcF*!JhL_OxtSLA*Ugrf!OBr$6^ySN#b8!M; zDm*ch@`zGFn>%X%*{k7GIFc$^!#xye3z~loNriNeA@CV_nXX1p59AaW(+K{>F z@72&i?O`)oIjbFKc$gW<nBxLV~JMWKM|f;^4eXSMJ<>8E{#D+Qln~D$qMMR>ri?2&ABU))c3T9 z$Jl#BR@I+%D+^EWoBplu?bvhoT_Q#!;pkor&C$SS43v`$jwY`qw`j{d-UgS-L=!(f zqqgT^L2K{p?M|@$TXt!rxS*TcE>%BO zjRn{vYnL2BOudj*TbIP*&jVz22(d)4^GRs|@o&*}wv&er?lt>p8t?_)?&@TMOt$Yb zIy*Zf+h28Rjm^&K8?nMeap|Z4_=Z3rnDnEuGrN56o>kwnF-HX#4#&Z2)f=I6!c8m6 z_lBmLe&Z24-#?R7M1|$V_a2^mQVS5Vv7{oH3~h91k(-WsSsgzNpF20BXlnAS-g`*F ziC9D&%`sq$hbQv;=zUz8WZzFs8uk!p{Gg~)(mq(+*^`;j!|~t(zbvj1G4ht4<2hh2 z%Z;4=P$71`zy%9@TxH?sVKlvv4y)eaDd}G|b36!<#`$yL{3BV%g`x5S1tcU|(bAt@ zPoHHKy6H05UZxkdZo6E%>!>g{zi%*nN=T^4%wS$tI+fqy^1Y~t`L`8t5t#tI7Ep`*7H0Ft_VWcPqnzwkcKRL+!}_@;Qvp4JU)<_3f=RZX*|4wn?Uhy* zhT+f(OwFnHge}s&gEr6$!;{;p+r{be8L5G|M#1x&*vHFWVQ7M^B_XD_M$!kgzMN+x zh*c)X%BHu12|M$KMyzH~+}y%#XZW4jHO9lbQkKBJ*5j^HV=nrs;fxv8o#r5cjwP=6 zCQem4+WBc23^O1&5@4E7Gw@XY<1D$p^lT@iDsz9PhZPPRLWXth79c?AoeWK52ew^) z*YZw*w4Hu|`8vrSwq_zPvR#V6+o_@sXSbS_gXLM;9dj#5kdI%#W>p>fs2>oUXq&=* z_Xc@!VpQ)GWtGE=ftye!ofCj%?-87~5s5{KNWpiQJ0o?dZWqk|IZkkOc?@sPjM$N(I`}nJ_*` zw(!ue#mFGMBksgizf#noUrB|zI5P-{w?ZPROH)SpNm5^#vW5z0y!=1bK>Q?J*8yF7 zx4h8XT@Fhtt@ss|aj(+HmR#klM#vnIZZY<1%_!_ztPorQZJ(DV#&wpk9$|tx=m&VkO!H> zA{yGAZB~+0LBizV&;l7WJXQP-l%=~jICbovVmp;m%RUUcM#3c@6~K@Wi4ic7^wGE0 z@7;EN4|-R4j7R=QK60&u35!t5@{nPxiBNDC$c9qp3_mV=!d~rJ3)sH%dtjG(8#`OZ zlPtn`pI(+lETBVcYi4Hl#~sApsHqL%U9u2WGniDuihu_`+T0@X+SXS7k2_?l!jVGp z)`o>23nl-b4Y9z_4u_uX-r65UsBi}S-N0#Zy~V|^E_2uenv>|zG zc}{w}qkyfT9|ux#So*+w(D=lNH*=@OQvC9Q{+TLicRWG-y6F>I@27|J&azxmTIEev$BF8dk zXX6^z4MgZ>_s!q?5$2rGh|9SxNab6!$uVKzC}#{u%MUP!OXNdW_gS zoo7(s^E_OMY_p`5yVxO2SpcIEl6frTBWj&5Jq60k7dyTZJFS(*xu3LW>A-VyvxVLA zgm^lf3BoP0FLmRTNl?GAu`x!9r=+&uh-;!8WToi5imi?7^T`b_?e+Ucd673U9Ac?` zGHl0C^8IWrh}3U;-fcnzTc0JP$n^&Mw;CbMoibFCzd9N3>I0k-oL(gFC~Y)aj^PCmQFm?_-$8G z(7`T}j4Bi1akAK$1zGrGs;|!tH8>@l))wH<3a;kjjJ&v($w|!g;nVBgo**0Hx|`(C zLVii6;5VwE*PL}5h|wcZqHAomUE@hzZ^{{aui}6ta{P?^=~h(+>eZ?cqPjlRD9?rv4dE2bg4lgfd908Qe>5$zfJ%?K( zuxj(^d?{Bw@jcLUFuAby3a*Jt<|$sD;~qD=$hoiW{OR+4(HsVndp|yR*L|Hkef5}# zqnuzv(Ej5YnY#1cd0(15EKa-=40rJS&2-YRr~B}Gm%v5ucATy?U{7x8bzMZWYe>p+ zQ-s^@v_K0_UaBRR<7yv1LD6~yh9sTa8!9K`&9x4xdSUlr=`vU9-*HVUj`fmpf4^|O zuH1g+vqQtfml1&x;c`a9wjVQJzjKiIOpT&@-bAg-cCx}|&ymWf?TdqCSUT;U*KN4r zuo|TOuwreZMf@%cU9yZv@s-+IW_f!Z}2weT82 zsz2BUgm!*fz4~%;#x@^20{5ZLy`-$E7SKTMU%VGxD#?x2qoSjV4E4TDLm0Es7cjBK zLDy_*$_F!YrOIR`O-+d=Qv(Nq)p>Nw(KU3%^*q?aVMudw$nL9hM`bWypyEb z-ffD^+Q|al$1aJHF+g%&i4fg8l<`nF!klyw~WKFXkKW7Hug) zcvF%}Pwop9F2}Om?zs5?BiAnk`m82mBYiJb3TxL%cHJqgd{hw9rZZQPQ-2T$#cf`H|Deib ztUq*P&@Ymi*u6J{ZT@Nd?W$C*mX{mwd_Q^U|w3Yqx$%9P!82;_?#%AIxqp z->D&IQ5}pVFZRyb*bb7eJ>zkYkVYHB5Wz38XBT;ObRObMFNI_EMFpnzZ`+eUVahL_ zRA<@*+ot}}44QL5ILSu|2B{<6KYEW*09~|Uhn=>*xRi-nW@8quQU9{ltf_Oi5P+78 zsEbN7^Q!Z5!;1Dmc6xME#B5c(85n#z*+~$IDZ(cdWs(E7m8@#zsVQjC$RwU92$D-< ze%_EkQIHD59tycWolvXty?SqJYx}F#f&608!^CQK=Y7vA8O89|kuu+oQr$%bk@nuQBG( zKMfR5boLt@*)KS*BdwNh(=p^v<9Gh6oM{OT@h-C!x3tMk;1J(nPYUCqY1&LK)d@Ve zJ#=2(MXsBLl$7huOK`#56z>}M?6=7c%f)0Sfq$nCnu{OuGwVOHozRSc>nBHHQu788 zpcret3obD4~Fbkep9dQhl!i|j$yjAGHMs9O+v(Z){NI2GR3jp~9ZOQ>( z#UJEIPC!#Tolu>y1l=?_`D~u_6Iyuh zz~}ftf>?<6n8r`%Icrvb70R)=UCr2|ai$Gz?PSab?s$#bX^F>x!Mt01_~CIsWpkxB zae2uS!_;Hm4q(Vr`KVwMjUql3_Q?@H{Qziu|3v)+_o=)oB{)QWLlJvZ=z1uGRs<6bpZ6>2 z0w@%th6e*x`o9Qf?4do%Mlxgw13e; zE5-jg9ao8XUvQiK+R7g!?7u~Cf4JqPBqsj+grw(I6s)V865Y4kd#b3|e3-@RU*$@C zQ+ZdSzt#Qn)mG!!hoTylTS-Btq`111EeMsQmi>Z+C}AJCgrzyG=s3i&Tj7PeaNN6W z^xv)lX$kCHr148#h0!|0OkkNj99D9BLd>%X;@@cW}zP59AVr{)(0 zh-BKPL>Xt-HE=lTMii;?A=Ztzj+RSvt>iu@h7W>s034gWIo0|V9vmDEYKdziT;bN$ z-kL|}ig;;i)la6kSly^>u|-mRXk^3+kdE*!{-NV6K2lG>fIM$7h862^9t<2H5)Ecb zkQdj4sKuCDjCY6B+h%>No7pQY!em?;{caQ!=EBv#n$~o2JlA{kOPnTz?bz0{fqf1I z60RZBGn|f*HO2BpfKE;LK*$;6JMHGYAi3jdYUh_&NUM(H;e zJ(dNy+HQ~csTAtGz?eJ|Zc{kNx->w#s&ZTu)hX5QKHZ)W@jhj4XlMZAgY%ftn>-G{ zs5rnX=mW5x8#4q9H}M%dXdi`&L-QDBU)t^nB$jEtw)pbJ9*a#td&7ts#K2pQrMc4 zFe(VzZ-vh+VmAD>zvt&@@c4Eh6Pe8N|C4kPxddIMfIbKAV_**;oPp*E{$YS@nm@D<=1TBFn> z^ONZygh%;M(`Jzh7(cPhj~<(>pbTN> zU<0R?#0YBtWGr&Q(K;s+fbw6es91t|p`I)B)3CN^w}y83nmi5RlR_ zQfkn|775B0{(4eAN4!LcuAx+;41&_?`A6C#v5^gq9E+pu|D#(TSnIQG%E3(I? zZa}YRgxkFD8XkeOv$;_J^b~fdz);+n zFx_kblGL6NJ{FtG^|C|-6{P5unv!JiqDy84he9Q?4#q_^*ff2V1YkfB`50@TAtusN zr;}>9kqxULn-rDWt=(iFbd2uR?C4MHPs{JyIh?{~&c{!BerMbm{@GgbEs`!u&E zHb8F*Q4&qX*2{x~D4u^#Nu&+letl5aV zO9<_?f>+IbHeVpmQRD*R-j{gM;M2eC%yIY0(>mXl*4tQI#qOxykeFYoG;Ox=2*y< z`U01Od#I{vLjOt!LfN%3r{aG8U4FpZz>{oXrMkfa;A*<_|J7I;xPDKI#A`wcyOCwJ zArfu|r|eKD^o^C(nyYA#^r0365_WD(gM{U@+tkDJMIiQbOz@;l=1-a_A&Kv*R;bVn z(tkGbpE8o4{o|W5lN2t(Cd^~=mqdS%bG+0B5-Q(zP0)b2(KN&KTiMB#BSbRFu5e(< zz>-msVlBVJJX5W#ic)|5B#!_h#UtVfRH!_>trLbCVD^&N>~gTO=GNEOPt98o@BqFn zo&i3P%zy6Eqt(RL96i&56h1E?t&hy4)mtT^N)==x`4%=3Lx%aPYfBz$2|J5ipk7rC zL!+x$HO~f$Uz2kPv<~4eTPancakhmY!|~c;c#emifc?hf5*My@9*drGuGB4N`#nxJ z)c`#e0nYKF!k8cvxETm?p@pSbs`J-E%)iwRNouz)1uz%Fa2J&jCYg79?~5+x`Mnzd z`*vuwxnpjCuq``P(6ORD(?NZgM}&t8YDU1Y=$zf!s22jZK&52}3O%y+(2nPFi%|Pld(!oPgeVk=1~w4YGl0)8HM`1MaUf{!<MW?{o`A_nmwV_Jl31=qBkOmYU(Ta(-yR5c{J~E(KPX2DhlAS#CQpY&`d03tAr52I{jqm9l8GPbv zL#spkc&46PlBjaE$9vIN>OS6{sTmnV>wWPCpc8kgmrv_vYz~-2bgBwspkDW-SP4}2 zjpndhbwZ5gYp#>Bw9!6#o}&c9laAKs%6%gpc)bUFz9wax0n`TVm6gvI&Ib=t1p243 z@`?gl4MUQ7MOw4C0A=ntT>4)eIg!Z9;j<>~fg5`+t(78PVnj2Zg@iqMpc zS57LZKmS|y^>zjeMW5tF<(lXAaEIg}c}3lSDp-!0Jo(o%ZR?>SEZ$++i`-pns4$>4 zEotID;^F2F(U4cqZYx~$*bsS|E8u{5;cC6j;Kec z5-S2DfBI)Eno1&-$D#+=_GCva$Lb5BoKn3|{YqNbWe{rD5mT*c2Q`g-_7_lFiGO*K zD^0Gdh0!b|xwVPlGM8q6Ly(SYK`Neah`7OPQnq9OM?LE(UtEHxJyK*X(_dbGSutf@sWlo_kF0qKuvJur% zF$beA$fg^E2kaI%L#1A=jei;*Id^h#E`LUIg49Jhs>qqv)OAD}S0F{eU2nZQe64yFOHK#EU23A~{oP&+AHec@#*R-b;QfDc@ zfkqqM>)1366hto2xNs?Zk`?lM-;)7WYmT?num-31chIV~DH%i+3agLzSW=5c6Ky9z z(9eRIuuvx5n7!)l&^4gnb~XA?P*#E(!&;|h?DiC^%-J#r-)c*0-So6RKxG`sk&W;) zUGjL{QjwlD(zjJ!-rD)?1M$iXR;%-KYS0F1z@ct&`m|^8)wIL|ZriOLp2^?KFAlp= zN0>M0q~rm8Bh%BLE4N=zd7nB>X1HK8&9HAiWZn>B++R@JpQd*-Y`uxM=Mk>oA*J$b z39q>Fdd9|>Ii4u~@I%e(w644=hc%>Xc(~gJ0!JM&^ANKve$VHB)LS?Eo{n&9Rp@f+ zAgN;i<0_MuS4aLBAqsKdOmfkeRGNJs1` zjt5lS@uzQtENiyDNbw^hb7PnPp26Yh67r{OP()9rl6)ATzqQ?FvR}Mm5K|%$ZZZ|t z_aeA~i-u9MKim?EyWqaZD*wJxVRGEBprAe@_Uftxu8jogdT%IU5yN!kc1J66*_1KdpPrr>0v}->z_X zTq%cexWF%*L5etPPKKb{Y7f`FC6Jj)#YItwZM=C=Pq4dKdpzz9Cbtew5_3* zLiX(P`O2j8I|GX7GnC<~3S-?rm!z`2IbZG3BwB^~hle-&*~;GxCiCRnL`6k;Ze@7L zj948uxHT98%6zl2Q{gR#`}%=8e>v15Ira1Nw@BvMXO2P06rAz z`XRrYt+d>8+`6eUK(Bwezxg)?OwzUYyBx=;E0@@0r300EedmM7V4DNk#exgY$<~OI znVowjSAFu)9pxLfYf+&kPfCj$*d*0l`xh~*lgWLah2!>%hS778gOZ7Q(`mJ<4T~A` zs{up*s!b9`bq`O(0YQpfB5v&Fu8`$hfe4KK)mf_phJa0L#Q=n1sQ$`WFPy^&Bu1HGTR3i)RKSAsZ$o}X0cTf5@bmb%JPdv% zBN$|TwNxLM7I3LnUA{DQH=}B9zl4|haKhS;1sBpq&0)EkbHDy}I*T`|C-8)GqjRDC z;Ifo$nC?uP@1|&esMy1Jh%bWiI0RYEdCQX+qwJoxJW)T*x6Ihmzf)N#xyAtmh*f9_7u+%G6X;`8)jA>yKE2NCdKp4?<1B0~?*7GQ!Z1qLEUKoq^nW zK?>QS8*1AP=-%YDk!S3eaDXK<*h^6C-U?^gAjUGZIJ+*|kdOG2Ljuv-duby3eSSLl z13aKs_10`gCp}_SLU+8|rvTMW8j!?~T&?wCF|#6T3s2IgMus=}nAG2m;c8=^BYZvC z-yB1AH1(xxpA|n>;@(~GeZ6C`o|1UGdcu2~6duqtI8s&@&^u3j7nsY|vx0;|Xxw}9 zP!*oxacVho63}_v5^%g`H`0wAO^KQvFD_2$GepA4ULPqLm9;nWz~vNuh1b1&g+9v~ zJ#_OV?Re|BPR(h(0s{`^urz{tE0*mh524_MvCR8atz-_w?Zb5r`@|0TYQCX zo>EE#@!ib*^4>&3XM9t2awV3!(5r_3FwEDjd-U;4=)Fcb!WQOwYaA2z!_ea3<@3`m z)}v$U;|Z}c8eL?*Eo_~KWgg*;sN9T@K1#^q-5hbE5a_FDr~q6vRdjKqpz#ZXuo3XK5E6F93%Wn3mXr|JK< z<#l_bBo2r-pHtKyWEbJ1OzsKQS}sL~KM;TU4O_ij(Wh&remi}*k?HXFeh+ebvj=UW z?8?lZ_K0jDca>k}jzmf|n|^0{;9iXvvQ5rTqaqs8j5pO>bwIL-4Cjt=u7c6hrg3ff z<80YG^6FsEw4f@~LznQ~P#0nv=W9oIY6X$aU$Wf~RtNWMbBzZ+M{UEOkz{T^eX>XF zK_HFH7>vbIH0$JDv zs;J~$SN6I^5Sl?QhFLkO`1gl9g#``56>86B#3iltxX9K$?eOYLv`?QxpLt49<4CZ7 zqu+jaN%N-V)W0pmO;4BqE?0%Qr_tcmyM`Mw`NXNQ1Fef|)t_8Fux7JUtQh)JO+nuP ztAVgFVL#LYie#QA0j8}Xa{u`}!3!*M$ow&CsQoJI=hv(cD8hZX9C8vivqeL*NHT=6 zN<74nKZK^fJ&`L+A)vmgr54^^qDr=DaD#JVxXDOYBWEGFDyH1FE-r%X+c|m*MmTim z;)`{p?H@_Ri3)l%DYhBcGpIk6ZMKcnkNpW2n}+7e%`~^vB5P{LpOd6LY$~4@v8~+B zf?ZUnXx!fTrkk;j@z&ZSOv-g>!M$rRyu96#ihHbH&?pZ$9aE?PEQ|Vmm;EF|Uhjv! zxQc^I)!WlB*=~2I477r=0?rYe@7vsSr60T%8bdKSSK1ssX}f}E zxf&9_-+XF9;mM`Zb|XFfy-A3dAKUqd!ycJ!=_E(Z{CCBgHHQx|*Pbt&33FQE+DUVq zMySjQS@QKY&$=#L9vm|P$$nc~MY0~Z9nhy}YUFMgX14j3~F_Dpxo97EI zBdZNtnTWWy8^xMWk$o=qy8*(OsIddPo}$z_7*J;!3R6!U^%|BQV!wuC$}od%dlu!o z9=8k8>V~mWWK~XEBpsOR39tr!$A!Sk!nS{X{)Xz-hprLffGFH>!(5v=8#Kq4R8E<8ElKy4aEOsMy+Wu$s?@Z&vh#!m88) za7G+%9mMNc#-zj%qUd5(%vx<$)9~={#-ffpaQt!Ms&OH}S-h|~SZXoLVFf=3L;C{9 zAbck@4o4HI9!Q4NUZzf}L|uTe{p8(X1od;%k$W$L>qZ1bVVhaBx<2>@7`7Jbjwb#j z1DhN&T=^cEp~S&Nt9w(K&6YzKHs%2ZT9Y5$rrlYwHfuXKjVA$y#!v)x(7`SjVscX= z7cP1ORs^-;pNetXN=qkRaHxrcI&BH{pSQUocf>|UW-|&XB|DZnO_W;xQm-U=`U19(E=QZqGubY>0 zLwR`Q)SeVsJDzA$=dYSCl-guEHpTEb`uUu$9d7R~$PPED7sIA>$XS;!7;e}1{EMgz0})OxZ+4~~dK z4M+SCj>>ZdesA~YppE)sIUs=S0$gO~swcQK%4qG+WKLA?;27b}UIo^RF9qx4fyQRT zSyFN5=kA{3nG6_l%Dr*zuJ#222Z{so;sQofXmDliaOYn06$2g`P4+wOb-2H(q_%I& zeS1hex(jlqxOWAcRQJ&{@B;a2D9vUdsw0Yt9{tW?H5EIA-eYX1xe)tqgHD4#&S%do z-QVu7M%0|xnxYSeF2K>~PCbXgR4yyNewoIHL(#v8ewF8*Ah zkw-yY-QF2j-BQbtxxwICS%7M7FG2KC6D z#pSJ0Nygq!R8&;zy-pZGsXoX;(4ZlJ(V(;gyrQC_-$6y(&&ucsDsSth8{OMHlJgYx zH+%{<6&TW~?LX@SgXyaF+wgh4{V$*V6}_fS_iZFi+#!4gXR-7oIV$QC`OyP519$jm zD8*C4^+D}~{&(6#m4qR$xuF5jTpBciB*H{cMBjSG7iQdC8VYlGK>X`@)-;nS! zD)fM-C)2l~?&)o0U!=sXW#&=;=nJ?<``Ze4jDBLK{I)L3x;H!$9|SIH(C+~a0`D;g zwbpoN?kFplpv={JNw?pyMa3M2@2**_KGm;vr-+MGT~lLrbG~OYe*jo&)e?f>8XG2T z$9=|7B>N$|t*fn#1ZP&Itpzr`dosu=%&5R=8-vE4lNByGmQwNBP#ex!Hy1(ruw&H0 zJ>yr{B9jLqoa$du__|#(!-*UgT-%eIw|i`JGX+v=ei8g@6Y^*+A0AY9io>Q%$>A0l z74-f%c-dQZ#??H{9TIb}u~A&38hf7|etabA`bQo8JUo)f;&t_*%8x&Pm>)-f|Hd%6 zL{QC=j1jP#2E&%|0J!?|=TH0O&H$y zcIghii}J&r20`D4J__;MJo!Q0BGG~7INDCbr+57+76Oa=avIr@BFyZsp0`~-ZvB^n z`g#(u&*lqtv~>M);7SD&CFA4aY1osbb4o$6RUzT~eBZ@uT{^zDUJp#|eWA?dtj%!h zYQi#G-R@gts@a{wof7v*7&_3m%?j5+QXq=!=*K7g+9pR$Ntf^HV_*0Z!j7=-P>u#lpz*-oT_+sUho! z(1WQM`o!@A7AYce+^Tgk-i6=A{NW5Q_((?^VWz3@HgOS6!2&!JD+R_iANdh%;2}>u;t@jZZ z*$He3KuJA*tY1V45}$=y7GUi=nkf8Io|K-rPZ*Mmf#gjVWk^-*{wUe~4{!)~K%Aq{ zhQKy+c32Y86QX`lca8cn{T8_mgX}N?N z5;dSH|NU5grfV`16DcmPnJ93Wua2*36kTjed0Mch@X6=WY;QOIYmAwTU=q7rOiqhq z-ejb_$kXgv^ipd=gRO=0p*h{^^A_(N%qeYjNfPD$yFbN#YWjkm4)5X6hF-WK%PglE zLQtVFL6*2AOfU@I%!NgQ3J04~w3?mmK7DHH``jL;#)n8Eo9?C3XYAs-_`L?e%WO2sweiH_bGpmjY54y|6ud) zMXVmuKatYO)fsP|plhNWP9=lO*?L5=mENi}bo%J>aGoG-KHfqtCzr4xFE9V@=y!LR z&@;Mz)81H0r3+46plEmtbfOWCP;-v})KcEQD-5|hq(2ESDr*na$w-CaLhK1?h5Dw+A8ylkD&KiqYa5PLNzKdAa+oRtT_ihDL%8q4 zSXOU%D8+)Ih;DGa<>*t}uDLlmX4B0R8x)SvQXea$Vcf(>X3q4WS8@ro#y)!j>+9>! zd^7)*T;8O@Vm8;Ezsj=~?7cf$5+|z)H11i`t^WP`)Pez8rLT}>Iu_T1oEXoJuu4%P zOLOWVU7MLvrDjuwtT_siHsQA47*Zmx`+jWYkTs52OX1Y@1rdD3f|HTLaFZ-Ggd}~L ztv=D%%76h3vG)3Wm4%xiVc2c)eM+3NT!Jm8`iDqfIX^!?&0&InWLsnN#MLe5E{s@{ z>>H=mX4gMvy^^0-?rwZ2tAmgP4j27E6EC-Mp-jZ!LLT26DUz%AL8oMrnZx$MJiqo> zCE?yGXE+!6tv(wfA7O_Q?fa$es3&R`XbKqu0%j+PA0nAWQHtc`NIMTMx(+Uw{<{s8 z3ar7}2czoa`)u(kvD7Jqxv;4?IFMy6?p0iW?oo)S8} z2fj}*TLS-*h9W8A8V4sZ&S7qTp16MM7}w4d<}jkuDkpbh9{B3Nj%5NZK9*(+8?!j1 z8$Wl)%9)W~F2){*Jg$3KRwZA%?s!T!rvR4d^k#kuylNsrCMO+c&D`FvY6pWy%V+In z`oA7!CT?VO=<41>`K|2Rj#f*UjP@P7DnQCX5+8Anz^ZFb92^`xHx$Z$5JqvjQ`y2~ zC*LfzZC~O=E*8RrYhlp`Q_l-49PnF$vSv=Vd@gYpV*@&5vmGw+UnvAo57Dc!v6?24 zh)7Lr8EDTJz%R;HEq(XY8#%JHqHU`2msip2v3`#a#p=56J<)$GHww+|k>=v#4fXu5 zhlF%bOwWk%S0ni(G!UU{(91S^%1-_SVhwal8Sd0&HP1e-0J;7Z5Y@rgVKArs^p}L+ zZM!21711PHLPFT?y+R_H$sPsdKcCk$UuoR(YY(SB5`o4<&3;QM4aq?TcRY3RZlW0) z#cF52u{5ws!;|YEmM_>$7LNk@MF~U?&fToH2ufv)wpVRFFJ`KrK|S8#ZmDK;UTGCx zHb0kp`a;j;et1|lIyTna)Re~PM)oORL>GMVR1}EYdDZP69P|QE0rb{a>yb#J@}eTN zw^gLYy5*T3Vr6#yM1~X96y1$wAHddWzHrzh7r7Z7z?HKQr9wZP{It(v*D~FyTNKXpC9Qu%uLsz$a)40gUuf%57 z)-T~@R-rU#^=q+W<1K1(JU(kNLU3?XF3qNY4h|xiqg;&D5^B{#p6ugx7XnO9NlD4f z#`e+suDu;j&~bs}Of**+0t!aJF?8D2$hTzfrdDFj@N+0&lY~C&5LHHg1zRDkU!!c*hx)|mkXazu4~BH;(Dv-X81K2$FI3DF)^hz@X2vi z6R=Ne(y1sZHyR5{_<=`p;AS|J;80&+Ba-T5^r(S31avZohyJx}KOt`K(kS%BOlbJy zt9q-^9pe$-Lns+>d~s?M4as(+OlOW83Q zq)xa4oWJ^lu3e+nkMD}B)YHzpaPbUxdBm|&%H6nRwdiu!Um3+c!jykMxtM06f&@{S z)%HK044~{i{@UD?^n^dsdFW;VqoyB>x0=ixTbOu)SJyV-ck7VmQd`aqCWxWIWkYfh za)|nOoOO%U^UOR&>GeH#C@Fq4XcfM@pJWLyl#^5BFMdE^lV(msld0&u#(7wYW1sN-!2rlQ4e`#mpd++dX zomOax%;Mhes6X}?Or11yIMRM`AZlW8>&SD(Rdk|-T(0_MmHy@NkdnS*eVL8O@5X|S zaJzrLDDtZeh>1wWYfwLfdtAZ8(=< znW>0EsyI{*4vr52^siqnHzswk;Ej!&2BuNH`Y5zj|TcVO>I4%$lzm1V8}{`CZ9HTSAq3 z9wf8u%?r?QtKtP0-q@E{i@jfTFiCaq_gsD*i3r_qRb;KLmNtwDX%)OX`O7s{ai*37 zSGDvfN#5shAYRbdo1x7^S&`17=;Y~Ag9s((2gddJ>Fj26N}bpEet4xc!aT9gwEQ;jqePiwdaWZo;#a_IC9`gp=$o4TGFA=$!2`j z8hrlXiAY|%xmL*460d8Fp5#^knt1uE-xXMhj{EWLFFh5Y)Ssk7Pj3s4v3sBMQj4Tv zF0AaM1osT2qaP;)fO9-N2BSBTu<|JFjPLe=&9?Li!2ZlL(Sh6-Cxmc^$#vDnz+gTq z!waCD?QS@M=f{bh%lE92f6OEbDEr)PhHbp zmKlfkwxI}ciYcpe&n|~~D3t1%)Q~l->5e%w1m@C_E~RxPs~?+kd30=Z%W5NPyHUm& zy@=?In-bvsr4oowA=|dadmX_c0S@bmm_j-A_i=RkIkfh;G zYY>ZK_|~4wpQ?oHMq9$@wYxuidtHamOgTAa^IZh+In#~8ACITd{{STqk1-xDIjW+^ zvFGgGS-BsZgePp3t)<@A1@pNDyp9-K#dIoSw9$)R2r_n4XpkM^Aq!Cn)HO$V6m_KL zxiZ=d=3@Ogd?n^mO@zGq{iBse5A@*KD10mASLkxlMlDEj0cWQNxNw%3Gn`&4CVm*K z4w{p_n^s7hb>lPq1rPTaxp?yNPlEf9dTq(Yg%o%s8S;LXn3}KfdY5B&GHqoSeM3mh zN9OJ~_T*d&g#L(vlKYVyv-~tL`T%p&NzQJU@<#NVL0zFt3w*;aqnM9j876Of?cO60 zmfY-2*+oEyK4AEcD0&UH1xj$Dnca1A#?7!xjTo*Ep3Vq7N{FS{#1Z``m|YF*C-67S z2#c6Fa=5wv@$+pQB(3NkH5^pCvKAfUkcAoAIU#2?0)inNI(iaa%Jsck_DoMQ&+|Mj zF3Q(p8}~f3PPNj7h4303ckul$4?%YmM6tuenbyeVGD7E}wJiS-?Vk35fH1YY4#krD zU&Kc>Qr=P&^eu;B{%E9!ewH&fwA)K<)f5DNHC4INL8LFH4Uy#KSKgmwlET=Yb)YNf1_$7i3+D7*1=I zTsRD6XL?pbG%HEjKM6>hMX>WqG0Rw)qJn2er^G_DE8xyMDWreC7)!-3sW6~XJzf1B z#)hVsQ3Q3)weAo3C?SjXww-6AarnE|x-;4}_uq_A(+V0?c+4iQ?Ej0YzmBTv`@YBF zOSgb@gGhtYNFyno7o=xGa zg>c^Pdb)sPKUCP8aB{s$@?lt+#e+_`>raekg$l~MUSp1!+FTC`8z5?N%l5}3G}`Ja ztJtkJ#~dOx2}4>bjCB~8_&)pe1+ae=E*T#{x_d`Acj)2@um3mBAVs@XVR+uD&=$WN zyh&Rlwc|PM+vWu=may$ef7rv+MDyb2HAn%F-+RWLXV3oL4yV90$CR~`r%(lmQ_u?( zH3mL(i53gX`t8ohP?ZuYz>H|n!l23nIpX6d6$Z>R!^S%@%aznE5n4`7h36+aVm@n9 zgri!lc1^*qsM2OK-KXKmEd3bJ&vLzEw&flM5V>wwa9*1D(zb`sa*HLKO@`j1Wojqa zAGXL;TKcR}#4n#aFWzb}cFtYO6%E1Z4YqBpsB4iC2Uai}4<&tB61b4v$a0ew+j02Y zF5tdcA5H`k^YLsC6w-N<{hLK5G5IfE!sz11tdS$Hj&!}s>v!E}{eN?^5vf7WR9!pA zgzfSD@C^OQw0~Ir_em_j3H`!Eg@vksDM53Hhvph}RQ6tvwV6Q?1sQ&IKWBswc>EfL zAjBx@EK4P21NWt!ydlSVhVt)ONFp;#7hD%NGh34n+#m zulQbOWv)seU)lrBu$m9?Z@S&2y%zq(yRVEO3`H$#6nZrRsIH*jW+ErIK0@9|)qR@! zzR*AV0X*GfY%G_m5@-r@_btXcPh zGgO;RaUeR^#jY#g_jRN&^Trd(B9#>t%TC1mJEiV))IxIZ7B%R9t|ozI&yhVGzM&qK z`Q8jf!pS%VSX-aL4n68HO=-L1!Qj*wq?p%FW@iozL`2_>x)RnNa`o#eVVgtVzk?{y zas$>|bpm=~6|Rvug?= z5V=si&an?Us2tVVMYcb{ZG&)VrYecXlL3981$=qf_5~A4K_f!{3au^fS zL>cGhjGq<55W}uAYOV>zv$Zz1`+ngF{lS)5{<-CVk?Tp8+kz{K_=}<+dE=k6M_z3S zTf5CIdY{d$04>MO7BZ$G){|`iH$VYrT2pF3{k2#VZh}N+$pHS_!Vx0IbsnDbrEZZ8 zXfSx`AM8p>L;Hnt1X4QpDgs3xk6d1qr$i7dEX;&h)abkic4^Bs%fq9HV+IHW?WzFu z2JDvJ_P}dV*7J4h2vux>?n2eOlN}rp#Kn$*fmvedm9jP|$M=OA$ z139Dmig?8T6zlc(5!xX+PXO6dTc_w`v2ADEuxzU7l_xS+e8M>lzZtDaXhVj;I$f45YhInPx*`4^NW>G$=ZeTq;*)S1uo1h(sE<8B+hEQ%wHf$)tVDpMyIhYGzB^oRa&5^>2=y=0 zD_e*KB!uDZh1zD~myg){vASb|#Vxa^olqVRbk!DqFxRBs|o^g)z@c$5EaiKk76#((#L1#D~&#bB8+S>%Om69E< zkLwhdD=}G?>8F&Q!6cgf!X4jZE>ApGFrF@Q&TpFBd98s7s1G~Fu8Q`SbluA?P(8~? zdHo8j;0Gkjcn6M_FWkPFC?>eC?+G& zwvD(muznZwPIvWPRQMhUwp*Wz`TTVXw~d)2tc?zZSQzxV4K@lBQO?EMzzQ09AcJcW zjXIt=q@aM@hnjr($ZL0uLyMp?eIXXc&=lK13F_x<*&v+yhuRW6T%D$$!q(1ocgxN2 z!?L^<)-x-#wIPLSB^`Sj;cg-r>y%N<>Y=}|PW5B{q7&tlA;v$=DQpOpt!iIrlLX|j zli@c6G-FbR6rxbjBkR$LTgwTSxO7wCfzx}_L2H2jZSc8Iwvp{27ZO>b{XZ_ife4k* z5yYmb&Kgtg1A1HaQph(6(h}X4up~H~zuQQNVd3xesxyQp0`kOnoiK%jaP>I}(qY|B zmWaEfGhIv28&c|tfPQ3zf7^jnP4+d9{S#spXEQ$Q%gEC@-siWz zK;SG>|||?@cUB>om~uS%s(|F!TV<9m$jp(xd^PV@n>pTV@iItiQ$Byii%i5 zkqt!Kckf$&Av9FL%k5uy3i$KQ9Mud!aKJca}@pVE+$MQ0d;J7qv zt7(Lr&W5Kt4z)7De3PS)n#Rj)WgT|kz|Q(Ph-RnF<4cr@O|_L@{s|;h%d1jV_y9JMp=Byq9%%Z*piZE=B`@BIP7Oc+e-L6=^Qd zTi+KR0TDQ_l{-BdHaUYuIjWF%sKo_Hiee()u8S>4$+!_NvkeV)SQrK3 z=hL(vpiDW*DYk_#2tAlv<_$3-ELkv z7295~ojcTbP;l9DwP3bH|4O#FY#nU9XS{fSpYHnD!g+MpaZqJCyn5?%A@YMF!I@ zeuCkc^dsKbHW(t%hnI#r`?PF5`c1u5YuXl5j~TIIYD)%1S%?{*TvR;`KI`*5HQ^}p zz00Uc{Q0#IJ0WE?9ZO zoKOL1V@$-IP5U{wp3n&hQ&p?l&6~YA%GbcpU-y!3(9@;D--huQ6fFHB%&9F@ z049@m(09sDEusUQv%SPO5J!N6RZP0he;=i~D=jULCW{AQH8(Re(327+@Q0!|0%Hxy8`?EEkOltj5fErzGX>GNT70ZM7KK#rHER3j^f15v_U z-e0@Bb2*HM$*{)Gv=78pDJ*uIjCwJm+9>0v-;cR-#)LBp?jHV)LW7661d0J{Yr;8S$R_e5)%43Ue8v*^_*Suc^r;*mJ&VK|BKm;TBbovQ6zhXB5!GV> z3O3(1Cm@{xux;>!J;0|D+~x$nmwmyxLkwSV?$I+$f+C2w>Gv3jfC;!mMK#yxgZpIx z;mLrQAi6!B#w~JFnSa)-ia()qvJdl@MI}gW%!^~>jemh zaeRI~$iKs+N@DD&||NcpaMMi!cO~qu=@$e7;ST_nvO035Y!0Ir)u8zI-#~9$ZcE`{F#3CDt zo4Z$lqmGIzwW z=uxWgC$V&K^-Vb5*PAI4q;U>Ggn@FIiG{^fv&D}e3AT^&q&L(X5QQ&I!}BFoC+>Y3 zrBzph{14293gdbiE76m=qLsw{?u~_L-YP zXlpN7gVO4V%?oyYb#Q0rT6mk3wUJAk~@@CRn-C%TCDzd{tE?0^37u;sTr@@>fgS_Po^_zL$OAQH{EeUW0y8!sSvHcoTrJem&` zamQ$o7pdPDKqX=XrTe=9e6}Ta-YWAbMLIesxL(bTzy0*lntv5%L*AS+nG@vz(Pi0U zo>DM+wOqUvep4H2Ui9K2o>O?yP~w~zj(m)lV-#|+7Y z$(-!$t)^9`acrNcGGplBJgHuapRbpRz~SNHC%YYtxw*Oa50)k-tpI(diU1N#7+g)x zL6VeUeHU%NWn2Xi0eQ(x=F&zC@&POS6^FN)*0Cc*foNW5RcVHEk8$GbKi+i|&GoYN zb>7PJ&>zNqN?*4?CwJDJC+1(Ix~OSkWE3;%iVV4+HSc0y)#hfvT9s9W}#Fp@QjO!ySu5vybqZ z$I8j(&RK)1vMMiJojS#P7nW7cjWTdS56%~zPfdRY@sg`6E7NmwsKQ+(M58@kNfVuB zrA-0J$;p1h|07OZC4Bs17?k+QT_~E-7A!?wfou=3gRFSW+9A?`_JHA7D-ePM6(~xX zEN6}e<^{t}-Wd=vCFgcdOivFJC6{Y|#KbfPUbP`=Tt6J>*L%8*b5YUCaw~Y?u}06{ znv2tKXHl2b)e*F=Y4i<=rC8FdO%EncBZ2sV2?`wE1IBE%uo9H591v zwNASKBwNA8j!;$0NXKTRMrc2@yET|p)eo>fJx)V))0>(|02}vXf%jeJKsz!(t3X}7 zz6ZXr1myqohO?!>M}PvBKG^N&e#55%KAqh4(Lx2sd!EYkQ`HQflu3Z2H(%86PYT74 zSs_o^HQ&vp4$l8w?5eBtY$JTlrAD-@G7zs#mkCY*9BCO)xioq6vh4r6Sbu4R_fcMWc61LA7y)?Akxm-7)MjrW0(=0M zN90=j_l*1SWOv+J))3F+Gim;zi}LBckZ7eAzOK9dQ!M)HQ?R!j&e!CYmY+0>ZtoaZ6`>W1A*8}jWBG9BaVZBd!Z=92 z^ti|%=?@do3m9Wyb_D=~4FB&^7b+H?teOALvG<^)?G71JlNK;cxpnRwvvDYiZTiiZ zDu>vFf{-E{iJ?ZG_=QNcbWa4ZCT`vF5AKtVg2>i{Te+Fa^62R1EfV2bP7D=x}W73ymeH;fD zR|S9GkP@)S7y4<2A5LyJ*b ziW!=T?=@RatAVj|M*xLPmb3aaT>E?fQgt=wOMx2cf99P*4tU7#>Th^&dwNa_OWoik z91mJY8;-k259h5f_>bE>AOEGb3JM6A-8*SMzxc?U5FR4%>f9Ue^mgDRSz`?T+Xa_SP;-ppA^h}#%GL$nOslwUqd)zRc~ zp3?6bMwLf5b$41>ioHhV$75dOl((2v7XP3pyp|*Nz8fQPBen=4{&R%0Y+mwiYgIZ# zd$q5XA!A;{fws#}oHoNLA}Qm+^M?)#7B#?3L}F*lCVyMcYe&Qzx4EmA&6<$g)Wlyj zCxZqqFCd&8pY#X#f|u7zNeaIbBLH3y$BAtc@hAOR5IOeE;d%3$qyq#HZC8%<;&yNE zN>M+q={Um$qIK0-3}H@ub?DEyGsH{vPHN!~T>i7e zNyVp!L_9W2E;@XZXKI1_mWZ~+`G{k|Tef7f)D}mkT8b){e&TDPe3aO7x0+>6&1rbDBc%Gk&9p6+^*q`H%`C27ZhbpN62c(oh4`G1u+4!AHa|TR1re7 zU+kwQTE}M#{0mVOTXZ9PqNVpRsreTzNu%UzmLaNIiot>SXNgN5U1FA(0uc;FQ<3GI9>1DwH#{eIp z5#P9$Ym&whZh|?Z3%=C*d(Td3{*309zLg&jHz)Ge7NXrV4IkG7J@2Xbo{X1U1)na! zPTlIWuS~wxc8H`Q!Pw2G=pzeS!CRz(28Xt>3BR&fT$#r6H@R*Cx#9f7PA`E2CL{glOet^;c&1%IBjoDzX>BdVHHASnOj zbV9xjoH{1&e5#izkuOb-B1rj>(}wZRX{xs7hYsdKNCI?MwT7`ldSmWyN@pGQZ0j)l zHe?$okJ|EK$(_(>QXfzn{TfdH1$yAQPTQ}XILfUg>PcYAt@>A}VZbu)dXPLnJ$$r& za3gz9i|^PHuwA;5G2?_O@!aCs)#)k_F8HwE*%RA{BtswiZ1)<@Fv(Z6D~Lf27;XGq z3M2M~s>=-WspskC=03T;79k}ueB~ypi=_nS_r+p>i-p6fQ>U7D-^5&0C;)yB)Jh%M zP8|;Ir3yT&Nrn97w}QPe<2UrojzRVDd&=NUTLr)e87&oroXZ6VDVZ&$)|qlZ-gjLg zSS%f$O&RRJK`Ko>_9yeWNPWfu`r>!|KwchLo(xI5U|;jSHgBuvpvo^<4mWQqU2$t6 zC>gB6cdHgY(169WC{v(C8ggZSghnQj;?riSfZq<30b(nn2)DhS`pb za(fCM^IO56_6A{a&@X2m+h0T0biM*X1Y~tYe0O!&5l)lV zS=A9}{gg%4H9=%4L`UzFQ}%lj@K2)AG5@)}Y=0&okX{#=0McKuY6CwzWmP@l(B59y zkLAKKHCgch59kN0B;<7LxIt&v$UL^{9(5niW}wJ7P?L74MOK1@o#ddW#kKjvDE%+D3+_<2mYf+?h^`XGliOGt~qI4j5Mp#J48_l`qk+j+U z!WlpjFLr5`TbHC@L?zHnr<=kZb$CN<`wsI9>{hE~x2>P5&YkYXNh}I`;mFBb$}ykU zQI^}IBA3E{d*1S-^0PrV4~o4!zssFNV~yYyKJ{@O0wonyFAi*cXsCX*hCU%#;9nPx z?!-hZUJ@Mxed@|E#n&%rivWs+alz+B*AH2nWFBD|hnflrM4M%1N8R^fA6EqBno&x1g-0Ao zNVK^yU_l~C7Ihr~Q?buz!?BtQMvOjY%2XQ9w}GE3eqd?cLT{`B6MtzwtaN8XRfmM< ze@JN$`iL?9^m3#}`!di)(2UqD+;=E$2nnqeu~#{hM$I@o%-O%$O@CN;GWHBuSo`)$ zy^X#Ex`viDU)M~$>Zrnsk;fC$(9J&QGac2T;3?HJA`+t;N=L`Wo%B15+7Mm zb~@^^zwt@lylVwXd|8b*l zuH#Z$HBG8l!C$MX*I;Iro>g=*kUfEVihd$<_XHaha^Ntr?0Q^uo4=b`Dhw78)XTL| zDuMXUtKj2icF#4dRmF2QSL-9Z$W^szuD#!^{T+GJ>nO+iAlij-J@CZUV5jjJ<5#WS;a;WZk~py~Av*z(;_fgc%sP`XMnX zi2@P&yL!ZabtbK_B6ekErQYM+CCKX~arwq&pacNi)ja@MlX;L^DsbtUdXU%0#fJokTQ${1bPxc9bhzDM zg1p8FkUb2Fg#bmu_mj32pLw_^_D1DpKnJ8pL%Se)W&nTui8Oy*oX(?B<;qr z^{9-*4;?m)zuugZ>caSf$DRiWi@hS~83eU}Qb>=-<9l;MugMGTgSDfPO<`Qx>))T2 zd|+{5qu}6PehsjCLmC_T8gJG@e`VinGfV#Qd(pSyhEl<~iUY^G((WCDA^0b2b@qQKalFCxFw2X;>H=i(C8_jAp^g^7quvzAaG*w6}ZE*~>@q z6GBjL4B>jw{BUS<*Y!JM9_{x11BkEqxrGXNm-xl-ungO!!r==>Gn`)f^Q}enD)Uwp zT1QoL(@o!;ym*MWAC&oXguO=^YRmDA?KwgqDTst6ZA^HrDJ{4qs|rqg$fz&5nSSL{ zys@vzYQY^8K)Tg%`7eJq5u;~98?;rLKY2+eid6vN0Dz{zdxfDXN&uos65=qzOw}EM znXOg8rIDpxkbDB~I1@H&Q1XcGrWjAxxOFE21??kzPl94jvA-V}U&bCPH z0J9nTH|Y=VWU~8DUB0Vyn2JXKj|QW%-I!f$Fv_^z5 zfxNi*E(s{@Ai%tu5{SF&+HHOhR^g^%{;8~~$;!-x2C!1# z)c^y-=iDajMr*Jv`rA*i;}^T9H&aM*CBaqt^Ii7OFV@DF#j>u&o5kb$fx6 zfK4GvRuEUy4EoY#%BR@Gl!(-uq8aFR;)8+={hJ(%$ED&G>K|ed#?sLB40EniKnirQk zaDNJuraL_0E82!2VG78gAaar?wgopknc7RU2&Z=RD2&Sv1p1fdo2AIoyord2$Sf&& z6OwrXNJaR%+<@Ec=7|G@TVsSv0}|DyamuZU_B!Lw;rQ4XD=Ey%EpOd{mH=kSz4^Qo27GK*UEEKz{o*_ zQo#Ni1$rCB8!Bm#7c-#K(M~k<8GjGxIC4InIpt|R#TiW8Au3if{qxO3aFA+Z*c%0? z6Eyyp$N+nNpXuf7g!nhdSmq9h3_9#utcN;3F^sJ5c^wW!B*+#c2SiOYt2GRNVo=D! z3@8B-d6Xnyh+x2OW}55Xsne@ViY5@AIi@ebc#IR|2~`?6BT7p>{d&M zE(#&fya9w6Yy!aEfY-I``rkImQ7V+1RBe{avz07VNRi8{ChPwUnZN0NA3;A6&FAL- zRj`=&*Z<^u+GtexWjqz zpTuLrRwjU;ZMkT?(~oQ{a~Tx1k{0hZ%;g)1Acd>gVj#xE#+A}{XD#KjWR zy8r2^m;%@r8m4!%c|c0XIHT3){`G?ru*DO_e^9>wN7d_cdAsdzO8Juy|f6kJ|juAT?Eeuf!>8?OuH=|hzB zu*M1r4K+^bJG$i@`rsg#^TzGD1BdoQb(?A>^8S9(>C7tLD1Wn`Wf&cn71_Pnf#r-> zUx<_ncriHAV^`N&-!9etSLymB*%QcIZ8C@#(Q^9Z>D=W%SV!^h&29AcPHk5!R}a2J zHf$M(2j1qJz~$SPgGEOt8huehBbFMtrjJ z))b1(_ey_dM;&K0QeBD@$%T3)#VsfsCwg;q1!PS*Ys-aWfVB6PJ(_e z4fWAlyFZH7jU}CLliB%DeT7!7l{Z!kTBgQP45^e>tnQtGe8sgn zBp=|X)rY$_m2q4u-_``YX2GFLGvgTnPecI(nsMWHOIRFfYC{h$|NN%3)4qL#d=>+? z?RHCBmJ=c#-RGdVT#F5Hi`lsDq=S1Sx}J9f6{4XOq3;i&HPyt%DwJh^(hb;V*!fP+ z+BlIm^_zvTG*CX9qw1@D$}Sc!)__tuv;J&5-NTk77<#UWdf(K)jc0FRZ6RFq##O!I zeo7=^Q~72Xm?Z_EPR7f_gqALD&a{tOAKv@@QZ~b%ZcWQub_tlPzi)Bq)p+SEil}I% zR;tsqo#RGU^^~_IRUT&PFk2x{ajewxE7jkWRFp|h45?SA$q5rwDDCJovZdZg-5o-e z=1rgD>W{HD`px_f7?nYk12s8^smWk=ki1B%+#Qk~Rp|7Lg7&!V9FdsAA%twK=GjU= zC`8S{H=Ng>X);3o+kL;9eqxcd{EP5_0Eff-)K&Ge#{eZE9wocM`b z|5@}D?ZVx*tw4)HutR;;L)j_fsRxPkZB>TdNrfzWH58|dM6y=@+S=T2MKTDiV{+e_ zZ;Dex9Sot!`ySha24W;{+glSyL!Gn<|1%93JkPYYhm{B!mtr)-D!SymA3TLp=!P2C z*d8fYTyjnOSoQi;L=o8vW-FRu`)XJ;9DcIP9ufsCX87|NtehZ+L8sdk>w~=;98c8U z*4{)(;;%Op5-_RVk2}b!r03Z`>duQA@coXmxIV4V{%Sks_eVA{7(ShD+$?&!N3EyP z(LXDc$4s9F6)em>v!TS5Yzq1D4yF?H{cR4XO*&*!C?PX)Rnc5R{VNU*e|hZY+R@iyR&J$F5_j%AT>?8=+v{;qI>U+ubyb1H!9sGdoZ0 zQuAHgx|SOb-wAc)g0>b$3N9v|d(!rwjINuNMPtkdrPsyBvJj}6+2TId9~wCnH9 zC@$X%Hl0(diWr@0Rb322<>&v)`^sVPrf_iEv0Hj#T$8kp#f0S8lT0!zAoxJL!Jkda z-UZb)952yTNs42>6!ORI8~5>($>0k5ow7*W(?Y^|`!0()VmLAR>KShA&|?G|&Dcqa z2B~W?e2+sZYt<2*k>P+j*1YmV^!&DD7KXbG+WB_Lw`*CNJ%_!H{*QJ!kSHdOq#C2= zfT&Kp>()Bve_hv-qN1=B#>3RCtgJl-B_$;?$)7N}xVTV;f!5rL_}3rEP5g^1h^j%R z&^?|yt%+X$iVjJ<($^5g z<7~MStoEa)&2Uve*-9Fiw`W^^f;d0zE%O!12XEiBt2ueZ2=`c5#B;XBi74N(*_zRc zgQ>VL5DRmMjkNc$8d(puQ?KU+%}NKh6&g1Wgp>D2AcokQkveVh`^_Czv}QeBhMqQz z3qhuc`pb|Uw-zfbns3-DA{h6o7VvT9UkMEA8ZB@|Xi6o_S^R3mr&c-}ly4t1p{Vv4 zpAV~Yz#a6vZPj5()mkJP;JV(HJd1BC%E5fsM9T0jJpz%&_}5#?m3t%jo=rrTyw@4W zY~iQn@XR(l^En5$d!4;C@M~p;?<#5*I`ip8j}it^3~JWL?#%__AJ`p|#81xR5P}p3 zbQ^@-MkM7X3&Lu^;;kPq5E*pIx|5|Ro%J6OH73tHjP`{&)1;(4<<=xQKhA{v$~zZf zm6Vw+a=#l_sXV&enXLH;G|$Sk-lcr7o{NzZ;QY1k3c)Dbr_>>Cz`EYfJ#Depwhl$3 zV0rZQN_0ukU2^gUC+5YU%_5){+Qmy^d92#(f;6fi5jwh24nWJe8R^x&5~hWV-S(i} z3Vh{#Y)kpunDYX9Q&U*uDL5NSigkCcZX4&0G_8L-mx-qt!c{hT4h_lYN&DL@fV34) zW_w@Al_xx*ZR3bX72PEqXIrWKNDa)=sb#bnz|cwOnA%{r=$tvG5mvK!wp03LhbOA8qGzP$E z;=sMOuD+gCza3UfTN}l$uDDyLB(PU z)Uo?e7}SRc4i}yz3&Qc~**eRUyX#SQB2Mq8Drsxh$n$2`OP<&MmZC#S&DZT&@!pA= z1j}nj>$`=yai6c0A6YBpq1fAEr5_X7j{P+juv^+|idf;~DfS=W_WQmrG{3)32Zm(` zo?Fr_0-;D`fE%xv>A~LFcTbw9n|tOm`s`$s?;=w2b5mn^#+W?(9fj+udG<{j>_^;w zZN(AgF7g-wGrkY?wEo)?7g^Rq&h+eiVrjVzxA$LQqxXkscpXn>*_v0=N&bXhIT}B>es(65l$rpR1uBY?^vb2QU52HXZxczr>tv< zK-l0d^G4Y*(7k-D%@rMCh*}SocW9~BJM1S;ueYrvzGcccO9kn~slUU$wTvCT1Z)Hg z1$44Jj(O6p>O=mW8SlF=gSkFj%}N=X99Um@oy>%-aIEldm@j!`@XHcSF`0Ed;(_0!=Jj~Md^|x4+fhlIL#t;tT~mk_ z>z~E4@bJleOJ+~hHHhR|VM|?jXW;DmP*G{26lG&bG?JtCcHbeDg5V2JQ|RTKfL&4X z@E>)EeW7p#E|bX`UPp7WOLwE-9~!N*PngOUe+_PJeoDxGyNE(7&@Lr;ysK=ZTVLH+ zZ#f@KSPCOuNThFmnmC+|`(XV1T{jH<((GQbz7oAEi6bi@knK|U_E$|RFj?&*%>oQ$ z)pbp9NCJ0FbO3@nnfNtvneP*Se-f5%y7}WA`z}XVMseiHen~$*iib+{e$OoF8SJ5k zT33Uc>|CX#&`%$JkLC#6at9{QR2A@N#Xpi?l>S~9^hEjIDG5?8s;sYsNNB;9(V-8E z=>pz@S|50;Xf?s!h)Xb4bT0T9acYUj*asoj)Ugj35igEeVhW^pTjJtxaB?Ry#)54QXj_cs28hl;$_hVQ3SzvJ0sR^yn!&rc6%ANA< zuT1Toz(54j)R{ddFkCw^E3cD1;x=%^`7N{+Kb(K;#u8FL~Rkd-Y&^;v>iLuR0gcV^>O;{Gyqkdvt zS>H>BjqX*~f|}6;O5XgMZsx%GF)wIfX(x`R78o9r<8M5S-Y?Khb%QdoF z#OmT@S~jH~_2*AW8@|+uV*Z*YZef^tasQoS%($PQ@nAa#zLH|q9Iv}5REnCqmQ=!1 zah_by68_ZDiru$&d5$F=cL~)Kv?(4Bj0RF@MvsBVnCyDg9YnmFzuh63gdK?7(31>K zIdP|Kh7S4k5YzX2cT^U{DUuQ&@wBwGtWFPl2Y!8d`{(GVS)XYze?uyFNByY50I}-P zCyAdL#KCmC>-|o772hM{hsm6WEG=q&mJ+#Y@l|ReMYjDiXqk=3SR#n*Zon;Wx~{N2 zHna##p|RRVf=r{ddMEevUY>uS_ESWmUOl_-XEzrNLZ424-xqBS8U1D`L&;RrT#vpp zI5`;us0);Hq;R?;$~O7>FW|0UCQipcSVZgC(cE zyzaL4`gN zr-}h$i$(S~b>kuuty8<5wg<|Z;E<5M+7x5Ov@`!comn&-BIlOb8%N}8@}1(e4z#noMiXjVpss+ zp!Q&en<`XUFidFQ&pa%XK4?z2NgE)0B#`+IG{=8Z$@($RUVX^_*+-pwaiSk##-)yP z(9HS!)erFGL7RZWz&6!AXRg7TS5jJgc+kwiVK_@o-Dl^8gNh^N;~n_2)A#i1kp|7- z=EZL=s_&w-B_jWt`H~D*7RRc4e0l^IJ_W(x^Jp9 zioSH{A=A>Ex~PVB-BvKS+-iw}WlI%<-(4gMQ=uDI&R!KxnwGT(vDl&_JL-I=O02G2 z9l2I^a=wuuE_kA-NGpt{N-r{kSAMZsIK+_4wGPI-@2%VLqmwzU@^%sDo8Ze z73X!9mcgh65bcH$ag_+QDc9vQ`C$N)&sv6+KRk8^rggIHEqYH>a_qP4t%SrG$m5bm zHdhSwXd6kUotcyuSKOvuFD50uhO}SQ#?-2<@0?79*%LNhy%{%M zj|0lUr*R&1Cb*^+ZOV(WIowBV=t6OR2QOxdf|LX<)Xz`q>{95;&bcS(1(#6t~_3NZs{FD$Dsu1ZwIV>Ysj$78Gtzm~_+`VZMKFXyo>db7{b{kRH(C*-{@03!?Ah9H<*!vq%2NCExFFTf zR{VOnuZHmdm|IMY*MpJ_-gAj$Nrr?|NtXQ$r<+&Ymo98J=dSw+H}CW9OHkcFEDl5M zL;;?>li9!)4sjnib0LAjk8rRjkqK)&m*+6GOn*><>^y0Gyt1IEfvr1iI^O2i(P)rQ zwnkrmH3g%uSTjSklZde;4iW;n%s7pjoT)P9a4qe|AaV$4d7hIN7FSTv-ImlDVKVr) zhvi2@^d%f=>*Uld`+M4OG=6(W3hlm8;9Jj>4$T_dcL`yj90ZTlX>NzLx4%cHXRg=Z zc_4APce9&R>9ON8)7A}IT5yry@&&%pre+mLOh4>bZ+=F)tGW_NGH+2m5}1(T?JgT% z?ertv-tOw>PAapc+7o=zS|9EwWBfiDQrCF?jjd7ow}Ax^J`!|XmG4bIYK7P2%EZ7= zT*<#@<%AOhOEy_2RM<1D6*M{G#U1y^0=?~57o(1MCdi*|c3|Y}4&+e+nM+{dFtM>k zM`ASJ*RtnITr)5}T2O9hDKWp7usLl}_9L_@@rL6*j;a!Wv2|-p^=g2vGriU6Z9<3C zH5{%NpiOOQHgmO*=A%PP=eRPlq_wOe3TcitI@|secuAkWLPdS%_{4D}M|KD%cB#yT zgx?wj6F=+Y%hIdmJy!PHJvrbGtNevGCzxxl3i@4-gIcs7Deu1(cB?Nqy{0lT6Z-S{ z6rnmLluiLur6vjx-fOhZ;AoJ7TW<{P_;xW?d#1>b#Ri#{Eb)l}mYu(--noef#whq@$IK7dkuFjRQI94hkydYjqB>AY? zQ~D44sX1o)r^f2|xqIwI=tcz%!@Bw{U9+6i@2>IGPTu*aVz>Pf`YVue``I3WMhL__ zt?jlKlh3s}^IODIIvw%-rNL9JThMS?q5NiFOo3J%f$~$c*pX{h#+?_po2n~U7NKgc zOWf`O&_m^;fg53zY3TNt~&KRl;+1;)Vp1?tut++Vnsc80+&UwQO=We(I-Xa+ytY=p};2h zM~3x`55Jah?6|MYHkbXU0}I{8tEeyU-P(%9A9ubbvB37wvlrDQuw3@7DpoTdZ8D6z zt)Nb&ew>L!1C1%+tX+A^9M^*jRI+GVVw3(6k?@cF>5f@{UYpJ4F$^ud{riHbA$Fs9 zRycLw41FM#>aVxYSEgCNnsAGFACs}T(G~WgDjBNE?c~b5FF)tLme5QejgW=wqXsZLfaDM zz_87=(Ja7`(vL{xiCY+JT;Hl_)%(O1=1TO3<>8%uf9`LrGQcgiL&|rNkkX`$v6P9R z(ivUPuj#IYB~n&WF#p+Gh_*LXthqZ^#SrpGcZI(H3(NcN-#-t%-08+gv3)!Vgll9M zXKGJ=Xknp6JB%1;?~sAj=Nzq-zXV50R8{fC#r9xJLp!K%aSa=1Q(?rJ`ub{H%;#CT z=?HE)4;ktlx5sD=UC#v9)LL;TM-!*KU(wtNvO4GBKlX8TB|x@FhsHbFS_8MWD>NCLz_syXkMX9=IGlTyALl zyW`KSmWOv>NHsM}JyF<@^L>+@5L5a%CsCv!4dk+r5ylOY^##(kD%4D}P`Cw93Y15lrDA zgr&t4%NR!K?TFaLP+PWs((I~StvZ`)SH%CpI4hN&&rd=w>9&&)a98ux5XCeos%XJ#2D$)-y?unh&b))%+c(kS7Zq&cP7oi#XH$9c?9tkh;=Y{c(1B z*IuVIng9PI>o23?Y=W*)n1tXEg1fuB4@?pyI0ScsyStO%I>9YS65QQkaEHO&-QD#Y zazD@c-gDkRtYNLW=IXAlt}fYKdrDDUJR&NyI#l5XmGArTt(;hbZ;e^5nf4!dg zqMdyc;9a}jD6_lt3~zdt0(a^qtmL}$yw9AZz>1bRb-lbZ0;5?~PGVn{PXb0pC}wQ9 zd9NFqL2A1sRU>})kGb~8eYCv4^xA|KJK&N(6nUy9^6w9fzH&N*~o7Vmi|#;n+(o1TI?bC1;^@4faf zPghVk*THLaVBFG%7}?ua`FzJTQCRYV<~963%VIZy76IV*H^yHk#p+BL7^uc!{nedq zZ}Y^lWym1w$1*5cw~QKacq^bwRUpokx;T~+V1`oeLLF1OQnm(~NJkKDeWSwj4F9Fp zhARKDh#7yB)k;89NMG=hHA;KT7eD^yEMn_NhO`Al;?j2Wdz7c!_le%9=^_+mAgHI* z`Am;|GTx?V6=~RUCF|#>4zE0HRnOLbZDAImC93=%A3GwQlJM(0M~gc`Cp#8{{=U-4 zMg!3;c$U5M0rcjX5m-5lot}a*$?d6&t}RwSz$tr7#5~l>@S|(NTp5u6H%$XgNl8i5 z@{!)&JPny+5nD~)?KdC)%NQOvg7Q4t*y;|I>2=6drWAq}-CXoFbOlp)hzXdcMeAzJ zd)d+VWv-zFu7JjKG#^Xi1J2WyMqIM0^Mirxn{Y2lnolxwYJWY-RG+oOQ3;6#;&19# z{<@oEFZiJdq7$OIr%Avrvj(S|m~1IVpLe&aLr>CwyWw-F5EQJJMo?@u_D4Ks@K(e& z#dq5W5a43sfAP_i48kPHN8SQ5vwad_;ed!Nl?(&d3y`L<^T8GlHy?wb%P!8ak+v-A z%C6W<(7ZhajKhQyjfT4a)gSy{EWj6ar0r;2^#0HfpRp6Y&0bxAzB{$Ges84LF>H=B zN7{X@R2+u&`~LlVH%~J{#`QTyy#Ia58)Zqz$0d)X2d1#|7TUs0tzsWV8R@TF?sAo8 znNZS2cW2?zH!65|c-Z2f{*GnQ3#6JtNkZRimEekhwRdo6_-6}3e*Ch-$tdReH&+i7 zRMhO(tv?2h%{fnR$hp`=tr#LWOD4V*<2LK9KBbt+9yin?Je~_Y+cKg026vz}CS#ka z6?wqhIm8@7nYi7(0nm5S(a}L^ZA5DRU-_N3QRU_3Z@lQC8m;*A zqNL-0JQhkjXhwjgmRTjPmqEisFL?SFLqsLCICiF`%e1_jzh3kW$6D3;fvNCEJTI#? zk}=jlucdbomgHlJN&zMwtIld)43(I;_|nN5)bD=F%F4(7Dd#~L8#*TXf8zYF zQWOKcV4iHcs=osAaG)O_O{#YTX`#&X>?YWCH zndJ90f5Hv_86v%$P%LlDrqxi+a%}9@bgZMs$q8YW{HL(d)i+)+|0&zQU^Vm$h#}OH zaYGv)Wc4y}=s1|lEC~%UKJ9iGC*z7aAbiCE=FDE3SUe-gwOdjC8`o_NOyU3N>+4Va znZ;4hUEaViAGgs=y{ltD+|9&|@yM(&Z1KK{(f-g#zU2@h)Tf1CXgBt@QY{I2Wrdq9 z)`taT${U4V#jY%vx|ToYT(xcSvbHY6)iWZyZBGnUrK zvGuGLZ|Yv3AT*J*xPN*8kb+VDH<|zbe5D*3yv29P3$p3S^zfVbrkgSZ zej2wmd$vKP*B~#?-Z}kr9FVGwwD}|UKYjYYekVXa2{DfRzJ6&py;0bOCf2Pd*GYDtdpZ--&? zJv!et?8-X zhJ8>X8GVt}DAe4ZypOi1=-*tOG$Is&KnjWEmr#P06HjKS8j;FR!{|0TH>_;DzAS=C zy>#{D#19+-l?ABTW}$YhR98p^%E&gshMn?U>&zvr7ayVYPyIk?xGY-bmQ#g*Iu3N5 zuwRc8l;^0ZxY;iSwA3%F`MhEgKa{dK7+R6l+TF-bhf3*bysNn2GM^?WXEob)l5bXr zPcEQJv_3{n;~n%*9m~nfRtpLX>80CQY5$osz%g=~xFxcV@W@==&zdB&@>1F8UX*dz zE4|^h0JV-8r8^_1yW#YLo4u(bb+QM@Z|EA7{(sisE8J0l<+D5Vun3FZGcZ{moQQqA z&wOhhZ~>j`hT`IrF7f)3;7zrFF5+|rPHtN?wQ%~D)SNisZ|LVVfr zKm7;~@*rm{Be(Q@Gu}RKMyye*Zk>H z_q{|zMN9z%*n6SO=h%{8_C;>>v<@=zhKwsj`1l&ky?9VlZ{NuGMn#k#A*od&M0$%} zKZo$mb1S#U9*V1uOaomABu%=*4+Wp=P&F}qz%xcgPI#nw1P95SJ?bbX7jB{LZVNVl zPc_r+rC}t>iH_g#5U>Wlp@s1oFh6PT3b77MN>U%up31vhdt3^x#x5-(kt1PaYX%52 z9PEeLb&AMpVfI~lW%!z{Ui-=5Ptf|Gi>T)7H4twViu8A>(uECk?V7C)DcG@l4|!jw z`Hsfoc6Qr<%a1-|i=%yK_^qvZIfaz5I}r_|yOx=W=@7(47j1v8Wz7LciYBH%-@&%P ziWzqjA+x?aK7%iG!Y=}O|3|qBIlf`=MS-^`sC**{%?JA3CD49aG~u?7pL;AijP)fTdexur+r&lEJQiJK4U z?KFYzU9+nT4ulum!$!xG&nja9+6x@eQZVU-2;nE6y2uk1BgzT~hRtUjV`>K0@72Wm z@$%e67Yrz1-!!wu_ou^5OS?cTy1FWxJnCKyZDxIYMhhed>g79Rx})>5$denwmCUk% zEP<7($0qc>lZH$WQ3Ot#iIQJsQgRef^YWKa=JflDM)mRAu{kPJLNr2@-o`2rH>M%W za7b9k6bbOc%aZTD`m9~BccQ9PRKUXi;1uYpFEDJ^X{E#nV!6osiHY|`y7cQOlmigv zNQ0@Tk}&vRe2+f>3m0$hD9Vi zpZUO7+gQikUmG88PTos)790YY{celc$jm^ag_QT zj23Dd7mm!D2m=%lNoS>j@8CjNxw`Cnn`KyGesAboY9vn z+fIBQOYF`}tEjs7)>gvZgH&HQEH}xu5~J34!=(V4!$fQf`h=~gNNKEeS#PCJAUa}LQ z%+h&=dqSC1nFZK^QR@?uR=Yn8IwR;dAPqS?{nr;dGCRxGmUImqrRTI^tmS8CeecA{ zNQY`aFH-%eJ+Uaqj9Xr!_HZtwd`rp@zq`n(PuGB_IX7_ePzV-y{VU~7kj#00cr=ym9C{Q;*c;y1Mk-YQ&d5s~a_ROa@w8z;frnegVE4x% zxN=BXRfWnz?#jW>!C^w1yI3oL^+MiIu|oq`%SlQ~YFd}-?M!~6qGYs*(dt)&mH-ew zvk?e{Ls%b1NEy7x8rkmmNxn4$bUhA@-cJ$KF@#nT?QoW=!+H-2Zft$c!~>&JPr~58 zKX;Hr2Uxa3mW?@Q3_yi;ro~R%6O};>HV<4oT9jv25{fHK{-1y$n;7+wc}k}u1~zNlc6@20~-4jC)Xep7Cat4C4<*l*NUL%r;pQY zN3Izlng7|B@QPkn`{GdS8M3#ZJR?%x&AFL5<*{(%L}jsR&(kzN|LzzJJ{A(!V7yWS zbw@`md*L2LeS95J>zS4cH*oCRsX3IIK14!_^6-&Q7XN~%r?wM+s)P~As^@IzRKLRG z8VlF=30b5mm;G@fU95oMq4}2NWcUvKhBRPLnJE>mYQ^Y^f$F-|#zG&GC}wT3XvbUz z){pm0ShlJPSn>QeNabbJj;98I+5f{b+HKt@%nfhgh^n3jGF7kV-p^H*xBbY zSbm%97H;}{id5X3^;i0DqQ+8l*Rt{q2W|QW7+i*d>+LU0C;By()zP>YEmDq9Y3gi^ zIf5dver3G=aWL(YwAEi*Ze{cD3tE>K1oa;M_GdbDhkui-msq`F;@<)$yY*hR9j|CM zpZ7S9Xi1Vx@=xX|gDm;Qi49f?*s-^8{p1dM+d%S)cM0gX-^6TKz3(w0tu4_+dM@V2 zaUD@4Aq~mKn>}Ys#9-GrChhl*B2#@e6A$(H8=nUSpEb-PjUJLFZW(ep*ibD)p7yq6 zpIqtcqSOT{xI)G1Or1SC@RW0O(imBGl_tVMu@Lx4a{Udd&$gvRJZ*@D(!JQPr+6oQ z{*a(8z0vjYME6Ulh-%^FLN}5xHnKCEDDG8K#Z+K6o#nEtl=g@%(3i^#IYy@y;R?L_ zf>~)wNBEh)iV3q<>y5ifajNCDOTHIVBVg+757%?Znl?RsAnEcz?WmIT@hqa*l%$~s zu|+sCGy%cm6*Qyom;SZIQq&utVXJAZZ6#cXfp3og$fL*GEr_seXf-{2K^HiQe93hW<*R zQh^iI!4H$*Bvodo4vhJxs5oVQ?adK5HW&$bS#srt97kz;BX2dK<$0NSafi=&$IW{bH6sM4rq`yY0KFQ4*nP-IW$Lic&4sB5&^GK<_CEiIkK z*`yvgERT^*-KuxuA6TcOTKev+&Td8S7z3Ukf<6317m{etuCX*Do-B0sCt8cJ^q*Vf z{_-Kj+Mn8ewjttZEdZ+h8a~&edaKTP0<_YSJ(6ph&sbf|m!)vj zIqw|Um<8TZIhnRd`seaxPzde447yo+7{Q?l#RovH?bpw3Fy9|i=#_+Z^w5AfVAi0@}_Gr%^su;lMP#2dKPxO8pC0Gsgw+Zc6IHgGc zB~Zb0;O6dECN5CnBSV{F$mrBc1#bfqBr5GQ9v+(XX#pTQL2@Xy!5Va9_K1+lS&$$s z6@~V=V1VnSPWDam$u-#*@`tt?69eJcHadQwGCHM1lu)tsD%)y~=dtC2KBgtr(YaU6 za4|F23X6{$VK{F(3?7zltj#`w$0!M-%&OxcQ#RXZZV?Y=>z>v3?uxlFSD)h{PQBo7 zQ+V&()w^djk5b@EH^=QAhVzRL5?Ep?2XbIHHmDq-WrLL#XX~`Li4?6<5PFpAb0|pg zqe8qL=t$UmkBWbVnwC_&E>U9U?lRzXi*1hPWHw3XlrpcSVA%Pt*7YfV>V?=$OX%hY znGO=&?yU>vk=JOA7m?O->!$z$pi{$f+-3fT?2wC$LZvh5hlusuw-#O9)JED{nz?LD zARh^4ZKIt)uLA7nsK_sCdOXq4zzOR3t)Gql5l2xg(Ms47*#oA;d9Xpg=@P60pr~d~ z@twpRY#W1rfo~0c$@xn|{%dyWaD08_BMZ{A1;!zBo2yc*IyC(NP5qL~v{kRRE5o3< zjvUYKVTGYZk?X-FH6i^GoXj(D*|FASiRLcWCuo76%(gFu@BWDoNJ>hBv{Z%Za~8mt z!+nehXyqp4)<~-CB&6yu2wwEcNi|=xm@Qz^8>}rqnWZp%Zg^L-@>etGP&w~|!^K;v zFbwNo<55w{vNug*JTy3R4UN^MdtHs`U*^8PV4FQH8>+1UJx*={4hzY;_PBw1CF;Mw z*+EmF#(!ypoLKnbTUyxkSP9#ZZ_aTTx_w!fLqGQ4zA!MQL(Os053-=kUsf4nFu#Hwg$g2~^yd2@_|U4<1LY)!*z(WAVwL=o7YsA;#mCX_F+t z%(J7#3)B&Y7(M|a^!tI<_^B;-ZphUangy&$F;?5;{#gh8st`i%i?H60gk$|4Ngr56 zw2Dhg#&;IS(C~CADPlON3xg1|wC+Z;y{wvDOHKOu5(LPeP+qcCj5Kuh9U&Vv-lX3a z%-==eim`jl3pr~)kzQpy{S3+kWmOd6R%=yf$K*;rL-Xjb`q$kK$Twrq(3*wG>RbBD z?$=H5v*nM|pwj&;Cc_F8P}rgKJ&pl6$;0x`C;b+hrIstP(z}FVbxzOF0wf&~?_m0F z!h=_Vib*j+FBkkyMms28LQAFx;DxjD6LC#g z^r8gEdPHJ@cs?VkPwNe^geJWnE)xv>))Vi*HBA&*Vd=1-3S6CA<|^EWox*S2 zZVvO-Z*lPvdZ~NcQ1DPkn!|l;PoCrB&b*>qXpKK0O5wRSimpxVT~mIzJ!&E4Hxsdx zV?Yq5FUZa*$S(-%qS>xswJIsEeTzDv8(*&)*5VR$z~Q+F9m|ji!nB~Yb^wO}&R^u< zF8+1S6&RvsOWy3l09Xe)z6!2Fij%VEASoN2b7l(bn4akUClQ0Ac2R4O7pXsL3I>Y` zdF(KjhQwn9weA87IKJS2>h&2h0-12u3;V5qcefIm%7tD=u2OZ-k)PI2%vQyEC?+sH zNGqPRRV^uc8~hdipTFMe{K@^I9^+m3wxt{`%0>fU>f&w4^ty@pNeGQdV}5ftJ_ zb*Ks1&ct2!s^GQBw2R1`!!fhDqjk117%W_wvH!Z_kFKpox1(26U$@&kN((%jn;|=w zEAXAHidfzK>XqT=_kmU8YmEclVw{Lc=XT{KfdkPa4^b=p3G@(vlP_1exME zwiI3=$~}CJDv84=maiSnaQ1PF6%|b{$Iptb8fh=B+wLV%ldM;f$q_5_MC#8#1Z1q| zi_ASlTZ#YdfKGN1r{_6}2od$>TbugEo|b%s+EH7UFVF2k6MFKa9;!`^*R87!K=uCp zZzq2ot^Lu;43+u-_HHl!K4;^phSXHPY#JwS_^V7KiySL-bn1 z=^f1lapfoKF+W#Y*NaODxbC@WWrQrP>@<)AIme{eH-|C z>1%gtU^MgVdtJQDqo5Bm82-CmfW|fRW8lZ)vlGEcUl$S<`2Aw5~(of$PK0#(*DYyMdN(*ej)>7!+jQDrM`-wvXHx7*H? z^|`=_>GqWId+ySch4zX!HRiiY83THr>n~5~WWJI)wgGv2ntWc}p@*L}d3J<<2?;tL zhUDltS@zu8x>QUBuWuT_=EzdL zheLEv_lgbGID$T?b(BiwY|8%C##If73%u!XGHEY{vTAQN<_rUP~ z!8Us{vQMOvipR5+Z{`hVt)GI?q?4$-)s{=_`d`TbumsyyQ}m7>+nvLC(+vL8HDh$J zSyPwYRxg$UPdC~q0zj@PHHYO`YGXdQA6R1Sxj~K#7V!7&G^^sH$k;W98(mfTOJI`@ zL+6(|!w4Fwq8+vpdLut+t0(kw$V?H~mk=!t+qwzz2ymD^2TCYt4F%oXRas97Inx{A z!q`tcY=H=xh3$Z(ut2lBhb2y?tRF$>fS3Nt3&ASWNx4d$*YyXVPL{t1tFrjnndZ6J z4K^|PZA2u&*4J)x<@!{7?`!P5^IlTYv$7VbNA&LrQlk z5;&P^*WuYYUy)zlcvv_7e0vYy%zl8TMaakQ(|6!~tMK7&CZ@c5!v2Q`mf4w;yHzfm ze%q<1C%2aVd@JB*ZtxTH!yWnB`(ga^=fTPFh3<7bKBJ`@Sla4g_ijR=LLM(<5K{#H zLKTy)pxYmxh~UYh2~ZiRYfC=^7>Dt<6*J1ljor$e%@f=bAYC@H5!aef-XYm{w)9S* zI`6A$i*c3+ZES4pYqOh|=La?@&GcaN(F!;d7U8}9YTKLlq<}uZm!~8TA?MxEC(_#g zfXLCD6x0$o zpCgmx<;)KoHs+9jJu<7A#xf#}Tu}jkIpQiVAEt^HCe}+hDkNm6oLr;J^Ya6aoTY`C z&ZRg>&}V6D?y%`-{)3XOKSdw@NWL;ggTa2^>(nRK!{p0*`Wu|L%Z%e!6Hu+s0Wa11 z?cd2f*W$C=$NH~JeZ`F=BWdMpdgn@w!7K6c8iqUwzI{$j|N(kIi!F znv+j@PMu&qeR5(+*}D)%XmyX}tV{;tLMxdT)5QdZg{G#7ssAdAr1$tPXm^QAs!uAYZ20GkJz`BV5mU#9!^X!Mt~X03 z5PU^YJcj<8QQ9+N8!QMc`(IhmrH{VI=RLSG*z-9oXi-!-Ea`OEm%qhn#PEl?jlDB# z#&ag2l`w0m+m+a%&fqt7=D(wc8@rajhsr*Djt4}IkmBv=kgBMvSP75FHvsftrajG2 zObjA2r+YAxI(%ca=GLLEpgm-4b~PFDy_gBmecJAXUvDpLB!r%087(p^p5$(U5&;&L zw7f>BKE6zuirp_&%NjE{`8Csy()es%;o#iwA`~_9T?gH$q&Fv0XNa;1&L3tbWY((e6-XKso2#kG!n*nj>tr8kR7h6(OxmQtw9@ zkPa!&2WwzL5X$dZw=sDj_kB;K-Zj_Aps&%vc~Exat#ZlPLUH<1+B8o1#*Pf(AtA`* z3J6(K?38De`d2webU;r=P|OLmdv;_J*VdT-#v)w=@LI*rA1Vvm&+9n;6J6+@e8Yz} zo$zL4=YjYYGlFP9`8ry6RCAsEF)#C$2jR$&)EY0E!ljc>fXU)BE52ldqi`dALgFH4 zgUttBd`;q}s;+@InW^t-YTW*-6_aXjw||A+a*TMxgp{>?96mB^cshygKT_0N+$W8c zkN#8hUPHtUDw-kTUnFh+Rl)xYra-8#hq`beLZSz4j({@x6gDC@+(we?!uk`Y_iOo1 z{_TJDzSot2LbkkmlyWl}0+cFYE)w;^d6_OECu38=KN8P;M(+!9Z$LCM5M`(F7ZqrL zZ~OnQkk{`FJ!GUx;%1rTe$1k2Fj2t`q|IJ^k|V>}eq)xio_?si=LfCRcl>&%__+fZ0?SHKnpY8GQQ4PBfeyMCx@WI;c59>dM* zX}?%dFqWCC_ePLD0dQUBTB7J%SDDnpM6&n)vyCF!z_*yvsz%d$oFClVhkfjBifi6yLDhdygS73*ftf zIP+o!nygWM@N&)`K_Lyeei2S!aJZfIJBB&HQ zpWBC`k-S&j$TN>4B*X(+&)&IaXvyklF0OFWtm6*?R|ZQuXu!~UP+G1V;I`J{gXTi& z-OuQqn4Y_eR!FHu7Tmth2dT>bis>Tq8gaP0B%D7X=%jlQ%l0!PRFk>4f^h46}um> z_zK1#(=RUGV{B}f7<6{H5zJpm-M3uBrIk@@zJJtOSYKTa_qr?OJ^`jHtW+8toB274 zzuCyCk@d5}cra8^#HuehcyHwC_Gi$k?EH-FOTCLP376?}+wU}@+sm4<$IO<8_n<$A z_x#W4OWflqzjI?gy!n*+c~`uUTwL)T5pH2VD4d=$T!ZXTcTKe-%b#9}*wLF(Y}Bv;jP)8MZL$WvQdk<`#UO8$&yEf9Pg*}nu12hlEzf=Qq7MfQ}Z$wq`8TySEL z5!Mlg}^JU)a;^*KJVT4hhA(9A)s*W2JfsSWKIrXly zjA90@A!wPUP+*_?e>%hX|5?t1wyKSO59=Syq80DCG&-6ef#07ZorV~H!6g3?PajC5 zATE|oEuZ?aM!5)rcw7bUU|Q+URI8n#-b!Lv6!c|6`vUF|in~|5T~pN4N(k4q4|M@r zQ7yV*ffW4jXuHd-gn+U?2U!%T`zi>a_~FO;_JqVb z;r78eySDo~Nj>e9NDt;x0;Axw6+cP>e%H58%$fEtP2iuFKb}r0X)l{H6WU=@ZpW1u z@nb(Jk(z-^x7-oLvjKt`rJR2v5w%bZ=CJ~FGliqxz z$XBDjF7Xmj@*sVS^V+)xBW6&=L{8%l4t|{o-+lRtQP9Ja6(>QAWe^|Q`*?9YVr#R@ z;_Myai;9?-^!EBL%m5QaDe2S3iE&SIo#xn?luiV=^9VundW|k{u_^w|u%!{jk52)A zcIz(LNDoH8Yv%zFu61J34=EZxai0y=I*u;?5QNDf!RNDJe)_A>%1qlp&~MzJ)}1GP z2QO1LzVRso--iSPm%Z~#)p|gP<~_xr*&6tFL4h} zL(nshjq@AO+T8M2z`5B#_o?@A|7>|pVAA`q4XBtH@!sZgUIIl0At6rp^ya2h8J1Sk z?X4~j_E^ewBRq-1vu>yZAd3I*IIZxTA$BYy{X1I`Ew>kk=LD$MORr`NE54a%tJ@L= zEIV+pd7smHkoL-V`vwZ9f!H?^=>fuk)6@LVlOEiw67v|>+ zdVvB>I!t6+3Kf*<3|I01M&D1j*witu%X)v!9L8^&)^I*fF%}R@^$XfTtGTB)nM_4Vbn4Xu4UNBGp z<*6ZE*5EiwO(hDOq_Z<3C8biofZbc1Hl--m8xY;*MqP4CXUVQHs{W4y6|>79RI{>J z7qi$ep6K4scadX%>&7hRm3(h^O-PBnp@}g5NNs1-mKNV{V`cq$)WS#Cl`|dO6IlH5 z$_c5TmUmbYtW7ISxr z`-LrNsM9K0Na#C}7jI`Td%uEEM|(gBe`+F#g)2rB0X_Do-s-OMzrNH^1E^@S>w~QtFq;_wcoT)w-yi*5q~1D%L=B?;tii z>D8cUp3|EmsUigMw~2P^#k8fN&1)F~Y|M`>&vq4cTFM>LE^v!stw%Pkq}u5@8;w{b zxDp3nS5`e1=mn>%zoFSkKu+fX=gWeXGV{&f=&E|Evm}Nk7HcXAPJGyZ^<u6A z5O{K%iygG0pP!Y&0~$_6CAhBzOY#b%0NU^Uz)n=^)1^{J+sgFb=N`6^wT2}NaR~4y z>&u=Qf#`S0Ne8`7578WAaKRHM<7MuAjf68wzibkUf;o;ZMy!3PgSFauEM9IQT{%0L zu89YQ*oBgC=jL6yb_#7rORST{W6?>-q?_q$a%bGg{I?6t%Xf~j2+G?V4D62F7=af<0o zV-qq0BFfN@w-|)2aAOlt46n^1_xxDiNnlreMJ|HtXvsw?eJkH>wd%` zW7A=k?AMNajO2D)@;-9`3ZPh13Gt9LB>|U9;b$EsA)KezSM*-Biy2=eBq&t96`~rt z4j3u%hN1XpXs0)Rm)w*urnv5&O_}BkrXme@rS88j*GzGZ<18-PdOPnjlQ1wEW}(y; zq6gC@Aaqs5)P8o<*MDVYBRkijBvG}U(XajUl=N)otA9h$(s@H^JXVRFp0L3Z;uu;t zlcc$4O|BSZL?|EAc+Hl9x=pSQL0xLhZkuVdRB3P6864Ia2G!j4+V3GNEK?c_*6lR?k=D#Wc_T&NGu^VSO#)Wv-S(PBwx_q?IQAh{cb*{_fUk zo3zCJ9^u!e8IHFM$E8IW^YQI16eYPCTUr#V!rV!6G64)nSjBD%s!t zASRX_tE8pys+F5>EhloL{))byO9hvV+Le=KftanWt>16&;MVcHw=37T62e#tEgEX8 zx)P3Y&w>ais*8u%Fa8{Pm0A7tJcb&Gu=tPv{HX^2^NWjq2!!qGUP?*|kAv{l$J$Yx z!z_d$B^4J|SZXO$NqtrIhuL(~+in@p#HoH^H>L*{ER2`|Q6!buug9R|Gt+oOJ2tpK zUCppLioME3New!j`ld|D)Ql3m!oR=tJk`S5&zbCAH%vn{!*|AiUwYfgJ|dvWO!E@Y zYJ;@0zG>m;cpikR4V_|_g-W7c9&}|-t}cXJ^h|bxESH`_L_vN9U&l4Y#74Ti$KJ$8 zg|PrZ-U}%-u4^@j4{OLTKwA0l~nH5#HJYeS2~w2L$=YBfO8E z_ghz9BcWW3svgUJ|E4W~w8v^3 zr7%Zf6QqJc+R^%6E9j{7XKplaHs}fYXH;=9%#0Pj4L_itI$rKDdll1U3_vY+dL=K2z%$dJD1 z(bV(9$^dF=>TF>+1lBOSoyg?Z8j2Z)NClUdhfK1qx(aEyWhfXyh&#Db=T58eUC`XKMQwAaHw|$=j5j`!j|@a70Zdp zsQ3ME3x7E6!#co~g~*an-uY5BnM2D3Y(|)r;q!yt`QD#&4a)tmgM&YKs(~QjbUI}kI` zj~z;;oJOGE3)7sinP8FVOQ+S$&gn(7c(G1ZP&{FJgV*BIWzkMROkEI!_R)W(E%z`} zC>>5)c+Yv|U9fIN9NWrEym(W<9+xd8)w~*;=LT}zEMP}?IqeDMOTYrh=JP{+g#!$p z0En3~+7Q^c&cJqNHh2aY&w@bY)+2Vm21RR#AG^37DdLTV%s`LE9pF-nLU;q>1Br z{XBG82V8FguMLQFdYm4Q1UBYXJU^Mu5%c)3%4KqHl;Hv%`t3^{-7dSK<^v$D+`&gr z9~wgHDQV*Us#MVhs2jiU@8L6QpsN_?^&6K)+ekr^l#tL9gDSAusD-W*1(R*xffd1_ zRF#C}M`);up?u;;;gBDq#SaEV-_wIR?h-%qwgQ76@^st(e9>Obc#T@+OqY)x06KXSLD5^U=!FU*o`-8Js}L8b8P@pZ)fh-YRwmThAz_gcR}P^ zS0~w+_uNMH`Or3`z>Uk$iA~SrndApn(&@??*4eKcULQ+A^d&%b}XZ zX%CnhX4m&6Pq773!u2%yKUo&GD+YYgX=xe2vTM`5$^_TvOp9AMy?hGqw`ej?@Ckm7 z{319Y;3y|`!Q|sOS*p9M)%FU$iO!n-y>jR3D)@AK)dskv!m{-w0@Gz|49CE0i+IGZ zDZ?gv`62c%w64eG@p7DR(YaTfVXxUnx3W`GCdgPw-*yy8{j86%Hy=*jAyB>#5m3E4LNoOsqrN~Anw6Mn3VZDHV(7s@`2 zyX&{b?21c}>-Qh}DSW_$>r7Y5#zdi*89kX6zH5vRBtNbo49yi+w9D>ISXTglLebr; zd8^|7`ULH?|9@n=G4#RuB~2_zD=z%`wD|{~y0yupDhv<74kbp&d1OHn}mXI@Nbf4a)uzQOwBKSadGummVAfm#95t#RdWg7FtN&` z*_Qh^O6Tgv3QJKYTf*9H1S`K8QMNp&I91LMQ7Q?tin%m~B|;wC?mM3d6gNH`fT4iZ zXUNxux7y+ARb<9Pn6)fi=u)M;nBkXtc<^K9FIhEdu`&?61PMZ`ju^g(nw84 z!}VulIX{%y9BBHfdSw*an(bWH-L)<~6*rV(_p6sZ z*L^62BW1F+iptWovs>1vh`!yur!Lj&Z@+#DJ1viM{Dz0X>mw=jLZ@)JP=we^ zt=YroExtpSD~5qrQ^)H=IL&h9c`=fbi@UVB@Hhe6o$JoyR7VYvv#e0lmASLw>gW{X z`|quX6S3B7MbvWZES{1_G{41q81s2_a^_&;J2M?RLoDQ=rmcINQ50homeD|ful7nM znXP`d8v+pte;uBAJpg#8J z;K6yMCC)`V4so{r$Gq+_^-ydlTgAfcm4sa(*ul^X(g=yQf-P67QB!S>2jE~Ze1$4- z1~a{+Fg#RLVqF6G4n5*zan*k`UF}@|#nVW-oFq6XwLU$&V+*_7HVi=TOHL44D|}g1 zi8az6hhE<7mq*;c29MR+9}AQxa|sh9q|3b15~sP)}U!N@M$m+}-kk->HSlTTSz zx>~O2-|m8giggLZ7kbpkt8K6cXMB5uRdE}2mGRU&VP7n#8VuK^IS=V-A@c$;YJ>+W zVw=spwu_-@Y5QrfG4?M76Z{*MaC`^6XNEnL6my>=nG^$Avm4KVP_!}s>k=t?&I3h#>(3WMazU=MJ;9|3jc+x|SdJwHQ8 zaiq2N77{mGLf|{ULiLNDp+!g!jm%vYak>OcdkKMkr|q-d{O8)dP37dIp%MK$`)r+0 zVWAi0iht#RjU|u%ba|z}XRb=}J@3H|#Td?n?O(m$I0btY#oxy4M`aW%WMDJsDH9k&%2i^+v9uz}B zP!}1=gkg>8)o-N4p&O|w{OAADIrLL23a9>GVeE*jYvMk)HQoqai`Dwko>am|pk?o3 zM?}O%-%Zro_dR9A7YF*NACIRX(!Qby*BE02tECJ8yF1>^^aZtdpRD0vOfmP{dB+(n zp4)6Em$!r~?U6%>r6N}9b57+de;1VXPqP-B?`M$O*vc{70`SG8^k z8}Ep_r%TY#S|YBu$4=#!U-DV}M7+`3eV+r}GP@SRSoHb3aX1(bpP{tEQ09eyf>6@) z(&eER^Vo%k8GQ}-5x6XzUYEOTyZo%ERX>X_iFLev?15jVkhu2fNRI?UlFRh-)U(n* zdyyi5y&`Q-__jiDZk!TO{L`Bwosk!xPF;mO%y=u6Cn~(|HjcEG$8l-z2==huZ`W0i zeSTqol_w-{WqWMak(SI34Xs*$;u@gd|JM98^AIh|U|Vk)^0ebomj6&Sv5t?A1K60f z0qX9}L4Yr^>4Gl#N;%R6({=yr&`QY44xQZ*@!4j}rSak!EH&i+ z#R6=8MnOX}IbCgs8A|1exV^nq-j>=ch8`vf8CNi;-o>H~*I(VO3<{)==jRv7-O7_J zGg-NGST!uZK_g83hXHWeAwv;ND7~bi`Meg4$dy&6-V8Z&6W<2M6%dbF9vX@`>uA+= zqTw|^j-&(N*sJ28T}?zSEqUGRH%GJ&~_4}3oe{_9ySd`t?w}6VYfPl1ufJ%2WDkYNA-QC?VBGM%y-Jorl!{U_yfvB2&Z-07AU9GsjX5fQ>BX%pBq-9;moBYVN+l7>E_( zmL+VM*;#vh2Q0rX#uCl}Dt#}mh<7K8+%+ekt5

Rz&2QM#6DHJCCm-w+QuF*0YdI z3oF)c5fml|;;rqYPZ>Zqc7$xkl%o`XQs@k8LdNTrQm`GIKS)xKzq|Dn-k&Z#x|aZJ zcw$QTEkP-u;H_?L%JHBHvGKQr?@?}5ZwkIEo3-k`vGsip2|{vWYflT=SAA-F7JvCJ zW(gKdraCP=tz7cvwxfXNBQgLufo=WDZd(vA}6?8T;J3hksRVY%@3 zg>6Cc&N=%%jb_y15=e=^Nnft5OU;~MIV2ZR_R9EK`gS==fb~r+9=DJ@Q=#V(xi!li zq%b&GDH#M7Ihl6C1FnKHn)qdaO)ZjwPb1}5`?!GX4crteas)vTItVR1@UVDPcMi0CAY^eE3^CtwGprt_sKy3Ll12|$@8-kf& z{FCa(0B0XxftUF^l}dc93Vo$DV? zlO{2?!VYM%Z23^AY@br84c3!r1r7o7pkoKJ9vF( zCc`M+hPFmq6VJJDUOoqFCv>dxBll*v^!Ui8BcGqlK_Vj16t3ThQNS`R8}=G!N=}h4 zH7i4m_s94+`t1!#WR`Zfk!(L49+y1)Qn@bGO?tuBGw{BRU^a5svh9BQCA;}*bfW5e z<14m;2k4tl@?tDrfX?5^CA$hs$9qC2U)pl*DWin90{}Mw?~NiYnS%m5urZ|sy#W7l zd&bA--dv_nVFT)I$IG7yv9Me@FPe2_u5(e`L@o%TTuK46kkHRHknvr? z5TI-BxEl6l*gQnqbB2L(XQ9FAg%0oo4#!?}N?f`vcR#MTajqeA9cuwrkK&UiABe1@4Zrt^M@0+)$|Y_KNioVzc{x1UkTHur34 zaQfg7oXA&6*9`7os3OuyJcQ3UWAJ2n5E|ag8z@#vL-S(kK|lUF{VeI!M2p|t?rmy} zt4&VvQkdI*t<|wjWx*z@i=Cl;awOA4!h591XbLNwi6*}Cat7=4bhEJ5$^lJ#TkySL zN`JrE9L@5im${Ogpk8ESKq?Z3C{t}_h~2AtJiRD)eW9*mm^A(j43|l(J!0V?W|{}d z`j~UgYtYy8j^rQi5cU6qE*8>7{?1eQ}CdGt{+RgeELG72e9q zsB#~~ejN7qGs~p!3TYU%Eaudg=)1MIL(-qKwm@UhtPFmVkDmCnM_}=C(&x~MKtRMe z-sFc1kq;r)*bPAjO}Tq>qh-_MTdy~qo32j%>F`gm5v#m`WtT|E`ovhpqP*hW)(40d zq+fdO{%>P8&wcq%r~>o zeIYL_+p1wtg+0mLSao_E7IuEHczh{M138WVE8hl|*3y2+z6p81Vr+_BOvY$WAihM^ z!?XGvkD_k*cyuJlBfpc*joID(?2Q~t0Aec9KwmwxHmty7kxu_3%|}i3mSBbk+EzOO}JDS*j%sZ*MQOxPw~uxdGxsTuE=XO3cdwZe-{7TfN=u z+!jYR+T`yOvHf~Y>C=^Bi%nJvGvn{%e(POUE~}M?x>=MhhTsQ6$U&?< zIb-0gCJOKG9i6vy0-WVJq*`=5IT^uE%h%rBz~@+Xm-i z=t!KECe|-vo0EFk?}X>uuVo8Q-bfmb*P(f;cn4Q+cP$*Km5{8E3!}VN!>cZ+$3BOK=G|*w7$IziXedvzdlYG)6CCJ+$Bb5b^#_wf7WTOeXxY+Bm z!$W6pA0JA}KwzZq3=ENgpl1_Ad5iHb&prA-(w#fHr1F`GyvBn!kgaX!-dU8^Twj}s zO|tu+5Jr@}O~~I`Skfx5Yjmr7PHTTF#_symr(tRN+|2k-0vp_?d0BJE=ZRiT@aGqS zImHiHrf(r?>6kEDyW?9*{x@~Em`yg-y^CCm);ecbxGMB-p)9J->S4sv#tfq`-0s-? zmNOg=EB;ym*xFt#0#e#PI}dp4C=+sQ<8E3u&Xs;%JJG87NbP5wh~L!BGp?#nM?YQ^ zj6P&}0P&2A%j7Xk2Z@3;N;*~n<%5r zu@K;(!sib%g(j6buJl&0s0k7~;9B<43?RL?)o+LDN7j}LPQk8G7wN-=b6!9=(*6x( z2P_QE*{U5FDTOJyKph8nb-XUSlV=@m7jk+mCDBpTUG2K4Ci@2sfTj}in_w%?6cIW2 zT0&^zA6A+CGb~tr_)RY2fF!9wLHX&QP62P-bzk7ycjLlB%aRLIh$4yZ?PCj9EY5Xh zQmo5o4&!SXsy6y}a2-Uef9t6dNRTH7`SFZ1 z%!q{$9>gq7`^yUR zPVQ_d|1%EY2|#)u&4*(FT#*#dcl5@E%oUf_*UyVYV(&P|rxL5&!G1}*c{W)t(_$m1 zgd*2$BG^u4xaU&E8-O^AGHiILZz#6tL~ZGKua6 z{ugG!kYcB_<+O{U{$$|FrJYDzg}aS$`(WXrQ%DU=T}Bh^E*uOL7;Unzdgl%oB!v^V zcBJ`ynj?lTK~}6LYR3ZtuaGO5aHHKT1QtEmVkI&+$o{9`8y2mWlzy2SL640tffvQe zJ?PY|`bw%#b!@5If2FzXseXgx=Ti#G4Z65>4#P=6U`F5T>%+C#&#&~l96QDy+Hr<} z5OPKv<5p5dQ-NYpg2H)`#uRnlfIALT038_TOD2V*;#QtYB*p z$RF;amrh2oiMFiu;e zUBBO1`rb_SYv-p&FWtl;99~n{zEeuEn^a`5Ut^=8Q&t8&>9oMMyGtu(Vb-B8C)AO+ z!2O=DqXD`=JXbWTOv->2JtOhQ2R=M~v3B8Ivwlybny}BN2mI@lm!yR1@+GUxR@hPB zg@=_2rmaC{Eo*AmVllt?rs+*or;^$dp=NS8cd0!h2CM|0z-r`K5WvjALsaQ0{t~>@ z=1#Q|pq7NVdB{^FhhA4Bwh$*r;DxzbT$P^1Qanj^Qx7)LG~d)7QPk7DSt%v~<95L5 zulHofXu988b51xiGqccRH)m&Ba4utMw+wqXsjnSb@?y}|aCO^o42^eR^&OT3=!B^~ znQA_koZ4VVH;pm$zujzb6G7L~CW zQ7{9^<`56-hL16Ei<3UsQM2;{YVGItGfP&FHe9IjT%pU`kemwk;YbS*1QDEFI&30v zr)AvIo}W@i83On0z8S5m)$`f$MXQFiGI^YpsRSPFxdy_3mYv0~l#Vt1OQ|^H?8ghq<~}M$Q@Fkf zL4wSP8RT_WZ8;X2)pct*bUooox!3l)MbDFE%f3>CNOf=ueOM=K?(I$UxPwg}y|Why zm8Zia938x}{gk;>6;kdq(wz-r(Y~GWVcLD_YGhw4SEB{bmN->Y9U6}1IX;C(`Y&ek z$!P6q)IyHS9)`LqCF!Z-9a%|MJzG+cU$S6j#??`idHg9!SqQ!9l!wSItOTUjnfAio zF98brp3XZp+^TAI`f>zuNP3J8@@5OUkkClvK6zf^Ao%;7b#8eSRy{wSMK^ol^d6_D zGms&o0XJi}jObE0i)yv^LGARefLcAJ!6>z40(Ulkh1?W)o87;MQ&x!5HE`b!AT*H{ zN%}V35lgxm@nyjf$+O{;kip7A)6Qxu>Kh83-c9y4A!qL}{f9a+VHTf5uvDc7MVMG@ zYZX3?8X6`&R3+hk-}ijZmUgAp_M0VdPMo|$k3QH^Ty?26P4q{DbI$Om$F^4j&wp?hL+Okw(d6qIKUCwOk()W?-_5GH^7j5L8gRhj(8vuvO-RBo=g!(~cU3 zv3@NYRuRXd@D$g2zLB#<$+2KCx;T;XI@0l#iOO+Fl^Md?GDZ-!Kvau}r3YPESZWtP zj~Y^3$T)PSTJIlhPei6|I*Hi;c6dODb0qlqb@|T{vO>MJM3P@zYl&R_tXj!v#l0W zukE>lEzj;N4%e^_t9o~R708WLHHTYL&CPO!5oUMN(L`;>XYIG@UaL3=JAVJJEtr#w zV#<>*8MBLVoQ(+>i=Mt2LGL?jvb#S=y$%tDHnNou_*#E=&ab>07KOt zA)KgbWwq=@kw-5ArTJfa3lLqRg>ZuANGjv)6A8|Oo9VI!Y@=in*hbUMtQnKI|80d3*{ozYOPDlu-c!x?F;=+2+)+_eN@@@L& z3CGnE^+fbHNdsGs1|Hj$_XdNm36+ zz}!tI3J^yuD`o-E?o)Pj5W;UZ0>kcc`!03i!Rduj@Se-_`V;lQEi&n)UySPqza<(= ztvwY_40$(P>QQc>$@zmd!XHcSss26}hCr^O_Iq7EeieyqOQ2=l8d7YFCm)J`J(ZBxllS(V)J$1$!pWZX^6UQDZjMhX)yH0F zaXJN`o|zy-YbBFt@Rgk?&-~Opt{aexqW+n+yG)!#+V`5vHU35(!vEEo9Pv%j(s zD3Q*M_qs92>9Gk2_^HX;h`l*r@9=!!^yJ1-!=~)llxA~7d>!pv2h}9@C#euD6!is< z2aLj-DDxsmC`ApU{%T@ka(|xY4Rm)B>e&rYAo~|1<)sc_5X}dA>5kS6L?v9?O53&j z6}1=hSU2TR(poPsr7`v}*8Z}UIYq7J``?!uhDZC*)jphDr$?X4R0x6tmN^wYL(w^m7-*si_%mVi9%+CbUP_G`0G@yAe^IuqcugNlke zP#-x}_I@SzwyF=qk^k1!;Xx^%aej7IW&`Kh7%z>=B*3PLjhwMH15Ea(XJ@G{l($-! z{GHa7^H=M7A8kKuT$Sw)IDEazUcwjwPNXb%Ldfyh&B_3ag%)siBDjD5{yYL9IaBWf z`~Ov&%JIldHEy*pjz?hzgO1R(H# z5pt#f(PnSQY58e95PUk6Es3|~+K_Ej_Y%1OJ&c5v{@JtE!OYvy@21<>C@j4*;NDjA zt@jd`6i!F}o7eGy0xla03JUXUY(Jg=_k~SXm_^x&-A&nT#z*%Yh>4V*00@%PI=u+@{K1R=V9}22 zk9cJlDcoT&vJ3R%Zc|*rX2580o#Rq1gH=rLXZ(GmC)@n^JXZ!xFx_D76~z&y0xRKAJ-!QzQtcG%G~+H-%rW=7SwEL()cBxvpcD*F?&_?^H zgIsw*#?h@*e|G2bxob$*Fk272>5E$0Z08K;wREXwZ_|Hp0OcorJJ430NZh3qMgPx{ zHz&*E4uO6a{Oi7kiYps$t)i?0|Eo}xuORxJ$AreCAqC#8eHZfjS#u;8MJ{&UH!lz`joaxzKE|PSwWjWk#`XMdOKfU73h1hq^g~AiVwrlJEI{4kq zqvIFZef2&ai!cOpTkdHswdFIs7SAfrAk++?yJc6uC-=FZa`sTFkm(?VrD zYdezK?7^8D&oj67(iap09p9z;Fq&MS(9+iIuI5UvpU*RM9kFMy1+;)KKa!2rr)j!}k{%bRh0y}b-H(&nQn8EK&Ov5ZgH-|!nSI-D? zW5uPK+~lbw$MDB*F)d!KC$UK88RO>}lU0W@8XbYD55y1pX)ntb@idRk-`YqEw8(YLp81vLXt}@iSOH zI4Q!ANva9^eTi0-cFZSwakLP3a~aRdOF@%9)a7Yd|8)zaFOg%zq*`*iyL~BWP{0m1 z8v-*hE5Uf+z~pXupPG)xWX&kbQ7gM$hH{Syw8P3Y%#ImF^^B#IXB1VN-4VB9XE@j0 zQcgf^P9XGJt-j)_Px2|}oZLlp)PeoYG9E6 z0j`lr_GN;Vp4fG&byHES8 z{?{E@%lZG#LpNRfL|w%td3^R4WHXj`I*FWY7C>TCiuy&Z$^4*eLrZMPOR~OhdK`PH z^B9%Qq#-BoN5qQnC!4==uPU^@Fxf7gzH%mW6FEVx@z^%HuAp_FF=JUOym&0QW2m&va63({s}#LNM3fvZrPGoMgeP9NT(J zGmEiwcSR4t%px-*W9Ob?x$sSAl(Tj-G6-n zkT;e7wr*p5h_njdbjVFp3%=EW!L@ch=0SCQ9ZT;6S5y^Ej!QqUHR6TOiOqqp(qGsw z6`uSlwjjdJB8{z$)G{ksjpN}}AaAYVrQM-?zj+U>1Y5tm+^=7o8gi5f;`D*I2=TuP zeDC%QKruwlgXi#$>AomMq45aSoG+v~J&@JX7R^AZ-ey?j=Hy|&IS{h-E(FQ87eAg2 z+bpH}4b%D-QVsuwFpfczi5d4bi|G~B08q-`w9MhK|1=fwZGSDk&&teC+S1y}VW&1o z=MCd+&KEA%cpwfCrh%+2e+@D}F62V&L`d%<#Y5gW1GnxL~?P@jgOBfx#P+SCurzJd`O>iYY z-eTI<_OHv@ezvnl76^YJu;<9`#81{jJ}yv|@43}Ws!~9x%8=X?r1V~}F=`}fVPuy- zZiV|Y4W&Xy$%isO#&1-%SGb)7l zRuB4QY-N&E6FJd#;almQ#Iz5la?hU&QzL#J?=|xOz;lzm{)`i}{}TQP^NxPsJ`~9! zWqwF(O?)gky6oj^wiL%;eJ^x9MLap;7YzWJCQ4ld%?|?&er|BjtToz@CgU3KpG=vI zY>$RMieFs0_b|}oyAPPkU`$61pW^9zeSMXZdM{!N4gM#!lEdZ6=zYA%7kkK~%hK&5 zY)iGU*cK#>$AyHi)of%}TZ!28E{#&d&dM2;%^GM&)R+G&o(a>O*IVgRGTYOK4-7y_ zo;1%j6Xf>svD&U@-OnB@IC6zlUK(LRwTEJqb}{#V_Imu@4Ym}I+VmVMHeyT?dzj|Z zsL(F>Y2(G$Zw7)q5IIvzni1TN+#lB+rUD`8He$+05D4p|Qd7dSopg0WqbOOhcTe#k z;zLs0|( z$lg}`rk7VS-*#E8_-7rzBby$FcD)r=FKdyVwye0 z!lxut>O-v^&6>%pIa?Ti5RRoWuzS;QoGVJ`P$E`EE#|+X$8I-lQ0}NWS+~r%I(acv zTt=;n)4=xf)N7S#T0+s4Cj__(NNq02K`HmV)~L9k%1jAA;YLg>T5W!%m z&!PHq99kitG=p&zKF0<~jM(S=pxoCa4RAR5@N@#Frqi6G}Z5pBslumw_hWI#aK=Z(i_zdH$M_52ZaX z*lXb>k!EOib=4@#_Aii?m5o*LO!4THChw?Rm2KghHba%i3ix!UZ13K8Kf72>JGh{& zi%)ilN%r8Jg+XYerl-BSPUu@PPJBS=u*5m{2&3i;v=Y7ne}fm_V!SY8-R7X2UKhJB z!nugO7jnJ34%A9C?P(ZTTl}MlXF8cljF&KNm0=B5Eghr`(4{PDqVi>ixmBUk3KJjD zwE*GRT(^dk89U+-<}`Qy?zMnUWY0tlt5E=wSDSB1Syi|`CWi+vw_-jFWF*_KSL-@R zVY-qAm9?5P){~{Z&hZgCi@-_*Z{#ywT~o1~9d}ZYkIw!Bc>`3WUC&JA`=GU`mibeB zwM>bIh|AM;3&=nFE?e=65V za`P3PY-fIzv!d=WBdp&eeOb_r3Q{@3*B?H)%xpbh8jF>{J?m#7hggo{uiXsznZgB) zFi>8ydkuJ-fFcSHHXXwCdSyX3_!TpLPU1Q8%-+y!K4i&J%J}NQQx17uC?)vfe$9wx z2Ypwd@*J6aIq|`n9_w;Jl0dL@D`j{dC56u{o`<7>aO9Ui(^EZLu$JC)Hfei`gICu> zJ8wB1UL(A>MdEbSM6)^l+|?QoPX+ynYUcW3IxZ7{n~*;i*RG6qcNIu5g1d^F3-W@1 zWTGbK;AuX??xdHV@rnWUPRD)2{zRKh9%I5pOIS=`XEy8O5QTa$MLuCk=7}Wzb6VpWW z5xwO$q34QBv@|qBXiZiNaM3`{$mKt~m1cs3@hL);zlSrKY*DdbsdAd7*$)3LgykLl zkA#w2g#sG0cQ!ZLXmm?eA7u150CBua{4=!b`T`tI9~qMCbTtkdDC!tIYW&Z*NeDo8 z{IF1(d{RD=4Kj_qtU+#D2X1B6pZM3Hdj%E+2V?8_1Ho$lVS_ZHY6hSuS_RN z{Ly((3h>Q0_KK_T?Oe2gbEYQBj2r~GDV$$cFog{bDL(kGB^v+fYfc5Ua<}a){i#Y{ zP|0}tOGmzQXKYR|)^gh5YV#jtIx?J_Z>KI(9`P7II=U?}E{=Gc8@sl$l1qpRkB*LR zWNb{ri+?BpFl{a_EhX|f82(QSX@o~sC`Mkw-rz96)#Usbo8&o-#l?(`9q1Vt4vyh= zoLaGqjq9Y8{j+tHV7J=NuZRag3{Z)6EIMypw!zpIUICge3T`?qd3{Tum1=zU!&?vc%l4ff@p?7m;6qi zReG6|4e_C2zqjI>tkjZAft)?%MY^d*8AV}&Iqg2Ga<-){LBK|GeEDAxBKobGwl>8! zUHDU7J&nrvKW{TIxs`!4=W&1h2^|)9K}tH%0Xar)bCA-^x-a1v8XBH^-#TO5CJ7c! zur!cMLXA^av`_&alrJj2#x&9@q&!Dzl~wlwAD-lyHrfA`b}*S{ zK$4=a$ntB2=icOi%PZ;3-+#)=%5rgYAD#W{FB8t<*DJN=bE-BXPG_N4nI15ug+|mI zXth*$OK`K3QUB{Uioae}GId&=9zeGJdSt*98CboCqX3j0JqWGyI9N3=1w0tU#EjJi zSH3G{H31fPpjJAHhMIStkm`y-W#c4$4FhUq>FW`{a+aN^<%K*b%+D?T7h6b;^<-9|=6_L7-- zd(hVi64|-5$L6{OyrTONh`I^-3MwJcE;l7YY^-O7nrVi_@ z{8CljliHzI_CEodi2Tzv?f}ENauosEE^<3!0A`lw1k^AzG{lEU0hYlHCrn7x!Xp3O z-&jk0n#UQxqi@$3ho|_+@0v+Fmvg{k4}7HH=HjwHo-{LpyOxR!h+J52Y;I;>{XL~5 zF#LU?LQ}PHD`SYZIr-c>HHqEpH{^PZ3~G0Sk#EbWF!!3TpH+8aeBDS-Xz8U~%J&Im z*c})}`u^w7pX%GDtlZ<{6-Nx9%)>fFYqdW$sdPNY$!fBLrx0c2!jUJs)8yTHFnCZv zUz{?nOP$@#_K+S21iE3l$4ZMn@@y|$9D%nzCBIk$L!yHwQnmz@e5Vd z)1egfz0jH#bp0ymK*Kpal#m$Lm4ZRIYYp#;)Vm?m)6ucN^G=I4cUZQII3^INYFh|) zhcj8NHBPO0?p@=aRHX+1)HGW@9%bVIj{8w_8|&h<&5{~s2O7yHJP%7-5@b}{_m8K= zTS+=@9N;V^;y6tDF*)LUhzYpbj22yX5P3VUR82e1NqZ}7qc?m$(e;g{T$uq$H<CLAG@Hph3|CVF-q2#t5U_jw!` z-_6Cy_1)U3)6n2>IRmtjf_l^Ht)smG>e2e6Q)86;fd_%9uKNN*K5!K@0Z}*NASecoxz$->cGN@bED^$ivt=#KU>H0`WF~N=8A8EH^ zTg_7GCpY_yq}4rd$Ko4k4xJ>rna|9vQPOq&3c5T8hYKD#s-|!~obxMgJUqm@baNw2 zbRu?|Fp4SOg+aUD+?I%Ev5f5v3we^T24ryO}n+lw4)g%0I79B&9Mf-YIf^}xw) zB1{m@D}h3wo&8+a21=S2xencjL-kmaMEN%VM%}_ENleOi~2hnAlyJk-}Gx zsO8kfO!qu>&-CyImS8KPE4duAIP=+!F$l!^h8f@rNyE`!h4GFV3v9#eYVqoL?m7^0 zkPg{)Rq{ER89`2mFg{1|7I~0+yQ4W?@a@<9?g+8jIXLf~y8mfV;pqbQXj?+X6k!Po zGIwt(ZnDgeKQEKnn;Tt4%=i%FA}$LfalJq7aXWL(^lvEdT)&MPi{U#78btcyiXUhO zM#3TzP3P3O{6o|Gq+u>%%^2!cT~T%}7Macyk;t%RG#p8Ac@G-&YO2zIziSLDS4Xl3 zte5?RN@&T9!%C5&jL@`9e~(5kATO6(z8*>Y9Kd!;El|MeVkaP=PrxH zDc$)og4(bls_V6pez^&1;4}7jSrg?cE~I--^r5<`Ewev{?`BxdY3~Q>&c&5LXtEZp zXmHx{jL$A+wQ_B-+41F?`|lG^Ma!N_W_6d4lf814Yo6a zEsRk$Mk+fx=5n&|guG&4Hk6um<_O1h1w7Cfiz-f+xzqJsj|iu)w$Qog<(9uJF}&G& z;RsCaLXktq`N_eCoo_2+N^kEb5Ev|pTuhs5>b)L#?dr3#HHRgc+cm6yNDL=yVp8`d zQe%-`D%KO}Smhu$U$x)!+_~uSZ;Y`gAklVsm~VF-S!MU#$jFJW|A1VxrR$dM9hTyb z{;0+&E9>Y_cpKjC2j`ONhIWRAWad{s+1xewhuI#+%znv3BWesBh{ds4B7gJ|U=%3) zfZU0#0}w3ve)7KYmTQ-djScsCKlEP(p&nas62}{A^zbZfFYx>HW-_;pTGHk*`WpX7AoY&U+! zIH>7|fwC0W9?025Gx*oe)k8%mQx5(cO3VVL4a_+cw^~NOlsPj-j5pLS8G1U6u8=-hSe+gV^Z9P_9&c`IpJyG= zS6E+N4My$CB%(Sva8V0yxT4W)ELXcG6d1BCK>e7w_?dDV5xeqWQk z=#1~i9HSw;nKR+*L<}9T!`d76fo#Y(f?)8>dU*1mR&tY3`)TFXNO1TGCZp73U8+T$ zo^dsjWtLG$X0gP^c$vkh$U;f&QZMcNU~W>|iwhD}np-`YGf47C!RWobTTnndA#w28S!bF%=CDGZJwNH3=}}v))^nq!(@I+jVHk7L z?=M@PP~jToapo8w&B^hmUZEC&sIhwNcF#CeoW9dvN-*w{OK9bDqu`ViNiJlFU>L+u zJ+d9UGGe}&vSnMZRqpj6HX`$B`=FRRJh-32=D~3`32$1 zgU_zhHg5$^!xknu)mN8-2w-!4!6eT>)%H0WwVrKE%*mmj^+F2U*01Nx8-cGj^+G~I z7JzRe*2JKlb`^Vn2vmJcNGDlZOU$}JNaLmBCMH2>$6La;fEoWHcTg($HiBGHgee^Kc(Ru;k_{OWJ)*5hl_{b9+EKsetB)$iQjHd=~923 zY6Jct4=T>OSExtiw2BAr_$@=iZFiM+6y@UiP6*?bd*l^UOVa_3#Y)kRG)B*V7zf*^r7vCz};66lkFD-ns^%dLW)<6C!K(&~3wdjpr};~vQI zmYlOXL@>zyo}$v87O{j4^EJCso<{w5!j?1W{ITWV$Wu}AXItc$m_d8wIPjW1Xo;mq z6W^VV`d6t){Kf2z0tDODEq{~#E#kY^Ny2G6T^lT?TxmlavO=otYErpQfz1C`-l&S}f*u!#6Ln>Y#J@t|B4sLWtuM zQJb66%Yit!w3?Ar=03A15o|4)LATi1Ah+hVug&sX{%$<2N=b)o?5V!e*%{nEKtmh8 z-?B0;bgS5qI=n+93K$wC`p&qFFsrv-W)d$ed%~AWp<5Z8ICssnGolQ=Q+1>9 zOG}@d|F}4DP0M$?r*-pi>NHUCPBF~y!&Lqh1-@J|5FHA@B9ZXUvblM+^n)lS1Z&pl zD~AgUXIPpE{Q4)8cGVXss0r{lOX**aPw!cWfS*pY*sLa|99%}7E{dOg^EsltTpr>) zU5pT+I-Ma=|2QIco)T8OVHMB8S+=rBu_+u$cqRyU%H1sBG(u6VfXw)cj74pq&wbn2A; z=Zol+BpD-7+Iu)hIBgKrlLsPU!QFpMg@7nWn-V^e^eEtPDTm(}4EK=-7gv0qZ1);# zigE`O&@x@@Ia4TxF8*bB}Z$LBBq7|<-UQ zT%h}-AMNTw>{`C+f6T7{2V?l62cDSS3W~@Y~ z?}t>(Jw5JDJKlcP>QFLrVBS!ak`(nXP&R>GcjosAs^&JwZ0&di8|M?xM&De17Fyy z7aT+TRd1=ZdvX3|-y2hVea2T04aM>Y895nIIe@=>q%7eAZo=fSu&`*{?`3pv(skXL z?t$C2K&R`R@=HqSIXMZVAZV@4J{P}il7+pFzow=}*uYc3*Jn+-;iQB?443{Lbd`lI zT-qI-F3lb%*ePkJJJR-|{L>u}w|YLqMFF3ClGdmglFc+cBGa5)4iJXQ23RW*NmL=a zG?$KpbMv=H&gYjD9bG5q$v`M7AiH}A0f#A`nZz+^d>(9fYrMGf)%92*TJ*dDL>VBx zZ&^o@<^|+T=H7G3II2Ff`vHI}>il&!s~Ic>Ug@8g&wvlW0bZ4f@lzx_>byJZZt?J! z#zgo)q{^9rjt-?+stYlm(C)nkHzYkBT|gqI8373i1UT|+@63B^rXjwlh^e5U0O;=4 zmUVAm-zxx~QTlWTlyW@niXfMilER1rUGtfkm#FdvjpZp5B>#jB81GZ7JUT z!U1?Jux#v=*Lv@{qI~^}bjQZPH)aiTO4l$dh`1>oaho@NvujNHG?f?=mJ#@yEV zHytL8t4RQ*!XWEb4=m*2r^ny#5LwSgy&v!3rw{M1W}u$Nm9!lVU7@*Nn}6(nP2>3G z;JcDs$T8Wi5b-w|-(Qz{1Rv(l(?FY`s%-*9xj!0t&75QUt9EVCEiQk?*peh#}xJr`1Exx$6Yh`b>19EDv9BI&3^0)y5lTtdo+k5&UuHq75D~ zeqAmHb})s}Kle%0ElB|jc@ z>q;tSYe4_k7vQZ{5I~knGJWWt+{vJ~kLchp)rk?+@7jZFnM=p3y(mI)oyqma!z4{p zi0e5%*NBQLGcv>nT7lU!HUUt2?SHGMd3!bZ+pQK0&`C4{FaebCSy8p4;~ujLT|sd7 z`|NxF;~F>>TUlm_P3- zli|5FFg2dcg}l-m>?gwG=yo-DAK@_3DtZKNZxVoG&cFIEj*Cy4^BXE$<#(6y5~d7PqbjGpvT;g)y*z?HFT<8ohI0=lWmPS_?NQ)TvQzsKuG>cFAB=b z%d?uk82rr3GjD}`G(Uz(Lxe4s;4zpZ-)EU};wjFw9Gcw0yPN3W5H%PdMHxR{6}$t0 zVf?>1e z3k8%RO*qdAh`hVb{Xe6&1|x0;>P{Xf3$MnLF`MM+dBdSFdd{wH7oKHmp{5GW{6)<9H|KFuhpn_VEKdtr({=B?!*>Ik47||7Um}ivpo*UdV@_6wGK#Px?7-JZuqs$B@ML zYsG}eTU~aJC5E`U>mgZE5$*}Enfad^6MLv=(wBei`4n;6Mzd z_7<&k@*n?L@ji$y{*Gt*)iQR!1qAA~y3j(CEes#OImKx{IYb{hS@GPs`4pr^(O$%Q z9n(nqmqIa`)aYV-OUJ_o} zb~<<-59}3D9`2!io@iA&fBNL5dlI$ChLMym5e&3TQzAdz<3i}R-#^S+;c(EPY?{_p zuvxm264H5jbgZ{~G80g{(-?gMSt&nUM{l3p2;cbHKsv!yuKrDevjPi>O1~(e&E~$7g`6`-n(n1lX0^D49HMgT0Y{ zGlk%EhLSIAjWEG?TpAXx=RNbe-v}GvqbJGg=DDCFG6o`TRzJtGCCv=wTk`5M%PxiRSH6HzszC$)%7wzMWH!zyOVfi+vv)t#^EIAew^q9CFuv7>CLV2V-XAcHy0Q++G)K9yviLn*!by`s7i|CN_?HSgpl~n z8801SyaV*cCkjS+LUnTj1}}+vVRI6v2lKMTPWHt)t&20Ti*(6%mVnDF^eFX}_NHL! zPVE9iESCZ`GwxIvtlEMu^RTe?LMkS>X(yIWiuq`P4ymhOCS@OggU=e_?}KmMV6?z3mEnYreg zId;AYHmCuRbyFZORJqvjbmb0IyEe%1xDa5{OO#vjQC9CmUT8Y@YGL=lS-xMw)0{YD zDQ-J_#ZP2ye*Fd9?g@WE%J*%z&5J!V4Vq=Fm^IQWziA~5NjccxNTzQeNjDIV+(Hxv zGjpjGwLZlpPbPq(mHjObDtw`uZ5Y)6KvP-LKKN>@`Wdk~mq+ueG<2-$Qj#s5v3fm4 zQGkfwMOSs|EwI&*3?ijPIm2>Pm3o=F6ingH=O5Ij`FJ?4KDAwbqu1myL!i;Kr?NV( zJ5GA=7I!*(a9_KK)^&hxrX@IW#4EIf$tuitAnWv3K3m&5>ao)WH=ZbNBo7*I>0bG? zxz1Y1k!8wB4ztR6Ll|Av3LFN*!43)h0W#GP)`NuYsF$Ugwdd9M*;0qPcP3@}e4zx5 z1DAsuQy(9WSh>EzPt~W{EjcopWqQJTK+<|-s1B6u|MZTICx4G@?C_2_YbKnzm}AGz zs83jMCu2-95N^(FPAZ6PjbSeDH=2ry=Q%(&*gC%Tx}4Xkov`zZXnv@VV)i*(AI#(p zj2~$Xax$%{v#NNn`7jF17@XwPWtkuNNsHWYxh5lUx5Ga{`|jU?8W?fDYiHkF+Lh5& zUE5`1Pivy>YIIJ|gVv+X0w;gW6YANBPR!aG9M<_cE*A%e^0}4p&&j^R*p3f_otW9+ z`08V#I$6`IIU7p<7MQKt71#ZIS;Uy~OUiauMG2vS7Hf0={ZMp){A+gh_(6vcjko(q zXw!8ytR0*Ith52h1w*TP4{K(b&0(9<4^iOhgSCqCkdR-txE3UN=0tJ>ghYF?d;No- z2oEX?7%KMh(}t(u`HbwxMdFz^@XPubT3*NbwO*6&X3($S_KY7r&$Je#k|0}2VT)re zRh$kZQan%4KE5Eysmk*|4j)fW9_!;TEKxzK|8{&i*%&o4NXhOb&^Rripk{NoG8FrN zdxEi@o$)*)?vD&Sow&N*j!in451VH`xDYW#M_+E(S-Z2Y4ZwZiv;kM-0Sfs1bUU<&~hf-1r(585!8F{>*m*bRlhGt5~YYkDbKtMMMEU32ccJH=E}%M zo#yQQ1gaxO`>o;pbR$N;Ym&dLH_Hs;2dZhmW0A5g%lB^Yo0)jNhN)topr*3EyHO!Y zPOwy|do{zx(H>lcrN6ZQRGvI~~t zwS=J0RBckwSrxzaK2s+3xKm{^;CZR>t1rz@9|rw?n^&mBx@%dpbDw+pM@=<1I;Wbl zE6aCQf}@$*o0;PSjoIJYK9)bJ2s6lD>OS}90(lamt(7c(73~3 z7QV*6l4UktQpOM*O6(@C^*_OD`tI~w)G;j^&k+yoy%#^|e*fPqlq1FwFkYnfXu~f1L6@f~&ow-R)X*iYxQ%Lind&gq69i?aIn<{biP;yWZvh zMWe=-e`5X13PYV_DSnTGrqqUp7H!$Fx3UoMaj1Bf-MKE$kZYyrf=t0&h+?W%j%AOr z%Nx2bYXDa--m;?AxFDS-xf}w)%au{zDQd@ zh0sW_y_qBRJjvnWRMCF=;Mn~lHS#+bRTBOE*Z%1C8%$&s)TpQ)@6Dvl{Cy1wo70>? znP)}R5g48+3XNLdo~XUOFsgYtT~d9DHSK7K#=SYO?Zi_1f9Z^V@A4-mX_h@ zUMTY#1FO{B;YWJux#%U5mX-_xG8t%Z=+!AWU0x-v>~o~orS2A%vCBwDKpURij5NA@ zGRvDsV8Z}38$@<382*2$45H0R6f!_7V%GT?{+YlRflMIIU#9g!GPi)-0K~>KAZCpP z@|pIu6P>nU)1AG(9MB8+3bbsFR)~T)gdA%~G*sF?h8D;Lyy}!K5n*Z&0+4nN! zyqt|gKKE(7n(eq~QOW8+<4T$V%kwE-dY=uL{1zr7y+bKr<1t8(w6MvFq9Gsyhm!%DY>UZ< ztOyqy{8AAH#f-QQ>1pcnQ#fvnzkR^f797&)S-oCdr~?_wWfK&9ojOT8J8t4_NCQJ#oR+OY#SiA1K}poo_rPqNKYu*@2^G9?3z&s7oXsv$AGIHU zAL$1`9pcumOm^x4sO&73cej5P*o9j56o{>=vnWiST1+bh!5zKbE7)$yZfvpaFvuAI2Ko6)* zP7UBe|1KCv#t8sDQafpR`}`$r2^o97*rr9{FbI&GEFSFQqYQIr^c22@(WXtPuG880`j!2mxUR0yZH+byv++shncL$2pEFHxdtDWX4GH@jZ@Fl72uZ7!`p@3;^MA{o2U) zK+Y@a=FP2BT>JAo^lD_amZ|TG;~6km2spHy_<69MES#@mY^|JG2cWyJ@(_gD7gwyYfIm~4>p#}jA*0z4 z0gT^bB#(#-U;59Uo>f9>Jd&r~Xk$SMY-(yUXMXB?$WsJlY}d7ftboRei2Bc7grE!E z`9u*Q$pRta@P!lxsJE?}R+m}ZZpE>{>?&bj@&=c`w|S`o=4E6{S3j&A1x<*2L6QQg zh{1nWT_3$)@j=p(5a)}y+{vzc8jHv__s8wy;};V!&5elYar;Ad)P3sCB{=E9dKH{ts+%&||cXHD$v^1{X=8-6oZGpD!QK+{q>$U7q zss;j#<**XY7ZFjk4UJ|ji!;loa4sQ5EO6Dr1FgARLnQS|r%7)>WUNFJ{j9e6{kTB8pJweb zRL*YhrtV=O$7a+1wH#EwmynLb9M#+A$L2F<_DDDR*kN`|33l;)x&=}Oq~9imgi9Kz zPbc%~JXdvNO+L*sP{P>FwC@YTM5=WOdgA z(ftz%it@;`?BXoGe$q-G7Gq52icUCoROz3uqt~BY7=)I^I0>&x(=TU#+)J*su}van zfI2tZUmyaeAesdA(WyfY$%~;VjRU(7rnxdzi@hRxXK&jIXL8`&&S zL%2)(?cFx!B#2tzg=dQHeMxK~J+Jp{VbLMvQ$z887nzLYqufL_VWIP#_Y00`tIhg+ z#!)9C{%AH~?I=s~qy)}R+O+s@_w{mmIQ2kD-DL$kl@ zYgpa?$acvo zNBuU2sr63(;@)iHA=^R2?}FmWExTFCjpg2k;L9`4yQ|KF2S#$n{t*42+1gOAN`gIE3IgNbyWttC8wD8Su>yf6i8+pm7Y|HGF>?mG`Bo z7=k%_vZqrxPX<#)rz9a6etYXJH*S2i*7I9GqPOsHO2_W8Sj1{EmZw059#lX}OPlxO z2kP;TxFp#?RbffVMn?dgv8gE_c7B5CyZ%Zqs|p{(0D2$s))(kXcdMb+p$cLX_G*RC zkV_N4XYA@c*zJ!Dbf0?$Bvv^0MBoT&OF1~OK9i7;uxUf{R`?tENP&sXTVEPSM_@i9 zF3p7blk>T;T4{1}G^}|wfa?PFr-1&$2JfBkpgn>kkVbJ&bRUT%r$gz{5y~TXo6sKs z%>dvN0wHwHCWj*EnO2Gqr3dnp&WgjV31xzJ7%OxlI0RIdmX?||<`}NR^?>6U-rU-% zvemo1fJ5l|(9L2_n&q|=(Tjl=8kmrPO-E0k+xkSr$N8FV*=65(*N@_bJxY5lR*~VR zf7Q3{pbP)>e(8vt$`RoGW_`1F}Q#{u%y^^_U!Bo_+@AXa0n=U+sO*XixQvYs%&&u zG$RC~Sr)GW;}aeMp$mOHD$~Q3OT|S|LC%+_FnRDrYSBlkuBQECoEHN_B0A9;E7XrL zt|~$&HYU=#{bmk=gm1CxW)^U9KNb5BvXI2hgys)esKR_mXb33a{nV(E%lI#Ol99zw z7SD>Vli{v;`vBX#Y?~V;PL3~7d8^G1PoTgD=nL59{wL%n@DS~e9mQ=6z>R||1$4Bx z#4w!|bw%NOB>b1)<4sj+YD`=BS$Ozo4BGWEIXUF|R}%#lKxwZ_vTgRcw=Q&M3%fNEGkBGT1b(*D8toL6o$()Rx6*?rMv>CcPj z)Agg}{8pt4dWD3ZP*r3=`TWllhmkk>?Ohg*amPnhd{m&a!cULvzv$tyuya=TQf@x9 z09Xx!B}p;X3niGU0Pp$y*T(Y#139A{h@8)HF=;|(* z3Y~~(Ou6CVyIr^&(0`#owZEwIeHJveuP~T0L(KwZXi)d3W9u(OQZu&4zm84%8*ZYI z11j~LujBXB^#~lar|?ktN|aV4Agu7hnu#vxzeY3J%|sx?xCD}!#Y)f;28MDxe)?jukA(ei8J>R}yFT-#6K>alAfYM)0d>am z2tw^K4v@jV@;}czvorfv5}@S50#Xgl9X*JIRgF^?huL}ck@NTHb0#;Gm=3$0#Mocd z$f5Jm?3eS+!R6U6=Qn?uaR2^O{pT>A9VLymvSDzl97+vBS6@*i6tgUu^|iuy2|gd+ zt7j!q7@TSktefmx=6%-Pfl|a&cQ6^EY2 zZIn*oMl6f5T$s6hpaWZ5^aD5qm9ZYqhA!YNzfW{v=cuu@Zpbn-7Wf-NXrRCV`AF5w z=yh#auhNv>?sA4IsP20KNQqM#2B>yrRnFX8jIbU!!Fxk{%o=>_nm3nnXf&($Oqi}N z4jMQ9Os$MRpj|LDM~xk{51XO+24B&W<=5P;jtxUDh^CJF(x{R2uThuphRd(OI#gd= z8Dz_^xR!6`9Ao5FEh#WFB*s_85;P{qt>Hr8+`N&B`Vb~>`U`g{-*F095P!o!kDesv zb56cCMP^~qBmFwAA`@nD#lKh1Xyhj$X7$4ABcJY1YRdSp*pc@{f3JI@P;;~Kz9CEw z;inlbe#PnB-r;aO2h7E0(?yx~0EvBj`h9Q;l}({08)=H?j`a1nIan`Z*6WJ*uxf;;Fz2tnW}40VG_Kfq9a7H=^mjXfi?Hky zT8EZxA22ho+cod6;+^ozmoFsvOt{rP=x=tXb7jcIhA*m0xyZ9~h37>PDYAX!R<+N< z{0h!rV}JvXWJYB(C-94g0jsjGNX+*cd{uT-8x%FI8Tw0)^=Lo^;Q*MwL>C>`apq98{hNRj&^Vu)^Sr2U41b^0!v zIZX(MTjW+i$mc{uv;8#bcD;Z6YA-6eP{1JWP5Epr8Dd%T)Ku&KbCt!?*zb((Da&noatZ|lNRg=Q{Bp-V#osdlW67a~ZReR%k6XS0Zro-#@%yIX<{iT8WE6X= zI|pCLm^l{;dPC+9+zQ0a<t6-@SK?cEz(uiZ>P_c{Uzi#pQ1-|FmT@`czw|0%%98CoY-4RCBLa@eu|YmjVCx zJJ9_k9tHu*6e-ukE@NUzL;S=H&sOGSZ*+NEcde6R$Ku_R;p|x`?@whpdGiYeX^MaZ zIUY^DP;#d@mO)JwuqoyTy>~8~@6a@QUS)ojv}~dG?zPa-#7#!4?&iw3_&n0}Igy)j zCR&w@u3)Op+}84^*{}GF6~bP#zjIh%MIN)_$t@uOendui9oEEg88k<;9s3q4V5%$Z zMPSE=QN+W5Zke{tlOjSjamna1(aBK}P7Z0*MOR9oTF(|y2+QeNvNr9$Ga^U1`>z&Y zk`T$#b^`=P-HD_J0&q1~Z&xNKc|;~c^V8s4?^}6}sm}w3b*dSn^CJQC4t-Iq7xoqX zp*Eot-?b+b4uX%0j-<}9;$r0Rj%ba-Wvz4W?Wu5ZOz?*t@|wEE3q!)YVG@^P<>#{| z?X*@{#OT`O)0prSx+%GYzR%3y6VnMl(cW<|##?sVuM#|;vTek@wAIh!z=d6FGZooG z0u!BM25)vm2Q0_OxXbk_=*Zbp0LKH&*=O~;zeRgzxpE?1^j_`p1>cH9<3{GlE1qm^ z8$kAV6)0gk>JwgOJ}{Q=H6$)r81c?krmh8|&gi2*b2WJx>=K_Gx3x1mg(nI-@pC(^ zY6e`+Wdpg6S9o2cs&elJ-;$4$pj_bxY`e!mLD+eEIk9|+tF7xA5gfe(-d8bWNp{7}5b+D7Y#(kWb5Jmd-Zjz<>2FK3dJpFaYmryt5>u>{m+ZZw7 zleerWKTO3^<&7p``U#C>6k=$mOg?c=jhTOMFlxF!>+MKS7Pq#64@KjZmOozkDW#_d z@A9)q;&0td{F~8*dIC3?<+O4FEN=?+G^3z2R2eRE8uu zJ08>eA!B*P`Uy?dN{Cm(m07+0X83Z}GxSEh#omMcTb>U_P5e#oy3(vJhkPn;Ps>KC zHs)f@)9hjKO7CC#T@H$}4ep=g5tO2Q!u%j}s-di>FBS}+%(SM$CcR%~Jb|G&ho9OX zVcGwl4xl?5)}@K!KTG*Ro_ImyS3$*FtS9x)tPu8E1Yat^MW6(t<`aBVZ-cq}J%*=k znvDRmn6Ez@s%Dtd!L2hZyZP$jvTUV z;O+ar&d*k5pCOM_GCT}p>0X{$TBaDu$c0&ys-jx7TgiRAYUS5ly7$#J&hVsi6F9PH z)A$ewl_9S?laIajkcw@)5X)Q*qoNf|q_k#ek6vZ5AWJ87*d`{Kb}(S44yYM?uEHo> zx7uM{pG#qgB1MBTGxoQ{(4@BV{;^#Yh}GOP0r6EaZrkeI8E~5=SI$%vQO-<1w=?P; zjE8*q^_;Ew%~cn|^?^UC$IioR*C{z+>Wp%ESMr zP@q{pzVfV5^rPoMNx5MiM8V60rJM(}FDnu$T~j9@KH#`SO3&S(Z9bin+%Uj6I&<5t zp0J*rZRRi7w_*VQU74Pp8>uUw7S0ck!fflT*Zj@PF?cUj$f|6nLT9O!e0I-naDc0c z3b8EIEFByi%F9{r3J5A)w>x?}MIJ+FyifSALRcM=XF5GbFY2mw!NPs%AiD zh!pL95t5hw67|F6j)u5oJaCMG|LAat4<=w<>_=<)KT#2Rpp@VAUvil;1xb&fgXvjI z8ynzU^=y~hTFFlh>d&rR@bW%u-$nHP!7k(=>4*9NOh^=F zQBjd*Vz42;rr3&}FFD2cr-o%9^_;N*8if;00J8P)<}R>-FYb5Ws{KbTT+&#YIoZEH z-5K!dQ?*OykU@*_9k;cg;U$`tIo(25(`6(TToFXXXf0w{-|R#_`WDq^1}=`i#`(h~ zhq?#HI9Vi8L08LWoVu!1x)b9f<@J)BO-_7niMs;&QQ4obOH1f&aqy*hm|eQj(gvI# zO*mK#~o-M;wM3uyUKv3gG=x zKq|4Qo)(ho#D_mABnI$t9YE}jI(jf!_zE*ZQu7-jU8BqL#wh=Ma7zGJN47zzFD?cF z8timNw#qkUg^W8F)2Qh`gCxu#YcfgOP^RUq{*DlaGdIT;?MKpKk}3+@KG#{VS)U`)2`V5Wk6 zyt~$rHNB5dVN#t4i?S#Bxd9vvL`4JpKQ9`sqvK?`sVV<#;}6I8Qq%BKtr9pOINIOl z+FEZv!z1_h_vZlWHIYC7L@5#;o_RxkH67su(ooM3SATP74+rhGA!^L8+`QOYzIfPM z^zznmxdR_f%cSU!-OMc}L*Ij$7BoZx5-S6UUccydauS?b9z-z?gJ@jWsn+g4WwhFk*QJW3uZfs+Pq^QT6f=Buu&j@?+lGwzjFJE2 zq#z*7xjgdqqSK^08vM>qvn2K^?)7+qV(i7Mf2=87ORdl(!?a&uh{4q^ucQz;;ykFJ z5=|lSj+HU`z*B%#*p}lHW*%%*4xLM0PSK~}QI>j}FD^)W5|oJuRtGvNDwvm2S>Z^^ zI9b%RBTO?dba_zIELPH98a!A(ybpblwd0zxR{Dbc;YMey{fbzi22bF|Vy3x0#d-F~ zelyh`Vr8Fzb2|Te`sIf`7Ai!Ad9t>8c;ALhebv8s1biN03bb$YLA-~pF8nI2eQJNQ z^PrxG)^H5VXI&|EYn|jOh=*Ac4CxkOy%Bz^I)rY(EB)h8DZ3a$!o?vMRtqD%>m$@B z5F$--@LEkv<7@xh0K389;{6aCa3}3e7YCTd?YNUD_2a#-66Qk0G)(3K-u(rfc_~Ud zI*z|k;WCWVMR)};L+qbt?NeO=?b`7&w^?OtKJ~BMa0U#B7%KPg$->0LMwK_dhL$xU zNP2jRN-RPtVB?Z^P+XnUOmBK@-0zw|EvG@Z?2AWBsfde!7;w5|`g{G6nM1B>58E#~ z>z!7wnY$wHUOR=|xHxy9KssJ?&=Aca*jK)z6;O!^Iq;Ol8%?M!tgl%#FUS};Tlr|5_oLo?Wc4np~yud+7k{$ zCe#>m?@b){0X%9soE>BHO(G^9X?Q>6`TY_Gwq}Ho>2)d|Ie6^C{ygrv4!69E$mx;9 zxQtYamzJT(!5^qjON)ymdALEfwl&yU)J1L?!J7x2=rN%YpX}{|&FZ?9*+Xor`45zM z>=?aoSR1mD@>35N*bgI7+z&-+|D^8$J@eapdwGqG9+%M)#uGqEy?0|BO{fAc`m0lF6SKppp_S0ihiv;(L z_j50JHn;avE}I%TS%Kq1AUOdoR{{?h&H~d4C(5=D+#0am(P2}-9lIk z0!08~c4duRIuUslC-lH#zLh$IPER~zDC#mFS(`TB>0Oj=!#-QX37P#bw^cDB20mC{ zKMdkToYcyJpM~Y+VAJYKG9;1+zTF$t-0iE1i>2V z2!2Y|I)@g(rgQK_nA>Bc7K)xR=)@Qe?YN_ODf!9CuBWxN$>8OD7LGFKM$u2@`{q5K zmsJ?{d21{Ac@c}dizU%$nUb1#7s`bbS4w90y7DYP={wtx2DP=fKk5=e{qKbwCX_oe zF8a`|tfXp$0b8SE#2daPPV+$8+xa}mU?0>qNliI4Ci0U%WgN{N~2a&Vmq@{&X(i`fXmi|3&3;KFM84=^BU zI%Q3YubRL~e2VLOr4teolz@X+W!=!Y7y=U2gQUflw~)UnRw6!uJ>lIT8Vf6964=3bbgS?XnUQA+{cj zRyY6sn#b>w`*Ii|L!fJ7vgv=wL8y*HClZ+ZwnCrL<1;E~BgIsv$AnWFtv4P%g9aXn7nC6jTntQ;uB7^ui%|`MM7MzaGLqTzc zuxgY&g=_MZTv2Zy#6Cdsr1!+V^q*Eh3AFcEzJLE7wqB1(qZhjRTqC>8W!Na(>jMzr z0qZaXwssfl`r6#KnR3h)zXlJl8ormA$yD+K7CWZ>PTZIC_Gfp~^Vie$h_$e2ZH&N= zy?1w#8KRM^z1syym}TDNThNtY$h_vG`I}4_zYVP2b7|D207;@|AiDtQB)gFM%#Ua} z?7t9o1=5d!o>LDi3j}1mgom;emj%z~VGT3BlgJbuZPxx2C2rn!76p?m*2sgTj924cd7XWv8=zQ^sk4?IM7jH~F-^uaQm1pzzQHp}=R|Y@594fk2cT#v*RDn52`Rpn!tT*WB z@Yn{K_Yc^mq1&&Wv)SBz$23u6$jEgYXxBmCM5cfE#ozpydv7y$uDM|?=#F;YjO%9a zg!X}pWQt3u?*0yQ>zi)~zrn$*6ZZl2K0owznWr~R-yI~VSLqgFU}*RzI2c|ovk_e? z*38J^&LdU;=yybN_bj$JZ84tb}1tClI0I2+x%43aXh=0`}~0Wb&`jU{^rFp z-}gY%5kps*m&h@#LHwCFVfxR%3P>gp0xQc_rl2#6Lk+|r$VSFS%@{OWMAyXsOt5LO2q?7|;=%8i!7tpwWj z_74T|j6FRZgP9{uMIR7VofTYHok~feCl0m-WRUYShjcJjgXRFPN9&s;7?@I^pCo7` zdPk?`#fV#bq}y+DpqV}oQ?0p2`@v}Op&|9%!2FKw=4X2S^~?E(A$h66uBB5#^t;RV zZQefA4-Hr1rgQSHt;e$J-eHD3nr*RNtReRX9x_-JUpJ~*Vi^oR-EKq>l8ovZG8ZZ5Yp%6b~Ne23{+19XSm z%ov4v%Np867hVf;;|-wOz_qE2{ z=--pvY`KkBoKJi2-pa0&`)%Z4sUJD6M<;Jd2{>+U-#RIyx}~!cr5b|2+jW0HKff!7 z7{u!L-rx0Xh6qM_r-tj}J_R>L78QxDKs2{rgBh*B?$-*~P zRpxJLJ1-B#>hKY+@?~J2w^6gxQwCtBI2ciPZTAD>4A7WHoAsAEPC z_l0i=KkO0kZftJG+iZMjIDIaZe&V%cSqSrjo)3_9PhwY7qR82Sj4l~*f<}EZ;8GS>pZ%xxC9Q>fu*B0&2@C8PJ>|W zseN?Q(nckpr)VrhwV1l<%#|O&SwGHCRq#c&+|DkB4U2$8PY;gEf*WNH<~mS>URN$y z#DympRTr@tHG6gU<9t}}hA{`%*K@FNNX;oga()%Xp8A<0+`-!YS+4p_Paib!>9@&= zG`hBJs>`d$t=5t2`Z|YB{Zw~DJs7aA0Jm|fpm)O#>E<^o$l-VddCZA#e65}S&n_{x zi{}MMN>~}d7GnF}dsuj_KU}sCi(TH9l-!@>C6N#rYy{`f;`_(x{OY$Lr!zBpC+d8g~R-vvV)=3ywJEl$vXw21imKTRFW1KiWj7Y})G^$tf`>Ae~dNx^}X z7~_kOCcnOTw^KNOfdHQ;>1WQT9UxNvU`3}^7^CJsN?6HgpHN;Z-MOP=Xywkrzi>{@ z=1_8_s0N6OF%eCtnY3pj8+p%1aU{{;#|_Owi87l5ahFxMc%gA_Yd2pWy!LQniu5H6 z^W*!mJR3}*z$YNIr?XwzOGG`akzDCr`bBHh0e(tB)ylq{z>=VUUP_jb*3+r;>na~1MCz~gB?@PM{ zN?Id4Pm}haJ=Ql?e}vt=8EXX&i%B+!{7e1g%ZjsFK7KjTe{vmP6--R1fQeCWR<|`F zd?YdJMU$r`g}@Ev*=0_{na*m3oxh4p%MY@;S%E8gSqPVjP8wjZyH#=!VNf0zTukv&k0Q7(_eX`s*Jz(RPauAv2kesyx1#U5s7;By-pEPsoB|fwHO6GLTjr*l>YH#`1YqR$REwiGbBY7Qlko)vf{-X^A z3g+<#Vkz5VXuB=FU?f@DJs%?Con-#>)3|JD%P@(7CF#90B69U?CI`F6REUKa2x!(- zqEiflz8gIE=k;Q$;YKGb#Kj3-iphbuD}jeq3zI2qqM(o8)>~X}kP7JRo_QlSXWut< ztc|Hs(tTD*%seKH1IP(v-T(+zDjfFG?ni2~e|M65L+(B*)5AtK&y8Q1*UrO0$~7GC zs{i(kqYZJJFGdz)23k~zSs~Bv8Gvp^KV)?!6Q0bU3(Jr z5tq^GsixTIuYs{9Q=kG5kNNF{y~zjJ#Mxg~Bc)WkL8))u_O1vj%;bO>KiR?`CkLKx z>!th=6k32aTgCl#g-(@T1pe&_$N0+IE)9K*>Poo;R`??5&=)f7un-A$0SheZ`!}*Mo=T`% z53Q8hn4Sm6ro~}hqgm#6#Ps2B;LPDz^(FaL&P=2BTU#z+9~$Ay`8M6F6%6d4TP%1u zdL`EE=HOD))V|uLb3!fbBsm(hTfS}SFXkgp6lz>J_Q4^xXtB~XFQocs>&wIXBb(mx z=N;9~yfK``Mto)AA8XHoE9=iuP2r2)1XybGB`-PfOA4TBloD>&g-Nq110B3S`RZJe-BD{2I%FbKZh72wqIa_+H`ZwSL7+R8UIE7SXaxs+m{lue zCG2~;;iT(Z;kzdr!B)k4xmV14!mMEr#*)37H8bq+_>`V$hPXJw6^NxF2p+4^-3z+Q zw#n>~5xyj82RcH^GcIEkAe;TRl{V=3DGVq$P&CPCWFe3GW;ca6CSYNX*M;G4b zDYED*Y--}mKS@WUQo#YaSlDB)rdPiLr!=70EWn2rN-2!84$eBU+UU!9JuJuA+=KLU z!KjPz1>`Po-(=IF6l%hYg4FA0tmR^7|A>qKO8PxFN2s~S7%UNBg9h3djWv7W`F!`_L0pu?j2<#w z52wjkNj8cJZ_tMrJF?y^?Cm&wNrj61Hd`ayZ$X)!o|dw*qGvZ9OkRnL9xBnQUK4yA zju@w04J(l}AOTEdYzbx0{>3i9NK2dD)I^A{18;Q^F@N+;Lut!mtHt#}h>%!fVc8%! z#bJ7LW|uq4aygvt(!+ki-RLLK9#29#*TwzbhKm_`{_cMG;2g2254#Y}?3WaO?_MU{ zq-CiV;VExeEyI)zaJ@=SwhCn&cFq+pR@^&JS0=A5v8ch-!5-E@uCJOoywlDK)EHj4 zjSA<3nRG8@AgPb3=1(y|0H~&>7BD)z>8PxuLsZ{C{!tyr@+qzZnaw)xx#?jX7%C*6 zam_c>osp>IW3i$x97?F@dfn6X-Z&UQE&HpADwG43lwEXIZ=js_%` zx`J>7DU7z`2zOM*{Lg_C0;$n(V50&gd8`nehOUlL90YWI#%}nE)p_wIM)LSaWf8Wr zre@d(q?-lByE0||9i_yqHJ7&#S#WT0plz;`3T0gmFZ1J~DSb<>-oWcP{R23%3Em31443qe2lOt2_*E^5>9^;`lv}` z6h#4WT6#npBdtOY z*c&r*EU=7s^}l&(F?D{Y{T+vE#H!W(A@V6=yKhut1Q>$ffpbdk(lE`7x{KEg|y!&~}x=BmmCk%WabN)9lmM2H@Sd}^$ z1i8FUTR**CkYkEN@*Yogn6zW^-YV@SFqxs`aKx=?iZ_;OUp~Pj1x~H7?HFl+TTu3w zUJ_6TPqCbv*RgLD%F4|(84(Q)l+b6+ACk1V4WT9{$A~&5Ltp?-%wwqj^bq`bj5~RC ztt>6=8+9FsfBylD^*QKYIQKu9+tu7n!%If5HR~C15UAz*p?xihBHvw7Ki^k9JM*bN z-Y#V$l^R~;p3+hS-~+w>r#}QV^})t36&X9#3NIiUj`|O}h3d(c!G%-aMSX-huFf^$ zI4NlPi!1;kNO)tXb0VdX-}oRdu9E)W{(6kJ0KR}gbgwd+beSxztY}=^k+RhaQDbsM z=nbS>U!9fK>l4@eaL!rZmuKw&DpMKJ|5Plc69C4iu&fMi!L?C$Vq)T_gZMgq1JWdt zY@pZ#Kw$&xg1vt=$#3@NJAen7oeH9XY6Y;^r+#XH!UEH;&K>apYL+o21 z@Gdx4{RYIL=+ERh$3v9TEoF2Dt+Od2n^c&xYv=7y1BXUaWtV|y*t&?ax4UG2hg3f>$<(A?wpdzyTN1yeT{IvN= zz@P~#E(Wy7FBcT1`p2c&4w_&`#x?`&ImTKFI|p!bfP35gaS%dEIzPir9@?vQ7Ki11 zEre4opXQHSf9gz-;khPxx-0+yr4L*JwVH;1l-^hZbqyAcM+9zh!u{$ojpKk{8YN*r zO1OmNp4Yhx<{}cT6Rdub7{lV6Uiw8{eC_Sdv)c0V*s?Mvx$&RC{Y+=dc)-Dpqcl#T z&bJtwoRlyyFlY&VDpNS9YH7&;pugfOFOSNUL?1&DktzLV2Um*qZ(ZQSmW8RwIK@Jy zflOfTi@(1Y)q2@L<+NQGWK@iUi!0>$8k-O~d^y>?_2~?hl>{s;rafSt$!rRS4eln7 ze>VZMGg0)x!qTz}V5?$}&;=iDC{FX(vlSShldq6Yc<^*%m2?^qY}VG+zQoG-Wkn3c zK@KHaB*}OH_a!bi(^3ejovxhXWmftzSG@+|$6h&Nm{p;Dgum{{fb`1PwhsdBDRzV@i@;-F^W;)<^VI zytDh;_kguXT5s>tmuCUoJ>Zjye*kCsx%hk?FRo#kO;_yWjdXvXuN}a-6zduXC^w#1 zb4SM#t?2b4!GJ$NWpauS0&mL<92oq9`I+v2PM(sARv;Z8I2C;jyT=_+ zm*J~`4(zPK@xlIlDIhIDOuXu+KLm;=H~D6FrT%K)ft_^7LwX!=_VW$< zs*siz+JN1wtKc{F{CwH~=!aPfpI@W$lne5)FayEPBal4qbim4K%XyPXq(QL?&bey2 zC$PGs2}?g0%exR(KfA~G0u(F%>AICt`Ztrl2GwgnP@%-O=$m9a=VJ}F~ zH4cZygWsF}#izc$9%#223bj8c341hxbyR-m^ z-6Z)c>-^~5qEXF$z5g{>|D&wxYK9E>=3!04O3yjgH3;jM@pQ49eb@ zu78JJt=RC@j%hxUbh`TXDnt0_C(&X8sSh8-Z=TCEaE{<{18Whna59TLs?NP62 z7_(Mag^zDb1}=N1@z(AS3;?ZM>@lc0!DzTG`6M<~tgbP-z|V<$%fxSMC;prU?zP>U z0)sY|L&h7|R&acKb5gs&9qIX%?A02)!6%?uFJyK&@}g|5_IUg)FplrmWk`}Zlo^sD ztC)4VPSdbm;Ah%>uCRZ3u0WdNhcKOyITFu}LaZ?@i|#mbK)U*4tBCl%vHWmy9L*49 zben1Xui?k3YG`Q@H0T5A3^*=IIB7RfdBlNme~8CirP2roEd#fjR2xioPGyMb;PSyVD8!?rm!&UcxFgIy?%E2SABVKbZlz} zmz&>Yz8xOwgJ&9JI`yo{H&tj-pi^e<<=%EdrL(@!);Z19J+JUaDKF%>mCQG~XVGtE zq5Lkx&5P~3dPQU?nRhsP>xz|UH29!3b@IVIm_+ChI@6Jh4kh;kbtXbGOuhOXblvaJ z8;#rD8t$({-IvGx_M|i%kAN#rDo<6)cr4JC@O*y-3%e&>K_0@?rZYsA513ZZn_Rs~ z4vv>0NSeoejrWHfxlw?JcyR#Ay)W^ZF&n+X-$-CGHuQiY&_ll5h?7z= zcK0}FYxZzn9=N<{jJym&MPs-@up@E9L2q?Lm?qWic{knOp)+L0wz>Fl{0maHax&7| zF>h0_vT%vX40WTNRv7rPcS~0Jig|yllp|rJU?Zu#qUcO_YYS#@Wx}eh`)VNH=)`6{ zv;H=`we6avfVc&Z>pjoeL@TcsRL8ruBoNn*)hYcvEcd|oB=h#T9egA_k~WMHjIbvh zPp>bKs6*xzip9KyTv7cnt#O>rOd9n6s`~1%sJia$0fdoOco4~v5D=B_Mp~sox}>DL z87Tn?36V~vQ*wq*De3N^L3-$h-x+2^t+yr3tCPmSc!bT{>98ubXEm`>!tn?5ZaPfv$NXk2{K<-w@~$?X zDPFdh+_$@v!E`6PCh?tFb)5pTSe#+FSJ_pKky8g3okGZU9O}E|9s2PpA&i3QZ!cZ7 z1slZNKW=71XUw$CsJeQEGJP@vx79^rBVpSaBeS@mV7lU_4-*R7wE@&{Fl#{UF;=7% zf$X`s#{m9>2~2v7c<|CHiPgdRH`=bKi>W)cg}Z)l!9Rc+DPB~%W!+{cv& z&TkPfXorqeSndPWw(d)jWSlhKQbum`rP|#tQJ%;F6@z`&}RPJ$+G1ZimvO| zSf4kO85du-dUQ$-KE%0^1>S&4vw_(bX9;TR?b+5XSx^po*}QH8aQ1LkIHv5!^)5EbSEy^|R%; zF+iNU>)%|kr{MdF_kU?v$lT#_afvp{VZWVZb!bj(T4pt; zY>p@FU1{^VPHQ^rU+9p)Ve_p?7kY3Ss#EQ@t3JBDxkFVht$;vIW{$!L+i`iF; zv$0oME5W+<&H$Nn@9+ne+rf~9=yEbRwK+aVuLE-9N_&~Y1D^LHJg5skS(_cZj1ixR zij0re`GIJRpBx(gBsd@=eU@pR-luH-Y;FAVrk69=;AeDTpU`QpsA|*E+lbj7tU7Bx z}lPS@egN3;pNstek+*eLKLc` z)Do*5GVUctEa^=rc;p%^W=%g2&ns#YHt9IfXZrF4;=jAwt|e&Up3U0L`(v6r^n54X zKXHp=vrEV6e_tA9^&a|IJrK)qLD!zIb6BBeDXe$%3_R4u zFR;?JszrmnZ!U!lE=&ua9+a(8{|puM`GL6AYFTtzcU+lBGrmo>Gd~yaH=>ijM7+{+ z@D$d7@Wfy=UGVaF(S>iVP*h*y7GG`u!0gpVYQ0|+39f5&L+7+HOm<;QXE_&~n7^dm zeV6v=zjZC=0oc-&aKibYr@$Sa@@3J2&nIkt3}w9!hEDvC(k99zl33O6;m5BW@cfS< z=vOfI4&a5M?|dkJH4vH(W*IMUY!i`~H%e~-zz2JFTyw(*{SV{!^Z)}k4nT|rSYm81 zYTXuj%DcNiMs;6!{`&RnF&%4sv!wxHYN|;2K{-~hn1E0WqF>LQ!>L;#tmMVWw$sQW zEIKBhY|)*eq0Vh6J~7y-`6Xno&Q-#dB~iJ(?*XgcP8|}cT;Yl*B0W-(tk*!cVwM|t zr=l@UZ~MS3di}L3egVp5#j_kQ(%Pp6DzF1ZY1B0|REG^XYAnYJ9Om50HPZE+`nW;W z0J39giQaQ~kYnGBmLBe&esb~v;knhG5YDPk+ZRs`z#z3oZ7PLhcJ@8<&m)%5dRj?f zqpFkSP?Cb7+PT{*Qys&^KJD>a7Y-{so7_zK!?BRAm4DQ6=if~NBO-G)#qz);!-!j5 z`E>FQYlGh-D{_U}Lg4@`oF?vhVt82*otP{*jE3%7et;VUiKj~zlKGHnw(?mtH1j|9 z(p^8~KeDw*XC?qeet+{NYBm2}S}XD}n};tH9c@#4y*}ze(*rB$yFmf_I%EcSk9D?i zAGkT9aS?F-Ek_p$)C@lCFjx&HCC26hN&*bU4!Hl%Ba|c(2P9<|JOLz#Qice^G6AMR z+cZhtb1rIKe|6lib(b^6?-;;TwboN039Ms8{9;s0ORiHG@QT*a9r3T51mA^C=9IqS zYd>H7YH5!o?|smyhaOx;OIw!nmukW1mj!Rqwf%wmQQSiK>*=f{l(Dh*jxInxm=^X{ z2p6N%D)ix@4@IDn%R-gn@9&`)FbbqYF#|#0@hZG_3I`F`aR}STV zzZTy%bQ@y*(Q+Pkp^-V=uMe5Kk(5NSq5fUt(OJ=(z$G6M@j$nP@Yk<*A*V`2ZvdQ< zkl&!-@o-AsBF$5=_6XAMZClgYISNf4y0`A+T3q5*0OVd;B5I94?^+4KF#&;P(MP5v zOH*5e_o+sJnB8iegs6GueR(Ddn`Vlg8!?*ivfuvpVCCq>3KgFh2vF%Gz4H-{J}xHq zzUJz$r71SK`9hhttqHMN4ED&X=Z?4xWV>*Nz{SxLZ+e;w#tj$!ET6rY?50mz=fChJ z?GRk~BoL+E^^}9cah-Q!KV_W&!XARsaqH%TPa(K!IO*jze?vNXT--c(*mx-}T= zoK%E#<4dA4ym@ZO+}JaTHH((ZzQJ6vRDiBP$=SPo>0!&aM01`bo0Cbdix$ZYUpK` zVC?ibnJ$8$lkuI`$pZMk7OJ`I&+EXR@H;S0T=O47;o;d-P@dXy9Izhb$(?YXyHr|+ z0%b(}3!ix2$;bMV5;3k&F?Ufh*Haz5$Fc5IA4Rj&)+SfTB@S+5k6!-0aOCa=87;Wh zEeqqJ{tS6xYMNc3_?QL7-kVtOPo}80!OWEivvC)g_0EZ2lMM7b{3cyDP*U^)whAGi zTev8u7#eR2W2jEqu^y$7QbofEy)pv=q9`RGv*uF6X1=7XUN_w`OXecn;%BgZ^4gu=tC z=YbNoGE@5Q9AtYZwcYoS3@@v3iSHvB^u5-;zL?X*stE`zZ_}8LXb5yvJDilB;^5zW z(7SwZSDGpV-Es!7+W@ddqUjQK$h;d;i-g>RIM8tjsTGpCo3iu0FOw2;f-(q~vs>*Txhd;1>Xh%m!6u)D@1mR;9Sxe|A z`tOhI@G@g1iRA5*@fK~lT6SemNM9`r`)q2q&T%L@J<8KtqV{qp8(^Lt3WmjX3(MFd z8~@sxU0MH7`f~H|bU4s|W-1ySt);%={u~{YMZ3?Fwz%t#Rd?^wo>$p_4ogP)k-N@% z3Q$q1z%*?wZw8H*FBFJ#fX^_R7R2mIp?Ggh1y9(x8kdA+O8y?h7ym*Wb!bv8ZD7u# zzl5??vU=eg`Ktv<71?h=bwhXR*xoOe0OVONwH*U$`8@L4S;!gY-cup9s&N^P;eu(| zWwHXy1H0I!TC*fQ0meKG{zj8_MAis}N*GfVth zzDJE<1_HhJ0TlIhB8SvszAPRPasZ+OLDum=9i1Yi8a=@%2dW4oJ%1iB1f_QXt)kIC zpuMF))##&ZQ_PvUjXUtEdW`QvDS|s<6)Rn;3=9>5%kuwgDJ4n*#|Op)NvS*ms{2c<^)EP+T$@@BgA`80NN9r# zVq;@zBK=(SP~kXP%6uGkdRM%*kAD)COv3%2$}o5pwwUA&s!7t9Nsa9CooudtBf9uvUM0#1M85w3srj>5%|!L@Is!s*kHmegU~>G>{tpLL|or0atp(JF_+ z=IqXPOe{`uzxp`>HwOA>))3geHI7Vd?cvEewLPajvC=(Q3AmcF`X4@byv}=aZ*w;2 zgeW-iC^A`n50-2#-nwbiw0mrP*y|XXl6>XHpc?9AAAWL=NEJuPxN~AgK62s*+cqD^ za9MDQ7=zv?*3z4{2ENU%DLxs`2%xUt^?W_Wo7tZp;GAGcVr1GCHgDt6lak954zuZw z6DZ0S{+Ly}KxiAY*fwoKoWH3CtoW`K;(P&;Alp+N9i3#Zy*?oBf}<4EG19zm)Dwq( z`}WACW3IW$kAkj<(=XTeP`bu0+Qj^15Vm71(9nX5&w*>s!QCk`ow~GhxWMimJ>hwY zJn~ScWF+cu>w!Nv8TyI!D6FVFFh%8>DkM=p$s+bGf;>QB%!OgY=LnK3zt- zHUYa+jwB1nFJS-dZ<3>N5phIgbfAdehydjBY%3+={`p-sVzsj9Sa6@3!yDE@x@HmOBo+0aa+0p2h4mS*BZUuzre(#ab z*8dCSYOOie{a$B2yGUVcH?}tu&mJ?u$^&8j(H$$7veJ}kO7Ic~y zeF-%Qg$U}0o3@k1jBcR~&7%7n$ z1SAUr5m3lUimSy8ht*XDQp*rnG^B3tZnVh`d@W^*ccw^y&N=UHW)*fyq+2j@!lV2t z!Ee?TE53)F&sU%Ob!tr{^f4+nedy`e z?fU03ZEzGv30lXqe1+C9_~CF&V}dA{;$7n7)Xw^Aq&-@?}K}+YiptJ6o5BQfm79 zG>$M_(c~R_+^{Tsy4ev0r(jx#+i$P?+F`_lo?b>CZ}YvkqmB9U9gYj1*=ce^bsqT7+T@0X)mP4U5yl3JgotompM~iO zan&B%`b990m&N?l58IS~9>~*7485{a1vmWMBnlHn3Gw>1xMPw?le0K)SxLf%KhfUo%gCtJA$-q(14cy4(t{B+7^S6C5*Bf0`F>szZd zM4Q14#ODoLMBcw|w{E!|FXC4KpB2b?qd`Uci?vTeKW3Ez#IQHT+9U@edg|)!+!MOQ z2O=U`fI3AY*D~SDPd7cMe*QNun9Yj58)DeV3gBC!&3ZKj%AP{gU*F&p;A>1v*fx63irHJxh8f}R171CZHNb1#-a<&_ z^2W4YS#wzX(gm0FyVeSMWaVyU{eu=zH2Y+*5*Lm=C2j@qgG5ekJtbK%r|^{)*tNcnEo-H=zo23g*ARcC+1hkoP~02QjqBGetog=98OQXuMRmK=%r zS0OFw>Q*&lj|T&qhL1#>nXilrLYf@8tHs*xUI<`JlEDlhNamZ9=9Uu5DWufrNIyC^ z<`E~l^e;j8UFW#2bJO6-5#v0rr!SJ)f+p^GDUGSwUs+7is_WifYw z2C=D*%;xl|Hh1?3t1f=^9rO26`bsbHw7HwbJ3`P<1$qzAAu1!zFJ^sRa_WScm%mGO zW#cxnKxmkL=etcB8mzTpOcRIk zG(g?UVjhe~&6!mMJWtN|lBZF{%*B3%W?6KmbM_VsGq2%z^!gJ2#K4no1V1LyfBlI| zZ`S6w8IMX&PM5-_PAQF?eWdW^eq@+N*=21L@+>#kc>dxZspvsh+DWtTeRq+|cXLB` zvpZvgLl{f#x>%SP)>V0xPk&@nKIGZS*T?;RzDEOQmp5=F0@drRI0hmMK-`JW7|Aq) zkkMvHC_y$=7utbusR})@@n$&{a~6~GPH(HI;-vW%NrIt|?AZUzEmN5f@>6m%6)uf2TM zZAN^`Oa;0*v^ReJVtCGqQ8yp~?|j5L^0j0dTl%Zkv!jU=SDuO;I#O6%U%iqOr|3qt z?|d3ZaHSX$kge(K@DY}jILCgLrtwpp1efUwIP>*(wr3L+wUl`p`-|&gYh;LDL8g9} zyK6h~2H6ht7+r|Qp!w?!V}+~n#n-&AVbj)w>n&TD>*DE)x}7AmmkYEdf-VLJUa*6; z2ZEOnzNcCE@Yi^4gNkA(les$&D1&aV=ci{KIN*fyE)BIO%3AzKC2h9~fp1rj--}x- zOyO>vaH$3gL&EojAD#()m6Lyh-35{-hic5_w0F78{=tjQ5a{Z6TC$yL87By+e9ah9DLg`iF^NyOBM4jCC!6Fv zWMb*h1HB@%-TN zE6rctUITN(Cz)r<^M_+?0EA1~#Xnz{yhp{0LBZzI#7uCui$8mwzO3nTWu$vm2yvXi zCv`d_*&9majEre?rQ_Wd4I?v(UHQG_IHLUPCQ)uEa1fhleS6;w)ZvN=J{BQDjPu?P zP|K{U;w~7D-q@*N~9)?5`41<16I4-5F;R=t!fXp8d;%4<+yywDq z&ZvhzCn+hJmc{3E&MlGK>H!oAWv7k~58Y_Dnl7Ee;(sC!(I0tOia7FM#}{k~qkA3` z5+4`W0i>a7l^TlwI35r>#A5`+Swzwqa^z*rAiD&-uoPX6o$+qt;h7p-MKhKui)ckA z14TyLlogXZxnCI?QmKw|)}v!==LXj2H9V=OHU#*M+s!KWe-JC$_p*0NRzVF6AON7> zo4{`DFT=xAVb&M=#|W2xUft?2R-leC4hDOKoU~ZhYelC1$sN}{NyORl3@A*eZCLA| z{r)KO>IIaIytj&xMP>_*DHBuE z#l!Q`nH~2Aggc=Oeg4#rD{%j5X=w%60?Xxp)L9V&KwRc?k~I$nP^PZ6wG~LDMgdIp zG@6jt@n62=p^iJEmsyXhP#kfZg5Uht*jOnbypM^AnU%dUN}4DO{3qZ+(qN3%*9)O| zuz=o`uhBzx%2Zj)gLCit!+t>^>#N-hsI~zN0R4^C6o9DkMbg&*;viThPlW)&p`>Yp zXgi&xdMLo`1N`xh2r9vMR#usXg-;P}_vI{sJ_Dm+x0$XKhd*IuT@N4>Ss2qW$Oe{w zP$sdQJiz${T2R*4r~cz1fBd2Dt|N((68qdm8<{alyP9vKA5Vf|2)GXP_(kLTIK@^!bku55S%wY5rU^|Lku%V-EF_0Xk{D%C1dV+ zt#Z{ZeE@+g0=TI!ZuWBl=W_*WQ~x)v{2>SAvhA;P3a~;^ec{;n!6ErKpz?WTv=$Zr z6EAx4TRZ9ZmPdu90IwBIJ)M9tspf5)&gmw5tY&vtFUl>Y$8M+n|6YO3m}ICFL^@lm zahMkRQMNqc*FE*WxTW+(z^8U6G#X|GIFc4~g-BpFKX*$8<^AhWqvo1HOds*3n%V&M zhASU0H=r=@KOfNCpTWL`R1#%dlvBBoSKpOcp>wVvLDb*iy_LS$3(cCH3`k z{dBL&!B;zORVok!%CHl{zyRq^Xl!|Gp;^A%c(dc3+`aNRE$w}$+2OR@^+iqYlgEos zKyG_=5~Bw4qSfzQGf4(DA)A z*X~Vy5cQB_P52j;-u1(ed~<{Y=XA=;AQvw3cF%^09aoBgmJAmfpub_|&oZC&Jp3fB z2S*2qMUJ+Oe7SKQmVi#@Fohy82SN5BUsRqw2qUDie3^fIUFzT~KuKUML=E2}0s&7( zw#W@Z;`%_UVw!YHj!lXePIKnPGfBN?4~iQz_sQ~5zX8GR`7o+jM`Ao~C_Qf0+q~@T zZfy}V(2Gje2?9{bR}q(_b&st>CCuNyZjP+fF0Qp*Y!bm$q@(3Yo*<~@zn_7Q{I#i? zTQRkL1}?;VQ_-mAcMQRzR5W!N8Y_Z z-p^Ox2R$?NbXV8jReSBVb`d5oD~^iv8VL#t3RO}kl^@&~A_2ZI27v!Bi?}!Db zBT&l8i7l_o5lHN7*kApT@KE&q<9o9~ z9O`l_%?2=Cq*A(Pd9vC$oX&IZ8}aJb31(7)Suv;UKqC#+;)NIzp-enoS1_p>p_~@(af*Fy=b_RD>_w`<`$MsQ2mF4eI*jGAjMDeS!Ta%((iqM_K|VOaGoM&_2!80l{OQdlH$qN#5HQ1~F>awQDu*$Yg6rthK6uj;kxCvsOXjN)+mCp=y1Hn*wg`%5N;(M$5dAs~c+S~5 zIBHv^eoxh1`K!jj@@C5w68e2a1~d9A_Fz0Ps*q)Nw+#AN;nR$4uS{^ktD37a-T zeRxNcHzOovhMqQrD&8GMZ(YW6SOKzPB6~wa! z%FEkAJAWLX42$mUmFlG z5-0w$9uf4FX7p@T$6+6bEh$rT21{C0KiNkX9i|7!L^3ha>{9#FWkohjv&Sht_s1AY z5hdr1H1zU|0dPf2*5zp_3x;C&U`%;!umy&%W-=La`&bNS#)ozV9SgL3=rwMmL2TKh zW0-f`_mM9j%*M@;#G}nwLY4cp-DuUl2a)V)_ftPTot0v1h>!bB;ScKR4sO})ULaZP z-*SaTJ}IdkY{ev#kxX~8yt+dHUl22r#Qo840_n*TdZoeNR;sZ6n(eyY!qXEU4puGi$&{q-_{bGe4& zNNvC7z?;bQH+44DFAnZ@C?eMk55mG+gHZ~bb)k!XJuIY2 z0Bgr6J+B*$Z78H}>v;KJ4(HS|=)`uM2o87zC0r#7rhAW|WInYQ^Oz4gJeVwN7F{3t zRju($gi};?O89FDtq)Mwv)-ViJ3Py%*@0V0s#zRxihUjuHxvR2=FvDJ znYx)bW`NI~7pG`XT<0%w4;L)#^nZ=sF4P_~kZ-4M@g$1iqnY9>gJ3^CCNvjml+kdc zNZAY;p-0DHfve=i6P&-s`j+6cJ^ECzM>;2pl2)5#d02T#a+gk{rN$$U&BLP`XLRad zp}=)I-zS!=V<9aGX9Xy=4{%=ZUeOkxOdo0N84WdAp3xW4EY&5;3DR!`Dm;d9bpWb` zX#&msG{7cmu0)lXoJCTcr;ig(H+$Cl)FwOX?w+@=n0-=)!vdQ0fjQ*&Qi58sA9)nM zU+v1I?*5oq=^_hS1Tb{4;hj-{H`n?^W|(*Oo7B62i|1`8$K~BJ+lgSj{6=c)RB!r&0^OS%V<;2 zD0KL5mE#5+CZ7fqKk;EcQrSK_!G`KHV&qtEGCVz)Q}Hbca6e9HH5j|{!(pTehDMs| zZ3#(*oG%*5f@fi$y8@I}I>*VxxO+Zq{ScE_cT~ zj$46jWBjlkHD;6Chc%N6H7rolLSI#I4KNKjq#o|nPRlKbdmAn_@-C1RtpeBWW>$O# z$<G9YnJ~kG*BNUTjA!isMDI;T5?-B8bmxqQrirg=C zI9~2ew>&@H8=IQWzVWzTa=ASPlJMLgRPQb|yDX}hI)KCG?kir-=@9dKWU$%>iq8-x zym1k64X}X0HZC_@Unoyjv88G!m?`Y!?L)o)wG78bQ}Oes-=1%?0fzBWa=|tW9E{jV zmHM49{F$xK9Dl7RuiDq8kTHD`XZ)S!Z92ZbT=06@FK@RV ztNMNI4bn-JKhR#R*JnEZS_b4v_QhtAzdR1p3>HcL_nCk8!klN}4z3z7LQYR_QNAvl zA77}HAD5UoGeZfPm1K!2DPgnwRtjm!$@syjgfn6|zsCsjT(e>%^DjWwr5@z zB%08Q{IlkAi$I(E>a&EJrFsMwAR;0*ELrmtqdPahNgEN9l|_R9_L05CBBt&5>)G>; z2|8yDUuc~sD!b#C1d*~e!ZaOQ8DAMVU|*PzafR$I^(s}{(-Qm)*rg!XY*Z)_{aPQ_ z%a<)zTl+jjSTl0V6j8nXRmlW-`-m_aoWlfm&5WN;q{AxRpxTTfoP~O zl`ZI{?GE*W2hIpd61BBr0YkO}6oTa8L8{JaT((#1!0iA7`@VPeOVE{D?^( z+cC(!ezVY@_qp{vvQBrC`UsrnPl3r9?>fo@C8*IkxD)j zQ?Ae@@4p}o$$qyuJ}2|>{gi8<6|q-Ds+x@Df(1Lc6W>!l`6gil`}A(`jkccQx=_2M znNvnG*gLn67t)1y!~l2OdGA9NQlgRQ#!PV$aE|Ax z6_4)ZpD2r| zgSXJ;G%lNu3$K`!d#yN&*`Yw%Pm-F3{gm6ND+}C>^RstCB2*_kU&ZbG;Va^HPRlnR z1nIN5)bj20%&kxax}L{)`=q$O*ld#H$}jt8HIA;V+rNcvNNOD6;EmX8*rJBr-a_Y&==)~e7q zxfBxW?V0CKD!$J<%frp2u?YU2eES~W)u7Q!HB@l8ERN@i0jH0KYA@3P3J-4--CyG3Wu9R?EnPQAXCgw1C*|cgc3L)P_jsZr(EhT@Y>$ zii1OEidTc1$Xl?70ByjOu1+%lLI5Lngu^`@@enO#F@MmU0P$xmr-hH6eDv`aJ_y@Y z3I-+Wial|k0&+vHHp;i1$t(5w+8^&Z&+e$~04kW}#`lGhp=;4ncXkG9@NiUa7Ii26 z>Dq!!wV~k=;5_6zTZ5+fwPQ7hQJ+EX^$qM{9KPhkDDZLp_4-@6Tpw*w?<_tH5+?}21|c=T`!c#gmUqq+=%%XUw&S3#1M)Vcd4eUbAS{oClWpu%oo}M9 z?)>>d8XKkbfKn2Kgwv4)QokMUXt~q#UB2SR!+Y~4G>NrfKLbmh%An$vL4$lmb=+yP zh-^gtDm(CN@A``LB3V0aF7mh@{Z@47D5^dwnH%tuM#tp7!A3TXyOuY=rzPNrUXmnl@3Majn<+a}k zn6wDY8FpWYHPp4uyggq|FR_CK+(C%nl&WVjEk;xi{D5oWGi(&i>>uU@3RFor?RkJf zVmz^$?;?5r+U=r%2ofwqUO)H&dY-{eRGSqX(hv1{w&9cN%1Pnp&m=yg3L!hIR*~OZ z=aTaoIL|VkezPcWf3e2uB@sE}!~YL_uy>t5e%00-FtNm@p!F*AgN*NMgcmF*u+1YK z)+^7tnSR+}CYtzBR0X(gd!)jo6NjWF%LH-_Z{X!M-n^Cf82*~x1&ilG5n#V|=DpF@ zLY}zcWF#UpC|0I)@79Dx{l#7z@z|1ytWZzwiJR#)pS}!!*W!~orxopH2n=;} zx_R4@s$_)&ZMo^oN=irY_z>HUUcI1osMY1(yK|S*tp(EPDdW*2EYa^~wxDo(!2!B& zpGCOCnnTQ0sx4J`RHA8uoltXaOx}X&2X8D}V){0 zc(&b#@eqvnyN-C*CUKKDo`(yk6Y34{-3r;dSW_;3Vsy6|0@oT!5H7?&-v5VPH zEpS*p;#=f)nIHuat&{HOO1C||>*(u(Qnl(h+?xt&*NvCW8r1$oywnfh_;n*qxT<}` zv~kz??28B-CBgTvi7YO5tWx$2O|w@-;~Y^w+Dl(AIQ0;;Hu^Ua9V$GHpd)5B&W2(I zLc?s$t_uGQBENnU&7|TyPN7Txvik^ef!}*52IMq@RZH^ssKE?HuvBD|T>!S!Iq@md zcN3xw&|giw2N^>-pcqSE&1G$ea{gN~l;B+TrqqC4y#MfGCHb+u5sD}byBCBjA(C*J1+5-eO_?3oU9mJQ9e z@u#`K2*Nv21Lh&q48&1au2W7Zyn$0V%ggF&$1#me)t_>*1o{r~udF(j`C2)7b&Hwy zYOuiXIx4{SFo{7zpB0o3DD(*~KA~;rOExseXg!=9isgCVPu_FW=pQ+`Kw(9E8R^V! zlhhV$KwiIhN1&ea=k<9-pjv%g*lo}arwm`(bk3RI3Sd@kM$Lx?{CxZQWj{S9Ybl1! zs8)BH)8@kIOYc3NMh|u!oXl|c0jw?k1vjAWzEp&p;So~we!O!1bs-?@cW{TmXmG*& zshm{6DoPXN4@jVNW&P&uYO9&VUCdYk2MoAeyj>y^ZmUeN7OAA>;b0SF3QEmfI zq1n~Vis?Mke7M0_?8ia{PT=?u9DR5(EhpJ)A-7)Kxh{$5Dq+!9O(L|lrT1U6{E?8m zI!lr&IXRXe!=li-WjWH$ylx=;a~C@qClv~xcW|U&I8ZLK;67m6wz=YXI-+w`!RvPW zvs}D|G>Jrp%)4~QaMlU}G^Vt7zC+E=$_B21QF}P>-pH|8@#nJrtJAj@Zja}eEl;=Z zBZ4@w6kkv*;EV87hEH3*o-p8=+q~pxgfGI( z=r^I>JlQq<0lFL`xha$5_RFC3{9+ONlP`+4^$mUy$LyVhgWFmwlo#D6*T#PGHZ^Kl zX@oeQV{yPi_?8;1fI1p1AskpXpkIPZ2en_fHGURka&f4Nb(i|}E5nmB+kPAUH<(bU z1IaM$X3k7IQ3t&prRX!0gmGS43sJWCQ%KNzb&?@15ttM?wtqvA>QoP*(@?x?JMYsqRz4eL7USF zw=gnopNe5N+`VKNz{vXf*R+pr2A=%gC#)VCWF*-0+;-}`V|oc6G?%^$2Q0Vd*p>~g z9~T#g9mjUXZ@YX$rYgHZ;N3o6Yimrq9fBh?jXoThB6dD7qXpS(b7yuL0=%0t#^}~> zM|Kd_kRnoU&B&$+DpBT_+DE#XsjkX8gkbS9o6@Vm1nZP)j!=VdWFQu z=LO$0xddftkUq_fMD5F%ZijcZ-q|TTQ`Wy3wyEOydhV-f{*(`{kU(>1{v~+%iRn{4 z&Y3X)XUW4Yw9sp{F7U1Q;+*Sscj(bD3G>+M855PB$<|5F1YOq>t_nD#VKS-oIB zb6{(6G0n@INXr};PxYcB4=L^MmrztxymI}Kmp9W2$?f-ab()@BO|Yvw0=WT zw0G<4F+z2HQG~Mqu7-oEA$%VDx6I5D8yE4>eIyG$`T%^mV1u*iH4e|)ji8Z+2vJct zs5GFct5IwPLCzF>EU`zx)Lc%^aLleV<|c@(>QYTb3BVf~Rbd3|(j&-T*d#BCb!+}+ zF7zWWV9r)c=f>g=7F%sGG^%QrQ3dik;e}<7$lP_M=b<06$~|p$dQU^zf_PnU`=DIM zCb?nxhby7wJPl>F7X{8dVaw}{GZ$KBF0Ziap6{+q#!TI_osO=pl@nfeR+pQ;CBL*< zZb`YgaD>_#%Ni@p&s@m4Dm9}Zw`Up263U8@Iehs;Vk{Rznd&wb_QL zsVV2?`oE&Hg!t5!)Qx6hZ{7#2ZeJ444fbXo(V!UU-P4hl1yb^f=?h9uzVS@41+ha9 z4OKN)e8kH#2RChYCp?ejh=$;LCmu=LLoWtMI!KJ*kz71KwAR!`NI3cQYo=Bp;CTqm z!yeXy*#u6Wt{k|?a~4iUUhQVDt*s>s`FKYx{?&FodLfn&$OdCB=9BNi2*g|jHJ32+6RadL;An4L4Wsf zzMX>oJt_tY9IK2&31JLAP15-A5sc-M@}LhFK{}SXD9IHk`FkfVtS$E`Zpy@P9F00ywskk zCb60#bP0BC{v*j(!WrkcH+m?-OZ;66z>9NSw)PZ-E8i8xhKJ>)jK18?9o7KYDu+DB z>!F;Zk0FnH0OtU!5YokYSkY`mEruNnzz`^K`qPo9wO0prBqddX8DZXR+=d_SkrNunh80 zC8`X(c{?QKru62ub+iyiRAsEMfWO1oUUyWkVc2Io6Nrh0{NyNKu$G?YFqVUwt#;O12!Q+h zUa{Sp&6Hk@sIo4|kXr?Cu*rKpVQ_ZTn0HNlF)>KR%`?G7nDGosrSvR*1QY|ZIn~T6 zV_=YT*1JMEQMA!W^&#~fCP6giSxqyenJ zQPB;BaU34m!7M27&7X?rH8yg2=NwUXD+mwH?lkM*&8w4Jo(Fhy>gP0Cr=)_wYvD$Q zwu>;1a-0=bXJ?>;OHVN4Rw+`4?&2^)u7xSAmI2T4$jS%rde>1Q&hUx=oy^dFgN}bd zkZ%O=V*EeDYx(9(Kps88EEO`DDj2F925A_|^M>(0pQ&i#kk0N~OuuTAVUu7fc6}Uz z!M$11wzt+}+TZP9=^}8@#1jijVbD?OuPS(Jy=QvAYe2{(i=WoVoFk3PFyE=yMrRn3 zmlG}l&-vfb{`Xu6sim-nD}o3^>=udZrD(~nT~|Ucx>*V?;49}-`y+J19(I>So@(y5 zzrpqsX&!qXFMB@fA1{!6X!ZbXqy#k53Iwj~l2_@{DiG{GtdFv{KohcpIZ>J%L|c!# zlqOv_>X<+Z#9ahn^0m+ih;E??=$l$!_)oxj01-zIYQ^SnBrU!D0D2q#{QXKv1o#If^r8TwU<+b46F=JBOj6VXEh5g2pOJ`Mt(J z&$waxlMH4G5($WGNp5>_hVRT7i*;L4L&}MjT=+Ry!;xio)vnJ$qWhH$`@YAs3E`J% z$ycCHPp!QrJo+ivTWVFVrW~7qv}H|^jV}m)st%^0N5QA;C&S-m0uUI|Egpg>kIpXQ zwG-9*aO#iQ^6)SjNtoXMQ*ZzZbTb6zw_7T7+$Tcquu_uM2Y2-)-7axO6cv&Bd1WBN z(U!ie+|$uY&>DP*+O)hr^lF7x_aohWszbFC6zcoZ2k6JzWm!u>P?n@=>&`RvYL8(>pHHO9U( zP9GG)bP(=vYG3x$6++^=IZfGe^l4*$k$2Wvb0q(`d^M~DsZO0~G;J=XIYfNbaynF0 z1ntcbOn1Spps^-DBo772^36u>ue3ps+~1A;=eN8^qJHTq4<^D9tNJA|6BEkvmNTS0 z7eX7^tbQqG!Lc_kpw2+ZGwkdsC39N6Mi;n{XLGMX2x8y_;8k-n`B}hw*y7>ZZEG!R z;Jv6W2y_c#8hxG8MRM2JKd{_+G1khBmCGYI)6tVHH})cr7)$cu$YtQ-wEYl{0$y}{ z@r><${SCtskU<4vMN#3xm=*p<$}yif6&K6vgGtEhM+OOW(SPf&zXDxp_waiG`CtPK zq#!63nRqFt#=s%w_Vg4sQ$=<4eib!cS$B6{&a|jXBOqt9o|-)px;7{ZWiV{$KKA}B zTs>|!Ln?ZA2m~#B=A2N)+w8wlVqRxO3v^ON&$Fak4fwzf?$MRz8-yccK8GfX1-bQ- zjz*PlWIT{G@YTmz{lEn_N7cE}Kvc?p2)}dN2ZLKWu$e^Rfq?~{_|HmR;#2_TH1S=s zRJRLnHCCJ${CK^RUsM!cQo>-}dO6eN0MS;v4xOvrFZXaS&8i7FCOuK9?PA|sLzSbq zXw|c=ukhU#3}<_!XBc*%B;SLmFR7i$wc+qNwPic1PT;k8KVimx1pW_>N#rk0X+Hm- z`ERej$0Bt@{Mi-hOJ?Ti2-gZ|=Qho{DGZXC%{URCRkk8jG)hL(tP54UoW(MyruYzz zw$Ll$n?LVPEPX3B(@OhYt!Ok{R+ea zcYrRUX z6n1Av3pmtp^Hha46Hs*Bd0=w1>*6tWTJy0vUi&KN%wqeVf87ZA76B??ifrk&d$5+j zPB00cQ}v`jy9_=b7c z8CEYQm2d} zCkrZ<*FV$Lj-~V2jj5?X!O;9I%?ct6Nsn9HOf=_MwvC~vY^!y#+Dfw)+*suTeqmOp zkOy7pk1Pb%{--eD{<0cferRy8VXvsTVZW?dz0Q&#gUwFlI zjS37btjV0Dznvd4G}#|t{1SzERt3)@=#wv}HC0<(Ineb4@{U~14YBdkC(4hu8zW|n zG-jYz$`t@i5qcge<<1AuLa?sY&qMW%D(qfr5&kcIHn+y^?e5QG?3PXkNyc9?FFT>*(giNTnb?uwN<9S}ct)V+Lahpqq zR98y%^ZIl2(R5nms6i=1M~>s6cIJ&GvP!AB%_@Ol6tk+p*h`)3XW$Tnc4vF0y2#N} z-t2$8fC%O)g1PM`Q@7Q<*5wVnF+?ga(Wr*=ZS%UXD~jnYu4D7Ih1t&X5rmXefS&H@ zZ#{2Si5ooM+O(bWQb%$}>-TRY0iD(sEXp_cip#B=y7x%jE@!rH#@pkc1qA}`vu;D3 zzLgOzwIdS`&fRP_x10>GxNgLn-soot$B@BFa;l#8WuTv~ZgdrUFF~B1$z5BYjzKX&Eud-YGCu2?Y^|N3= z^YJ5nbrSB{E|0G+q5(cs=Lgl6dmoU)>?8jxQVvN64=3$T#p(Bt*?!*sW6+Qa)&H1zZoy9g_^L22JUoO)9SK%2IQeC8X6i>M#j>p zVha$2@msdO#{COB?S}I9piC{H8B^^EBt>o2En4SRRmG|4y1krij^fIf+xUT(wH?iO zq~8^K#P4`XE1kv}6+-O(`T33J56kp(jLGN5RBJrYXuzaw&PL$?=x*70_&r*L&@lN^ zLUF@2vy1(wPKt-4`5(%2@%Ww#r^c?Y@ZD#ynVMEz6*J&4$j=M6HHbW@xIk`*10*Z` zAD>6&jbbKGtbuIK5~loKvRfczxo`PwXSg*D%0gF1UBys*{z!MhW&UQkqhpyczDs-3pNuZ)2oP}!9xbuJG7_cA)3CG8&Ve; z$I~m(_RZQ_Z_@V)GmFw`ycwbcc=r3H`QwZg8DrbV3fLuHXwQu?dU9#7)Oy_)gm94ke)ad|sv7mhTmg;0IGr18b z#RNVZVm93xPQk{-wV(c)6rY(HJpwR-RK$%OaD)vVHv|k&EOn5AlG+Cd9NGZD#`qN8 zb8i+e?87+`h4y93`xQE8Swh+8b@;fg=$ysMTzr9k=ozMt(QGZ^wKhHUPDzd#g2_h1 z5oiDJt3`#GCpDcYyEp+uLSNR!-+WZw>gKQ9!Q)SM!^~Yn<>vjW)lM+_@wn7@?Z?Z9 zeH$L_rv({lB22%|_fHA+zN}+UNh>V^U%$1k+p3{%+>Gb$7{5OeCv|>T53(aL!a~K5 z>)<$-U7deP*ia)!4z*O)m?osh8JxT{d;ATHi~od0EsMwxGZI{)I~HI2gXr#J>&EEa zNrM*(F-I!a5RJKZEitSMe^me>UwF0toX=8^PF81 zk+Rwy;s-0=g)fq)(WuzYZ$4-`9=bP(5t+5d&$Y3_+jyf{zTauny{FM zLXp!sEn{3bqK`o^OJHg(*!#4QSwi>e%ms6rCpt9wMN>sQj7`Cnd;CO~w#2cBw9fZs zk(a87Zi^o-B%_5~5g+_e)&I%xAlzd1&i@Mif?8E7_L`69c~?J^J3l2Q>5dq!UBo)l zdH7ky4!jjzEEs(DlM}j4L~@7H4+Kuo=6%U<)AihCy85J=)=O&N&!e5<$-~^n6Dz26 zr(fz8zrAuafMbK&HQ7kLo#BH%sh8eu=8`3<*{i7Qamp6myn*Y^hl2D<(LfyS<=3wb zcCXOnYZHfuQPXV=$tfdrw|?|e+YdYnR47fP!uS-iH(|97+w?P*hwmlUy2ujJUS@?hkFZ&95G<5QwKW=MkDyPQ0FeBA)_~^|e0bX9O-PHH?%Eoh6$Hhn41~|LrtUi|K2kW;N?P2H+np_-{p~RiX zx}K4`&#lQ%8GLN3;V)6{?j5xG-okY6^z6DkMriRfpGTBsND|x8?~i&$wLcYcFF>E{p&A(@^fdRH%UauGcHBDC=gAEMYW-*TO*(v`88oT_Un1k$-tFcq z$;-coBvcTu!Vea9cIM18tAfBuI5Z+i)uOh~^8cwL@u zw_)`)aDxq|ysU635_6eaFetYA^(f~OYJ%Nxnf1a6P zDpjHhw7jBX*TH;s3b&o%QY~cbR`tAulvFoh(pU?U`u6T$)^VeZ3=do8n*VD(N<9um zmJjG8?bQDQ(H}99g7!X4EkW(wjU<|S8t;sa+s2yKy`PIPv5cC})cot&Sg4lI5WKnJ1-gfovi$tUX# ztl3j54Xff>tDcPW5#COH?KzC+ot%f#ONl}KF|CXZhak)bqa2a30$|-;|KwRKZW$Z} z?G@Kx_rXQ1j|8Mq_jE>=c!2OleR@GSBJ@D3zvkw#8u?W9?sg9>*+8U82}v)1H#Br{ zZQs{OK?rakA0Cl~aHcQwBW8wUe%0@`ApBqTyQyt{OCv8S)^~K%0K9QabBLVwm7*#p z7+vXsToOVf@4r-KNA1{Z$(RU}&{q$tf58Tll&0Ea!Cjl^j$xEZz>f+vanP2t+lfC2 zdAJZ0tGKn6-sboI=L+ubX`$$|!%DYUqFoAqcKHs^r_WPk4N=w<8M2khkO z-4Gni!VL6wIRhzk-1xEm97x^n-%XZ|n*F^_gDn{{9utGhVlt}{J{v&#s}V#4@f0L! z)J<#jAr7*mVPW7nFS8KcmAr)nJ(0|3%R^6M^t3D${NOn67CM|Rh|A=TdmR^%@NIJ^`BkN}Z@)$};G#sP^ zq_fB$D#({hAmcjecw*P*dzf zM3s+#ov0!+cj{K+u7abRFy>cb%XIi!7|0DTmKnwM8LI-y(%HK@R)}GsbCD)>|GrUj$!d~rMq!j={$M$7 z@cAXt!D41#cy_$h*k@@r*pl~xL!2*m7Mcl?c+PIdxClVa`se~rpj7#s;9HE)$g_DC6MU|Q^#1(1EM-7L1raA@Mw&{;zI23nkA zPOp@Uzq~BI!u2|i%$x4Wg;oB*FWu0{yzX#5UqO*}fgixEcz$D6-W&RnZDk8jGmyh( zG_n&clB^%Jc|L!K{cdfo;i)RIh8?_mP1%P6IB#cm;QlPea=&1$JzjIBSxVOdbKdp? z`W_OLs)uIJvtir3nB(C&*SVd$OdG*#wa4_ZP-Rm7sevXdGtXK(<|K6M5NdLfrGImj zip5DB@=|bl9Eft?KBFo_3VZ6J%kUrqn#%gmnL)cJ&=>sej z?(%AE1OloP2F#o+R)_*N%RQ{1q65_Ah}pOp4;~}Aq67GwY~EuX*QDN4DiH6ngW%2j zG^8lz??%m0-6pF&IXYS;}M-O%9Ad4@lXz}t%0R?js3qW6-iz;gB z{-#YWH~aj~>Gk_6OHFETJf&7zSJeD?G3$=2*hDo)Zz<&L@P5{lMPaMm^tJ;l-6LK(tB&#GttFjXMllY zz7~p-YemDbk~Eq&WYtt}F`DutJQ6TPU@)weI0TyItf<$bDNH-txmmP+C=1G!j^$jO zJ>FN^>~hGPR>8-cpBpiY`G-~89ArSALhOBsi%PHsK*7cC`6 z$OLAkWWTjfXgT|3wQ2-SN5EJK6>|d4mVzJgEpWHrKDUbt-UwFv52crf8bGZ8_Uz%6#C7 zd0&W?=7>KNgg1JM;lmQ|!?*%eEXT^{Qnv=~9lhD*f1HLEoI`$utJ(TGaJWObl|B1~ zQ=7n|@*z#9rGh>|;gD$hfsAj*$yyxXgi7XN$}2~O`*Z8UmVZ!AbORs%=Qr9}l;ijJ zfbqS5%kA;0m5#fL9uUgsQb)X2CY?LBGXVa4a6v*WV+l*IVy~7LwY!6bq3yw)fQn*KD0tUA`7R z+(QFL?E-Lf6K8_)n?lCun^(kxv6#~2HesfSz2HtpnH79T$`T%@1f)!Rwe&@seta&08kv~?fP1Zo@gG*Oy z8F;qfl>DsKa1jw%0SK6fRAx=@;Ku+zK0iIiDE(V^o`&eoFZ4+JSGLMaZ0}3d)a z>jImIsDJ6sN^+{Is!`oPdwP1-|5I*tnR2PqF|ZNTYazL;Wd~FqY_rVNYsrf?t(>dA z@U~8V#PlekbFQt{c)nVSe8cKbPpmCA5j=K7!-}K#hMwk?@uXJ0ZMQ?%#yrrt<70Q; z`6Q6!T*>_eAB~PYpF9Srl$-YV(1-R9WDCD2fPl7=bNqX@Gxd{As+o4jH|RQCYbWcB zYdH<}u1Ve3cwV&xi)C7CJ2HA>;`@_DC?84_D2FpEgTM|?BLTDNqfggIfI%htc{P<2 zO-9aJkG9p^4I+ONV&=IEXy%soOpvB_UPfiG8iaM5odMW0IB5La&aqhEI$snxp(<>* z+;Y_G@qAI+66oI1wY%7#L-Ac?BI#J?iu&#}`5EfywNU6+diu<*Yjvcf#m;L0p8FMV zMzqxei*X;)%vf`rD)2HN5Z`Ks8ROFw;IBz!)f2V$?YP}^v@wb`+Rf^h)&FilwEzV9 zZ%1V2j;;u;nt`^E-Dmb=0@p0}=-r<&@p^k<7g?UaCZ*VG_=sIte{5EdFq_O%v5=Ea6_Yts>%Nk7+dXp9w{ClI~AM;E0 zI~-Q_houiw?J`7zIxb71-rj-`dI31NFrekrnvkTI3S4qo8KH!X%61d@7bgv=Yfu)* z_Mx|tApoZJ^@8rFgc>T1$m>_`aJA4)3SQC+ZfFJDpTkx+Ue(}$xWSUIq!`4^MO^gf zPOJk%u2(^oYW4sryxZo)YFi~LXj7@t*KV)r0mB9gp9HmV`Fpy}9tp-N;)cIEGy?kE zo0e{9Mr(2>*%#JnhMhPYA;U{e=Hv7&qjQ-w}ZP~7p@UNssGug;qeu; z>PFt;>CL{{7{k0ngf-;m7YFhfuzIL&C;eHWw`jMY&&|*h5D!Y1G?<`rvb{@`!Ljd> zbWeC;mp)MWK$%JW#MZq*yEl@^A28Paqg{&Uc7Dlal`v%AdXLO*lY37n;_)^6ysN9y z0>?8A{^SeK?wsEF=D!s|{yM0I*hrK-gp7uWdc7fqR}d8LM|!b1>P!IeMZ#yM_qf08 zTEwDO1}=XmUdywvR~QSosqVMiFo%El5Xbp%BbHGNq5}q+3Z8=Z@5R)WKf5uW|F%)G zI+iB!X9P>;OsmwLEh7=1$p=WkJ<)qu@Mz|0<1CM#tJ$__%l=>i67kb$C^8T@p81Sq zA~Go$#_wca32Gi?M0tuPQz2w6_CQwQN`|(wfc-bb^4B%9x-cbBxF6!BL6ee_T7wCl z6kgRmF+o3ZY2w~bCT3pc{PIEUG!uMo1BEtT>Eb`O-JZax+g1iEXK!t4gq!V${TaFJ(Sz=E4d3>G^)z^Phz?z?rM| zPUMOmk7oYc4lHCW|7Jv$MqKqPdxVr?8gC3aqEI2t ztMjUs`m9gZ3XYP+5l7U-nQ6v+gQ4>l?yU2-%i{tu1O;bQC#U!9As}XYJL$cOdW`q1 z-$}{IiBHzF0D=RFP*}-0q=r>cU`tuG#uU>B7KyF$k?)(Ozs_&dX-c40t8C>^XFQ&@ zGV+%k5U_3&sNVvC6Y+_hJfJ_CoY8Jae5Oo8Y%)&*m(BhQQ1c}vBU`_6oo{ww)M&K- zNJE1(Sh=^-!rtU``k9O@7w=V(h_O84wqTHdaNu6H8&5b)7p`PTelv|^XLd0}540=* zR;>M9$SWKZKoX6-=zL>oxVhu-sC%{DdAn(+@yXUSFf`O)zS7_u*FU+4txpH9rvP;Y zXh0z0D7#j}rUw%$py}POHc=PzYqAle6RM`Yvvv>liCW$vWSUPkQ*~CW_x~*s29PWi zJ+EGwI$#9kAxKf_P26X}IbUSm|51tf?^n+C)MtRT^pBTq;QwSF^8e48FF_Vy?bk2h z20S>rbMya$kCF3H?vrxwgjF4b%?aGLr5j}AUH#e6q?9!f|K+E3cMAYWnyGyVcr(-M zI@B$z3nj&RkC|dB);cXUK8-MR<=DW!LUJmq;$9tNUEK|vqJKW6 z`)XKIcsgoLvGbK*?0K@+1{aST-yArCd(v`m?7EJ^=k%s+3PfE*o=!;O$PM&}M<)XV z<=ZzQQ+xklbK5c)qrN)m^m}*6(fb_2f#u#1bVa8D=AR8^d2|l0|58S;D^8=eM!HZz>!3f}z6)&d(sEjivn5w)3+mL?0nww}G^Em2p2FtvfBVxM1^b3bFc z`P8t?nGeU(mF-^a8=+bfTul7;+5zwIa$w&B(Fy<5-WjTE&D-@Ax6|!3w-cRfV*l|^ zw7-JkYIUBe=oq&vpF{SR{T(Z?fK6RIlc0DlxZ^II74E<=%Fxcjq@wkvFS*DNJ6dK^g$9e2Fx=bIjt0GQ-J`Qw z-_6}M{};W5Z(iHQhI)xy9;BhQ?nCE~mg=5hb)uxH6e-L4aIz+v4?MkjekF6U`QQFi z`=qE}Wfdj`AT)izp+1JkQ+TV*PIKg$R9zr5#B+w-bB%v-`W(u#Le7LC5Wh zEsJO;v^ld8nJL?_N3Wr(Tc0&gl3Ad`U(u(61$jOg(XprGPm*nXpRpX?J;wrXoBX4> z1;BsD@Z^860TMaAA-Hmfo5Y^CIsmVfkC*oqKC`*@{pEf@9gXsDC;-H!YkQOpjihF9 zw9>grazPAAblK7wwN9hpm_kw2)sQ9m6j%RS{Mv9!XEX1dOpLHQ6-%f)Gu3wh93`3}sN@a_!wOCZtBlYQ< z%M(Cy^>*OGU*xhMR38al4jU;sK6=W*>K<>l(Z8!O`fhi&VB&t?UNaQln)-ckWxep> zrQ4+xe<=JPrF9_Z^)*8!EC7GvpkdbQMMOhG8(3xrgm6s5bW!Jbbw4*)uHDrM(H{BKdx|rcO-LQvC55+Y3H+nCOmnH_K%G>%LQa_)2)^YgwTM&v7>kZ~r2P))1N6pns6fF;n%0C)9NJ1LWkR__IDSBs(86WH&p`*lhn& zxOus1J$O6YP%FpM@&4l0be$|$O1E}ni2?*U$yw=Mo=A!WJqEQtb@dm>ZU4umv}q!J z;wcTD)pQHp8BV?cG#e*M)j*2nn#1SYgSg*JF@T09V0)tC;s)v9n9o>y zipp_40QpnBqYrld*t1K+Dh+G_xLSTr0e=Dn;c}M%iCL)Y*F!^)_js5;tC}0!2x)Mh z#`4Y6BSSIY^XE)vY)1F1TRX!=*LO@h-+&MM;r%z^ouC0kw{j9*b&cs;?!P6E{z|Wf z9sc+=0MGg?l{Pe#$f(lfNCSvW8SIT^0;I&~m>6FGY`)kTw%?!dtFC6E9{h8OM=LGK zF)=Zs&{MjfGiAQ|#?|#(zkh#RwBZc5{c@2$Iqe)+u;|cZ;3RQ;QFp5dV1$BIUx8 z(ElTu6hM~wTXyrmR__1A+isMcLYta)c*B^_{a!Bs10s*J>UKy#h*c6$1bF$J|IMpL zE&%r~fsgp%tsxmFMV`rPX8%_m8NB1X+eoH*3(Uyv(B66X>VOxK{G6};IAz}(uJ^$*iK8u6F$^lxmbSe8!XMzQ{{JljH7txyr;R%Ufnd00vMW_`&m`{pV{qpeHPVe`@20J!GRNfM4MUK$!*D&^_O=HRSKw9V1Gp zx&3N+_3gjB?>W`}-PeB}X~nCYlWeRcQB*Tudw@-(j-N5hs*yM`tuVft@-w!}`%djH zgFdRijXSj?l1vctATo-C_68A=uS-K9APF;Ef&Y0+-%=$CJ{9eDx4_u3Onvlt6-S-D z^<8|Oy*y`oWU#hbX*i8gyOgTrxI?@FODa>Ct?V(QGK~9mdMHONU6P8Iu~b`NW9;Wo z3Kz~Cv6id#RM9)3oeh@h0!-K%m*hIT)m@iM?sBTl#RO>|y<(Dj zH*7C=u2|BCJ&X5*ixu{|j2lI6(CqDLEt-z{7*QuxAF~`|2|b2C$>Q@4?!;j$M#Y|P z4hHn1ZcLp<|9wzX^nb}ozDD+fGQwQ0U8BVu3%eb ztjqv^ss}n9^0hh(bB90O`%_JFv^+?#K5w9T)1Etp((3dp6)$@`^H9HVJQi3a|480d zY~v07EJN+S7BwKH4R^QN==0d%#!=xv{2XfHuBiErbdBl^{jJS=O-XN)KNv5jP%>|N zI&_yvPVv1}Am4^=LyZ=Tp(8D^d;Ew;ISgcJCRTm4f5`WII%BegBex%w_b zA-K{GC|1wtF`G#kFp#b)KIxeq_@&P5ITdE1xatS{e<3=LpWz0sV^9w3 zoqp8n^}m-afRcyKP{LP*u=j7@08q!4tHsW<%hdV}dTtWNakd(k$E)PTQQBg~)cItT z-)vNAtIi0wt{Sv3xkmFD+N)fe>h(VHj&IJI_!{(`+4Ir}#Zq3s#W=qLiwr$d#>Q^KA*e@UjsDx3LV1Cg;zf!L14_1jwrk zEsbIPk2cNLPV7hD1HxMJsE*r|M~~z|UJZrVdYeckPwWkleT@>U)wmn4)tL6YUk6mW z%%(%P%3DVVT-F5F2?YgAii?f1zu+xdRc6Vr8io(;$iYJsC z>3(3t@x#^`UEkR-ktHjoDUWhjWjn9cTB@U(N&oiZzQ7{Am>7XlEJ&vEnv7(J6-0w| zo}6?xvtbw|yX#}Uv`a#54aTJ!(6obVBre&zLfu+~3CcAyUr3OFn^4&a+udGV81I7F zUoGE_@?*W^Y$JamAn=^hBL2nnhV11DyV^WW{SnpjDOU z2md<74;#`CHDUG{3)kbsa(Mnf4HoAN{HeK88~+GMN+Odp6&HRXEd?n3LNh!t_yO?T zpN$}TwpiT9UmBm9NrKbmD#ezWPev&2gMXVgzgP=47-ROWcZI^-qU2n3(C*FkeTN`; zIBMcawN%F%IkB>w4jHO1a`a_MG26~!v)=xmtNjaA7vqgqw#35`QP1dZB5jH=c$sh4 znt{P($RWGAbgFt~VvaJMOD*DX=x96Rzkzc5pD07%cBF*#PtV%rbtISZ5< zCy{A@-GVzTwwoAVch<=ZLKmvp%45blr3IwXnrMz5eK>Ap(d?qB8*fZ|)7|{Xb8K*i zlL$P9D_~+3O#xKPhFUV7oeWCPw0P(RxvrQE5z z+O2SekZ_^g{WJf7!I9D3@adg(EMI6&1WJMa>H--|FO2e{#u}_EPpmSA6w%yi;Z7Q^fU>mkwfC%3B7a`GJk{ z8_3{Vp8Jaimy03GB-qK&oWtDSV-%GB@ap$9@mi_Gs}!0f8yWDIPc%M^o_*V!NQneT z#F_>cFpEw$4^?jcqhGdm)st_p^KCq-UQYzq3RRo-+s)Q|>cCw~c8XRpYQUK#4haDCS~U5Q**_~AM^FB;o_!Zvt5%B z%5&@!w;u>$QythQ*%Env*JHG=RgVCefC-V7)xamcjD9Kn3kX{_&U{A)3h{Ay23Il{ z{5O|u<1sU1BTbf7eirSAhchoOx8fzgBgcE@(?Wu z5!PWyNeT7u;-F~*#kXq^jpxfbrPNmv`nrU^(|fw@n@Ng2Hf+pxjn!_??1_bC>uqRq zDW?w;OTIgw#tI&ru}K*hwu;DIhevU!v{b{>vRE42_E}sHdMk7DFMX&KG(<%4@*o41 zwX6b6GARGmcEq@6M(05W3hHX>26KY2tdU8c_V!cm`wOC%OjZxV+E5XhhyzAM@4V+~ zO&~_pm!UJuh(i=N1H`4q@&0gD%<(7btrgHRV7-|&+rE!gewD~}HM3Q<963Pme^}E0Cas!;nN6rpZUh-sCc!`&_^Ii%c zvx;=R9o=k8{mt2?j^{fs2h*yL+PF+sgoAy^5)C<4)WZbUXJb2t7Fj0SZ_K$L7^tb) z`_zI#=ZX-BzYkw}`0GThxb+MN^7QJ>e{%t{BPi3+shT1}vFeljCp#5-Mhp@{@h_4U z*;OhyebOf-T30OJkGFpHAbBb&Dd6%-yo)NW;cAIDa97|T0;r-cS8c~T-tI~PQov>gv$#<%T2zH?g(f^WOb(u*Gcl@Cig!oniA zyD-#N z8~KBR?I-$>Fm8nht3Dp}K|`Pf1-=|3_E}9vfxtcJO6p;gA|xbr0|T84HCtM3R)XdV z@jCU!8(-;>$kD-0da}tR>pIH5KEyM43AH_~M^MbP=7)RV^u%VCW_}Q(VEhI_5gCok z*XP0KnP}T?xp3WUgN!bJeXtiorc%UnKLN4k3sHxP3z1z-KhqtTRC{n->%gi>nRRrE zlm@L|veH!udg^L^I^haOKv$>Ms`u_{6Ok zx#5|RE;l7FCBHx1CGu?7chY9X#z<2i{MWa5YU4TK-a%j~wRorY=~*Hal#g#n4DCrq zPGg1wC_-`OXM!T#_0=|MA?if2!-uQp+n(%k^_(Wn#PoYkj&hBSB=oMnXGcm6kB7^o z*L9W3kks(@Oprv_?dK4)^nn|->+@TNoj9~<%@sXa>39zEF^VRi2C4p^o4e9zDRy$c}bDvVB<)V zCb(p)BdKcik7xm;kI>&4+qtp?RDER(xd1!vbZFAfc(ol5BRF;RL~ycx`QHnS4;5 zmj3kBblf~k8h(HvYI0h~lGFsGHni}pF{I$L_@BG7I@oPXKixXXeGs{X=^v>2nw4z( zkW(veY6&sWr40Ad;z?Kpz+M7}VQ!dBN*7M~p+M82I}LI1uB{Z!3MNIs2rc~pY^tF% z+yW?A@!xLZPqLOW6_P6!zmP2yUUte>WUByDXO00m|!pn?<LqZBhh)S<4wHpO%3~%yx?+rRuh+D)Dezl{&Zs$J^ybct(y6RHNQV)H#kZo z!V_-bF0&FSdBl;}rd%E`*0uiEuneFeR2U2V-&Ds%jJ#>5_qL)zqQ?El@K+k&zry9C z7>`<9Y54!0<^TONW)LWG{VTcn*Dpz||0x3X|E`_&QPja61g-sF0z_eC#GQ3+)R3N* z*6UFkXfcn{X?D@H5n4kRv-uyH&$L~jR;9h*nN78Du=soC7H6iNaQ_746FlDn|4PMy zhLAi-y`#}Sy^i=~<(CNu>Sxz?jL$6uKd@|M5KmU3oVZt^+Ox`;FLnp-^>74J56g&> zy(Ngx7kb~6wdUYQIUb)wtW z+a3)>(I&Z)!I-6Cyq~E4Tm;fDU?9nxMXGvMg)dtGajPq*Yc+9k26}C-vFy?VrsU6e zWW@li2j&1HYsBTk%(Bh)L-~-Ke{p$hk`p`g=0i@)AN;EfZ$5Uq?dY?C7qe3+ard8Y z4>tR~3d%MF=J{kS$ZdYS?L66XU`dy7hX?!Z%28*GX8z>Yk}V1Zk>{hYD~GnUdS(O} zcmjwiBk_kc>L33eU9e^REE8R{A_CMc;(ooHZT1oWhBw&T9tU@jKYbrVbgHM-H}VI z?%VnX`^&(UQP1X|FM7EU+jZ~fc-|AGTZC)3&rvL~wSrnP!);cpsDzhmf}1R#BWkgi zdpNPHv%VBn3qM`z5G{Ma#wQQDcy@Twx*y?|1uhP4?51zjNJR(jdBK2IY>|v^<1hBm zgITS|M)m3pEBF23?)cl@BCG!{T z>2f&Ee*EbE?H#xJ$iTOzAiP_40JfoY1t%#lV%xoN-&n7gaNFeV3OMZiRXBQNBfXtG zZ1UA=VScU#K<6-$r?6CTOQ(zoI0{;SsmAnCWB?pC={nRaEA#-{t7)a^ z^z>0ccc)=LFWLF9JpTM#?8133Ghi;J+ONv3R`(zj9nkEMoPND9Z|-*LnWlO{PV{tW zv9x@pkSER(4hm5330bt%yZ7I%f4;`vf0)-|nT#B+^|Ny(+eh9RN$BvIL22gjAeijp z+Jtx-F_wUvsNsow4L0E>OBBQlk;gkd0Nu~L{CSRJnY@ub(SY7X7qbBttSk2fw{+1D zFU8~yPm0k>=|ls+*O#5oFFx#swL~$h`4ixQC5jnGGFLlaB9>ot%kY+?b|fT@G@6v3 z%T=hC9LZ6ZSbQWcJW4!GUx)fj8O}_eFvg9HVjR7{8KM4 z%m(IWDK$Rj+!kL}_grcG{FgZtuK88~RYUs+V?=}oC=>vkLj!c9>H?z=a`N*T@4};n zg@u8ZGk{T*Vj8yKi*K|%>RUzffz!wC2HI!;l$xr8;SNe z%OUtju&!%qmsq<_V?Ih9}GjXwQw*zLGk1>TK(u! z$obLu#*UcS9M?F-4CU)ZX}}-?Pgf*dK9Cc{uZgvE7OJtg>8{}d${*Pz82*jpt92v0 zT@NSvJpS>)oWZ3wABDb-`9B4$sq5+|b87Fw#l&NdZ3QhF<+KqI#{(X+a%~c^XEg=dD zift}UElGbo0ZE0wDOlpEGrS(R>j5f&@CFRbAFSl({$xJ!N-Z!T1mMHAJ)Vmp2{PHR z5#szfwtw%99-nP|uF-|-oy^hf*|fBowW-=(W?xBTEpHPSfdyeghWXt$*W$Nqw)2%V zPk_DP4_7PBDXj?B5@1>dj9BhgdCa%DY(+ZFubhj!&cl7_8|qRE*7*bXY|XJ^KJyX) z_IqW-qsad?QU|h<`ZT*p%fx9w$^qKres12JTy6rf^vHi$E*C(@nRqVS~QfT-ud`f1djY!d@JG;6~?2J{-q0e;LXr@~Y-D`nsOoso#{$fpf&#X`HXy^#l1hGG2yc5f=w%J@5SvF^2@a~# z+J1hQqz645@DzEd)tK}gIl1@T$Dk;FC}a$i{l7xVn3&HJIq!#m6rbiy-@X?ZWeaVJ zBV}kBYI9if=>2N8N7`HK?i-=Gd3TYpQq3H`JpI=R?83Z%q`A`QERW){$BuNJ+#SIq z-nic~Q2%y2ws^H4c^aJmiw>F0=U8l&PRd}pSo-2eP36gS)NYZv>e_}Y)uF0F0f38U zZ%9|OeBs10n}|EcQlJMu`DZggOCrdMXgC=JPhQ<%;>H6zEw$*ytxA2Q(!D;sR zKqij<{{8^=+xY*{D*%K7JsG?{zb%>;Kwb380B;QF6DX-`RI4_YvDyXrlN6(=PBR=l z9uLQL;fn#A9gew83dIMSrJ@#jaI{hq`EO`Neij8z#W(uq_PnGju>hQM?>}rnY*toQ z@idM^z^PR_9;+rXTMUe4@&f~jK2uP@m(LCYSpEJ)?mGaS2Oh%B$?|-Q8wjv&U_d~n z8#YB}Tp+e?+#a3qu&l%Q5Au!aSQH0-8}x}er;;#5z*$rgo7CgbwYK~rF}1XDj6-z2 zFc2f?KiOnk%68^zN|gE>Sj)v^ZHhB3sw%st3Ubg&%!Fr=CO?83t@gk)N{2%X_f+E^ z9X-fw)H-F%Y74@2I#IoTy(+UZ&0S5&#JZ_$;aF`m&opB z`*b6zSq@7A8(w0E0IMmAUR^ZZcj&^qF<$QZH~7R~`Q4R8u-P zHaAUXN^o1;ZaxFeB11z%_p~C&g(Ys7rp%ny4&Kun58E)sLPS!O-!u(=nnILdiayE4 zb;`bv9QZHg*~n;7adAZ2_;+RAA~#o{6-ybf6B7a-5$I z4u-j=#kW00oN2k5@hh zel7u-99COz^X9>Z^&@#cY8y9?p&>JJz|T;W@>#KL!AzD^IGZL;0YTW`)WJ(j>gu#8 zc_vUFZ{4{N5WImQPNTcPJTN{!b84!FFhWZf~U-7@B>3e{}7Wc5i3> z9t$?WTytbMp6UzllEGM5sFl#qdEND+pddRPC7c|PF(T48v?QUUgYBBLZT2LMRc&Ew z(+sl+6!kC0gejKxDVsi%%!Qs_zZ1#5=Cp0I&$$2YoG<%8sKQ-ipHXxr_Z=@SN+VCf zFOO`NhNhM7)45sRzeN?dNabbDl;@v&UMWh1l@7a@4xT#MooVY`A5*p0@>5VR`K%I$ zcCCLvr4I_UUbB8PS3!aoK+^vFgmt{wWZguVlaJrsgUgaiJM?07I<&b-dHD3=IdY`- z*({n#B)L}liv>k4Pp2$%ha25Mtc1#ezpVypaO`&;{r8v{7$r(Fr?Jznbll&ItmiT3 z7howdYhvPL8*_3bqL~>J6Nel}E*>_A5>pbzuj4F7la;jW40kw2T?|D!haTKpwIn{g z3h4R?l_E)=81gPChx&wfl&!GfOipf7P!!4QL;F@grv4Rer-906@d6lqPYu}xB?`OQ z<=O|*eS3fXiAbqNQHuGBO%IMVQw}1efY1_lYsltzeSnV@}S>?BJ(1T(dRt z<>Q(#v1aoS-v5C5_CqduJQe>J9PoZ6kurgV*oH0H&EBCIBv>oNb0~@|I)UXYeU=9{ z-3gv&{-=cnw1<#2LMc-R`b^cLqjEC&(!q7VBFdX$X@a-P6mn)w7)2Q6fTA*DI9dUj zuu&zMl~dEyWUllV3Y9x1QJ$rNlT6u!4_UggB(Oqz_a(+yP`$kbYhyhgQeNMHqbWQPmBjW;-Z z=o0RNlKCz*O3NfcLg0UQ@kFhG*K-)Ualy;aA2pmD-FzWQOlt%S=tPh1wjW+ij420Y z{PKszUaZ6a0qBR9l%XTw2xQ5~7P9z<$SM`<;6(ZNV({%v&3Mly=M+(@F;Fzo{kGP* zDgcLk&p1KaXHz!)W+$j4CHGFOK-IuYN~8ov^hT!U-L&p|GqC2#?A6i}Wnz)^5nPCT z(w{-aqH&ZM2t99Q1b+wSYq`abdcM4fuG|!xjckyV2DrCV$$r83^%NdUrGyqFAo%Sw z0kYlDSMX6LCdFS1ibL_BYir}w2hJoFrkH1uHPJl=MLhw{S41E5{qbifHjLIgO|huw zIF23d2swW5o5*XAr5BBAHnfW5OfD3(Y!Y`^n=qF}`m7+cY-${2VGZl@m(f6DHK< zWw*pDRZ%lU=cCNRft-aKwV6q_hqMOS$M)x%>Ak^^yG>UN!ENkLwsMGEpS z;};4DL!~#Vj6Ys<_~7#qDMv?IWnE`ia_?Yb@9^Tcs{@v=KkZYDl05w;JqV(i>a=>C zTV5WXmPW*v8Om|S!}$)&oc8WQ`7vz{yJAN9SI10?wa&L-Y^P8PNMlpQL`K=}DV=a3 z);k3;f2?=Y8@6qZ9j4etJx_AOcMpS)Me;>_6{qy-+;VOM@*;A;dBouq%~%jNaw<8!B~0f1_B z58|Y}b%?WdgZk~$&Zrf0GFdD`pP`4my!@Iq%h|)z?UM&-v`8}-UDB8}3jqrua!!ms zBW_Miy#`yqJ_DUIS(No$M%^sWM zMfes$j)07{ml5`$k1Mg@AQE;)>y^feeC`Dr^?lf(nNhvmZAg zAZ6#33gWdQe_lbAr#`}^``~RHqm{m!5zJ=n^bQm7)NW%<$ZNfKQcI77D{N2f>UOF~ zuY<8dk#IG@T5&?GkJWkw#5bQX5qerhSqN4Z#s0G88yOu@NhB2Wre7zjbs#pqpS}dB zu1X(?alQ+#7??XLK3r5PC@InJ@<){hKxi`1iNwTYYQC5kJ^k?IU4U@zBn+9`MLx@Jx9Rs>m%(evpvBG1 z+8O@uF!qj)JC0Pw&Z?CHR+gR5G>bSIpq_lzxMq%6SzVkbhB{|U3Nqk8mX*Ef*N+nT z#Q!Ps1JMn7IQiazXr>7s`e$*T$szsXZzJ@4M@tRS;;@ZPO%P`e@ucclh2s0bOBP@Q zIJam5{(HV8(fk{F1;zb68qm&?t3<|??qkjzoM+A z%HPf&VXn>~dt)spGxH~)?^NOWSp zc_u!dd8bmL-ZB235zqhT0{EQj9p@kRLYbJR=T9y95X-Gy+}UnS{+u-NG}yFl0C;aq zOaS|B;|=sH*+LAtJaHXx*c;2bu*r3x$3$9FQ<55sBzZVu*f0pZDUjV_%$H!`xoqi6 zKZvFFr1#T%^hz)<7(ojYl4RQGc(rD8H^vc>f!wvdF%<3@WB<8}B%DL`9C9Qn`lMNv z{wO1A8ami8gBW8#;#`+ znVkghdcT7&2B^yEy`CSJYaVqX1ZJNjo6=u!cAp=_y}#caEP^0P7O+Y~tiJnP37*Sh zCCp3pH#zY!BFxWsLLAJSh+JPye^S1!Rv#QJMpAdPkNo#y`ssS@@`yRt){ynmI9-zi z39yio5_U~ZO+6D_hbVbt+3T_CSlz=JT82b%%`Nzk!nv|QXrxYyZCRI`Mg;eh=bMLz z2NP(PL;$+H4u!%%lLKpT@Z6S8mXD2)f07CMC)B(-$iTn=u&-e(8*hPSNfh_jXMj)G z_S7hYLJm-2V@b5%xMCZx*6+}(+(G99R_EeLGWZ2kFFq$VmB?`D?0xXn`prWkbE&^P zg8g!63|jnP%n+oWLJU1ffNObSax%K@dBMzV{&xqjQoJAw!A>6_N5$qq$@g}N2t`;# zOf2eV<*<_{>PT$kCO>k*2eswxN82EIV*kayHe|IrwuJS$p=^NzysEn(cH-=xr-^ns`}xqYv4oXo z>K0#!2^;UeZMv|q;Gaf+g+kQ0F4DP6{QcqdbT_>CDaEx1NuBwL(9`bJhodFazpA_; zk}gF#nDNgypHYnS3HiVm;gH=MXo80zs`~S+Y~i*`63f;bGPZ@qyI!R<{Q;r24$!D6 z-|LWTqlUvY@O%YhS9sZx&M~&t=2qzHWmHoVelefuQQ@<@PC>?rZ>G4Zg-b zs<^B%A)AsZk=rvpeCeJ{wToCjO6gBV^4Io0k|Ge^xYP!Q9r<5hJ5qXoL=5;4 zEwTv=AL!9-zR^UPH+TH;_(m>JwNO5PQd}QUI+&Q+;uQsLZ~xJ3c$L0NAmvq|K|$tF zqnQ&UZi*1qZ&*+WKR%}&A(}swmTd{b#KinTA;6f37#eD6IC44pe8YgINk^VeurmxI zA#m9ug_13l_w)cl(18KboEYCO$vi0#dL>jedHh!oS5Oa2s^pSoRlx94gF*ME4H~>$ zjAVi~S6EmW7mym-ZhN4UqQL_`ET~6UpMjQ=%A@(klk_EJIGNmemoU|y4G4k_y4+4> zG-Y@V400*V{W6+6!_&~SiNXUG7NDY&Tc)I#46e&Gnt=PgORGxC8?Po48zamp0S$+> za^abgZ$NVPj>Uf4?b5nB9z#>GTnsUakfL>YaWe?^p0j5tH><)c9y&IqP}9P3EcGMx zY&aB=9qe=CoZF3_@FbNhpzHpfZn7k=e0zp`K4IZMO7;K!|uygn@3c$n1y--Lh~UKZXp%-k5Aq&YF<4?WXJ z-Ab)51xsd>6>_BCVi*M24iqxp^=sLW+;)RaEbJqlw_)NeS$))sq&B)3PuEH69#Mq2 z?XgamJl?$|T(r4YWrc%Ip9r*+9k84{Znz8gUE|oFHw7QXygKJ&5AUwxxqH24S38~B zxZ!r2ytd%PCNMmG&nE1b_J`E&*|WeY!#yt(!cT8Pw+0j*@6XfEN2Z-B_8Li8s$JRX zo@enWrCLJN==v+qSIW<(wIp}<&BA-4ozs=#%GPhKLhlWLJnnBheyz4e%K9j|nWE(w za)M(UMKIl1;sJ-RC(bOoVo50EbePQ*$K|!9cZuaOrFX6;#Jc07x@rtoeh9r}ts@e0 zH_!!ln?e4qByE-d=&qs|fq@hM*N-eEGIP=QaHJ_>p$ zB0F@8xj6Y===H`;GTJyXJzX7XEq$pWo`-5oL0s>*h9rqdi9Uw@UTf&i9UG1$^7IqL zH$zDh?72VR@*G59$ci!z2fQeArzPOil*%w#@O7vzQ-Gc`f){MD0~7?6wGK0+4!b6| zcqPRrmg0M6nwDekTS5n?bBzpf5X;sxSKPY>g!o6S$lNaClWP;gnPl0_;HnwEHawRwW?tz z4vU+LZR74He~zOvx?Ct)m5vt0{K~0TAbB2Gu=Bm#SVLDE6Jaiv za3Xv3=hi~t**~mabLno`aQ$s%^^Eo8uH(IPmX~h7S6=;Pq|}6K zAUg6L3wEkCf|vSyPk^b{C?^$Hr<2wT2KnsUgyUU3l&4=x@6x`|q3;q5zOT`IcDbz> z;x<9RgFSr}mW^$5;egFBYIM@L_OSYjq<^IJw8E}8)BNtjbOjVoPxs|} zdN~RCDQ*xYxya=m+dO{&mKMxmqM7G&zo+e%o+jCVmFnkkQ}Ji#3x^PkTo^M7YFx7+ z;yWA_Bhjw$kbYvT7(K3nD;o0Nms;@-WzNd4*9}7FDQe;TCoxZpUCmMksY9nmtF>}! znuB-4rDFJRg8MT~kXY8S0T`lqIH}SApn$;^`&l$bn!dZ5bus}b zMOee)tx{N3m-F>$Y=nXT*k&G1#`YV>c z<{n~xKWy7gEXm!5ZM#G`MHrH)o!zlQc|mG=xyO0n&5z5{VpbBY!z=X5v|~+8?~^jJ zMnu$^={uDA!vsJYEvfR(`D2GiI+ZCQbn7t8u_;bDdlwFfI$W*5IpB7+RqJ2EHex)p!e1qjxjL4NHwOSH&sfG)znz8FpcBCT(E*fi>GHf$3-xcw$W<5>#D3sLg$45pFBRwSmN zz&OO=XQLZSVp2Oz*c=@~#1G7NKG2(~!_6(5xF;#-TU2+P3G!cS zD;rPzRf{+ps2Dojyzc2vnlI{_XXge88hl#QSPD7aCR+Zgo&IIO393u>0w-0mwR>uB zS2PjUrE&J7x>v%-nOcH~T>JD1x*fYC1k23Jr|IN>Fy$mJF!30B|DXc0qz{iQW+|i` zChf85tLyd&S<-YzG7HfMItcra^Ad#f0 zl1V*x#Zq_3cDZRlP5k5B+Hz7D5)9bN_Nq`;b9VFM9VqV5oiEj(!=-V1Lvxe1*4uig z70-}&!C#XA8(nt4{P1Ai-}E{feECW(MGu;F1GKliIx)LD4Hdex$x^M!Qu!ExYTh|v2K^@#Eaw2OwBB?agG}xpU?JT5iCnsyRPqJL zpgJxKs@{h@TT~vO`Jxf2%=>{O@+W8OO~~YaK|kO<{Xe4VNyHzzdOzQmxcNPwB|Dx@ zhc#boQXDlj(eF(UuMO5dcjxBLtkh6Ex8lJk8-6^C!|npKel?u38Us4oedF z?s&b}J}=t~e4+kRs{!2s#IhSzqRap*eX?{`dD6{BYl_*}J2S61=G2suK0BCTDrg#S zbc^r8sCKNAAdy|Pw+b3J4Ss8EPg70r?eV&;woa3F&4|J*4lop>HiV#2CX0z}C~26D zOe7Fu^iftL9bie{jrM}-k_yqG3S++tIBWN5_6_7Fl$XO4%VqrudM&LtT1{rEZaxj1#(AH`RHN2bpx~0^vg+2;iFg0Kt5w%n zMaQ)BQPy5RP=iwTD-b-1UG-njJLl{7+zSK`E5{9&r9S|HcGCsR(BaUGSHSA1*8KsI zVNM|V_uahZGw#vve)RiacPnzfF;?A(P>y^_NU%ret4~hxc;qAEm zS=XZX{vj;cYjy8}o*^P6X<(Z$lyo?sDDwkjeAGyjTjO}EH@6-{PS%0*JJad z>Af31tXjCf&xzu5d|&6^@iD8u zw2CY6)bAd=`hAQ_rfXvI>{ehnyuMT97X_v%p4TWFtFAMSX|voOu6)N3<}cUlsm@sK zL;W!doXY{eL*g#aDMcBamC=m<+;}6nhQ&+VB5iaS**U=4E4(^ff)qQ2D%aCX`T3^l zxxrKpPK$V9{|B;b=%j5ZY@VgXYEO0+!YAXTo!Gg6G(1)>sqk66eEcd@TR`sP{Z?$d zmo@JkgMd?+j-rWg(ZszdIUM3@`MQ|8K3i1pxAR(Gq7?#~#6N@9^u9Xq zLbs%LB&G@kv>XZbc9OEeLS`vKqy%}6v#eG|mTx!qfm59&*cI-LSdya#UMmL1UH<&) z=GdJkb|bl+HonJs&2Tc(m?gr7CPjW#OoL>8=X~<#P7HeMstN~7^eWPli)7N|@JN*p z<9QA?Pq@+Wez?lv`maqs`eaJzuQdPNAn_js8YIL0{fGiGK0bWi&y)74Tu$V+wzeHt zeXyAx2WieOKsc?-Fj^#IXaQT403kTwfp0dM4k!S;_i6O0_-Y?T>{e#BUWJ3E|4v1j z-|6Q#unTNBG-WJUmK@Io1o6H%DXL`kxcGTzjFVXMZr6c&oY=jSzlS<9 zAC9rJA5_0zWR2gvKAY=L5pK2ex}8H!b)O?Blzt1I+~L6_AlpJo^SJXDnVtUk`8Ho7tnVA<$9WTfrYR9GXk~JprZ7cB zNRyY`5sxb8sZP|@DNj>Lf3loK0-xI*t}rn|^p$_KtrMwSM- z7$cU5v|GWcryYjoH!(=4iTnz+GJT>TO$3dH61BM4=n`nKiKQV_tc&^6xO%qa-fc%X zN(Q{r8ZYU-!C zoDbF$rvE-9eoi�j@4P!T#vLv9}yzwuxxir@W8aeZ{XqCigml`yxSE-U>8wpEV-mVm&7xJXu?3`6= z|ERKkOXALySSY~{-reY?iYs5HP?-JK=SCnv@bqu9_(S}~uKm0TiA;p%(&Xat8gQngIo+uRb zYdQ}_2~$7wH;f4dyVOh&nMP>%i>Eo<7<$u!#+Al=Bg@XIPy|_0!QteRB-wW}m zg6Nn3v<8}W;}X4ixgQ7^uIcEewMRDmVUUI$TfKmV`$OGGbX45w_S8`EyGZif$hlOc zyhkQxHHHcaYBF)MNTf7)jw`^omZVZ5bAtSu`=!EIltuA`=H!pV_U+|P19pky(onk? zyC$^ODX1}b-nO+9MWkhB5-~pPE)^SZYD1$^`9njw>Vw;0F{f<=>a%Yt+>R|QsH~K#u%zDzu$XSz&qg^idqI-{dAU%On@%af1A4{MwfvGx`{i1BH_w|23QDR zkEceJE7H4!iR1IT1A+j2T%!o8`u{;Duf*C13)M5fd5_buW2Wy~Q2ry2FV61x-@wvI zw3Wh6+7Lk35#00`+wkA}9M(}5*m;w~qlkOkyyECrwjNc!3y;VwrMu1QvumV((lWIT zt`3Xob-<+I(gQu&`NhT6hZ6?Bb*u(_Yc$pno%bKiTaiiLTxQ_|QMk=ZvfprX`;k7*-Ts4}YRoBeDbdjnRBI4xL1-){e@9zPQ4SKoiqZ zJ{`q+Nc?!51Q?e6XXXb96w6C`%6f=l>;$P}N)i#Colc)U?Z%Wm(+sZX0tnCyN#{2^vv4n zZdG#|`EE^@Njj}jpDCD}|LvxLQbiWDab(6NMx6?nPOL9&FH{S5uM zD|?r(#WfKl-s^h)BnIlYJxc%b|D^?hLIAlwpTw@XNQGR*SSu8kFp5Nuvsh1$qM3LLuK z$?c>RU|)SLCx%rU_}k%U?M<|%H67l_~aWa;8)RqESWP%&!7*bp-6hR9ljNj zCV}|P$TOk^F@1PqS!=EX;2V>_(QtluX!X;XH}Wtw;$RWM-8Z?_i|GK@qpZBM(($qU zoD(CXD1(m33bO#Ch_r%_tIeSIAmAN?zEW&%>}km_OPVs#;QqvJ)3YK%q10YbYr!{C zX}C#&_&#tLB@m#sJg{4ui~e@?bkWP5v$C>_e2pej#x+ z3F2!gr8Y)#Y_ri7k!s#D5(?1*i0o8IWOUL_NpDo|mO@zU)=3jnPCWJ+ zOdkQN`}MBvzH`IywAW{1{^dQB@$E8@b_pU_QDc2M4Q|0=r^l7(B>Cjkxk5vkUaToy zd03I<#JD=0gYn&iVXYX3%}>2}pKlp5j@IWT(C`Igf^zkAzvYRuP*zCeEJrbBu_*3g zH{Y0u-%k@P!{IXaLvCMXna2^vQ^7c%*?y%0YvSQH&hE`50)JbR%DY+)X<@j@4C9D@ z&eclIT$8GIv%7(Qd91|YPO`r&pk{}@&}+oEO?ZCMu$=7;IsjfBkG$2{o#~XbMmu|J z>8s95E~rph#nojEF=64P)~*^+OA7}kMJNRt#G+Alyux+Le7?X5j_V#&!wQco2k!_9LaY3ZxQXEH`C2HN9?=rE zyMMh-ak1-wKZa2=1g{fWd zeDs`ZOR&4TOL31XnrJMQa z#v)dER zR`wI)K)PSit=ph}Q#u@>>00oo2B7^uGlY&~N6 z*W0BW!w*zTrjN~YAXVo4&BZJg7mqembyxjlV1phX{9#sT26xn0XUW5R1()f=JCO}T zKdh(m?^w?uMTp}R$7cX7;YHrUe?yODWuVC$nGl-duZF|SkT|I##EsmJ+o?ymY zyb+mI5a;qO3LJSV6G=wS8cIc= z)O$IxKG_MB7UN1zRCbqQh zzOf2rM+j2J(Q3cV;Go-@Dv!_fkuo(xDv67*PM}^ktqBw_O!N>uBuf8{nRW~gf}Abv z84P3cVK-<+PiY%WK>hpUCSjGSoWjM3ZuxlK)GkeaxxtuD)p?)HqC3PH8BpoAj}#(j zwk61r2NJLIl;o&rxa0n`qHAo>CM7+B%T3OMVqDO`lqyG>O0#l?Vi747}ctm8r zRA9xnOKulSk+YlMu&D(*K{6SMpR%DyJ|fD-*XFLDIRCaYiR3zul+1P~vnprY>H#WB z66Fz2T`~C>NHG70-P-sfgL{#=g9KZhI*)tvrqdW7wrI&lzT_hop&`fm%E@VK2c_HA zHr$)~evGE#`24=!D42?y(1-Q=zcbRt#no+SO5atll-R45FRG&J9ZM?i@Hk@{O{TN| z8l3M6s3PB7wY38PjTcQ^TZ}{QNK5a)ao6&pvs;1G`vo?u?pJ&hvGVz{?~Y%72tv&R zbNBz;)gvu!0!#dxbG&gk!RbLZL7xR$k9?x--^*hpa%#HAq7!Y_>06#ZXazoBzR4T9 z(sgscy4zL1g3}Oo#1?1fCANP|aA*q*UGm?8THA9XELmXC7~A+>$h$M(-uKfoEzxIp z`w|@TyFkm+cSk9Y%`>?FhwSn@cxwCh$mnd(JGg0TpS*}4xqq=tkkIx#TPG2O)TGpK zP!+-o2}pr958SGI5TGG)Fjr)x&au3V@^r7B&XPNnL!zF4KK+1VEHxD|8L^YyEABt6hHX0SE1 z30FDwg;ia2d#vpqZ7D7$m*c%2cx$6WfN<1;Q9W^cEZ751)Zm{+!9WJ3aaP^Zcf=jG z1#%g@PjlIPe={_N$!Uo7VA7I21H43erj=w2b^1Li$M3y?=DI(9U z#yw!G@$%q<%2@EiGs^s<#y|N);OY!_>Bmi(>B&;Z|Dv7RoVt9HscV-4`E~qKyc~p! zgt{Ap9-_(mxFSt^_Rke=1}R&k8IwBJ$QfXCs=mp8c=kM{MrY#^SMi;@{=rN(PiU)q9o<@6n;lnL zNo@dUXJU=J4Kb==l}T&3sUb zDowz{*Ec5}hJu0al_I10;_n$E;rOZ>kNZhl(qF9VD_gE%*|m`Zzm=X~WrRV?GlOST z1|^O|DA&CQ373y3bH7i>Y%fc2Yo)oTk(BCfX>*w&X+)Zf&M4Knse*$j$mjd5nEj?4 zLcq^$$VJ68-vE7IG1d`?Z|wdT~8N@kvRYw*{J(zaubsWqwyP@bb#OQ^+V+eY{JX`3H% zQL6lyY<8DuPh6ue3Fy$Ms|z+l#RL6aF><`0N(EV7v8qjf{? z`aBzk!4cYVR1R42>R+WZHWiMtapt6TmCy~ zX%$StV`t3TW#Q;TzZ{O33tmKNF`{P57zP~L-c?B>075l$^ol=K!Nyh!kx&8&yx(r zKtr=eLHg7cjf9dSO&lZwHRB>gu6#GF3!tQCJVsFTA#z1~zH>F!JjY=gx7b9<=uw%! z*LSV+c+VaqCO!N4bray)08B7R)Lig@ipm4x6u)Q5*6>bisY`P_kTKJVq>HSMB* zTs=CqK9Nk{nJ;m_HP6|Ft(e-WzWktI)1Ce??6)4~cP!7@PCOPe zT)m&&{RX+!X^XtYc?U?U_tHwT4~`IhvW#P*8K0xgpH4aC_V0f9%QW2f?PzPZZR2#k z?w@j={idFsuGv{i`Al@H?urmy!tYgi%vfJK*lCgXO^|O{ygsey9*HUL8o{p$Rr=Ub z*L)fBnBZp$ljt0*fBXoad9>d|rD*+6$o_KtZKTbcL#agRiYZr;P;P=AGW-oCTtQP? z(w_d<9E)E0!IH}{{WX-)w2TNIh1h@TDxZrLuD_??Rf>S(PfE|_ZA!WACFUT`T@Ow}jE1^F+6kfZJmSE^tU3B^>2Ng~IB(^0;cb9o6^Me@!&Q7{}$Beq(; zm(E&@ssIc0eO2wAErun}u}S8xxEl%IwVfap!?Y9BSt9yUPYS;clnO@1#`0;7qUxp< z-f&-9$(ifKzxdWQYSw4&VC4(?i}8&^-hlvzw^(^xcz^Z9D1nl4-+HSFrS$w98<@g+ z-YetFgLx;uUoj`~D08{&+!yqdpKods@po^OUQi--DX5@kkb)&U>0zZVWj%4PH8}>h zYCW_$DDODioJrSge}t^r{=H6JONVHqcjP1;EeweV3hj?+5Hf|~vB{Fn3GouYL_hkj zIO!LJUNUgrC#1So>{WpL(88c+adiZqX7efR%+He3=i9X$@~1_@ zW%o^V9r6!E5|D4D-1l0(&eSGe&9$Q*P%NO`MhorGQ`1?MT*t5+j<@EM&XkhCaMm&o zLDz%TX6q9X!IK5a)W|LE^E6rt|Ba*;qGKNs;bA_i+;$92`_o9;mwWFW?X81x^MyQ+ zx>Krb&l8D{`!R_1sH)5bcMAEMj_A25#!pD}&ruzxTh&abQdCBFLvr#*g7Do;)y&;qU&9NR)LvDfdP$Gjlq>SP*K1=z^TOYpX1e|2R3`7k8=Jttl9da_ zIwEWiH(L0ArIgqk`|vrljd9i$cj7F~S{7WrLdXij->J@+~_(+O175R{taQd%=!XeH}2z6uyG zV?@_VrQHI2sW;;h^brjxh4#q~cjoMQgcFXHR%i5}s? zPHc{(N>T$uQ6~1lszSdHCsq)*^+)>A27jyB)(^G|>1G~5od z!P)Y}8c+826qis}{FXf^X0t}8a0jalFF8PLgF5rVnHh9(wN3B&84J~ z(@3XD4Ie%~u~zB#{lU*SaYRTdiG-=7y|+5KR1h03hSx`{W2z;rz!C>S6ncI8H-%bo zuH@s)g$xPObHiRwgB8&(l`I_GvvXTfMr171M$|m1I61iSsFv8k2w3@AR$fU*XjGoA z4pK!)b8{w_A5VDHtD&Ca&bm_(f-mC5!niuRVcDJyc18g*k+^K$v-I5a(P-n_c#8gR1ty2nE+#^6UX%zNcj}K-kNIp*@Md5syFB3qxhb^D%HZwR zJ1gSiC#K(ENl`K87)kMo@l8G zUf?({x3h3tg2$k`)pnR#SIc1y87DdmA#*MBipb$(_02OcMQ_Y{EWFjY#fV;KO(#rG zh!Is}AYtY!=}+iyFB2}mDm}_f*_0NjctarZvmz-1uU-sLEc_N`P9|J9o496}anh~B zhS@P2QrH@De|pZSA=K8~ClY|JvcuCA_bTST8$TV&&8JZ*+Gaq61{@(BxPMCy|3?Ab zFp&!1xjYcLLW|IGZaSn+`-FxpR@_tAM0oZeke%xI@2W!XF!~=Mhw=Lhr*DB^%?dhM z1=SG^0A4ifpc@21uwkjwfybJUD|xuEb;a&QSD3;}se+<-O53rMwCs zM329X;?t?&Xohc&!-cYpOXFo8r+KF=?p}_L&6jb{Wb~Ju8TY!>EB zUr&x1S)dpN3VaLJIQe+3@AGY7H{a*u3yQ$39I5nw7b#;_u%28P=rf#ZmFv`?lmr8s zw){U9A4;|D$XFp05z4>!EW1?zqW+ZwGDr}=h8NsnasFyLMbBvXU=q*kVa2&pcYLfQ zyYIu%aueCGO^?@U-iZfC{-9&7^KMcgOIYXkYMb!TN+X@zf}*PXJ>_MUdq{UjMxN`) z3i%D8{wFU*Lt*RnZTBII8*guTg#2EIll?YNw|8dp>6B5rz>t@{U6IY^8Hm$pHG8(_ z3*(f}j?4jmve$D=Z075Gg!{`qE~o8|L(EWab95FE6-9_&s>dI9-CXU+H@JF zPY`a+GsO6qz+jD;M`)((f1>kDpLPp_rTZtLFkz1({xJS7&=`8cw+)j84al{fow%tb z!RNqPN$rnw%~iGH%)!|oKFPGft3E5iKi^`_tjKI>Y7N=6uWt1{q^2;c=IS<1GA<<| z4-MEgh0K@x_bYk?y{RNW%GzzYM$Nr=wbc3v?@*-&%0?IeMm&cN?}DL#3cC@zNk&?I zT_GVtU^do^_b*H)MVBFB^|w3vs+7t6s6WFtOL}DY0a3rqGuC?v*B0<~kuXXOS|Yqb zsbx`M&3Eu!;k+mU`5SRx2i>gxj(P%4y0Wl{ERk)Id1t5xa>g7h*hWLM`HMb-$Y;l3 zOxcw8qDW0{Cw)|t)F}gl4ha&1|5e(qP6(_p780`q6uf05pQACucE%m~EtveSEgRzK-!u;sM;R2{#*pmUWk$rV_zzrh?MEu4UJK z4r#4mcXA+j)OZIIl&249=4==`-5@Bkl!pf8JEvT7a4&i}xz4s~c9s2FA}y0Fi*tOq za?;siK4Pu|Zg!{lQO^0Z1umV<+(T0TPbGJ@WRbzPN1pM7EdsNe5LGlA8E7QU9<9P@ z^;w)(H9KLl2lbCp7@CJ>x#ogFPAB9EVInaU70>+FYYN@S_<~2*zDI8*0)N2_xz^Sk zS1AQ-w?}F>I!K9}{Z}IE4$r{XrP*}n3eTjR_aEM*F<004Z2~J8=!O{3YK&9o~P)9sV5p75$V-O-a!y*|czu^-bnH0PQbaXa?OBYhLck@ZIFh z$l!r$=Y7G6UmMTw*=nGKm1hs3f7Qmssvp3U_H3AU=jp$fjoOQRC$9|;3%fd1HgkF` z$Iq0s?d8Upq~o33iZ2FUa$u5wqAz&i`8Am~jkT1r@u7aN!sQeA4&INEHSpp8Qe^4t zXvT_d9F-dxKLrJ_S~(SG9E{X~SgLSd&6U0?YpN%4U>j~#3 zQ%SZOhums84s6};ub4**??LZ!f5+ZZ>wW9u>d%}!<=;Nfvb?-?T+%+b4l`R#&3;(V z>Z}$++fuoa{yYe%;y^My{uQw*rCWP6R(%R#HK?k-v~~ewh1t~IS&NC>NUy4hhNfn? zZ^R&!3zhhtAx}~&p-D1b@*uu7)5+H_GjlX;RE9Z0Z;tL>Rum;$qI}Tv1RBJ)&*SuIGqw*xqe6gNGq;WLx3*F z%dSIw)N8qJx>a_+av@{6dDYPhwi+-}S{*z`4mL=^&r@h2NyyD z13ue#qQ`0uF7lsSWBKt>T+u`m^wE*{MCGDo4k^e3U&$kjhDzybzM(<;bA=fmS$bGJ zipuH}QWOsxRQ?dNPCaR#**0kj13R4+6Tf<$Z{XEMa=x8&C@vH+{Jyu!zd)pO z2)XY35KKXO(qb`*u=b+E|BZic@UVNUR#uq}Ztk01^fn@`iQy=rJDK?9^7o^2pR9{_ zK1)TU2I;_uAeSkEE_=zh)1^v#tPS`ok5e_wb{O}uYRtLl?gDnXSPyPGFUQ(=Pps+uK{ zj}tPYEX1jc<{-={u@kHpJe ze2@prMf@sK&b#UXaDT20DgreqqRTRx!K(4YlnSZ@E4O53MS}#^fIFR0@%z4raSBQM z{G9SlCA_;5b8q=6oJtGj38Nn`965#9hVMp$g>?*OW%;`$eyJ7FJnJzaH}riQY-+eS z&7v`5l`c;LSxHVQZhCNilnut!-5d ze$V&EFV%e_W2{@=+C9JzStR#XiSIAYLuZX`Z46Inuh&+vO-JL^DUz-xFEXrBKwXo; zA;?FUrlu&fc0uQXf<-HF6=lI=WAh-BWsU448lR__&>4oPY)%G->o6o_@JrBlaV%_X z?oDa#-9Ikqx;eg?z&{faxfCJU_j!C?&kcWC$A?YU?_Qnuc?VOmVRtQM$GH#g@^D4` zGo>>sXZw|~^%u@_UDUVC+J93`6kgE(eIR|n;2J)OMC|qeW74*g-qt&}3+#zTM@xWD z4cxY*Cl+)t77h%m9OdzkE`k_HQAMn11QrI)n8GyDJPIs)wjTt;CC^xMPLIPA-^R;i zQ}}g}Cf-f|8pT(%&X&Ykfb}yj6E;l^Q!iC;R%=TtgOlwxMUkV={ieMx zsV6N%jBg=s{&<3tCPUcc84qtNO<@G3tVsbrIND?#1IRVxB%o{&H{rc6Rm`&Cj@=GcHCOL_Dnv7dkbD84l|va)*|h0~}cd09vVDUfV8 zkOE6Q(3H1ldWBmG?0Cx|JAVZIWl?OqBRUZK3ief~?SYW=2tnzzMpTGM182ar4RB)s z3vBv($FyXvw0*zh^jwCR_ytK?Q&!bQSA32&gjm>}Pmfpe3&TJGB~|cy0Spz(poW!= zlqHUwSkJ^4*mCp#)dIW&F0!-nc0ws^0w_&jR&CDL?mKLBlIVEQ8_<%L>Ex8CMbVgG zd>SXJLLB!E4);lNq#}H6WXihq@JcL}hgLOA$~#78$*9ps$UDN0M&YC`E{^%00s_kf z+gYLnH5yu{CG?IJ&NLPqsQHTU6_vKtrrP>oOS_BWhD`=p^sU@;O173iHEY$~}#4Pe6@J_+YR~ergO2_ga3xwLavDrs-i7C%gQ@lSM(Wl1;@&e!W zxuE`gCs~kPE^%_VtgOdRu{%qp-iuNxmqvZOu%jT0Duen}Fi9ouTPA&&Ao_ofGl(VC z)+a8&lLVuGF|SIcg@*Hpe`1})v;{Y?w0x{%$V$fxQV|V3=7cC$YgiQxaPLG#Em#*+ zL@SrBNK@DAe>1=il)_$6P2RgnB>>#qNe-a4C9ueN6?fGnsZ#9{#ygz2ydA=33=vhY ztz0{Og9bDLeyzfQ`U|$)284yqvcM7Haq)jR5<@Ds1#-hS3`bLwzph^|Rxp1Yg{j1TIQG}Q& zA(jSM5PSt{_R4dNLim1fiQ&V&m(8=@wTVeHx=43dbH`(_#th?H({DdBIPl&zJJa3r z^{b%y2gRqm2=b*8sjGhF+b5Im!V_o&BI*|Fq7tEO5N-$pbxg*+2;D1amo3w>#Aoo_R|st z>|~HDDR{X|T(NOt;BlqHIFeZed?X~omWo=G`}T26T@P@`U*>8^V2fCq!9F#KF3H^MRb0OpLJIX*(k2y#NG`eX!WfAK_;|PzM^B%UU_r?h zlEI_a3`c~ImTGvs5Ti&&rFz1Ap7&Pf3+Acm1*=EdlHMvfp@`qP24pZ&wyws>@V z#!y9^+El0vQdLy}-Gw;GDt+;JIZq{2gMjd-Wx7bgpF8(2vI|gP6q{eEJCh2P)B>6m zim6YnQRj>YhIdM#IqU~QO3TwCw$Qf+x4K7U?P)4Iu50_`xH0-wzB7C7)?GvCjU=cD{-titwbMA+=*_J&+yR>{4v(RBvNSrjD!qJ_PWH*b zuH~+HKC#TN8_%jv+|sxie;oWn+X>!)Pn?GEI6YCqMQWZ*T5nQwh@(Bzp2!#&S#ow2 za}+R3+LP65C8rasAAjNYDl|*EyWgDiU%da`dq^WArc^QLB;4B%WI&Y*Ug5tYw!iNVe&>6qwMh@<`Fl_ofqQ(qF7Cek;=r^oyUnaq z`fDt11X-%H2#!f)9^G^bPXH1T9+h87N>UTLpaAuT1-GA3Q1R$Ka;9BCgqNU%{h+A* z5UITSFSD-uhF-iF3SfCA?UYx#=$lL+hm1oYyu{YlPU0LBa!lp2iw|YkCL<*!<*?nC zP#0uHicVBGB#~H*6%AKV@&+dcIcKeCB-JKgW|>Z__dE5^jiSulz^Tjjwa76c%M9xz z^|^J*ZR7j8yX2Nkt5vPvr>{2wAr(n*u@$g+PfT14IwqtHL50NzErORutp`lOyG$`9c{<_x^?#Je)R#&A~y>^C^5csdho5ijt&gDwo zs6Gl+wsds9YBd*?~f6je4^07AxGyM zG*l{c1E%RMzsoPzpjCn$!>!V>;=iK@X+}ZKKg;od`+rYvhQlas?tTKGT*Mfl|Bas3{ zBgYDXvT=tvsp2afJzl$*B;qKFFw%Iee(qvRARi;m8KXktGPqgeB#%fHDY>gMw3VSE z&|n#JL%u>>L3j@s{RuBTy89QFhCf28D(;q z#hwG0_10J>#>tQ$&T++JPQQQ!3ZaP-0jm|;WY+09fOW$l;Pf58Lv*`ZbyNrqw4E73 z43WY`phEl8n3JxVJ9nkC2%Sr&m-by1cc^=J?-g`)0SzjAdGV~uYEV8U@SJF9v~lv4 zxH@xo%Ih{Sa5jJ7;BOdr*7bRBa|TM!NZ2!C7`wie>d|XYhlp%Z2fNO&hrn6`63ptI31- z`BCYVM3Jkj81O2DMn|8(Nv2B|ubTP-v#rNID{DVHELF_y=Zp8g$>!1VZtGK%`NRZ- zgg^jBxk--t_Vx^qTYjICT5*i%ot<7s=UMAC&oYC_K%gaFuYKXxaCs5Uh3Tsli!{K9 z;jd4L*?b<)T>E%^uzoIBB%^Q_{a4q-nCJK;D^RM;XWrcWpa%@PcN>WRE4xIK*}4eD zMTz$wC%;S%Z!YU$xMMgt-VgH5J>o^^<&5)8Wkeuv1g1;;cC$wmhvT4cju8B2aDUEf z=dxtGu)WIqj&v+=`k~LDjVAFLej{v0mx6JC+ozUsu33r}P6sA78x52(EEOIU|mo zA`Wd)bzNM495R9!B$H||b3tYye;A4yLki2`^Mr4e#ai>81W=OUA_tgb*w9-z+KMtE#PgKxsPQ z8Wy`fySDb+9Num^NYC_9*FOCUF0lE)-*hidUZh}qvFRHI;E8mV#icajM$^(Psm9B- z7RPPUaI38gAdV;xPigPl4f}fvS*@x!OCO4q^G_ledfle0z_UKnCdySSn8)q|3gu$Z zhqZF`wgC34ec!c>Kj%s7Y@@JW@p^;<99JevLPy}EbD#;5vDlVA3MFi}Q^ z3I3IwH_iWg=BO3*Uls9iJdj^jPkx=cxEH6iyZk6F^38$clO&0vox!*Y?JCjui-;7F zC3=YqsiDFhW2@WQVl5>ZL_#W4A!GN0HN5(0U>6#V_{b9p4ZNQbuxoqrh6#5EHRiP~ zFIStM2kaV)_~yY#kOSjpfa@9bl8ZUW+Qa%K&=He64o2}e|GtVKlM^}w!7wSEnr=Gm zSL5&fWy_Mk{0#l9?euI&wW5>Z2*9OFd(Rpgtf%8o$hkRVS`QBzaW z)C}h@PEb+;lHS2W${e9rKQ-Uk55Q2ayu8>ChzS)>nmOwkR`}C`^*6wfXD6H!@)Z#U z3%{W9k`cCoCe_$egRwhAm>>&9oeR=P9190mhy%Vnu#r+M@+c0g%;Z-nBq8}3tW!SN ziF5df&K|1MFf0#On(hlnj)JXxV%;DMcR^R#VB$OQ#mz^(TmQ-o|EIUwMMuzm;CpE) z*Dy!AdHsw`ZB@7RY|~o0wM7MN-A&x+8Vp(c+oiLQa=mDI7GC41T+u2sn>vGvcHIHZ zeY^Q|>+U0;$e}#P^&Z()kH$RQ9{urY$Ck#t%-vK;VWB+%sf(u(RB#CMOY)RSSK@IN zjZ~awnfUt}oylp7z-Ixcmdk|5T2ga-xbGvK)?nnbN$sjM8t;1nwcy)ZTBG zr_)O49f>Jzt_r7BgGFr;$)sG&Kfv_E5gD(Oo)p*+$q3L>#zWPWXJo#1FUfzGH^Sl$ zsWwg}4>2@23Q2lWae4cdW55_Zyqjm)tBFT@T+&sYy(|GYXPRFMa(h7%N3 z8pj&>zfO?!a37JQD;nav=w{P8}6yTCP>dq z7R@Y~k3Ebn2yOTaP;pWn^T4lk0>Wmml@5>kLOFRNkxUG6CDmR=hYT}r|8xa3C8aiX zBso|)SpS#5frvle@0SP{_!02KuK=>Cc9+L*NLc&vs`c}Y?#pe3v}Lygh=8vV#h32o zx{Pkmt^MOq34A{pqnh_$m))xaQGVVay_Nmx{R~$)RKmqaw<+YSE$BA+zhyiy>oG z<`x%=`TO_;jSn67|G4_CR;Z32A8rmabho zmTm;3W9jbhTAJUD&-=dTdw%CE|8O{mz3-XNe6G3XnwcNoZw=--u73;DMytEoo$Cyb zjY-ra>1qjb)0td_saSLEv`deh9FPC!?AI=koDS;~`7+-EghrN|s;cCZ+>kKM&X(MN{2s(J5VaMs zd;XTp+BEIBX;s@BiucyG<5;D5BTSxVlS?2>2agUzE2dO z3wciimXNrwu45rQzX6*1=3tQ%e*hrT|*GA8Tde0bYLuf|Q#B|_-JMExkkMbHmE7MuUDFV?WVduu^O@LB zh0(82+g^Ii$*_dp|4XVl1^fdJ7FPJes~Gn8O7sUY${U5t`QQ5T0@V-P>z`TJ(R~EQ z8e{M{bRWcAa55o6(1ggy+@BQEN@{8!A@G3UEzI8+8AiCcYFfVDA)b_k`BRF zvw|N9u|Gz=l9Qw*2?ynjln!Vs7Sx6W5ZorEoLq0mH?ra^sK{wd^{CWfn%kMZRYB(P z^n4^TN{c9if<5Y@Pd|LASF}p{3bmPb(!6lzHL1p4N#)y&mtZ{&DDW*|Q5w_P?D`b8 zYFMLOSIIM03@|mUGeRJ1i^9&QMSa`|-L5gs_Av$-Z|SK!^vp4FI7~$lo2lzEE0I5E zPOF^5w2@c`e$tsYI$xi2zhKKRLvU^4lXIt@G%T51JnfA!GQO8f;r9l|d!=lK1h&U5 zmdoW&b8V0BMl&wRABp5&Of`N5_6B%fAI;78H(WERm2=zAx$Lcg_AC}6`s$ex+*Jo` zViKmNYr{ezjlaO;!`$wmW5btodnO=h19Z{;CgzliJ#y@WhbK6Lu zfqRgfwcI@o@i`;0rCU9M{Z#_5AZ>MB@kKavx%>8%7;=d|8iSrQ_0{YaohMpQe!f?~ zMdo>8fj-cgqu&z3FWK-RI9SnUJX@I)mT5a#L!B&nxYaDE-5k`Ahl`!jD_VO6zH!={ zU!A%QLMMZQBBz_LQ?3<5!XZ&&^?$fBI^_S$8v!^_MlR5sgnUU-&ljUgm~}O_C(AhV zfkHKvU3!E@zh3(b37co&P3_ zAo0Lmx>i-q{{s)~*i#5UsHxkqZ#t;*j~%jgP<+Z$K>=J}* z%N`Q(x~((1;1pmClK1O#?33$MXVlnG8>m4_UxQ#9!zWp7aeLPTg|ZWi&%Vmuqy0|y zVCMK~hlbgUvXV8+QC_KVM2cm@EWGWs0*StF{9}AOvSDHaB;>TY9fKn$lWjd+#SUq7 zpwz&0I*GJdXs~|?WACL^O8g(|i?LW~$-i`wZW6a0GrR%+{sZ*>sqcn>)dR-oun*T= zQgL=mp?rj)AFKBoF3*wzA4rV4uZ?M_DeM+XzX*ujZKi28`YlI*2MH>B8|G& zzJ!i2n)%9v5BQJFE@B6!SJz`>hhwr7)Ng?DK)2WLPYJ}R!%nrI#8eSuTf;w z-305WLifYcsoDN};|ED>D1CMhGunwud=JrL0SDQ8Bk7Q3`)*pWhrLnZSTEWfOeYO#0rW$@X}R|fIxL09H#q9)W__1xX)xvas~DM*lfeRD+#YT_E`1QNlt8|6U9%)T(u})pwqEce zCHm+)R76}_8XK6T3rswo+G*dZ=(?Ib`Uvhm&{u2rt``*Q$66sFn)$@Z&i;-uD}$1b zwUSaE1!!ZcxbqzMa97Fi*9&H3JZ!Cv2Ot$4aDQdFVkW0t%Kc5JbVdPH=8NL2I5n zy(;gJ9du8uvV#)Mv6k8(VBa7v*O)iEE>dUxx}Z$Ot?b?ViA6484q8vxHK^96fgS>N zwo%DpcA`_>xqRtzuIG_7bKj{y*@24?e#)=yD@eN;b>mRQQ0|w#oO(huY2SV-sfz^1 zL~n}(E)!+ERsibjIBVsExl-TL={IiP`hVGv2>0{_R=?P;!CW}``Tul?RrmufL4ZwR zd!DA=9Z*O+(kGboUkhCae89`qk!Z;nERl)}f^qn*eU3O$cAT(=+w6Zza~L$pl^- z7FTUZr(6u#F^6Y@gRS-3y7r=>E+VaY-}xM@S2#Q|{-X(aA5VDMx(C`Mhg$az3gV{Z zlxqw*(XDY2dF$l6R&V3Co3d(Te3FzpZ( z5<=tF?{T#~nT4@?kYdR!P;Tgl!QxhOLYI9Y)^FT zL)R1JoAUCrUtF`!tS~)Q-P|CbbS)qDr;iUeE&k~fn(H_xBUkA?NQ2`TmAr3RpdZwr z=3(W_HlMezw!5qGeGds~N|SiSTAlfzmA-9_sZ~Ec;!_noH#api^MRz2ZS{-+9d;}u zx%=}XGGXicx;&pY1hb#D?(hn54hM?|X%$3vy(9F*agdcit)uw57WN$&^~1r<{Q;1u zx*g>oiRjVK;Arg)?=cnVKN*;KwleYL0PozIm79YiG-L{+QctYX3@#9*mjs}Nq~hO< zO*w1Bc4MdCtEe5<6xTHX;b|8lAdo8g<$X?-eS*3Ql6Ytbbz*x<1S+6bNQZ1vWw+yB^Z zm&qojf(_AdMmXJAjV@>2NX(ntxJJ*h(RwIy{`JP7J8vA*hh8h4yuV)MYwWz6aKub% z1ne*KJS|I+xABRQqRI^J$s7a#mfwIZ-k(Ijk5=e!q2t3NP?xXY2^$L(p~-sS6}vU;*f-&Rsm~S zw1|m0XQ?dWYMG5^+e2}4L=;YIV3%yhkcmrrM@XMrTTjW@aiL2LF@J07x%}w(;NW?5 zbW*7KDW@RC*S@6h20XjZs1wO=14|tl>aKS%77kKcpLxjBc+wC8EDEL`Hw%{WsXNwI z@X}~FrLOv?EdPVc0s^2W*t)ca`I+kmMDB5#gxe&7CKjfZmy+T+T4jj3P?!XqZeu$n z8{{4JiJ#0+*G$m@_zlV)rO-F!!&6&HuK~=_nDi=M_sVOdQ`;e4sc875bjTxw+?2~! zpan^_s>xLS9IEGiQp3lhGewlOu_b>QD^BFdx06tg|L0m`e5-E+?N~F6h>{=EI2=|; zST)jy`o@GiW}$Ko>iv^Chjbvy-bs+puuj#>hQQ-ZFW##Y`$+Y|Ulo~qkd++_^5BHP zxgpQVnB!j7iK(fnZosloLUl(IA{@<9mEZ7}k6U{9tsZO+c7eVDF=ezsyJPNpW^QG= z0a!lPC%BcLA^7pjI^N0N_ja*#ajdO=lur7{`{Z7e%qXbd(UTVaYd~FBgI|D_@;o*b z6RPO`Ulo_Xm;R$LsogYo2k{P5Dn>Xn9UCoQ<9f05 z9vTXxr}u*0uV5NShhn^3Gkbw8GS%%kTBd1)BK0;vhr>)1pOp=+YQ|vd$tniymMZJy zq6G_~t56XiS?4@7vb&_&Q*tOh1~&$q+eW{gJ!OXu5JeNHD{z<(fmY;nbQa**d&$PTf2#Rse*PN$`IzbNJ0Q>Qh4 zp^2I=tr9f-c_!C=B;RP2YG+2KiA%difg}$g7U)zT#y@|<_mA_{jhj1bReY28?aJ)li{*NK%N#w` z&xqAlN(kPEj5AvhMLazyBf9r%U`gmrGkJtPk-jre`WbrwzN)R7{8O&F6jSImIh6dn zMcC4>|D}10C2eD!k+OcD!gY+Y6XIkkNZpgR?b?Dmbe0MIP=QI?0+i3Mg^onjx!mv- z`QWZ}O8WY3vTRnSwzfYP7S^TRScA`Jm`~9MDrxa-MBA5}ei(oWzSp8)O0UOt%uHz1 zk76QV_}cWOsId`IwO2zU3?Q3&FV>V~P{$M1TJlrhXNBaMfCz4>>M_zUH|pVxL{Y54 z*L+6Px#4VxEVe2hrw&IvDU#*;jWh$Oc6oQu7N|@DEWVm3=b#u87_L|$g(F)yXPw@(GZ6#-uIRNPz7T`kB+)NpB)$cKK#(ta3Qda^G7<%yO zxTO=lIN3WuT5KtKUsOUu6g}5IvJ!at<2Ih~D?(N|>z2yOY4_5MMhMRS2zVX4T#;$> ze!U6Mhu8V=K##;ck6$1?zbN2R*Ph6*;x6B`r~D|@Vz*ENy z3ujxoR^R=2qOlS==C_5SbvfeDjT}}87bMCD=v-uHY%VVgi<L zaiX#S8oamSeE>ZgZ7h8alj(h{6e`&pGIOX{rjX9d&0P#0K^*S@i!^v`W|^<=FpDqB z2PK|L_2h21D7>g>EkNw*6`79hJs1pjbz0fDg2*d0G%&aeGQiTEp!8zXekx#@<5;1t zj_ZOSxqq`hu*hI_wqy^dVTk9TfIsU>rUALv6*$GibQZ_D75=szqf6svBh+)@659~` zQ@KcxqXGfzzg|=oeI_%{!Y11d!YDu2fpi$v-BkY*@($~LWu%=>wDRn6$==X;^Aj4# z*9X%$37(`^;J%q9b?l(eh@sQB;F>s-1o<*WXFlnyB#-tYYw;jKJ z2Rb!m4zliAIiLfTIrC2Y^`~oD8woVQpquTca^nQy$n0Ltpt}~KmuQs{8%1^Z+o`oE zHfeC&t?qeVp|nHLj*vyL#-*KO&~PXvS?QNn4B6Pa1lApkr7QHvY%&uPyu^IzaUL+a zvF;jL;hiPy#_ys({PudSxL=oNiw1ElbQgscT>4zS1qB7WI>c`58jiErN+6fcU@%yt z!txog?qYiq8SEwiS04y3MCnpEA!>o1t;qTia{;Q3h{fw#Hzzc1ouN(_^@z#XHSjO_1sR!`+^!Bff|K9eg`$?8 zUvP5RMhWm`!f1gVh67VV0#5i*sFMzf(#b#-kCZ;I`g8Z|Nf8d%wEMM=*Z5HU5qaNl zV_?Q_g@q4RTw1S!f%O&}GsGOX6__O2p0w=+SBL;}+2~Qv3Bk zvqH)@Yivc1Hd7u2e69@Fra!&F6`AwomprU!cszAcAX=JOs2fdXBnvV<*SiF!J3~KG zj5M&RgGV~cZp-}oVwueK%YzF7`WK`dPmJP@tz__rh$mZsJJdXoqW*}X4(*ugRBx-Y z<|(ZC7p?z&#U9a8)R5siV4<1fsi1b+glgG z^75o|r~VYN+sqf*cf^Oi9k5T7Oa$1evX^2v(XZo!B(F{=O0sES3zp+^MzH-F=NuJX z1)f;@vegZRFz6JEr++^MIg)(F$wS@e=GSAFtvnVwdcU~A(S8r~(zJRmufEuE!=kPc z%qR9tII$pkKl6MO1orJXCZTNx3aeX zJu}`o)B~ttE`f z0xG?Niu^gkSh9T--J#{5dewtm7~R02AHq(t7=2?Nyfc(Yqx8%omJcvnb>5SRd5GXFVjrXN!O8&Lj+ z{Ty1qt`S4!JOxdFGufEl74|ATA%3mR6^67;H_a&{wiV@c&mP6XNiZ^^mV#(WKGC|? zafmr{8k#A`g_I`)k5Vj)R`6y~?tMWg<6>ga%vzbq6occJq6my2mLFr4d8-N(UEMln z0g~FqM(lUC1!-2t1g0a9Xgbg-9tEmg4*k+We$Bru@wj&=qjGtu5|ul&rvkiMexiSX zJv;vies|wB$!?kOm!Hgt4ti}XWpg^2MXwCKl(dy}bSugguaJ{~EB|N4gh#$)14OA^ zS22P$F-rD+tAATlFy@n$tcJ)(o7~A57dhSnr+cF*GXYe?1s^tD4IL54HQ54_y)gzw zZ%0BWMm5o)7}gC7+5YXd{HGD%@NSq6O!t4j!T9>~|26&t@2f!7oc$zLI9OKEbgsve z!GijYx|qC&C+osRYb>?{IEUS#^Mk2)+0%u`zv{)O3b9Qr9Zp&Nre7mPl)5eqsI^5< z)ZGGW*U2-*(>3)Q+ma}mzKWXp^0l&x>e$)}>Liub%Aci;8<7o5ge0HDQh2L<%_}|u z4pFh@=%^AN?(t*UZ6trL8k1fwy$0%FBiQWz+RV(%U<9H14E;jB$ncKmiMRT{sztzQ zeHs45epQGNRDCw5)8YiE!;?fnN1YQow1#C_mUq>0$@PZw^y6!kv~>K>Fazl^t8ls4 z(27qZ$)f{t8|D!;*5y<$P3KUaG(VvxdY)ycjO8`E3 zP>e_a7UgLicZ^J7yF75}8k+WTe97_|#_y3;D0KU36n6U*sFO7VWwPv;TxY|R51)oD z-5CG9sktIF-+rccoxkV2J1wx`RXNqWIg+PYY|t#N5d%2H{PKip3N0}X2~SR4T~aq& z;}w6wr@J$G_gNTUkV6O(1+YV8c+}5lJ?oXqx-ncFRo1pkHj~Bx33luE`<}T_>Q!-~ zvcaTNPs`@@=rB~8NCEIUh$V7EmMV1ghxddp(13H zsaOEXv3VfQ=uw5cQ$I}v&MzNF#-yd`>27a)*-Yza8eK#)vWkcgFm(z5%nq_0Q_wjx}$^_srU!!jguDrK5du;9>4-q^e)p>L?MLV$d%UowG zF>}aE+*d+Y8gdi*9(62AFw8y%H6fvlXAprST3zT_XnV-H^Q}rEAYyeCnA&d0C~)!) zA#6gGSeGYTW&9J;es!&slSmMS%5$z6VNlAEi3IfQQR>O0L$}iZ z&Y#T@5oXOp@W)MVbuE7VaFwP^_MF@KK|=ixJG}E}~AQaew2*r-wmgx$WsDA+ zj⪼a8|%|rxeYb6BKhvL5E|k=)@U<5vrx=ywmuRJP*2^+N`#4-WzOnfDNfweOYkg z9b)I~URJ7u97hsB|lV-YX`~8*87uq-9 zQy{19jr3Jo3iV_m7oq9g(SX~+6qF_D9$;exe7g$H<{m^8K zLN|f{0s;f_kNzL90Al0p+KXFW0w}m&TmWl;JhzRg6P@QwgnNppXM5+w$d-z+=|9hX z?p7DGCGAGwek!K;hw9vptnpy@uzJfPS1Ih!*!$1!*!dyRKdeync|JIrxZvgE9M;Rz zoeVe}`&$P!G|8oYOV_Pq)4!8P|C~0>%qM5BiYirPdQn-Xkn?qxa=-j z)|OwmbGq(UFRoST%s<9fs7}!_;$r{CM`um-XL9<_@&{YqNBD9f!0Rxe2H_0f59{ws zz~PS-$x(v)Y)sVvcYG4(4;m8RiB4>iTmsRvm%xufpA|rl0lNr+`AV0-sRJZ9Ep|~t zx0{U72V&)%H`bhQZ%JZ4{qo$Hqw25KH=2JsHPc|~GmR0fD$OkI~Zt{FD$ z&UJV|d1a3LNN7&+N(3-XSz!GzYK=cw-ZYAqo?*zMnzP_=-S)Q$c*$<_n${Eed|qdq zgot-(I!Fk75hK@TG^&4)mu4%Y%B??($MbmL>D&}DWeWOYxnqy1ja#nW(Lo#|k54rwTGnY<mz1}hz%^DKzqbLfYc5E6R#;6kA})EP;nb~Eg!m7$tTUC zqj9GsjtUrCAGap3rqw4qfK(Gf_`adiXfL`RQ2k?GwIYMhhKVi8I`Xen$) zcRBMy*cPMhlS_fB8z-s>j^Dc^S)iQ=|5eF+cgQz=eDNs~*|Q!2L!h5AUiYk?Rd1cb zpgZq+dZ6LQ;Ww$FJ8;nv4+uC?wrMjv(J9w=h<{(km#EG1A9kOYJ$lJKH8auAd+6On zLCurV&oj;I#C@*yRy`HBoYfU?sa*PEp2bzW7lL)!mJ>9IPsNJF&O0s40|C*j^*H-a zQo9NC)MDY^*1;4Y$-FcwY?2ps#z{G?&t3M${K%-<`yx64lqoot5IkCgk!a~QDQ1Tc2v``_ zCZ_+rGe?&O45e55`phouW{SUvX9}hyS^|-h^4BVe~L>cFqxkon}UZzPFOwoYc_gt6Q z7xW`)=>7H9P6N~&Ljz^`zcQv(RG(lfAI=v3%2 z=+Yu+uv1yr+d;!JTy}6A#?m$i*4RRW;XIe|=gWwaTmhCE=247a zh9_oO2$spDLkEN}f=hRk*x~d#PhBxuuxB<7BEoXnLL`2;yQ9W=WSy;GCTL!OTMXn3 z?R#~1IhNg6IDUF^fgv*=PJ&I28o;UjQor?V=k=flWhprnyp0pa+7hl5QI02`9i{%V z@1>?<`Xs?_;N^MlE{#%>^t|rB-j<`0eyEkUjmbG{j*Rx)%u%+Y)|L;2b8!g3A^$` z!Jk1}ACh*|RI%a=S?KlIJdBJ(Ac9q0bt)dj4|Q-12*>1`UJ`QIk-i50Bqq?|pSz6b zN_tAubMIhm{Oq?iuV{((--F`Ajw_Iy#o*UsM>pk56nurBB%CC!tnVouo0`;fK$u^> zyqRgV!hoH`pvHo2g3e>kUIz0{9J1&K>eq7TUmM|y7C(6LvqYp8YFd%1JEbEFFhB*@ zYS7QMA$yMFrG#`3vPNyN`weL}0dm>ink$wPP!SeV%Xv5a&sXT=ZyEx^wGQJCk1T9Z|N!Pd;Oiz-(}lZRS&w!?;s zazPed_h&CI_NOp=58I_YqED|0QKoBVM9b{diYo${K0zs^d-%H!zJ$rCey2@Z@tdQ1 zz8uiVQ*EmxQm`~tlQP%A#~`^U*kdBGz!KO0H86W2d8^qd>>yZw@AW?+2m1;+?^JW) zrwgxIqO@x@2lTs2R~*cL$}|80=(UREf@~hE(Fz~*epA3)iOOF~n3CT#>UsT((|eSY z%;nKWzow2Q!Lmc*vJXsyM=GV>29J1}s|v}R=~ESaMrI|k2wP43ngP!2XCRB& zpvvtVYMST-d4!3~R*QX8tQ;P+FK~ir>(k_D%sBS`tuf}9-Q}!*(^fahP2h&Xu+E)q zQ&Z&MTQcBHpt+?Byol~1sqMB8D~U?4Ufz%^L2ocy;Ta3ZPONyqUL!Ly+#|W2!mw-| z*d7T|8D29nX*4=WYK>13BF%*Z!Lq~4F&3P9imw&@qU0qcBm`Bp@|kjiJin@}4X#b0Sk0Nr$hGEE*O_g~ zDS~xiK6$Kiu#ksevJ&@3_}Hg;M18pIg5c3vNjL$bG$0Lipvt<(2hHIhAa6Z5D-q7ibLyP>m znf^H!$+Oi&gn4dK!yX_{Zh`+!>@WOsGSzP~mG_7i@?Y+yh2#B}`$9arC2Tg)piC3hjcWsQDN zTdlX?Ma=Yb9tP|x+k1RB5k@=SIHDJ8HUPlGj-(@gJD72&p(vtvi7JUprYjSP4Gcmir}WGZhXwJ>ph6oTfn> z@6@+@YH|JY8^mR*m5Gcls}O(egbsPhzE<<-huNBna2Lcq0J7u|$Hc@4-<&N;_50hM9t@>UF#Wlee8rpt@JWp+o$k>ac7T?QCWR{u5h9Jm(lltn+&0dc5A! z;E7{?YP~zz7D3Uc#&)1>xQ^w5Lh+)10l<@ZZg;I^)KN!dzW)CH>8PyNvH(`I0>}+_ zrK7}&V;Kg6(#D)(u^Nok=<~DX%gM00mc#kHg2hpnhx@#)*$l6kftPw=yO9-_yiNNT zhTqW_&q)-TH>2~U-l$o@1!F!V*^aPPjg-npmH?VZ@+}DFgC9==f>rJq!*$(B=>UW< zv-z9#dMcS-UREPV$MIAW7Df$gj4yzF5fo9XN=;=jpCo)=;rj7j9uy34v*^9?P=DT) zI`J-a#VFReW5Eb&BsLR(Z%Ov2z_fz#QL-#5xE^3g@who9Fv=D-q{*&XtEYev~ zrH8JNVxXmPSSO#dKvCaD_JJF8WcS!=j6jEeCdvrkFZK+$%M%ABMyf|W$A?DR6%L&p zRdTS9T=$aX3wKT-q0re_1^WA*Zu4m&)pyUTJ{vZPd@(0dxvHD-(irrEn?y4qWqY>O z?~e1Ru$-_@0>~)wk~;$8&XWK8B!T7PGD;44=KVIwLA zjig1uq8(!okg}*rb5Jc!0Zb3eb+v;d`P>c<@~dyAo4M0WwgZ@VU|~~{33lEaw0s2@ zv08bH8<7jlsn`hw*5G{PT4s2+*~&1SGkkoLWE{8P6iJ$o?}n4{Z1YYn_>S3F!5Y^+Q4ICd}%BEuNL50(ThtSLuRnab}W=I zkWo%LZAirz0JWx={~sg1!2cy!RU1K9R6gX>_IM=F3vN7J@f88e>?{9m!x{mW6{XA> zb~qJAW`TM8I4~%0nm5D2XmKPPknjOA2cRQItFoiWW{1G^u}m!=c(WDG&`+Bpj4Ywe z2c;{}iXUa&O_0aHilGI7YubSjTggU(WO;?g(Ka#TPY@vFJi!{8YGy3Lo3C9{+qAyX zjvYCFOZy9Gz*uNFbUv-l%O7itu`r2NAyv@F*)YAhov1xJ%f{!LyG?ncS<2iUSrSUN z@6VzA5?kS=9=$iOwuD3?Z)X#+HRp20m(>xE7xdC7p`*mUV`mdVY1x-O2?})PoC~B0 zUnl9FOnkz`4^I3X<@>_OvYWC!(OA2JS#}K_z~2$cY-9QGsP1T}`%pkoN@{KX+sVk0 zu$CF4H~i_M)@v3|zo+6l#6vCWkL{3Aqz&SaU-^;~v|=G5VqL=sa6mi~y>cTV$Tpku zpy5BU4QV5At#OKHSAK+1$#&K#Sg_DG7dum0!#2}** zlC*YkH3iJ2BL(IWCY{>r%b+)U`C+6_)@)_N)(Rpk3pzf67XYJKI!;csx=nZbgGSrc z9U69$+kU@F1LlJO->&LH8VgJeX;@D&gSkFSj9HY=7iF?}pAh7fG;)xK zk$(LhfE9n4nEogy!HfmM=V(%##`Hb3qWz10BAu-T29H!$akpTuA3Gj(vUo9=M{8X$ z5+bkb{tbcE@8>sK+=cq%Ru)mFh};C?M|AN%cj;?4_}YW&2DN%Zl7}~z(m&j-2E|be z;v(4ceoqa*(fIr`d(+Brv)wr-rHf7pXIrw6JdXo*06bmXJOUOvFWOhPmxs147&HT= z-F4vCf1h-5ll^J#!^V%eDko}e((%zWu8HVvP7ODvLnDhKPIN^ z1c4ez{AeLnn_>;7YDm5go!Pe7q$oY)jxOo>QPT72cGIgNB^tj;&ta{2>VvX_N|4sl zgd(5HgE(^%cp_sT-m~OFrcWcSb0r$;KM{|L(qeKk^3+B)9TX(K4+9VRKCL{v`rNr( zIKQ#cN1INyxcl;r!F+$`=U0d{gm}u72T$2l)bXXY%M?FVXN+m)fC{b*EjNkyk7k;8 zPX@>K)@<~zT>qSid2JY3H@Z=jWH(E!0v?D5%n>odmk_%?M#(yI|7+mKb|*MbR0427 z5~kT76XOIE5W^)Zng0H{S}SnUtC-mA^;htUP|{NH7jt9TN!2{Cw}G~v)!Y{D&@pMl z8!SZli)5dKjKibqC*0h#+=$cqG?@#+D(J2>Ucp0BSa}&llZt5;LBY{9Gd9e#xkfJ& zKBga~wo_v$rK<6x#>s;B{Jf(D6SR}vE6V~n`$!HgEv-9y1)$0xW#(_b@KApI-0gd) zRNVdMtpcoV!05n<*@8Z-v#5M}X}O_FmJaqdR~vQ2cpgTR)F+eF2U>E|P>){l0sVCb z$B;brqMNBJPdMViS>@bK#N1B7bNl+dsbC&n{}zEb(>@jS1_c$gFjAKTKh`9HLnqc0 zc#TJ>!NK>2hOaSl6jMz4k_0rEV_(^fu+-Cx=kpUTmS`|1i9!gw#gfIqhQh1z(2 z6hZ;WGX-JBCMJ66859#JMKKZUewMov)ZMM&^wemi*}E8Y&q>+8p`krGJ-}!rd$|~) z!txGN72cyiq(IW>< zA<|!_>a`}kc6oj=u%T_|Ao$6yug85faHG1rMTW;N|McKB?B*nQHJK$TTJN&F+n*~D za^4;&lJ8t5x^nMTz&J(rEON<`0wyE8FLIHBy>oF%HVtX3JVZ`K{RjlJRatup;e<}Gb?Mm^Qi7EJNcWeo;3GX?6K!eUDm;L&{tJB???lg%2+uE5W*G!_6 z8SA$~LLPEc^g%7aZ&?Tb!G6^a7B{xP+jYt6O5M9NQ>W&f)Y=b?gI?{%oveUBgsuh~ z&#y1%c0>XZh>Y=!u7jBXP4tzy=t;=cx>+4eO99pu_Og6}`UQHO+Bwe9)ir(0+voChyo-p)3v$n7ryAv7 zafo#+BmKDI@JYdEKkqJ()%9q>L_XUmqe1D~22Te`u0*B;&613uq_xI@Jkd(F?u^xi zEe3_kd(Algi=x`>KW0QuD}{mh`gz)P>1H{~)AMrwjX7Y`kFZ~Y!$!d)rth>=Wq1DYJWyX*2eSMygFKC`MvOo;#eatPre1@Gx8@~?1rC7 zy%6v6b1rJbc&ft6a;oA<4vK*!NBl9zL!xxQBGS}ZkG=Y}`tX#SMu_LFx475&bmQTU z4Kz{RB->&B1JTy5_Menl=NBtdn{X@Vqu*VIqBmzoq-=V^SNN*b$efuv2dyt|!^fbk z4pjK7z7P4Bxn6=IjIn3ra%)r(j;)rnNxN?hc>bZR$!bhtO}UrY_Knl5@?MSbJ>~aRrm*gr&4*@XZmkEnA>jqUnKHdpO{zZ#Eyph@-b zm00M;;f+y(2)f6P>80BC!1eyUtB2<gSq4ghCwe9){-Ta`S~XQ>jiGVJ-h&3czX zQFRn>QtMBO5;7JqnW#C~I#P#|<`NCHx@Uo_F@Ic%M2D1fk2`X-PaUp$?A#H-^%*#o z(b3Vxz`23cu5_apPqOjA!FbIM7t!b<&0D14Y2lSvwB;oOLG>wSvxUBqOxk3$+{>bG zv&en}x6{ER_X4smYsHp@c*otX`JayTtm>2j1Wq2FI~@w-W+v2RWz}f?TaM3Yyn`VeHm1J*$+7AwjQ2sE#ys>pR*Z2o@vX z9*i-W?w|CK>pTiSM5+rFlk_d1yNLp^j}Ig@X~k|*zh{X0C7Ewr&5=|y7c)KGx4Vi$ z37=RqU3#c2zNI}J7m4COoa3n*eRR*1MgLOi1+9L)HQPkH)6PqOx@=Te$`OC(ZoUio5t zR{h*}-M2xIdxfIZH{f{Ywp_T?j&Ax7oFEH5*D*k}$#dX6fZq)0UVaM2 zQ<5;v1e4^XeL8_!X_)_Z0b>3x$e=czO{&BkreudVKrlNKV+x#?T{t7|I{gahNJ}vE)0JHE+nJIzT z<%FIL0R5U&^L9rxk|ELZ!ma*WK2|WX(!SxMYl*`8x^?d}$;jgoelX)Q9d9bXAXP~lp*Qzu z$tF2VSJiG;ti83-YN4#^0oA!OqrNnEM2zJ^jX5dZeSdzYIr>i~Nv)GnBKqU}YjNpjv425Y8PNvh3r!+jn*j8SVe4lv&w@gHBxt31w+ zpfkM=dsHKF<|8?IjlxmHwO^lyEBpn-kL^mxG4EZ=(@Fe!@)%dOZN*)JC$kUk;6P2CB4&Y=P z?oRuCVR3sAR-&5tv4*r2m7mY7R;VLjn5YMYHnI+1_`CYgK(`?Jk;l$M%zIRx`|n5d zHCv+;MWrn)nC8w?EdKQNwi&SR#}s*f^@VBD*RVvrNpZ4mdeP4p*SlQt;4!xgroj(~ z{V1uzr9x?(r}Np=#sedZtHoUJ6fEDWvcQryeTt#tXESwWIl&51Fb`{c_U`4JN<`@4 z($4d(z?I-qg-N`FtL5hE=@h|z3+aWO8Bg1)*wbiYs&f;%Ux;8+=u~L8*_us*NN_FD z{b_Ka!HU#QoqJW>q64)(uF%I3SyQhU)G6SVs8h#P)d~l3o)VMf?^VGr*uGDRegcT^ zyDH1J$mnkftsDPhuQG)3?_vG@Ad^w1_@w749wJDe@pDHgY4(M+{&(nwC#GBT`7bi% z2*eIw!oX-*gtwkq-t3`$I90Si>)7N7cq`=V$D6EtSX_5$3+BfHE1Pn)MvAPD&By5M z;+N%B{p}V7%}M#jsl|elBqaWE*iLAv3lP_HsQeTl3u=zjg5u%!HlcU>l8q?qbU*o4{hus zR-l~dV4p{a;JVPPEL5CPwltK?lNGQ;B4CM*2A&k^y5ey8#>)_GlkAN$#jFdJe>2WN z2`tYCb7qG`dUg~Tzr5Z39zTTRf%k+GUaETNtUFJN1`txr`+0>DKRc83hil2s9jXgk z!p&Y4^N+{604Pav4Y(8QCRpezE~w6MEvKuqj0WiLKJdtJH5Q z78AAbMY-XpF696^8+eK==l0{9r3XUjGxA*FnR13YtWvteB#Z74RhHkP+CeTmq%U1r z93TZ3R)K4-<0m{Sss{Oj{F_EpVJNrFbgbL}e2CA~jI+|I6D=S@pPZb0Ka!0^BHd3) zfHXkXwB>5+M7$OBZF*XV*K(YF`Ql`2jLT}Wd~iojiJgM@-Pd(#TrYet*C41pqo>D; z{I;hhX&zC=qtu`YIj!g9J%N^<$8=p@t`7UB8lr81%})2A1jrX_uLqi{*LdiE(>L#p zI9zuA`2Maju53+|d2Do{EnGaTRoGbe#bpn7LrkjjX@Hhq5$Kn*1gAq!hR|K^GF2Ir z!@(vLSU?S19@O__9svN_9nz8e5G3B1J|M;ZPSx8hm0&%p3&j+s76EqO^D91WXhojt zZVEIL_8+`w(U$`62&ri6lbh`%raX@aPMl6iQ0B9 zPTqb#5cw+RU}UG`PjsI#3!0DRDWHEnQjf$pg}kRwtmN@y!L^#8WD&-qSD=P`&KndT zRuqH519Cvw<%dJER$t1Lyo*OWCJ(Q!jDSPa8cUgn@2_iPb;FRV4`8lxJv?g{O4c#I zfaEc8SBi;j^+Y$y$!zr&&@106VY&}kn{AI3dBm<32s(RvLu;(tf=DvvA_!&G5I$+h z;JMxWGy$PNo3Hp@8tkJg@FMHg7|_m@dLGUoj*!vzw5Hk0Ia>FsJJG3XRb$=8c~IC& zaBFReeYbySjv%YR_b~aDHq5+af8m$f&0GNE(cw^427mI}tkcnP zMbz-ulcO)yaqq5Z8hH5dCH9^cb!^WUCbC?u1yJGBn~e4&-<-pr8gk^^xpL%Gy?wQ1Gi&z%nAj1%OpBPWhb6;EQ$KPsfX1 zKeaSLSPYS zh@rGmMI!>|5H}GIaH_4OadS}wWn*;f{g@oLuh16(oRL*RMFDZ(^qqlsH<1%p;_$^i zvHwTbTSry-MO~vH0!k~=2qMxYB3%LsO4p$q=?3ZU5)f3n^Kj^HknS$&u0waj-T3?7 z_q%u8F&yU)21A~`&)#dzHRoLGF<;-87WzKklk)Xqv%TdzmEDEEOGwHNT&Fki$B)D= zdo4jz^VbZ~R3-aOGZ$;uWVYfvHf^3xr(=_sg9Fx`f|-&(W1ksoI4kXtWp#uce->p3&~EFlHo(ezQ{&&At?P^MXeJ` z6jMRuqTP~M1V!Bof+;79jy~``JmMOAV>?FlHSgzN#lucHLF~usk65r6I}|;CHtwt^ zM6elzu+5=DQ($xlm=68O8-YeTQD?s1`SBw} zV2Itvynl=+_)^nD^3ZTOkeCR5K02Hcr4#y;P5{EK048^Nj<%l^^%=~(bZ}3C?{}`r zl}t;czbPprF@>T4izEGF%&Th@Mr?ypu5d(|t(81D zIG93EFeNkdjdT)^|IDu8`Q99`p%N1l8(Uc!0cs44^|4#+de#V-7p(ioA&3(B&yKC1 zW;J`Yn-e}^9oKTWQAWv=hC~pex^IJ?%nu%F^pvuPVFP-x9ExRU7FJ^HtWN`!esp=>26VVgaIPE-- zzQDh`yBwH8F&l9=WPiqH&3_ct0(uUW(+j8>Kz@!L0!hsBVu zj^2q7X%jZ;cq(uLMlZy$b35$_2C4XJ7=Lmsr?vOgY=-2jK@?pFkT}%qe`a|Jhj*e(qjkj|GymD?AEuVQ0*IG zm^4igC<;o;%EUZ$o&Y!g|8i^a_@WOlF$-!xT)T85^X+)dbO$mcU2;mU-PI`RvD}tn zxpNgNd7R3TB%M8uW|q{il=47)E{uV%<_#dWGG*=uJaC1W6Vo5RjZ@UqdxeA0q}{xs z@Z;?%e51}?YAj?-LN2V42HN_Z`|rn(YSP@gCYuUh{XRuD z0jyU@5f`dqcr;NDEnBodzr*#MGi^mrs`yxedfBO+qAIt#)mC0oYu770pAGBgl<4Ba zP2001Of5DGGWyi2Bmc;vC6({lX!frIazr4BJ&B{iU+86lXrg(H2hB+H&yJzuLzb0X z?fa~|b=p1q!<6`3sV1bo2ea&_>f3%%@vnnA6nn?jwhj-z-Q^=@=dHtz|y|F0Y zbwcgw#t`f?<;-RHi)3ntH*94aq9ZQv6Y#P+GiVPiEokub$LMKLE%G2qhEsiv zE^Ay8Ja>L=c3H*4Eec+>g#r`q+>rab#%ogDGK2lP!RGCvx)Zx!aVE>TIqy!6@tx<( zmerlFWCW0Ow0jv%CF%OkQGDy$yaERqn?1=IkZ4_`}6$n32J8S%%Xf!XDHo;YW%TZR6756Ua9$v66^=hC#tk=Mi2|5oVvA z`@(txON$I0>XNu*cyGmgfB#COfZ>;#ESVG*L9mxjIEsJ1J7B3MA#5yQ@vAx+_Zg!} zCVav|>8r>jiHV7Wj$WXPxCN>(tpf81;_OG@7Nht>iz)|R^;%K)lK0+r`yve`!sGe` zILIZ6AXbR^{?IrMw!KCKdrbiZjq-qsLrvu$JrBgYqD??QYJ%#Hb{{4j^Uu&yu0tX~ zSgPl1itpH@z@?>Sk{TZL#*a2lE33Q-=N*X?m=lHIIW^1|+Z7@Y7tPoG#`68$z{Gay z&}e+*^FsbMx1DsqHGrMga9nVQfNE|TRe}4hHQs}{ofJ|~8 zc5Wm2#QOvJoit~NkOu`gUc8Emdds_#N_EDpSa7>l`hDUh82zMum<)IR|bRsCGFa(7N+xX&=2 zPCO!qmNI#__Xxo!g2^nKtF_}Q^Zi*|U3zj%TliO7m{HWSA_s(m7k`9+a>BW=vox+85m+HIG2p7ZBpE_OZj@oq4de-1_X5V# z#MF*o!WDFJAG8n~XC^g%DK$!O(3O@RQASJUAADQu`Ryx^S_4!mphWP(-Hio(|D>jf zfI}HG;p7;YBzu#@+(-A$SNw_1?v|N_pVQ?*(0?MqBr|f8AYl{`)L_K*!Fj%OmZ(qA zr2;dMP14HbDpKEn`M#T@YACq4j}buu zw>*jWcxHKm&y63!b?d9XFeM2OTZ_*aIH9XbgQQ1^P;UB9N(|S;b*KgE%0I+yYQw;$ zoWTDM9lS_=cignJ^P_Ikq(}r^u0r-QrfDYw6uKF#zF>9>^|iy|3-^^Z=Rz zTiS@>{vv`-cjIX}Y|-2uAI`kZXsg+rx=%5w$fbM*~KSH&J z1uiw8W{oY?2Nfrt>BVpPg1*Z=8JexfH6HrAL2vx3%l{MP&J*-Iuel0oVZ;byLRFE5 zsWA5j!j8hyagh#ozL=Cz3eAAc^4m zPv#*UrS&pIg5%514zc2li;oX!*9*Q<0igtX)URSMi!CHFa|N_ZV|8sNfWTW&KnU`l zl`WH_;M!358E1lKcBrlv-vTo02PZRauPYbwwKcNj%YIeM8isI?J6`0>bVPD ziLGsX6;{hkUZhy5puN8WnZZDqpqW6R49tngGkw>zXNGRFVYW=dZNhaua1`SS9htcj z4an(@*~+x7{@ylaTA?KD)ag za7U1utnJ?wh5($Gl||>0w*c}WF&6if(>HE-CWgC5fy1rvM%on+)8t^X4fA9>XK(7~ z$*{=pR(;Mn=SxdVRq7m=umUOb)gB@%An2XCb~}#Po(y|pwO^FZ?5=KX{EUwmcW~gi zEHnDaV}Mp!UD71O5shX*(UwJp2Yq(MQ@05-3#uK6j`QZ$t@ctxSN8`thK%P|hF$u0 zSDzzx$w$fJ>sfDZpqH=7WBxnn%eGtl$_Fk&az6WEQ2LA8p~)PCfJ1(+XVhxyL+I>^ z>I=jQXxxopx<#X!mzo7yWz1>e+&egMJM@-URz%v#il|>dqOCx?uTKl>&ue9nsyJ&* zv#=LoP~=p8zoNYpsP4Nkxr(CQYE5DKB_*t3UAiI3>WlUx)u+^F><-6Dj;?<Q3Yy3U2F)?QlSK$h~dX>+Lq zmdGH)!~_i}(ZvU}$uy2g8!*|yilhG1iqbYa4eSorNdaFV>WT49L~08PQz75$lwB zt8%)yHZg_YEB?w9WOV%RCJ8cvw=aGm0AK(xK~P?d&tT5tF>(<1dHBzTqEwi?vkO(V zhPTvL^#xOfQnFvB6!7PRHXva68fFAolGB%K7AbMp7)YQ$xCfZrDmwit?=dwC$LQPY zNm~tl5VIyKl>y7uRKjcOWWtDkmWee>%$Qr)&F{@n@|y%3AKR6z^u|zJ9v8X|U-_;7 z5@8i5(HE^5t{@ec_Pqj~hc=JU#Z%1~u5)nOTaJ0dtf@?p{~i-l4tzJ~a~nFx>)sz& zY(4U+&!*&oB9E|C;KtI7vU2$7--aa>~Of(q%Z4$!*IBfsTO`hQ*`g#y0n1l!BU;EYvZ@?PlNgH#))ng zB@`}yZlS=#9iHFXDaCY-ZE@cmA2BxSZ7%y#li%6!;ZsnTez0;vU*H{e?~7wY4Q+q7 zT2Px6^Ed%dOqdTp)PFQb=GgM5NuqWzILy@lJUKz357X1jw;T{zZWon<++|RjBlqyb78;kK9)jpZ( zra`pt0v%o7juAcqMSw`?yJb09r>xQ>0GldVdXWgngePT5@>7-UeEe}6qRBLZ3shXd zzt#mBjp3i)NB?%#doZ~6Cy|z(BBWNoU{uM4NC#BxF|qx!Irdq(VpIwfvDayCVYJ6* z8;{G34DdhLR{ljch{Q%+QpC#DYj0^w8W%@ByN6)uh)_2Nt=carI@hftxy)+{+31Q? zYRIxOF%kcJ32K`m>#khwh$Xd45DhV=JTBE_<>gyS4SEC2CrPFzPW5gue98|R5=CnR z&NAP~=Sa6d&w^NeAEtdU3iU_@p(#$L&2g>Ixd>f9IXTxqK0hiG+h4}+BzE3P8bthD z+Q~{oLK`d{dObucV_h%9wRg zBB=RA=?1G@{!M$Sxh34nptsKGaybgWi}+Ga7hhuJ`?tzk?$PBmHU7bs#wQ!tujWl# zEW;@}EZe?|?>~tcjE(G%unJlk%b{^96@>-+6Bd-*mH(&O6UO93lzP?^*nKZQelD!x z9I(q{YuP|QC-y+l*dW)uC~#)+!%x4;8Kn6^fFWOj!(N_cRao?!;3XBp11rK;<2uIV zF0zp(T1WzW4Uv+kV=OQI4~U%Xo^v`V{CZYYb&h-@%U1flg0kdy_~mu=p$=>C%VxBh zs7CLWkX@UCEBAt=qO^%WnBG3c6AcC(@3feo2xuFd%^UyDj+aabUjBaJy&^zxv1hiE z4RB9i-(uj;^ZoP9jnC-6lLnM3E&H)}SwMI?amUPe6>73>=uniW z?wSaC|FZqEjCk|#B3O&f{8ewZ?5#7^0|y3c=pXPl3>LtAKAyKvDhJb1I%_TXvIzKLRVlQV1!c5jijLeV|08Tslfl!Dy2F&s_}7UXT|dSGtB9#_>A;gMf@skzZ{m%`o3Bp zMGi>f(y5@DwGNTJb!|~ef@A`b(Z-)T7f_&ei@%LDVcRZ~O>xeqGDk55aQeoL=0QNz zHQ98=aP2;=(27!OR1O8T6h4z$rYAYi_KEn_fe)7;rKZSJ zY5(d<$shzgX1b=|t`|ghz96^v)LIQJp1t`{a#Vo2etcSX%6Aw@n5+^ls?n;7rT$YTHq-j#!%L%4 z1-ibVR#QK(oX~Se<&yR(nLSLlsrt9cck!b)5$C*{9I-VyTru~oy`nyHSvdt^+6~&h zdCYh(aH|#)+eMB^-z2=a;h)q$;aoeA%Zd|s3FNcFNBeN#s2N9CN!OIeyy^`lvj(2k9a4hhhIc9+sV zt|t@Vmu+Pe!y~J8+&nhg-pr)nNZ#V0M2tvq6yWJ^nz-&x5e!XPFi*Ssh%SEiHM`T{ zc!B_Buf92?3KoJYxbyW=xo9Je&fU$UM{K?Pag@}eEzf13qgq_)1y3Vq>-R?*RTrWj z+RMu^EXs#H<3qfvK@5p7AEmCf|G%5ywO{Mf!|*={C=vdmMzAhy>z3fHB4o3S9niZsz=b5i*Vzh_^Og&Q z0>s(CZ)FT6#&{Zm8Se}8hyBMV0xx}hV^h~<4lo*>zQP;IlRr<{F~qjy|H!mgRze{} z#aZ)nQZ1M`*|c=mglpOd0y7ABXZl-hA|+3t0Ah*=g_w3L`4)Z26ZO}rn_vF!)S$@% zY-!Xbbj#J}0Hgi+z9>0%d(A)VnBqIBWrrE>4eS3DCd#Xvv#@Kh63O`&AY2>)>{C!* zcqBg8*sIgW41l2lx-QUdSGjJukH?-T=}Nh7F1&TA`n4y1`%pk_03f7oEaGMFUF=^@ z7og_q8%QPeg|gg52^7U(3;Yd+n=BpTeX75oue+I)V6o}VS0t-Hc1iZUb0+1S<39;k z{D5hlokb8s{^Vp7yim4_h=mN&?B&DH_S;{HyaIFAZLjhz=Xlptt*qe9OqbCBk{V`FmrHWo%h5jUav3ZMKR$3a;I&T{ zfUCLMR61>;Be*vt7TVdBO07k=@R8LF1Z0i2=Rn9@mT3yxIrms-)K{?V4hV zUQn_bX1!~lYz-zRfZR6QK@;mZ(9lpsNI9iLTkWz#4U2@A$LMBL3Krp;>A7N`+1agb0;$%T(`aD~%tFrP9`r=~1622V(}ZR~Cf-)ErbWVMaWBeD1Kf6N#)(#y zWDtFpOyWwu+au@hSnZI3CQAB>G5U&ML_O8J*=&3jeL)g7CAsOU*fOCbzPhHF4`pGZ z`Q*%nA>e1>qqRIK9?9j$NSlzFv`TXm-Eo*2hsHSy$$CBFW0CzKvn&XX*`!H2Jsq7c zU=~~m;oo?sDlKM;%joAUtM1C6w|uo4g}wG&%ddgsQHMiB_>pA_wz4w8d}Es6D zUs89ngO*EY71)s-u;EVX-d5_ecO6sDRtZ$T_w`{M*YoWf=!;@rUp5&IO0KE2BXsV z0^aH)sq3>fM~;cQqgL?Czo=~J&xsOG9&@=b(q^Tc+ifTpZg|RYM)A-E$k4;O`>YQH z3uIj{UPO?SQ{z1s{up$3tQQuxqys^BjbOLY{z4Y+RQA7GpIqF4JNw&%$XkSFnV?RD zqsC(cyn-n4Yo7V?kddM2MjQbGd*EAV;Sq;&Aa8`aOj;7zGQ$D$plji(`|9&JJyS*T z+w#|VK0-@uP23WoAdQ&k<<2*-dc!0+=ix|3Qu_|!ud!KXTfzrW_MQ(;iAm2&+U6Ny zO)H_xAksG;a@P~pHxTHWo6dr0jnIy&30|I;{z;!))RJcVrIZY~0o8{7VM<n}UP6S{n02c8>Tmc;H~=ZCiZoS9v)k zt$}YSDS3^(q2d^4euR4Iq?9M6D_?0G325GW*80X`;EHSWuCd?grZ7-9`?aP%-`r~_ zlJ(Y#uY*_#9u

j^iHgBAgf+dVeRxVY>= zf!}aoKzM+k)P!rZOi|v8l8UUBvzCs<@$f{3v~jC)9QzpiXaOT!AH47lUIIv7?U>qC z0E%x~#7t=xa+cCk3YnRKLOT&zgX6omL#3SWK0llY1mLXK^Hiu3V6X?Sv1-k|r=X^s zbt+a_pswN(Y0^%b`B2H@%ez;g>n22b5Mu+=%^D^H7R;=O2Va@ib^S-HH4+|hEGmv( zT25^FM=3QaGrP(^R~^lX_*Ev1QiE;sA7e*UpNH zS~vFIIbh9-{>}>xUW2VE+JA^KTlO|IVVA!1?B$YJV1NGgs2jd2ilEZ&>C%xm%;9i7 zTulJZeg4tZ%SDFoQb1O+8U2`lQOM6#W`3aDJT_uaf4u*M zLewahJjM!7W+f}BbLwjNOQpv*c^I&2DElwmomD+doJ1blNHRU&uh}5mtJz3C2N}&*c)TC4-@Ke1&L)S*^IUzZ z;zY`lPo?k1_ZXxl_$&&{j^xYEXVHe5_#Cr@mT+x!{Xm%4I9VBRoL1k>MnDSWLq+Tt z{|KeW2l?v!K4hTbRq-rjvH`4FpCm3if!b7Qd+uPwxEgUxjB5+MbA~@u#`!*8`+iEg z8c~4ftwIwAfSI`tzYv#IT*@^Z!PKVcz~_G> z70cl?A?S-Nv#v3>LNtCHM+rmMd8fzgIpu9+5P%R!pl=HAS244AIr$JqV+iKls) z?YvHl64na0s`G;5tvB2Gvo_c7BMB~lazPA zNrU-@3k831ulLNLqw^;4epGa%5j$!tuqI_?Rzo z4t=l)-_B|1AxQwA=iex&3u#KnPHO86yel>JsVUMANzYGrL@%wNYxEVCEQpL>2fJ5; zS1kpmCtEy-MqjtlVkD&!zwmF;a%N*lcESE&2&^ZCXbTq|oCqg4kTSPRFs^(fxmfle z!zdJ@Ewn3m?wI*(ljb5%Sa6Y~Y2|q)pQ?6_y2k9qo0&;K0s`&`e&}oVDEwkkTRLWqYEU_N>*Q&B zDNDyY>2$mSn%USm=FKb6+w*l>Yd6t&$&?m6o~`G+CGnoCADx)zvx?s=k3}q3$|A6? zc?v&9GP$xCf-|Psr_{9EQZwkEJFP68gr-hTRBYNy`sIt$_0?x|Rp0=*B2+HYx~_FLK~zWL@2!a6t6LpA0C-Vu<#AAyScl7c7-b?4aT$@X^cNdJk9(E@sk6M+ciDEGce_qjVXbR(VWCS-TqUfP zt~&fO=zM?pd^!Hvfy?K&BnO1c2-R$JVp>|sjUJ}9d`w9VPA=D%TfU!E^ie%MHcqxi z>u0_amumpaKn&n=B@;NL?mZ^*7fC*JMv$ZWENvaF^|n_2kI`d&jd$n?V9`(hbLu=3 z7b1EhMWGT2M{3W}k;QB^rz?D8S(N~aX1GxJ%CURQrenssl>Yf+sI`E*go_kqB0qO| z@UBnNFgqCZegWsl5>VP(2GjvH)F=5k;_g=S+1yWIlqqp;`YQaPOc8TKJiM+GghMa|_ z!<1%myFD>B{M?+0KkRp#R9tXV6}p1(b8$&V+C{r6FEjy1w)M7e2s?J-C+?RT{cV30 zT2lV#ykTknEaONXb}K^a*Zf(F@4dqnQ5XD$rOMk-Puif2>yK2}d+?9fX2Uvf-}M`& zW{n0iq+c}S;EHG^itFd340(3M^-*Vc=Dx4JKDEGLWtA*@4BbY1d!t>0R)P|1zk=aW z`YL&Vl18O2Ct**w>M4N{D;qL-jw=L(;2UvQDajW6WSC5~@0so0bX3j}`FUpKtbIU} zYeR6hit*-Ag!Rsb2t})92Yh$smoiMkk1))`5uK=#Q0;rO%>1oeW8jQsorUD}-x@ob zh?nJBA+5N=L2{RuZrIv)M=`#0AA~K{@L<4m>7ww$|G{9UqQYg_$!`xIvvIWq5I~Ps zO@@IAE~{w6UOMBuPp$<+fUFEAL^$q77aOE8xqBDaKoPRfwSssE*vqAgsK3o`0NJv_ z-n5d~9&5|Gz~TCzqm1#=_^E^=6DHYyR0MRu;!TwcHI+LD=)v6lY))l4KwvIu{57Qp zeRLt>#(OzFu!y`w*q-)Zk1(amMH*x^Kq(o>qnnpQ!fQjOnqFaI(c9xKfB_}r;l!?( z{?!*6?tLy^Afu5O?j566?wkWWfFzxi&vCu+dm_dMJPW43<4yH_N36&To20MZB-1baJG!zq_QUL!OY@FG2{W-t1%jEZ4f%9< zYFBGz-uc#rKCEzFqQVZi`hxCh-e33a%o4dLpUB3$zas&xn!(i-unwVS1Gw%-`0}YV zO|rzxL{mURl?d2u2LUZ0#w;QfL$0D&F^>`Xez0o_nl_#XIy_{{xjbaOYHQNt z01nFsJ-(pVM+jEZ*OfjR+R`$rDdD&^6P;N7)Qggg?cUHlqjeVfvF~JTOrS@egQk$_ z*hE7{N#QF9woJt&;nawV*#-&EeR=(?h{qkPyYqh<<=ewY01-Z2#gnxVU#HxbZ0NUD zVOW@%{D@gu^d@p?D=X0v7>t(Tw*9Ek@S0{BVXC>4aiQ&HJF6%2a^TJ9-bFEq!ZI;| z@plNA<6$@HJ>*%Y$49L3NQt>-Ic1$9Q-jSaSpVY%FzT=8jUE{dg*N3R$jDUc>~F2- z*L%{n;qB(OvUX{+KJ3v$T{94aU$1E#M9j0Ta4leq55vbYW%5)mfQ^$^HNL`pWjZsP z<};S{TVhy1B-KBs-JL@#v|>1Jri&6&)AuZE9SS`9r_QiQVDbp7xhkjSPkzwe4cf|< z3+NGmc!utJn`Wn1A; zHEQ0OH$we#mc@Vk{>@%kkl~MmMBRolCLxV3CH6!HsX>!aZ-u!9_lnD@HtZ$M%;iOX z#35NT(dO>b3d}(ue|K4N;esj#RuywZOi)MSVnR}tfg}78cXOATVgfn{JZ(XFa;q3) z!#{|i|F$7Uy1WL8V@^VH1yL{LXMR_l2mFE{U<0?*72ntpnxq95l!M^pbW-!`h)G?I zcA&UqchL7<`g^|Uc(g^KaW=5WbSgB7>+7S@Hp55h6x60>BSk>1FRf4BBxSy;Tz2{+=cEpODCb1m>^QyT>s}p$#d-sxc;v~kHNFbJGWr!z5+d<(a z5tKmT)nfZTyjl_h1DDBP7V`b+mrVMkD-7V_swT!{N3yR@==kKVl= zJ}N$v^>Kga76Ugz>L9m;aeXiyk>?nB3Q%FtURrze|dsTc%%eoWV3nuUKVn(tNyXd20iDCE*nC(D3Il zscr<&0^-uHn5HFhEM4}G03laaCkYh1{92E_5pUPXCR=4OLyZR&)}Z*8AsfJC+m354 za62@>I|uSWzroA>R-o}8SK4h16eHjfa`25$NO(PX0fW%l<3Ef=zOTg2C%an3owdNt z3snAB10pk!u_y(>Dhm9)-?F}YGX|ZaM<)x-qNVhZ{XtBeEFCw}bF}6!Nu7<^g;4JT>UUh@^bj*JssPUlf(g@L0$$VWQoe?1MRYMr zkp~wf5H+JxJQ?BKv!z-74@qG6r%2Hk;D>sUL4nPunD2TssOVb0E_yv_`e#&Zm37)( zLs_Y9i(BflDFyKADGRRcRxL!EM1iZo91C92Wf>EW0vb$!2jby!5Mutv5g_Sff9wR! zJo_3Ww-GT*!ec{2Sfb?VrgpLw*J{SZOrIZIo+_k63?iJ6L|spPPHh{k$9_Kv8avOj zDP62DHyeHeBiRNp!e@9S1kb<-nN-YbS^s+qzqTSi5ot?IT^O z+))k#$wzk;9#X&P^f7nS*e$4Sa70qT%c6w%p>fgZx;gg=~ z!GQS0#(wzGSpLn8#2G1WgMpE85ZY4O+$ETf@B`}p5=i0AskSAatf*Lz^R#<041N*y zwj@jR%Yp7a!S%_hAt!|~hvrt~oN3mu>|HBkh6T`yp%SE~wKqINXtwdHoCl%+%ttO<%Os)A(=)J4*-4g9G(<8E3WR_$5%&V+Bdn$LA#ptP&Mw(=pt+*@_pJah@sxc zXh8x|jr*NQiryP@{mA%SK_QQpq0E%Yblg<(^zy)(@~Q4TpHqLX~ zzK7f&s@bveEd()k_=kE`Hva^qCgDSf(-4k$$B6N_O_i#mUrd40a?{4UHg)XlI%mr7 zPq~d?u<~JXVJPR4K$3PB7B;78^I-s{uG)Bk%blscsjBM6cHW=?-vu&4(F9fLP!uYc zu;S^4P6X?@3Z|RDx1@bVOquQNZI-TW?B7ALu^tODZb*-yc?DS&HJ6WGj{jZbLqUai zMN(#XB%-m(e|`vJt$zK6qmPEHY_)-7@9*n>mxr}9DdJVdYFjYtvv8=LDNi8OYhu7r z$*kK;SkYQhCm@hS)2B6%oOzO7VSK1Kzpn>8V_SP1mj|EEk*!!)txQvdo_mReaqR@D zaCL;7dN#`h?<2*g#z8Yp5yGjxus4;L2LTrE#DBHORK=VUCHiDk>}Ov-%b&eG{lG$D zwK{1Eh8$SrQ8EvF1p5yD5GpB?3;4lk;qT*F=)kU9Z%@AYl^&5eT$W||I@m%0A^(s; zuS^D+rpb5`rs7&=qV>3FWAg0pL>0?*Z$h;}X%l`j%=@s?!d~qY%q|Ev5K2sD`R%D3 zCUW5Cgd>6pcQfAm66to?K&59pH*7-$tLa4rgk!8&zto)Jq{)T`2B&4?n{QWo7_POu zgF$_lDByg=_c9FOsjNTY)>o_tAND`613m(Rqi|`uz-+X#WXcN5UxS|0xGTv7tb2Rr zn01ryAqj!FIuOn1UX4Wl{$SX^@fIUDchKtUtC-6V;|>)A&0SJ4RmB~ovlc1pwldF7 zTXYdZ_F{7jMrYih+r%wSWiDu{dzg&aeJksKin<)E9;e<`o(U8+6WhI=!V5z(otqiI z3!y%X;jBqaAtubpR;p17A|NQ0uyRJB}F52!v@^3%X1W}L_Hw8ax8h4MvEw2j@t@q_0iRmTgS|%5 z`RV9fw2||XE}UDjPDLM!nyRXFa@Pfy9NrE#o=75nN_#$Yx3y+j2~+ACO)jlWjgv07 zdS>v0eIrb^)7A+s(cTGO-{1$5{&3QNssI0+7Yu!0lWlcnbyvi2;|n;;$6ey((--N~ zRCs2H>1vv}0fAlfIN(?Bh+sz8*)rZLrNivfVY{B-_=B_l zXf97SNuBQe+b*hEUtrG0tBd@+T%zNBQ1uPtf)oC~N867O5#@Pi_&9#!fD4*jl1M$o zKIvFbji6|+Bnb$RPm?I%-9NpnYvL-_=;&M#x&~9S3-tdQy<)Ej`86y4T)3gaYm~dZ zuh94n+`l#duj&WsaDV$S-F!0)%H9m!4;ve#>4ofp#>X*dV*CLW>p1eZ4627(h>K5T zAn?*e(om&f_-uAn4h}mvH+05!WBb0;D&4^|jY_8OUMf$v)5VEL;MF1tBxPcJ%zE_? zVmKMstAC3?(zLKBm^goE*#bk50qhJsiuEJ>@#oJ6H+T2o@bEo5exgaeH<30>q9jD4 zdhdxhs~cshC1c!1kJIpJ@kPxs-gTXsv8zCUSZHta1;Q+nF|YY}!7-`0{G?#Z;F|xUqQ6Wx#fp5a zrlw)JV;Vv1)L45w=P*qxpFI$Vd_AjTYfgLVi3VFVSIcbSj1gn7sB-=&84VTQ&uIKF z(&3+Y1vh%s{}?!HBnD?@>Z$E{;JcPnT5IWW7y9RbYr>?+zUT1_L>;3160+n+k|}Jc z3tnDA77EG=BJNU{RG{B5C*%3RM3J`OrbWlH3cg{bWBCKrT3NswzYIQSE&p_z`=WP>!-?& z%Ts07G_r^YjFy{Ho{stS?u3Y@o)?#aa7DJkx!YfhA~p`=$uU(nwMP4)Iox%3M9swI z->827@6f(i%M*YMvNAD^WHprVu$Y_gu*U2ri758&3yehbYG22=<5s{HlUueMKRZp| z_Tt{=ZaC>mS&Q9#Zr6;Uhy1KfnYirN& z@h4V}-xaohezT(Xo#S10yYbjUb>ol!7owq1T443m)wEzL==XwcaD&>( z`l`wk0Bj&trg_@Guj*?pOFA+BoK9a)F}bZ1A$mQ>ncl5E7j01pBvRJmPCbR2nsy1= z`i=@>Wa(!v-7?iH@Tz!{(ihoL-@l}VJ+ zg!|tduceRlGOk9m$FD16RsUx6t6i(ula2XD^M!mDdO?g-B9>rMbFIo(C9qg}+w7|# zYxjepkZWLPDhV&z6beNN)@=RQDuA>r7tSqFwVJFau}3!%>)WmJe0M}zSvgbWKGNeu zf!idzU&%vo(_O1xtBo9j?~Y_Uw!0$FJyJ6QL3>&wr{PO?!5hlHXJ;_GR2WmpIGVyn zC;XV6-P)aLSDW$P7=J3~vKOA++|Fg{h(mGcPSU_rjx2iG5s>tXI3+Vxfy{ejos%tsXcKSH;u`N%aLzxk8 zrJVXTOi0((7KfV~KgOZ5yIbgHg;OqbRViwB9?G;3<%-t#qvZXxftDgzv-qzOBZdV( z4yy_FfD*p95%!q6Zx|0nwKE<4N_btdr66W~&CJafR%gmw>k^O|guIQIc(qR+ckg2^ zWnIzbKp1~Rg?DT?P0it6@?A=sS-;4H9+$Ue8##LAg+rgesb)Q~NX+7NoL>%>d&S=G zAuvZ`fazA2-0S~_a~$DBtB$#(v`wv1MS=HH!(=SQq?3E<1VtUSU9487dV1-V^$q-0 zGXmor6(uE|ActlJ zmFD-)v1ex|<+k?9K*jp(1OW8L5A{i8dBoSE&y%D%Q%}EYghqbss35fXDj7O#oVud+ zk7&an2jSPrTq^r?Pw~&Qbf1i{{f}l9O2KI1IQCkx!8K{r2=Ca~K=XEsAvzqNltn6Dskp>kr ztYP69Z?!`$Zw@Pl)Cy)4u~fK*{j@R_JkyN-iv;fg&tm@|ZUz0r>EGQLQow`xsJKhRzb^YF2jqJxgUX*981)&J6JP7;v zwZ6&wTD_MKU?R4D%9c8W$sRYjxaQ~IbrFpNIdM#jxdDko$dKo}Ygu!jdJZNOApWc{ zC6Lyip4*@ft-C-5L1OM&iY8IOqC@#0jF%5p_9*49uHBlF|3NbWz@pkte@e5>>E{7OC znW?(6t0I?sI~Gjk<*FuDRpFXXG9|`w}^}r&M=CKL+O;v{#;y1voCeG;Dj- zUA-4LB5fwYV4=jYyNl++d0RuWv0VRyb&i~OB3enUKq-Hh<3$5v0|s1I=0B(z6!`^n zbBEOsLE!ki^;5a#VJ!zGGrC2nfIZfGTU$moFJc0t^!z??r|QVHUiS(eR+`S1qqWAl zmUhN-6b>eI)J=RtSOl(cgX%Ep=N2xj(m9eE?gNI`=44;%IHPulKS$i~3=~wm2Gw?u z=KGf$Wt5kMsZ(E@ZKMXY8yG0{fQs!ePBuS^3x*Qnw+g%$9@`w2VLi(%S)sAx@ak+2 zhfsVq2E?>#_tHG|wJosao=TkpY9HG=qC8ihT#AKTU#$ZBrr48*dS>b?)|geF^pyJf zJ1X0!gYNUw*QVkOkih$hdNl@qcRq77+U5JRXnmsIl$W7)Z9Oz}We4Zyor5fXsS<^T z;|eT4Arm7je@PM@;LFrQ-VI=@w6)0}0; zjoHK`QjN+~UcTf^<@YZ|NsYwrwOL%2o|XQ~guf?irIvPS(&b9L0~FJJe#o5Pz<8sH z?i(PM*eumNhK8hfSrl`s6RGZd^!(~obH4UvG2XM+w0<#h(pc1({8L?fvcO8j-A%+^ zikh!D?54Dc>uQf}md}#FvFL)^mEL?q=ib=UMe7csPVknJ(|>!wRJ#&B=*-TZ5OS8* zWZ1e(z2btvIk;a;Rrmeqr}km@Ow*gaHiesubJek#z~++ff*GlflMjWF zK^D;P5wTAyFaM12t)1uO`oz4O|C7Tf%1@4cZ}h*Ea|~{VoTI6flzD-eq5`lx2q>V) zyTX)#R629Sbb@pZaR1v>i=&yB}Ab#9?P*iuxUa`on$N zCMl`t{86vX?wzORR876vX%R?VHfhz|f%ySVNkH+5EJzX#^z6?A%i82Y%Yw2^H`E_DW%F^!<@4Ew+AJ1^~TK)OQ|Brs6 zk2w=a+2f?g@t3@tWid*3VT+ne56(ZuxW3MfpK`~`Vb|?b)?$A=qkgXA!h76V$p)*X z;Bt?GO$_)Ir_;>Wy5Kioz_3|uLfqKKysEa{tD2&vHC5=U=Uh4G(-*Ofo7*^Vsv|lk zbSAG3^u6Auc0iFQgxck)%?%Z)Sv!X{C%!xHRevl;%*=g(6+KEvjETCh3nQKxVNEuzrW)TQZfw#ZUd2}(xDyn!8x~#gjl+1Tc8jTV_QOw* zuXZ;FW;RJ6T{Pm^-^V+TzPNOk8?Ov-Hnim`MtfZxU(_Df=`<9+I)xG41nnxCv(9_R zxAc6?yU}ar%YjDcxh?}|WZ&!!ATc?hc zhr8~BK_AlACu7!dbtY{Yd1599(HoIr8K%4%xcu3d7J&oE)xN$uz5Fy9LW15Te6Q%AAUjwYWz z<3uYwuhgI3>*& zRu`!FIeYbu8Rw%yw~xl6ZdCrr4joGIfH(F=^qb@98DdQtwa$We-lVIT@# z>q?euq`Il53LM96`Pc6L(LT$}aeJ}ug$<3RRUz{@j-v}zo9|qd+tzwef_7yhmhtH~ z^LZ98VcI(iBemx_`Z{91bkr-mhf->+xvOF=oe@^SoYO7dzE^lXq(7OzIn2&SL?$nn zHr9SqKK6~A&yKm988UF=L2%-0Pbluj8km05lAd}Z+EwJ3Z0dEh&-BxGOrn))Q+GJ|@vKb2a6@#W~}vul44!`@MbQ@APREf)AKZ zqIUOWQ>mm?OICe<%iFzldqTOhT^V$lbZ;97&c}9Dca$i9(~56A$n?r!JS6iuI(?*2 ze`vucUUz#l%(e7PymHb8`LN;8%IEU8%ePwBy+P6Wr9IQALoFZS(8k1Kak!#;yKBuw zmoelfJWJ$Uyf|he=ev`&>p+a>Geb{t0`K`x6FUZ-UvIje*sm+=l;=gyi(k@VQEW3G zi}~b!J{P*TulP?qN88{#~b@&bAV_Dp2`Cd zaV%q_gcJ(d?NW9E0}@<=4VOquFhmyOIX?&W(H?teQRu}W0(zHljn14KOCNO`$@SN# zJ0iOyPCb)eHx$JpX{c9rdWv71oK1_wL#ULm5LmtUhJQH`P2@I8@%ddnp=mn6S>BoL z^p-bY@NfMAQgvSh+Y$6KTvW?m=-;7lOb)ls=X&AD>e6Q_Sn-&9%O^#vb~MEH7k_qc z(6lPOu1WGei&uwke!hM41>d~S3?J>+&(oC{6T9r=KNF)$5!q(D@fsrb6cCQo-vR?9 z=8U}zzeZ%{+VyeEvT&E0K$ zh?i=7utoLesPMwVnd=i8`*-0KQuFQX`}2#l$_1Aq?PmXD0dy!aPv^P^(rUu2J|QbM ziWWmAl5|hnSxHV`cppmmT!ndcZ-?y*UGn+<)@>cQf#70a3ne&k5m48JMhG`8oYyz? z9h7KZ3cFI_l6a_osZ7n>z2?_m6E|1qEcTuqHc50dILZn+@x794I%$aPjB$VH_H?yW z{L*i|({axIjF|DVnQBJB3jGe9Zj(qV@r_vbC+#)=$2(_doI2jIkA#v5=0kiEmpkq; zm--~^Ufwge)`7~M33-r5=VNshoYAU#-TGLwxet>~vii8e{nYK;lu_h>nXPwck}3TU zl)V^|DfcGQPN}$A{dv*fP+T&Y&OQe$qVMc&U=BOb0LpnS7Cs` ztB!)hL$*1{?fU4@tgF2)$I0V-CJ+?+^GB!VY&E|DN%Dm0mHmO)V?n{VNZ896FUWV2 zoHP+^ZDT`eM@K2xf#pxw39wi&K4|9kAM<;$k7-_Qp}Y@Y2~2_?z*+c&I8M$T}D?Zp_YQwhe{H%Ds4gbq)g zkGg~|8Pu4$lgdcH^uAM=`R1;&tVcN$G;JosH_O5P5#F^A%RN){gF z9Wk#~)z^A~43Mv#d_^_lV?arzFg39y`1}rHlL(HMx>ln2RTq#81x`i3$r$DBRpjjW zRNWYI|MDy{d1El6e*9{uMGVz36$;MFn+RpFP6pM*DLl5`!BPrch9V{4NmSoL;0?Qen0**_E7JMbABx~t(hQY-E)R?Q zeTVd;viDmsV71;CE_|;%R8ET1OKq|atyoO7RqSE>%n6f0*R8(P$zkz5zBqqQG7C!i ziws$qzn{=O^Vu(HWBbZ<0)JK7nX}X8sfr`IiO_+#D`r2X zMjsq_{M)Svn!{XAzTu;CytxaPyPwN!X3D+mN8EO2l&%~V5b?D_zWk(|%N{lQEHqF5 zjpuleaZe95)Papb&0YLSXjqu1!CWEBYQpuN<1=e%v)$8g?)*2O1A1C1Y0Oz;^7QMX z)4lD#d202&PrSx9n)MMKn#aywKRlU&^oGV~eqW0d6p-n!x`D=VmsUGx_(aicdkv&oN ze9!he$%Tr@caOa@wV$Efiw<`N%8bNcrK6$h%Z=RI^`-g|!VDW|7yj~L`W7oR*@E1T zX?41qd!_lhlWjg^l@Ic`JKywAW#==iuNDed)5e|7H=}#7eTG}&OS?L-kDIy~AGQ;#lVHqB*&5)!5ZJVT8VaM3feukz4I6>>H=`hMzQ^98x>DJD0}zrXxs0-w4~bM$!*R?AA5hLA*) zH>Z`6Vdv-O`QO9@y-QI2)q`GK&cmUjdfA4_2=232`S%)ASkn59aa0UWM)Y9oBTWi; zN3C-@o$o!x7VL4K?i{~M?B|?u^8CrXhW^gr#O!bUuf3L@hB?9(kp-9O>|Gn44oXIJ z&(uP0!D?7|?z|04!xYdv6{?QE8sw3#-xZ0^?RLK&0P*=kLpzX2@f72&gu-k*l8T)o z1ZxfjQ%!wF=0G^$3y1=W_Pf|gY5y?wbyqK*76>DN^fn89L5?k}9tHsedYz z-pmT}w+9E0mD2FGs&-LnN*S1=XUmsS>TOBj)J)p5=PSHVow4Uu-UyZzx5 zc1*T)Oh`00`!0gCH-}w8H7B9-D%@|VtLL8uGABwYq)5K=ZHj1*=X~4R>sF-eg0=2@ z!NGmy>=(Ik=6Wzv?c00MlSaRhRIhWc5{zk@i}^v zLel}OCAG)r>ZS`ieqoyo3Yr1ss_W15;_d_xYBqmt+}h3kbne}{6_F%+&Vn4A1Q^UuA9rDixs z1BvLrE-qP}btO63P98OT+4W->T>Un-Q1A|=={@CQ&@$$zUm^54?2%u)o-dnQ_cDhJ z(4?*lkXPRiab6`0jCKTf%8Gl>e48lnD-gr84qZmwUKl|d`M zxE))=E{j=MieAR|nLDok7zQbt#+-b#HANDU^0dtxzxH4vLc$Dhhm7JAH^hm(I|#2C zysm@8^)O99Cm#dXS!X>qWrxT~eTxdeuIW!ZXL%By>hw0$VhK;W#n?O=(+ulfz-*FC z>hySrS*#8@^(Km(>1%? z>?Xp7lqz+2DNn`1>T-l<^#I(4XM)#+|7_{qs57;`H?FOiSYt!y8sqZ$Oljrl$OnF| zxj)DEpb6U*JUssK1Zkg0qY$f=udv8Q5Rt>S8FQI1&j!Q`u@SU~aB_+gkMo6<1nQ1Pz=?%3O7VOT*9 zyeq#f9A{0KS1L%X8Xa%r8HiRfnlcOgDQgBnu%#u1StBNve4T=B1tt7pY7FLR9Pz1# zXh%jNC_G2bmVqKZ&LU&I?(?$;(_Uzke+>H>(+_N?>l&9n7v-J!{(_-W^gKypG z19CPz%Nl5KX+J0R`g=63&+H#$P6)Q*G1_%@T}HmQdAzLI>1;Ri%)Q>3A~{n2-78h6 z8qbSC?`u_zoPAMt?e)FA_45XQ2Qi~Y>ns?g!476spj`Kce0LUR6>j^yXn?9Qh+uh< zqJJc>t<7_9d4Hzic4wtW(jJ%@Kk2fu#TT0}oxu8RrRMkOge$oOY;~ z3qOE#UCGgQjjckyXvM(v8}7W=|u`LC&yIY(D0SSP^_Pomj8D@D5;1-kL^P zoQ$z*AP@jOd##}0lz-nBsXeWGJtTCjm;1bwJ`W_;l`=dc9u@9rt+UDC^YUyLcY`dq zI=VV-dkKKLNQXd%0iwJgx{#DCa`#zy-=3qum;WWqzwV=8Ry<`xjParjgb5tO)etnL zsZ}H6#mOJD?;p!$UEXd^<;!vUGJ&$}-{1Qi8HfYfmC{~}JDfc+6<6>#asR+b*M_++c z@Gm@{;%WG4plGb1Kej;BdvBgsqp!DjtBQup@kq-X`urhfDt4&$!99cpR6;bnYJb-s64oZRePZAVl`#Al)qutQ!WgQ=As$3u0*u7LVQzGc>5$%~*olDv1X1@n7Y)m( z&rE&h`M6T%Y$47VwGF7GEYL47u?#hcTF4TV@Uv83aO64r3v37PIx|q>CsBx7U(!hyB zD?`ry0txamw$)i9>m}3MlI{u;c)>=+;0w#UyYrhuDExu`fA|9rIIm#Wf`_uKN}zY3 zh6Ng_pR{-tV!KBdduq=$?zwp^i_mPC=$`?=0PKoI&**{%*b=Q~OMB>@sKinvh<^gY z2#{;Na47w0>Ho03)M{=uSmkt7R}W%}P)22`Z_4s4O4$ zrxwv#>0MEcI5=sZ`0~wc7^+TlaLVxIcMfNKX^WEqZvGfwlUktACEgPOR3@A2>$;_t z6|o;cR=_-g1U?&bA;S}&Q;-=9&D>jwH(pv?d}(cM9kuzphJ-#M+=>hSJAou?=tUIbCF&A zq4>gV%moc6!oOigb)^8Ld)1*TLEp}$qtoVgf8ZG3<$`~>#oD56>@Dr>EeiS;{oC2* zX7Q$`rYj$N7O;*EF0{%1 z=K?4Rl-)w=+PpU0{m4EMS2LA@m$$MzJJ4?8zGjHVq=EWk84d4GC;XRKdVzICw0QOb zHHIhHvjqzNwwh4GHg&`b&>KDOKeD9{CQZvLtY+uZjE$OSLRh1shWZXZ zg1(C_iJ&)M@X)^|yWsI;p8ZAPf)|Uc(a@i~ZXE2dI@cJ}W}8pPVjtN_rcT=}ONFo* zBivPE0B$+nC>ofjJ@>o_Rx6jDXgkuS0BVbgIoG<^}*@E#0z z!}%YaM+zn!qMAv|L^i=qI*74k?;_1R`ag;lsGvZbBChZifA^nOcj-&}g05B+&9r&Snj0)$Kr)U2 zpNWD|XMO(=2Fk|R4pJ9Pz}>}k5G6YIRMlMqPV@s=ZM+6Jk)m>ilv-V$-|oNt$@Q0Y zxQG19FMucP?_cdp4m!V&(hyuPkVqt$&h>#-%FOJ2!b38$d`!>b2ZxtydfpyY6S~Iw z{s6B6yZ}HQfGjKLS2x333jY-#+8N&T_>s5Gd)&FQ=WKu)uiLT$e8XSFs!FKvxu%U3 zZlvWH_DIA}T~Y@Z8V^x4m52>EH_ewZ874$R_!T*vD#C?(7eRq?E zfnlw?solP5Ja*uq#GM^6?la)}crpJt>CGHkiog(Anvp|?!<^f)0NUcB4ETL3i$Ogs zY@1%&;5jJx0vt@VZ*@?Qs9v@Sm_Fkg(u+uMoLYgi{>!`1n-YEkR`##qZ23fCSB|Ep z)MXSY7aor1Zu~$ZT<|}p?k?9y*}vs4;R+9a7`YJ=62dF{fB!y}xfmYPGD&W{?MG*N z9}sBbY~uBSfcc08Dz*vydZ1$f;NeHFpdiP}C^GZf(NSfWc7qFdUJh@y-sn(Zc1^}R zIkoMavW4r_I#51F$rK|FCM7Eh5A`<~AH0Duf!#*!JCbdQSN&f0XFgb|Gz;l5*}3Sz zuYg>%YK3FO!Y`I@@xo9GU>}!G;YX)X{z$Dpq%7&5U}S~2y;3r`Bv1AS1(G}fisw);otWK;}w7gFE) z`2pW7!kEzNDzv6j@XJK!*j`e84g$hFo>ee{^oRs{^+|xo;fQxOMja!-SHj=LtGhRp z$J)ure0E6#EQOkSK}EMZFON$T9~!^$NbhD4qs4?);U1>Pz1)rkBykEb-qhhp9NJEi z|7fb9Pgn#?J3H4A|5toM>JIwNPS!ZkCnhFx^dP|ehqrH+?o*Ae4LOU!AirwrA(10M zkioA2tOfT5_AbYC-mQFAK;#2>EI(fp?!A_Rg@lP4y^xZ63et+;Im>#I-Mr=mp2tb4 z1LkTxN%A+qXn|G%oeul=b`?=o}baDh*n`qwI$4+)#~tnX6SWJPTU@syv|i zE>%z0GK$N!KmxPEr5p_qT5uOjVkmrA3xxYYx=L@>=Pa9Pd%HX&giIN5F`)UZLi$42 zQH#T90*IuJ{|U)!_y?0C|5B;2yIwG-$Pw-&u@c9WB47jF?&_%$B+p>8@<- z>&*$SA29G17lWu?7D2|=0qOsQ2}@PW+&Phe7aY$3ZC-Fg$_jGoD)vD&O6J6d(U5rM zhEr!a8T>gSbmaW}oK{2#RJ9m60gc+NLi3*qyR-!`;5YyAR|r`tsoUU2>bXIM;%OIj zz5qoEx;Q&*KW)CaYp?OT2)a3QGVm$R;zW^Pz;%idund5i@FPj-?4$EnCGO$oG6! zr&hTJ#FRa~PG+ZXRai~~yLP)_j8)w}0ESBUby9Cu4FIR~db#`~00Ni0SYg*FD`IOi z@AvqlKTEYp|64T6I*3cp?_WdzHLB#b&5Hhi zykjjS0S@#xIHc^>zX<7aaJcF<%|IPOMG&{&-6y9x--i zIL3;qPKbvs)R0&vK+B{DmJVP$2!I0VoD|b=G0YRD9Xl%qvbhg{t5MDb${+u4l_kQ_ zEP0`aB6(^N@ajWDZ>U;<%B{kVr!6Sdr3pAc@iwC+dw;r~U0%Hxgem~u09f42?9RQh zP%C9rf{z0KZ4A}CBf22It!!&?S3qm#HrOL%lh1f;dhl#m7U8sS( z2dHDnwFd7KB_(`EK|5zb0liBhZRkhSxk=zh>*nTu@Mk&lRt)^4kqY{Z^CQM@SpPk5 zxL9m#Y(+(d{l;kiwYJLxO3L0EhvmEY_&dJuP^Tss@)XR>0K+ljyUS`Ji07_520&gI zwvLtd3+n8^@0=NMKcti}{t_k%SIFS{0=!3}!ZCQ^AZf5DJe=JlPKzrMT-o`Xw18qe zpiv{Q@-o(w?Z%yZi8k&Mry?Ezcl0(l2PECLOB7XS0Yo>TjRN1K`yc1|Yi2aXjKENFTKiqP< zf2%ivD`?L?OFq`ZB44vWN^|;z!+1yDB0u)qx9SR{(bS`tF48B1kO;wq02Nf|ujQQE zsu^}EgERv`;FN*7|1?{q9tEOBz$e^gJOuuBB8)CHUJYFVxr+GRn~_ zt)!uK3aLbV|8T0kp`Y_E^*O_x)$f4~T)6>Q;PwSF+xqP)Ko+11_`vJbd;x_Kwa9V( z0gsEW7^Xu|0=kSqV7;i(d;aV;3XC@^{_7!ve$K|lV630wyJdNB0_ld8)j(I% z10teItD(y6{WDNJ)dE194)Jindx9+oMSp-(#ZdWc56}-!hvgfkp^Z*VV-xT{_i4E0 zx4(Q3+(fEn7zMyp)wIl4dN}oK*K@eP#c8Q(t=^S39w>g-7x63Lg47Vcvs3(mZU*)n zIL^hsnqd#dJhyv6bPeFCX6`)p1)h%y?gW%s_y`cr?VwZ!;2$WA$I4a)S>}EhXM^%T zi>zhj1?UVXM==e`!o*RA9JNo4LGoq=z%xO@8eD5YQ^MU>{^;m5&1e@WiIxhgXBPjgf!6YHgKxB=8i-9}C1&#N&s+=6#O@gYwtQ&3n zS!RC(Gzl1sVAKUFjeR$2V@s;NJtgMKAg@-r{$S?Z&&3y{-(8GtggtfTc^BjRAX73n z0|i>?PKR44mBz}c$YRkdZ)MQ}x?EZ6G%12nYP1ree%gVmK zC?{)7&MHh)%B2UvH>-5Ee{z-75`e)dH-h*BaDd@g(P|NT#`^M7)=y*J_m5JiM`YxQ zZFf_fu7>|2B!|Z45fw&MtWotGRj#b*k^A?vj)EFfW3M4OuLjwIZiA+ocwkLWSJOOU zf-OCd%6pKn@)mf~7CfMiuwp}H4UbdZD+^6$g0!=+&)+&f`FH5*3pqR+RQ+M0F=26{ zrCXndWJt!nE5y~rbZ>bdy`00AYq}3jv8K<|W*sQj2)L-RiUP5%3W%B=ID8<2toQqT zuWjX9tZt>{*aP{;Ra5e4dE5yA+&y(CA^QYeiHy^r49?%u#`;6MrBQrf_|#Lwx`)Qb zuPD}lg$61x1>gE00`I>Ss5c?bvnyo2Fzk!`WTi?#$p*J|3K<>gjkiqGqft?=3o>K#JZOA$jr(>(BL$E64O-#f8TY zme_ixrc|F7R0S;Eryg7QmLhQL1z6*d`LllhqSsWR0Gmcg1Cs8=1nX!F+*?0<>K#Sp z(sQvnLOPHwV`i@`^KA|kgeX~U=0QGv1Tl3`)5$i+_82TJuyf$-ATo)a5xFq}3c}E= z4_MyER4=vI9ebAq8qeVg^?uKDGiE z5AZe^CCv@8xEv?D)=S;`u>CsMr#u43o?uxUsjER%T6Lx^4Vl&IR7$J5_xvKuU?FCS z2la+GNDrZ^?fju?D55|38&%{cD18|%Lg?5oPglOPGdEuiKD{CVG{z78w~6ubupZ84 z1<<&v${Nf;dq_fZOqzy1x$T03i#yfm=~~RmvtK6FNhQ!b5h*yLnuH^eLLt$5guT{X zemdX0^G7FU8RKb(n#3{1z<$B2^o7KD7s$^lD!BaVnw{_J)g=i`=-#U{MEZ3rmUQI! zLpeo`VjJ&ddZY_^^L4QA50NhVD4PXNJA}&cli0$)r@J*)o;QCsvM?Vz`#ajZX+Duh zPg^S7xFXiqd1!=X3OdlW3jW!QZ`*%&chiZA8hVO+WmWaWk;Br9-tda-=;%OPPTuKO zv434JKFO+q^l_^pq)ESnat%qUE%Q+3gSam_3TEaF`tnsjKQIT_92|%7z*MUd*ir|| z`T|ecUyMx!c&2wWy`ga9Id@9K0+q42c2sC>pde+yaBO6z3|OhaUceAai+)N+_Yn*} z?eRh#*IP$A2U9aMy^&PHlclCuBw_Db=0`WILL&IVi!$12c$M#KLre7}84!8M&?X!i9 ziDer;Q&-pA?NOGkd-wiDEZ$17fReFjTBu$iJmy!$G1Z1jSIvbqTA}5GmVr6H^gdM_ zs8$A4P98wRnxBTH!>sl45%raBO>N*3rShQ1#%$ShlB=T>^ zF7Y;h7gy$EnuG@8zIn|?v7sFhq$7ylb&?-K)w@)d{f90>+KT5>1}zrV%AnQ8_^Y}7d(Oi;pDFCFgGUPX<(#oa|$60)Q-*Aj`tFjgBk z=#IyleVsxWV&wxJ)bakhaoJpMd-fbmChIIq9^XIdzM}^>x%?qt`{VSkv36{YPmpu+}99B8)y zFWutCJFQ7&Q<+Hkq-%wr(IAo+#ePRg)CB=mM;xlMsd-wic#~IXA+kft$uBA+De}N9@UMf>eBEUtbY#Z!SLGjQTY?@<*KJ z$2p4sc_s8okPi6kyQ&uj5}MNOoeu~pdcu1+M&j++dCDFvb$?VT-9NYFy2KQnNm;0M zp3V@{xsGpjDt@WpHr@wgRIoyu2mQlXPCsI~VdjhywTPOMGSym5S+x>b|HLsd354@^)E+0EN^YTuMVrX5 zIas_wIKutd9q!R_j^pK!BAHs`8EB76`k_KUA&kH%`de9J!2^`d?D)2aSigr}4u>z~ znz5Cmh#YD2m&6Xv7-N5-S)i1wkeJD?-{8hY#H1uuyjyFcSvfBJ!O~{6O?VFYKg!eDKargP3y^(S%^&g zo{$)ztCuK5PcBY13E$RfQdoXp5Oex#J8JKjw5$E*)(bO|f5F_vUO_yNzCTn~-rtrC zIz4`5T(UOFMM5LonbMccb$;rk54xa$yxWfr@=T#1p0>UhplII}1ecdFuEjlFsUK-J z-Z)(HF8H-Re%zgDy_lxA)cMwyU%z5S&wMT0*1|K+qH50e!lpLXVrIH&a{CcOthu{7 zTcbs%7Fk>(1zlJ--DBah-jsQoHo+9#7cH2hpqGt6lyGlK;#peTpWamd^nu(*rSS$! z&uA*k*MK@6BuHXoVke9?qiC$Sk8JV3^E8gqM%>vbk30#gnR{I5g?y7QN0SM!-bb<= zE??SkDZrfs5q4pV;KP9T1aCc5N$KUz57y_NOR)RHuLVD&Z#$NBy>|M}giC*A(>g32 zed}o`o{5DFtvokQh<-BWiy8RS;e!I3ajW_MYIcz0#wU2YdJ?89;?zer+xd4O_nOyd zUpGQ``ri1M52Qu>GHH2RTCv&0 z!NI{C+8RpCCV)tRpaqA93X%0#$M{^GJHsI;dv)n3r&z47r^ghG_fBn~Lr9#TFqyUZ zX`PVy&bh-^{>=N7*RpeRm-oHg>T*1)(k_vbLf>=SC*MA2@-)8XC$Dv9cD@12@5`6# z-jww|Lswl%Dc%>DR=@L_@y4I2VQYS9D2fh@zV_o47*n6#Hxlixy4pUQe!ItFh3{;- zsThzjE4!ikvB!=>;c3LEt<_p}{C!UPUyS?>4XiB4GOclrKIYp$Z9b)nB8I~yhH;>U zvH6OHpT`DyL>pzSrjip#yZvs}TT|0>acLx9LCKN7y~GmhqbG?693*RbHG28Z_i5}l z@eG!$d$??M`q$-9)6Lh&^-}%ewRohWBEk>T&`HCo6P}<-7r=5T9jy(0ilE?s%a=Uu zZCpOp+ZjQzzqcoF-2eB#4HLW>EI|&LsrYwogZBk9r?d5=0vzlQwgk!gI%{qhez)3< z9I-_`D{agXU4v@G(DLrCh6e8+IeMQ!yCangImIgx4auTgl9B%J$fVnEC!wmRwK9FQ zo)4~`r|gNsS0+7(N|8oCYBV2cZ^GOLRJQr#l{bad4-3wmb_q#*ef?^jb=wPj=nB8r zb?j+0Qc+@PU9gT;RUD*x9tt*4oX~SO8*f!GJol@;S=aZsq)98%DV6y9(obfEJa7Gd z3yBmM?1O({lln8;p$ZU$O)=!-b%}nSoMQuFmgX8VC z3jy@OhF%3$J?uBid=o!y;46L9pRnzqDJdG|$y+(yU7y2Nm*5(K(5jNL0aU=0n>*-3 zHPe%aF$tt{9v=5B^r04bR!?jVNn}UpUgK8W52gP1!Zw+Tjr}`qg zTgv? z5>Ns)n&MG3Vdy$bl-l^$qrFS3#2eEUP+ZJ;b&j-}Sl!$VljS$XeJmhQ6BCJUkobDLZ_Jru|qa{IQ}u;tvfX!4{U&distU1gpM=#p}H8} z{;T#!fsa1Ee*NJ(O9m-`G;*U2)-32gJLPt*qv&OBMBm@Hhr!h37gVkMHcayuCw9i; zMrW&vM*5f6U;I5?9(DGA$4>q`U?7s%WiEc>ba}cDw;nBO*S+iU^SIHFMZ~$QdyvEK znDnP%n#PDoyhdsa&SdYEMt*FvpW?;z(GmGh;!se6ht#=GMEyVYY0tdqr-GO(B$?;WZq+lXw(!d!9!%@APR`U2D@!t*u zhB5zqLEv|#0N4k0I&$knLvg;>qC21NErM<#789?i>l67*v8p< zpYeHvRi&pO`BPI7=(80*&yl;sXBC_8Lt?2T$u%Xj*{gbWspQ<5ujfrhyzPq>@@^T`;w2owx z^)<73Z_Z)jdQ?xAX(K~-JldkYf~MOF2n4Bigz`@W0hhng9k(v-vx8X{4a(6 zZ)X@87^HC_ol!LND-s&Kl*r>F>!u=>7u(&7`Q4{BkT4@&se5+JLlPQSlo}=XR7Xav zDoO}{`mcY)Y^+pKwFyb)VQ*dK0uM|`^kG;+V}iX1f3q8Vep$tPLqU)MzMQ97xc!Ev z3a*{j2}6ASqGAn6fns2hS6ty`kF#nx-+_ukd^g>xzz(zU+Yvh!Vm7kPGmbK$uZZ2IU!s zR1f7DaugSd*|e(1mh&~mSSBIdszy7tZKeu}`!(#eefj>7CtP*cJk=STUVU$GR7h6M*Yk$jQtxG@OJh^S?hnP7ik@j1TUQ-B`;urN@@4yq87rv{ zl{AO^)4&3jfeZA*f)JP_*0$B+__5xVg&V;1#e0Plyj@P=Y3Y|_!xdd9P<6chw6wGo zzRAbQsr*+IEY&$5qen6TXa%Ijz@Ny*^7~6a5eP(3bu~Xoi^Jx00VVJ_y&5h*XN6i) z2R>O@Sy~>RZ(qLL2Pab*gb4XimiII^Q~Kvc7J;h$dz`L#BfW(5l~)fQgvu)5jj^gA zHS@q#;wx8OUWPc#F3IWX@B-2PL@}%+Q8P))q|v9N0#ft2(a#3C{)k(P%VJ~&K2VBe zl<=rITrZ*rg7o{$!sQKr-dNGl%QU?gnmYT79dPkx)6nt(I;SxEig6|zk>5$8v)wuo1?64@=TX( z_n)vf1~v?NsUMOQ^VW7&*>-Kx5C`u=YP6tGb?@&rCNJ&48dQGKydwJvku%Ln)FEBB z8*y>fl_A94f4?8_*k?}Yb-mBX4@I?Ki8`iDC>!snV)Sv$XTRm7mUV6CV?l5|RO=~Z(oM(u}VL9hchi04a zXPUeTxXPHr@0SasIaK-tNY&gL9GuV-P0~{V(|{~CBWK55-~12<+Hh&yJX%Xdv6m;t zg%Wj`#ws?D=d7dc?J7QVvpuU^htMlhtoGw6#lGm(&3j0siIa8U4B4o-m|srlx>C^s z=q@tEXXtUq5{#J#y*n6_t;;GsWB9(IzI@>R-|41>)1hRpj}U|!dhI@T_A{65;{Svf zRITK5{>D>{s~HtASb!`S_Yk!hh?WUOw-6C(H+eQ8u)?0<;|ZvSvtCjllsf+EsYY8g z`d7zJqUrbizywYeYrdvTvpg=I7!lli1n2|BczhLqrJJ`3d{bt^qWoZsY$m2|%+rgK zQR1b2N`^)!l1BVG+#-8A(V*-(8YTP`O3sl~V5n8Vg^UMWJn}gYR^dtS8V1h*Bj)c! z{*OR-{OP55+226;lycp!@ufdQj+fdj^yiy=mh}1{JI0Q}P>~6b1A|S~2I6kK>}?@2 zkTU?6PZ9S`3$2@`gQYeq%}e1)6#%X6Q4gZiJJ^DHTh?X6!Hq+>yg zhc!4~NxOfTVAmN;PI0H#c}Uih`5O&f21|%s+uU@&v)x6B^QOtO7v5W1V$=p*OVG!0 zZY$;OZ0W%A==R#GD{`y8BEWtmb6(E;+^?om7k@Ed&M-<((TXNv127xI!$~J0p$CtF zoi!>t_k)sJp{m1-NUGq7_9*|y&F->OaU95yl&i+4`9r@pgRQ6t`em}V#eljmuf*&s zqyBeaV&mh%)DLP}T3WaZ>w6)nX7T%ON?CA}7FQxON(A5js7fb)zER!VOABv0uR=-w z@Z_;iz&V6(_b}60=mk`=B27kOalp|zFc{=)A5DJkTrhk*fIa_dpen(IN*#nF!ssww zv*(q$?~LbVYx+4Ri%0uA^p?~6QoC8t zoCYH>B5gcr3=qU^FmQJY$He-D4dYrS_D5*qRyMtt6f+-J^A zOI|v8XDd{z^M{1O6j9Dw#9OaDz6m}uY~MogtByv0-@BdG9J7z}CNJQBEIJPEl)hpQWEPK8>fOH1l)`Nrep=iMp-pVv;sCh^{Ll> z=9cz^pKeG>g12T>yg+kQHS_DE9Ig0hd3`nS10T>gs51F&QQIb`bV|K_5PcY?KU2)k z?itnLbDV#j@PMdrJ6XHvY4sGMMOl0jbUA4yPnxidB%R7YIt5%u;h;hw!6We`-)-GJ zcwWAIiLc+DZMW}f`kq7eRldogX&dObOX~w%}mWzMnAdvhuQ6UL73Sn>CED1o?!n^eY!li-^`N zSS=|o)_8MQ4wpLF;#AtP6V9s>uP#&E`Ny?;?d?0O-IPsJDaw6ZKE!b|l_Do63XE6F z&S^>9=*{?JTGOfGL5I_-OiL$@4Ty2f8;6m*3I_dgYG)`8M~bQRPwBzxOZ@cZbD73g zPGoAM07?hn9il!4Iby5X7+LX~BLy6l?demYECRG`$M6wUE>A!$AmPM*sd+Y9L zi8VD3#LaH#!^4bj@Sw%TV=p>`*0jY%U06}V zAW__U{KZrtlY0L z3UC8HV3E)7MI+!gJAXELdILl`kR*t~UknEfi?^G#?8}==YWXBr;j4){_NxO%qIJAvzfUg} zG<$T1cF;@;0cZ1Lz!#(-wus(c%_O3$moz>1jUtTk?zUT~>3o;$tVzXExVgZW;j*Y(7w zJJxAj36s~Y0>Z9h1yKf@H>?=-+wC$BT`gappEG%gn7<)pi}!Dpp%oJKOeS5jUn?Kn zzrHB9KWP#C(@`qARTwH5*ell7JVVf_)BhDgeZ0!+L+Yl-PvnLMp|JDX&~HggY}@l7 zcY>E`dwcB*)O@;25M6kBb3OC^@9p90;1Gf$&7g0jZEOf^Eckduxjf0G6x?SHJ?NqU za}h3yq&y_VP*nKf`P7~j^@CpKmdJTZZt}J~LykX$xD-p%;?#Jx6&{xu1%2fp_a{|UFrC;(dm97NgpcfdU9{>7OF>p* zh0M8fRza~yYu4^;{3a&@%0_$7XciIgtyTl?&e$qin$xsCgX88X7VO0Iw_$u~H-RfR zKHFyw$(+0!`j>-P#3;=nzjo$j`I1M6?7hxbmh}OaUA!~>>K`T z1Fu2(LB*1~ujn(~*lRgEbQ((h4G0M&@&n(Ns8Et~*fd=9a^9%K-Gs=@{(_%D*K2zZLxX>eYj%_tF0Tzkl$noc2dmwd+toV3hNw7Ugpr5} zQ*0%yxs+4?ik&Xac*89>4KCkq^k3}NHlND<-*L`XNNaT~K@g?-^}o=*@MUF~w>B>H zB=BiPm^W+9sTzwMkh&KYjq~?6ehTDA-cPxNu*hT zYo|8=hbDbQ`i*xQBeKWMfcneQ!3Sw|Y>t_&J9K#nw4dnd)91w?AV9!#4wcNsZb+M; zKi=TG-kYJaeyCcTglev(RQW6x$`f>rOv&{S>F$~oqFYDq+Ie|TG`~D7#>ozZLR&)u zlHd-9ne3;t)h%AlEA(DE7VXOM9Z4Z%r}I}gy~(BXdj^R8!rQlMcd+Twv`SVlwSW230X&dy+xBM4IoBB2>3^pZ(*I= z*tb`@{IL#%V$a!A`-=*Do=)Po4NddKMs0zg)QS-)wAEgnuhrhflj3HJHTAi;frE~x zeAefJkfGbR3w5V4^sj4oB9_FbkkC2D<@dJ@yjb1=lwMvC)}|_Z<{8$OutzUC9iS&< z2FH2T%eh-_E#A(!`V8&g3Pszl432WDKD1{;KAR0Cb{A=JQ7nk~P5E3HzyB#zbuCn_ zc!oIF^_eld?Got`J8C9r4c4_PV#kcWeJiTvPRoKf;c>lbUjMa?UDzGUWa<)O2&nno z-SJEYrZl*C`@~^a&_DD}k7`Abc;`XKEB1sw1F4=^*)9Gl2Ctm+8g{SjN}lZ(qW&y# z?^o}B3Rs&DdZI!Du@5Qj-NUf)K6gaM*sT4%Q8*jjloV|=LjTpcZ$q!4WbqcVHdtDb zU&Rf*g0o*aWPNB?J|!-N-VhSVyC=IXgOl?ENoqWM&bEIybMA~3kI(Pt?=dYmaed#D zNn4vD-{xws47S2$e(a7(Xttst)PL9)Ix9bWzhc2xOH!r!&GX-yRk0p1eC$oW^;u_C zJ-&|2ed_6e>a5&3&PmrSxH(K&NI>b)ZwZ%2Gi_g29F6p9rP+xjl{B;d??}X^b>NHv_gMdUJ^$Zl)V#8^y!Mcp0 ztZX_}`^Sf*vwJ{%lM*mL7Ta8`G*bf1qOLu_dPrbbg4w@Ns~{wgxEbW+rLP6rFZc<9 zU^a&pRYyP&$<@ip^odFsVm@zUukLe>OZs^7P=2ehfh9qBu~Ylg4w%#p3MYRRPBSvg zvd!t%!7BgWK}sa+Y%R$$&t1!fYM;v3GGDalUsb^(xjY)>r;xIOn1?-W1{Xz5n$w`Roz5eYmGJzA2WctYG+k1qOg`HqIL zOU~3Hk`Memkf;G+4vVfaam}-~4-9p7_10Mho(nZMvV&I| z3tUq}Hzm2gt{L896Pk>tNh&GXK7U)48&#mUUCQ*S+_0P`yJ7mrYtxq#cJZG~RqFHG z3(3)A7*!`zL=A3lZ*Cl+;490R9GDnTpXNs}S2t>&UJTYPUOja5Ycy%Q)neNn7A$FX zCRo1>BI1NunSJts+!_QI`#5ZKrUpd3T{$~7p*%nia*AF3t7QIEc>!b%aJhlgX4D7z zk-FpCBAh>5}}st)zT8xs?g zh=@PZ+CWVFs|)RDSn3Dx>Cx83BipLmI8?*JaM1be5{K`}`|6Id0MT~8l^L7I)J1UP zQ8hfETj@+@=-(G=npJPVT+PNx4+Jx0#gSLRW&@F-340?b?>ULF<9wTllo6it4>q@! zgxx|u8@YX_cvoE9YOm|Yho`D{IdwT*gXS~wS61cd<1lF0?8`(%Ww01=82V;ZK>Dre z`tCb3`Gq!Bc81&yyu)ZN8A;{TE-shciMai9*nZ*&N89<@Bp(XD8^6WQ8nwExuuEn( zwqfUw=q8b3Ep~elx@5jfE2`GnE_xoGyYd^E20fkx=SH10sF~cQK#|AMBN)UZSf|&s zRvBE79v{*-?3=NTskLyOA441b<8QoxlLLKFjY#+8GXr2g!zq69fJ%L~>J0C3p?bCI zfp(`%t!@wLxd9+NYRtFD%gPyPXvu+A$zA?L-i__u*jiQ!*~wmG*F}Qsk|l$Bt3d?W z9wLD)oe8siDZ{U|NXQQvJkDJM!$aF}d$%o4FE<3jg_gaDpb-0)dkTCfiv>`Dzv{_U zx(+;iqod=xOKc67ds89ZA>>>ZqtEV98mrCxf6f}7GVe1JQL!Cmt~Fj3DYb={0h$1% z-#D-}64)CmsnYMmy-FQQkZ!MIrlg9GzxQ}woVr@hUr_)7)mZs|0ac-jR)FU#jjL+& z@LX?#H{2Q-dlH|)=>_U>RD|KP!LDDyUgj)MuHBMpV3*gu``8>=6CNG(3Eitib%`lk`U#yrSypsMw=D{9&p%PGA_dV_B=N??FH!h zmwkO;v2j&1bYRYuy&ejdUfGWhp}a2ch>5_@7UEZ*e!WQ}YLSD&q;K%Jd_KDWSRY!K zJhxg*$Y3ugW1yJN5KZ<9_~55k@F11ak1*eW;PD3!Md;Zzc&e1?38RBMH)d|1Ob&M5 zQpgb&aO?4s-*p8Jf6x_XCm}Bd7Yo-2A$sJp&!)Ji)pMSR9EoD%$iMe^6;@j4{mg3( zACq$O1eY~BYu8+{&HABI6!o>nfGb%jZCIilpDCg*u;_`dpfH-B@-zuWX0ejUs}NXx z@RDf5dIxSR2d-F*s-cpXBl^&0H_h|-(^obl6h!#n(D*wvCKPpl6-K+_uiaKD}iwQ~NqU&sZfOsn^>rYknY(bj=1XjUb zb{+X;;8uvzNCRIRrEG7>1}Xz z!KbUnnUOTajctIj^P=zO!vLJOc<~#4AxrBGb#*Jjl$G_nE=J{fgbz|Nem1nFY(stG zsiClyyTR1;?mBb|+7a79z>%VtGH|)SJbh|6*AmExYq!RjR_bo$#2%gaIK0lo#A!Re zcXH|iuu;%)GdVwEnhmJBE#>23?pLaxE#k&3o*D^vdhQ_QuJ%4DLRdVkCvb)YdSR8B z9zjcR8|we#J0*(6MYJjvFG;=4-;poTC^VZ4e~?osEl=<%&{x0GDof`BlGu+P*_II4 z?OfrK%!xvPFhU(0-#7!O`7I9*@cAZ3fS;}_@{Yz zjmxOZqm>_p>}G?w5mB=aSW$s{+9EVdGLk*s0|kTqa~Ds3iAg#ib~$sv=z2-x%+K55 z`~7bVdv)FX!8)k)KD>dkx6`diDub`QwK=wOAwD+|B~GPR{3Y>9{ZjNrMsAioq&Ujg z*M4%Lsay#U$@fL^>nZOl;2bfVIA2iLVs~za!sG;;ykJN3jD{*-2^?4@mn|tu_s*@x z;D*R?`?4*2suz1=l=&4B#;&i+^V3nHnN#xPJ4e)@Fx;E(l~kZ5Y1+>80uA09=0LQZ zMJFbGdyx?_4f9BqZ}AvDUW2W42I6DMH@al2^E5lVg>;LcwVBH3yN-8OEN}9v`RAmH zUB5m0+ELVhhxGYnvuGgi;z0%lWV*+HDL-EE?2NFuUsAtsO_?J}ytJ+^?D|GO5M8*a zb$KVIHFpk?rLvd|2%iS;RfujU|@o>+8u$vK>O$7!#?ShsttJSN@RSx6w$5?Ce?Ew0*3&P}8+6>v2L$=K0cTIMSJdW0Uh;Zc8_A{qAU%oNX84`nGuL-VfV=J;TY z%gsK|n{{qk>r)0}LYOLcZ!`SEK=JmEwS|&O{B>`*kM(s11}Cte@;eBk3R+U#=#nH2 z8hhRFMIs)Nid9tRRVQTF;iYI-~F5}be7zrLLCsSvbgky(FE$?xzC1E=TY zgb%CgF7F60<@_mo#B2v`CeFKyKfPc02%Z;Ng0V|E7m>Fr{@x%Vr3~<+@X&1o>WVUY zTdR{_YYp%RpPSzPh>X|KQlcIBe90BFP(S4EPF5eG-xj%3@0BHM<|;dJ+_y5^=18vC zu)!z_spc1G?M=+k?u1?08_RY*dxa7Sky-W(FNAOk3YS=4GcGz8cC@n7N^T5&B?+yM zmGR_e&Dee>8F80*^8)^4*h~6;tXAx|ia+avUQ9-C73BW`y`0+i$iVmp$YbE@t}k4u_+ImRIF# z2@|-4{aZ4W7R!ahnjSM9``(-TKLkQPKS}`i(k9-gKzZAJkJdVT8^A+se@OChPvPX# zi;(wV4q_gPn)DouY47!5Y8T4JnUTCJd^156&1;Lsg@8GPLG^(mTGXEUrve?)ehe1H z4nf$k9Z=7`$0cf~sp=jO7+C{M{WAq&W~s50Me-t)F-q;SV2%U!q_9dO3Bk zf!X4u5pc?qJN_oU>n7}avwvZb+85?mY?*KqQ5(-I6oSJm(urxp6D+0BAhbJeEvo$? zrrR%-Zb@-n+F6e_xDiw+;?HL@+m;=tAKdL!v@&3p%{{H^RFy>jitlpn?S|L8h{0)t zp7~m&Y-yro1IS}^cyte=`m|hu8`nimjaei)O=jD=Ae~Af>3m^NgsLFF$gOvEGV1OSvZ2F()uBJV(=j|x4MSX@lim~1o_W^+X88- zMbEXlwc`)vM-xlH5YtwR!7*toywv!`!-$gKduLQYq}Ama<>}pMB9Pqw{c-Qi-}W6T zi*+iqk&(6U$7x^xPN2vR=x4;iYCL3w>xY0a!{{;MV}s&9jj0p$PgdKc#3Of$0h9oa8qXiD?|_4c-MWtC=m1QZ}Zf`g0F z^lIyDj6(Lw$Ruxxi7lSn>BYLzGsK)#Zs{?l$E5&?%HUw$@{qbxb2I z6~9yl2zIGyLD&VG96m4Y&EY*7pBs1Rjwme*tn$)Vel%)8$mlz&K?+TWrOs|{4W-TD zRbQMBR|A-C1%AmDLrJi@4Z9`=XT9`<1VmxK%-V)0LSRLZYAFRz@$T-D+82salqtHvQ>caNba$QeJ$3sjs++gFj;f;eUb5tGB zOZinJf+ReaR7rIq?1dWH$mzZ$_|)6=E6nf=--u%27OoaCHvCb6FVP$Fm{H8DEAEBe zhL{nXxz~O>7vdTyPkr3CvbEG(Y@WZH+uHEqbuM8^VZX1J{VeJ5CfobvP%|W^M%k(- zzhpa&#^_e_JdN_}eEVx#rX6U-RxZQ=*cDl~~x)E2%0Ig7z&=LDKj+d`o*sMSO_9%jl zwX+ib3-M!gg}!qUZmhkWk;1T=zuuG1LVns7Gh)xPJ$aT}xU{?J=~c=O#U(qjYHw@; z!Lt_~`%=DVvaS3{LUj_WJm8?&u0N%77Ag(H>#Fth5q1##&0Y=QE#L-iUr)iv^M5+H zRb4wffNKO?Rq|+Tqq$B@nkX8cJu}0?jyYE^mq>Gu8Pd|rt3+-m9R1yhf{*7JX00!h_{8Bhj|W^>AcoHvhSKYwEJ|V z2y?E^f`VURyLsZ^e1pA_r)D~6#WF!N*}4nkbVj;9pc{%U)DZijaGm*YaNobfC%4R( zFJm1I0H{OnMh&ej9*6K)C%Fpr&Qi}}Xl}a$s1DjbjRL~k^Hx!*c-(6zV@nKa4MhGs zPD4N;+WMy;tGM;1bsuMyWy@|k%u-?M^?Pk^o{wupp?eYCTBHR)M(VUai)JMIsHXir zoW*@X8kHD*&l8R4GC4JEe#ub(_#atgejlm1rXcKLyAA*HI1jfc3ntcWHw#zCj^E)^?wi}nP?C&q!b6-Cvet0cgiTzK_-a^mG=^em$VTYGKzWg|> zB(hX@w2*@Z9w}g^W}Cx&ck#b0Kw`*#(iQ)refy8)m;WgF0=>9M#n47L={$rTamT}A zCl*w7XO+~Z3>}yO>Lg)CVYJ#HP@%leU-hKD1%L!lg-6a(g0YT&J^!~m!gj_<^Ol#F z4}e}oaAgGm?TI?nOzJjXjSxe&Ei5!vq8<_dcd>u|rxHud%Fcf5ua;3Tl2ayK{Jwg- z=&_oCi=`MB$;vqd1kn3TOy?6!Qd)^heSbeMjOpE~w;UQhszyH9>iCQzP)nHyFnqgH z&Hr({Ka5?b3+Ka_n57;&1UmdDkZBQ-a@h=1e$NH)~eQ!PMID0a-+oqWS7& zMd)+moP?hQ7gdi0r}jBE@hXo3X#kenU%Au(116xKyXkEKWHj=0x;I3GLj;6D}a7xHFSB^l;JPFrfSd^!YhI`x(`N&FQmm>~El-jg_lrC2Q&h|Nw^c9rlbY+&Vt zAEye&XLp8)?oyG^R@)9V^f!$f2Kh}Cd0z&`=ujL=HrF7jFd0g z1B?30hhb+;VgQOXQSMaY`B-hgUZ|ddEVECNxI8)qB*DPeF7#isw13YLc;R0S&kZ}C z6GTl?f=R!+OFWvB6if0|H1J4_R4fVz(WxbvhG{i?!!YUbueh%rYJn*RF+Qf9%^MLPs{stq6hLt%7AD(N#W1F{s`EX; z1DTXYfLl&dZ#x9arfK)`5i->$wQMqlx@s6om)DbzwZVo( zxq-d6`#M(N7uEkuU96d3!p*G*ui77#(15Wk5uLNtviey1W2%@lov=u5j@Pw;h-dWLINvpvY{8rYlo5&ypj`ubqux~6-ME?F=$Fz;5q z>h_sp3aOP3Wx72SXijEb1*-+nL=)#mDqXR0B*0DwJXFMHJ=02rXJ^z*GvmSuzR-(p3JIKr3q?jQ zz-IJ9YPt-t>*9Aj3>oo2_?;A6Zxu;NyOXcSyFoFpr#JrxsBCCESV0SF83B-xw-|J| za9%Ur!{^*im%h%WC?PKX5FdZaTmH+J-O=^?1qF7&sN47>BM71e&H~zzDJgR9?(XL7 zK#g(4otn?ibRhaQGmx~`Y-Ltv7h0HHxO8s*ckLhd0pc41s1dc7r08`YNde5Syx)iF z=Mz&?H4WpU7L!1#yHmFM-h+~%vDLF_mQ`8G#VX>K2$T@aNa1)|#S}YQr)VV4PaH?3 z+Tr^E^j1M{I!cQjI5Pr|?2Cx7CT?0Mwe;*_PG)&ZJE&-;5V(6>QUBZ0tmD^ohYB#x zNpl|d_0PR?@0u%VR?D(-aN*TR1B4trwI{=zg6i6P=IJ#r+1VjR-pp+*g@i&?2WoyY za9E42kwO0av}-e~(!w=xhZkPa07GqJL}|hS9kLLp-IXvrEGIhz`_{J1=V zqr?*78B5ke%PW(Vi21|q)B-W4SAl=xEsAx+BOqT#GQ&w5Zpr$#kgSmRF*E7Fw~GAt zpDc*8b3!X_iMimPk_p~U#>S{HwL1Ohd*mO2iKeuFdKUR!+L)yH&7ZwhaQ^5_l!u)c zM4)vAT=PVSB#*^pP=u9cL7cjxtut6hLX}b02;iszRRfT;6+Bwuu1GgJ61P&BFtYelpBwA9>wGf`F~Z$$~Wk$r#=$+z{*63lawKmL^C1%&og1 z5&XjzF13Z_6?Wp14SVZz`5|~3kS$NE3$JSx9+;Qt73I%9&=74xy$i(h=YZwBgt_f_ zF-IfH{P)+l9A<)>nULVcrns!eZ6Y^>%$=gE@NquCezK^duAh^KHTfxA)xycyM&1KM zvKg(Xi+1nv_xp`;`odOmf$ER+zUuZxOf+orgrq2=y2V%pikyzLepZ}5Z%JApNDe&V zO1b@C`Fy8Z{qKz*$aNJDS0oh9D_P+h#2_5=Nbk`?;LgrtcETYibUZ+<+fH{v$tAjU2nT3h`s)?68Qm- zb~eJ>FV_(j49&OTxv)0fmcp%fLGEW2`izb%%5U{3%+_5!?4|y$^_cI(wZrwVxjaM1 zED}BwV_NA9!fvI{t^G%G4GoL{60^-tF z7Tg;Y$?6&6&MsEgq1|Hy)C>NDZn-(Xmg+LmD7t7<<|qsBENoR%%9>> zl!X9^iKGJ67;kSI&}XbFV0o(5Mj`Q}@qL=a(h84n9y=e%HQhxpdv5vkoS?ase^R zD5-edUCFeR{iT9v&EJvf+nz}iZ{8C|6i8pI;>RDybB~jGqj)^J&=c!hoL*gtPhl*t z*ssWt(mk@an@SA{!kqJW61#FkcfIjKS+T{1&=n}3fu!_^m8g$Xh1`mnfc6*C)C=Jw zpA{0SfZ8Z+x8^m}+o-cJY3}M0qc- zsBC4dGB%lB;|vy88Gl3An9E7Q!S7MB)oYR7P(jDX4nNPJ<@8AUbKQh|r=LW!cG6>s z65Z(Yg$AGuWneGr;O=AJ@21RHU1Fw2o2wTNmwny_%{9A_Z!X6<4!%&}tSt5P6E|_e z;#q3i*Pq+n10<$$cwtUtSGx10R$~*jn$-Fm~hw7ex{SsNU4}so(^|tJq7>ily50ezR0qFr? zazI7~P)=0~5b!XEN7ye6jmM7UR~-W)_YA8`ox!O>4d?YRKEWmRQvIbICdFXB)1FEL zB`QyrW3RgCPkdd@6B71icAd_;l)A%#I5@;a?*cSx`5w4riExGb`WoH6xMb!&TDi<; z_^8_&N@##&;e3KfIQJ3y>}^JY?svR(*_B&orphmItR>+s@w)ZZG9+69{&a)B{aQz# zsd;wsE*`^vt-F?<$<7AzJGx)pTEZ}iHr3qe2p(JWHf{m)M)#n^Lkbv;r4>(pdzVL4 zNjm#Y5z3M9(pULbs6Q#>B+Z@EUtwBH z;JF{hqsMeTp}p!AnL|Im`aE}j{(!=L!Rm~4^aO6LOEMm3ds$!%?x?6?czuQhmbRAy+yP_N;gC`=HciK!hX*6U7VS>UO$tC|bGw*@D;XMw_rtZ+NldT)$BbwX7m3-zxbI;4M2fM#3nQ{p_r*alGYL z&{K>D7>}9_>Fkl3*^SlNS81JIh*8-ils#!QlcUOp;*nl!nx3`6<}zjG!^P60BGIGate z5H>Tz_w1fGR~ZWL(a_PKELOdX=rq_LaVt#2K$CeS)(oa5mcTg0e`qedNL+N6`2gz$ zMvw02){g4CI-PmhwR&WFFT+sa*{qtTy=(4KaA9jPjF6gN ztO4XkXtyv{$9SK|v#ME=I9e=XKxG_ICK;-rCvvks@Kp%B+^+od-AnylBv3=VFC_xU z(VxXv&%2A2aaG7QurvI5QK%l^FhigN9K)(vf%HRX&D+e+3l}j(x9O9j9BTP9wbKLS z&x$hYrWUfn01f|8tq^?=n4uoeX(E|a>XxO5ka~<_Ey{q9#yNj)wVt?KIypNlQ+JQI zW-ch2XmL<`TTMbbWvpIwRm-hff$IFU2s3+%Zhw^2`t*E5r*6HX zUA43!uFwuaa%HW*QtY!N+jm9iy#HsIMk$ew>s%z&eb@X}moqM*bMShvo9Wsnh*D+8 z6v+~HaowVQmI6)_ z^yoA0Si~h&>N0IVxU{){ojm6Bw)pDwRR4uvkFKvZQdHTMrc1XmDXmrDz0yd;-3f>x zc3$=!FKvgg9k(AyIv|AT?+dEFThk{R&|B2OlAAlp*O}haV>@2k31ac5pI=-lhS@C1!)6WmGBK;@jpdP4) zl?Qgb`1wwvGch4c33CY`?4?KW1?MBTFA?!0GLY_3Q@HRE&DC?AO47E^pT@qpde!~G z$RKt<`)yR$B?f7pP{oZm^-Huxy#wrRFxKc)zXGb_-&() z1+^J20Cf;dCm#EdoxEHTm)RYYj9e#2@+b8CO7q@y&|+jlNv~L>l8Xoh{1xI0A1)Oe zX7X6719=(fqO{vpj%^qV-^CzwB1}$x8NW9z%XbLt)3B^9Oo+hTz0*}aY^nmeiz|0IDS01BergN zwCnz7Dni~A37J!c-$oi|{e4C(!MHt5na@0smDlm}??wfp`j>EB)1Ss==nx@$L|1NE zbQ{AJS5-C(Rp#7fP7M@e;5E|rHKDwYT=%TT^%{byey)T_h|iqc7aSGqzt1)2#$6n1 zsClP@PcNGMbuhO4+pcmfo8ACG@bvy+l+mm(ebgC<-#Fg+Pf}O+isxmt^p|`C#?{L% zbzB4Itqh>&)KpVCi-x+|MTsuu&{(FeY)q0=M2*q>Nr8GjfFyWKS$KIeggoVvjrn^@ z5ODB~*)UfEJ=2R|;-w+G+ci!3wFeK=(sQ(GWPa&qA95AnLghm9;WV9~>@DY}j+>ME zoPBjlGfGh@DXAGyC~$s8BKB-n3$e4Ux-Ai%Dri^|-eio}BKo3q{00`hJ7ZB=gQA=L zsrnYoj7T9g`dg9K9}08_KU<8&LhKQVp|9Myu4 zM*POxrcQYBB$zhn?FbL3H@B%;N-82(a=bQE%zat5Hv+mAWS{^}GKLp#D9l zUm|?Axy+-`1)-QgPj%XA)khBR(2H!RZC0{z=rD37aTYMn}*_ACTp~;oKIZRq90UgaBoC2v4q6mzc z5A>BMHz=YU%3nSM>PL46VDH45KP8C7j>3hxwCGP`M~5VPmkwTB@ISAJs_gl?TTFK5 z$Df=*!ZMF>y-tvbs@IxQBZ6njJs2V@MnuacUJI3e)(Iq+wUo~T;RvQsMW#fFIFCr=I*Dt-$?SMd&x z{I)dCW%k?gIl1aHp2zU0#Hv_8Q-a8adsxG)ThJ*KY}YFxghupFdIxcH#`{G{TP2_s z>r#1_$jV&bM{Xi*qouK@H*+JQp4X0&*Van&HY-7EZ^IGwXmPGJq{wvUy-q6@sS(d@%qkn4r+-ucEy{V_n>{AgT$@=`rlQKc`Br5%i@!R1i8_6e#twn_T2^x!D>;gH;+NZ(vT1S`nRiFv~@ zHEk(8S+2F>FybTf4Pk~toLQWavNl5(0M>g2M)iB_==nW58Ao%y#^&us$BCw#nuHZCB31%9O7EsJrNSRvfI8gaB^sV{ezco8`^!StLHF{E{H>OkiMuW zT|bQhH7hav%)m8Mv|PIOma;!!Wzk>qXwP;qb@Yh#QO(^*h#YT3_Qvm2Co(^0j`pxi zi_w)G>d*0&-|vWblX+TS_DH`e@0B+}u%@41F`(H-S=dppeHghtymP!I^wx62hCadA zJu=x}kl1|bbBV_lmpdllD#~?xJMAgKyOrgbM|8pJXQ>NThG-v)O|b~!(;&R*UNlxQ z>>bs=g{I14ZEnO)E{k8Ujs2aNQ`2*Hqi;IEkKWucvgkX0==$Lsy(ckxy|q@&waK!N zIipxyO@`05p;gIxH3H;&9!7Yw+(`KJVvrbbcka7BF?4Gt*%^hfthRWayU2VA5HtUb z7;nqg!!{s$YcMO|SZpHeOU2$4Cu$T9FtB4)AJdX7;i$!N7vLD#1NRdXBXF)@Krl7 z{x=x^ZhA#ls5I6aJS>uUYeJ^ z3sW)}Z@C}4P%Wc>l4m)Y)UOa`dbsgbw&4&@NNV|~%$}KgX}{sg8NRILGCF;ytEe7# z#Jg5MuZD}4qeVtI<@ST=aO|>^_6W@rW8$M$#>n6-%y$hVW@e}c@h?Jm;`UuJ_BX3h zjF|L?pVJy|iHu>tDtXIJFWBCbGAKxjPnV2g59fH4= zx@m`gkNpr-s*-3GvpqG#!rSWmACkHEf|S$qYoh&Jh@(Q}tQ> z3mlMt5IJb&oICxUTCzVm?1gX)9lD9?Uq7|Cf1NpV5HPeu{<(0~+1;y-FKGI$+09tE z@a+&7llz*2psHaXzr}OEl^=D@9n~wpajKx8r0X8L)&RNy$Xsj)g3n(J8nM|fP&n(> zv-iTgk?1*&)C$HNKT08C;gDY@H^O8H!CqOJ7rChWBE3CRj|41? z7NPi82-El&nz|EC=Ziy|DKxE@0x(!S6}jDYGdH)zkLnN?G=w9%1HVrM-WptDBB&Cu z&{AQ^*Pe9F%ku#SL(kQPh5TRTT%`&lb!p0vjwe@(=O`SOX>Gl5oHSk4 z0(L)}VD~so<&ZD&h{-j8rzVeFRqiAa{ya1j(#3qg{;3p4-`IGYTOHyR*$e%$Vp?oj zj2*{DSawi|wP>cMQJ7WjiRYCSTg zBA|WWzf~%ETM0L&6({}SG+Y^tE9C$Ik7C#}%s^Sjdbu2od*rn#VFu%>SiPJZLUo7e zNG)lSdMeK#daXj`a5%vFc<8M|Os-qz(HFrPJ|-?-fdOtQy?vumHty#lt~Ux>*J=qi@<~nA&Xs$ zq{mJ^=Qs_s+yuVAqlZ8yeaBcr$ue+^@ zoCqYj zw+-0ej$HN}&oYbOtrK$Ct-l6No-UVlDdnln7$X|k;>-!6_(Jadq; zyC}GAQHZKe0cWLk96v5~A)9-^4{K$TUb58^4i@U>7Tb{)?8{VNPWvdz8t5`y5gf74 z;|qHp^NC8HpMP;U>l(_uQmP0VU<@jK>bm~+i<|inkKmeP{bp-L| z$n`$y`I)RSdCD^_x9=-t{JEjEsq3eEOUC2EX-WEI?e|u>FEJRK@;Q#Z6WuL)DFcxw zYqM$G=ods_Jv?EOhD1Fqr-NAmW#tbcSqYR?%g9N*m zFeU??k}<)0)a22HHr<6a0DPi~ic;)E0N^i~BB4TghYU`$xEO7QDenbjWZ< zrk-?4v!{N<*B>r2y+Mw!PGgNIZ*O0MBdpry#FASqtyQFy`a)UoX?rGpwqi*WlL=GT2AYnwh=+*0$xgTyV@r@8l{XLR!NaokgaZ>gmw}QEn=|asJ^iRW&Fn zvF=2rSWd)IB{l}#LR)XH39;R^n_uP9I-WLezm!UTXd7JzN51(?u~e`IMHO#P&`&A$ z_R8Ykpr8R%-cSU3HD{7N7mdqb{PhW7jJ>PXhP;p_x?(fzYzB6);%r0JxCU-{L>|pN zc9=G#YH?xA9pO8aMpu_iS&Q$qLp=3(=Q9ijpRLr9EvdwvJVQQ9Wr#$3U+o8qu7tzI zm-jf_##?Du{$MPZpZ}KJIUg@(uT&L!difcdb}8?qd&J1ja+^4n^e-vqM?KOYjI#Nf zR$Y?jn6GggHr_&k=Bk;lf1_o5=6p*2v_q!Ful?t8;?KfFXMKE#vX-3W1qg~$n9X|} z>U?T-bw-3KmeappfC=qwyPP|KO#4Ifr4DF4idj=5{h7DU-m?6p`1XP?tD4)p8Rm~f zp5(TAE1{Ki$Va8H^t*G=(v8^Qs_xaW2>wB$=_pN7qD;{92+rl ztHA8U#C*VIE7Qz_&4)l|U#4W**=b1YsW;DG2o}j__iHDv;rg&@yN~%!0Nw^MjJC8u zMZX7u@+J3_@!oBBw{d%4(lrPP5stowH}3fec>M%0JCn~#A@YAl1(x6q0!rDkq^feI z)V!%f18z={Kt{jns9AA1o${L)c@>bwa1%leEfc~k_EaYr;D>rlbo=b31lDKnn!JEk zV1@S`v>F%_Ubbwvu}U)fl(x8Q+|U-#kAyWI7^t3C;@?(*e}`QEEdlg^VBIdf(=LLt zG%dy`brrF&u%MJlQs${mBd^Y5ZDCPKPNJJ3wUih95PAuWn4o~&CL8!l^cJ6NIrE)I zMtrMjjhz^*I&7uFQ<-R`t z+L*C5W@L8N2%p^Ba$Qf{bX~Jk4+TTf8qoV`HSeYBlb*a=nTOIXoQnl|gL> z0F$X}lL?N*e4lUMG4VE!D*NAANOIn&`2*lDg}jQRg-D%5Aen{(gKQ<`C^DZnK~X}& z2h}p9GR(LnwdrXwy5}NGqSz5&(o1yw95Qez=qNI)JDQAt2pVg^f8OdDu)TRdY?6}M zc5o9b#%tOGQ(ncS_PyWg>iL4i`>PtOS)HT^#pmws5AiYb*2+cYBYYhY!mFREcabCf zZ%^qmVz6u>(!5(!E40+gxWE4l(sV;idh8`7sjSNX;^i+AMvHb%skDEh>{~LQ2$yHE zuX~Q!GCk?TKubGtVH%1V2*Bkun)t+qelf|_WNF846> z{oC{aQckp-IcnnK#vpPBRq6uw74Z5f9XxK zap$XDUUw4H$tGon3Qt|JyHX>UN`49n@~1$f zO;z7tb&(j6!}=nI)-Zzb{)_3`ql)EX#|L5g&Ro_F*RHCMaT2!;m)+jp-RMe~RXkOY zpXz^>da_5CMu@C9?ToK))x!pvfYwV$|7%c5OS1n{nNpq(<$T{lH_@CIwTR>Vgn_6z z=w*{X7LN#VI(fd&MvP4Iosgmd0M9AE4s{;(L1wk0OZ+k)5h_DRyb2z@BARAo?_>fg zTe=_bI_7JzGG58I6CO9W{nkUIRoYU94~*mM+PUs;*xzVQp_bl0F3)?Pk}gv?1;xDl z=(0Am;&O^fh&x}?#%aE`%)auMmP>VsK#v{mDF#RqKa(W)%nM#W2sYI=}7KS*ZJhizOKv_ z;kj*9mbS7oJ3!Kx<&JcZGyV4mvl8WQA@sGwKnC-ih*@Pm1*Mgl*6rLgFQLpQdI=NP2at z*GI`I(ScQdzL~>?O@AV5LOmzp#*t??bYn~9-jX7BknkNTy*emeF0Rm2`p+K_wfmVj z5+QxcJ;X~`(9L{kM&+&DT+GLZ#3}zehAdN~Z=8h0fhb}c&55nl^X_W)5Ak#y^tPmR zueq`u_xmyylFtuO-T$cYZ;Yi0Y#bSi*Y&9FG5=>vGK%h)+1YO-QDJQ*3XQr<4mdlrj)hR0;t7%33T>hrz-ulQui{AqA)a2Rutuw-cnj(3Qo)bN)tC z3C8U5PQnGq2(QrW&m-gI4)UGo8lOTbuWWJXZrfi&cBrSTzqQ?@)4IJIZxU!_ch{Cms9F+r zQy2HjC{@lR?jU%-5Q^4keuW9E4!cH`54ZzX+VsXI8YE5d4C@}UCrR+p9Ahq$42*t5 zr6s_S@^xSa?oXl5Su3weKZ#fnkfpht!i4|4F37wLYN#=l8g<@`W7xo+$j6a2Mb~H@ zNIP=oYackb?zO&!X=-GF+ghww<^D!T_YuKpGK>Rh#;b3VtuDIQhrtuZAwbT!`1nhj z_6f7|Ys{ZIl0!3>ubyE2-(hu#%kCNc)_T3ZFJB|Py$}QO4;25yc<+>NxH>uJcLR67 zmIXb!K0%7K@g4oEc0gg)|FA#7pn2`m@3Db(Y)8w>j@Hf%ofGqum{}dSZPj^gV~xI5 zd6ddB_K)s|6hw~Rnr6Bnz`XU%I!dtmDV^IT!R52m?3R{>m%G{)J^2iJzbp#tQY=B6 zKjl=d{$Po_`spa1)$Zemt394Ym!$M~FY#4BJRF?m4>Xx!I1?#rc+dI}88$SgXAb(f zpALKM93ZV1q15)EI7qxmX3nQT;(O704z_9v8;ot}2^Yh&Pl7cW zKcr0txByK#qTVRNK6S@gy8LmaAO8$lwe{NnA4eOgu;os-7L&@02mEz#iG*QdF|d3?nNap#!I5i!$*CVSq>>D6ADSDx z$VG)C=h?(9s`-fZuRm2rdcHSNOr(x%v77?K!BJy_KIuC-nH_H~Je68;&EW5Snc6$S z{f!w_$@!4+-R`j=0xkM@h=tY0y&PcM=y?_+`=GGikB6woBq$i^ThJ1f7BR9C3){Ytu8-$4<0?j(0SZ&<;rf$b|F&SQ{|phJ4?^)7x$rsC#$rJ#e#j&Gca#GZpm%{wwnXkg4M*--IC4#HH5CaBTP7MnkHDvw2>*Sa{hye5fKS%qlJvF;9_>e+dMonVxqKt^{msUoZQ zb|t(A@{WwS&K}9P47bThlo)Te7UlM`pzA;0CH#p-9XI_WI!)uAnCQGL?#X$_RUM`u zG{DJvFkJbTC%h-%xl#ynVt#Dm)G1XL@#e_2^-j z4nuY1mQt=XwBY;-TjF-luE)lzGnDV4?@Yv@VVmr_5w5_lD?5sAYj#EBzTc9c{!=+Ucr@wEM>A(`h zQ1cO$7KYn+QV=0TJ^l5KEhfOgk=4)ZYdv|}qTdA0GDJnCs@?MEj$mBMbU^E9dzRfs zjsxwd&Ub`FfYu|LDjMcklIeDAmAgyERuZ%sO<4(pFs=4GC4wTln1y9eHw~5)!w-Jx zUW+oG)-$-}1P?YQ?3U>XL%;P<95}g>ql42K+%J$?xInKw!ukbmA z1fC?;)u@d?`|jAY%k4b@t|=UzzcxvNA8vr6vKJ9-Re8uc!QCsr1ecdbZd}e8&Q7w7 z>&mLj28qkn0V5`bxIr;q6-q(*g_!N0bgRYdhCL?g{92Utps&1lj&rp3*=64Qk@nbz zM<9(TeNtzof`P(knMGTTsB6n;<<6w%w$xzi&S(>h^nAk9(iU$fvKB>j_&~F#J?qMYuS6K}WF?k4|} z@W8TwJtZhqy7Kc#%L2h>+>VK)f^+xjz@c|jCF{z_>>!oQ>CZ)jv2?$+egiTML_*Y( zgEwNCg`B*xrMFsBwzDa>j37nB();+oK?lu@hfj#8Trb#^;j`c&TQSMkNkLwm)IW&L zkEa)JKiSVqUZt_FV)MqiHnTF4jfPH>th0~RBeq{QzKW=Bx<_tFSnKWSwazuRrB{e< z5%#_&b%QgjL_{#v@3SEAq#{TjV(5>o*vquOf%~T4F>Sl-w$01ATO1EkeY!=0nRoiM zS8LwnT}>nB368nvYEV}xQdQK{7}N_r&d`~FN?N8*56Ms4j)-%bt-%&QNELIfs7d>2 zm!65o8TyRx6$Du(x=04&&7kO1zATG#Q~c+Fd;8U~w@Ej!qn1}>zs{xJmaR2P{-EqK z-kkgnZ!_4wHstmC=K8C^Ei>lI%$w%Cl!?|d!&7oFy9z?1Nw%x2f>cXmHjY;+;acC$ z=fRz=U|14~^zeM83H>{shU93e<2)gKcBNJxiB8MC|4gYj`97s`jpK2wvf4X!oaye1 zSgt`$-mj;0fL7twJ z&M$jp#GsqY*z&BU?Mic>`?Nu zE8GHVvQ}}wVz5%@guM~Pn>QHjV6BKbh$G;uGm^`ud}3yvw9izOG(g+Y`8e|2S{kFE zXc8Gcmz=CCe1{_F34dZgjFt*g^J4fY2DgZ4AqIEC=NLJZ@52kT$=tdUGfyO!4A#3W7eYIr(3Vk-tzHafTnq$}YXU|(B9B2c47nAlMC=)+6 zHO)F@GO&zEBhKS=P*lL%{0^d$Z`)E@ikngtTL=YjE+Tvf{`ph)D*_kbJ0xH(C;X@` zq8xuq$RjDBLf2TpsFpQQ#A~#)D-YEc<_qOhwDm~cn|0Kw`ByrDgI?-1vG@iwj&%>8 zqBK7@uRV?gwW%byQc5jQ1m5_a`pf%n>3z)5MNUZ;W@P;hFRSME>0kQ+Xs94qc)+{) z)LLwGqy#p)m&Pa{Kk%fUA0=C0>j1Eqs$cdqv@ld^u*t7_W2yXTikMZ3VLG4&DjeME z3E`hawy8uAi(gFul$`aC2y?sY@`oY#F=Vj( zrALB--unz)Ma_qMSyQhSDjt--2$o#~P!b~$khcE*{;~`Czq%7>>8Pbb$$yX6sN`0g zpeS@2OVHoIAy2M-vj4)aD7BvIpTwj=QK^9(8k4#jiuIILrPO`9%%Gpx0HSN%BisJT zygJq%eG;cXSk7m3=MCCZ@386p^8i@666g0c*<6dl5+0BsUr+ld$K`+Ci166h7~qZk z{Y$O6n1=eYVyt6k>7~V+4Yx;exzdcD3}v!&WrH>{F5vYgyb@&*eltp@<|%AdJahzr zX@Khf^cMt4S1v!fFjVp_o`)?4x=Z(3P#IpPOxo5E$5wN6Y)MP(^} zY3}6Y^!JJ02|f(yfWA}uL`O40MbHkj@1>TXm{Cue9?72TqYbOsCI$Y4eBa3GLdpxg zS6PSza5uoFOZw><{f8mkcwm&^zDf>kpLS@{EG}9sC3Z*y!tsLtGF0n>t`6q>{QQKP zYlnu1O~$fB;$4LQzIRsU;!?BSH*UhDX=Q)6T=lxNQW|V!Kc%*;?o!9qgrB-BGv+z1 z10n>V$HGkWv#tnf)N3OJL)c7*=jz!W?i-NVfUcHB(c)h}>_40gj~Q2{luxttP%n3X zp+gN>&cWWE7E^hN2;v6H0w|TiIiAS#%iP+^+uWtaL!|(VCO)Zj zR2hV0rSoXvi2@<2a1^o7$-z~5yD${;;a@HQkud0+ni~{yw!DU_q=xY&<~!VQ6gcvG zs<^jQ7`ZWVcnpMdu>{fY*4-3E@6v|wzlCPWSvoVTxv>Kp5g8CY!-+hZ*}1tXOLq|k z`Ix=d`00GlzpYjQA&pa1R4luACvB0mFxfeiJh-W}o$l@umF^9C;5FslF2v@-aU%%fC=LGG&B?+6 z^rk?PAbI;+&NCHxaq0NV3BrOikKoN`Zj#T=gnC|a5;s4z%&l!I173hE^S0uI$ia=c zx?nxN;M$pK6-+_x(6Gb<7p}N?E!yqv#HBGQUm&_ehV1Q0R+$XhI+f`e3m6-J7R`?G zgG1G%Ua2xg1q8hYws0VxF8-y41dtC$xwf`te7o4`8S1>#e{Y#KzP;1`WX| zJ6Lp^=Cn$wNa+FE8Do(sRT^QAVMg5Y4o${eZxfqF*y4epSt*Xe1 zD&?g^)d|TpwXWJzA(IIS=ii%Lw~pZ52?YnLKoMfVsPxVt5qDf?H{P1~!NiPBYshZ0 z9_h)3BloBP94{=LZ|zFQ zVHx+99vAZ*+jL(VE7fQ1O>|uIJ>N$D(}`}qG5*&tL3#PnSb_lmq#`+$X_bPRS1ez{ zf<}{ldjYgNZ}l`9OGsRt>i1htHMk#%1j%)mEN*z28GCk3e#WD>AzDe@4mw%GCN7O% z7_v1jmo+)szCBRSUnf1A@7oD6lez#6ZtNcGd)9eqWC>c>p+kmYnp08K=zw~gj{4M} z%oil5OBM#Nn)7W#>yvSqdd9k?q+XDyyKF}5!{h;Hsc9qc5iV}@sG<2fz3psdvC)9q zyx>qwa0c37nk&_lKhXVkshfJmncaqM~QUrHaY>+^Sx0+R?p_|rCe7I)2(#qgvtFU)7EB^ z*XO4xjxJ$)9e-E|Pllj*Jo5(EmQ}@WHV-3be{K#`^rme-5qPP1+hNR+dOcy25<-LIiicM>?f(7k_jTa{sZYli+5{W4Y=9PSfq6Pg4ojb`3ITRme^+ z7rQsZ+#=xDhCigwcEQ;@$mHUNZahYQ1^j8D%~QweV+1Wfh9*jCL-QVVBgXD)ilakDMMmhQBGO`65T+wItAVzc|nYrkp*$5|Y*#4?&J}?i_nT zvCeNecNx;sxkIN*Kd`piqDn2M8J*^X`gFOH!PB+dmvHlI3U*;~`C(hhvWPBjc3%Qg zZBF_+HF+aK*Qe8HZddc|t#OzlWLt&`u5|K#3l67obmDyUffaKmT#WVj)#8>iQ@hxE zJ|b&s68h;kYqPB8iGCi^6Wtpv$a$MlvHAH{bF~71mhItS9;bG7kmobxFZD{}cvGcc z;P;l8Pq;j+axFghFX-HYnSN>^^Jek!Ztb+SG>EPZr|(puPq)H z+=z=U8_?w*yn0b>kJ*|N)RuI5t+%jxm&e_nLW1VMuJH6qhfQz%WWSj2Co)R$LedhA!vA}6rpJ#U1 z);mfr1jC^J58|bCNu>P55$`1fQRNw{TkocUOPE6YW$}uEaS9fSk+W&32iz+Rx zamOAw*ecTxGrNJQk!|JRk6~X$k2nx*wMIoiJVhrS6CFu&BK32;ap6~<1=G<+#*`87 zr-s7vZ(Vl-U-Q;SMXkwv#mv1n?5Ik%`awTufn}j7_@4uo)5lg zqmca^t;CYM$Kg0@$MaZmpyYyeY=e2*{$WYM=HuQg|rR&uI#Oa`5T!xvsOJ!}oxMuqr>i!#^L&j8x zTgz0EdfiS9Mh0tj_)DUe!Ql#e1|@8Sjay{A-c!oP_o#2G!}2Lw!iDn+9YjBSmba4@ z=KbIEcE!%rc16$sM%HMx+WJnxG{Dj}FJobLFe z1~zJ!lHtS9Z)acVB)3|NW}1 zQNM1~m?FyDF9}uDCLH#n*k9BT-84HrUEX1iC@RA1i)E9A+eW<@e5)ckAn}Elw?+-= z#rgw!OHLy&#Nv&qj7ri=SfP1Rw3cTtoXMCm{vqj=N_(N@)I&aC@`dA7X^t8CmLM&l zp-_Z4hf-A|mcb-JrE^#L{fQnd{^S_-ZB}5Hl<_?$LDf90_DZLD{0zopJ2MF)Y2f4S zHyxR&sGJUzZO;Cqhu^y?W6T_aJ2Z|JfL<^qzdD6oS1_aAdTGF^y4Qp z$?_;q7YiNk`>_4sR!7qF#}bQSmZKZibE7i{czosnL6g>`4j?%!yWrt zj!-ABz!6rO$LI1lSGXV3!XM2pH+vth24(7#;BxzMrgiSBJ_rU`YI6cz6tt`GCvSH&E= zX1|KP?=@2`YlsL=ugG5woL8jnPd?ar`o0h}Q&ebX1^kbaEQ3SbT27R};7Kl1eJcHHoW-`luBteR&w??8|V&&BNzj2dS3NhST~< z`-mJ*_Y{j@r!KiOWum9<>KifC{O7?L*S#AFSiVLdQC#ZQS%beQ;AsbVV0PRbp*d-f z{r)wSaGEH!`m78?@2HG4iAMM zfHShba;V3olBaZ|4!NA~OW>!|j11Zk-k^Ow^UX<xxNvM>3)wlV2)so#PAB;(0e#+Tq3rZK&zw0A`ckAi;3-~sUq0991XV1I_1wwC?aZENWczi{RfGJZCjPp4vY zwD3l?q1$gij$8~X4utZ6ucNXo!Rg$Z|$RhJ)%dVKBNTEVKU4vi2GN@ zOsov$JTK^|*BMiObc7O>L_DK#zG$0j_b`pcwm)ZRbXm9X&Roe*{6f{2zxd~4JmPZT zTu{jQ7y8E4wX7<%96+Bq{)28^`05rbWA{;wuR_)qPeNRwa#K2*3=fu;>>g%3wnPEN zwoq-3K9t1LIXBm!yP&43YRHVs;d1f`XsDXE6%Y2e0YW^w0lU8l18r?a#;2pEb6F_W zQcZxnQq;|;z^8RlI$LCe?BfNI!Q7wJe_=Re5i5C?4f|=LDYXZ?ethfd?OobibfBW~ zj4+A8nM~tBCmcy~?7gNCbEMOk7B_OTTaxA?fdIS(aQi3d ze+MeVgkU67URL7fi3;zG<(LJ@(S3ERUlHM|WvKUxEt&?#Q|I{-25=n`fb;$fTfX<> z!*!^t#ilQ0(kZM*va#49R>sFEKR2t2|GA^?p1w2&up#u^2W!UNWZ@aia54 z`a4A%0KUARUf?Zb==z;r9$e|`v1f?szwMfUF}g4)&=v)E{vbqQ3Hocua533dt)fpAKP&y;Pk zz$A+U*lP8NNHETirq*;IJ4sxeu5ndTZQrgK*w&;kKCPXC`2S^g6^;EwAuKE`1kU`i zM!IqH4W3w`fS?^Gy{>BbaDSrT2@n$CoZ{fq%4E;Apm1yhWA-N~pB+XvCpWALvju

bs2^D%OgJ(TC(w%Qm-8(YKIZD+^{d`+*n6=3~wOHFyHu1fDg z5hI5)SNrsL<$&GvTUZ#*B&k&7mctxKLaQ*2Wzd)^G z)G;5~vip*0_|ZOg@OnjD)FIiipe0#s)Rtwj*Z`FsT;;32<1s(#++hV7Y6>k2$Mxcrl;Aw&!_QtpjMoReSGy>RH{MkyPe$C2PXxnp zD&roD#ZBiOI@Qh-fVP^yBV!`t=?q|6oqdqi)joTV&gpKLRvCA!A->(>z+Upi)nQ66 z$Ntew zq4LSmf2N^cA7YU0x-;upU1gqpb0G+zgbYreiZwH0ci@`#bVFpIc!1 z$FYRY!u$M(*4xvK@UO9799sc+z04e8uGPC6^IE;-9*jyfZ$zEW9h8{9)Hm~NDYKP{ zA)R_gE~NU=$Q90%(FwHi&4&uN*z*I{rs2UkEI2;=^CU_eim4n|MoQM=1hYHDbXsOl z-qCNAecfwK70I zd@wn6QySGUY0#^AukxsbL8u)>cKeY39&mE4BB%^JmkvEy{@}_E?&~vnopb06ZS$z4 z_jct>Ht4T2$CRAx?K#3(%%D)g4Fb*XD$zWIi_|61D8aQqM zOuqpFC)H6IKYZcJao1Jw6&C1$aRsQ38#J(+gecFVix!snp)VouNaTK&vpf8(t$BAqFL=$Y#UVFnWhJ%m zG1yPz=E2aT%4;+CK27-f5)TRSCk_-4_u%CIoRBDd?SHpXlyiD*V`|1W%KuQrc6*o; z2Wb|guXgv@y2nQlxt;s)a7Bx{@`REb-hspT1a0W{W-SN%OCQbF3AqDybK~n7r^n#L zZ>V*wb!CQt>$4w-oAv7b3+xR5>U{3b1enGR&vp+yO!RL%-@Zbq_sNROEmTJ^vj{b@ zNK7nMjswMsXyi95Y2@=%b!uqJwpwLZAI6l%kt-=>QcE*A2-z8-Y0u&$xO#cFtyc7# z1bOMsu*5Tsa1T84*Ufs|c-fd=uWvX5wYe3GC7CEFd{q+PG$kY@oRv+^$au$HP ztB~ys4P^mCAy6C?RILm~lxKMJ-gzX@gYCvK%^N})u(%SxPvDspn1`Ibk%a29cF(|l zHt}uv$jX<a z+lI7wyh;AW4hb$^SRXP&`o_AVYJbk~ar;|hrT(b1M2BO#K3(1j{^tF_8E`$<2WHc0 zhs5)4Ezd>}Ko=wq3ze_!x(fy2ybmzybmzwQrnyA~T3YIJ!Q^od3oQ#_W15qBuAwj5 zYG9Uoo?~ZoQ3zs0ZNzg4tGG}S1J|L9=l=KU5{R_);9BjrpKDYIR88jUq1Pq;H^srh9AYQ^#KiX8X5P@0K6A1w z4mR7dRppRjptJ5~$v{1L<9*u2vY<(1`$fsEK&wJm?ek;ccG|rUXvqlY>p|`fKT$3V zFO0+CQahnL*6HFWZxdC}VaFE3XYUS~;2`ESg^CDQRBnMaonr?(LK|C+U47Kev+bvL zJ-WRR|H>anH$jEzxr|IE%vVLNm@?nEcRk8@3(t(Z9JTpQRnl}@Vzsj6GG`Ksi@Yjx zwjJ4QcSC2YHm~n-cm!J;C|;%jczEi9hJXUV0&sp{OW4 zb+fdeo|p5%d`Srn&79?sj-N%6g7UOuWaia!D!bhvl6AwwiuT=v3HC}NN@C&x9ZTE3 ze2`}C8jW>}E6fBI9YimR7ykxA*YqrWsFchJi@t1!V3XH0GSysjmmY+l8kR-lanW|! zG=D3>+vN3*60G~5f{zBF9wwZ z5}oICHCHe2wAbp;-caT8cz=1Y2u?p3lG11@iJ28>-evsyO6?8#>3A~VZ}QflN3Hm? z-7}pS{6T|!Z|uyELmy1bw-#)?a`w`pO%Rva?KqJKQ#TUq4RD`bFPT`6oaJ>JBZv6P zNCxKOuBnObgQ8l$UmvxkB;t{u+{lboaD`Wcz_Z5{3}44%Kae(eI)f#@4BUqww@4UW z?83ZV{j`rcxRxF|K{2G!kIu%^zKv)9g_7p0T))TiQx;u(L|E2Nyf^*%)0-RtBHZU)SomSM? zgx$WU3ORCo{u*PMCH>R|7*CCQgtXY0z%oZTVP+&%pf>&L&3FF#=YT@^8YydLr+1EH z7X*<$^mlH1YtqaTkB+6+`Ntr2m&E{uBGDDwkIwk2uUmV(8J%2K_N#k*yRhYPmu16MFInqKMBH5mnKv4 zL#=8^eN@tXk);UtwD0CX-!p3q%&IIQRQCuUveyN?ff_iaCi;!~f**hn6O)s=7bmHS z_4Imk^>R-QEu2z`3f;9FI`z@eqV5t}p6)Dj{fLRhDuF`IoInE8bmu#?DA=y9uIjlO zu;c!;$qX>LXy(BLJZ`pg#_`bf-cKG*M~ibkB%F5`JXJ_OVUes?=i>wr0=c7Dz~-UF@F2LFGSo2i`Kdq21m!!uHx4MzwqHZiQQ{-R}hJ zmK?k6U{x7)T0sqlpnPUs6tx!>NpEW?)PQoVMP&t364b^2n9)3D22_7n7rvrm$n5W2 z!qZc(JtWN~y}C5x25GMP-wJwcXlNWQt~FbMJpYp@;K#T%T~Ri*Eup(WByPJ_`|t*E<-Q;K?V2u5gR zi<*18gp5v*zN5bv+(VWX5f)AwC@zHqlDq!B#NxK+^BqC^@``B6cUXerD6fsRmYB`N=26E<1Hp9^$^IYz= zN2NgXMqmgj=pukR^3T<0_lc}0va2h_V&A_}s5kTpuIxaXpoJ#vm~csRjB^GaQ%z*Y z+)2O(`g?!?s%dv+1iSayF+#Zu?_z|bG4Hg>n;Y)b?~YR@s#?@J$s1L` zvW9gfew2HWjl0o|Ksfb)0od8r5>*D+acEPoCTX;4f2OC)SzB9cg^LOAq2c38^YcR~ zC@3Hw<-1bbf1A+8G=IkBiUg!YSa?2(i{6pX*`XW@m#`HmgZK`R-ioq8Q%_?kTue)n zs_!AA@W#esPOFaM5)_8N#f+_nSX+)pt1DmDURF;O!Kzv#N$7Kny&t( zT6N=K=VQ*58E#B-Lgsjp`PR-MqnGK7$`%;_M#^51H*6o)_{(QTGbhz z1|h={79HTRG_xrAhek$Bf%6;e*igIBzA$=@+7e1nm#pQg?K8hrLoxKu*nrHKB_rb%i5z$)XDt?#&58@t6M2 zdC&0w<~-K)jfK|R&>A!XOA_i~!h*L_z-^%Wv{m>;?THHcO}1D85q43|q-4fGiy|om zYGZk-Q;oO0+zAi3)88lRie|E~4UH(*@J#xvti-3zqZqt$2)-jIJFA#`8kp}bQbV;A zc`SWMI}8H!P*CK`m}E94TGU4Bt4XKcjFM0Bi^PP!TnneFr+$+eu8RR-_L5QqwmABX zt_Fvz;SHs|q=#`3do4Q!)%A=;`nIn<1ABgTWPc~M4{at}4E05`Pj|ADxx(hBWttCp z(zeiG>ke9v)!@fMn?LESL8%8WB=U@AeK8pdiBBjNt!5ck^Q(xzR&6tRtBExAWvT$gi5a^ z$oMO(;scX4SLQv^gL!|BBdo%Dw5~PSA@YZ1ten#Qw3t^F*z0 zqRgD2E;Xba%;xp<5&muUyLZ@q^$r1NgJ7*c_9(q8eOoh;dRwumYQNAKQ>3gL5)t8E zchvfGKh^qGnqr(DCO>a&|8AEC-(wnHdG>fO--KOGM=g3hOZNyXld_dP$awG^t1N3Z z!8^1%)UW4Rvgg;Knx}KO54e+`&Flw`kG*EEt2_yg|HE@!uFX^tQ{$+;FrKH!U>*dq z$18luB_(W)_=dFegChf-WccHN#PgGX^`q=vU|h7q%*gQX6_@KZo3{z?Wu~!?Pem*! zVAhY<)+^83fi9AG$|`HgwfgS^%2o0V?x zS3R1&!L3{7ifq?g9-?nG95Vh#d9aQ+%J0vkyyKyYF{6AXH*zw0&I4r`MtFO)9cxek z29^*^T*E=*f!gbdS_G*5C=wCNj9QZEG$og{Dsf&fSClI9L6fTljX|$(WZPG@2D_Z! z1Jj^7qr`e581K?-ebi+x^0p&_+ACrc4J{(6MSFnb{nuLsQbHwGmO&d|UWI!IYyKEphUYq#l1myuSVZFqO> z5&BaiW7-^_wzM`mI?_&mDqrfb15l{Yl`UmRWNqSx_L5dK-GBtNWtt<`6s|PH$C#gH zna-7o7@{L=LHTtIU5)8h1^taXYZQbjF7U~f6#cg0X1%=2U`{4ah>5D5_D1lLM80H*Lqx<3@8<8k@+q`mqA5LyatrIlk@4zva)cu=9W6;|a z>YQhI1q3mU!G*nBD!r0AuRp{NfR1~TZoZcwOK5>S;e3~NJ28-1S_Yj|y~B-3{ZX z8YHV=@{y-jpCOql;{2=wkB-_zX={aI`9}Un=UPWYU1qD;{~VDBa-IQuyk;A~VV398 z4~tw8kPah+hbQXlJ=V{e_|qpEki|7Fyzms+nI&BY_gQ5wfp;u$Xc7x_cr}0Jo+KE#Ouft6O4oe;{lg4^kHC$T8jy3 z0}&6aWfqkR{5Aq<>#o(SHw8Y`Qn^$apZqZTMVHaHS&?w>3CkW~3@@qCeKlE+54-RE z+Bom`_Lx0bt<^hpz+FYJbhKf)fOC22RlOmBYD-y|2oj9dcOnE6dd1e6r%R!~~HTR>20 z>F(~1B}GCh=`N9uC8WDSVx_w~m#$^m-;MA0^L(D~>o$S$-GxyAybDis4bHX+F%z(2%Y|hgyMxWH17h$bRxwL({$2B%Ra}jIglyz=>w)?7xh)z(uUl5#7wa zE`UL;+n!_*YCH?);1Y!mnM6?wmapm9tJ=IixQ7Kqr4IfLM#eacM+g9l-~|SRUwX>T_94huoOi(7~KND%}UJ?&i!G=v@Qv7WCp#J@Vs{f_&2wkL{e7a&QfN z71o9@eXp-~Ev^gKQ6rA_BaNa~&ckJn;rk9%EF#o0S{$?F>eWtdC5KS8Xm9Gs$*FZ= zKWf6aVMZh*kDm*{S*5|=QAtT#;>SuOVh%!Q`iNM07?2d2?Ms~8A7BFWA1N8``N>C4 z6Z+p`Q$Qwjs86QQZ3b8wUNB$yE?w6XYeXJKM;jSNQFLtJi*5JNFPT7pR`d4|%VF#5 zMAv#+vQjTbOB#Uib1asJD3z&?4|K%hEUd3BEH>rJd^5*_4i?G9lMKnrKQG=@c|P6$ zSa>U-cgCMvJ{^+N;1e(M7Yax5CYIUkEi5Tn?v=0Dvh6hzLu&Nq$6La}`bXsl&1#4f z%hOXF**HK;bVh69G>YF=L%1Q=3ZTDT}gX%=neW9?sRIO4Bq8N4KU2mMarO`Ot?dD;& zcQ4bumTeY{eM1M)&$Df$u=pUd<`(+n=IH}|WL)>~SIXgF3rkgkE_2ob1SZ1pR$NRD zDe;Lyo8hzlPrs90rx>qOkX*La8*2NV2IkT*q4lI^%q}<3ty6RO0XJ%|mh1|%ITTX$kD|Aslg#C_kIfUu}UbgmlbpH1sdKbYBTIoK7H4+*&5eW+nOGrS}c zG(EUVY8Jea;AvC`Q&nuwc)dXw*w!K$7weSU9M(+3bx$c|C~$W)7BXbcW#A9zG3kvc zI`bV~zwFS8l?fb-j`Gtd%(1AhXBc36oR)zjpL|^AVrRuTym<-U6$6SxqTa;2RhXPv z-yDqV+Ji#V`uy|lfrI-O&mLwfHBTm*O4ohX45?JJ@^b>SM(s&hl>JCyNBmO!llEUh z%q3HAGbo)!k(QQ6xCU*J{Dx01YkP(^%+xdxtCz#A(1+(^tgKW?o*oz0a*k zBA2cx+1SS9hY?~)0Ly?Bwdzi{yworUIzr;%;3y~-tSM)jj7__bVrC)>kZ~48Spl`- zYwmf_Ac=xs8Ga~f`m6zj>WbPZH6o{{xw&FB(?VP@L$D2ORnuqJ(xKPsw7_QQZbDe} zHpTbA^$XF60KVw`J-6HN+EhdBulTJ~j%-pfp%y#$W~+rOgd?yYWNsBa!1-SmnS|*| zcvXI}x}H+ygsaXm_Ey&#iiPVE?+YSXm`-$a~5dyBy0x1lmFQ2o%x*yojT!{hAts^8lV_t5H0H`45b1Yb0%G({yec zxgmXXVVQ&<%Lmmg2A5JN3xP1!z)MZ%L;0+5iQEIp8%FVA($D$gaK5gr_a#l46!89L z06ONM$(Q-O-B@4`Sj$hr3|-+NVt#_y#w^K0w-1M`#J)Da4n$%f@Df(QWaonce3`nL zr2dP2|9%KCHAqVHU7bCkt9ef0Vg=kf)}or`yC;#C$HLIOhJ-@E?`zGa20h1%G5Pig zpaK7FF(#^V5e8~2ni_wSlaoU=hY`y_BKn;`9zRd@qe`BBY!-?6<7wVnr zqt>XS-Wc(wY5lUq0~Uw%e$IpO^mFV@s3_X)zkK)-Ht`&PUFLx%2I*X70V8_#m$Xr- zvD?5Sll*D)>$ev`l!c`b7ALkm7y!RLlM?7+@12&GmJY5YS;zc5aF7DLbE6a5mLqNvx&%{I?UpM?Xhy zc|c`ehgIXig!N=zWDLMbsZa%ih3@P|Zh@Jn30+48=r{HhIXjU=+D>1CzEcq@n{(gi z|9P+#B~Q>NkDVR+b(lpMH`Z9%Ns57HY1!TlP#``~(x{^82N6!$x;FLT6c2EKqS)X8 ztj;^B1pZCu{hd~4;nUJNVQtTl+|>j~*VW;urWMY|={-LoR+`?Q8z{$%TEb!>;hwvx~ zq(YsI^wa_X3!fC7DoV4-a9IwE`hr`hVKcffDr0R{u}7LX_4;*Q*g%~}c@5msS{7JO zeK@FvZtTA)`G4z?@GP^Z9G_lx3@)U{ZJnHvL#h}K(2gjnzxJ%Z(a>VVDL|&<(qEd| z%0MU@64=sjCi(m@R?G>nDU+f7$8a9zQKfoqg3D3v10xM1<0F0oDRa-qDJdlw07<7* zGt9LS!HpFXpETW=NjuV}tyXMOpK-S#(fRrFdtVN6T86L)VjuQ`Qkzp>x$^BLV2Ii} zY5{Zg>UFHYKT_5YsrxjGd=l;Yn)?f@)cg{x)hi8Sm%coF53|kOr`biROD z{pt`T`eA?MXEkiif|EfW7P3vf*m>@eX)ZCH%e@IKr+=CNTFUsRK$|o-+u`g{xFFys zt#nK9x;(JQ?EQ?pC>OQuQ> z47gO;xl~$rKfp!#rzS#3y-Kg=EsrjIQ=muDUFs>{1^L>B&En!3Zqv{?THN{kp=Z>h zS#D&0hn#PD#&3o~uWt)r9SH+`(F^T$9Be1&UW=86`I3D=S-?j`2O{_hB_pu&;^p1JB` ztxQL?tw)Ki00DTp5puRJP0b=iNdO1`(977wMmGez`Mjv;TCcHMZZ(hAu*v=w)}NJQ zgn+y+R*LjE_@{@wChzsf~+GLt(WR}(_rNi)?euF;-tVAg*; zh8lM4QNLGGQZk#@3yNJVx!%c$zCOBo-q@D`+)5I?*&XoBLl4!;r)`DuzDXF{C2LgI zbMtk?k(H1wPkB#YNQ()QUp|sxBxN6|i+QDJOMLamq_eB&-z21IeI92?Yi^_K3jzyi zk;~14O<8#reQjbU1^PX~U7aT!fi8V~&DZzHXxJ>~7eCBwd2cx{zwPR}Y7;jjYjmi$ zf}n5iVO{ojXi@ZjbFa`sJvAsa+%lj}=|0b2Gm6D##B^{)v*h$?an&0W=sD@4lFTFa1V~G%Ny`qgGT8^L7;XLgrphWP! z{EzuKbGuwpMO>{VW)+lI5HM-O%*&ZxxY-jGiA&o*Es%MqjHBuJ>#lS7&kRwkn;O)+ zoOWK@KnTdkxhLoR@O4fxmg=UE0D&D7_(a&4cCH@BTmB+Wae z$R*2}nbNflAEdEveJ(koIoU5GK!&N`hl8?i5*I_B#tjTiDN?N-0q56A=;Y|o+aUe{ zGNQ8*4JLep1}#}u#OV;iIJVqP>MTLL|5QNoQAzmI@oSSd&w4ITHpWOij*f{8y(qmVBIG zU3YwCSijwmXLFzWSd(?xRa3ucoz}j;oZ0@Fq(KEtSXzVQHG{Fjuhn_x5U1@7NTDbt z@W|M^Ln54b6lo6sW)EuIQY`aRz3Q964Wz^c#G_@4r0VUoZLgJrC*>LN#~upbel}N7 zRCfYWhksfO@2XajmW#*)kQ#}NrAg*!BOV`DdZU_7v?FV5^h@4DV!O<2A4R+tG9p);RzB`h+yJj4v8T zU=|&oWEbduR0{lH`I?kD!YZKSKEWmVe&=oZ&3v4$)qF<*P#qSyh;D({+G1bGpyINT z!xeY#!*7_w@m8ZVodS7J%H`qD=DH_GjY$!ZqqV7ou4~9b+D`Hfz8GQr_-`*ue1X}^ zMI9fPPB$M%Cknk`N9XQg+w|LKSzwW@G$Eg!{kHUh#jJFQRUq9Cac^W%oY(HWd_)Uf zX$Kea{oPZ9mlaRqnw+0rGuHa=ZIb1AOkR}MuKJg&g1wjLo&7o;Tn?sOZX<3Hln3Eo zTZj6!-ra!)8;q}mT~T)UW5^vE!s-?1_#5z({5|lXuM1rCI}pirR>JeewGjQ zH5O-oFcGYGphkZCR$dTId#baJHPmJsRDU6_r#w1L77gIWrc{b-V+`Z|S(6!FDE(N$ z6|L!_b7H0sYu&pEP4bC^jxoNt9rrE^;CLW5CZ1f%^PW7}DX#s@m+6xi(7SV)m+QBs zCTjPD3$C{qpLmJ5iecXBcGLqKad#Y5>Gj_*7%z^7p3<_e{#0+=HRt*`)5L`h)n9y4 zq>DDOLHh2cN{Oj_R) z9qx^)_G<(67>9Odk;ZeGsy6Y;_!Du~@7i`EiAL!TXj4C90gd>DX%*hgZ0Crt*8xP1 z-Uj}Nl~ni&D0NIi#a!ldTYN4tqyflUbWWkKZT5ccxP;L#&L zgBwa;y6&;@LAYqZ)40kc$~JQj#GJ|w1#ms3(vt$YEJ#PE@o%47PFq{_#Gm$b+gGN3 zjy_0v`8?I>Xm-*YliYLF54~04G`QxB|k<{)&*24M10VZV z40S=cN-Os%2AO@WEL<5V@JiIj>ot5yK~cZ?BA=gL9`+F};4ODyElCwb$8b|hOkWGi;W;JCwry#Eao&2}Bc6A}J|RWz4cG?_!Eeb;r(x`RzO zB`B2L-Upf5|M-m#E`dsNWvb$mK}S0y?auB!UHs2V`$ZfaqRmQ|9vPoxZzkgIcZN`Z zUX>QHjTQ*P(4Z);>Q1i|CK6O72sZ6(Qz0=ms|Nr4()nW#loIrV)MG?ptL=(%9w%|t zmBJ7PCLdsAGumH^zV;jRORqgTr=Cd)Sn&C#H{53NpFJMWDl_%adodxcEN?qsUVg5P z@etHyY!_khtmph(<^B67R(pSdX-F;8LT1`h3d!V3cd%IQ6NWuD&fR11{dI0S@w(s) zj%XREqC|~PAdYKUwcw>>N5a3nuZ+08fC3oxYj-+DSk2WlX@|5f{4nQD3&T%59U`>+4q`8SZF&zGVGnkmc?Q zaeO+&TRG4cGELIrfPf@$A8e~yIzQ|~IsYti+<=0rD;B!G_g6NLx)nOPw-NOhsP^aZ zuzl(D-U>!Yh21#?Rptafv^eA2jqg2W1SMJDM!~qi*-a=v+gORQ4`fNU&dkH*=zAcR zD2zy7CvoInFw`V}up+#n^uR!u{Y4`4G8{#wrY?xoX8ijFiJT6T9Dl_YkKt+}cDH|PfT4L1#C>BLP{5f5qX@-u#qu)QLl&l9e3 zMWbqkkyh*EL^dTvsS29UP#?1W08>7xjfY|j$QeejR^f-u+VjH9N;NouoWt|qS3~Ks-~F}f zy9uJktSbUc8A6kjtD&+M64${imJ*96iTL2HE;5JIL*JC+q-lN&bL2ez`RNvvp9blpXmG-Bep%} z;468bJNW+0QLsUuH?B1ezJBYacWWRTnz_&2ep4c8Nf~V<69x~=5ck;1kysX8h|&fd zg1M~Tr15{2T@Lsob-O@vby9ahER@jkuV(dxSx1g9Ue#MuTSQA{iE6tG9&-g!Kcgi7 z*rA=v#6AoR_%9MSH?!1EdQqK{tVs?CUnWK#IG}oS^g?-~(^J|P*|X^D(+5G(l75RM zJfor6Vw*zD|8cVn+lvXe!6^(AEJc zOU0h+8p}gjc)t$9ClWnP}u}E5_iNH~nE~L-&T!!|Jd`2Ov83OziiO@3eGTiOtWPT$&CO zXKi}{4z!x5jWYB<%eKF=KRt171vau2wC@Y9>FNWx>^!IY4ZoSB2ocHtHfD+@2T?${ zaxIn>2>rZJd`$47g0MUVkS;w4wp+Ms$R?}QCi4JljbDwhu+O_>{@}p2(RKH8Qqnj3 zXmi%2aNzs@=-eXzRI}76!y2ZAQH#rb=Ln1{d4E_0KO)@EF@HsD>~GHp=-V2LkphvDfA$Q6xZKM`7y&$NcR?LTFhT z7@imy7;tiNF|yd+bpn#^>RHnz>=TSmXRwBrB8?pe{3~BbhIvSoT)6uFlMulmw zqR))JVqgdh2tWeF@!Y)^3S(fK)9MKLg~ykC{;ZkD|r1 zLhRYR-6!Sm?Y_nXh*jVygqoT47b8a?r4k3O>#{{lDw(=WRVxf^XppMc{i(x(oe4Gv zvTI+k!)rK<-m11-O;E_f6@G4aBuv&e{P;213+x^Q0Cn(6r79?7s1`C=k%s-+M# z8F%#Y0Xfq=$9IX^N!}}#h~&mfoUU}xEX5Ak(aJ#rc*uwOud$v1{?TV$!-FdfYxt|4B?NAJj-0f%J8}7Uo(0^2m6+xeA!KN4|7YfV$Q1WsgO$qUS^L7C zO(Z~50vbCGzqbVVOw>wvnG)}k1^wQtPMY-I>34Tu$HWu71uUl|a@pmL>Xmn)nF-jg z<}5tyJ?tljDj7(Z z>i&y=qu3tkbnTl3LP9+oxPnK!rVFL2A|OGP63S2mcQK&=H|0gQ6BH8Jqc!Mmpr}V9 zO^DK?1mJ(BEZuivQg8cqH8xBrk7rZ6BSOI(Q0Gxr@hi{B(bvxB0ZR0r$Uo>q|84zF zujqQgN4)jSXC;~WfGYNKN(1{##y^UQnp&Z?yGmV?o{~_)J_Y{+7tU*VK`h$*J(a>g zwxI@2Bg;NoXov$e-m3Gpi$e9o&k9U>*%@0&{#|;Hr{Zs)ssuVegxW@bSl| zB%c8j7PJ1vY@h6jXyriPBo@{By2r%ac3@SNd8Ae7ELH+?G3`hekWq2Msx#3`iS|`M z3*z+!Sz@b#6DQAq{v=SdS;Z`y@2vwo&wNYJ!-Cu3w*Yq4|BMQF*1qEV*NGvkvfR&Xgv4KOG_|tf(yi@C=-h16Oxn1*IYEmrVJHi%W8aGM|+F6 zM+zI;5`p$7#T&nV0E&o5x8LLIi1y;ZpX z9fVY|GO!qc)|XLQ%JTX1=VW#xiRviC=^)#{$cTE_-@iNjW)U#A@Mn}VwGmJ;ua#^_ zP}!Qpmh*L!CiC1{r^#|Egv5g-A2y7Q>&Zf*)=dSC4BQ73iMcHN`SZ)kdY=i2bT!p_ zUvxozeSMh&klh1%KbuM>2-pZo+ly~cF@FU7UO6A*=8VG(?5#sYaz~gOTorlH?k^NH zAQxMZFS|m&7atz+ww4!K)|?RH2`Et3KDtOcyt#v?iMX|T%+HjkPYo{Z0ofp+3B*=a zS36B=f{L2!lX-v||CiGSK}M<~61@>d{Xw`uZ6uw2ikKKT|A4=Q`>BPChJ53XA8Ec( zlyoXJ0pr#09HgC%)M~6`-;wnip=dyCn!4srFn{b}%ckil?{CfaPRGq%e*=yY+hjL(8t=D^kiEt3M)D)I;P|7qg_jpPQFc+uGP|O znTUb4#cr@KJ}GJ`;@nOBvEt@!j2^j0`2&g{iy}#&#z`P1uD;JpI=(sN`vE%7Zq7!+ zLXi!{*#J&_Iw0=o;T9vM7|QaIcZc48-}IFE2OSjMskO5SVyTCnC%OiYXd72mH8o#C zEzim~QHMn;F^O+)4v&?1mq@k+DziKq3@jC(q=(LfVL_$G3Lw;xjS439({C>}^fA>Q zrZdU_+uS&O>WEede7|%7I{U5p%ibW4b!Xv(C%U`uYy)xmXNImlN>A)`v)DDNmCgz+ zcs}tsE3};c{*<|%>7I_t&yFMQEZy+Hq6^WwS+~%&oTprouxW5F(QAb8HBvg>7tU8q z?f&^8E?Mw(Ch1jMJ7};@#ZgL-Nr-WwI#nJ<$z4_%0@zspCy!}y zw`zXSr+V$>6%QO_`3`2we=YmocPquZ@2^4r;=@+61iTA}i60vsOBfBH?AH!o>IyE9 zS2G}A-VthK7l9K1DE#JhjQf+pQ2C|bR`DYsg$D$qMQ*k>zfSb_JdDe({+ju zfsN@C>m#1X?Ipx_kEL65T!Y1|mJg7Vjz*v0^an$gUm*?IV%3-XKKL%CE70pVL34q8 z7j(|%r0w+M$1?Rt@^n?itg8PQ^`V3bN*kc!2bk4|Gbli?=W}}1(oEG*J~x*iIXT0l zwEu~VzYKbd7xETx!X;>hnZnEpi~A2rh?AlvqE_nr_%4y8=#|Ln`(Z*2-41m6FDGaD za!2)+3`tqOoQ!Qya~XFk-0m!e%PH!oSXjb$lj%*GbyZ(RHF{M}_XCQY#Gco(3qF+Bku4tI2X2Y z)yp-98<*>1maU$xv$h7TF8VT;i$E>zLS?>J-jVz53kNslU*>tjJy`CnQPX54NIBg( z@k8BmC3oLmn!CN=ZpL&kA=U(O_*kX_znE%dP*w*{mivH zT~t*T+=DKbCgvV4b{W-0ikHz%ZUt%(=1k*ZR*$)zr#^7}!ezVGBS$fYTB6(^0*RX$ zv*XSYN~+u_p!B@R>L*k&etLz>KwB3DJG0vXJsdC`8&SiQ&|^&x4knqMC873@fWE0) zSzni2l4VoA>!bFB!6da(KL6$01(*PTBOXmPS^F+=le=Nl7EsCofrR)wHvoJ6sY6}= z2(ApV_FaJ0PYa-4S7rX;1`=@>3r3ukd6_P?uf#8G*Z1|&Cjq!p76br@yP~>BH9D5; zL5*5o*Q=pk#~tWiKDU;Q!7~D4bg_KP$$e$SnY}4Nv|sl&jDaeXk&T)+FtaKM@E|tDg4O4&t@x6`J82${p-oznbLu2s!4ph6pako!~|W*`@^`TU9@q@rR_1m zV!YA6?AMds;qS2AS=K6vTj>^8CFwzUgKdZ)TVfLQx{AGO#hbNI`2()@8V5|~B%-zD zr<~K}<_0@TBW+vWtOqq2)A!Z!8Jh{y`Zr{d)@BUwIO|4iy?s35QWP>IOYgjfJroh$ zb8~U#bF71Woz-7>CUJdhz!rPHsO`R~ak*0CO2gDhZA2+JX0c;ALNOctY#bmWoaiqD zx1A@kleie5DEhb7TzQvN>2q!5t~>9}3%N*n*duU8uv!t*aV#$ruT%J(^{?ccPfxE* zC)6r+5@mbsca{dEccTn6b;t(77^gYl=`Z{~_@u>CpfJ$;Z*%H{?%zzoaLvXDO?J=E z28RqX!UNy>iCh&#qXUuMhNgN+>I8eXBzh?dnqiIRF-O`-bX2cd&07CRZ$cIrfRaG7 zn%=`81q~HBVHcRa*_2S1QZPCa2->j?5nWBH@>Qpi<;xsMP%iib6WgElJ7y8gM~qCx z5OY}{I@k_UzYV1%pZRk}uqJeaCwd}%yY}OJMW3@#`p@QiEw?%q(eI?lOeitgQ4k;}5zAi}b{6H+$U9G%)yb6PGo?Y0dgC<>Bsa^01Qp(+>^PwI^Zl_3Bkd-8B|w!pNVE&LE;5(9;}c(x4jQ z7qYxOCEW-{h9@@5trT){ufWaetm6eiS=5_WRwU+JtQtM3nE6D%=>G<$R?Kdw(V00W zUyPn@xvB@J+5_qcw@mPsAJPr;+5W;bkhY;wqO|X8XxE0 z8T*?%-P!DCMC_-TjQiCdf<*H8#0KW4rH|3CO&&QO(z^`$wZbm7ThB<|^#@z1n2V#w zQR^wD$w{2g%4xyGw%Se!z&9d&8IsmfP4Pn$;OmtjGgCLwuMF!iqB>&*r`&iL`WGdS z62T4oKk9Jo?)@*1ghh*k77*7K=A5&1FHHkqv3z(UyF2o0l7(bW-=^l*B+*Z~M1??;cLn}=Q6 zyaJZnwhWiFQhvdLhIY<$5`I2?TK-35wL4*@bD2-v@C)o=4G1KpAn%$Y_f2s_Rz>`}S}cw18Dh;^gXbD&0{he$3`Zl|)Ba$yxqX~wzLCyJ7+u@^ zF_MhfsoMQ|r(8OEmPOa)VWr~s``5H=am)^lp^6C#^mn0D1YZ?@rL%^#i$;}B`7oZaQJZJrDZ(szG8fymc~d)v(5O7h5%Gdq6))Rf%pUi@v|%g6NgVk4O({1 za0N`gMZ3Gh0U59Su7&Zpd%q|wg`_MDs9W`uL8~yva^KGdh^gMuC0cHKP;5b@ETc|* z2nwGIkwO1xpWi@kluL3}M*9%z_Nvdpw(u|LqY;+(-N#ps*A<~d5vKfez2(IFh0y3L zoK5GYyzSFd6UF1-_qmTB!71#0!nf>EmUY@zOAMNm=nd>P3@wO5uUe!RZTv>klN6m} zL$M%ubGTQ3pl74=ivu0;a`~Y2b4tI^B>jaCV6V`k@nk~V-1YZjEv=%lMDfmEopE>f z4IVoOxa=$Q5TFv(b9l85uQZz;Ws9jCTG!;xWjOQ6NDrj^K4SffVk$scv)xaO#FmF zkOKhbj7Hs5PfOIxzLCeW>eSj!(0gA%?3!&Zd_r1%1(I8jAC1^~r)%i2n#@KfeS$5{ zH=OjHc|ozE+btH*+S)#e)>GI7v&z17|iNjgO{!(ATG^_!Eo@MN&A~q{qzG{-y z5alv1xx5gE30b4@8@5>r-e_p&vB4w$=~}g2TFoGb9J;7i~(-lG7PNFF&bb zZ+JP9(A2Nz&71{=y+$NhW*_9PwWoEn>B-RpDeQu;fkPt}M&Zj^=OIq3-&9}uD>744YW-4WHNCtRjr9h_V+Sdw2 z|2sc1aO*7-vA$79E6xo++%s)E{HT4S2tF-vv|6FTPHxZ~L7yts$^Cp}f?nm( zaa@*gk?`-Cycm@{we-L_A06L+(Gy3a+(`a&*@J*~K=M;}<)fBG3b&u%6E_|`I=?($ z|0w_RmMG}_;`#}l*ZU6@_RrcNed5N&cC*Ky{itPvK6uiwnJ!!rXV(?rT6|>s`dje< zV-lQ<2tg~nFRUqW&^t)PIz%Z7#=jbo2p_kj45jhm2E@k3nmDE8assyoGYZu`MC(#z z25nRUfabMQWGU>;*DB!uZjEGMeyKZ#YmZEd7shf5DEz4dT^a8;Xf;^jQZPS4X6n5L zL@o;%es^{Xu zg)4k4KHkQzW`^!f#U8+Gj$HsAx0Gz5UOwAzOiEkm4I8l7l_y8 z&zbD^#-=ACMu9(A0W#$&k*8GhR`b47$ry7@S~CMCMU=6k29hNc!>UfAl{l|iiE+P2m%4@z}guL~s* zRDBDRi!4NP>-k2AwBR}}uS~9?s*048qKFgPm(4H&IcT^)L~`9+b4xEPg|9fq}|;vhQAqudh%5H!Vk${B{-JFC`91nX34d~65#!a7GaCNV_&ygj4orF|w!$GSI?;;?nwqka zkQYfZ@`wOu#4>Wam$-L2amLhP-G*~J`_VO96X}(T80mDSqA7;fJE@RY03j}S!Sk0H z`}@)FWRCWIiw(5GpSdz&|I5w?HaJ#q47b&`X#^G)yf8|S-E(2J*pj{^5-fl|DT+CX zXiamPnqDpT_v-8un~mT#Jv`V^Eo7ph=TZB=v`bjJ@uMEuH8dY{M{BhFn713J#S|D= zCb}I(1Gek)28l#2z6M@`a5Jm(q=K#$fuY%gm{VC1+DxDr=OX|jPE6ev7XKEYv-4rQ zZ0T_+viMStsI`tgDieGoIS~^q2u#PwF^~^I^=G>e) z+CS_+=HPR)UE@=fA_QnbQ;q$wFrW0WpP-V`?UgOXJ2J7vA91F8BYAI2x`Fm?z z<>7CtXB<_6ZY;VNY%;-x=7xG34%-iYMG#@eXJWb)3DX4@!}$*%idi$>88=k;+E$;*-Q^JFVU%L5b%FSE2rCRJ@MY$Eg#-MDypuwsiY;) z8o&#l2=cIF1%ff*)?%uFPNP~Vn=B?M12?{2cj~mciW@Mn3A+UdVOn_EVgCH*sX6T| z!teHgmr(b$Udp<$p?TxGs2Kc66#{|=w4(KGtMA&Pc5$q&VAz)6<6QFY@L#%#E`0y*z4Mr z4R0zVK$2;jx3*IeyY_UKLekNi?ar5%oE*A*=0?*|F+lZ$x4ybTEO)_r74+4CUgnXP z>m#5Gforep_Y5-s+(=28?)~d-9`=4bfu6@(Y#ngby9;wAvYRIr4{*XOyv(j#Z+}Hj zg^S;AcC^c+1kgUf>Qe3PDM&~zYKVQziHbrxGRc?nT^zO6SLCJ?=542{pMtXiM4|Q4 z+Rcp|h;o4?U1_D#@x>x1bwLsSrTy+TU^v|M)n2@AF=~OgZ#9_x-@i9T1jMZvG8+T~ zrDW*o|KDYe=5bj#f0cTWlRJyX#~D^iK@ujAG_j$_HEvz0;{gf0rmqgpq_wz5ot(O7?0C-TYR-`Y%Ae4AnyxTCr<;m-Yht%-&E$h{});=0* zqw%K^dLU0Yoy@Eh8AvrZ5Be}XKsV{e!fM5GJ8Mvvkg*G06T!^qxXm*8M$o-Ht=Jy( z-uVZY?TxsB7>e?sj7z_Wu-7!&lJ@0mQN0+EK%2j$)Zdv*p}1rp#iEptsa8s>^?0Y2 z4FGA))&|d+;_-+M-ve0dp6e%)CtvKQ9ny^EG%^+Zwa5U}-QUQC>mYSurQhAG@?_Wu zxJ(Od-G+NcWn<%Obm&8`GuEPZzNn70ZOK3Ml(ZV;A#*7kKyJ}i&pcDrnv%V`egT_yo=>d4u0!9` zR8N+>8lk^g+O}WCJPN%AlYjdl+)IohUXjqY1XFoFqW4ZqbS1rKlDzH&*@EWi!+Qo? z(KDf19{=y;7xHI~dBLHkc?DS!j^*O0WR8*Jdb{{cW4YVSgVSk!$*CVKSO=Q1 zflxO``REYt9W92JvDY*{r%K^)-8SQ8^C*oA&zsy5cdAmqOCtb#d{MC=3RR zNMVm$Y0rlP{?0)ax!B2)Tnv###Dsu}mJ2geqO%W!ME0lKx(Sy(!x}gD8wwAv7A~rB zSnJ#SqLxL5(|U~)mz{;ES%cHItrxI@Ut?X}r6n_7=};iq@rswq1z$!QE+(nx@axGn3L55WE ze^mJktRKL;X)G!LsHfkl8>?%CiX!tc^8h^4%&($=-@oZZU6h}XV+UCr3AB%<+6z+R zaAKLLa($E;yZ_T!zsmSU8>ufX0|?^AF`RVV&jSE*unf}Z4)aZY;{z-U0rtE4DJLhf zi?}~=m~7_2zAAS9O3OtFqDW=v-`;bNOy6;%pH5lEFQ`qApaFXFDbl*a!T`=JEK(8g zk&$9<^KSpe{=p|!TmPu()S#95zB92~wB_Z@UbCz_&iy3%)BWhhfh|3F4#pG$Mqrbf z)`5+jG7x=K`&j_e^8=jzZK3 zC^5hBGeL;2N5#EGD8I*KhUy!Uei4H^RPbf$Rb2P$X}>4SP~e6HbzQkMOyNp(yi>j{_qR2q>I88 zF27fvN1^+!vm!O%BwldiPWBH8nNI^}u;NTyk*z)GMJ?!d@g$`wi^lu&gB1*R*!(%m zH^)8vlFejCR`sZxgVUJxw{pbVy4qvfPFHYY*T;5z$K`7RLrptm>WQ|SxNe7!kv|Py zpKm*C|2_@pr{xQJUFQ=A(M3=ZZCiX-@j-K0_WYV5Q^mjjqdGYuzPI^okbzli2nz(a ztq9)sul*Vy4c=T&db3Ia-Ml-?;4`_qPO^320z04@T%X$MDto^q929GB(q7J9Rr(_+ zwbqby{C1ltb9r{KHMP&Od5^Q1N-W1=9C^uaO_WOH%zbJ}v%_nTK`nA*^Ae7W(G+39NwO zZTCv^+{E~w+Jtp+Jr|wp>TbIwzDK}5fA^~GLYQ65&+WK~hEc$(nC-2Usf09PHl2lO z%&J3fwa{H!!suiNGRA-cxnRUamrN8lr;8qUEoH~@)X+$+SmnJ)^}z7(Yd(jUd_HYK z<(W$4C=1mo9E+uA+&gnOAYQ*yGIdqE4GjqN=isuu!}1eiQsMXGB^8B+`IAXA89MDW z_am9SXN~wD-jg)9f02sa$y;_13IT}@iYAXhv*5H4kRF@PE z&!(sepKnCxN^Q_*p*rN2SxsRL<3K%awPU16Fx83%^;K+EnykIO=#q~AI}3>NtxWx! zzj)!{BWA!f8Vqv_Sy+$<#QwxuvOnuu-3! zQ&ZcN^H#H#kP2(`e{pW)Y%lT0df&!$i^Fl0FwR>a4=+VG7efg@oNWa@o@ugg6KeOy zBIv;XM!?#_;P(wG2abuWv!g@64OczJOhPFo)H~_qhM1cCw`Ut)KI#&tE^>_?HYbZ`RntC17GcI)SG#t);NG-U(@g1H(tlZ345 zj@p9w?hji`tLww8G@%ccge4Ym2v#JiK4@PIwz6vTd1z5<>nS7A<#(x?(eOG>UDHmlG5Ms7 zUTt{<#uffU-m$*+U}cEG%8-o96qRs?EchNTxGys9J7l)T&H3FvUifon&{$&qdOaUK z-@moFu-Gf4n=g%(|LO_*P2N|c_@VB!WBal;Xh6p80`3m~tU_jaV7@a_P6*yE_c_I7~3$tT1eGBEOs zxFvEG-;{ZG2d&KMHh8GrFZOJ&n-z8&Akey5ucyN`a<^h}-Po8C5TK9Ic7fB3QS1kF z;Q#p|Cc=HZ0WB6O^*@&3TZ!|e@}@U;*LE90tZUK*JQrlSqhoYdMQ2;z>x;G_LAQGB zcQoap#==;VY;JCCDfcDE?Nc((VA_wv3Zxan6N}#E_jx_;#GBY2%IC8Oc6)c4FQWWh zxnzc0{qYPIgqAGsqRRETQnKXt`1M=w)aP3dWN()SPIYes-#hNMJakxd=(q6eqn=GE zJUB=2rX6Sq$Y<nKxr*cW!ZR)+#r zODK5PyH64-ECUiS1-|xQl9d=)~^YwiDYUPr*6M0x6XUFoAf3R6?#Qm?Q?js&=Oxh?%) zif$8BfB`7-jUwYhz1+e2!(7 zi|XYs2{*SdU#)1AUeR>|Bm0sZ|BNM#9od`skV`5hp1Ad|@$?Z4rSo~+2V;O)W+%%H zFa`h7)g8|ahWc|_T2jFb(+3WJ>1x}yvARd7wa2XjImG^e;BbJo6W98gf^oOo)xzU) zDQG2TAVJ%iZzb?2!*63>+a9Dlt?-7tizK#u$*>7 z1f-MG`4b zsp`gkcexb)i15Mi3Nw&>KV0`hwX*c1P09ms@ht9z=WaNz-;Doe3A%r z<*77o1~^eHvfJS6YjN{gzL5!Dm*9iFuRRGGwN>>}1EEwlq7tR>&>hWvKdic6p1|X; zaO$7gCh-D7Hku>sm3pFea6X_3Cf`m})*O=1@Un>w3$t~rj4!mSiW|#ufYcO0^Eo>6 z3t-m(JoVVl*|bk-p7T#1E5365WUZbKu6*pc=tuIVT(;Ewg7!udaLU55&)u5P1UlB+ zxV0qyFENfbp;vde&Uk8#TzHX33Ru2wWzTImBVsZKd3kzC)GfEoJ(7}&4#LT?DRdQsO*w*DDoV};8HcthG$VzxGawnKMuL3~`=4<5DfPpLo_VA0 zI`>lVAs6r&zkbdAKF6T0v#<(Ioavt;zD3k;e+?3$3sK~yCG=*TzYS{~hRu!)N9p$^ zp${397H;PEFJ=D3ez9ndTw7l;8&?v5O6)2 zu=TJpX!C|RPQ24bE|vuWyk=*kQeOf((;(n!&5kBfNXwWwdsoc6dJ$g(H+lJRN*@%Z7}PMKarlO z-$orgH#S{EtnlmT2T4o$StA!?KN((ba#Xik9_{@ud!zl=*b#ZBr+c<^y!1!)m^`>_ z`k9txNF`yiEUK&t^?vniP_}YF7b1`vs0nOsvsG0wNsl0AjxT`+kT@HR3ZRF68(b)E zEF~9l+BC{ki25+wywG!MO}XAtAPx!1R$7vvuIqU)t%6BVKG>sPN>LZ*nwW#G<$DHz z<+uc@jH;HLEM%=O{AKoImZAsiu20&(6l)js9LZbcU?_r;5UAvUF-5xA3yFVSQvP*- zpugZtL3w$MqM}0qhrf=&rNr6<@lVT{Zv*LgOpI!=Tsa|5vRcuZR^b^IteKtT?VHoG zBq@C@IA_=R*ul0Nr>5@OD<+Q6uS2^=+ZYxW;}w?JVmu*x@3ojDW5=y(kAf80Z1uHX z1f3ISb})54P(3ECvnAv%<6>kx;vZt~NMXk#u9jAnkf1AzR0kP92=+J>l0nBY*9bZG z`$P|iq`*>Bf)9X6$}8#V$xTB;!%2)mT=!n~ucZ{Abu)po-u%2i2Kc#=(UPh`%)M>* zB|f{Hv2?J&eR~$!@=kflYOO9hVfe3}4-MfF^ruZH5{e=DK*dU)ZtLXN$b*iPrGiy}{GPIT3WiYP5 zv1=S0-+Dv7+HQX&iBp4K$du5kg34{3{p@?SbWkBFaR~|*8i-6U+=BaD37@k-)<#=2 zs$JfF)JRP(^`=N5vpIuKgw~zcvM?Wakp>ig!FyH{_9>iO@XUqgKVZb@+Xt+%lzEJTyBondfFAP zTH(dYLw1856X;621Ch0dHRloD=!6}^=qkOqRq*LR^UEJca8YnIGTS=hX>TG6rleP2SC2n@Dyeu+JzY{|H zf?HPxA`&RvI3%jKO>4OQY-Px})?!3dG$dfb20PRa6PeixKFW%Y-%uv=om93-%gA zQj=d@Y6dPHew;Sp59#{-?*EDWXchGbzyv~u#3HCCZB?$eL5&0UqYmI3P`OqCJUAM* z44?bdVD4Tzl2R{8D2S_D?0XjHd?*fYbw5SNJ(?DonptsX<|7E_!mKs=Nq#9XEp{7x z;8BRz`Lg+UYB@Op<@Own(!g$(m8pYm8~gtBEV~mAjO0AEl0fs9;2sVo*rWaLn+K$(1-@bgaW7^4cIW?EUw^`u zkBpAb=u`|yS3LO7j`MiaX8q>?b=fyzD z5G_!MTp*uA=Sm;aiw;8TEqn*BXpJvrFihnol(rTGt+I5|^h*_ILF=|U#*D(mC2Kzl z`ps(bS&otC!Eicp3EX`72~G18(h-x0x#4IIE-_g(2OhQcv_Xe!Rn%6AD?ZbeU8?72 zkpvy2fe0G^#d!Bg4FW~e>5@xUyPYuE{7j(eJ%3n?1O6y=iQTRyRPk6E?A6*45Hw^@ ziVaIVMF>F;MDGSs_b0rpoj2`ljq-)BE8-@N-egtHQ~HyHJSFXzAMcTM{($%~6gCwf zIH$;Y()Nqa!KC)EwjI;l(sRzm!U6nK)SLVMgz;^5-s@)#D_Kd*O#h<=00Ry#o0M9g zf~mLRX9p_!gr4~~j3dwZ|k&fU+66fC`4x|gCKz)i3h|DQeSd3G`5VSnI} z>E2(li#=pLur%4N_{o}~xb#%XkifB6@fev-K<*-N$!Z{ywCtBIaqV!KS+7k^&H8wp zvSd4A*_xsNyknM9cjyK{kL*^yG_9em3W~!f#p8Lvem_G1b>xHNj~_ctPQPfxivtug z>s7O`-R3i`>!yb`rI*mXF7V!AQ4q0MqoB%G>kSiAvF7?vAie?d;g{#t)+ZgENRBhd z7#evmI9SsR&5Awf*WSV;OS=czA~-N>DXJ6azYZ=xuaXt}rM@B1R{efA|F>^J-S6`g z=J|8aYlEDA%!rVyYJuc-d~r0FsNMzoUP{3s-=jb0ch950oSpaHeb+NEP;hhO*xkJ} zr*?X4W?{i%2WJJ+nc%sy+S<6bHvUM^s^`rhyTTeD6C*4wjmBajuRrki9y>(i4!H{` zMyC3qi4I+`7Bda4nlD--XK2_mL}Gt96D6rPlfVR}O{MKE0_bxRWlUQW_=iWSJbwHD z@@7eo?|%e0Mny-yx4;=U@t#z(Bv5_$z}BU)WZN64V^lHhSlsq>f$V4?o_+~&GXN>e z!Fk}hW)o}8Zkvx%!KdHyI|wh|6?J>Ixs_)mY@JoPmHVwAF&)j0S2B0QDv77il>_Sp zVSPU^bvR;j=F)0pb(ppw@)N2x(rG`=N=71D`e~L$F?&B>?=Cle*KGHb&->!p;6*s+ zBmZ_HEgV4uuaLYT^zza(Rh~LQ*QsCCAgs@7DKA0)cbeP0(R_=?yQ!3=&6CaX{vSWM zhc&33E*~QY67zc}-dvr>rljz|68?6lF&F8+Z?~;wv;`8BO%ZoUJWU4xo=Qeg!bCWd zYPB(}L=qG_0q73tRfqMW3W<=fr$_cg&oz5I<;=PE#;JD;Dz(w9`ShBNZPEtvoVKIN z&@z8rCW9@k+?^zKyOSE=@4#UzKt@gb244wmCyKiLGBQ#u? zK$6(`0@L1Km7Y85zZ;|*Mol5};*FsG0&wMn#TVWW4HMDUG_#=1^-;O=SKaXu7Nq-< z4~`RLFW)V5J)dHv;Q86@$TG+PP$d3bc2JcA2zXl;XcP9xmRlp)97q&kCz`{K zN4ajWDGBL zhZI~Y{{^a4Y1M6!eHZp;n4f@lxq;sMACIl17H7hTQbIfa<41nQ`Wkl!ya1tarh#l9 zKC2jK@es&r9KqsEUKdAxscwiY86mn)u;>L+(}tFIb_!`Hg0sofoBtRioIS&=KDKtFKuS>tQwCiA(+dFVGkxO>;5&I2)ZTFH2{dHYP)<|AD zB6<+?5USdpupjP~x-`r+X+vDx4|R=nxjTF?=e`d+%tugLVf{HjUv{9n!bw!7clI+! z0+^MuJFQdd!v}~sI5-o`fA2JrmkGF#34WSv9OQZSye)dydl&W<a))q|?u+XXlSz#8_?*G9>>?&X5RkxtSMSkopwJ?pdQV~VPx-8N#J_Af3H zz5EWJ)N!Y=a&UwMeFGWC!v{sWUi7>tql$&r>f7oX^+Bze_X)Au>Oud^%*K|K*)TB& zorbyQ%k0bb~;=EGs?u147c?LQ=R2lj;5wcT|kkB&1nJ(6O$?V=hk1)uNX%9xiJY0g+n^1Gx4K13W5@r;dibjNv&my;T%uVqt5 z9a-{%4M~MXw69VPU7-q*k4jMzz*&U-iGI zWUAbkTC4GLtysxKd(k9K=vmajs@I;j`d0XqgAD~?6@xFMV^)O+AoAP#Y+N)n_vY*m z<Dqu@__;e3#85S`cbE;N2Uq6%I^tSf7O+uB3n6gmtu{R27iAN zv8z_NR(ELL3y)&+s!QR5%&OZMsH}u*VRQKa3(&FaG6{mpBrrrY8mt_xt(n{KSKlP| z{*Vkfl-#D)4&a3&xa}`8B6#iY&3EK;MF!>}CDz8CGGT;XphqvORh`W?h#osfFjSs?cD%w`6zGBlUY>7@0%ocKiD6YH2Tu`HqTssntZq8PyB5_4P5nl`GeV zl$|XnW0W{jNVVqwV%( zSuQ0`Np{c6+j(DfHyrz%41T{ah2^Q;Lc+$(_Unr_IT;ivJgBlMLgrO0PBz$~y{JrB zOb$&r4j8wDtRLRp4kB_AbK1dr#0~us7;tp4@p^-W91iw%Lb^lIV*YONiYBD>hPl&t zzkyDExi+gdBtLq4*UlT%mj4VFRD%KrRr%Yes6j>O<84!KP-_RCs;Yi`lwZmDg2>Ts z?uDm)UD3mIH*T%x=;C$@2I-{F)2Sw%$2HP1M8tBuO%44?0uXfc7-&BTwcx)NBcZNR zb6j!qnwgUz-CS9V!mF@|60pUv1}Q!s9dn7`M2Qod&ZT%;`PmJ5_e7t`=e|v=+{t#6 zBGsoU1yDs;HrUOThR0RsQyIBCu}{6%qN0>sd^gBeJM&Q*FOCYdE(*x1oQ4e#2;Bp{ z7~9j47OtP%c^}CCp!1WT@Z+c|TMN-4Tcqf@VdXtt@ZP1n>v^wl9aO^7xHHLkcsf$D zIOv?mPJZ}kbDvw(Yh4K$y<>^IpCxS&9Yx}-cIk6;Cbx1`V%%~-8wD}n z@~Pc2Zf+RAA+&1bw)i;bv^^Wa$iQlVWc$Wt1C0J}eBA-urt-SE{wvUVkMlS&v zecNoW@yihbB%NrOx2uIN29*znf!xq_U*Faa39RJ;{5D#GySvVBC0d?NluZoW=+$0c zZ6SeDoVBG|0)f)1iSEcxdO)dZfn2HpTP;(*a#6qT?)LTbwEZQHk?RPZ5glP>tjidJ zB?GeKPKPg70nHwjn+r_gKDJubF$-$E9j#M%znvQ-ha5&LZ<@idVGZ}Y^YoROylThV z)-H+#?QVe^8|L<#VW*?G$xq)*Psp-b#}$;-`5S5E!-2rP357}0!c(80(EsO5=WX|w zcPz2bs23fUh&O%<>fm=yY_7=5yy`qy-sb(bR42me1UX3bTT3l6U6rR!dKqv_%FPYu zTKQoTEaCU&ul1T9acyt=ryv5_NM+@HLEnOXDdux83EL$i8fM;b^qoPh5z^Zvh(fE4 zc?>}Bd(dhE&OiMAMj#8OFSprNCzg}bopawabbrzQ0cIMUkymFUR~=M90qj}Xl7JHQ z65J~+ONY#spq{?zUj$>jv0b95s?pe-oeg&IF$ue?AJpgKI0_%q>!AMx$v#}J-G-Nb+VSLfps*GR9 z#n?KxpMDxmwfx(|yuU`fstmu>bS}>U z0#Chw#hz%v9WOJAcT5U!L4%5reSN>dq(ZOrOAlb&($dO+T)Lu*GJ-040y8Cp(4 zN261($pxSCi3UUK4E%o{QZd>pWc@x9qr_l9av0{13KMIdz7&5_pRVUml^rGuq4YYS ztoiA2@G{^8;Eet{u5X9vqf_|blD>w|w3SkXu261lZc__}lWC(~9-?%_#;`vkhZJ;;}Dh`Z#Qcscv z#Md5qq(D-lh>bqhu#5US1mjO)IoPncz zoX_ieFljlmN#bfyRjnYb&oaE=bbl;QMhnc3q9Mt>Pq?{AKX?`1+{oxQUD`9ps?gjC zl5J=B1kNxte94VIj~w8H_q;N%WTMZ0T}TnJ+30Za2~%v1+>tZ3KQ&3_cQi&MF~6jS z1$p|WmZ|6Lp@=+%BonH90*f_K!T96bmqMsFqaS|uMvLs85C|b(ULEl8nHGrMt*ifC zKGQ0;dxqO+0MtFCxLjLYtFF$>Ad4MlJ2MG(^dpQi6ashj=0nyNlO>9oGgUcm4t5M! zBw>J!*M=1=N4r>%xp6eV+%39yg2cwgak?|~0r zT|iy^HCsqM1>`BX|}slULe@0nB^&HmJj2Kg=g>?ZnUL5NBSmacQ({^((l^Ch!XBOR?UdV74Hq$b?Q<(w_wvd)oQL7=o6JU2{R2# zdi|U~#w@MS)Z&w~Oy2^(mY6l?RNr3cOe!4s&}me!P_mg{&YRW-JUXceRNUU^CXC?U z_yQ~d^y=U!69C0zKnF|?!azxamM*0v?5D!KFXzsmHQtHo>bae{ZHqHow_n!)pR-NP z?9Oc$fa(Q60oi3Uq`Ap)&@+dcT*|n6U>gU$;8acHb|!|9J%W-mrt#Z|pS@oM)J;!v%aC)q{O*YYEMov=xW5NLNJ@4J zNi1r46i(gHTyxXWbskB-1q8~T;%9O%Y5IGjb6QV``Zc+1DiY@T9SUAAJ$QhC!BMn1 zE~#$$Z*0Fx;lDOsq#l_r?Hh4u=_!ym3k}w_f*zO2V^9RnxNGSI?v`V|%ErL~IfZ3m z4l_1cBDZU)jZps>6UNK8fixOJ4l59?OugnS?_1n@gUS&rV5`~vn=9V~5N&)w+4JoS zIR8JmAOb6(a|^bcGWe_19k6Z!$Jx(%iLG6HK z&}?K51W;maFcd?2=oC|6mXPHe>v<@;^pMYxgL6+9da+*lP4Xb^geEzXn%5VoqMB%M zwa=9+o#dn6>UnTFEd};_(`P|bED+3$PL?pp{@v94hDX4!qIR8^J7Hl6Kf@zU!EE#Fc7@Ux+_2|Id z6D!JdXNQe1p9igIC>MLDrURl>Yd8M(bVbvwdS01Gmk<;ncqb!DUXcG-bz3pm|Mr6)84R_0rMNqrkw%s+8^xo+Ggp2fGV*<9V47cT-| zG9Nk9S!b3P&HGNd{aH92==-^F1me4->^P*4pvZJ$^_9(c=NRNBOB=hayi=^X&SzETrZL$9kbmW3;%~)kprc9dvT?`G zN2GIesO8UZMR)Ml2azy&JAf2I3nIU}q-SP^D;FqWY8#vi;)%MU^-20+Kq_hk@W}IUh-D0JOZ9>j~y6oKDr` z(HBq`MVCV?zA0;rAT;i^uC~Q&9O__oN+Ya;2mb2o;EkESoVr$1ixW{(i)3qOdj{VM z2^FJ!mObxtJ~zp$8q3Aua&vjA-m}#&cuz87*B+$3817O7H*Km3x<5KNk!cs3o9x7= zv8eh@hk2AWLXze6GU=q|Tc@;|&Xr!Tt@`XaHywGxGFAP_^R}Bsi3?9R4)GtXF(Nsf zC#UJcp8E>k7#hsuRk2CILQIB>4qTz(@+3vmgQ2&6G{fImtDMIB(2<#l8B(!%n#RnT zsCN_fn*PcI`aXd!BfyB$0G99mv^3KB^Zj_+pa3+FZWX$=f>up``a$~4e`Qg_!qfL) zeL>dhy*@szTMd{d(8Y*_CyZAxxij`yHKT54gV6P^lmTDPZ#O7Pyj&)%kew|FR^$qx z2M9uWM4A9$lm;FvBD(TT2=yOLoAUhBJs`R= z!IXT~W}fItj$HH~4nZuE>_+RKekFQ&NM8?Jfg2e@m@2NG%Fe-2Z8yUn|2FhiN%^Wo zj^!guLekPNi`(inxjfPq8^}Fy2lx~8NlFYckURlotOG6BG) zW1!g8m5pE2`k>=+AB6}k2Wx(e`xNk%zHZvfwl`v1`ay)p)al@q<)$%P{NwM z>1B)l3kDoLAEVxI{I>5+^?f#KqqI&=M0RS{5C~+J{j@jbze>E(DjxymY*@*$*5p30 zYh1f!XK%mO^sUfI;?GSp~Bg}0d_3Jmro`vA|%<|L7H@qmWW$f_ie93zH8q$H7Gp}Si9{I7umIA+`QKEzj+L; z;(zaM(Zt3uqU!_2jrTd7X?#0p(Yts?g}Y2{ob~8 zI#hvr4%pvg(2eviq%ay*0CEKcz~D_D9-}1G?rgkrV2S{;fSF0)0dr4$W*;b(dcIP% zg9BoxZrJvUh*9*BBy^MfF4#84y2*+dU2J@fa;&ug$zKoCRZ|U07>qr+H8txyLMrh3 zb%n8*_-uSTm6wb`b)0?6E_t^sYDV>o_wv>)ietP5gqO)PE2bz#Z>VW&*!~J5s{R7d>-z5Ax(p&CPMpksUdS9|m?7wGl_FB#&=W z5}?NsZY2Lkh;?81!XgP;_r1{3i zoE7JV73If=lJVl?%mlw5u{h$;i`G?hhNk6ty!s^_$NtVvdaQ=|*K{&#c?!FXN^hr9 zGSzU(ujvV6+-CdO#1)HrMBEzAx>X;f0n1Jt%?BUFA6T(MeEkM_B}RzTw1l2G7-U58 zvp|NAQ;$=VxC|kiUJD;y4sy|b=-vtC$5bo-Omn(@d|_#8oBGb8H$)kpXyd3QT~i%*##HSQ z>?J@fh_wv~q#a-s)fqT_u(H74VXD_w>io#zRPOgyN^T8%6!Z+CyN&q4&G>5{iV=%^ zRm9`#Jp2aK6N$)b4-rJnyQ2m!afM=9RjIiMq9=Caos*SVn+a%@4`AHiX?0zMh!|_3 zXPd$`wY50@NGOxvD0N^2JXuf~x8|?V+P9TW_BTqsWvLEOO5Bnnd)$XcR7LUUY9{Mw z*oEtyOE1wQgwpYkbffKJg;1v-<`B#G^*=b(*e`m=x#W+7xdHnV!6Yjy_CuFb@5^%X z>SwHB)JKmVwH$OkDbcD%4lyy$Koi0mCSGz#1mhV3z?94e6DJ6S%lDcSTp~tACv(gF z{NpqgF$U!Nk0W;BhnJ|}>Ea3*S^vC=zwWsz)djoF4IOv)k>4HTKOFN^SF)HopGcO5 z)eDK*^1F-Fmx{{8Q_&X><=9*qsU+`7v$VopdZYVZz>&}=y*52hD4%9wX;?2I?e8MJ z^HEfrUP!I`NqD2=;slo5N-q;=@1z&y^dg2`r!d!A&PYBa{WsVTCs7 z=HveE%1s=nM3b_d7O5ql_cK1v_cxR=x@vqq|mW`i*$R;_C^<3Za71)5y@!&LhY6ciZ z6_b)OP-Ql-=0)>wlRhvNb2hi(n9%-@7NFUmXnBvZ{W4JZW|FPWNB(?w2A{&jrNoIQ z8nr6^Fes@CFSCXrLs`y~mdjI*RSEiS!_cc^2Lh!m^4qTJJL9pv&0>*5=Kg;0UI)XC z*r$kVM@bj+Hm-biQ*sJ4_nY5;3`08)cWPCiXnRV8 zM#ET7R_-ToJA#tGT99U`@n+LXu3!s?)L1M(rr33P;>_JjjSqBEbIIG-oV^?0s&u)jAs6~U8gWAsp zxFua(%Uw?xQ}ZP=CE^fIwhstDzbDL>n! zAlHVy1jX!lmE4z2ie$ubrJvtv5@Fz45}CPq`NP;qt+O*={;qn`b&;IJs;Uhp-;8(< zt?8GFO`){?HY5cJo3QaB&~B5zQ}aXlwSfwDt#xXfy`Hc3c&RI-q)6iizU$j4*p6Rv z-k}@4cd_Q_)72=HZ4h5cp0^-E>3&h=x*9=z8r7ekC0!(+?j z_uImW#)z1qiJboS;A`hXn?MtbGCaMX*MZxp5 zvE-%DIiqR}f2@!B*0D3j`~?72WFAMJY z@sk@b;PzKcD~N76HSCOK?nC8$RHJ0m`j!N1j*N$9Dq71)4DW1dh-R_Sgl67QU`Xg5 zZdD9kGz;t^8k-f=YCvyq6vt|-A-q=HYFTY=mym7V;#n)Z($wfrwK5r7Bc(ptrB)g? zTBbhsAmr`xia|psMQ`+jf+B98AY8g}DhX>b<~=RS6ST4BWo0`}UeMUSF`lB<98zlU z%SJ31$8FZxmnP%&A$w-##T85u9_4B()l%8q)iO=;R4D8nyp_xzVdG2jGwKRNt z8+XbjGG;l@u6S{ctgEAWDe(PAvpve#u7kmWic8~z%{=$HgLsZEf%XTzTP9ao511a! zg&4u4Q+)o<7w%7*!6#}$SEOGA$cD`vdLwHh^F9`_wH8n&yvQLft)iV5fV#Oxj>EX* zpGK?F7>23%op^v#{asfD2xFa`MI*9=lA{8(IS^vM)`Ti}OJaI~In4s6nYW8@+s;EA zwiwmYuzVdl+F9bw3|5(&t-|>VSAYhxCb_UY{7~RXj;qD|`e_!h{OpgAld8@@5);+Q zHKl47LZn^9x;DR1nnt>(fx(KOIwRjj?(uZ$Es%Z#M)6eeIDpMOSu^2xT(A&$J1cJC zj#IlxUnkdoDyB$4RKxiX(xxaNHIzpHTc|BDbuW0N>9q5qc7)h#OCwcmzW+?~`G@i; zAMpl3&KQ$>rpe&7ybGehC(`o9#*fIEy_>A--GihR*7TSNt#AwT-3(}?6}2VIrdUxW zW=P&uYqd!4w|YC{I1NV$%R&r$?D6)dnWR3yR)R-Sd|_?8qx_^BzVT}F>2YKTgP;oD zSJwqTI@exKB2#Z29U>nepIPr?ww5z(%GL6Z(3rwWO7|+~CK7VR5hY@-gHVO8EuVuC zfdEGLr2&qP_|Ha4A3Uh#1&b{5QHMs5FghC$FA#c{$_#|82=sj(!&?tNyO1kB`Y$JY zXw+8ZyJ_@7ny&=)dwj&)ZsRAubeQ4;F4!GOthyZD4cT2BZ$&Koq-k6X;p9gpnE|Y! znfT+5r*qD8jt}o9&HmKWN9D@ybAHH>R8WoMJbkYxu4Sj+b<`I6rg&hzcFNqI%obDe zIrVf=-Bagq$AlTXGl`(hXHW+9Qc=$=&%=|ay>l6J&!Y>|y+V?pedbd854p74RTJg& zsbUHb33do5M#*wZ7)HF)45HJVBe@e|$|pbCRB=hWCcxHynh_S87G3JfY#&V%(+}BF z*T5=ayx?6ScyBD`p^HAUw2BBR+YO<39YeqV>atMut^eIZF@hyB@i$`X%MfpAe@|D6rb<~`0X2)yz|&C$=M+@L-mbt?i}Pa6gTSJr3qPWL}|N97gd-IcRPnGv-c;kGaw%9SiCN@_%@i<5(a-8!}`O&+#L#!aBUs&n- z;2SObgsXqQC*ux}&=iRT!3M!{lNVI(@kH%S1x<;6xL3wyJwuMba9coRWgi#L*GKA3 zvinim#gn8VUl@C36RG60kO|ILnXu{2N^(pM!)0qFCnPT?ZhwUd-ceq;$y@i2Rpvqr z&B@tdTyAQoi7~jJ=n7xa(z3nt)T`mxGpyp0eWK|SSykvT)%!~?3hrljqKhT92_N!mTVmJ!A}+U`ae_`WnRnubK8P)-1x^qxXD4m_5bx=Ry$DKK+&o32rmu{G zbrA#~G?S!fEJYirH0w#EUGr!~N{<1ARFQ8_w)(kYQSeYZ`?glkjW}yNlEQYcaWFN9 z(zM0H+RI9hUvCC8B_n}yWnH|}+zY6FM<4a^gs zy2UjSA>3uY{M)VZs6P7H$GOsRVyf`yId(L*^u)^0wK(AHST`*%vaK9X2{6^no8Hpu z3PAheqLAeL{6VgZ&ZNh7HiUc9-I=t+R6Ng;Uj=pQPi!%3_RsAozR7x4hqf3ryh#a} zfx|6rY(8IjDe?siC*6@y0|>JkB(eDY<{<9ezy0BN%+7t3CA+-PfgOG4N8Yv^-b)+@ z3fo4Fh<<^(%b*!Qt{5KE8^gVn-Mr9ZqDdmonB` zr0TxRf1)fWk(I6OxAo(s@~g|sUp!31x7+-<(~DX|VbPK}>(IjlPEAcr!3MaW_5-!J z)mo8LS(r-k;rDHtiF6<8LT2=)Jx=DdU)7ljCvqrvb*tBhpAidb(%?y1_9E+jw=h`ziKOT zH6<6pLsHsIuvSnD!pXTU9gvNN))g?LNZO=(szTI^nd2@dztYMkpiheBoqC5xu12+~ zuNK6`y^`SNQw3nZHtY)1|0y`h?5bFIiz+!g=u(n6U`eo8|+C5C3?loCH%*$9N3NJ(zeW=q}j|% zHNZ!N+}@$g^{^-xcG}o~yE&Mvt}1gk^X}xYwLX*FB`&bC4x{Zh1fU*RcR0%Xjr`)R zq(n+XVBfwtpXo@zVZ$PQx7GS~!1_2}<||ASQWfOv0}WD*6wfv16f}&_JM346(j9PVifV;lIX8R#^VZI zZ9uLe zbCQh36>J?#eeK}K)oe#uXL+*fQ}F|?EVmUe9$VHQ(`?-?y#uA(hf+S)_j~j0M-k0D zA$k>M@(+?o76~a$zEB-piG#D9nO?rDv&y!%^sxHYr~V~x1x`G^?(6HF8CL z_(0bMrbb|)!n|Nrf&t2XJyxV*d^oZ1W7GdGr@Jg=jcM>}=?@rP>b z245jQIeTJEL5-}v-Xt8lA&@KJF2ZqZH$btflT)Muwj+A}ORdM($<>t5HutaMz4wvh zuGm}Oi@r+lRP)iVI6=$%AFiLj*Rl5k$Jjgdn+w3djQ4G0hXj77kGi@A>^hGuUfg{vc-7jZH5k&o_EpI$^%MvV;FX{JdXzEK;tOx-3^B`Uv zs<EX?CfT-y#1rilUrWo|*_xL8D;()vmCAmxmU;?@NDECR z+BkDj340VUe)GkyTJy&XroYvc)KhxPh?;O^T6aUVn%L@CE9%Kpmev*CtvEZiP%1Yy zWX?$4ax)HGV!%nMV|ddfX-c8EM`p{7Zi%7XjJSr2JQwtqQMvuQ=%IrDQop|JUgk_flM92ZK4G-$o#z7 zto=V97-BH65eu zKKx{?J@hgc!!`WfscPcR1N>O(d>LuzI_(7)4$~V~M)N=P_$re=oH4SsoiL8jVq*GEv%)yQ5jZ-t0QG3Rk5;GqS zVooUl+hm0j&}U4oSbrwT1}FQ7=UACZwtg!=CD0tpP0Cj(?QJP|SMz!j`{@^qz zzq(De9p!@q6-~1t!QEKMpHse7^A~Khqy9=-p*H*a#I1*3Io#{k(f_+Z|6XuUe#^zm z0FFv{#EPeihPRmM#r?`kF3Vh6WkDQxEf=krnjv82>eR(AI9Uw7p+c$>+ZX1v>GAlQPkGzNf`d%8mjg~v;_ z)YYkv!L|EALjPwal7mTWpKWzKki!{r|F&#iC+$H!gFDasX$GGC4J61e*E8|GgS&8F z&N8f2PHgh#4!mPH#%uNJC%WOB#3x_BCNiJ8J359>3|f(yU0)i{EWg;=BpN9(kQNwi5P0`#Q=1{Gb7Sq16?wqqMzT|KpKj5>AKwBotJ zL@$0ztI{mdp{`>eVfKBfsQ3af(f{x|lAc ziwEO`D4*ObM?wQNsK#sg)2cR*PC+8!lUQhnE^_*`Tx$zWZ}VI3iv=L@%pgrL-%>E5 z?nSPx>STGtV9rdd1VPgcKSNn2^{Ns0RNpmpa6BI4@@=UD!kjS-E7s!Y9W?GXbX=&Q zVdguBCtRudsFc3B*lKih4>pt&D_N^S0WQU)lt5Ph^}zU);O0Dnwziw;PqpEfbb)ZJ z!b4Hd0C9m>SyNZwWG^qZ07d>DuRkUP^b9c;(GGcW=TeOPus$BUWPt832tWVy!GZmE z7@BHp?)!!;#P#{sHGZrBTGVwsa+|gEgB2Po$Jp52E+dYP#FcN`y{LF^^DLE8vk}BU z9p;Fn4$^1+S`M4TPhXj!Y=BfbCQ+l}^0I|44ZoT(^HMhoczM3EgOkqNBie^R+)!0| zF0#U(6y|XU;|yFZk`f-aeQw5MF__dyB1|2{{0!vPQv7=xR^dgDsXi?`)(9V~QW|30IiFqn_z8l+P-r9b9y zcV90DBuJ(h&JuR9pSKKw!Vok{R-Bz15?)aA0$MC6*xpMe0Y(ghM+E|6kF}>R>vdpk z6GjM;u)wk4h8q(ALfYqvM~N~)xt=BOkbOHmDUUFd36k_kO%C+jc#DakfOA2GMG56I z4{t0kDOdO=Cdzy!PslK*25g<%7DWiNvZ`=&cusm%WTuymM3e!$PJ;i@;muOfx|DP6 zt{nj6E;nzv*;2847Od5)c_!^%6^~6YKm&%I@FMf-%4RGNz;_rYl<&@x$(qfFbY^(j znwL*G*VIe9n*7j`k8D%mHhUILr}tjkka?{hzmL2q=fxw5B}O?cD4p`sEDGEi)8MC} zw)*W8#T6VjJkQ&tu|@V-Y;=5ap;1tXx_)Dp_BPT_*?W$*c(XPlVaD?Tvzl6o!;&_Q zkwOlK0rmwd`*+Ts7VN0}Q2T3Y%t`0himCIt^)F^8n0E~3@v5&t8QXIvt)9KosA1i! zJ3i%ADXMn|&oVe`^e=RpVthqE;ZC~_MxU*Y+E62pZEU<{N!KeyLry6c1_oJuE~{~V zRj!HUd5MhFAyvJ$af&&lV@EI7;W`A4=PQZ_DJ4h*qomK332Vtl{?rb>US;tP?LYiL zllzwn<87Gt*;t8DyZJ$ov$LqV$ShLRTBO0^oDO}m8o7&5&B+t81%y7M7*J>AG$)2Q zTe_my;`_C=zM6KZN6A%WX}gMeghxlG#(v2)1j#bTg%W}Uz!mctAHU;z)q9h-Dp9;Z zke@sn#-`II9KX{SXW}bN=^-P-cWlAvKilxhKwlxqO71JG^1<*bM8YG}8!D~;)Z7*! z4xZ}IjZX|WNZdB%UsP8|GBvZyV(61%qX%;t$(jtne=vfFdztTkgeu5ORQii8D}tqP zuDAq;klr0N-xH#M6eGr?J+O2Kl4OlfHCcx_+nP2EH-pJ+-akEVWpjAm&GrEDnlI%? z`J@iMcQN!z*!pa@(iR=VE8OY{Lkq$*wL>gd7`Lt_)Gp7vzaJOd>Pp3RzuOP+HR{$s z$5Hn}>m}D^$Jdp_oJ@zb^SvZ(V^4f6B0g!GJeSsucAGouM+a1_YY+(QFTNN-V`4q3 zW-yEBIMechUkL5_2@u`6_3(0+VQO!;AL)La?bTv-L+^55s`jLZLEH zOXZ&Wc71TWXG4fVU0ZRb&0@n77dw=HzMX)M8)nk&+D7NjnDK*kMLTJ3oh`d1l@;zE z#eV;uTq!Ng? zS>rRX7IMrB0p&U#`Zxj z*??9Z z9&B{guZ{_3Bv>8l!W^s9)&)auZV3?)$0(&;5ywqc{R@%x!gGwb`qdcH zQkz2AhV3d+ln!cQ%Pp9kTtfO+)brAh_$&HkM???)eB`NI`WRJyF=B)d)Rm#f$*j*Z zX!F9Q!9qw@NGX!rj6c_o;TYgBrIb>vq+j>sx2OKX+xi9d-uK7CcVgTXoVG)G3M&5y z2KykX;OOazsexQR{9bPyD=H)zw7(&~blojs*)GRl=#O347!M~X< zEqhaO#Iy5q=aO_Xik%`jP|{;6$M$ zwO z&|_i6P1EDTl(`{8|3m)elI6ljUn+$gKSpe)^2P8S89RA@q)gs=Z#H#@uT-P*6f=)l zcH8h@mTDIGGlEtvJ?K@l)e@(5zvN#4MkG*9H7DRSg&r@n^EA6nHkHYIa!N-`6~*VN zTlCg^H0SB0^Bdj-Pu6rG@bqd?4Szhm0U^8tM8-(#>H!li;{(*NFSoGJWA()ysq7>W{5;( zoE8x1*l#YEDDVca)q8&!)b6@I2NunqDiB5-%mgia+EV?=uTOra*BDuxKF@x0PWJWL z@UJAV-lATbT5E7vyn{YJ6f_t`^CWTh23AL=e){pv$*1}TC;n1d)Gz3TV)LU%e@P=zCq-ivAznmm{-cUP_>`iJgF7m$d%rhu@V2tiyox)AZIjQn7E>?l@x5G* z9If2pgo}NbboZMyn+N*X>@V>3#Av+h_s!v>Vonq%yREo)UX-$9tIL1GxcKaL zm97q%wAU^En7iRG9{=kFs87P#ylmL;IZ^EN+~wW(vcsZsJ&)eudlkDI_C`tNm0r&k zoNvdC7%Ac&`RB{c>VPYM1}`V7BcCgFKkPr%u}9vWiU$jPNA>?gSQPoe!2v`~t*rwN z-*k?Dc=X1VtE3gDM=o`1x1f*DFFwdEjXR1HmM8SfxyWN0JXN6VcuD)XCX zr7VmZmP~5Bq=<0DsCntjWSvLDZa=LfnVStHKYms6a<|Pgw?uaY1nSmSOs0xkGa22P zw`u_ZW&0}O%{6565*xB{3{K{ThyP3#ixxO@_ogLTHOaf5^6vO?B;nHh4uQ%B`P|A1 zWP^mKyf{gJ6Wfk`NAq$)?;gWh2zn@YTIj5kch|H`EQnT#Sm1j9hHd-I3yL&~dRy?Y zO`WKF)gE$r*)&`1_3TZ!>v+RmtC8N_<#;fyRqG=^odX6vo736Zu(L&6kzdx2zPmgb zOgJvYm8r5)NaH1(~Jqhi$JfoLz4=c{-h|Xd8+M8ZPwAt?{YBwf8(?d zJ29Xr>_EzvAXX26)S;W&t+;F@{IKWJn8uM}civm91>+Wg?Yhcs(XJ6BPO(8^lxHsR zF^}X|Bq0Swui3kw_tTlM(k%#s9wPaCK-cu`9+mPN1X3Y!`tzoH;@>(Om7{e^zICGX z83uUGyHo@*E+Xvd-q-E^kTSQ{8=A=#$Wq!QXXmH8&RejC2nlC%v zT>bsIRt)UZ&djw*OC*9cvRT(xnoYt3d5erE~MLn19y!u1GydycLUuPsPQF!0eJrV1?#%B~>3e;HT7A}EvY)=cBK(5B zAI9S-4{6bmUG*4Ma&-Q&T`BwqtzGm7|H4st?BY3&tA3j&n{EhvJ!5%I8HPS%7+(NW zTbo$OsW+SkMh`71eNm{B%j{V>kyksqkyi%|yJu!qJM<0vuY|RKcsjfcnDX7Ciz?9a zzC(Pq$#T9`GkG%JMpg+M|4yS^{LV4ud)HT-(*2r*lhb&%-9Jpc__YXf23Ys(>l5p% zZse^eySk4rLSG>H6fX>TtG6%c5nHRGx3WeFw3~?2K0#r3|6MkE22t5%nx&)I!hU(T znf?UMu>*t$Vt$#!jQE8DP=6w%)dU+Y0*9p(RVpvoN2gUE{VDe0NqPnCgn+C*OB^`J zXttML+|?WSVrl@4L*hTkp!qlK_Ql2X7$N@t_9V~h2xZ^dkxN~XgrrNb``{_i$E2rw zM?@l)7~~??Hb78-CIs%BmXgX3eI5=u545^FaqC5`&jaAO_--}4_?cBz6*oUGWBWbi z?V98A@&=}Q0lT7gfl(t!OTL?VSj>>~VCltGJ-q7zJdlNgg8|H9#; z$)p`$k6b1bu+z!QQHh+y9Z-GP*}aJkCM6Y1`ksccEUzh^^UP4qbn#NHq@g<2_eHNB z&(xw7*<~8~zuhwjzpYFz-to60K9qcH7^$<8YF%#))*zo>ZsW1Av`K&m7 zYp=Wd{Q6IzrTeV2kIn{8RnGHp+N^NzXTn)||9R=bzz_WFy zPBzcnP9i64>lO7fZI1~InjwjNY#ROdigmtRy-`<5;@K2?)ckI6BG}5iAKwc(LRE@d zx~V66&J?+p5^=C=x2F0$SnnmrGds(bc2W8kHLZS23OSDzm(OB+soR? zO-`7E?5f$18Ik$-Ve4&N9({d%yT9v|K#Gso1?9=AuBM$YL0ra@;Q(t9zyc0O`7waH z%FHx*-&P0g7eKQT0~8I%1IV}gl2?@`ky@3^L3vOTX#Ra(9jV{*0v&8$3v@~=qUCRG z8bu<;`>SXMMB_$|KOS=IF_%W*1T_QG6Id;kf8~E3X`+gPNkR)w4&|KwuY3ole5N=V zvV}jOW(>q&q=8aeEB}8h-P@N0`m%| zzfXDGME7W^%cj;yQGL9&kK_IR8pWM@D(`Q*`d;Bx`W_E>*hJ4^@B z-jYy!$jcjJH}{7uK0!7ocX!}#R1ap0$bw|R_b6Mq((&2^p$qM2AKraOnPCHhYur-2#B}@)=Uhk8R$A!4@?roxS@>kHmmx6KIh_ih!DyrC8yuu zovPUP6#2>bkM6m9qm(7du|sA{J_UH#PONu}e`P9(3wbEVTY?$3uV1s;*7@)YQl}U9 z_A?QcCiTaCG_)VNMvZr~w37`Ni4t`0z9^pV;dS*%^nG}n-2qF3pn?mYqD<61b8hCf zDJs%cXp}C;!t@890$pbIgvH2Ucd|ipbfyDcB{bkay&cen5_Qek)9V)IPY~Z~FuPf% zV>1|a-b|yr{Ot*HiXqH9RLYd>ZjpqZ!_8(pht=%Mn4*r5w~RCAP_H@kRp`+yXWz<~ zC$`B?{9#mol>5F?iFDuXK5VM;4Ms`9Og(*0^m?%OU|_*r^DAg+BO@A-lzy*zqxKNZ zZP)nw^~7tG{T6CL;^JFSB%A%OU&()=Dgm8o#pDu4dYLf#HAf3x$p8qQEMV3mD2-6* z4EE4aB${w?YZj#2K&$N;1yPcwf%-{tzr3a{rHQk9mIgT36F5Y(?M~Hg%a~*4531w# zf5$#&YPuiNlpDcE-!?zoGd*5$y!=-g?M%QCWt+qO{C8#$(3tt-36*i9wBmZ0j7%T&fkb?WHB`_;R#TiZ z>zSey*N^PDp3aOOOM1ppxw!n&rf@C7K1s0g0KL=^@AvKVh7cS4;_;@vXWj3JAY39M zpki_9RJ#ec1gaV|K08YIdj+#o0qF(wueI%hgLY1bo0Gi7dyrI*R7xk}gnA{!wOD&C z(>kN%%{IK4Oe{vbxd%m(Kp-kCj9Oj?{1Yh>SOW0_HCpwuBks!1))ond{PH>{G1)G> zO`WS+4=G|Q0p3Vf6+oDO`LG~Mbd!C8*m$ocx1&#jQe(04DU+>YFp`8c`I#zUy@%HP z;`PI`=t1@@}d0}r^RCAylUh!k;B8>gtS#)TE~ZGFo2P_4Ysa-#loqc{hNFJ zQr(6^4~~t!hiw7T4!Gsfztc39Y5d~fhG-qN%EpZhyDeZ2MMpo=(q=ZdVJ+G8%tLol z*v{PxF7Er0^SNQuXwFZfV4{3%ifAPzQCUk}G1J4_CPc8g?sP~4lGtXR>BQs^Tq9J` zHFO~uni(bbXkQWdec#4EMUZYLxNm^q4GcEnGQ$v%y?^@{GJIz&+`4;pgWT+=(Zfm> zGh0ZdmISk0_i&e8EVL@Jq+vmNZS)kK}53ft@TjVxN?OZ^4*PVR+)sC*tn)9IW z7}8$c@%ufxd1`z|xZq;{$wB^p-gaL#SN0$rqm0AiCN9XR*q%gjS`2}Ly?2y z{Cy0rbsw{`^vJ|gNvWN$`jEi62bTAE1Dfx{_%%CwfNIwlY;Aelp_kkyohU|&n}^l= zO|DlqUJP-B;}SG~V3JaKE~JVFr88vn_ORbvK2TFr#=*N%eTEc(- z%5!>Laj=5Rr&W%>w(U7ti&`ZMLcx1qD@`{d5z8gaebpY^uRZMRV;T=%iPz+zUJgM~ zZ`QF^#=#)#&aSlKr6wHH00Td0U38{Bg}_JcuIDqy4w8-+gVL1ck?6xW0oL7IJJ=2!y~j=vt?)%5c#CH&FVo;drpx zz3f!=J4>y7pyy~Lhk3BJ8#9j7d<1f3-UXlIEiMPvC`_og+`&*CFkN#jdEisrdaIGe zi%@~N;8nca=W9iTDkWh~c^xGOsDk)I!gD^}qJbc8GctegYGcMCdGAUu z=jh=*{;*teo2{@ny?{04BR9T%UZgGOu7z+4#b*l8AJqnvCwwe;--JcpC>i=Ci<^N- z7oG`Za9yn-9>PXJuBb@FlCr>>FGDG#G@2syQB{vs`pa zH_JkEbpv$ilvVjbn=lhG{)yq?ZXhm(NAFe0Kt2Rw^4b>dDk;xrHHda>3$)u`ID8qJ z5MnLt=8`?dcz9VvjDp|N`DJov{;Mj-0(`wY3*4H&PKk)1L;1cR;bBfF4%NiFrwr-g zFE0pI`4mDqd(fnF9e3F>Ak&k^&(*O-adKj@M1R7)jCuqUFmu~yX+_4TH(k1K6k%e z!@DnQYZiL$ON2EwHGD2FDopo2JvEk8R>lPtIuLdBb_$xKjHf*;xl{jf5(y+0?m^}^ zwy1R|R{ipR1HA;BXylfiMYpSl(^rpFdc1fGeI`Z-opyxuuyLlBfmYf}ka6v{c9TB& z9*GazhT)zGa*!5oZn*8(*y1F2Ny?wGsn4&oB&s$;*>EH^U+`yW^+ zPYB1CLz7vd(rVY@%6GV%vqkhB&O2GV3;49wt>}*cVzA^&*R;6hC$Iu=rUouQ2NQ zLVmfJm?*C~Er31;QR1{QAnb0FaJAFPT&(G=I}H(TrsSva;-3D7pjJl1)_87O6&>w$ zxayg)Gczw)4vl8$>*uY@9>hOA^j0wQzNM-8ux8rou8pS^2HxANSWAamqvY%wk#)95 zvP!B!VS$L)%VODC#0g-#EfX z11>+ZqC>9BUa5}iGX5;vHLD*oS1LTLnwUI&|soKe|K zCGlHA;HHy)A82BIAerGikuI-Z0%({SX>lZVw7fme&JVSZ>ccBMXWo=#+r@ zU%EY0WlufoVI^g8MFnS;;u=uhKz`nRaTMATL_x~mRn~tQR#`c_JLTxR*b;&J0C1orb^>YSbXq_g0SRDdmWl3otYT)Jzk-IpgX5f-U0aTvrA z&{5oB3TnANd|@0BZx^O;kM9(U+SsT;zMVjWA|u1)sF7v5O%pA(gqZ3AL|>GQ%&?7c z?!FdF#kT{<+og$qf;f6(Vu9SlX~I6XzW~>NpY+DB{wEK<_I54XOJw_>rLKx(iv~w; z-TCctzC;p0R=3>7ACc3kMCTC^49!)m-ISNF=UDo*4LgG>B=U6$&g@zQaR0;WbeB zaj0k|#Dv|4=0ce}X$`Y-5!I&8vc*sW&zSF<1!}JTpB#)eZ82A@6YhAYo;Z(b$@Ad2 zdl?A~#&HUd^c-nYu|`W)`V#t%1tP~F-qQGk040J0#juS@Gw+Kj0E*x!=6+e!jAB+W zeBJt^dChT`+bmS^CzT-#f97H}^TzTy9AfWL2H1%}{B zCKXosnBx}A()eU0MXq*s_5E!5dwD3B%<@Dq3l!g^p38p$`T+33&~LhD({OWz1!X#) zkY?+`>tWRd!6;5FO?oybg(`7$^&v$x@N@n5s=F_SnYg}3K+OoLkKCs0UyF5sfoiTP zfqiDR+x|E2tDljAhU8!JMw50cXl0`(f(vtZW9#L?zN@73fa`vi`IYqvFB?!CR#O@s zsc&9yHTcp>CcA(=CU*EnI|h_|)KpDD*hsOzYy=9(HqLe%H|e>P3V2UbN; z73kV`ofOU2c2<{-dwCD&_NdE<{CR!ks@szbhFB}TXe+5TK1}9fCpDe8&erLO!-=m@F%;hw@1V`{?9k2 zZHyPPwzN!WNA!pkZ87Y6UCNX(F#S=)T1S<$<>C2(dY%XHkr5d{I2alm=M8ZqAdIvz zIe)WA7-7R}Ah5-*OVfW;#m)7{2Hoj!+Ulr|rg@vZkAhnW^Vp}~KrgA%QBNPlg4Id0b|CC%dxM(gqXkKuRpFa|>_WqjF$?7UDicq zV;(i*ek7}-r7p z-QCj=NK4mLVBo5?W%;H|6XiXJ^*#5k0fMB^KZp?Xp^(7AuXR@j{a-|K9u zmhZxFwy+3{U{Ew9xr^<8OA6Ds;~%`$H2&3qgyd^uX9PoBe0==&(myu_{q{dNY^>xn zh|2CdgXabe%AQknIy{$n|I~G^4-_Ap8wmf+e+T)ZaUHg-+7K6u=1JPbNu6Ejyo(y{ z;nmGe9>3qo*wEZQd9SQCW z2paE;8p<3K&$g)oswpk;)B{v?%kxmzjyCI4w*wDx$9n+l3Fxw-g>8CeifCaN9LV9R z=xvHyRo;PB{7g<%zsP;jl}qL24|~UoiqgSb=^L9U6Job-oJDxB;dr5(4+YGKcIz@` zWC1z%aEvd!G-qI=WFx_eZ|8G$eV5Aab5-1UbH*7taiorHucPuqEHh$8tYI(huUoVB}`?U4Q0VR&#jkttmrdnn4Vn_tX-oI`ZovSIWm9p zhU#+0GNR~;t z-giT)4Tte$q5P5uI?zdkz|)r{WaCt|$sJ?A+=X*}C|6-ABkuL_zaiTavfV$d*D7Ar z6pqgS99<9+(M*s6$B(DAP6tCkpurQyNu6yIz^IvhTX37~y;#TM+gXv;dhzKP&;RpC z!3zPFN#=A6mjJkQaWgK>x6Mk%$mg&Y@J{pW@WvYnjcO$Mj`9NJl@7m0=YK_Yg39xV z(pLv=LO^NlTh{vTTmbyOOd;q#F*5Qplvzsy#25Nc+cg{p()!-DWUc~uJQU%XN`stRo~)g+=nY|~=hOlRGda6`*+-&K)-<{7gYHW&~bqgk69f?;u>_|c6zERPoxd*ZwB2aDqc_i zaxHYXGVUx*?0Aa|M?O@(=Xt9YLl7YkEAeH{08|HM*AmrvN}`LAU;Yb9)Sk%9{N2$1 zv%Yw!HqxQBE~K4q@Ze!y>EM{GL6S-gR>Mmh>3#cRxH-`7p1W_{^GNglOgIu*@~&Tu z^-WUgE5iSMH~2<(PrRrVRi8$|a!wDcqjOd>l%iUOWl!kwvQLF{(_lL)YwKmv`v}=> z`h@f&VR>#?T2n6w`>_G4wIaD|%5;i_$l)5uDI|Cho_{n;6@;5BQ#9jy^;rM3RtPN& zIV&(6(Gnq<15OkUODpTbpz0B~e&?Z0+x-4+NS&!ipPb3|>e~gmK4*c|Il1NM4|Jkm zVQQ~B^Q{bv+fg$=GkAa@Q3%pm+bAGtV;0^HA0m#3*sx(e1wcT<|JGhMd9_- zE~--hf0luP>ppQ!*%7(N$GUlgy@2Q5{|`C=dhB(X7O1p)p!+*S!gYpw-BOm<4;bjg zEiLJ;3$qtxD^Pi^2GQ^T^#X+Fq@3>C>v{2CROI<&=gMRmQzNwQYA6OXDO<4IvEmiY zy3N{>VTcexXhUO))=p|?IJ~Vu6?zi#I#B$`b)klO`|KXBk4dYo*U8;}SJM+^ER^Jq zV#=nmM16;3u(x1N8#@rs)p)SggMVXck{L;G_c&VZa=eJ3yh8n#n6z%xaz(WJ2!F!u zBEaMP$GQ90FFzK|?_S3NGgo48oN%9|`D8BM^0LYZCTyJV2pu8j(b+@|M{myo(->g1 z`_?9gq*K?HtblSfB!kNoaC&rA6<_RaWU8+!26=i zn`puIXlTAI9A3Nnql>Jc7R~a|ubO7MUz6?1N}E#PYV`-gl8TL^FEG~S< z9_1O1X{DVt!xigDOMd~q(B{{mc0hE6JY^7{KY94t>+|0TuE|~TFA#(C0Z`Ln+2(U= zK6o*iY-=F9sRqb@G8{H~S zMCL0&!EBTK@MsVIS;(*T(D;Ik{DU#@+_wAU3-t4}KKppD?FQ$U^=^7F8dpftF+%s$ z^`+#4+c&)P8rVF<)b!Iu6upyOI-wUH8yPu1FgMx>v(1A%BL)9^V=c6TjsA>=l^wWC-T6P9V9djJfK3wD;vho4ke(O z?wc8Dc-c&^^NuEaGH^_NeSe&7JuyJGiA`2}tnFW(Ntte_Pl9y$8oUV7kDuUBU}hy6 zR~!mJ(UDUX%)1G4S!+hX3(RMK{)LeShg<_cf)7DOII`DxN?vO@)Xwz4vR+bmO6yLA z$SiAsB}Kky8&dAO`nt=y003loyQgO+bWsG>0t;%i>FfzThpyfB8)GG9*>k`CP4hV- zV`BQRxq|D($tkJmJ>xQIjV}EPAZF}PJ-Q;q>14x96zfHgO0x$Z;Wz0t400!8G`#6F zmLJr?=oAa_Gjl=@+N{h;15fHk3u_r9ix@2|gn*`*HGB)2{m%ZTpM;-j6NLEZ2rQ%X z7yXNf;9ysnlMKc!aLsQe{3g|c=mo0c;j>iLm7tl-Np^8vQvi~|ux&j+^&6WCxMZVf z<;p{8L@{GBNmY?@Ooq#a7J`pwv`ENKD7T;=(fzRBSq#GGT~MmS*YH2|xEaSk=#noX z&i124)HP}Fv$)u{Z#3)ymgY|k09rUoGF!dssrh=^B@IVU;7uObHQ&v8oJ9%3a?E71 z*2Ky|?G`B8`f)6nJruOMF9yYcCaKc#M+HgqDqCzuSokLiA&ypQBT|=^Y`BE;W&c2E z3&L|icA}a#bAg;8#X!`ET(mR2LDGFFMDLee#~0xG%=AU}R*0yN=6Ec($=c8}qw|Z$ zwJ!Ped`FB+`-*ys?R>(_hd3kL%~TEDUT)pHi2V;ro_`_vPvA7;LNhA$o4R9`F(_eS zM#uJJVSP8$OX0JRgu&E@1d@4zPfNmH0*KZ-S}RO^6An5VfITG`uCVFDS%}tB7TYgr zXO)ruDQ4xsL+JDov&6g)9)`CIz-M^&h<)z20nmMg^uf53M4lELz&4RXGaJg&>8C&H z*zyG$E=kyuEL;^VH7AT2p|vM!{1!2M!LAo;wQ2pMRD}SY?}8JgK!n(i1E6Ixu6T`#Hd^^ z6ohdca{DW*60g-aq3euD+JU~A=`~Us;S^#p9kbzf>V>dH1kU(6FOJ=(xG9QMjPs73>&YOt1PT{kYHC4!ZIUco6$aKqS39%>HLV!rkWmJeX9dUy z>XxU7t<#MnS%yJRJlo`%+L5i;0C6*>rm4XDGL6{(b{P6(M??ce4selQ%HmEQ=b%0b z-SPYw|6Dj;?nj%EF>Sa&FC>|%0Png)Aa8EqVL;y4X7zIeCPGdS1d3ik>seG8m$U(- z_|C=x;ztw7&1ef1ZqmG#qVSkFnG|?b$?0`{JRc2M%QDA#1i$d?UBcOuzYW84Et03b zqLzcIOfNJ>A}#8w145!Kd=YMA(n{<0n;|g;kP?BfmpRGV5sAa0VG0vN9wM*#o=7YH zBzs2B@M%s@ywZ|LooAHfSz9Q!BU4o@UGho8FQubfQ>W9fMRstsa~Pd^jvW4ZdUt~U zIq&*Rm*4zc!`QTn%4TO#l9I#_If?gd9xk9y;ZQ^7wz>1)|6Q6M8H^dK7i2 z#(IC87m=n zkn-2>)u@@OCW~e47opJV@tJOfOy;Li;W)o09m5#q2-QOydJsr9M}QHpxqT3kj1KP= zSBLG|is0dvZ^tvfSMaUM1#M#3Kvw_$5COJ0p*v8F2}X%wJAS@z%@>Ee&yPlZd;L-_gos6UsDgA3o{g~D z8o<%)zz5LpqyuMsPOu595q8rv-S%S>c zoS#q5&OMpEpi8>N$~017Y~ClGeA+6y^I4tQeKOuKaemb8_^{ZaKL9aY{Gx?apu-mC z^CXnj2MZSFJ#_@9+Px6Gj2fx;@6fG?hRT-O%Zc=dXkUGXP2o~rj`}XvvPGi%s#urC z(y#gsi@lS!H@qTglCi4yo9K+6+&VwZpLE;%Jd2zRjw$71NFcXmBpyA^?Fh~gX-+>o znGUrs&EBa2Jdj}593yM)cXDNewxbTw7EVl0;Qa9#H@jsGIt>Rf#)q0n-Vs~7}O5c@BPFFN;{~PCL>K( z@ZwEvE93Z4N9~Jp;LR3|6IixUNRH6BWXEMsSX`&^kUI)};)8lpQrf0#f)1^O zkMl&pnWE|e%Qf|H1S!AJ(Uck!6MZ&UCv)+65}4*B*QJqe&kG|dB5~%0eXGt8sI!g9 zPSj1_%dvptmGOFcre591KlOgGPxZ59!ypEw^wyL$w@pWdqR4@VSlwUyTun{wYXeT( zo^X|?>vP(=wLFKHwp;HGEZC}MMf^|D!UejupQmdt78jR)B*d)0PXsT8FiVXVGH2y? zlj9AIPqqnAe!*z&;Mk1*gGTv}XjWA5+Yc*OZ_I4s=x^BDoXC)Jb<0bwzneg$y9~Tn zx0vxcOWfh0>1`KjU+$%txAY{x4}Dy$w`p?er8re$)8LIgs^8$+@!Mr7S2+3NeEg^c zG!0ErJw$Sctr_6PX@xK=U0mg%!YX}{$7>cA3e%n2Ph9YB-!I>5+fFgC?SF^J8gEVT zb&CYk`A)DbbA!hSY{35ZX!;;s719hfqC}@24!e&NmQ@aBfVNDiI ziS}086FBxm8tvW?vx1KHwxS`5T)h3f{4Re;_yi*Uu}9BlpbEoLD0zF)^9mFRf3&x~ z)*Z598AK61VOY-s`>TVp`b%7`8P#rOcfSI@T}Y+q&?}>N8D}H}kU~Sm0-l2@8*&U^ z;it!I%HYuHZW<}QP86#^K)O14_n8Qqzt8skSwhNorlARoRKwnjV#@nN7pJpsC%4qm zjWH?nDVy|3wpJ$V$_&3s(|$m~qZ##H5s&U=%<|gBg}_dQCMS9t(S6H_k9c=-;p*rj ziCaPk-}O0;;4wRwt}lM>{nF~=H^U7*KY?OXZe;LiD1`A|$`pAQ3$^%OZcghs9#oSz z7}7C#tymO^xMLliU-I0&VOMru#_QO8$CA(GATH58@Vi;nCcQ@K7o!lp54>g~%<3tB zcA1yMEnE8XQ?h;RMcs*gL%u6&w+61cI=XZj(Bs`T_Ib$xjSH!|jza?U)k#}&RWSbY4kR2iD|?m4FwswaKPQD}m9>?V6x znhi(8(97e2c4Y$}g{zCTCDQz2AF&YKyY>o3=yh&CCR81W?_x?x$q^ZW(jai0eZ=aZV7 znz8p)042&+??( zXOhbMv^x{i8i{Ho86AoHjr)sCYYMAxxCv=~eo&rJV1;ub?DOeijEq#DrKmhxat)PEQg0r z2Rc92vogtGv6nKrp&03=8V)$R)`?3_&uKKqVc)3EH$x*Y5UmqztZm+Q%tw0e48pwU z@&1a1f9lVw3cxfSgFf}QC!a7yoRL?hyFqb-jak(($Pp*Uqv)95<)&Wxh&pQuD%7hne6QV}>G7G87BNV)7@mpA>@HG|z598p*o_nOW&yM}p%xxNNj zhay4LnYU0s3L$PjYn~+2CwG|b1OQ67KwF)h&@F^PD44<#98v2dgi?N)E)^>p?G&tU zD@HHL`!!tdTip9;M8Uv$?o`^A_pL*NA5*DH_<+6F%x12>z3#K&tv|+xXA1L0XKUm3 zjT|pxEBs^h%rm_8L?(S4sT$m$h+uqp{d!zytSmHoM$e((MF`(PdI8@R>U`9l`FN~L zXXdn-?U)TMWaDl2;I7?qN%oNAIK`CfF>0K9wD~+;vE?Gz)}d-$Xp3Ly-d%zBHXf|JNGb0xTHXmCPju+?@NpmP zol9MCC2g(4MT{-Uzx>c*H8Sl8oGX*7Ph+V=~CYyQmQL8Hh> z^Dqil-D&bT5jr{)&J=jld#)KjqDI>6z2y^lUBA2;c1H{0V=7v^{Bhr^Zk;b#?nVD{ zcWnRC_9bjoi2|z@!#NE^m=1^?!B3Hk0ULz|7dnag7yYe0&}=1iTff_BFAlnKy&qZ9 zUo@XnOx}BER7ZSzm(4FULDv&E<#>rMk#n0qq;APo=yV*%v0eDW>*8z03-9`raZ6St z^O25(wfTFy?NUTym+-lBFB8%4XO{LnmRMS2uv5N}7wqgo$m*SmE7OZ{e@EF>4zK+^ zo`Nn<>)5#3T(2wj6JKvvJG7>3uH~*$$tlg0+axD8^R9~Be(RLCzQ}C-x?|l@-sXN! z(ej3(UiSf_^|!-ptI6yYndtGJNde4<_=QMBe!~HUh$Q9V2$@R2Ib=j;9B2In#wBWgHo*d%JG63*G@Q2*BCDMAIWKHoPdos z|5II@R+SXYXpbme$r>M(2n|zwt&m6v=CcY2-s@mwqOF_U$gZ8FEq-p>ftitBMzXTi zl%oCCC%Oz%o_XMnS?KpqX;XYCFq3Lb;%U|W?H@_>-n#dmHT;-5{+@tM^VU|1IIAkw ztAEF_{QTZ3Sw||nD0AM(@Wyr;bF5StuPo2s*>Qn8dYR4>^Ey*Ts;R3>ExqepYzuzE z;JhJMEHeGe;MNV1lu-GEmwr{mgi$4ittIx`@WH{Z{NhXDXK2}IxAjcPQ#YyRA7J!^ z%MUWroUOe`oN=Q3@`|vbmndkC(IZW`yp;C6q)n}21@WPXbW8|?PPHGw!&)x?wD81d zlbC^Ro-aRde4;LGcL;sK*4muh|5VWT_pZ(&5mAWqrw<8r3*m#PrOxaQd{hCyA3-Rx z;QG7%^&`e7bcd5wh@#UDngf3(ka3kA^&+fUhDK0%0zB)@PwiqTbT9b``)sN zl@89E@3DjQf{mj3LTc`^BgtcmUR&De6@f2 z=L6w1jdb~v^`V~a-$UA5cwloYe6HzbyW--8jQ=x+IxL7|`tLmT*h_F_!%F@TqN3J^ zQ%q)G57DmUQ8s#`_F-+gA!2g0?S(6Qowdu<4z~!yYs8t9bqjZjoBc|5 zZ|}+M_Ir=U_L;L5xwtKM^pCsoJupeSTc^-|%dd_)SLVOwMjHpM>UmqJB34(ZM`a(e zVnd}Q@4C6PX26xU<@+DX)C#73>W(?}r{rbs4#L!IbRQrSHLiG6Xc0{CB!`~*i#&ru zvKi_oo19C>I^Pdy2Qw$*{|pEH_Eu8qAU7z6;<3bCiDZVal)NefGSVgKjy(5t-hApD z`^iHd8B!L{lRS17%<#o8HFa$Vz3LY&jBUnS*U>c_KyEa-#F#R?i`Q!ICP?u{?@k>j zA^E)=VPWC&^71*CTKn4R^x4tILZQ z8o!>7tKwb%#XX2OQ*P7y$$KAat*HpPm~Z67YQC265q-FUNo5w*r{G2s_qO*YalLzH z^HwM^hQK4ScA{8?LI}27(%nKh-JIX>19vG*2PsTjsk#)5N$DlNSG`?bP3s2>yKY$y zB7f~M#zyvs9v&Xy!jG;$(f(&vmLwuOoFFPHYJSq6O<3sMR*;WE)36ynIKmZNMbGq5 zml&}c3qEp##V4k$^U(xnR=O05_P5TQZQSr~o5K_&A^s%G=Fd9q6h*h2s(Ho-m&F|y zFT(0(wayR~bHSur+U+;Q=gY>yELS-PY`qA&gRJ5 zvm61O{Adc_9Kk8a6xP(j-p=*D6HCXvkroP;APUtF|H+Q2!)5aF@^((VB2*qdk7GIX z%mAIyw_F%NhtV4VjLiSPs;)91s^@FdNDGM64^gDM8$o}7EVU@RA}K9PNQZ=UgQS$S zbclc~Ah96QN=PW+!h#?rAR)EHJB$DS`}*Dw_rtw=cV^Csrte8cTxcyGYqr+NozU1wV>D=hZ^!}>%Y=L$TT3b?XH+%2@)g}a= zIG%&Oz2<^8C;V$cd4R%>d~R(-5l6pt=KQ8LNlW6Piwryj4W`rgoio6Ws(6&W8wu=i zRltBp00Hn_CO_dIY@6?4dOhH^U}5LR8-xLK7BjjMbG)rL(a`rJzz>UOwvE%rO=>HsV#$g>DRP z3$@skpq+tcZ4lpa@a@GONg9Ubj$Y(j> z?q4=Bs;IR#ti--cfTNt(Ok-w5)`x8ra>Fft%f~_XF3EF;*r2q=_kp5xGf5Uj6GNJh9_DRUG0{M%0w&jP%(3jaMjC-t6ow z(U6AqasS}pO%agb`-1svJE5NwL-hF>XZ zcnOC%+mV0!uVG27lCU@|-k{q4ysE0Yx_fyy{EOFqyq=+g(Zq&z!+o!5^`{35_Fgoz z$hj%N%`*Dly3{ElM~}FoPtqc?l#7ci^~DP=KY0%3Pm(&*Gc$-MPi!Zv3|$j&89bNV zYP~k5Kj`XOv-q7IEl)MO^Tb{i(%iqGJ+uxPZGJ@|6IfWw)FY}p z-b|E7izi7Bw2+Fp*q!Zf;aeg693uzzH@+Sud`&a}gqgUqBP=doB1%?bON#rkfB=9H zk9HcOdK>1|!pFx~(AF04)e7XeG_1F!O0(f|vE>*u_Vko8M#kBMQ(x!-H$tS@n(+D?)eIRi!d(~;-p?$8pc+=B&MoN4bltT zL+SJ4R1re=Uro0v-EUiUdOI?H_RFlGJgV=5Y_+aVgBL2rrfR)!a&j^v6sGt0s4J?d z;P*GiH}=I9mF!>3kfl3)s{WcaYcrVt0}ULE$ii!cSR~F3N#eZEP@%EF6p{3k4;T69 zBT{?tyvVPzQ@eBorpnnMhd5w8YG*af$%JfmQc+P!N=j0arGoZGMR7*k7y`~9oY7S6 zxxVwSX$yz?eW;^U!Y8xg@phq1As!hXT*Ngp8;OlS^)7jf4PQ}d22%&Vea|JlvkWJa zM1^3nb7FsrLvB5~`Wp5o@`p67Rs_qJ`_0pA=w8M%N5pP3st~UtoaW6R@GYrLeW3on z^`xLdB)x8jK=Hd$IA@?CKAhV8xxQuNO`| z^DuQgxWVK1~E_EZ*$b_SqAofwchN%WIrT&a~Rh4(09IbQ^q z+Ho%(MSf=LlA8Sm6HnsTqvzUV8gB8GFm8AG=k>m+;sK_y>1W87=H1R3*J(jUE#))3 z^Cr<)$8@P8H~+nPA;FF)tbfG5SQ8Z5h|`!T>#TtR&9$|)LgbPEEorCe)FS5Ss6JRs zm2P-Jph^lKn&V21O|qjo_rG})Y#q?x0|I42qaYEyN_=`Ba-STS3tRJbB5<9BvCsb)C=N$;+>7 zQY;J%y?Rr`;y4Xb8 zQ`TS0g&UqV9u7jcew-`qh@XY?xb27MVOl2`_8e#4chM*f=?}MR8h7{m|J+@d!~PT~LF?Xp?ti{+Zaj{&@r4TP|I2iAnM71EQne(s&Q-?xPgAN9I2 z*tZJdjIel?_K}KL-JySb*+8BuYq@Dng|3=vNkT+K1PC2lYt8kYu4)Ll+9W^0)Tne} ziUVByXk27|-Nd}=0H@p#A_boM?8K9FMq6*g^)A^5=FSnfD*Bv|2GI~Ye~>#E>tGBP z2zp66{5u_TGOhYKRc=HJ3WctGW@Pe57!sYHdNekUF7MxmWhYdkLXn#zcY18kZy#4V z?!;>G3Av2T&1!moVCl6DRPM}vuZLk-DJuSbz4I%*F`>s#=lSbqnvYZOtuW_T7pLIc zc=C0V8*r_O|4z^7oso)MliDh(J+tv56*|s(gehQrx!MpSspLVwzRu{nWIFdZH zYK-QAh{E{}>Swh-O*;C-^R>w~|D$*FGLEcF|0Fy(J6!at7;1ZN{8}z)-%of!iw318 z>R~BJlE7-W80;Wync~VV^X;iX`ak=MUmhLcDUg)xIDFySxtQEmAsc@BS~@yZo}Qlf z<`Dq_ZAQS&)V2b)&GB24*jm6lBr=VPRa&(zp_BriZ<|aQ7INR}*N#oTwaX(i7gkY< zGNN`RpA&z~%P{_X-h_AQjGz;7O>^l%Zuu-eOo#LZ~DfUE$^i_#_cSaPztWB7EQ2sybo0fB$3$d6em2SqA^q#AtdCc zyjs@0qs1%mu^X?h`kAkh-wM@_6gF4e`kL5HbK&Cdqs1mXD1IB7ZSOd?Z)h_1J`v>( z`Cxu=>@|v=oBJ6h(Npe;&xW z{2D=(?d>o8Ci`2$t&S-grLNri;b?h>Ij!@q12f~^4e#8KpH0jsBYlRww|;;mZ5<10 z_S+Xa%2BQZ2OfhsOUr_!Tl~0(2|FC$p4$-bBxXJj?$?6m8iAI5-a8M94|@-b)myT+ z4vwI8Rbu_hF7cYIRi#YHrO2U2Iw0wz6^1VxxR8e;nq5)NPKE{PW^WRPkY3c(DrvoH zBLv>66EN!&L=(E{7rkV(B?-a9A9$qud#a9}`j_3aIn((U=zxX=8t<=Drfec@P29Ek zI>=Aai8dC7Bow!Pd2S+3Ngf3pkXh&bHf(qK)GO=yOd9QclIyp1cq?#4F`NFX=h&*u z>ZIdDpLW+@kgm$gmRXAkAi}N8??^e?&Nx zn}vwcX2+*SUc=5-P^-^su%_4#AW8+8d~%?2zy6kS?orL+1LQ<^O5f zfkogR+~^PNpa@HCk6X0p_GlJ!%?R4LLs*)47{$A+$Qm* z{_LzS^3aKTZQAyrQq zixy@iIw1^(%EH-ChuPH_cDlcoqV7+$-gk=T|hGOlzg!H>a_vrP2E^xBJ;qY*0 zfj3%JUp;m4tK9*nvywJR%o=bCU;qXrkU;C^SsR|u(^M>skcZZO4oi&*RppU_cf9J5 z$B1HS&Tea{v~WZV(F`$O z$KUtL3Zh78B!a%at9)oPJsmKtHh$vBz5C$WaQWlF7@dQh?t%NEEA77tiH-vle`TgL zdpu^}lq+>Zvo*STs0kZ>IgJn)GWwW4_1c0 zw%HT^14omNkFV?vw~K3bPS5>hSm)d+)6X$ipB+vN8V3AEtq4CHFwARyVVpi}<)zKl zeBnb-7Gs3P_yq*YD=TBC(<<0qVu1tpX6~-#%yEfjqCMb@lj9GVYIJ5VE-tpVi9Z|l zJBr&OgKE?D5y+Fl3#bh;MyVEE%ib|umu+g3wKT?)WvbVqt5{Oe`nFMnI+Nf1@#*H} zOPoIH;=&IS^OxRlu>4R%WD*Hk^*tM;v}At5A=5j<4fcWv#G+fg>m8@+ny}}4rOK{7 z%#Y2pj54IT4Do&C{ahHXB(EbMDPAQ+n;yDT^bg0JhlpcaRy(zB1NdSuHiGU~@uDT3 z+CTj`@^DIR@$q_hCNH29?7ij}r>`s5J-QvN5`;ub+YaX{bxXX=_$%sq)o{Ma^?T0^ z?9I?t7}i{B>SyoJ@@_3+tOUaBF8_8tzUo=bfszcZ8kgFY^tI4YjrN?(?SPvcDb7s| z4FR_vX|^txU54B#Shd?)Cw4_PfBz;j*!hq{T)r#buSmPwr5o+s^zGj>YK~cH2$d0` z)QjeR0e+&w89~1tifxeF(dMQ?-ia($=}1lNKw`l$rM#rq2&dbpA4r~xdq!Zd8y7T0 zMQMj8P2SZBKVZK=CXhlvY+bwOiz5q#I0N419)PnMXp_b#Mn-~$mnl%}x9#8l23mYE z@m_c}RNWL%{em?RH7iN)L$+;C-p%=$wyyghyaUgV;Y>4g#{F`&w4#Ds@AoR~jWPFh z!iM$hV(>5G*S4pR2^_z^2?nufuDt_%P>nHFGqY=yv^2{s?g$I>EL(!dJmN~tCc@fdMQ`6qPU-)_cVzpdV<7ZVfva{Zorp$tWu=x~ zR0ST~I;(GR@Ksw|PI59`UESVi#!Sr;#OK-BTb4ma;ADdRaqJDpFd6#dt*E(EhWYElsmJyq=ehwcpjM3B7W>CAM=fh`&W_>g@uJ7fS(hf zVQ>aUXWv6r+z7M-#Qb0|7^UCGh3?p?S}RgOHA?{ec(UxAzCDTU2Q71HAD+~`^&A`dhD{(E5748Re@7}eG&J1X za!AqnD}+%bNnA$HIQ8z!@-BeBAaat@cNzZIdyNSFbu(Jpexhjddl#_rq9Rcm1LYMJ z1h4>k79NN09^~eP6@PSc%F7ghLN!P#2h>4AygFqBKe}*8X1! zMO7swCDzazPVfg0)EhS8K0s44t@;0j{TDvt^hrOztW2_r3O??!%_|T^HbP<+h98T%kkYW*aQNR3tW6xdMgi#>wD|ge(HPm+1HpZ z5v^=&bk_+|g0z!yu6Y+>4oihb+q+{j+Mh*Wc0U$N6V zR0Ltvv87siTChO-wIMxbkThlu2ff#B}$GC09q26uP8lif|Sd%y3; z{dwzopnIC0?y5Scj=b+FLS>~zQ4n7tLO?*Eh>HoyLqNdELO?*{!oz~E1Y`nDz=s$1 z@5L42!Oa8SFa-P=-$7W_LBZPC!CBAF2*Sk5+R}*L-oVbt$jbhcwZk!V8$b9aR#Qb) zhYxl}dJd-6R-}rimPX)<5D+X(EUcRi)l4i~X(23}TZuWOEUa6}e#{)3AwlfS+j(C& zdDfL6AV?v^g#;B{(hioKJ(MmVfu}PKv>Y7n@7}*8)$7N?Ko^$n@KuGWeydvSUTvmP z!ddu9N%PZ`PSMmfU*R;Qu#HjzBgX{#Mdz! zY3Gj_qt}{3#MkM^*XCHbxEdkrrL|r+hvfAZry^dH6gr)n?c>eew0im|HWq<#-HCCe|39% zo0QuCtk6}$9(+E-Jrj7sqboX!cbPXObl*orUHT93RA_gyAF`gsX>wUKy}b}zT>lYIZQB(H2ywg_z4DyJUuNN;PYi0hno{A&sY zSQCu&)Np(UB$W9d+4N{tSiYO9!1e%HsrfSuCpmZrF4o+R9zhAgL&dg)d>wH0(W>2i(&Eapd?I{ygb_Gpc6);7@ zJ1iMq3$mV)rGv`R=v$PRkj*sxDU&|01Jn=ngZgt6(W^H{JTEmF-YUqS#3!uL(!cpp zMRf`S;UVFaTWk&S&HvIUF<|w~%T@^KJp1SzS92%@^XNAoS`4@egG$#`T@|CHuR=C1 z7M^;iK2YS-&GvCTyG99E*N5C&afTX-l4pB8%S6?2U1`Prd|aQPq5wSo!vX8KynOz} zeMP1-@f9Sr%`4a=y{;4fJL-y{j%fRB{UuLl9u@ju!nL%_RLdFMEJPAMbmC#i!_1qQ zr%-j|PFIySL4sDaX`~1Vi=yCmqsA-?dPvpTsABJ`ckvOP4lb*Btw)|1ap0#^nQ&{r zygtZ|-A%&o$Gi??c}*5Ps;wSjX@e-d!l>_Bn#xZlqdVT;5>m@iAEPEdQfPg1w}4$d z!0@{HSk=pQndX9Nn(0_)C5Gu#U;03PBH!*XxcN#8YWvBIsblCm`SDcViM!EmD4!M2 zS)Wn=)zx2}7j5P<{*prZEex^v!J~Mt3ZdX|XR}{BtEzpa5 zG;uRbQmXG^O`zn}UijL1Or!asLzz3W_4D8;iBQiXoU5KKq;c2Cho0hFCjvRq%>J^n z){u^z7!#P z7S8(!m z6-`KDw2nxE3Jbu;sx6(8pl>UcnE$Ny-TV|}S%M?qc^e(Ys%6I#eI>c0z>#!5cj-WO zea(y7r0f7t%G)kwYjZF)uZH*QB%SS*N19ykNcSTf=5D8hx+VWY+z3(t)$t`eTT# zKi2@!#1RDhRrLh*)0GAr_6UY9 z#*JyJ!H~49?-axvlQc+1rKKV+8W-)GnMv;(suef2kMb%fo=`{1JI13^77F zom$}0A&BoPDd7bBpSixp|73?Y8RVV@KvvLbwI~ZMD^BXvYOqjy#I}BTbOl7E3>5HP zr}0QIWgZJ?h&jnYsJw^uWO+$bbTW0Mwr4QdXmLhcNWD~>B*Ra;6(IK*%F%9IB}g4$ z>Z=AaQgI=yzyK6V0!|;t9dGumbg7JXRNXvoUov_p4~6H@RK?R{9O8}s0$-=Q|?!ZRY>8u|)g+IN#o)aej zm$edrc9$X{;&oyAkSAlUWCA31KkzEe-|&uJ>7J3Zb=Y@Driy3?Y!bPqSVor7Bc;uwBXo!^J$jbKCf(D6870pWALrw^M!lg6FD!a0e@KLh&X#~= z@cDv)G-w9;xzk@^rDJRzi!$m!Fwc#)1Ruel%XAjWLxb~+uQ-5IsJ+;DfAQY+^y&Ra z6I|)$1Lp{dIg?(xpPd!04-(8@IyCO%yKd*ZW^;RNZN>dZ8Zl8lH#h6ish7K>?#C@a z)=^&Q_G;4!&co`7`D!MJj{@;ZIC>a*?2-?6DyL=U#69(wYPlDP@|FSXw$m%#1LUeo zg6;T%^<5C}Z{9x4@_{%BtQ3rJPNp#H&W2Bt7d_My-+muyI!<-P7Z-cWg`yWP1n(#eCL~vAC3!Wu1HYUs@g#;vjUt)b4P( zH`V<7bZ=;4GDGBkz2tm*3MApWKd9PWYI0ssGO-7R&fb^9%xV$yx~DVS1c*)(#1T0Q zx%ityVHuX`ug{kyDcMlA;ZGNIaQC9z|1`rfQIx#AX}9Owtj0rl$k`z4d3Jg%#0uRG zDBg^gXZGLWlW41meP>u0BLCxs!rkRQ@M3o&G%9L&-NV+FnO3=YwF^za@L;y0e(4Cn zh(qzEI#${*1Ud=dOzCse8BapuHE2K}>RTEA_0JIJc1~Pcnv#Pfv2MjH)z8llr$*}I z$L{sh&v9{+B2#~&DKiIzmAySPeqG>HMnc918_%bAYao}WIb{hGbM|0>qR?Nej(E7AN#(Gn3kZGuP^64pZ3eztVSz; zJ$r+60{O3KFUIrJTizNvqzSf#CZT^c4#N~0QTErJfA_+SYyJ+l%6OQZme#y%T{$)v*N)2fsjKHQup<%XK3 zINl4#$Hg(ZUs+H}r>Q!Z7^%%#0LI71%jej*l!Z3LHZR>Y2!o7`jceuD!NW8@T5Nzw z^Sqin)cpNaLPSgAudx1tejTJuPKV@Jh*N?2P0-`6=UY>Og%CM8ImpDk^}-~wFohlm z)X2Kwh*a#ozAabvYDt6s)|-`Y$dcU|KT`H^CQ&Sq#F7YT^<$drU8q4fG>Z;G>CvKp z{mL6)IvX14_|nN|O3`AmJJK3=;_{+(k!w=nI>PL@x3^5?e6^C)A9%GL^dybCn_WmH zt0Yx1+6jf68W{plg%PzhML5ff9rJ;fk}|jd+`KmN$D8F35kSX~w=XeF8yf7lr(yCF zjA(@Z*j!E_NHZT@rV!H<_ker^1cdq}D_&wWrzWD*VG(I*RB*sPyth!uupN6nbKXAw z)=A9=Qmc{D_80~~Lb_Uzx_v7>o{k;*h1n=a@a|HNLX{m2{ty3M3Uc)Zxnkk?x-UIE zUu9})o(Bo4hi@6etG446jF7gE2%EYt6gf(TXG zf?V2eS3P(Dgo~4?tQGO;vmPMhCk-8s91MiqK)dFW+i@Z!iYfU+sG?(oQ?A{76Bp3lbv``TR*t+FFU7Yn-Bc7 znH(y4wmN2(C~sgE?`Kh4X#k-TAtraiEjPkp(1p!IZXBtim4yXN2ZT$E$pXkH=c{Q@ z0M&NfBD~rkJ;$Z5x_A5zo2$!xqR;&l4NNBcGKTOn#Y}iqTM=0(K;m8Q~1Ja_e)Hr8Im=|;A< z?@0EncNKaKa_6J*pVZb$;+^-W#|pQFB1OQ!B-n)+fL*ax;$-<_kgoIN?T(kj55Rff{2i{D9JlpJry`uN>}sRlfE=f zeukQmuy9Z=(w&W7W9-_oiv5W90O$G!)(|#N(qSa%xbAxWwM@3Rrm)u)U3g>L^M~A? z*mJM$!)p8C`X?z4EDTdBOe$%^&Hx0}gsC0LfARq#?p(^eM>d=<01n>3%&T`WNKGhS zvj>~O!`fbp^5^OeJ%a-!IquEV2h?4ih4$y>q$>B0UDG# z)&->XO+jI1gtQ&z)}%WMhF>C8CC6Z|)?+r>KhrRG-=Jg}P;fH$_@aay z5e}C{MP{44z_Mb{52Q^gk`_0XsO;$!CU61J`WPvl-xe!9=*hu|%m`V%!j~NFvuR{Q zo}eQ+Um0GL8T=6OD!wPvGahu6>$!Ki6aoxeg0${>s0HTu!|dS zUZC1W39WGn34Gk?@I0yS4ri3i>G>{CQN!WAStF|0T9B`vg;qsi(aL~c9)c>)6j}IJ z1l>wo&?~RH^0Y!}TTKq~FWtH=XpoVVy^>Nlpe42TiG96|uhecDUdG?CnoAkoBDaqr_V>CaubmOw4N5%zQZ8W zLJ%PIz5sKubDME{u8dY}2NSphAG;}8$7E83pc?QV$J~3!Ad1m1)N?UFDekoU0Sb}+ z#B#2a5zZ7ZxAZPJ;8Ye+zhJR2u#QWKrN3t_3nU^<%_=qx??5s*jc5j_S z#=HMK({PGtf$#oejoDKyV%nScPxxTxGI#v4waI^ciB(SHWyX6cpI7iNn2@2HhTE-H zp0zW4zlIvA<3&>D z*l;uuk{S>xSoyktlELfRh)MO?P7~qSf`P0+N9Bo=;T4ar6kg}TlNrF0W-}OyDk{ya zbxB#g+@7Y)1g7GR188iJbw{U;-zvoNa*yTQ`E+ZZG-}dtqxr+i#zQ zI76F)&6KJvl(>|lsDm6)vaO9?gJ=hCELx()DGa!beEd~f&%ZQG7=D%;dLH;TBaU$K zcD~18|3iJ_cV+_#j`4!m1%@!rR(+e^4O*Nn{x_DR{HSk;t#dK7<{SMwTNL$wPR`f(8&Db3xhNr{u1MV#&@KT4Et!`|i_fzui zSC4oWIGx8yjS1ID_p?8?KC!g-c0wpywjb_I2DWL(N@oseN)Rvg!8OEhqzYEH4VyIV z8lHU?f_;PkJwAcS*_K(-j;?X$ig1iQ(pz&W{sN!_ud&g$iC|yuVE`FEy>T`e!xs{2 zV|rEaw-fpKn{YY>`*9NO<4?H{6X*NBgP=o7)myb7e}@u8R|ri>HqmL!nldXoNy;)V zTn`y<#oCEpr&h9&=%HeV$AXN_Y2fp+gx$h!`cBWwFn5Rp7>Ts7N$N7Ga z20ni?6)Tm)Jn&1UAi%J6`zkuDzf+JTIuIca=HvSu{^_LEg9EY}&{pAPk`e!O%IZSG z;1oD}B|<|>auj6rQPLjri==!p=(1YyvD2Td5INjh89UbdJt8!0Z_Jq%WTrLswxPsq zKsdpjupZ-}Njk!a3&$w{0=NGZ*5b0N%3)M3L-~h{G`_BV>`Tk`Wu6uQw{{W3UNt6& zrM(^Ki%4R&h=K zdZhJxH+ZT^KW^`r_{vqs1zmbwu!?Xcjpu;87Gp-`CX_r#;~%d-!SvArm`l*DM>M)p z9XIDsVZ8RZ8r<2murtEg`Z2e3=Uss|`;y_V`bUUS`>~33*9FFzznnWbj0WY;oyti1 zPb|Iv86^!PD`pA=pfHuBl(QMCCFKU1s=e@I*MTH-@;7Un>qb_DmkHm*QX#XibUroG zqoRC0U;cnir>ZPn1Jbn^6+4Jyr|tz_k+*NeIy;IJ zD*)`vkD-yMUDE8SXP!4;{JE2j3_yv@;}sOa9|n|($iMgBwrMIqo(k_+mGiva{v;D? z{*gp1U5X{mA&j{kAC)1M#b>bTSy9g=AaV~I&I>6fGxl7%Z*}U{-1YJNvia%OZI~ZB zhC)Q)8E45;+x^=wK{)VQ@_UyWqfMd*fpk?&*?Gb}6yZ{rugCQ`W;ZX{8{i5t()*04 zHcxg3uD%}D@PXR}p8dXKv$IWSFF!|n zuM!d90-Jw#YkD%4+JMH2<*M@FAamTg5ost8NM);SNMr5Q6u3)rh9^)F{OUctuRar~7@3bSnmEkW2x8b5GzD()6a zs#T&0YQxP_iVlRNn|Dp~=&I+z+jYY1u0}?JHOFbI$~~$R_g;PJyP*GaOO{RP;QDb< zQRs0@XY97~Hzdl^8+h*R$k%@ z@N0&w1+8>OS$V}U&u&I<@PUq?S1iZs!;KI`EY6?Ni! z>*){^9vDuI6D{6$I4#c_$*U3PYe-KQ(rpc1Qo87K)(#%k^@@~bFu&G4-7I{GNYCR5 z*FCWWVWF2c#fV7dL!V}gd$r!tAw6B%w;8&r~6Xo!SyboGpZQpafPqFX1dmzTeC$;r)~ZUN`^d)it}PH*1435Ua%ouajA5;$FaoN3QWDMW9h>hwcnfKN;#)A#gJDXZ#_qg2%9Ig)+7IuY5 z1q!b>@F0xi$swgQKbB9Eh8vr|X@W0M)k{8CfHhnV_ z$jSAewb9VJF~5VxQdtOztel}&0-wjdu;><=y{_;$^hHv-r>RQou1}p8tqp1$kZIo} z*Drg2C9s^Url|5F--#=9dA(u!Lc`SgC1&mO-IdX(iQ8AlqiZY0IGB#AGLzTjmzK-T z$rl$65L=^}qXl^x^I2CVrWE9MOv9N1nGq4lon2tR;7N_u$tG1C{yBk9QUmo!pYVQBUZ}eUI7YLju@fYtj-9jE3Aj9d4c{B_E%Wnz!VfjhQXI%U&y2*>$I4yKY4>tAd0@1q?$TdhI42v)E8Z*MU$ z3K&^gG0SEavH;A?%*X_Q;z%&o^1GR4P%ymHYOs5=4vYq}NqwB?uB3yIkdR2?a|eL4 zq~fOON;(SwfvKtKtVN0iExBF3OUp7&@VDgTWJ|@!KYbTFC$fb!W5Rolhg@ks!|?u_ ztX4=P4{17wwYFA1qO7|5z-ov8PslU%XciH4345YP1(+6B)j)j@W@1SH7c}U159it_ z*xsR_Bf~OF*+-+ZlaWEzEkpv>JFMyqs^d>9ia-;(bxvj(aYn%4HzlZFOAbscpV)N68|NA7b^S!BJMPmEtHVkr9GWui}f;J4iQk z)2S23hK`^tmJ|oPIq=gk&4jsrqSt7NR&RKKgGweB3NF7PS#t8=_z$nXjwG`NbJ=el zoG*SCk4<7T9rwD2hxNaC^cpClH-0*Dh?pO$^ok2JI-DB$8?qQKt=YMsN;}VF5h2M8 zu-78CcMc4ZklgB*bYptW(p^`@(r^{bM2T7%+mIC@mEg~u?Pfc=d-__w`+2D?K}Bpe zS>O`n()3r7uYf(qYiICKh@0@M7JwW3xOD9)5=XW(k`))zQxR>sjWe{~c&iLNj#qXghdbc9XJejU8o~Y*z<^ctVE1!b>MRqTrML?sJER#YdOH*H0RXzG z<;tkYb?)jE@r4xKMCT_tKXnRA7wf0n{p=(!bvilK;*oQVd>-?4ztG2q%Y)@bcV)tg zfScEYlCBCwudJd3*dr@qeE9tANB6oSv-Lwi*&2aGEFhEQze#}Pa^_D$^R{UEK;gGS zV{jeR3=-#~Ku;#X2flv+1zApK5#&3u>_YttSxph{o=@n2_G+`v@y|wjDLA=C81T~`fhli1iXM%NjK2a@Oe>axtn>5&W=q^e=C?cm}~bAAt7Hlj1QpINqjIXYwh-z+Ms zzTgYH`_~{QWVj}YqB*sVZ0=bH*(x=z{CkXNh z2VRW*XL>D&&iG`};!IP(i>aKh(td!Nt}J&5_tTk@IyULdzWLP4Rw-67rXrWeK`5M? zB~3dk9ftkgcBW2zdv#oqz+^ftrM}Ai*H(Kb_q%!o4AOY1y^L8Oap>kcbXwo)2j^ym ziNOK>>)L;>h2RFW{1awUzNgh0 z==x5r`YYQJ8_p2RJ%ojWZjpu5`gcMbecl6AS7J7Vcp zc$#}vE%b;sH5@HsqRL|fzC`bJS~CBj&{hx?7J9|~Km8up8q}mI$8vl16$6yNm4BoC z+}FQYnLlq3LZy_-#QLqQKTisBAe8=f1Gu&%;eR+p(M96?U_Sx$#ckU}h3MY^-p{Xn zr%)iDZ3nJctyU(JfK4k>U0M%g)Ujg-Em&{Cai8%Tm_?bSq@)be>k6uo6aFnXa`NG9 zh#F#Vrf$A6I*W^kmNJHo>Tmb~T!+EsZ!uyhqQOLtEnZ4;@|?)jAFmg}21W`?w&z?2 zXVVsLA__`ea~|xMuY=38)Q$10wADwjM-8j;AAYQ83w>wT*Vj++*o;$KMJ~Hn`!mK3 zn;&FQlVDFkXhU+_gFSR-Mqi}eoDy6{tl-Sc&K!m$y{mG4z9_t3LAUR7JQEjonVNL9 zDDl+NQ_Q8CjJ2gw>0-jZX`H&OF0}C({%_X7Wbu*z>FbmJuQCB}7}6ygj3A4~Cgiyj z+4FGfhtd4-FcCqJ*7t+IA7b%l5X5V{RN$~rh|+GUAgv4P>`lB~;s`G+B=z-7M}Va% zVX4^D(umU-c!=DzxIXl3fmHP+-F&J=u@x4Y9}kwS`;xwHv=-u^8HIY=Wg z1A`e3!t77&N}oD|NnAFk-ZURcY|Jfi&p4?M=N*@=h882%sxpkE&PF!{i>_Ksg$N6w z5)DFi<=^rfs`G;L&_!vUnTY+BR&XTuyRrTFmitK9_i@slfneCOZb`(*=uKJk8Dg$8 zfwgpIpClvyD3SAGM*w&XJ9`RA0Lxcsd>68;Zq@LCbO2-ADgcA8Ih?xmwp*Fc7mSIM0ucMX00%N-Y^Eu5IyT>R7R-Ct!!U*r;Fia#7V_g|d09l}z;36CwD zvEHu}(JcY#l)zFH7A%Nf;eC8F>itE@+2ZY5JH~;$6(Uo)!z2lP&(nCiK zgkX}2m1JlL7-VcqOJ+5ZS5@s(Qqh)nbK?f2MphUA0Zlq8c8F-2i;>6!p@a7^_h(_M zUuM!Jqjm=uAqCHz;wrhD{5FcsYAtDij>>4c7H?Pm-*bYxwLkI+bZLlVX;y7rKc zM3!x&KakY()P1qc!2vc!*1A%IS;{^zzH{3Pg;UbMnMmP|jtLt7kEJel%!hCs|1Msl z-HE#zBT5WR8uTcy9BDzPhKS>$f8(-7ivIQaO=p!r}omrQ0h{;54`;Fk(Ic{|Ck-^be;rm-lD= z+o|p`N!}2DazXr@kufsNv9h>xn`+e<3eL=?9f{8>THwnY#G|O!1*)9SVi;4By$MH} zY31?Eo_EKWz7?6Ol{6)S{nAD=CJWvyea4J{&L~NSR{nqAu#e6vizedIxNumv0+zrX z|EN?3Z$r=HEf^Q^koL)bEBO~LVnQYIrd>1_CO316*16KrfI%nFsg7wUZKqclMu%?s zy}A`vwv0oK8yL4f9RA}7f1&}u)wWNsr0Yd~iISGqFs_bA2fj%f7OSfGEHN3U_ ziEserlfJK|aCtZwF-|Q1_&@9EjsFWoMeD$2zmNZ#fqIU%~l$1P3<>T^t+h7c6i)!Gc!TT&EE?y!pCzEC?1uP7jWg8zbfl=*alyir76*L~q0UO30XwZO&j0B>Z|C6h zhbws4EUjD+b%lCZK-In5iGSn^7IYs7So{1R?`vhmVah=T~x+2wb0^Bsm{95EfaSk+#TaY)BmAN=-VvS^EpD@}Pt^ z%F!_~C$bWMD?fN@zJ7S|lN9D!Ny+4n(T{`VA@vx^aoc3z3 zIxfj-R_dzGSHCAYY6j8ZY#j@9)<`6rA5~?Rll@3>|Cjp!(+ZkIl<)X{pkIFDz&QsZ ziJY9B%dlG6kbk&;4Q;c|7<}ICm^WTx&jwK^#pN4_M4+>E?UT&qabCBrrad`+n@xsT zTSEEc`cu@=RBFVCUI|@$mcyZD#*GD%Qi+-MDn5TCqcYzpjMnutaF9;3qb);K=;$eT z=093M2z3?C*m{$p-Qrf`Oax~Lrpk-es$hLuJ@0D^qkD>KS-otawllr?!Q~W-PxrL9 z9=FQG^&YRSTTi*EA~>UT`!*7Rj%)MgWt)3NWmb({dnB%x)7v*=ZL!b%eE#>Dw;_(- zN(qK|Ub*?+d(nR8k@p<*_U&4<{<~{xCwiB(rf2TpHv)!L2Ald` zOt8%3R{}>*gX9B)IA@*E*QYacg9SUhA%aU;MV}jm+pJ#cza#YE58zDwvc@}B4yuj-Rga&w4Jr5d5+k>27p$@?E5E2{yTVK~MRMfHY~2`)3@j6`6d`tyI1{1q|dL~lOu}C{dpLlLavBF&(@t=^++9>E>yjyk}dWRY=Fhu?o zS5$w^=xis^LGf@jm!mivi{~+aYUuJ3&utoup>fqkJ{=aF{JdaWjnJKvW6>3%pJb)) z!}IW*LG;9l6_C|Q%!JoddTS9$=35?XDo1H*JEkke&C*bCgVheeSh_yO835N&sN2Ju zX!o>FX|j9;&+3&fy;Xf)zaOh5bio-K3nx5t!D@tPaupspa7gEJhx&9pNZq?~L+UK$ zaC#-&wpml-Mfy%|df{U#ce-#tuHAk~-WYv(`slWy99FR>>T^T1j!Y^vl}^_M0qkkl zq4(O-rJ#lFBd39)^$GG?H4@`mrvl4K_1@B-_!m5_T%3f5TJ4}tCgk_uQXCDXCN{oE zGJwto8BMl^lCf}b?55%qV>2?MhK&ut6>-A{?4g6l_5S@7OYNkKiEaJ(_N~UihS+58 zb1x=OtixF$xwd7C`<1s&(gf1a>u_JTqOuk$vhn!(Ag3AHN4{zhueIu+b%?W1<4-i` z4?FpNUo9-iIH~SH-o^GG6!^R@O7uZ-tBbc{2bVX=6(f5Mg_Ap8qYZ!L!*Pk>S`N&^ zzBQNT)4bG2LJZ%IcTaJ3KFp&}i7U-~@!wk3ZB$S;ZpN~A4BwrIk~*=}E!yH6V4~oC zX=gu|UY&y>sIQhGhgd3YNEOfl1SKua9Dl>);5}hd$t3i}hyWF9kH*&I5Z+yE-59W( z)O#Wmv!`G#!GR+GlZtUc5WRhu&Sv^DmQu>h@m`eJHQ;*1JF~FxEf}S(zns?C9~n+z zN2*&G-kU1Ym}`pM=~kT87BkKNBK7PZB}(EMEM*F0ot+m}5{H>mUN1?P79AdMnzd~t zR8+Y`cyH-5|5^Mr3I)rF=)JnbpEOj_)?UgQEETZ zI}Zcl18w!05OT7)kzTDg0b(x>Ugy4kIkq$21W1#1m$L8j9Ykr}d$;cY2mAob+?0yQ z7-0n(MFw(wVxr-8E0uuHdqRpMCMITVVEF^qrd809xKOcY{K^v`Tp{Bz0!_yyZXp+$ zBCBIc%CKNq7ae~F-^7Z)=V?Bp_^rg5GsYBGR7lc`#`0Jw>-;OX*zrzHv16f+THlw2 zV3ZMD7v5ipM+vwfJouuh{>kvb*y7in|26arY*8xTYdW6eUj0Pw^pu#WJ#4Uc5##XI z-Pbav|F!T!{=l=ZjKFOIq8o&60C1cp_j9_dw#P2Rm4tF?52;-rmu9jD7h@||48Ovi zZi#E`_R3K|wlzxUL<7}!x;NT{PFk0#bEdF*kG!_~DQi^I296sKGU7{lJyBGc`1pF; zm#DHe2}46DX*T-gZ^E^=a(bxj`XBkq6~VOT>--q5!OM6aUYagWY)iX8;t|>QRLH?#;lOn( zQF^*ETHc2x?Y;%~0HIj^FjsIPC1G?!KbQ8nxBl^H*Fwqia?U-y|2WUkeo2nFQRjk^ z;QhTd#qT%?d@`;a5iRgE`-;O#(|u;lD#QE96&%$1&FmYs`#{pERR+Ky;n>{m<|)X^ zz5^#zV6DOn5_EC`ntMFbPb<$cTu*fR>@>Y~7vzSCtoGHqUuU}x6OCIudL zUlb9~Y@?(3I;0sr61bchbLu1jL`rU4mfa+?783I2iZlYvqCPvDpe@>jqy}Kr)Qm22CWCgB$$DH3=?w?4G%YXdbp*x`j=G3m%Xka_oO(MUbIKxvtDsKKizIa z>#E@d=}mfC;!q@HGc==9Z1w59nG5-7vbbTxO>`61LVm_-dr$%VZ>4a_88{(GHE{kk ze{h0DY5{@E_h3VyZbp$lZy3mC9k1PJ`5L4^CArt){1Bt;U_WuxU|K9QNcXTR7 zFY1o_L;ioM8AeqC^GBXwUgamjQWF{)syAD%XQ>$TC#n@YCj1M#%@0$#kirur$A z2}Y2z^75Srb5+Tlw)#so;H_I#b7GQ`UB(lJ8sOBoXaBO66M1-O$RgY9U-l^FI0Q-7 zzk{?x_cNG(#6S$(dq24Zx!de|zV}|qXM9{97L9ml&Lnfm0jLaL#^EzMe_jsGdYGHP z%#~TJLhHO%d2Ga`pg#Ymlb#v1>BHZg(jsW-;nuU4d;OOE3I{Bo@wP1TY zXbOnKBX!EQI*bHiqYp<>9@8yt&@guUe&S)gZN}~hT5EjWE}Fsl|H6%89(mqFPeOF) zg0sSFcsb0MFKwEZTzH8OoOr;nMOqr++1c6EitX2=yi8SK(GwpU5ScHGal}zJNvD6! zj!I!j8OKWbWQ>R4b~3*EFqV5_4nik68YO2+5epVxkQGWXJblHOd3RmHqej#sC=$~1 zOTF!TXOUi#MYYE*A6iYBV* z^9nH#9`?h-Ba#62)MZ}y^icHA`rT&u|EqpCrPX(77=~hfM?2M+`^(ZS0>G|9Sjh;z zGcABaOknuk=gO~LMD+pf~?^5$p!>zRQjO~w<+(YTxp6S?6 zKHLs`f&1K?TuIHDdEOGBs~%$hyAQmPVe>+Vq;sx-qZ1Z`#9}^y5Y~gf!-P?pR<(35 zRg9SV+nrz{3+aBt@dhodj6W`;4`H(&HXn=w=yv$QY+4b3ZAi9gbg5m$J5ry~Z3>_{ z>oy|=Gb&6_j`4EMAw|?VjD<08UG*M05r!sPC4FAvM{NJ(9H$B-JGBaZxH7NAerGNm zWidQVhQmJkmM(;vmf|P6P<$QZswtLFwh|PS(IJM1_dH3*(B|8y49(WK{v-PxbTTZ7 zPaLt7{!J{;&7TMpG9y>4*JEVHZviWmynrAcpwmX!^a#tu_N#6xw#`mf-XCMD_l^r{ z$s}JPPIB|kJ1Uo&Pwi1PJkX~(6Y$r$ZNw$1;8dOmdX7z4HzHg##S7>bNnTePv1T;Z z617nHyn|fv_|hFwW-rG4erM-2dszX4>y<_7+OswseQF-gW5mMd>Ybd{ejU>va}&c7 zW$vSn^*I4Wu81I`6T~jt(W}=vZyDSvl|7j#pN8sRdkX3ySyu7#BgFA)j<2CywPC#} zR@hNDcIEFvE(dK}6a#EOhF0AiHL+=XdebhwY-II#MmoTz60H;BH2{{sO0`3k&)puvKGky)SZ7n09`92c)kzhpigL{uR=L|F zKI7VaZlsUg6r@VbSWYsARrTdfC`J2Gqr%Eyzj2mnjb^v(9(=ga&87NkMgG$m`ZqBF_a5 zP@|ld&-hZFt=y4YsqC*M2Zl?k*ZBjj=g?~?K{Qyf`QUA>T}(Dfu&AO_keLFydKv%` z$CrvlKDV^jI9|sQSyMg~(2DP~@V)IxdN(&JyxehinPGKuH_pzr!$HBut;4kC@aD^D zyZ*cZsk(uir?-tngc0HEcZ2HV;{nhDad@mrJBm=e|IDq7f}rdc$eg7h`PQMS9$+bGPN< ztfIlHU3n5WERcCg0oTq|5+BPz@BAw6#utC&S~_zwu5 zKn|B1^7kKz0w8K9y7jPNhn{?*<1E@8>?PvlMufvdCex@U`zKc}_2+3^|xR*0*t3;Le1x0)xi}6FX6GAzT({Y1>)*{AeF^S*mC#Zz>QZxsNPEQks;m~F?8jbS}R$wHW_+1rMow5rblZunm4k(9u(ky#%iN62WLBzSQ4qLJ5bOt zKa_$zqV`)k9ea9R!kmNkOd6{MHhxdvL|0N1TQFBynTd6stUO?A{M32r#uG_2ncT9r zWTF2&8P#s0>eePZk~J5@KLvSJKkHX50D-E&ywC8_hG%o#CTUsTg6!4F87DcugF5`E zXL?uLvZTHaZTRNOJ^UvWMT`Q938p0GQbq%CL7LAB+HwBTzo~A$DGfL?OSOc+(QW7j zV|xj}E|+#C(nI`m<=NxGFkQYj)~9>51~UKa8Qf)@;|mZwA2L3k6u|;8I27N7r$&Fi zfWgUne(*z)hr{tp=_E*9OytWS6Ul=}&yvRTGp^MK%VGC$!fWu6dIvC(JNnzFdnQdT zdx@G*Inoy6dY^E$d3jQ9pz$Bf)!s@rOQ$XCHV_px)#aTJ&D`JGFkT$4q^MBUWP`c- z4F3fiqvD=QYvM*`^jOgR%x0rWawz@ohBE;1*_b5%z3=qQ}oV?&1SD!hmAC~VZ*}S%AA|a>H3Q$Cs zp6`IbzeUFf6>EjtFo}t@N*M-JftfAQ>7y=^m+xIHQE_5ciZ?b4U%q?^q1xy`Lm?88 zKXzKfB_g!(Nge#za-sGO9bK{dJ)FNF-Jm`g=SIe3TE$aQslcIEpIm78wI}ISR;(4G z&O+^6f|VZL$wWe&8A)QQ#=E)z5l3$45URK?ilhKh#l;2umpBq)T+yivxRF}%nLr!P z(8zqF7zk82W=Br`*L2?(=Y@p|X#s$Q9LdD#8@zw{w>zhCnEbrUqtT`|5hy^D(?QXd zZDiKsqQhLffl5+H2-f~Yo{VSWzy7C#JS~-$5BFtl|HqPJ@;?&}KKm|M=z^;L=i%V9 zn3bg1Qs}>UpN(RH$=^J=h2G>RUK^kI`Oh5AH00D=)E!unvs(v$M znhtY#7*{)4rTIp{JO0u@Z$UJDd1 z+IPVT=aVE}4N@bi0v774@Ps=aFAgVxx*FEL<-9I=PK(A=IGL*OdoKuR^+e*}%@iy3 zRD|Vav)~r+K0^@5gNt7KN^Zvz78O-GCiQ2QH-vtWLQR5`-AUI7PdNMJ=P8lt77rpc z9ggOkQykkEO|D|e)5ky^>(1K!1Wvb!nbXt8>bL%~=0JU8sgGp%nAoLtbqnd@~70KWaMWKWf+}Hh#3Fre7m(aCt|t)pCaz%eW6b(YE}AYtHPr zH)$4WYGk?UFG^+KlOK-fJzC_Ex+l=g%or+@*_4Wan+{CU$k%<9yaOS9jJ9r*R7DG@`yGmD*cmURiNkX|gG~$oE7p zqQ#sH#IfdH6yI9`7P?-ufU@K?y(TQSo(ZYXp~}T>A8f(Vb6Ol@2B8=DO_hYL*1K}-O5%2W zTV*m@>h|s#XE}p6p)Ml4;ds~E#sDZ})pluFOE@5Vp6K1}j11a>GqF9S8Emk9PBL2PJ&jq#PDB#dwJ8DIHCRX!$q_b$Z0-7-VM^AQw1)0DR#{9azS`whY_fxu_16og zz@eNB0HH|v_)^6@lfDQFLggCUT+bUSacQh2k4J7qwT(X+i0g7YbHVap3t66 z_qrCK6KR)c6i1Nzd-EZ_q4WnDddvIJl`9KxF(|#B>Ya&E58VZ0&1DxV|Ddwv{w+gc z-7!?2v)9j-o&|>9eSVAL)`!gLVqA>*-N5slPnqcC{7 zP$Gpt5uF=G7hrM zQIAj^?ANK(uEH9uuqQDb?_)Fk^>Kc`+pL?sBFYyf=cQ+HzqbQ&`M?sp!{MAsxbCa* z2VJU0i&cNe0M?6v(ym*FvkgUfK9?GZwuI)SF4Ucg`kaLH6{jF{ZmCsY3({%AmF?95 z!+OuVJKpA7Y;{J>k*+{&=G8Sal8oHdZ^_^a`J&>mH7easTZl_p-lZ%&Q0*{P3PYg!4I)3r&%~s+) zy)=9IIPh5!F*k}`WO}Z?l!M-yY$sBfiQp7lz8{v zHI!qPRZn|&ydLv4mly>#HICycqef%wYx2)iySEF30NwsWiF!k{H#9u4rbi||M<CJ;L&>jeRI4`nYPs`Qq&NP7--QXXk4jA){!L6~)`K&hDb6&W%tgUt@ypMD7abja z>e6BcAejsrjgj&30s1O-C(EgTlSP$YZ@39eK2>HEb1VTRK0`-#_#q@8K1yET&)xG{ z&NE?!jb4CJ6I^1ZBj+30XM`rhZML!06oi^Qb6zwZh`bRoY#-FuPx{|hjMvHNvU!q; zP;CHk9X{vKjim&E>4<~r9(O+Xi)ut~q^N24boEJnqW04e8a-LfRGv)w{l6{3fHG0h z;{wve9@9S;NrqN$;yw%B`5^25w@bvouV2?wQ~+z~AD7LK|I9uV`p-RI!Ym-%uU)_o zxbt@96+e)NsvB6AHnTL=zzN$G|P-8G%F7lDEM5OGnskivk(zzs0fDtoob}mRaCe@}@8P&9!u7Zz zP{or_Jf!{$1MygZa~Y^(bMT(IS&3kwTU9cZyGB({RfXVob-Z7ld7rFj<$`7o*JlATc_lk+DniV@7j1hzT8E6F4|z!JzmgGl%RmzuhG&ToG4!s z-TAW1?m3DaOZCSuSR1zXFYui2zNbCf@xZcc8=fsK8V{-0$1Q9EjQW3Ets8(h{qrnKroOxH3!$y}`Me_~Ja7Kt0A$jwx zM}8LJvKG@5KN2dxcuKZxYl1A;1B@p>j~QK1(+wWir2S3s+nc6UKa+ibRhr>i+TPK<>v<@Ik|aQ zHCk%Z>{Iiy)^D$LzA4way9t-1(G43RFcM6pWR3lbeV_ff;mqxgWI1@T4`*~`#ISWy z@CEX?!$p_J>T_AG(<1C8A+I0nl2;3f*Uaon?-NDV&mcCn z^ZMp)X6K}TKhD5c_|GsO zyPDN1Vvg=^UrL^DabfV)Ga&Tfbip0PCftXouV5&6O)R0V4Cjizt-FzXPANgumHI~X zHZ#>{&(!Irf1bB)F=Hojcy6Q0C~k+|9qK=vMhoKMSp6+EI_1281v#$Y2uG@uNo4V_ zH3uu|QTYCt%N0g*i>~1(0Q1`oD))pfg%1@U6}$i1>>Y2m7QU-66tO*BFm}6Mtr-ew zO!b#o+1i7D9%?8d7>f8u=K)B#^``%qbpzH&$$^BX)Ovue@#4hbsAY2(d@9xHr@F|A zY+<%F`2)4<+?^N#^NsL#w)i{=zOKNJ6)_)cV}n6YKN)LpgUaS9|ASFaA1SbvOX$mH z2NSeB`WtrAkUu&(asCz-?G=ON^n_7Y1lo_8p0$hd9$V|$&NMRmOJ=SM!R zFZm{38q=I*=bj&4%#L@;HNH$)?>jHD9HW*VZIW`jF=#Q?|GE?#QcPjJqgqa$3#nIA zWnB*tn9NHL^tCTk|L1+*tSkBilW%`^e^55r>}RBrybA=qx7pIxX)1FixZG7e)x)xC&| zs`dTS)JEQuQ?Y;8rTzWPEOhYqvC`4LM*9Jz$+{)k#FDLXqF`a zrc>iN5;(uDfapSi5~9lW#sVk^zlwROc2Rs_2^c$P#{+V$x&q-z8wQ5j9iCwJ4+iU% zk)`f{;e%Ua-;mOs55}CxOTm3&dqceecC4;xamS7 zh1T8&2GAqGoh2Krc>{m{+lh1|1lucwR|qh3t)2qy+U1lH*GqYr%ze=Q-TfbqQltVaBr-2~@^Sk0*R*2SGC`>B%& zChN;w8feX)R!X=Kn}|qb?;5p<#b~)tsG53{^RLF&H+Ss7j>%VO9MRlu4s*(%kSDnb zLmSnxGc(z95z*l19CWZvlGvS{*(rIxN`ZU&*U$~j+fZ?VF7nsj(MezzZRT@|LCXsO z9u0$);{N$z1ROm_4jX4qR-A-CbH&8PkqQb56wnU^`l@6o&XQKz6_l=YdW`*b^5UWf zhCIzSIx}KgCHF_Aj!dxC?rqLhYQQq;Acec|T9JDYFR0&|xpb&><~UXTVO_HpYpWyR z(;#+O{n{f8gDH;c)2oUsIal}M`BeB}pE>34xvpX(UPKMp?BPhh3yV_V`j-&(`&4k8 zwYg+|d&TtY#g-6(mPo;9_s!bV@FQiGOg!spK5ruJQB6iLI(Fo76=}0W9Fg-d**Ahu zgWK^qN|A{>8%2Sl80%9fF@NUV6z$+|($K*IUR6jZ;7s<-gt=+s4LfZAT>l6>IAukh zA0{gP=^|WoA!9>dak>M@Z2MoDb}g76v9tWn1w>TJ%54`RCgK>W1>$_ zcdJ@AV%@!nvE&T0Qg}iA`bC|t?)pmGVC!`4W^eJuC2|+s$Wr+|CV_~82c35T4n2HxOgF+zpwyH56tcNr5)4{@z>qY!o$htF_e`dB+k!7|jt2a;8%21MMs`IcGDGJ%qui;cgP zoLBq*|4??wicGA@x9SKpmCHYoY*l*$^M%pEA*Yd$k)7lkuFZrrec#6^c}>;w)Py?t z(l4dlFPvzxYKb}ac?P^^q5 z1MjDuv^GuN4C)Idzcz*0+kZ(568K)>A`=NxW4Aebm`~xk#4ILpyjU4BN=sZ0lIE$s z=<{iz>#qz74Ko;sBf^VW?ReXFJ+1b$;$0X?Gu2WuXFq%g1j6~!L(pP5T z8$+M|yrG(tnF1Qv2hJSa&03%W7vZVqh5qwqfo2&cXrsFcti#A_cgUt;{IbPukW+tm zAjOA=VX1ut?hhM1)YW*Xbvq5rg<)5e*CMU@s@D@{f>IkX`t7FbG{YAXdf`0JuLG7E zl-wFj;DKg%KFoqZr|E7(^fDB@*$!^B z{#5+w8RR~cnm#nh1Ff8CQOa9J?uhc^Eee3wpIv8tPm?*1a^Kzguv`_gH#n$i3*ShR zzkBs+v*|7<$JA`$XVk-_%6|Ax9C*Px33Dt^`jRM$GxmM-`1cxW-MGsk;vf(ciVEIQlmLYOz}b(m1c8VGl!oVWHdF$ZjLlD#d@))M-{Tt1=TbFpadf7g zUe-eG#%UslMG4N&PGojEHO4BULb9;#4;MeAc{n4F9@$tO;|I!F4aTdbBcR-Nfo z*#7~l2R>3&EPiQG=;Q_E<~k#c zlcU=53$)Y6L9rpR%H8EEJkPz?pJRG-KA75Uvh{8&UAw%?>(P|LTN?Jh(dHg>gn<+g zudd;M(8jSj5A6L%=`<3Y=A-K)31;GJl6S#S8fJ=D+H7M_S3ssLsduue1eA znny@va3yo$8C=&iMf^qf4eLp-o#IyBg)eQ=fi(T9{|PdA&*hb?GY9ely2U6oPS5H9 z+RkdWn)0O-O)Hwo0Q$;Kl&Q;4_EJ{8bsgUWc+gV^x>t>*fTbnMs@ZsG2>0hVI(RA1 zdT8mzqpKeUWa4VJEWzDJqeqk{+K{cAb6s@;{ugR^k(%{<%?c90Zoxtvfmi`045_i9UeDy~Ce;B94{eDGgiF*@5TGTus?TxgBpn1yE|;Mf@t zGT&3>MGf+A;R{2b)LBi;W2uQjgb5LcM3LTG{K*=>c|P1DiH62>=PX35X-GlN&3Sva z;f^(BILVVqWr>OEg0?plvLm_yY36D9Ji4O~zNYgKw_TGwJ6{^%EoR8+s@r9?xRmYFXAIm=pExg8KG+PgzuR2Y=UXL5m)Gm@mqSsn0COt=F6 z&bLPUGQVBYr7^E6;Y|A5s(({fO1<}Q9@=Y}QK6M60TsH@#+4cjJ;CIM!aAzFt?i-Z z*F$Q}fvtJ4L3=hxPaO`Ygb?iTtj)K~MoaIitx%n1-q8z@%C72rhX0FTF|~Gu9vnEr zpq&j1%X4G1B;guDf_|ZPTO^l^3OShJe4zZ<&S-$rUDtTq3p$XU!xTe=mRkEkjL%4C z{?oE%wRc@eI0qr-t=r*fc{vJv34#AMSIEX+TmbpI6lE1yv+}m-DIsJfES>}%c8ekB z5{F7R@Fx#3jyr>75vPZq%b?S$tgQP-{cVZT=uZ)T2uK?{5NdBYn4di1RU%@-(>g3B z&0766O#Bs+q2ZB%@{uoj@fV*vR|JK$mBqt`*A1UH)%?`ZV{v@-;(D!hB9hC$S?g%%x9Cu%4Bs* zH0RMYrMHC$C*|{r^D$Aoo8F3{J}zd2EZfmweN z82@zg+3gzc?Scv?R;jU%G5$|NkF*Hhx#2y&PQ<0O;d3lFty`%Pe){;&x!KY8CNBvN zimEgbo_3M+dDYtOT{B&li)~ydgmjK8KX+vbZ+H2AVML_kX+DOm+BKcN;08l8g0Hb; zz2MQ=4;l*wSOG z&`Ck3;{(FyE6q0#sw#9Z%c84e$yB0l7(KNzYk|YA&bkG|`37+B)h>*<3NaD_xPq>6 zBjZNTQMpif__Caqrju+Zs1O2jmqxk(pAh4R-aTyC-U3^|EeU$LRX-el zj$ei25@e-!pUr2Ru3qNcBVt8MDV_TRNQQ9qa+9JMg6FBUTx$!#zO6ya+DRKr3ZW4b z`E4WLTWRZ*tuNapCurJ@S$N~5n9wu@jMXzrsO<5mikieLZV8eTH+Y*+YodpSuV%T@ zRz$v^T|0vB>R7{%Ed*K*t*p9#vfCXm#*V*MX?}RZ&Ye%ZBn#Ync1pvY-27omyqFg~ z>x=9`S10Xju(Z*zx) zJ2!1Gz|ExM>y>cuZk2+oybblJP7^O^4Xu9fKVsE7{j9_l;X+gvps zVga6L1FrcYji?dO_SZ`Xd8Wv{wT=pnpYwdNEy>qsyTQJPHaw>|A48VS>ubV%iIT6+ zS0`E?W1YWK7vfF+u*E=;e0x6Ca~YQ32wGqv=(XL5w9=hKXW5ywYc|)TX=Wg=M3j4; z3qMG{zdOOjf5f8+j%#nwDDKX;M8f*vDT%`NU{2Zq2V#&&H#GOnol#b|rIxF$Ll zD;a^U2M)$06IYWVU07VYIP`3*kX$L=jQ90$))Zjw^!G*mL9aiW@;d)(_I^{iNivfT zlrJ3W`ZU|?P~IYVkaqXvC^qvyNI*kh3%h!f4|+-P1%Xc127($i5| z#q8>{r}k4oyo_7{A#+SspD}#phsZd1AkxT9E8ILP>8Zz$_fy~RUPbA11-(~Dma=eI ztLgEZ$z2aVC?X=zN+YrSf)GXN$;aWT7POtRZU-A$2i;GZ=l(DJ0 zwG1eNokBE+EGUS`1$Ic9tX(46HVz19el{P9U}8@D&S{y2)P-lYDMXDBDnxlrUJC|Rqfz$yeFDJk`Dd^F$B&eE{}pxmPd*u&kuesiQyc9& z=&=t@KO|)Sp@s#fEePcbmxofWnCo<;pbsuxPo&~lt>NVn?*#t_lK`#3Z<^8W&)r=k zpsVH>`cH$X0%F*F%3G*U&+L{W{$N8;t&i<}E#=e}XE>l&NOAjbT3^3UMujqvCWwp- zszT?>!92MRzYNYgvZfc$o1S|s3bXr0beEdYSugx8%Revo+D-;eZoVt_F*T$->*i3g zBVLZ!CbcJ#5ylVL-QE2ch9{0td!VpF`IxJ6(ubGJ0D_8OK?|;Jps+=hTBz;^fCL zlC%2&m{QO$g4gz(B{h1?Rk@Z1b38BGDcfO2>V#=<^UrsKZWvcQJ=dm^!_qo2b9(1fN%Q?r0l*zQ1~767JdVgJcwqQzzT z-ZxIuio~u$fOFnum|!zcx%4By^Go~G(WAD5j?Jjt9LGv|pTS0FPRnk;Gu zyyQlaJ$C6U|3B&?8;X~{AcYfvc=k;~#Pinr7X736i)Zg*V=kvUJ*dp;>eo2X9S2r> z(=TTQ{q-Ha$x`E$HJ6Mpf^6n7sYxugUmCq2uH%aPZ^@5}XX>zhgnL&v07{)qEB$nv zhj^|tK|a!@F9kW%6e*Szx_vwuZFaa371mk~(Rgw9_dno8Np|Ci;kH;W+1al6Zi>MG zy3i~YU?tAGG1PoGfdAPkL%CITa|cX?cyf0? zlw>0!O@Z##2#;3rgvzGvq+uhxXcx;=7Z_{<{j%8U&-yZiH{M&s`o}bx%{tQdbWLD) zZr7aUO*VHkuMg)H(2Wc$uAbnXT&~ic50}C9O$Vlu#GVY6sG#7z zx}~1#t5MshBgXNai&mQe@{kf_gA0=hqM=0o)WBjAXZ;1`Tz~fw4EIspUE`CAIo8<0 z9@H$AqMzT0vS15Loi=g}=RRC9=SrT42ljxST+fxUubuoJ(xl&>9OTtMDaOpE;dKCf zET{dDw>zN?(X6Tgg!sKuMU$hsCq6Hc(H@KlXIQO1how9G@mOSAZ}ccMKKb1iT~>=+ zX?XuD`hBTk%ZI38K3>^y1M>A>d3mgRG8kfCz5tT55&nlmlkf#U z0z>|`+o}%Ir?-Xzr>OLXi=%ArLgn1Y+r^?Q`WO7ktVz&atY^nfcszZmDFLqQ;FP9S zQx?W19}tnQ^^W6CD5`~0)bpCjdj_m0ZVVb%lr3^n?sI*1Kyn_1a?MCrX zeL#^5#j3-@9+wl-(xM2?@pf$5(;oiGcEZRL9!otv)vGyJr;+uMhZAkPz>Wm51TIhb zA}{EsI_nGxcn1$qIG>{D!pv6C?=cur++3tk-vAWhJ!KO<5ZY>Ns+&|y&w1r*%JdFY zhv-fBRig>Xc^r?6Pu^_e796?iwopl1hzQ(7Pdd-^wnm79!heH7#~W8$!ug*zzfWgC zP5lNtjftlIceK-#DJy7luMNU1FXUB9J)wWh3I52d#m)6A@D?!+)-04mPK>^Hc5szn z^^ZL3cV7QSM#ZarKcjEV`<#!+O}Eh-FYJ!ZAMw`GKXF9x-xGsX(>}?#3f$o}IGHm4 z!QUk0qwW;=;d|sV4Q`N`vC1HwI}R>#p)OFme~OIJ@DXU4!UQ8eU#j{SiS%MVNn^Ux z-=8Rlc_=kH`W)+dPnedOEGb0k9ej6^p<`3R42VY+kI?_3dR-%r`6J$4y^Jd=psXFh z`T&V9z?A~fRi0Y_r_nsVelM3hR(o`|TZdw!ZOKyI5Q&RX37Ieb&G^-8aBQEq%y}!L zWlmnvrQ%9m9Erv}-s6GRMi0U4Meiv8Mk0IWcQ=-}7uRxp%HPC@KIW?to|7p@M1_H5 zTe&}o$-Q5t1cw@7?)po6a>8FKQ}BbKX0jgQrX4o<#p2Q|n`lcX?n@k6Di*Hz?JRZA zHYk0k*B_9SL^e5cv#hE&_3U$)P`$Ek!q2xVj~}KFcV~Q0`A9AXObgUq zPTnRZ!+qYsF6Z&DZsuLA|AFGDz!dOF_#`B8x6vDC8E<5Ww&~3VxI03P=yF$~|HUp8 zL3e}b*Wt2^#V11C*M4#Hl#z)&BR>qfL=!hp9)bX2ak%;dQAx<3BXy!wS?Ww0$L{4> z5Ml&3TxXl1pRO*M9FFs!;pf_~Tg3fhL}|cM_xg!PHG7(THtC&^rp`-6SpG#hz6$S< zltMfbrfX=(P(K0T-)OoJ3)r!nL#(58S56wSsSHXw`9BD0|3`S3cUeX%5?brYH{?XC z!$3xcYRDxFp1~*_@dL>{b*bl_$-RhV&O^3@3V#h_CRV8K{{$t|(mW=AArF35S`jO< z?hHzDMslQ={;rtlc~I{fp}!p&6l#3;j+C$WEMdIG$eg&P=#M8bfcDZ~ZNJHHg~EN8 zf$S>xCY6o9>uQg--sCj1?x3o31xE@?3sW2poB+~F8)#I@+=evOUn-&;RhX}C6S-2H zsVS6I5SA7e$u#;Z>+)gd7d@E1P+ML&oZ}xS0T))sWA!8sOKAfGD!}kY4;Udxr&b#p zMJ@^qjQI>uLxEU;8_*6=KPu=#e*L0obUX>yS6Ots7`A83(x&u0xQ8F&@Yp(D=06`s zAQKw=6{85LlE^QZo&BzYq8iZ5>tl_~?GilboKQiylQ4Daq;rtp~U@LA!= z?pU6XUALxnl8~I&xI=DrI2MVPe zjlX_u1oR5uZbXEo9a`@oYPf?1C-vR{AiTpyVIT=VyB>*z0Y<X_mX(p8fi^p@5x_?XHkPL#F?p z4(oM6%HM1_uFS5ku2q``t0v@x${@=HOwYGofGI14Iw>jOx+ppMR-hH4lc}5zxs&PL zDfX*V_`bfrwu38O73_HZsPuFhCfwo`}9kIvOkvSE%L04Yeh6r^X^nuPRVet_fR6)=F8TTC)yBnBuR>g#}I`n|0!U za|H+;E$RrswTQ^bom)0*S1xBxyZ{{_CN)(m`*Ro*YW6L2C)1Cxpmrvyww~JdH7m@B zotuXWGlH_&kd+f^Y90cJveA&)gYG@MsH7x-Q6Onuo)i-!Bq@oKYy8IMT`WBkvpc_* z^({UM96%6A9}S$`>taFyrh=_mtpdNu91xv%&qgIAz~f?KZf@K>K#J2N%WFn9*&ir! zI~;z|)FcMjk~;uNhHF~@nyXekpa=`LNY=MhK_>5;_kMZvuWt{;AT4g$r-{jeDUZNe z8Q`{?Jjq7|(B&x0eVx4*BsI|F;ux)CL(a4h)d-tX|xmI`NvVfKmakX+ku3 zfZGQ^y_lGRDI)E;qdULXTt4tt%0OTQtXZHRj2{zkoqPqUF{K7Qa)if>+C8joF%_js!K=BH4_5GXMbzn~Iv3HXt}6+crxbt=w>hlLRi&iAsKD(ltb zLGp14-^zc70Qu<`3=Elw|CcZGm){=_rPCWu4sLpf`1I8rIFb(yE}YN%^ahqnT@CsT zw%tAXmEK`y6%~b~E%UQ*B_F2|qfGk3nTg_zvikOJkS0p%Cc&MB3UM3CsVT|S=fY{A z__8LV+_`}+=lC2unNA;`@^$+T&zukfJC)-_xKnfM>gq73u5WH)B&ozG-ng!6VCmKH zC=_+V77En>!|oJr9A>=>s~@m*xvh#MmmY+o6q^MRDoo#GpphmIqTe;oMkh!hkovt6 z1YU59w3+&{0LkO$?8C*zxaDJu?V+^c@j#;Az6n!x)nhBOq9fM%i2l2W$GJsK1l3fS zNUu@g&YW9>O-!t+sp7;TV+(m`p{LB)C3uOcQ>6iJQiFPU_=q$x&L~LO2QcxA9!(Iq zK}V6%u$bFb41>x!THNVavwANJ3v~C4N`iVfoZR^hhKvN?iySOsSI>N}Qi=VxdErdh z`~HX{wSSd!l}&1UIMvsI5WAWoqpl9VlSv$_T>O1wW1|&e9%dwWc-U42!0{C(f9>WW zF#hEi6IIUXPby-WwFi`5>%J|UE?wp~K`?xLd~@NzFVS^(-@LdJyt3fs&ru_mG3-<* z*&ZoQo1EH$E3^Qw$VFR12#sc|;^m{E=+Y|GKGZy0MabtORiNXV8v)Tv98tpmm2ND> zYeMaA=z&esTBgTj?2&C71Kutl09TH}oZ1iDZT$H3G@H539i%m7C z1FWlr1aeu+HU4l-O^Wlrv6C&@QjmvaNq&Ll+tfjwdp8(&kYLfGZjLck3{^~jtm@VE z^>tP(8F2)(HV+ymv@B|lLzC*kH_BY&B#IcZ`}_OdgM-dmbHKvd*e%ys(f^k$f?%fl z8u!#Wpi`ec$Z2gQDX~}3F9t6wL3^Ypn6U?r?$9gLG}awAjzg9uHfeAYGWgftxurSr zO1r!BeSE)aXGTz^Y;Wqq`!m3s1tk`$lL>ia3||z-=UWbDJmA0!1JSp2k%7r(e>F8T ztz#6HB`cLIp0j&&v<0vd8U3eqZR)2pX7q046$;Q$N2v@^KNmn`+$elKbY5D;H% zlC=uNv2^$6rrmPm6ms7rA(3{?0R%D9BTcb7w5~2$`RK|E;6oJXFhZ~0x>r9W zO1?o0EGiUm=O+Qon-ShgVSsDTl(AJ!B{^`X8c*jwFa@t=j_y#;;E*RuM%S4yfWdnw zCnT5|jlFn5O^fC@i&Im=EQ!MJMYOcE6q*(@YpomNGGr~ zxG)0>Wge~Rjg8!rlYlCCVrfZ=CQi_q9z|a}i7HK3Ican&xGYc%G^aVYah5SY=iKDv z=C6;XsWiEf>1=>(taj0pY|8m~N`CfEiaYUpX{z4dL{4>0P1N9))0#g{&%NGTDrNgP z6E0bz!Y#}9vh>Tx+_Lm_4<*Ht_Ta}xg@WS>|5vV~M%%1$WAX^3RN*lBSfH1-!RjMi zkgmz(2tVkiO~P%zL+^S$-{I5E*}|yhPW%a9pzRE*+ZI%JKv#Q;gB|kn(o$VjBE04O zo3iw0%2NK4peO<9@U&yK&h)f{jf~0gT>U!u_kKSM7rBc6*wkImMIcbx)xqrK*w{xo zJ&dB+(rz3y=B5JKwQa>%2YdUd{_o}H$;-={&u0;y08K2vpa3$bZ=U^5*yjs{AXRdS z$-G))mx?KGcYKR%{+p|Nx9?SW-wH5~j*hyg3)QZVX?Th1!_2`7SidZsR2#xwTWwZU z4+>}6A^N|+c~_0hE``y_WMpB{!vvV^JV=1=o;-li@I#o)&fb3Q;tsGS5hC@Yhb#4H zC5h;j;|>5qZo(jx_B&rQb~U6Vb1(y3J><7N%ssoLv{Gq+0o(>#0@DG>?doEMImZ=f z#njh9DZ%N~|0bT$>8-$Xzl_6OQcz1Ts{B%XYc}wDC#PeT;bLNgnnyK@!ev=leT$`g zf+u0Bc>{VS_#=p!9%}00q&59wRKT+xKs2=aER%JRG)Ih=SJzBnjTtmW*Lz_TcA!qY{jA3WjA{N>v^&8B!c&+CM+%kXYv3216mGzCgep3RCXU&JSm$-d55Fnios;>Br*42iJ7)hjO)D}830)u;$4 zdcK8bSUCEG^sfZ)GuU7>Z5UuADmOXMOQ6&FF)q-Ib|-$J_|dI9R~z;X33y&yT7bku z@ut1j{QS->Q*hz~VqoX5Nn@XOZDTa~d^C=Wy$`ba$96mCL*H2d+Y@{O0z`koZlvi< zfqpa;-axfpjnUM>DO4(W1`?B%PS|?!_fXy+_uQ6D6aa|Fi5HlC2MkFByzC{ZI(=Y~ z#dr3ZrQG;QYHDh_HmuL@2!Y@vNflxDqs&pA}ivl%tATZ9jPa| z(~rhyv|XBSFA{MC9hp4I0b&*;o`q2)w>%<2My~dX!J0mr}S&h9ImdcIHM$_ zStE?Lg5so(+})0&H=MT<4V6J|cfzQiI3L_CAH&N8uF)87cZ3kpl}%0-`?NxR8`gh_ z5aN14m$?Ve5;89HB}(jnF!y}KZ{@m`T;|(`POuvTb9L{KhG3W_!SirlFyc1Mvn4QkN=*Gac2 zHWAH~WjwCUu!j=|bLqhq^dw;Jradu=J()bNjl(KqOUs=g>a@8Qk~bAfu{$#KybjRQ zI>38CLEObJAA;QY9f>&XRzb-WVD_dWY@Sfm??`uDYWzB*<2W!sDkC8wm@VWlE&#cK zYr|#_fipn$ufJ*p-_|t|uQ%)M*q%fjuLUEAZ>{ajT7OLK)K9Mu2FxTqHi-d2ZOJqQXH>P-EO<^oLD?JKnETn)(d2{0@no3 z^`u?QCm>M3qMt9)-(?1q;7ZWfw zDkKEx$O4%X0ii`x&|6!_^`nwmh{IUptBLLN20_!+W+|%V_LG~93zveTBItp*LW?#$ z$vm<9Cm_Jk#L*~tE5a3cfAqS)cd4Gayt$Fn(uy#~#z$;A@`XQl;sv~>CZ2@Jm^Wi_ z3gk0WEm#sM5+x_5r$u;)%UsMC1sc@Rz_tAbRhL&+6&{^%CI|cCWv|88&|$vd^d198 z4VM<6-kh1y1+xRyATSDeBBd%o$4Zz*OpY`3TX491Fc+&qMNL!SvwZOJv4xAP%SYM~ z?gP5${>{=>lGk$5T(b0wXju9Dcd9(alV=;?t2{zrI%9LbX4`PC zN3sgoW`eKK>`4whFGN6B6QT_V0iHYeLdP4yH?3hWTzlV2pKd&NlBQR-I@9k+MW4>N z!&x7cJzvZpjewDI8w;j)!51_)>bA_YFwcFn38_Qx1D~Sdee*J>E|yN#>$$M|4bxVihYf9PH^iEc#w<^-lV1|Dk9h()T0K}jdDacxKn&eQ zD|c^6JnjgO@6YRu_T6H^FGp}bH!svX(`8%KB(CrRMh%IKE7mY+_N^O50>cx^_PQS1 zpewuhr5DdjB6s41G`_%i1K-QSguDLUmk^G!#t_;vKELiT9_RB`B{|Ri!1}F9-XhQi zBLCeJw2JjG^KCTPY5RGa@Wr3GRqD?zcvyAWoC)@prXF!KoTUwVZ=B`Hj~-4Ox`Ti| zF7mZG5#k^v%+D}z@8}?hV@X1(KBRddW^ilw`GzN$?sv3*UaMQ zP4$XXbtX~=*KQvA)tpu3oS_O()UbzX%wwof@#*OB<)MwnjA9>xTGmx{INmxyEAd!v zT-<%x7yOd+g<>q6D(y$MZ{ygTxw1@9xl9TCp^|Slky%6-QSH}wvXxkB4qDOmF_?uS zW5gQF5&DyE={bd+gYe!8qAcOF9QP?Mdw+)k@IrsdvRH9JP-FH`OpH>gn0{($t7CfRYyi%qza3mN zfO9PR)4^7CZLKaYTwc1z{kxlmu3n2fvJ(L=7!AIZ=kA@K7yijkqb!Ug-fCQTBk5JO z8n)`lZ72+_&n^u7?dXI7FXt~?<~ITohdv?7we@J8ChvRc1%h&eM^R`hy|U3QyH7@~ zyTqui^94qWa&kP-8V{-XU0-+_?vilkYM*`G0KWO^fon>-2W{t;zza^e+NQV2$$B(~ z^qON4H%O8Ki;&Pfn z3}u&Y=9)4ZsAQDyyB^=Z;WTcnv&eW@?KXSfFg3Fc*J-a`q5QK}y4JY10USB+1M>wT zhVoO}O$^xrhq+MH$~gcYve}?Zej6nb#ioya;H)y_fG(mir4V5i7O&i z)>Lo@v<-}?+8aKZJhJ6Hft{1f8AC@e6>3IMouG0a63r^kCk~(o%w04*B3ey`=FQ@# z7M2SHZ&^_aDohutMG5aPo1>e)`bvJ}ZWn%k^>Mbt3C(ITZ9IXCW*jQJg|rBG~}4?^vqW z0VPa|F(NYwB@3;4%*dZIQ%hYy9FsgwOmWkZ-O|lx>M7+|3`_9h5kdAJ&DSh~F{j$M z)d^i(jW0PA6%q_sRr)^8^u^aP+R%!!C7H1!f7bCBcjDD7q+^Ty`h+i=&n+TnpE7_X z@93E3Upe4#D^U+J~s1_laOjnf+^1cEww^=!DRsfr^r^~Ay>8=A1MII_7}JG z`|9D5&`Rr(VnGfX(U^Yy-H4lun;OOmb&kO8k9^=to?WpXpt-YG&i#`paoDF6)(pW6 z_woJ&5}NTd-u`;5H)-)gej$_sA~53pRqisYS%}t+Lo>YxZ3KCj9s9SMy!Lz~O%My#|We^MDFi;#H?|tS;dUo?9 zRi}dsEaZLPDx2rMh4wMiv&{3E42k& zklOHb{=%^8n#7c=i^~u7Fcrd{_tH%Rt2&%Y8`hWv1p~aUNj^I6#`*T z)*&}rGpi|KYI+bk$N;)sN95`md((WqE@8%fX(b3IUQ2s$I1eX~&ghoS5122v=Sl6S z@Srmh6uN@P|44m%(86K65`6&7=z-d`HLah<%novK}>Cg>wI{pkr#7X&zMLE8O^6-fC>^qC%QI z(2#{(H`3&V*3;<{_6;EuX<6(a-A3RUNU0f^@mdB}5;PV5EG!p{?H^4hr z-MawAKNE%U=+!BV_;dk(1Uir;!3Ait54!Hc+2bwlCVJS{nEYRxAdAm&iY!8~a>cP0 zu4yz7q?VXeu%fprz44Z1rwhDFzi5a~_HYoQDZ$p{90fM$Hr6y?m9Qn&3pF!-tflp5 ze3Ma85oKhkcTH>Hq5n~12cyUe{UDkr|VbiDeOsE|g%N1i$LixrLEtI6JK zMA=^2nEunv7@70hx)xL~*>_z4aQj^7{Ph|w`8e;z_rgN8ePQ*r+v?22?K&4d?#IFR zF9U%mpwR42rHaduUg!Nn{ac5Mx=VrQ1hp3}RHYKmki<{u2}^F2txcx}9v%}BPA6dk zlpeG8DXpt~W&BtXG{VW-aJaL!y67w zwl!_=qtpz}8sN27JE0ZNTDNp9R6Mv&(rl@h$r;vSc1Zep^*S`^{&nJiB^RrM%NgED zXNrw4H9~VaHcV-IxpfaAPMSp!+xV$aUq!fOyu*DGupVcTHW*_bT6LmsN;K-cF`!Y1 zRzy(K;od7=R>xVuHZ55~{hD9cpiy+K=61Bm-WH1_R}@i`?FwHqTyo3z{As#^JUnro zA3h~1#yTH$7CZcC`olEWrVF8N5N?Peqd{&`e?V!0ns;N916Db{OhW4=Q+gVWK)P#q z!!y>H;fIa0GtOpuIDWLJ{@{Lxpc+4=}{rY=^-o)c7yg)`yj=wTpPi7$T z0MKI@#gO4`S20W#0S?b4B_)2HI2UES&+=({oAH!&HmxQ zW}FS`GTSG$%3q;OY#>PE?3n+LuD6Veb8DgoAqfzi1osdUoZzm(AviSdgy2r&65JsK zcelpf-2w#f#+~5q4)f%`_kJ_8)(k)TC%yWdsyZcm?wwrLBD<*i94>9|t z;>A)DTOgGE8g@gltH`^cU_1F3mpZRv#<~fsBx({Tf zqa2E3#A|73Ne?;^db-(2v+pM~p7-WocumnOrUi&u43PVHHnpwOJkjL;)wUQQ^Ek+h z^Z?*9vCdX3oVVA1g3}5WLUy-m6Q*9fi846hoh2mO8d^IuB2#|8PF<=USlE@jPSBbq zlAz#@q+b71%>(pMkl4w-uUu@L-+PeyHpR?SZk<{`t$FeFm1YZ{%I>sQ8^1%3lmOO+HlSAD9&Ofg8v+cdfNlvyP&kp1cJwvN2Bs znLK@gaZ~cv*0%&EefbY>4FRI@S60Gh&vQ8p!5af!K0bSrU_hp=8W>S=TFqG_fCYvPB>uy=+Okj}nIYIyTct#L0HNp*mpYZOQ~84&Z1@Cz_nrVUY{VIIOQiuZZ{ zEg&tXXa95^^G-Tu{@kDJaA0bw5%IlMp!8Sld=ypQ5b0S=Spr;$*I1evA$ zw#@a^)eb~na=o75)8Ul#2Ah|`_iWU)>-B^_D8hcFGTvGc^9Seq$|(sGpy^q~yCe#W z(R!%YM6cCE_lGFEfMP6|_}@A%(Z9_Lqx~%M_Z9FtxQ5@0SJy-CENfWiHJcO1*L|hf zoKtf)G>V*Wp?P-XlAANtI#4z>vf}ed{;)kPr{lA2!a&-mS}qdeHKim;$}uPUzpxzp zH7dn_?Ci~@xb#;Pb1in9kJ;E?53NApd}WAgU~ydc@o6qU3JG)EXNkmxYqg-rjdH>C z_nPs_DEXkKk>l4JbY7TBdnelE+%PS5PyvS3M(Su`RizXgw=84bKIx__eUGgRU&pQ_ zHT#I%2*D#Fk`oCttji(r!_6AW)vlymQC9ilzSwqnjU9N5QUJXKt#h@i=^mSid2f(DTmoeGdzp8e+nyXKfAP5}6)MNI0$`>$rPB2c;~@KdOz%X5_M=EMZpsHbMwm)rkLlfY`1Ft z6*kK2TO=CTluUTlOPYNPi3^VCq^w846Dj-a&_6^^IQ*56I@_btVIYus#J?&u;*Q$Q zYU=~U1*Qj~MYVL`A6Oy>3m=64Yqn7I1|;ofN-svK7(=rZ^P2?aI;6{)BqdCPN`C|N zZX8!RTUvvQlx2q>&3rJDmz?RpZ&m6*MFcSSkc8IwXpT)c1;byf)9CtjbfYR^RAkX? z#{ChKytE#E3*_pfgOK5YOFAaOj_4n6az@pWn$}z>By1ZkKpVT=_~%{O#YO<@BTdGPPG^2R(5X*OBdlYfE|-EY^d+{4ECI4&;J;7%YZeODQ#2mx z;8^EzcsZFu;m=ZmzkbkywA6xZj~t^me$>_EZ^tQf3!36fE;a;|D$){wpG(j_`#RV` zhNF=Xih$7xm>WoN%|7rNZd6#bp>aov@+MO4ps&|>Y7FJb&&bW5_Kq(y!!(Z$E}1#r zhK|q7G%Vc5yaS&#`ewcQE}FX6wF^81GWz=DRT@?zPx?3;8w40PH0qgZPjpv)qvmnT zTrG&NDTe+ZM}1{%6S#2Xu*CxnuzdaJWq^udM5C__bmvEZDa%BZ#0;*V@?ji3Jub>p z;RLYG_$v3YkLR;jC)zkiGo-C73WH^t#Z!{-LrBk!-<;SdrPrT>*?Pz6dKAkz*0-!^%9uee>S14P{%1Hy#8f#Fu%NBv@vVhp2T3KDi4eWwG^Da&Z1e1x@t3o&f-TsIOn})?{>e8NQ4(b3Ye6o8 zG(Hy_TC}tSMLW8ry)N^7pg)R%(p@-tbA=>R0`VC}%Zq& zNQ|fktc+&dqECfmK$9f<4#(UlMc5JUi}sEikuKZKqEQvWgjrR!gI`A`TJMWL9_N3y zFposFIWTt>FFJ#p@7&PEXd4ncSAQ) zNxs0&c^dTx44!t4%Nq_Nm^NDJl7(T}ggv^RjIpYH;0AZnJOe3{g`7@b2|>#c(BKyZ zzu#7f6nigBAr&c+i;cG~^@Ep(u1A%o)#u*WWCNKxtrKW3bMM^7)2p8WN-y%=ArcBN zPNkKt>M#LD>~)ihcPR<7LSPcc2Vn%k9HH*$n>U*An{Pj@xq9)tl(g`K_)~e90kd=k zEkHaAFtHhWHDGW~;&n0MVJ7zX=}2POK)&jK%N=F%tn%?|+Gwje)6Ed0-bOMvoF-d% zZn{H!uC|<}XLsy5mMlW?>CE`V@@Hlou|SYvDn(M=H*@``0CGxW10t#d^Pe>ifB1Q- zGpZDXrx%xHYbMYrDmgb@jkmu2T>g`E&6X49CPq5Y#f$e1?rNwHZ)jGOOS5MUL}z%13ErOWatY=ceJ$!);>ceINzj9R z0ahw-)Q@2sF}q;E+LY3Hl_*BV5Q~qVdUpJswvfzy=a~w!Ow}%~wyv0l zmH94NObdL&UqLV(%&F@qzKCj#Hk4;uw=^p5NFX4+m_8Eg!%4m4gs+sgCR#}nj~CEQ z-%AOB^oPDy&L;w2qv7_;B{GBc(c}j#a!Pvp41%n2wmi9qvYpaw&+R0fFudM1Z# zBC}27suSI)Bkx2W>^Q@47I8MqQ41m;m=shX{@wlg@!ApCml18bFxNi!u#xT4$-BzB z3LbyfW@ux&>&8^+RrYmABrP*vC~n-%;9q(C&CF!@gzoLSe7eYf?orx&ZM21lEwgkk zDd@Avchhk#)I~hgfosX&53}cdT(f^5CptIBsHz|%Yq253=l3MU6mX$06#K*E`d|Kl zT?oCy)ddFB7Eh{a8#UFDOyAS%S-K^Pm0652Fcgr62nbmvf+mp;baDLqL9M*s%f=m5 zU(nA*xdbPsmm$07^aK|IcGgIzfHWG;TX|VdC+n=`T}JTqMYExM#`>O5(}7pAHxw)4 z6|#vacJKe6*=tpW^Jt1(;5L9h*8@ZP>b9}nsr=Zr^6^W85^y^#Os0 zS~eUGx1T&G!>u!!zvWglE`MAgu*9ftnjy2JwN_pwJ-9IAkuSC0*=~6uYAq7H;C2%O zGB|>qS~J?}&h}S4)n*lcbF;!j=x1i(KP19tl^n8mXV1Y$AxHKp2s}}`)`gBi9Wa1?T_cC zJ7&D0UxeHc@JaQ8lW&Qybvyj#&oK=jnU2?Xn=;ojN}{N**HP3Mo?Y5I9uhqtVmjZZ91Kh~<7w*)S&H1~oy4;R*HbGnwo%?RgsX9GEG8`@R3~W{F&T-2Ewe z-og#oSJF02mZ2yuF^reVB8+2IzRZ`I970W%RBf84IjdZQC|m~&83(2_hl*vlmEAA( zbh;_hmpBEx>r`cVF2|Sspzf5qKec?$+Wtu=ok!7qb>R$Du-X>&c34PqzclF3ar2tB z7PP)J#2Z?CBksA@JZO4M)a)Y1P$>I3UXk&|M1 z+DH@gxJep>`m$e}hz}0$Sw=<^8kyfvPw{wn=)Za{B~n*5n*xpnVTdFvGx#!36o z(wKHDu<>}TrHtd@4%nb)ci8iKkn%D6_8>RsML&=Z!YiX;0!=UjglJ zsE)U0jsHOK`snhUxcKq7sMvuSQuO)X{E3chb8M{o0GT(}f_u)Xj^(^dir6s$+ zs4JIWV+qgAC*$V#O$Hx94^puW{fdS)SbJr{j{dgPVf;TVz^BiCuo&)P(%M}691OYw zs*6hi-jc6q$&fvw_}L;Arida_A`0z-6}^KMwG5+walv&zMt_?YHKyv0dCj3$;XkI{ zXiH$QKr{u-n?ih>gHm;zss_L3y5zJcm*%nB^zfL3Bv8m`lD(Sdr$D#F^DCxHYy+@QY{ z;hdCoQ)1BV;(B8LscYxfqq~h+0;CN zu8^(xS<~v8xMAIu)YdRLNasCL%$fHR77Up;c7Dr+pFQR2>1on9A18=)$gvNvVp2^j z8x7=+K18fozFgMI_(=tgG-r#yX#&G;W_ZbBCX9Z_dZFLaEqRI+$!A{3Ve{lwyJ=k; z+eu;W!$wv|brpCdNpxz0fKDS`5w{3ISKHMZag>h_&&G`RjW2NJklM>7$9`hhW9dX4 zhtOAr#>}`YJzkLm8>^RiekxP1251*w{5ekn0HqI)?|RwU%3eVKBDi$UvtE##rQd5N z=%7JPki{$`Ei5U46@80m00fJs@$m?pSA#*sy`4wpeLZ6A+-7|2oAxyNn%v`n!jGxW zv5O=4?TxWp)zT%a&~v}F=QeHM8|u-o+S7(MtSUMdliVdSim;VBKDX8W=<2O}y=7-L zg3K3%#@Nq0t^s_}ug^m#-A8oXt(sj|#tydT*AWU+M)AqE8u(^T`nOjGdL*Jqwd-r_ z`@(fx`Zb|&uG`}}`T`AsE>~zoVd_&qmPTu?m--G}I%FU;6pr6I?60?4A9UA2{?Gbb69%mjMnCCHR=5tj~- zm9Tabw9SW$tkt!d<%jMIX#1vI74DWDemrFI+*VpxkUgXysjVwFG~Q1UaJQNT7d2CF zp`;Hj&KR$f)QHXzgKTWzcq_}8;!2e0k6VW68e*`(X4r(T3VGP_+`d2)xN46FSw5H( z1l(%8p&42(0kz_5~4PH zcGw@&Vcw-4!(= zGs3Yp_bU0`F8s6NczWx}Ne@HYQRonasi67Jl+zxsIlwYawUW zYas{f;OW`cllW&t@l%M=m|ud__%A|&=~tKeOG}9sNykzfP23dps#;<3<2|6SM2$oz?9n=0*n$ z)rLu^F;2VI(8brC>7~-l2Jf303zEgGT2^*a8OsIV+IrH)89%5DD0^=(P!Z+|IXQ3Y zP%Ty)Wzi<2QILpFRn3);C|;fh7df}RO;Zc+GXfAm@iu*8D%??@5DHg=3O5x&ud8fR z@!3aFl*pejyQ^SvzF=>u0>%LcF>Om#Wz>VqFN=?WPfTVAP-@>|_gk9i51 zqwi7m9PxKv3GlsT2g=2jBjcV-@->Bhhu;MDwly~mV-NJyB&nN0K93y79gm;oAGShu zT)Rd*ckeOn4(hfmnF&mLO0+{6_^ig;owm>UTaA$M`Cajb6L40ZMA`8d?UCvAS~I4; z9qw6?+_lvIuuS>v&-LY+SfSF$gq%cO$EwzD@1yN@P>Ik$P2KTk@Rvu*Be{R4om4}v zqG6{tTnPsDIZ;ha%x8#Qc0XKMKdZEd3iAuUj}gwtY4;}I^=#JhDi+>m|L~n8FOogk z4$*|hYM^}H)Ot?(PcATUT*RdloVG{+riPnLNZA z>YMNLs={`Gb%Soe$^vS0F_nS#GctLkTL3f`Sp1Z>ele%zZ|%P!yW+ErTqTsu30Ok) z-o8@jRXt}$&$}CV7iZMz;okiVefHs)H!}@uv`<3ZPSHByZ5&8H`RC_ zUZ;m!Lo(h~e!;5B^|EX7-_qNXjTdY9O;`Rcyo8uvo^G|4?-wwuDg}pqx4qJ?Kj{X6 zw91PFo?d)nJKCy3RoFIIdEElEOa6NG!Bm7CqPwy930s(=U2FD+69!3PD%p}~tVK65 z%iKhrzmsT+B8?bzx*3pVsX#haWn#uQhv7-XR0YL5QL;$UX=QMWJbvpPR2SAs@HOMG zH-DyTesFIzo`mpILl*XCb$t|J7D~(n3`^IkEk2*mJ8xwllh;WK9|KwL7|54@BtoZg z)JBa=j%7-bO6}VUfc76L8y_MP@^N)e$uaQ8kDFtn9Vqkg*$N&E~xP$35lXx6d#d012GS>?8ReiI6 zR$`gF+&=X>IV(R(--rlCRbo)4MUU&RU-@YG)9_AA1!_MQ+p=yhx70LRS9?a|EipLd& zlv7>ZDS;2`Bl>pN#4e6rM|V~2I{emxV-j`6I1yJQ%SvP_;vTcR7W&Alm@XL9GI0bf zoRCO3SoZEG0tNhb@sv`>QZ!}V_|K3MRw=Mt;=9XnQA~uZwoW;SJnGhH`j-!HW9X)6 zd)Z0Ra&h2lyb3KLTxkDg)OZq_}w8GMk-+Rm*p=zs3^}DHDgQcxEpp~eDf#{pQ&6MLI0h`7JE|4T!qfk%ENSc>P&LDdVXg|g7gofpC*4t?uwP3 zKRj(Trmp4{D}1ew9rG5~W8PuR_5jI{Yl*^uaucsARHYB`X zVds~E0S$x8da%|>&a`WkD-NK5M%F27k z&7Fm%Ii$FaynuT+T^dyx{vc3to#X^B3+r!-gy-WeVp)?2-!5>@W+UL!uXf1RYA>0+ zAWDUF#k}dR6J}m8Ym-Kl!0&aevhjPcDwbNrGJ80*V!F3R%|GBk|K=Y7SlD|_N83ep z7IWs{aVU0I3OR5p*y-3G=Mp~v#{<)o)qVXXPMHS9Fb5l~C^MlkB_-Mj50Dldt=a4q zNZ0|gAHWmzYL0e&9~GAP@&f?CEt!2g>wH2e=(qe1m>J5M7N;wHp~0c6%Pqr%VQV(T z-bL9gm!iiu_~qRxCyh{{$_gzf$(@bk@w-C0HMp{@k?Y_BE7{U3%7eo z39HhAIDCrlTYZ&Kq)F2pO7!y~3r~AtcCZP9xNT)Hf`3;x_kdFNK9R=b9-CL-c9?a@ zx{w>KOTl)J_V@QcA>`-cMoz0+ zvsJo-x?yW>BuEw008!+RRce~y_mm`5odB#@$rq~s)nOvCMX;rkCeO7^{!I4_ciXtd zQEw48%CG4Rm*@ND`ZH0+iQC7jG;!I?%*=Aw`8f3hRLKfCZA7q=6R3yO)=z+#!#aoN zotbGzqk~Iz*V-=fdY}8xA^)6gLc0z*fHf6+?@P#1g`Vnt_XU)$%Sh%NM0t^dn33mS z(Ir_xCF;Q|CkhF+K6S9vq24#RK{1S9IT39)qEZ26P(w#&lLTXnxU>jTr=5CvnZrP| zQ5$h03W0Qi@ml*1jWXcMgHK3O1wTR2ay=h#Fyi|)w@WB9$1qXAlB_B9?X-O2ROwy6 zw5;U7Q{#(b${3N&>Wq!wgQM(z65>$^cdH`$)vYKFV}yU^2%4im+Q zbm6lJj+;V;B2B;sH-KhD+L{uOaf)e-+R>$S9N~4}A!oyIOMhrIivhrK9o%THEC@32u z?{ig?DQ(9q-e1i1ToO?AmmymEBu?*Rhm5Y86$B{$hw z6Tjd<@XXoI(Y#Y$J%$SL94_DKl<$P^ObUmP=f4TP-5D_96#$a{7od4EGBQF? z@Yzz1UWRt^mL0V$5VXB^G*ypkEL%9m9i`$*u1wo~iWX@uzI`B)uLR(HW2AuX1{}-0 z4>1zFQ@T(@;v!VU!Cv=JaIe(;q!mni;M}-cVIEYp7nBrhZIHwZO)HLHE2fuud46HU zS^uJ#nyh@3if6^>p{V*u&s=JCg{x9cTO>tmz1hZ`{b zt~%EI-%wn3K`d7(O7Lz+fc^bH!K`R$(lnX{M7uhK4!n26Vs;t&t%G^W)_SC)! zATRQl0GJT0NTZt6pd#wyBLpxR4(ic(_`-8Z(NN>^2R9vPL}S=V&_v_?Mnpapg@MS) z_=iOGHYcQoSa6Lc75J)TBZ6EhWy}#J^74md8;qQU$+gQkXnw^~?|&WKbmZ0xep>dn zD#Vh2i1m@-7RiH}ZD$cb(@QndMjXzv&u|#u$pRhgiFq0sT7Y=yxIOYQT_(|Q*focs zh&NCe_PD_+n@jhj>=Kr+B@$`6ZtUIxTvGUS9X3XxnXRpA^}ikPfu{6$uHcP6@aFu2vJ) z?DCFFBOQf;PF7D_-=MciX=wpSB=uZBJRN(vS47zBI}d(LRIS@b0Ad;qwk{!E*X~K! zl;4J8xiBowA4JjHF82b8GS@mXaxKVqaHf6a5yY0r*l8;L>;SO*rT;$&)EN;1gPvP# z18F^?wt`V*4kTR1uJe2i_9qA8R^}_AFdb3OjCUod)((!3JXR*LgI|?C0F3=r5VzLG zlZ%VKa_ig5T(RJL%>)0Hw0kCWqs5IRK#9Wfgb|kpQ+ZzqksSdgI6N zW>HB=Zh1KdpLMLd+t0xdQO-MN$HKXQL`G6Us3AeV5K!^#d4lsPk_(VUxn}7A^4HgD zLg%Ad=^`PyuO3L*;)dT+z0>AuPTe0~@hjEmyYI+f8(IeUpPO`TmE7yFtHSnP@_D_&?5HaZd}`&H$3k25W`kO%X;lHzF9X~kMU z4cmTac8n)^-AVLSubL7G&9;g;@eku{T6XJ{#p}m=N;#?di?n+4ri^GwGHJ){_G1Od zmB0_jIx_>?rfz)>^79LL(;1&cKI?nMTkyYvba|O#l1W^pWD^h+ZCXGF`n5w)bjkA& zOO!0P1;b;wFhZ6mxgNYJZAmf^$fdrlP)WheXY5*{#eZwhXI$pX*`CXacNNlT{O+77 zzqq@9{Ep8I+j*`>p>W4QR_x(_o<@|x`JX1* zITr+Ui-gQN@TM;by!yv+-yjXq^z5HZ4y1^uj}0_431v^J3K4%}FgRWo?-hqlBf2FU5|NbfAl79;=#c0!ex@f!vQ0^giz7IPlYadC zxyCGSR%M)oXm@b;=EN5{K?b+Ps4tu9r(SZ9z3_J9B|%tD*2j77BOW}+IC}ja3@n5@ z5S7itZoyxt!C+ywtU|f8YNw1snC!*P%AEcRChy0Ho_PO`<7NU(S_1Q%Dqv}(i*<>z zHUPsc_71@5UMQDDr#M9gpl?A}#oIf+L#i&TZ$Ax?M5UrE%6JCSbWOMGf+8*SUDcrp z?KMk%!tcb=x8`UWy|l;e%2g7F#g&v|RMY$4Aj>cG7eWjO%nAr0!euHr50lO6A$r;B zuZsRI?CXypB%SYH+kmyUJ0of9wMI4w&X2tG(L(6#EX6q+KwGbaEx@_fxZ(>nUOkLA z$na%Kk3{*LCLT8ZZgpoLM0d7Sv-xxR?2=^f_{q3vx}Omk`!PM=4A6{~e(TCl9`PDe z`!5SJYw&OPCsD=lLuai;gMNr_e`+tC>j=so&Gu9}MbK+CO9|>Z7QTcKc)yGu@E_RE zmM@`Xqr~=jd?;2c!L`hh5b5sCCSX81bly20OICq#O1dr;orMA+i$l^P5mijbkRmM_j5uMUR? z_hQXbB+5GQI{JL*#L7C(W^O3Erwo#a$RH3IuaD+GheGGE;at%$p}xCZO6&+DB{5dg z{kj_%uW~pLQ;hPbwT1`7EHFs;;5e~6^d(^+=&O(HcqIkd5W27&gDLh0kT?5OSi}4m z-E>TkZ|^12KZAd!Q<~<*8ht73|6Yxa#H?C*$N1snxABz(@r=nt7mMX}p^WE?p9=BK z3M#%9reoPDD!hKRL%&1rf2Vcg!{ao(h!<1M&oI{eh3`p{NMWI_o-6Y8%gR7?`?ArO zl@qXn`rO={Yz9A1j)|?3(wn}%z9nwRav20-ja&3Ktv*u$bQ*|I#Clwe)h1ctTHIna z$NC*3u;^U>F@)U9@jX-93DURGv_VVCyYsnG|A!M|?8eidH5v_Iq0Qiu#tyr;f5a-rGwqxC%I`wF(rY_~&b;kt$nnZZ61_5DEb-_8*G}Cv43V@CLFZ}}6 zGs*HGs@Z8TeW3bKo&OEhdt|IAPU)*VYjG_IAOVJb#IiC1E*c*2-+P72JQz4Vg$NTM z*Hmeo%-kv|RuXaoW8QD`Qu4A?0z5B2${BhrT?zB8GOyw0a`qs87ocEHE?h!Og|dCL z!z~g+@QKfaLRFPjR4CgG%4kr&c`fLHl#0)xhDxB)6x<53*I&^ORk^=G322(%T6|9X zBh}3=XK^{Na$bcP6c~h?+86X3KrRk?;nZ+JOZ{T*Eo7QnkgQkw5j46&*%K-R|Pri*Y3Nvy928M@E23cn%;jhTkTgP zuQK6sq`R=jtEc^vjg8PadGmQW8l1#phh+Pl zGW9aP1Q~VPkaljicq3dAUHeMre?fc7AZ(6`jJnHQmIfvL9)?dL=CXqePv^uhCI_D7 zcFBtDmLxL-yq*6v_IB~A#OL%fl!w9F{LM;-^ZVn{1yQ}`uHVN?J;0u@l$9(OY$l-_ zrnD7;;dUQ}^$|vl0d%cyE?@3WEPOno-_vc{ryh?`y1GACgXoc6 zHVv^BU-~N2P)uVr6nK5mqE=82Im@R>(|MO(;l}f!+#l+U{KP!6ZsmFvR`5lY5XByD{Fp+@49Kq zMh_aq=#jt2?)?vmiE*C;urCI&$2mrX-)TJ9(E~l}ec?^#qkOmfqBE5{efX|>#f7s~ zj$A6EgIh;@Hil0Rw~V&qr8$2h2W|nb6K03|PB6dg^suMTl}W4nL?r)754poi{qx2Z z`D60=@-s5N7KBEVGc(coDG33SzZ2lLYC5f;FDBjyjzwg4Lu>Snn~dpZ@V2Ie_!uuZ z#pTHROz_c7Cs4=}z4s+XciCPAYf20fU!N|(8cxrtkG7r+=SXyK8ITb52d^tyld((i znXi{S?6>wC9186H+HBiHpUMj7A3Xn^cFs%Cs`FmHTskU9C}tFr>Me8SH?JF>NJ2SDyhKN zq6)AT2;^rf8-ZkwKM)52*@PXv^yU=d8%BD<1EtiFXw$!O*nZNawF=(YTCQbHdUzlx8AZ0tsgP_pk{iSHh1j_^6 z6E71WZywj|QtkcduJZ|hdfGG2$#x++-J}cwWd3j*!oyvCS6#A=5{bVCD?UV5ag>o{ z*Y=u^TXoDxi|tQ3L!CXi%NtqPq0`lkL=g)pvLvBQKKw*AqyDC`FGU zsV^nCuA5==cICZFVbRgBd*ju;JVm$L(`0vmMRKJz+E(;^&^fCfji9rE%sY**{2&^I zd3`2Aa=@{-FT>C@=KMFcRmBa4X~Dn=^1o6l>?QPDrr7IFE@yuR@yM~45drO`UaOU^ zRSumZcTimp9ZDF{>(`8Us5E$rojG)}sjLVfP!YF#KuQV`aHc5*fQSn4QK!X%M#-#h zsY?p%UHtIzV@yUyP)^b8p>vu%b*M967$irt40^lAjLwF&s8x3J$Qx9?aefa-+av{b z0rIw|w~v6pu!W`NOIQ`P!m4u%F!9OF%L_0bXxu&2&=e^%s|;UZ0#+j7+`5&vW)f2Xe|Zp!C{z5~;^d z04HFwx*=8iFJ;ksrsM^bknNk385tB{>8ETCC#tBZ07794jmPcxBExzmEE%sTwMZffk3A#sq^e*OxF@P`X8HyBX6KNVx{FyB!6BW_CZ!&-e1a0HIq&7E=Eh zE5v`vFuX*W#DDSXh&PtVHkAwb&VSPdssN;#$Q@pH>~IH1$H9?7Kwn7UV5K7ySPAJI zO`$Y@pJNzLB7fvF{Ru&Yr-(BBUNp|yCv}8Ef8+~L-wC+ARZz1)^b734W+P9VG+x8^1 zeM$@m2x86~A@a61F7FurG2r>anO8-m=n51k1)BpxPb><8w_l-~fJ!)*Xb{@&xS*Eg z_H38(uck0|TzNQOZ@v*Tqbkj|sONOH%-HD1SWx2i!1|rf;#og&6>0f@q!)_$k8Et% ziNk?o+xv>HD24NnVNzwt8or9Z=2c!!Z*@b5YEh&q2ekGp()oe~ZD+}I{{A_>V3fB|t<-puz69y@=B6R~i z-b>fY+?bzvfz!&$_sqX3KZ4BPqOMSrm?pAAOcL&b1nIuzj%q zPs_Ph-r1QmmD4&0_-hGvm`53fUsU}?q}OGE!RaAZInOMM9uyL9j;mS#QdE0xOuKtm zD{$!L_(gKHd_}JZG6Vd=mYg!%9;`am;XhTS6%CO53a>TYbk>4VyfTxD0Dv`4;qI@8 zomHPWvu^^h{B)e>OoX$RMh@m`az}M1o1CJ`9y#=VE_9vwMmH0v^|nswk+NRAEbvZT z&`%q@9lU1VN~FJC%{cu4tuP_H0&U@bTHA`jxTt6qK3y4&n1%clOy&`Kq;K%dC&&CI z`=`Z4cjzWhPWPeZKZFd{`xKMm1n@PM7-|Z{;E=Wp0>sa0M4NpCcd=PQs~+uymKt4H z@wQD`@3yf}4lCmc!uO1~c_Q19avn_M2@TFiH3V)O-**_jdXBly`jz;u=g9DLzL}b; zXlM}J&22g;sj7ZB2O2v8JGgOxt}#i<_Gom zm?Yel3s;PQuZuYzw_Vq}r2}4e6*it<7yua=NhE?M>_JbkIMVJuuZorex6fDemV?Gq zPxW2STih485a5ZSg}v~t)2hxM2qGTgwcxo*!lW#@ow(M&Q5rtT|okGJayXQHOkHjZ(nNvV@IcG>g_ub{l z(Vj48$n&qS$x|14eV-@l8n0F91{OR|EZ#s>(rXTjR1tj+w_ES(J}u_|pSTwAIus8Q zB=Xy@KzrXgVOljG5d?U7vf5|O$FZ(GXxikP>?{r<<1k;AKH?UTdl$M6Cel479}u5G3t+fBwJ!1-4!`5m}M5Ny|#m+P5#C zEwuZze^_iK-H=^?-M{GX@K8Yh`RaA2kMNNH`^RC~mm3bRlv`ad;C`n2u2r5B2cE>y zvL2sf^jg5qv7pBboZd$PN^%@LJc-2yr(I?9Ilyw(YbpL;|3pC6rS{%>n7`QCM3#j) zB+~-wimK!vy&r~EXXr}zkJodPUN*vA0?L@C3-#8KM>Fh^sQ_B#vp*uZrwDMP0PPNM z0h@*vxqTo*7!`VckSB`y&nWelCXTo~GoVRG#rBiaGc?T1C}^c$N@+H$Dk35W{yh(h z7w$UWo88X8l{c=V`~xeIWjlFaSzY}TkeVXbaU9{u9!Mz&g+S1V*k6M{EtbE4Gn}_? zS+d3uovF}YkCTc>LA60PYhyv(Y?Z`+j zkYy3MZ7}D&DvHs6orGN_%Q*KA-jY5rIBlHA+MAD3Dzd>sbtg@DM!7mBAn;s-!lF1~ z5J;vHgNgvG3WeCr@aX8#5k<(ii*Yzu@XGN3b3_Oh2k^qTEJgLKbsAOu?KEPLtd3`k zmd)4i3Jm%r9ItO@!t8oq;Sl^-iXLd^3GgdbQ>`R|wVrDs(_1~d8c68h^=H*cUY57< zH#eu8Gx3FYlN9IRid~nbM3pHd|01A|q*hCD+1h zWMBKej=uLYINSa4a<89a&%n_xH@IOK(%JW$g(5-M7RgT;&&!|Zn>?BeGy-*>DSdNC zTkccJ)*KpD+)XV4g+y}Q| zimgZSH71uW7OL#Pu3KPsboi>|F8`b|wx8*(TzYIBigc(2y}nQi37Jnvr0;KAJM_pW()3_h) z+wY`_bxr_f0Dyak7x}4(f@QvP7r2g)&$k}_K!hE(jiCy4`BHPMG2meSLWa{Ai zDUH#2Ai4ZA^7n#sQily`ud!GApMpT7SuU&Bw#$o|7nJvn8`qx%kGVoRMruzd$*<0? zd6{)KbuNDio^`lmC~(U(ZAD^75XVX^9U0?*dVailsd+Ne6(N6Cbr(O@=+P3-*Up!* z;D|2h<|W|B)%ja<<2Gd<)ka(83u)!eCb-pTc>NYBnC-LWsrg%xkVd1FfTy-;^w^cQ zI^>pbYgfZ#d&|Da6k<$v$8G8AZdhzK=Fe0>I7v(JBcA}jlVTiUw02mK1LZk?tZO~g zNBP9WWP8feKW_iVF?;)t?tQyi^*qb__0##V`i65-epfrO$|;@rG^{o`{-BgIu37uC z+iOtB^xh;K;GdjmO4`I3-NihLUA;No{cT5`FFvl*`N49S^YoQ>dhX5Sz1{qt_kM7* z`#X|cy3ip<2+$|@mf3_2K~7D5%Trw=SNDa^p<`;qxk0nLHG@4dVn{P-@x37os4{h- zGZi%!=g95udipjzo)L*IM;pt}AI|6NXp@4Z%WN`GzRSgGkvd`jtWj=a9vNQ1wc8q( zr7{5|FaxzjLdgD@ffz9vZv#$6@9h>gbHD%En<`cH;EGoK+rrMdrj2Bc&ci~#j6458 zK+xAL(xf_!HbOn8*OkzjAVAzwDqv^XyZ6$yO*r~ir?@JO95*DqNeT9t&K|UG^nY>o z)=^b=&;KY5(jna--Q6J|h;$r4Iz$>ox;sQd1*BWz97?)dK)OL1qy(h9@8)?vpYQ$t z*8S(+dzNddi^coA_ujK-UNiHW8QU#M@>En$Ebe(DiX)+lUn$hy^_wKK1tJ z-vIJ?2tW!p^?-p)76${8aQ)^fnNFu`vM|lethP1TAk;Xb5Qa`4}t@3 zPYyFW5v0T1<|^&2WLuC;GP4R}5o3+9lt0a^BSW)RIsI5L;i2c%o0Q#P0oye*AW#y-EC>E+8}9a%^Y7K>Z3|hSY66%HiD05 z#97Py`~@g9Zz6@@#25wzmL>mBPU~B%%9V;|0CoM))6mfHz@hyH6}nk!7;!s#DW|*5 z0w0Z=yQM#|vSn!ULT=#X9Hpe875)9L*fXRD4vYt(Qsn{LtL6I7N%DpYX)aTml{|B) z62Sm259nifKR5k7sTT?bNaV#QTVMw25~|OMec+_poptYtD)-rxA$M~-*)y+ z>jQgyT*oX&vHevJhkPUF;_4(joCPGKon66!Nki@r*Va(5%=3i>J zyX3~kGk#-%W87z@c9VX1gJqB=Pu2%xEeiZn^f@P3V{1*$-h*ZO|sdy0EL>05$zF{@o~yB>pq zYy|HT_|vq8DIC^e%KOx}$L15+f}_XL$gzihL*6)v-LadfSq$!=36bMNrW%{PAM^y#rX;y>lSMG;-O*wKzq ztAl}JnD)Tb)PbcUSiUx@oh`y^!LU3XWbUIKMpJbo3;d->JqV$;>K!LAsuPAnHfUVs z3mt659!LEFbEZ3|N(%<)9lIS@JSE!4Xe$vE4YasKo~xzYnF8T@5|~-m>}gU5l=_ z)5n_u?wU!4UB?cq@GzNWb}>QN>k|#q5bOeV?tGlt@jhL&v5=yu&aSYvhShCCxWVgw zG^ix#Y%>wPcF*!JhL_OxtSLA*Ugrf!OBr$6^ySN#b8!M; zDm*ch@`zGFn>%X%*{k7GIFc$^!#xye3z~loNriNeA@CV_nXX1p59AaW(+K{>F z@72&i?O`)oIjbFKc$gW<nBxLV~JMWKM|f;^4eXSMJ<>8E{#D+Qln~D$qMMR>ri?2&ABU))c3T9 z$Jl#BR@I+%D+^EWoBplu?bvhoT_Q#!;pkor&C$SS43v`$jwY`qw`j{d-UgS-L=!(f zqqgT^L2K{p?M|@$TXt!rxS*TcE>%BO zjRn{vYnL2BOudj*TbIP*&jVz22(d)4^GRs|@o&*}wv&er?lt>p8t?_)?&@TMOt$Yb zIy*Zf+h28Rjm^&K8?nMeap|Z4_=Z3rnDnEuGrN56o>kwnF-HX#4#&Z2)f=I6!c8m6 z_lBmLe&Z24-#?R7M1|$V_a2^mQVS5Vv7{oH3~h91k(-WsSsgzNpF20BXlnAS-g`*F ziC9D&%`sq$hbQv;=zUz8WZzFs8uk!p{Gg~)(mq(+*^`;j!|~t(zbvj1G4ht4<2hh2 z%Z;4=P$71`zy%9@TxH?sVKlvv4y)eaDd}G|b36!<#`$yL{3BV%g`x5S1tcU|(bAt@ zPoHHKy6H05UZxkdZo6E%>!>g{zi%*nN=T^4%wS$tI+fqy^1Y~t`L`8t5t#tI7Ep`*7H0Ft_VWcPqnzwkcKRL+!}_@;Qvp4JU)<_3f=RZX*|4wn?Uhy* zhT+f(OwFnHge}s&gEr6$!;{;p+r{be8L5G|M#1x&*vHFWVQ7M^B_XD_M$!kgzMN+x zh*c)X%BHu12|M$KMyzH~+}y%#XZW4jHO9lbQkKBJ*5j^HV=nrs;fxv8o#r5cjwP=6 zCQem4+WBc23^O1&5@4E7Gw@XY<1D$p^lT@iDsz9PhZPPRLWXth79c?AoeWK52ew^) z*YZw*w4Hu|`8vrSwq_zPvR#V6+o_@sXSbS_gXLM;9dj#5kdI%#W>p>fs2>oUXq&=* z_Xc@!VpQ)GWtGE=ftye!ofCj%?-87~5s5{KNWpiQJ0o?dZWqk|IZkkOc?@sPjM$N(I`}nJ_*` zw(!ue#mFGMBksgizf#noUrB|zI5P-{w?ZPROH)SpNm5^#vW5z0y!=1bK>Q?J*8yF7 zx4h8XT@Fhtt@ss|aj(+HmR#klM#vnIZZY<1%_!_ztPorQZJ(DV#&wpk9$|tx=m&VkO!H> zA{yGAZB~+0LBizV&;l7WJXQP-l%=~jICbovVmp;m%RUUcM#3c@6~K@Wi4ic7^wGE0 z@7;EN4|-R4j7R=QK60&u35!t5@{nPxiBNDC$c9qp3_mV=!d~rJ3)sH%dtjG(8#`OZ zlPtn`pI(+lETBVcYi4Hl#~sApsHqL%U9u2WGniDuihu_`+T0@X+SXS7k2_?l!jVGp z)`o>23nl-b4Y9z_4u_uX-r65UsBi}S-N0#Zy~V|^E_2uenv>|zG zc}{w}qkyfT9|ux#So*+w(D=lNH*=@OQvC9Q{+TLicRWG-y6F>I@27|J&azxmTIEev$BF8dk zXX6^z4MgZ>_s!q?5$2rGh|9SxNab6!$uVKzC}#{u%MUP!OXNdW_gS zoo7(s^E_OMY_p`5yVxO2SpcIEl6frTBWj&5Jq60k7dyTZJFS(*xu3LW>A-VyvxVLA zgm^lf3BoP0FLmRTNl?GAu`x!9r=+&uh-;!8WToi5imi?7^T`b_?e+Ucd673U9Ac?` zGHl0C^8IWrh}3U;-fcnzTc0JP$n^&Mw;CbMoibFCzd9N3>I0k-oL(gFC~Y)aj^PCmQFm?_-$8G z(7`T}j4Bi1akAK$1zGrGs;|!tH8>@l))wH<3a;kjjJ&v($w|!g;nVBgo**0Hx|`(C zLVii6;5VwE*PL}5h|wcZqHAomUE@hzZ^{{aui}6ta{P?^=~h(+>eZ?cqPjlRD9?rv4dE2bg4lgfd908Qe>5$zfJ%?K( zuxj(^d?{Bw@jcLUFuAby3a*Jt<|$sD;~qD=$hoiW{OR+4(HsVndp|yR*L|Hkef5}# zqnuzv(Ej5YnY#1cd0(15EKa-=40rJS&2-YRr~B}Gm%v5ucATy?U{7x8bzMZWYe>p+ zQ-s^@v_K0_UaBRR<7yv1LD6~yh9sTa8!9K`&9x4xdSUlr=`vU9-*HVUj`fmpf4^|O zuH1g+vqQtfml1&x;c`a9wjVQJzjKiIOpT&@-bAg-cCx}|&ymWf?TdqCSUT;U*KN4r zuo|TOuwreZMf@%cU9yZv@s-+IW_f!Z}2weT82 zsz2BUgm!*fz4~%;#x@^20{5ZLy`-$E7SKTMU%VGxD#?x2qoSjV4E4TDLm0Es7cjBK zLDy_*$_F!YrOIR`O-+d=Qv(Nq)p>Nw(KU3%^*q?aVMudw$nL9hM`bWypyEb z-ffD^+Q|al$1aJHF+g%&i4fg8l<`nF!klyw~WKFXkKW7Hug) zcvF%}Pwop9F2}Om?zs5?BiAnk`m82mBYiJb3TxL%cHJqgd{hw9rZZQPQ-2T$#cf`H|Deib ztUq*P&@Ymi*u6J{ZT@Nd?W$C*mX{mwd_Q^U|w3Yqx$%9P!82;_?#%AIxqp z->D&IQ5}pVFZRyb*bb7eJ>zkYkVYHB5Wz38XBT;ObRObMFNI_EMFpnzZ`+eUVahL_ zRA<@*+ot}}44QL5ILSu|2B{<6KYEW*09~|Uhn=>*xRi-nW@8quQU9{ltf_Oi5P+78 zsEbN7^Q!Z5!;1Dmc6xME#B5c(85n#z*+~$IDZ(cdWs(E7m8@#zsVQjC$RwU92$D-< ze%_EkQIHD59tycWolvXty?SqJYx}F#f&608!^CQK=Y7vA8O89|kuu+oQr$%bk@nuQBG( zKMfR5boLt@*)KS*BdwNh(=p^v<9Gh6oM{OT@h-C!x3tMk;1J(nPYUCqY1&LK)d@Ve zJ#=2(MXsBLl$7huOK`#56z>}M?6=7c%f)0Sfq$nCnu{OuGwVOHozRSc>nBHHQu788 zpcret3obD4~Fbkep9dQhl!i|j$yjAGHMs9O+v(Z){NI2GR3jp~9ZOQ>( z#UJEIPC!#Tolu>y1l=?_`D~u_6Iyuh zz~}ftf>?<6n8r`%Icrvb70R)=UCr2|ai$Gz?PSab?s$#bX^F>x!Mt01_~CIsWpkxB zae2uS!_;Hm4q(Vr`KVwMjUql3_Q?@H{Qziu|3v)+_o=)oB{)QWLlJvZ=z1uGRs<6bpZ6>2 z0w@%th6e*x`o9Qf?4do%Mlxgw13e; zE5-jg9ao8XUvQiK+R7g!?7u~Cf4JqPBqsj+grw(I6s)V865Y4kd#b3|e3-@RU*$@C zQ+ZdSzt#Qn)mG!!hoTylTS-Btq`111EeMsQmi>Z+C}AJCgrzyG=s3i&Tj7PeaNN6W z^xv)lX$kCHr148#h0!|0OkkNj99D9BLd>%X;@@cW}zP59AVr{)(0 zh-BKPL>Xt-HE=lTMii;?A=Ztzj+RSvt>iu@h7W>s034gWIo0|V9vmDEYKdziT;bN$ z-kL|}ig;;i)la6kSly^>u|-mRXk^3+kdE*!{-NV6K2lG>fIM$7h862^9t<2H5)Ecb zkQdj4sKuCDjCY6B+h%>No7pQY!em?;{caQ!=EBv#n$~o2JlA{kOPnTz?bz0{fqf1I z60RZBGn|f*HO2BpfKE;LK*$;6JMHGYAi3jdYUh_&NUM(H;e zJ(dNy+HQ~csTAtGz?eJ|Zc{kNx->w#s&ZTu)hX5QKHZ)W@jhj4XlMZAgY%ftn>-G{ zs5rnX=mW5x8#4q9H}M%dXdi`&L-QDBU)t^nB$jEtw)pbJ9*a#td&7ts#K2pQrMc4 zFe(VzZ-vh+VmAD>zvt&@@c4Eh6Pe8N|C4kPxddIMfIbKAV_**;oPp*E{$YS@nm@D<=1TBFn> z^ONZygh%;M(`Jzh7(cPhj~<(>pbTN> zU<0R?#0YBtWGr&Q(K;s+fbw6es91t|p`I)B)3CN^w}y83nmi5RlR_ zQfkn|775B0{(4eAN4!LcuAx+;41&_?`A6C#v5^gq9E+pu|D#(TSnIQG%E3(I? zZa}YRgxkFD8XkeOv$;_J^b~fdz);+n zFx_kblGL6NJ{FtG^|C|-6{P5unv!JiqDy84he9Q?4#q_^*ff2V1YkfB`50@TAtusN zr;}>9kqxULn-rDWt=(iFbd2uR?C4MHPs{JyIh?{~&c{!BerMbm{@GgbEs`!u&E zHb8F*Q4&qX*2{x~D4u^#Nu&+letl5aV zO9<_?f>+IbHeVpmQRD*R-j{gM;M2eC%yIY0(>mXl*4tQI#qOxykeFYoG;Ox=2*y< z`U01Od#I{vLjOt!LfN%3r{aG8U4FpZz>{oXrMkfa;A*<_|J7I;xPDKI#A`wcyOCwJ zArfu|r|eKD^o^C(nyYA#^r0365_WD(gM{U@+tkDJMIiQbOz@;l=1-a_A&Kv*R;bVn z(tkGbpE8o4{o|W5lN2t(Cd^~=mqdS%bG+0B5-Q(zP0)b2(KN&KTiMB#BSbRFu5e(< zz>-msVlBVJJX5W#ic)|5B#!_h#UtVfRH!_>trLbCVD^&N>~gTO=GNEOPt98o@BqFn zo&i3P%zy6Eqt(RL96i&56h1E?t&hy4)mtT^N)==x`4%=3Lx%aPYfBz$2|J5ipk7rC zL!+x$HO~f$Uz2kPv<~4eTPancakhmY!|~c;c#emifc?hf5*My@9*drGuGB4N`#nxJ z)c`#e0nYKF!k8cvxETm?p@pSbs`J-E%)iwRNouz)1uz%Fa2J&jCYg79?~5+x`Mnzd z`*vuwxnpjCuq``P(6ORD(?NZgM}&t8YDU1Y=$zf!s22jZK&52}3O%y+(2nPFi%|Pld(!oPgeVk=1~w4YGl0)8HM`1MaUf{!<MW?{o`A_nmwV_Jl31=qBkOmYU(Ta(-yR5c{J~E(KPX2DhlAS#CQpY&`d03tAr52I{jqm9l8GPbv zL#spkc&46PlBjaE$9vIN>OS6{sTmnV>wWPCpc8kgmrv_vYz~-2bgBwspkDW-SP4}2 zjpndhbwZ5gYp#>Bw9!6#o}&c9laAKs%6%gpc)bUFz9wax0n`TVm6gvI&Ib=t1p243 z@`?gl4MUQ7MOw4C0A=ntT>4)eIg!Z9;j<>~fg5`+t(78PVnj2Zg@iqMpc zS57LZKmS|y^>zjeMW5tF<(lXAaEIg}c}3lSDp-!0Jo(o%ZR?>SEZ$++i`-pns4$>4 zEotID;^F2F(U4cqZYx~$*bsS|E8u{5;cC6j;Kec z5-S2DfBI)Eno1&-$D#+=_GCva$Lb5BoKn3|{YqNbWe{rD5mT*c2Q`g-_7_lFiGO*K zD^0Gdh0!b|xwVPlGM8q6Ly(SYK`Neah`7OPQnq9OM?LE(UtEHxJyK*X(_dbGSutf@sWlo_kF0qKuvJur% zF$beA$fg^E2kaI%L#1A=jei;*Id^h#E`LUIg49Jhs>qqv)OAD}S0F{eU2nZQe64yFOHK#EU23A~{oP&+AHec@#*R-b;QfDc@ zfkqqM>)1366hto2xNs?Zk`?lM-;)7WYmT?num-31chIV~DH%i+3agLzSW=5c6Ky9z z(9eRIuuvx5n7!)l&^4gnb~XA?P*#E(!&;|h?DiC^%-J#r-)c*0-So6RKxG`sk&W;) zUGjL{QjwlD(zjJ!-rD)?1M$iXR;%-KYS0F1z@ct&`m|^8)wIL|ZriOLp2^?KFAlp= zN0>M0q~rm8Bh%BLE4N=zd7nB>X1HK8&9HAiWZn>B++R@JpQd*-Y`uxM=Mk>oA*J$b z39q>Fdd9|>Ii4u~@I%e(w644=hc%>Xc(~gJ0!JM&^ANKve$VHB)LS?Eo{n&9Rp@f+ zAgN;i<0_MuS4aLBAqsKdOmfkeRGNJs1` zjt5lS@uzQtENiyDNbw^hb7PnPp26Yh67r{OP()9rl6)ATzqQ?FvR}Mm5K|%$ZZZ|t z_aeA~i-u9MKim?EyWqaZD*wJxVRGEBprAe@_Uftxu8jogdT%IU5yN!kc1J66*_1KdpPrr>0v}->z_X zTq%cexWF%*L5etPPKKb{Y7f`FC6Jj)#YItwZM=C=Pq4dKdpzz9Cbtew5_3* zLiX(P`O2j8I|GX7GnC<~3S-?rm!z`2IbZG3BwB^~hle-&*~;GxCiCRnL`6k;Ze@7L zj948uxHT98%6zl2Q{gR#`}%=8e>v15Ira1Nw@BvMXO2P06rAz z`XRrYt+d>8+`6eUK(Bwezxg)?OwzUYyBx=;E0@@0r300EedmM7V4DNk#exgY$<~OI znVowjSAFu)9pxLfYf+&kPfCj$*d*0l`xh~*lgWLah2!>%hS778gOZ7Q(`mJ<4T~A` zs{up*s!b9`bq`O(0YQpfB5v&Fu8`$hfe4KK)mf_phJa0L#Q=n1sQ$`WFPy^&Bu1HGTR3i)RKSAsZ$o}X0cTf5@bmb%JPdv% zBN$|TwNxLM7I3LnUA{DQH=}B9zl4|haKhS;1sBpq&0)EkbHDy}I*T`|C-8)GqjRDC z;Ifo$nC?uP@1|&esMy1Jh%bWiI0RYEdCQX+qwJoxJW)T*x6Ihmzf)N#xyAtmh*f9_7u+%G6X;`8)jA>yKE2NCdKp4?<1B0~?*7GQ!Z1qLEUKoq^nW zK?>QS8*1AP=-%YDk!S3eaDXK<*h^6C-U?^gAjUGZIJ+*|kdOG2Ljuv-duby3eSSLl z13aKs_10`gCp}_SLU+8|rvTMW8j!?~T&?wCF|#6T3s2IgMus=}nAG2m;c8=^BYZvC z-yB1AH1(xxpA|n>;@(~GeZ6C`o|1UGdcu2~6duqtI8s&@&^u3j7nsY|vx0;|Xxw}9 zP!*oxacVho63}_v5^%g`H`0wAO^KQvFD_2$GepA4ULPqLm9;nWz~vNuh1b1&g+9v~ zJ#_OV?Re|BPR(h(0s{`^urz{tE0*mh524_MvCR8atz-_w?Zb5r`@|0TYQCX zo>EE#@!ib*^4>&3XM9t2awV3!(5r_3FwEDjd-U;4=)Fcb!WQOwYaA2z!_ea3<@3`m z)}v$U;|Z}c8eL?*Eo_~KWgg*;sN9T@K1#^q-5hbE5a_FDr~q6vRdjKqpz#ZXuo3XK5E6F93%Wn3mXr|JK< z<#l_bBo2r-pHtKyWEbJ1OzsKQS}sL~KM;TU4O_ij(Wh&remi}*k?HXFeh+ebvj=UW z?8?lZ_K0jDca>k}jzmf|n|^0{;9iXvvQ5rTqaqs8j5pO>bwIL-4Cjt=u7c6hrg3ff z<80YG^6FsEw4f@~LznQ~P#0nv=W9oIY6X$aU$Wf~RtNWMbBzZ+M{UEOkz{T^eX>XF zK_HFH7>vbIH0$JDv zs;J~$SN6I^5Sl?QhFLkO`1gl9g#``56>86B#3iltxX9K$?eOYLv`?QxpLt49<4CZ7 zqu+jaN%N-V)W0pmO;4BqE?0%Qr_tcmyM`Mw`NXNQ1Fef|)t_8Fux7JUtQh)JO+nuP ztAVgFVL#LYie#QA0j8}Xa{u`}!3!*M$ow&CsQoJI=hv(cD8hZX9C8vivqeL*NHT=6 zN<74nKZK^fJ&`L+A)vmgr54^^qDr=DaD#JVxXDOYBWEGFDyH1FE-r%X+c|m*MmTim z;)`{p?H@_Ri3)l%DYhBcGpIk6ZMKcnkNpW2n}+7e%`~^vB5P{LpOd6LY$~4@v8~+B zf?ZUnXx!fTrkk;j@z&ZSOv-g>!M$rRyu96#ihHbH&?pZ$9aE?PEQ|Vmm;EF|Uhjv! zxQc^I)!WlB*=~2I477r=0?rYe@7vsSr60T%8bdKSSK1ssX}f}E zxf&9_-+XF9;mM`Zb|XFfy-A3dAKUqd!ycJ!=_E(Z{CCBgHHQx|*Pbt&33FQE+DUVq zMySjQS@QKY&$=#L9vm|P$$nc~MY0~Z9nhy}YUFMgX14j3~F_Dpxo97EI zBdZNtnTWWy8^xMWk$o=qy8*(OsIddPo}$z_7*J;!3R6!U^%|BQV!wuC$}od%dlu!o z9=8k8>V~mWWK~XEBpsOR39tr!$A!Sk!nS{X{)Xz-hprLffGFH>!(5v=8#Kq4R8E<8ElKy4aEOsMy+Wu$s?@Z&vh#!m88) za7G+%9mMNc#-zj%qUd5(%vx<$)9~={#-ffpaQt!Ms&OH}S-h|~SZXoLVFf=3L;C{9 zAbck@4o4HI9!Q4NUZzf}L|uTe{p8(X1od;%k$W$L>qZ1bVVhaBx<2>@7`7Jbjwb#j z1DhN&T=^cEp~S&Nt9w(K&6YzKHs%2ZT9Y5$rrlYwHfuXKjVA$y#!v)x(7`SjVscX= z7cP1ORs^-;pNetXN=qkRaHxrcI&BH{pSQUocf>|UW-|&XB|DZnO_W;xQm-U=`U19(E=QZqGubY>0 zLwR`Q)SeVsJDzA$=dYSCl-guEHpTEb`uUu$9d7R~$PPED7sIA>$XS;!7;e}1{EMgz0})OxZ+4~~dK z4M+SCj>>ZdesA~YppE)sIUs=S0$gO~swcQK%4qG+WKLA?;27b}UIo^RF9qx4fyQRT zSyFN5=kA{3nG6_l%Dr*zuJ#222Z{so;sQofXmDliaOYn06$2g`P4+wOb-2H(q_%I& zeS1hex(jlqxOWAcRQJ&{@B;a2D9vUdsw0Yt9{tW?H5EIA-eYX1xe)tqgHD4#&S%do z-QVu7M%0|xnxYSeF2K>~PCbXgR4yyNewoIHL(#v8ewF8*Ah zkw-yY-QF2j-BQbtxxwICS%7M7FG2KC6D z#pSJ0Nygq!R8&;zy-pZGsXoX;(4ZlJ(V(;gyrQC_-$6y(&&ucsDsSth8{OMHlJgYx zH+%{<6&TW~?LX@SgXyaF+wgh4{V$*V6}_fS_iZFi+#!4gXR-7oIV$QC`OyP519$jm zD8*C4^+D}~{&(6#m4qR$xuF5jTpBciB*H{cMBjSG7iQdC8VYlGK>X`@)-;nS! zD)fM-C)2l~?&)o0U!=sXW#&=;=nJ?<``Ze4jDBLK{I)L3x;H!$9|SIH(C+~a0`D;g zwbpoN?kFplpv={JNw?pyMa3M2@2**_KGm;vr-+MGT~lLrbG~OYe*jo&)e?f>8XG2T z$9=|7B>N$|t*fn#1ZP&Itpzr`dosu=%&5R=8-vE4lNByGmQwNBP#ex!Hy1(ruw&H0 zJ>yr{B9jLqoa$du__|#(!-*UgT-%eIw|i`JGX+v=ei8g@6Y^*+A0AY9io>Q%$>A0l z74-f%c-dQZ#??H{9TIb}u~A&38hf7|etabA`bQo8JUo)f;&t_*%8x&Pm>)-f|Hd%6 zL{QC=j1jP#2E&%|0J!?|=TH0O&H$y zcIghii}J&r20`D4J__;MJo!Q0BGG~7INDCbr+57+76Oa=avIr@BFyZsp0`~-ZvB^n z`g#(u&*lqtv~>M);7SD&CFA4aY1osbb4o$6RUzT~eBZ@uT{^zDUJp#|eWA?dtj%!h zYQi#G-R@gts@a{wof7v*7&_3m%?j5+QXq=!=*K7g+9pR$Ntf^HV_*0Z!j7=-P>u#lpz*-oT_+sUho! z(1WQM`o!@A7AYce+^Tgk-i6=A{NW5Q_((?^VWz3@HgOS6!2&!JD+R_iANdh%;2}>u;t@jZZ z*$He3KuJA*tY1V45}$=y7GUi=nkf8Io|K-rPZ*Mmf#gjVWk^-*{wUe~4{!)~K%Aq{ zhQKy+c32Y86QX`lca8cn{T8_mgX}N?N z5;dSH|NU5grfV`16DcmPnJ93Wua2*36kTjed0Mch@X6=WY;QOIYmAwTU=q7rOiqhq z-ejb_$kXgv^ipd=gRO=0p*h{^^A_(N%qeYjNfPD$yFbN#YWjkm4)5X6hF-WK%PglE zLQtVFL6*2AOfU@I%!NgQ3J04~w3?mmK7DHH``jL;#)n8Eo9?C3XYAs-_`L?e%WO2sweiH_bGpmjY54y|6ud) zMXVmuKatYO)fsP|plhNWP9=lO*?L5=mENi}bo%J>aGoG-KHfqtCzr4xFE9V@=y!LR z&@;Mz)81H0r3+46plEmtbfOWCP;-v})KcEQD-5|hq(2ESDr*na$w-CaLhK1?h5Dw+A8ylkD&KiqYa5PLNzKdAa+oRtT_ihDL%8q4 zSXOU%D8+)Ih;DGa<>*t}uDLlmX4B0R8x)SvQXea$Vcf(>X3q4WS8@ro#y)!j>+9>! zd^7)*T;8O@Vm8;Ezsj=~?7cf$5+|z)H11i`t^WP`)Pez8rLT}>Iu_T1oEXoJuu4%P zOLOWVU7MLvrDjuwtT_siHsQA47*Zmx`+jWYkTs52OX1Y@1rdD3f|HTLaFZ-Ggd}~L ztv=D%%76h3vG)3Wm4%xiVc2c)eM+3NT!Jm8`iDqfIX^!?&0&InWLsnN#MLe5E{s@{ z>>H=mX4gMvy^^0-?rwZ2tAmgP4j27E6EC-Mp-jZ!LLT26DUz%AL8oMrnZx$MJiqo> zCE?yGXE+!6tv(wfA7O_Q?fa$es3&R`XbKqu0%j+PA0nAWQHtc`NIMTMx(+Uw{<{s8 z3ar7}2czoa`)u(kvD7Jqxv;4?IFMy6?p0iW?oo)S8} z2fj}*TLS-*h9W8A8V4sZ&S7qTp16MM7}w4d<}jkuDkpbh9{B3Nj%5NZK9*(+8?!j1 z8$Wl)%9)W~F2){*Jg$3KRwZA%?s!T!rvR4d^k#kuylNsrCMO+c&D`FvY6pWy%V+In z`oA7!CT?VO=<41>`K|2Rj#f*UjP@P7DnQCX5+8Anz^ZFb92^`xHx$Z$5JqvjQ`y2~ zC*LfzZC~O=E*8RrYhlp`Q_l-49PnF$vSv=Vd@gYpV*@&5vmGw+UnvAo57Dc!v6?24 zh)7Lr8EDTJz%R;HEq(XY8#%JHqHU`2msip2v3`#a#p=56J<)$GHww+|k>=v#4fXu5 zhlF%bOwWk%S0ni(G!UU{(91S^%1-_SVhwal8Sd0&HP1e-0J;7Z5Y@rgVKArs^p}L+ zZM!21711PHLPFT?y+R_H$sPsdKcCk$UuoR(YY(SB5`o4<&3;QM4aq?TcRY3RZlW0) z#cF52u{5ws!;|YEmM_>$7LNk@MF~U?&fToH2ufv)wpVRFFJ`KrK|S8#ZmDK;UTGCx zHb0kp`a;j;et1|lIyTna)Re~PM)oORL>GMVR1}EYdDZP69P|QE0rb{a>yb#J@}eTN zw^gLYy5*T3Vr6#yM1~X96y1$wAHddWzHrzh7r7Z7z?HKQr9wZP{It(v*D~FyTNKXpC9Qu%uLsz$a)40gUuf%57 z)-T~@R-rU#^=q+W<1K1(JU(kNLU3?XF3qNY4h|xiqg;&D5^B{#p6ugx7XnO9NlD4f z#`e+suDu;j&~bs}Of**+0t!aJF?8D2$hTzfrdDFj@N+0&lY~C&5LHHg1zRDkU!!c*hx)|mkXazu4~BH;(Dv-X81K2$FI3DF)^hz@X2vi z6R=Ne(y1sZHyR5{_<=`p;AS|J;80&+Ba-T5^r(S31avZohyJx}KOt`K(kS%BOlbJy zt9q-^9pe$-Lns+>d~s?M4as(+OlOW83Q zq)xa4oWJ^lu3e+nkMD}B)YHzpaPbUxdBm|&%H6nRwdiu!Um3+c!jykMxtM06f&@{S z)%HK044~{i{@UD?^n^dsdFW;VqoyB>x0=ixTbOu)SJyV-ck7VmQd`aqCWxWIWkYfh za)|nOoOO%U^UOR&>GeH#C@Fq4XcfM@pJWLyl#^5BFMdE^lV(msld0&u#(7wYW1sN-!2rlQ4e`#mpd++dX zomOax%;Mhes6X}?Or11yIMRM`AZlW8>&SD(Rdk|-T(0_MmHy@NkdnS*eVL8O@5X|S zaJzrLDDtZeh>1wWYfwLfdtAZ8(=< znW>0EsyI{*4vr52^siqnHzswk;Ej!&2BuNH`Y5zj|TcVO>I4%$lzm1V8}{`CZ9HTSAq3 z9wf8u%?r?QtKtP0-q@E{i@jfTFiCaq_gsD*i3r_qRb;KLmNtwDX%)OX`O7s{ai*37 zSGDvfN#5shAYRbdo1x7^S&`17=;Y~Ag9s((2gddJ>Fj26N}bpEet4xc!aT9gwEQ;jqePiwdaWZo;#a_IC9`gp=$o4TGFA=$!2`j z8hrlXiAY|%xmL*460d8Fp5#^knt1uE-xXMhj{EWLFFh5Y)Ssk7Pj3s4v3sBMQj4Tv zF0AaM1osT2qaP;)fO9-N2BSBTu<|JFjPLe=&9?Li!2ZlL(Sh6-Cxmc^$#vDnz+gTq z!waCD?QS@M=f{bh%lE92f6OEbDEr)PhHbp zmKlfkwxI}ciYcpe&n|~~D3t1%)Q~l->5e%w1m@C_E~RxPs~?+kd30=Z%W5NPyHUm& zy@=?In-bvsr4oowA=|dadmX_c0S@bmm_j-A_i=RkIkfh;G zYY>ZK_|~4wpQ?oHMq9$@wYxuidtHamOgTAa^IZh+In#~8ACITd{{STqk1-xDIjW+^ zvFGgGS-BsZgePp3t)<@A1@pNDyp9-K#dIoSw9$)R2r_n4XpkM^Aq!Cn)HO$V6m_KL zxiZ=d=3@Ogd?n^mO@zGq{iBse5A@*KD10mASLkxlMlDEj0cWQNxNw%3Gn`&4CVm*K z4w{p_n^s7hb>lPq1rPTaxp?yNPlEf9dTq(Yg%o%s8S;LXn3}KfdY5B&GHqoSeM3mh zN9OJ~_T*d&g#L(vlKYVyv-~tL`T%p&NzQJU@<#NVL0zFt3w*;aqnM9j876Of?cO60 zmfY-2*+oEyK4AEcD0&UH1xj$Dnca1A#?7!xjTo*Ep3Vq7N{FS{#1Z``m|YF*C-67S z2#c6Fa=5wv@$+pQB(3NkH5^pCvKAfUkcAoAIU#2?0)inNI(iaa%Jsck_DoMQ&+|Mj zF3Q(p8}~f3PPNj7h4303ckul$4?%YmM6tuenbyeVGD7E}wJiS-?Vk35fH1YY4#krD zU&Kc>Qr=P&^eu;B{%E9!ewH&fwA)K<)f5DNHC4INL8LFH4Uy#KSKgmwlET=Yb)YNf1_$7i3+D7*1=I zTsRD6XL?pbG%HEjKM6>hMX>WqG0Rw)qJn2er^G_DE8xyMDWreC7)!-3sW6~XJzf1B z#)hVsQ3Q3)weAo3C?SjXww-6AarnE|x-;4}_uq_A(+V0?c+4iQ?Ej0YzmBTv`@YBF zOSgb@gGhtYNFyno7o=xGa zg>c^Pdb)sPKUCP8aB{s$@?lt+#e+_`>raekg$l~MUSp1!+FTC`8z5?N%l5}3G}`Ja ztJtkJ#~dOx2}4>bjCB~8_&)pe1+ae=E*T#{x_d`Acj)2@um3mBAVs@XVR+uD&=$WN zyh&Rlwc|PM+vWu=may$ef7rv+MDyb2HAn%F-+RWLXV3oL4yV90$CR~`r%(lmQ_u?( zH3mL(i53gX`t8ohP?ZuYz>H|n!l23nIpX6d6$Z>R!^S%@%aznE5n4`7h36+aVm@n9 zgri!lc1^*qsM2OK-KXKmEd3bJ&vLzEw&flM5V>wwa9*1D(zb`sa*HLKO@`j1Wojqa zAGXL;TKcR}#4n#aFWzb}cFtYO6%E1Z4YqBpsB4iC2Uai}4<&tB61b4v$a0ew+j02Y zF5tdcA5H`k^YLsC6w-N<{hLK5G5IfE!sz11tdS$Hj&!}s>v!E}{eN?^5vf7WR9!pA zgzfSD@C^OQw0~Ir_em_j3H`!Eg@vksDM53Hhvph}RQ6tvwV6Q?1sQ&IKWBswc>EfL zAjBx@EK4P21NWt!ydlSVhVt)ONFp;#7hD%NGh34n+#m zulQbOWv)seU)lrBu$m9?Z@S&2y%zq(yRVEO3`H$#6nZrRsIH*jW+ErIK0@9|)qR@! zzR*AV0X*GfY%G_m5@-r@_btXcPh zGgO;RaUeR^#jY#g_jRN&^Trd(B9#>t%TC1mJEiV))IxIZ7B%R9t|ozI&yhVGzM&qK z`Q8jf!pS%VSX-aL4n68HO=-L1!Qj*wq?p%FW@iozL`2_>x)RnNa`o#eVVgtVzk?{y zas$>|bpm=~6|Rvug?= z5V=si&an?Us2tVVMYcb{ZG&)VrYecXlL3981$=qf_5~A4K_f!{3au^fS zL>cGhjGq<55W}uAYOV>zv$Zz1`+ngF{lS)5{<-CVk?Tp8+kz{K_=}<+dE=k6M_z3S zTf5CIdY{d$04>MO7BZ$G){|`iH$VYrT2pF3{k2#VZh}N+$pHS_!Vx0IbsnDbrEZZ8 zXfSx`AM8p>L;Hnt1X4QpDgs3xk6d1qr$i7dEX;&h)abkic4^Bs%fq9HV+IHW?WzFu z2JDvJ_P}dV*7J4h2vux>?n2eOlN}rp#Kn$*fmvedm9jP|$M=OA$ z139Dmig?8T6zlc(5!xX+PXO6dTc_w`v2ADEuxzU7l_xS+e8M>lzZtDaXhVj;I$f45YhInPx*`4^NW>G$=ZeTq;*)S1uo1h(sE<8B+hEQ%wHf$)tVDpMyIhYGzB^oRa&5^>2=y=0 zD_e*KB!uDZh1zD~myg){vASb|#Vxa^olqVRbk!DqFxRBs|o^g)z@c$5EaiKk76#((#L1#D~&#bB8+S>%Om69E< zkLwhdD=}G?>8F&Q!6cgf!X4jZE>ApGFrF@Q&TpFBd98s7s1G~Fu8Q`SbluA?P(8~? zdHo8j;0Gkjcn6M_FWkPFC?>eC?+G& zwvD(muznZwPIvWPRQMhUwp*Wz`TTVXw~d)2tc?zZSQzxV4K@lBQO?EMzzQ09AcJcW zjXIt=q@aM@hnjr($ZL0uLyMp?eIXXc&=lK13F_x<*&v+yhuRW6T%D$$!q(1ocgxN2 z!?L^<)-x-#wIPLSB^`Sj;cg-r>y%N<>Y=}|PW5B{q7&tlA;v$=DQpOpt!iIrlLX|j zli@c6G-FbR6rxbjBkR$LTgwTSxO7wCfzx}_L2H2jZSc8Iwvp{27ZO>b{XZ_ife4k* z5yYmb&Kgtg1A1HaQph(6(h}X4up~H~zuQQNVd3xesxyQp0`kOnoiK%jaP>I}(qY|B zmWaEfGhIv28&c|tfPQ3zf7^jnP4+d9{S#spXEQ$Q%gEC@-siWz zK;SG>|||?@cUB>om~uS%s(|F!TV<9m$jp(xd^PV@n>pTV@iItiQ$Byii%i5 zkqt!Kckf$&Av9FL%k5uy3i$KQ9Mud!aKJca}@pVE+$MQ0d;J7qv zt7(Lr&W5Kt4z)7De3PS)n#Rj)WgT|kz|Q(Ph-RnF<4cr@O|_L@{s|;h%d1jV_y9JMp=Byq9%%Z*piZE=B`@BIP7Oc+e-L6=^Qd zTi+KR0TDQ_l{-BdHaUYuIjWF%sKo_Hiee()u8S>4$+!_NvkeV)SQrK3 z=hL(vpiDW*DYk_#2tAlv<_$3-ELkv z7295~ojcTbP;l9DwP3bH|4O#FY#nU9XS{fSpYHnD!g+MpaZqJCyn5?%A@YMF!I@ zeuCkc^dsKbHW(t%hnI#r`?PF5`c1u5YuXl5j~TIIYD)%1S%?{*TvR;`KI`*5HQ^}p zz00Uc{Q0#IJ0WE?9ZO zoKOL1V@$-IP5U{wp3n&hQ&p?l&6~YA%GbcpU-y!3(9@;D--huQ6fFHB%&9F@ z049@m(09sDEusUQv%SPO5J!N6RZP0he;=i~D=jULCW{AQH8(Re(327+@Q0!|0%Hxy8`?EEkOltj5fErzGX>GNT70ZM7KK#rHER3j^f15v_U z-e0@Bb2*HM$*{)Gv=78pDJ*uIjCwJm+9>0v-;cR-#)LBp?jHV)LW7661d0J{Yr;8S$R_e5)%43Ue8v*^_*Suc^r;*mJ&VK|BKm;TBbovQ6zhXB5!GV> z3O3(1Cm@{xux;>!J;0|D+~x$nmwmyxLkwSV?$I+$f+C2w>Gv3jfC;!mMK#yxgZpIx z;mLrQAi6!B#w~JFnSa)-ia()qvJdl@MI}gW%!^~>jemh zaeRI~$iKs+N@DD&||NcpaMMi!cO~qu=@$e7;ST_nvO035Y!0Ir)u8zI-#~9$ZcE`{F#3CDt zo4Z$lqmGIzwW z=uxWgC$V&K^-Vb5*PAI4q;U>Ggn@FIiG{^fv&D}e3AT^&q&L(X5QQ&I!}BFoC+>Y3 zrBzph{14293gdbiE76m=qLsw{?u~_L-YP zXlpN7gVO4V%?oyYb#Q0rT6mk3wUJAk~@@CRn-C%TCDzd{tE?0^37u;sTr@@>fgS_Po^_zL$OAQH{EeUW0y8!sSvHcoTrJem&` zamQ$o7pdPDKqX=XrTe=9e6}Ta-YWAbMLIesxL(bTzy0*lntv5%L*AS+nG@vz(Pi0U zo>DM+wOqUvep4H2Ui9K2o>O?yP~w~zj(m)lV-#|+7Y z$(-!$t)^9`acrNcGGplBJgHuapRbpRz~SNHC%YYtxw*Oa50)k-tpI(diU1N#7+g)x zL6VeUeHU%NWn2Xi0eQ(x=F&zC@&POS6^FN)*0Cc*foNW5RcVHEk8$GbKi+i|&GoYN zb>7PJ&>zNqN?*4?CwJDJC+1(Ix~OSkWE3;%iVV4+HSc0y)#hfvT9s9W}#Fp@QjO!ySu5vybqZ z$I8j(&RK)1vMMiJojS#P7nW7cjWTdS56%~zPfdRY@sg`6E7NmwsKQ+(M58@kNfVuB zrA-0J$;p1h|07OZC4Bs17?k+QT_~E-7A!?wfou=3gRFSW+9A?`_JHA7D-ePM6(~xX zEN6}e<^{t}-Wd=vCFgcdOivFJC6{Y|#KbfPUbP`=Tt6J>*L%8*b5YUCaw~Y?u}06{ znv2tKXHl2b)e*F=Y4i<=rC8FdO%EncBZ2sV2?`wE1IBE%uo9H591v zwNASKBwNA8j!;$0NXKTRMrc2@yET|p)eo>fJx)V))0>(|02}vXf%jeJKsz!(t3X}7 zz6ZXr1myqohO?!>M}PvBKG^N&e#55%KAqh4(Lx2sd!EYkQ`HQflu3Z2H(%86PYT74 zSs_o^HQ&vp4$l8w?5eBtY$JTlrAD-@G7zs#mkCY*9BCO)xioq6vh4r6Sbu4R_fcMWc61LA7y)?Akxm-7)MjrW0(=0M zN90=j_l*1SWOv+J))3F+Gim;zi}LBckZ7eAzOK9dQ!M)HQ?R!j&e!CYmY+0>ZtoaZ6`>W1A*8}jWBG9BaVZBd!Z=92 z^ti|%=?@do3m9Wyb_D=~4FB&^7b+H?teOALvG<^)?G71JlNK;cxpnRwvvDYiZTiiZ zDu>vFf{-E{iJ?ZG_=QNcbWa4ZCT`vF5AKtVg2>i{Te+Fa^62R1EfV2bP7D=x}W73ymeH;fD zR|S9GkP@)S7y4<2A5LyJ*b ziW!=T?=@RatAVj|M*xLPmb3aaT>E?fQgt=wOMx2cf99P*4tU7#>Th^&dwNa_OWoik z91mJY8;-k259h5f_>bE>AOEGb3JM6A-8*SMzxc?U5FR4%>f9Ue^mgDRSz`?T+Xa_SP;-ppA^h}#%GL$nOslwUqd)zRc~ zp3?6bMwLf5b$41>ioHhV$75dOl((2v7XP3pyp|*Nz8fQPBen=4{&R%0Y+mwiYgIZ# zd$q5XA!A;{fws#}oHoNLA}Qm+^M?)#7B#?3L}F*lCVyMcYe&Qzx4EmA&6<$g)Wlyj zCxZqqFCd&8pY#X#f|u7zNeaIbBLH3y$BAtc@hAOR5IOeE;d%3$qyq#HZC8%<;&yNE zN>M+q={Um$qIK0-3}H@ub?DEyGsH{vPHN!~T>i7e zNyVp!L_9W2E;@XZXKI1_mWZ~+`G{k|Tef7f)D}mkT8b){e&TDPe3aO7x0+>6&1rbDBc%Gk&9p6+^*q`H%`C27ZhbpN62c(oh4`G1u+4!AHa|TR1re7 zU+kwQTE}M#{0mVOTXZ9PqNVpRsreTzNu%UzmLaNIiot>SXNgN5U1FA(0uc;FQ<3GI9>1DwH#{eIp z5#P9$Ym&whZh|?Z3%=C*d(Td3{*309zLg&jHz)Ge7NXrV4IkG7J@2Xbo{X1U1)na! zPTlIWuS~wxc8H`Q!Pw2G=pzeS!CRz(28Xt>3BR&fT$#r6H@R*Cx#9f7PA`E2CL{glOet^;c&1%IBjoDzX>BdVHHASnOj zbV9xjoH{1&e5#izkuOb-B1rj>(}wZRX{xs7hYsdKNCI?MwT7`ldSmWyN@pGQZ0j)l zHe?$okJ|EK$(_(>QXfzn{TfdH1$yAQPTQ}XILfUg>PcYAt@>A}VZbu)dXPLnJ$$r& za3gz9i|^PHuwA;5G2?_O@!aCs)#)k_F8HwE*%RA{BtswiZ1)<@Fv(Z6D~Lf27;XGq z3M2M~s>=-WspskC=03T;79k}ueB~ypi=_nS_r+p>i-p6fQ>U7D-^5&0C;)yB)Jh%M zP8|;Ir3yT&Nrn97w}QPe<2UrojzRVDd&=NUTLr)e87&oroXZ6VDVZ&$)|qlZ-gjLg zSS%f$O&RRJK`Ko>_9yeWNPWfu`r>!|KwchLo(xI5U|;jSHgBuvpvo^<4mWQqU2$t6 zC>gB6cdHgY(169WC{v(C8ggZSghnQj;?riSfZq<30b(nn2)DhS`pb za(fCM^IO56_6A{a&@X2m+h0T0biM*X1Y~tYe0O!&5l)lV zS=A9}{gg%4H9=%4L`UzFQ}%lj@K2)AG5@)}Y=0&okX{#=0McKuY6CwzWmP@l(B59y zkLAKKHCgch59kN0B;<7LxIt&v$UL^{9(5niW}wJ7P?L74MOK1@o#ddW#kKjvDE%+D3+_<2mYf+?h^`XGliOGt~qI4j5Mp#J48_l`qk+j+U z!WlpjFLr5`TbHC@L?zHnr<=kZb$CN<`wsI9>{hE~x2>P5&YkYXNh}I`;mFBb$}ykU zQI^}IBA3E{d*1S-^0PrV4~o4!zssFNV~yYyKJ{@O0wonyFAi*cXsCX*hCU%#;9nPx z?!-hZUJ@Mxed@|E#n&%rivWs+alz+B*AH2nWFBD|hnflrM4M%1N8R^fA6EqBno&x1g-0Ao zNVK^yU_l~C7Ihr~Q?buz!?BtQMvOjY%2XQ9w}GE3eqd?cLT{`B6MtzwtaN8XRfmM< ze@JN$`iL?9^m3#}`!di)(2UqD+;=E$2nnqeu~#{hM$I@o%-O%$O@CN;GWHBuSo`)$ zy^X#Ex`viDU)M~$>Zrnsk;fC$(9J&QGac2T;3?HJA`+t;N=L`Wo%B15+7Mm zb~@^^zwt@lylVwXd|8b*l zuH#Z$HBG8l!C$MX*I;Iro>g=*kUfEVihd$<_XHaha^Ntr?0Q^uo4=b`Dhw78)XTL| zDuMXUtKj2icF#4dRmF2QSL-9Z$W^szuD#!^{T+GJ>nO+iAlij-J@CZUV5jjJ<5#WS;a;WZk~py~Av*z(;_fgc%sP`XMnX zi2@P&yL!ZabtbK_B6ekErQYM+CCKX~arwq&pacNi)ja@MlX;L^DsbtUdXU%0#fJokTQ${1bPxc9bhzDM zg1p8FkUb2Fg#bmu_mj32pLw_^_D1DpKnJ8pL%Se)W&nTui8Oy*oX(?B<;qr z^{9-*4;?m)zuugZ>caSf$DRiWi@hS~83eU}Qb>=-<9l;MugMGTgSDfPO<`Qx>))T2 zd|+{5qu}6PehsjCLmC_T8gJG@e`VinGfV#Qd(pSyhEl<~iUY^G((WCDA^0b2b@qQKalFCxFw2X;>H=i(C8_jAp^g^7quvzAaG*w6}ZE*~>@q z6GBjL4B>jw{BUS<*Y!JM9_{x11BkEqxrGXNm-xl-ungO!!r==>Gn`)f^Q}enD)Uwp zT1QoL(@o!;ym*MWAC&oXguO=^YRmDA?KwgqDTst6ZA^HrDJ{4qs|rqg$fz&5nSSL{ zys@vzYQY^8K)Tg%`7eJq5u;~98?;rLKY2+eid6vN0Dz{zdxfDXN&uos65=qzOw}EM znXOg8rIDpxkbDB~I1@H&Q1XcGrWjAxxOFE21??kzPl94jvA-V}U&bCPH z0J9nTH|Y=VWU~8DUB0Vyn2JXKj|QW%-I!f$Fv_^z5 zfxNi*E(s{@Ai%tu5{SF&+HHOhR^g^%{;8~~$;!-x2C!1# z)c^y-=iDajMr*Jv`rA*i;}^T9H&aM*CBaqt^Ii7OFV@DF#j>u&o5kb$fx6 zfK4GvRuEUy4EoY#%BR@Gl!(-uq8aFR;)8+={hJ(%$ED&G>K|ed#?sLB40EniKnirQk zaDNJuraL_0E82!2VG78gAaar?wgopknc7RU2&Z=RD2&Sv1p1fdo2AIoyord2$Sf&& z6OwrXNJaR%+<@Ec=7|G@TVsSv0}|DyamuZU_B!Lw;rQ4XD=Ey%EpOd{mH=kSz4^Qo27GK*UEEKz{o*_ zQo#Ni1$rCB8!Bm#7c-#K(M~k<8GjGxIC4InIpt|R#TiW8Au3if{qxO3aFA+Z*c%0? z6Eyyp$N+nNpXuf7g!nhdSmq9h3_9#utcN;3F^sJ5c^wW!B*+#c2SiOYt2GRNVo=D! z3@8B-d6Xnyh+x2OW}55Xsne@ViY5@AIi@ebc#IR|2~`?6BT7p>{d&M zE(#&fya9w6Yy!aEfY-I``rkImQ7V+1RBe{avz07VNRi8{ChPwUnZN0NA3;A6&FAL- zRj`=&*Z<^u+GtexWjqz zpTuLrRwjU;ZMkT?(~oQ{a~Tx1k{0hZ%;g)1Acd>gVj#xE#+A}{XD#KjWR zy8r2^m;%@r8m4!%c|c0XIHT3){`G?ru*DO_e^9>wN7d_cdAsdzO8Juy|f6kJ|juAT?Eeuf!>8?OuH=|hzB zu*M1r4K+^bJG$i@`rsg#^TzGD1BdoQb(?A>^8S9(>C7tLD1Wn`Wf&cn71_Pnf#r-> zUx<_ncriHAV^`N&-!9etSLymB*%QcIZ8C@#(Q^9Z>D=W%SV!^h&29AcPHk5!R}a2J zHf$M(2j1qJz~$SPgGEOt8huehBbFMtrjJ z))b1(_ey_dM;&K0QeBD@$%T3)#VsfsCwg;q1!PS*Ys-aWfVB6PJ(_e z4fWAlyFZH7jU}CLliB%DeT7!7l{Z!kTBgQP45^e>tnQtGe8sgn zBp=|X)rY$_m2q4u-_``YX2GFLGvgTnPecI(nsMWHOIRFfYC{h$|NN%3)4qL#d=>+? z?RHCBmJ=c#-RGdVT#F5Hi`lsDq=S1Sx}J9f6{4XOq3;i&HPyt%DwJh^(hb;V*!fP+ z+BlIm^_zvTG*CX9qw1@D$}Sc!)__tuv;J&5-NTk77<#UWdf(K)jc0FRZ6RFq##O!I zeo7=^Q~72Xm?Z_EPR7f_gqALD&a{tOAKv@@QZ~b%ZcWQub_tlPzi)Bq)p+SEil}I% zR;tsqo#RGU^^~_IRUT&PFk2x{ajewxE7jkWRFp|h45?SA$q5rwDDCJovZdZg-5o-e z=1rgD>W{HD`px_f7?nYk12s8^smWk=ki1B%+#Qk~Rp|7Lg7&!V9FdsAA%twK=GjU= zC`8S{H=Ng>X);3o+kL;9eqxcd{EP5_0Eff-)K&Ge#{eZE9wocM`b z|5@}D?ZVx*tw4)HutR;;L)j_fsRxPkZB>TdNrfzWH58|dM6y=@+S=T2MKTDiV{+e_ zZ;Dex9Sot!`ySha24W;{+glSyL!Gn<|1%93JkPYYhm{B!mtr)-D!SymA3TLp=!P2C z*d8fYTyjnOSoQi;L=o8vW-FRu`)XJ;9DcIP9ufsCX87|NtehZ+L8sdk>w~=;98c8U z*4{)(;;%Op5-_RVk2}b!r03Z`>duQA@coXmxIV4V{%Sks_eVA{7(ShD+$?&!N3EyP z(LXDc$4s9F6)em>v!TS5Yzq1D4yF?H{cR4XO*&*!C?PX)Rnc5R{VNU*e|hZY+R@iyR&J$F5_j%AT>?8=+v{;qI>U+ubyb1H!9sGdoZ0 zQuAHgx|SOb-wAc)g0>b$3N9v|d(!rwjINuNMPtkdrPsyBvJj}6+2TId9~wCnH9 zC@$X%Hl0(diWr@0Rb322<>&v)`^sVPrf_iEv0Hj#T$8kp#f0S8lT0!zAoxJL!Jkda z-UZb)952yTNs42>6!ORI8~5>($>0k5ow7*W(?Y^|`!0()VmLAR>KShA&|?G|&Dcqa z2B~W?e2+sZYt<2*k>P+j*1YmV^!&DD7KXbG+WB_Lw`*CNJ%_!H{*QJ!kSHdOq#C2= zfT&Kp>()Bve_hv-qN1=B#>3RCtgJl-B_$;?$)7N}xVTV;f!5rL_}3rEP5g^1h^j%R z&^?|yt%+X$iVjJ<($^5g z<7~MStoEa)&2Uve*-9Fiw`W^^f;d0zE%O!12XEiBt2ueZ2=`c5#B;XBi74N(*_zRc zgQ>VL5DRmMjkNc$8d(puQ?KU+%}NKh6&g1Wgp>D2AcokQkveVh`^_Czv}QeBhMqQz z3qhuc`pb|Uw-zfbns3-DA{h6o7VvT9UkMEA8ZB@|Xi6o_S^R3mr&c-}ly4t1p{Vv4 zpAV~Yz#a6vZPj5()mkJP;JV(HJd1BC%E5fsM9T0jJpz%&_}5#?m3t%jo=rrTyw@4W zY~iQn@XR(l^En5$d!4;C@M~p;?<#5*I`ip8j}it^3~JWL?#%__AJ`p|#81xR5P}p3 zbQ^@-MkM7X3&Lu^;;kPq5E*pIx|5|Ro%J6OH73tHjP`{&)1;(4<<=xQKhA{v$~zZf zm6Vw+a=#l_sXV&enXLH;G|$Sk-lcr7o{NzZ;QY1k3c)Dbr_>>Cz`EYfJ#Depwhl$3 zV0rZQN_0ukU2^gUC+5YU%_5){+Qmy^d92#(f;6fi5jwh24nWJe8R^x&5~hWV-S(i} z3Vh{#Y)kpunDYX9Q&U*uDL5NSigkCcZX4&0G_8L-mx-qt!c{hT4h_lYN&DL@fV34) zW_w@Al_xx*ZR3bX72PEqXIrWKNDa)=sb#bnz|cwOnA%{r=$tvG5mvK!wp03LhbOA8qGzP$E z;=sMOuD+gCza3UfTN}l$uDDyLB(PU z)Uo?e7}SRc4i}yz3&Qc~**eRUyX#SQB2Mq8Drsxh$n$2`OP<&MmZC#S&DZT&@!pA= z1j}nj>$`=yai6c0A6YBpq1fAEr5_X7j{P+juv^+|idf;~DfS=W_WQmrG{3)32Zm(` zo?Fr_0-;D`fE%xv>A~LFcTbw9n|tOm`s`$s?;=w2b5mn^#+W?(9fj+udG<{j>_^;w zZN(AgF7g-wGrkY?wEo)?7g^Rq&h+eiVrjVzxA$LQqxXkscpXn>*_v0=N&bXhIT}B>es(65l$rpR1uBY?^vb2QU52HXZxczr>tv< zK-l0d^G4Y*(7k-D%@rMCh*}SocW9~BJM1S;ueYrvzGcccO9kn~slUU$wTvCT1Z)Hg z1$44Jj(O6p>O=mW8SlF=gSkFj%}N=X99Um@oy>%-aIEldm@j!`@XHcSF`0Ed;(_0!=Jj~Md^|x4+fhlIL#t;tT~mk_ z>z~E4@bJleOJ+~hHHhR|VM|?jXW;DmP*G{26lG&bG?JtCcHbeDg5V2JQ|RTKfL&4X z@E>)EeW7p#E|bX`UPp7WOLwE-9~!N*PngOUe+_PJeoDxGyNE(7&@Lr;ysK=ZTVLH+ zZ#f@KSPCOuNThFmnmC+|`(XV1T{jH<((GQbz7oAEi6bi@knK|U_E$|RFj?&*%>oQ$ z)pbp9NCJ0FbO3@nnfNtvneP*Se-f5%y7}WA`z}XVMseiHen~$*iib+{e$OoF8SJ5k zT33Uc>|CX#&`%$JkLC#6at9{QR2A@N#Xpi?l>S~9^hEjIDG5?8s;sYsNNB;9(V-8E z=>pz@S|50;Xf?s!h)Xb4bT0T9acYUj*asoj)Ugj35igEeVhW^pTjJtxaB?Ry#)54QXj_cs28hl;$_hVQ3SzvJ0sR^yn!&rc6%ANA< zuT1Toz(54j)R{ddFkCw^E3cD1;x=%^`7N{+Kb(K;#u8FL~Rkd-Y&^;v>iLuR0gcV^>O;{Gyqkdvt zS>H>BjqX*~f|}6;O5XgMZsx%GF)wIfX(x`R78o9r<8M5S-Y?Khb%QdoF z#OmT@S~jH~_2*AW8@|+uV*Z*YZef^tasQoS%($PQ@nAa#zLH|q9Iv}5REnCqmQ=!1 zah_by68_ZDiru$&d5$F=cL~)Kv?(4Bj0RF@MvsBVnCyDg9YnmFzuh63gdK?7(31>K zIdP|Kh7S4k5YzX2cT^U{DUuQ&@wBwGtWFPl2Y!8d`{(GVS)XYze?uyFNByY50I}-P zCyAdL#KCmC>-|o772hM{hsm6WEG=q&mJ+#Y@l|ReMYjDiXqk=3SR#n*Zon;Wx~{N2 zHna##p|RRVf=r{ddMEevUY>uS_ESWmUOl_-XEzrNLZ424-xqBS8U1D`L&;RrT#vpp zI5`;us0);Hq;R?;$~O7>FW|0UCQipcSVZgC(cE zyzaL4`gN zr-}h$i$(S~b>kuuty8<5wg<|Z;E<5M+7x5Ov@`!comn&-BIlOb8%N}8@}1(e4z#noMiXjVpss+ zp!Q&en<`XUFidFQ&pa%XK4?z2NgE)0B#`+IG{=8Z$@($RUVX^_*+-pwaiSk##-)yP z(9HS!)erFGL7RZWz&6!AXRg7TS5jJgc+kwiVK_@o-Dl^8gNh^N;~n_2)A#i1kp|7- z=EZL=s_&w-B_jWt`H~D*7RRc4e0l^IJ_W(x^Jp9 zioSH{A=A>Ex~PVB-BvKS+-iw}WlI%<-(4gMQ=uDI&R!KxnwGT(vDl&_JL-I=O02G2 z9l2I^a=wuuE_kA-NGpt{N-r{kSAMZsIK+_4wGPI-@2%VLqmwzU@^%sDo8Ze z73X!9mcgh65bcH$ag_+QDc9vQ`C$N)&sv6+KRk8^rggIHEqYH>a_qP4t%SrG$m5bm zHdhSwXd6kUotcyuSKOvuFD50uhO}SQ#?-2<@0?79*%LNhy%{%M zj|0lUr*R&1Cb*^+ZOV(WIowBV=t6OR2QOxdf|LX<)Xz`q>{95;&bcS(1(#6t~_3NZs{FD$Dsu1ZwIV>Ysj$78Gtzm~_+`VZMKFXyo>db7{b{kRH(C*-{@03!?Ah9H<*!vq%2NCExFFTf zR{VOnuZHmdm|IMY*MpJ_-gAj$Nrr?|NtXQ$r<+&Ymo98J=dSw+H}CW9OHkcFEDl5M zL;;?>li9!)4sjnib0LAjk8rRjkqK)&m*+6GOn*><>^y0Gyt1IEfvr1iI^O2i(P)rQ zwnkrmH3g%uSTjSklZde;4iW;n%s7pjoT)P9a4qe|AaV$4d7hIN7FSTv-ImlDVKVr) zhvi2@^d%f=>*Uld`+M4OG=6(W3hlm8;9Jj>4$T_dcL`yj90ZTlX>NzLx4%cHXRg=Z zc_4APce9&R>9ON8)7A}IT5yry@&&%pre+mLOh4>bZ+=F)tGW_NGH+2m5}1(T?JgT% z?ertv-tOw>PAapc+7o=zS|9EwWBfiDQrCF?jjd7ow}Ax^J`!|XmG4bIYK7P2%EZ7= zT*<#@<%AOhOEy_2RM<1D6*M{G#U1y^0=?~57o(1MCdi*|c3|Y}4&+e+nM+{dFtM>k zM`ASJ*RtnITr)5}T2O9hDKWp7usLl}_9L_@@rL6*j;a!Wv2|-p^=g2vGriU6Z9<3C zH5{%NpiOOQHgmO*=A%PP=eRPlq_wOe3TcitI@|secuAkWLPdS%_{4D}M|KD%cB#yT zgx?wj6F=+Y%hIdmJy!PHJvrbGtNevGCzxxl3i@4-gIcs7Deu1(cB?Nqy{0lT6Z-S{ z6rnmLluiLur6vjx-fOhZ;AoJ7TW<{P_;xW?d#1>b#Ri#{Eb)l}mYu(--noef#whq@$IK7dkuFjRQI94hkydYjqB>AY? zQ~D44sX1o)r^f2|xqIwI=tcz%!@Bw{U9+6i@2>IGPTu*aVz>Pf`YVue``I3WMhL__ zt?jlKlh3s}^IODIIvw%-rNL9JThMS?q5NiFOo3J%f$~$c*pX{h#+?_po2n~U7NKgc zOWf`O&_m^;fg53zY3TNt~&KRl;+1;)Vp1?tut++Vnsc80+&UwQO=We(I-Xa+ytY=p};2h zM~3x`55Jah?6|MYHkbXU0}I{8tEeyU-P(%9A9ubbvB37wvlrDQuw3@7DpoTdZ8D6z zt)Nb&ew>L!1C1%+tX+A^9M^*jRI+GVVw3(6k?@cF>5f@{UYpJ4F$^ud{riHbA$Fs9 zRycLw41FM#>aVxYSEgCNnsAGFACs}T(G~WgDjBNE?c~b5FF)tLme5QejgW=wqXsZLfaDM zz_87=(Ja7`(vL{xiCY+JT;Hl_)%(O1=1TO3<>8%uf9`LrGQcgiL&|rNkkX`$v6P9R z(ivUPuj#IYB~n&WF#p+Gh_*LXthqZ^#SrpGcZI(H3(NcN-#-t%-08+gv3)!Vgll9M zXKGJ=Xknp6JB%1;?~sAj=Nzq-zXV50R8{fC#r9xJLp!K%aSa=1Q(?rJ`ub{H%;#CT z=?HE)4;ktlx5sD=UC#v9)LL;TM-!*KU(wtNvO4GBKlX8TB|x@FhsHbFS_8MWD>NCLz_syXkMX9=IGlTyALl zyW`KSmWOv>NHsM}JyF<@^L>+@5L5a%CsCv!4dk+r5ylOY^##(kD%4D}P`Cw93Y15lrDA zgr&t4%NR!K?TFaLP+PWs((I~StvZ`)SH%CpI4hN&&rd=w>9&&)a98ux5XCeos%XJ#2D$)-y?unh&b))%+c(kS7Zq&cP7oi#XH$9c?9tkh;=Y{c(1B z*IuVIng9PI>o23?Y=W*)n1tXEg1fuB4@?pyI0ScsyStO%I>9YS65QQkaEHO&-QD#Y zazD@c-gDkRtYNLW=IXAlt}fYKdrDDUJR&NyI#l5XmGArTt(;hbZ;e^5nf4!dg zqMdyc;9a}jD6_lt3~zdt0(a^qtmL}$yw9AZz>1bRb-lbZ0;5?~PGVn{PXb0pC}wQ9 zd9NFqL2A1sRU>})kGb~8eYCv4^xA|KJK&N(6nUy9^6w9fzH&N*~o7Vmi|#;n+(o1TI?bC1;^@4faf zPghVk*THLaVBFG%7}?ua`FzJTQCRYV<~963%VIZy76IV*H^yHk#p+BL7^uc!{nedq zZ}Y^lWym1w$1*5cw~QKacq^bwRUpokx;T~+V1`oeLLF1OQnm(~NJkKDeWSwj4F9Fp zhARKDh#7yB)k;89NMG=hHA;KT7eD^yEMn_NhO`Al;?j2Wdz7c!_le%9=^_+mAgHI* z`Am;|GTx?V6=~RUCF|#>4zE0HRnOLbZDAImC93=%A3GwQlJM(0M~gc`Cp#8{{=U-4 zMg!3;c$U5M0rcjX5m-5lot}a*$?d6&t}RwSz$tr7#5~l>@S|(NTp5u6H%$XgNl8i5 z@{!)&JPny+5nD~)?KdC)%NQOvg7Q4t*y;|I>2=6drWAq}-CXoFbOlp)hzXdcMeAzJ zd)d+VWv-zFu7JjKG#^Xi1J2WyMqIM0^Mirxn{Y2lnolxwYJWY-RG+oOQ3;6#;&19# z{<@oEFZiJdq7$OIr%Avrvj(S|m~1IVpLe&aLr>CwyWw-F5EQJJMo?@u_D4Ks@K(e& z#dq5W5a43sfAP_i48kPHN8SQ5vwad_;ed!Nl?(&d3y`L<^T8GlHy?wb%P!8ak+v-A z%C6W<(7ZhajKhQyjfT4a)gSy{EWj6ar0r;2^#0HfpRp6Y&0bxAzB{$Ges84LF>H=B zN7{X@R2+u&`~LlVH%~J{#`QTyy#Ia58)Zqz$0d)X2d1#|7TUs0tzsWV8R@TF?sAo8 znNZS2cW2?zH!65|c-Z2f{*GnQ3#6JtNkZRimEekhwRdo6_-6}3e*Ch-$tdReH&+i7 zRMhO(tv?2h%{fnR$hp`=tr#LWOD4V*<2LK9KBbt+9yin?Je~_Y+cKg026vz}CS#ka z6?wqhIm8@7nYi7(0nm5S(a}L^ZA5DRU-_N3QRU_3Z@lQC8m;*A zqNL-0JQhkjXhwjgmRTjPmqEisFL?SFLqsLCICiF`%e1_jzh3kW$6D3;fvNCEJTI#? zk}=jlucdbomgHlJN&zMwtIld)43(I;_|nN5)bD=F%F4(7Dd#~L8#*TXf8zYF zQWOKcV4iHcs=osAaG)O_O{#YTX`#&X>?YWCH zndJ90f5Hv_86v%$P%LlDrqxi+a%}9@bgZMs$q8YW{HL(d)i+)+|0&zQU^Vm$h#}OH zaYGv)Wc4y}=s1|lEC~%UKJ9iGC*z7aAbiCE=FDE3SUe-gwOdjC8`o_NOyU3N>+4Va znZ;4hUEaViAGgs=y{ltD+|9&|@yM(&Z1KK{(f-g#zU2@h)Tf1CXgBt@QY{I2Wrdq9 z)`taT${U4V#jY%vx|ToYT(xcSvbHY6)iWZyZBGnUrK zvGuGLZ|Yv3AT*J*xPN*8kb+VDH<|zbe5D*3yv29P3$p3S^zfVbrkgSZ zej2wmd$vKP*B~#?-Z}kr9FVGwwD}|UKYjYYekVXa2{DfRzJ6&py;0bOCf2Pd*GYDtdpZ--&? zJv!et?8-X zhJ8>X8GVt}DAe4ZypOi1=-*tOG$Is&KnjWEmr#P06HjKS8j;FR!{|0TH>_;DzAS=C zy>#{D#19+-l?ABTW}$YhR98p^%E&gshMn?U>&zvr7ayVYPyIk?xGY-bmQ#g*Iu3N5 zuwRc8l;^0ZxY;iSwA3%F`MhEgKa{dK7+R6l+TF-bhf3*bysNn2GM^?WXEob)l5bXr zPcEQJv_3{n;~n%*9m~nfRtpLX>80CQY5$osz%g=~xFxcV@W@==&zdB&@>1F8UX*dz zE4|^h0JV-8r8^_1yW#YLo4u(bb+QM@Z|EA7{(sisE8J0l<+D5Vun3FZGcZ{moQQqA z&wOhhZ~>j`hT`IrF7f)3;7zrFF5+|rPHtN?wQ%~D)SNisZ|LVVfr zKm7;~@*rm{Be(Q@Gu}RKMyye*Zk>H z_q{|zMN9z%*n6SO=h%{8_C;>>v<@=zhKwsj`1l&ky?9VlZ{NuGMn#k#A*od&M0$%} zKZo$mb1S#U9*V1uOaomABu%=*4+Wp=P&F}qz%xcgPI#nw1P95SJ?bbX7jB{LZVNVl zPc_r+rC}t>iH_g#5U>Wlp@s1oFh6PT3b77MN>U%up31vhdt3^x#x5-(kt1PaYX%52 z9PEeLb&AMpVfI~lW%!z{Ui-=5Ptf|Gi>T)7H4twViu8A>(uECk?V7C)DcG@l4|!jw z`Hsfoc6Qr<%a1-|i=%yK_^qvZIfaz5I}r_|yOx=W=@7(47j1v8Wz7LciYBH%-@&%P ziWzqjA+x?aK7%iG!Y=}O|3|qBIlf`=MS-^`sC**{%?JA3CD49aG~u?7pL;AijP)fTdexur+r&lEJQiJK4U z?KFYzU9+nT4ulum!$!xG&nja9+6x@eQZVU-2;nE6y2uk1BgzT~hRtUjV`>K0@72Wm z@$%e67Yrz1-!!wu_ou^5OS?cTy1FWxJnCKyZDxIYMhhed>g79Rx})>5$denwmCUk% zEP<7($0qc>lZH$WQ3Ot#iIQJsQgRef^YWKa=JflDM)mRAu{kPJLNr2@-o`2rH>M%W za7b9k6bbOc%aZTD`m9~BccQ9PRKUXi;1uYpFEDJ^X{E#nV!6osiHY|`y7cQOlmigv zNQ0@Tk}&vRe2+f>3m0$hD9Vi zpZUO7+gQikUmG88PTos)790YY{celc$jm^ag_QT zj23Dd7mm!D2m=%lNoS>j@8CjNxw`Cnn`KyGesAboY9vn z+fIBQOYF`}tEjs7)>gvZgH&HQEH}xu5~J34!=(V4!$fQf`h=~gNNKEeS#PCJAUa}LQ z%+h&=dqSC1nFZK^QR@?uR=Yn8IwR;dAPqS?{nr;dGCRxGmUImqrRTI^tmS8CeecA{ zNQY`aFH-%eJ+Uaqj9Xr!_HZtwd`rp@zq`n(PuGB_IX7_ePzV-y{VU~7kj#00cr=ym9C{Q;*c;y1Mk-YQ&d5s~a_ROa@w8z;frnegVE4x% zxN=BXRfWnz?#jW>!C^w1yI3oL^+MiIu|oq`%SlQ~YFd}-?M!~6qGYs*(dt)&mH-ew zvk?e{Ls%b1NEy7x8rkmmNxn4$bUhA@-cJ$KF@#nT?QoW=!+H-2Zft$c!~>&JPr~58 zKX;Hr2Uxa3mW?@Q3_yi;ro~R%6O};>HV<4oT9jv25{fHK{-1y$n;7+wc}k}u1~zNlc6@20~-4jC)Xep7Cat4C4<*l*NUL%r;pQY zN3Izlng7|B@QPkn`{GdS8M3#ZJR?%x&AFL5<*{(%L}jsR&(kzN|LzzJJ{A(!V7yWS zbw@`md*L2LeS95J>zS4cH*oCRsX3IIK14!_^6-&Q7XN~%r?wM+s)P~As^@IzRKLRG z8VlF=30b5mm;G@fU95oMq4}2NWcUvKhBRPLnJE>mYQ^Y^f$F-|#zG&GC}wT3XvbUz z){pm0ShlJPSn>QeNabbJj;98I+5f{b+HKt@%nfhgh^n3jGF7kV-p^H*xBbY zSbm%97H;}{id5X3^;i0DqQ+8l*Rt{q2W|QW7+i*d>+LU0C;By()zP>YEmDq9Y3gi^ zIf5dver3G=aWL(YwAEi*Ze{cD3tE>K1oa;M_GdbDhkui-msq`F;@<)$yY*hR9j|CM zpZ7S9Xi1Vx@=xX|gDm;Qi49f?*s-^8{p1dM+d%S)cM0gX-^6TKz3(w0tu4_+dM@V2 zaUD@4Aq~mKn>}Ys#9-GrChhl*B2#@e6A$(H8=nUSpEb-PjUJLFZW(ep*ibD)p7yq6 zpIqtcqSOT{xI)G1Or1SC@RW0O(imBGl_tVMu@Lx4a{Udd&$gvRJZ*@D(!JQPr+6oQ z{*a(8z0vjYME6Ulh-%^FLN}5xHnKCEDDG8K#Z+K6o#nEtl=g@%(3i^#IYy@y;R?L_ zf>~)wNBEh)iV3q<>y5ifajNCDOTHIVBVg+757%?Znl?RsAnEcz?WmIT@hqa*l%$~s zu|+sCGy%cm6*Qyom;SZIQq&utVXJAZZ6#cXfp3og$fL*GEr_seXf-{2K^HiQe93hW<*R zQh^iI!4H$*Bvodo4vhJxs5oVQ?adK5HW&$bS#srt97kz;BX2dK<$0NSafi=&$IW{bH6sM4rq`yY0KFQ4*nP-IW$Lic&4sB5&^GK<_CEiIkK z*`yvgERT^*-KuxuA6TcOTKev+&Td8S7z3Ukf<6317m{etuCX*Do-B0sCt8cJ^q*Vf z{_-Kj+Mn8ewjttZEdZ+h8a~&edaKTP0<_YSJ(6ph&sbf|m!)vj zIqw|Um<8TZIhnRd`seaxPzde447yo+7{Q?l#RovH?bpw3Fy9|i=#_+Z^w5AfVAi0@}_Gr%^su;lMP#2dKPxO8pC0Gsgw+Zc6IHgGc zB~Zb0;O6dECN5CnBSV{F$mrBc1#bfqBr5GQ9v+(XX#pTQL2@Xy!5Va9_K1+lS&$$s z6@~V=V1VnSPWDam$u-#*@`tt?69eJcHadQwGCHM1lu)tsD%)y~=dtC2KBgtr(YaU6 za4|F23X6{$VK{F(3?7zltj#`w$0!M-%&OxcQ#RXZZV?Y=>z>v3?uxlFSD)h{PQBo7 zQ+V&()w^djk5b@EH^=QAhVzRL5?Ep?2XbIHHmDq-WrLL#XX~`Li4?6<5PFpAb0|pg zqe8qL=t$UmkBWbVnwC_&E>U9U?lRzXi*1hPWHw3XlrpcSVA%Pt*7YfV>V?=$OX%hY znGO=&?yU>vk=JOA7m?O->!$z$pi{$f+-3fT?2wC$LZvh5hlusuw-#O9)JED{nz?LD zARh^4ZKIt)uLA7nsK_sCdOXq4zzOR3t)Gql5l2xg(Ms47*#oA;d9Xpg=@P60pr~d~ z@twpRY#W1rfo~0c$@xn|{%dyWaD08_BMZ{A1;!zBo2yc*IyC(NP5qL~v{kRRE5o3< zjvUYKVTGYZk?X-FH6i^GoXj(D*|FASiRLcWCuo76%(gFu@BWDoNJ>hBv{Z%Za~8mt z!+nehXyqp4)<~-CB&6yu2wwEcNi|=xm@Qz^8>}rqnWZp%Zg^L-@>etGP&w~|!^K;v zFbwNo<55w{vNug*JTy3R4UN^MdtHs`U*^8PV4FQH8>+1UJx*={4hzY;_PBw1CF;Mw z*+EmF#(!ypoLKnbTUyxkSP9#ZZ_aTTx_w!fLqGQ4zA!MQL(Os053-=kUsf4nFu#Hwg$g2~^yd2@_|U4<1LY)!*z(WAVwL=o7YsA;#mCX_F+t z%(J7#3)B&Y7(M|a^!tI<_^B;-ZphUangy&$F;?5;{#gh8st`i%i?H60gk$|4Ngr56 zw2Dhg#&;IS(C~CADPlON3xg1|wC+Z;y{wvDOHKOu5(LPeP+qcCj5Kuh9U&Vv-lX3a z%-==eim`jl3pr~)kzQpy{S3+kWmOd6R%=yf$K*;rL-Xjb`q$kK$Twrq(3*wG>RbBD z?$=H5v*nM|pwj&;Cc_F8P}rgKJ&pl6$;0x`C;b+hrIstP(z}FVbxzOF0wf&~?_m0F z!h=_Vib*j+FBkkyMms28LQAFx;DxjD6LC#g z^r8gEdPHJ@cs?VkPwNe^geJWnE)xv>))Vi*HBA&*Vd=1-3S6CA<|^EWox*S2 zZVvO-Z*lPvdZ~NcQ1DPkn!|l;PoCrB&b*>qXpKK0O5wRSimpxVT~mIzJ!&E4Hxsdx zV?Yq5FUZa*$S(-%qS>xswJIsEeTzDv8(*&)*5VR$z~Q+F9m|ji!nB~Yb^wO}&R^u< zF8+1S6&RvsOWy3l09Xe)z6!2Fij%VEASoN2b7l(bn4akUClQ0Ac2R4O7pXsL3I>Y` zdF(KjhQwn9weA87IKJS2>h&2h0-12u3;V5qcefIm%7tD=u2OZ-k)PI2%vQyEC?+sH zNGqPRRV^uc8~hdipTFMe{K@^I9^+m3wxt{`%0>fU>f&w4^ty@pNeGQdV}5ftJ_ zb*Ks1&ct2!s^GQBw2R1`!!fhDqjk117%W_wvH!Z_kFKpox1(26U$@&kN((%jn;|=w zEAXAHidfzK>XqT=_kmU8YmEclVw{Lc=XT{KfdkPa4^b=p3G@(vlP_1exME zwiI3=$~}CJDv84=maiSnaQ1PF6%|b{$Iptb8fh=B+wLV%ldM;f$q_5_MC#8#1Z1q| zi_ASlTZ#YdfKGN1r{_6}2od$>TbugEo|b%s+EH7UFVF2k6MFKa9;!`^*R87!K=uCp zZzq2ot^Lu;43+u-_HHl!K4;^phSXHPY#JwS_^V7KiySL-bn1 z=^f1lapfoKF+W#Y*NaODxbC@WWrQrP>@<)AIme{eH-|C z>1%gtU^MgVdtJQDqo5Bm82-CmfW|fRW8lZ)vlGEcUl$S<`2Aw5~(of$PK0#(*DYyMdN(*ej)>7!+jQDrM`-wvXHx7*H? z^|`=_>GqWId+ySch4zX!HRiiY83THr>n~5~WWJI)wgGv2ntWc}p@*L}d3J<<2?;tL zhUDltS@zu8x>QUBuWuT_=EzdL zheLEv_lgbGID$T?b(BiwY|8%C##If73%u!XGHEY{vTAQN<_rUP~ z!8Us{vQMOvipR5+Z{`hVt)GI?q?4$-)s{=_`d`TbumsyyQ}m7>+nvLC(+vL8HDh$J zSyPwYRxg$UPdC~q0zj@PHHYO`YGXdQA6R1Sxj~K#7V!7&G^^sH$k;W98(mfTOJI`@ zL+6(|!w4Fwq8+vpdLut+t0(kw$V?H~mk=!t+qwzz2ymD^2TCYt4F%oXRas97Inx{A z!q`tcY=H=xh3$Z(ut2lBhb2y?tRF$>fS3Nt3&ASWNx4d$*YyXVPL{t1tFrjnndZ6J z4K^|PZA2u&*4J)x<@!{7?`!P5^IlTYv$7VbNA&LrQlk z5;&P^*WuYYUy)zlcvv_7e0vYy%zl8TMaakQ(|6!~tMK7&CZ@c5!v2Q`mf4w;yHzfm ze%q<1C%2aVd@JB*ZtxTH!yWnB`(ga^=fTPFh3<7bKBJ`@Sla4g_ijR=LLM(<5K{#H zLKTy)pxYmxh~UYh2~ZiRYfC=^7>Dt<6*J1ljor$e%@f=bAYC@H5!aef-XYm{w)9S* zI`6A$i*c3+ZES4pYqOh|=La?@&GcaN(F!;d7U8}9YTKLlq<}uZm!~8TA?MxEC(_#g zfXLCD6x0$o zpCgmx<;)KoHs+9jJu<7A#xf#}Tu}jkIpQiVAEt^HCe}+hDkNm6oLr;J^Ya6aoTY`C z&ZRg>&}V6D?y%`-{)3XOKSdw@NWL;ggTa2^>(nRK!{p0*`Wu|L%Z%e!6Hu+s0Wa11 z?cd2f*W$C=$NH~JeZ`F=BWdMpdgn@w!7K6c8iqUwzI{$j|N(kIi!F znv+j@PMu&qeR5(+*}D)%XmyX}tV{;tLMxdT)5QdZg{G#7ssAdAr1$tPXm^QAs!uAYZ20GkJz`BV5mU#9!^X!Mt~X03 z5PU^YJcj<8QQ9+N8!QMc`(IhmrH{VI=RLSG*z-9oXi-!-Ea`OEm%qhn#PEl?jlDB# z#&ag2l`w0m+m+a%&fqt7=D(wc8@rajhsr*Djt4}IkmBv=kgBMvSP75FHvsftrajG2 zObjA2r+YAxI(%ca=GLLEpgm-4b~PFDy_gBmecJAXUvDpLB!r%087(p^p5$(U5&;&L zw7f>BKE6zuirp_&%NjE{`8Csy()es%;o#iwA`~_9T?gH$q&Fv0XNa;1&L3tbWY((e6-XKso2#kG!n*nj>tr8kR7h6(OxmQtw9@ zkPa!&2WwzL5X$dZw=sDj_kB;K-Zj_Aps&%vc~Exat#ZlPLUH<1+B8o1#*Pf(AtA`* z3J6(K?38De`d2webU;r=P|OLmdv;_J*VdT-#v)w=@LI*rA1Vvm&+9n;6J6+@e8Yz} zo$zL4=YjYYGlFP9`8ry6RCAsEF)#C$2jR$&)EY0E!ljc>fXU)BE52ldqi`dALgFH4 zgUttBd`;q}s;+@InW^t-YTW*-6_aXjw||A+a*TMxgp{>?96mB^cshygKT_0N+$W8c zkN#8hUPHtUDw-kTUnFh+Rl)xYra-8#hq`beLZSz4j({@x6gDC@+(we?!uk`Y_iOo1 z{_TJDzSot2LbkkmlyWl}0+cFYE)w;^d6_OECu38=KN8P;M(+!9Z$LCM5M`(F7ZqrL zZ~OnQkk{`FJ!GUx;%1rTe$1k2Fj2t`q|IJ^k|V>}eq)xio_?si=LfCRcl>&%__+fZ0?SHKnpY8GQQ4PBfeyMCx@WI;c59>dM* zX}?%dFqWCC_ePLD0dQUBTB7J%SDDnpM6&n)vyCF!z_*yvsz%d$oFClVhkfjBifi6yLDhdygS73*ftf zIP+o!nygWM@N&)`K_Lyeei2S!aJZfIJBB&HQ zpWBC`k-S&j$TN>4B*X(+&)&IaXvyklF0OFWtm6*?R|ZQuXu!~UP+G1V;I`J{gXTi& z-OuQqn4Y_eR!FHu7Tmth2dT>bis>Tq8gaP0B%D7X=%jlQ%l0!PRFk>4f^h46}um> z_zK1#(=RUGV{B}f7<6{H5zJpm-M3uBrIk@@zJJtOSYKTa_qr?OJ^`jHtW+8toB274 zzuCyCk@d5}cra8^#HuehcyHwC_Gi$k?EH-FOTCLP376?}+wU}@+sm4<$IO<8_n<$A z_x#W4OWflqzjI?gy!n*+c~`uUTwL)T5pH2VD4d=$T!ZXTcTKe-%b#9}*wLF(Y}Bv;jP)8MZL$WvQdk<`#UO8$&yEf9Pg*}nu12hlEzf=Qq7MfQ}Z$wq`8TySEL z5!Mlg}^JU)a;^*KJVT4hhA(9A)s*W2JfsSWKIrXly zjA90@A!wPUP+*_?e>%hX|5?t1wyKSO59=Syq80DCG&-6ef#07ZorV~H!6g3?PajC5 zATE|oEuZ?aM!5)rcw7bUU|Q+URI8n#-b!Lv6!c|6`vUF|in~|5T~pN4N(k4q4|M@r zQ7yV*ffW4jXuHd-gn+U?2U!%T`zi>a_~FO;_JqVb z;r78eySDo~Nj>e9NDt;x0;Axw6+cP>e%H58%$fEtP2iuFKb}r0X)l{H6WU=@ZpW1u z@nb(Jk(z-^x7-oLvjKt`rJR2v5w%bZ=CJ~FGliqxz z$XBDjF7Xmj@*sVS^V+)xBW6&=L{8%l4t|{o-+lRtQP9Ja6(>QAWe^|Q`*?9YVr#R@ z;_Myai;9?-^!EBL%m5QaDe2S3iE&SIo#xn?luiV=^9VundW|k{u_^w|u%!{jk52)A zcIz(LNDoH8Yv%zFu61J34=EZxai0y=I*u;?5QNDf!RNDJe)_A>%1qlp&~MzJ)}1GP z2QO1LzVRso--iSPm%Z~#)p|gP<~_xr*&6tFL4h} zL(nshjq@AO+T8M2z`5B#_o?@A|7>|pVAA`q4XBtH@!sZgUIIl0At6rp^ya2h8J1Sk z?X4~j_E^ewBRq-1vu>yZAd3I*IIZxTA$BYy{X1I`Ew>kk=LD$MORr`NE54a%tJ@L= zEIV+pd7smHkoL-V`vwZ9f!H?^=>fuk)6@LVlOEiw67v|>+ zdVvB>I!t6+3Kf*<3|I01M&D1j*witu%X)v!9L8^&)^I*fF%}R@^$XfTtGTB)nM_4Vbn4Xu4UNBGp z<*6ZE*5EiwO(hDOq_Z<3C8biofZbc1Hl--m8xY;*MqP4CXUVQHs{W4y6|>79RI{>J z7qi$ep6K4scadX%>&7hRm3(h^O-PBnp@}g5NNs1-mKNV{V`cq$)WS#Cl`|dO6IlH5 z$_c5TmUmbYtW7ISxr z`-LrNsM9K0Na#C}7jI`Td%uEEM|(gBe`+F#g)2rB0X_Do-s-OMzrNH^1E^@S>w~QtFq;_wcoT)w-yi*5q~1D%L=B?;tii z>D8cUp3|EmsUigMw~2P^#k8fN&1)F~Y|M`>&vq4cTFM>LE^v!stw%Pkq}u5@8;w{b zxDp3nS5`e1=mn>%zoFSkKu+fX=gWeXGV{&f=&E|Evm}Nk7HcXAPJGyZ^<u6A z5O{K%iygG0pP!Y&0~$_6CAhBzOY#b%0NU^Uz)n=^)1^{J+sgFb=N`6^wT2}NaR~4y z>&u=Qf#`S0Ne8`7578WAaKRHM<7MuAjf68wzibkUf;o;ZMy!3PgSFauEM9IQT{%0L zu89YQ*oBgC=jL6yb_#7rORST{W6?>-q?_q$a%bGg{I?6t%Xf~j2+G?V4D62F7=af<0o zV-qq0BFfN@w-|)2aAOlt46n^1_xxDiNnlreMJ|HtXvsw?eJkH>wd%` zW7A=k?AMNajO2D)@;-9`3ZPh13Gt9LB>|U9;b$EsA)KezSM*-Biy2=eBq&t96`~rt z4j3u%hN1XpXs0)Rm)w*urnv5&O_}BkrXme@rS88j*GzGZ<18-PdOPnjlQ1wEW}(y; zq6gC@Aaqs5)P8o<*MDVYBRkijBvG}U(XajUl=N)otA9h$(s@H^JXVRFp0L3Z;uu;t zlcc$4O|BSZL?|EAc+Hl9x=pSQL0xLhZkuVdRB3P6864Ia2G!j4+V3GNEK?c_*6lR?k=D#Wc_T&NGu^VSO#)Wv-S(PBwx_q?IQAh{cb*{_fUk zo3zCJ9^u!e8IHFM$E8IW^YQI16eYPCTUr#V!rV!6G64)nSjBD%s!t zASRX_tE8pys+F5>EhloL{))byO9hvV+Le=KftanWt>16&;MVcHw=37T62e#tEgEX8 zx)P3Y&w>ais*8u%Fa8{Pm0A7tJcb&Gu=tPv{HX^2^NWjq2!!qGUP?*|kAv{l$J$Yx z!z_d$B^4J|SZXO$NqtrIhuL(~+in@p#HoH^H>L*{ER2`|Q6!buug9R|Gt+oOJ2tpK zUCppLioME3New!j`ld|D)Ql3m!oR=tJk`S5&zbCAH%vn{!*|AiUwYfgJ|dvWO!E@Y zYJ;@0zG>m;cpikR4V_|_g-W7c9&}|-t}cXJ^h|bxESH`_L_vN9U&l4Y#74Ti$KJ$8 zg|PrZ-U}%-u4^@j4{OLTKwA0l~nH5#HJYeS2~w2L$=YBfO8E z_ghz9BcWW3svgUJ|E4W~w8v^3 zr7%Zf6QqJc+R^%6E9j{7XKplaHs}fYXH;=9%#0Pj4L_itI$rKDdll1U3_vY+dL=K2z%$dJD1 z(bV(9$^dF=>TF>+1lBOSoyg?Z8j2Z)NClUdhfK1qx(aEyWhfXyh&#Db=T58eUC`XKMQwAaHw|$=j5j`!j|@a70Zdp zsQ3ME3x7E6!#co~g~*an-uY5BnM2D3Y(|)r;q!yt`QD#&4a)tmgM&YKs(~QjbUI}kI` zj~z;;oJOGE3)7sinP8FVOQ+S$&gn(7c(G1ZP&{FJgV*BIWzkMROkEI!_R)W(E%z`} zC>>5)c+Yv|U9fIN9NWrEym(W<9+xd8)w~*;=LT}zEMP}?IqeDMOTYrh=JP{+g#!$p z0En3~+7Q^c&cJqNHh2aY&w@bY)+2Vm21RR#AG^37DdLTV%s`LE9pF-nLU;q>1Br z{XBG82V8FguMLQFdYm4Q1UBYXJU^Mu5%c)3%4KqHl;Hv%`t3^{-7dSK<^v$D+`&gr z9~wgHDQV*Us#MVhs2jiU@8L6QpsN_?^&6K)+ekr^l#tL9gDSAusD-W*1(R*xffd1_ zRF#C}M`);up?u;;;gBDq#SaEV-_wIR?h-%qwgQ76@^st(e9>Obc#T@+OqY)x06KXSLD5^U=!FU*o`-8Js}L8b8P@pZ)fh-YRwmThAz_gcR}P^ zS0~w+_uNMH`Or3`z>Uk$iA~SrndApn(&@??*4eKcULQ+A^d&%b}XZ zX%CnhX4m&6Pq773!u2%yKUo&GD+YYgX=xe2vTM`5$^_TvOp9AMy?hGqw`ej?@Ckm7 z{319Y;3y|`!Q|sOS*p9M)%FU$iO!n-y>jR3D)@AK)dskv!m{-w0@Gz|49CE0i+IGZ zDZ?gv`62c%w64eG@p7DR(YaTfVXxUnx3W`GCdgPw-*yy8{j86%Hy=*jAyB>#5m3E4LNoOsqrN~Anw6Mn3VZDHV(7s@`2 zyX&{b?21c}>-Qh}DSW_$>r7Y5#zdi*89kX6zH5vRBtNbo49yi+w9D>ISXTglLebr; zd8^|7`ULH?|9@n=G4#RuB~2_zD=z%`wD|{~y0yupDhv<74kbp&d1OHn}mXI@Nbf4a)uzQOwBKSadGummVAfm#95t#RdWg7FtN&` z*_Qh^O6Tgv3QJKYTf*9H1S`K8QMNp&I91LMQ7Q?tin%m~B|;wC?mM3d6gNH`fT4iZ zXUNxux7y+ARb<9Pn6)fi=u)M;nBkXtc<^K9FIhEdu`&?61PMZ`ju^g(nw84 z!}VulIX{%y9BBHfdSw*an(bWH-L)<~6*rV(_p6sZ z*L^62BW1F+iptWovs>1vh`!yur!Lj&Z@+#DJ1viM{Dz0X>mw=jLZ@)JP=we^ zt=YroExtpSD~5qrQ^)H=IL&h9c`=fbi@UVB@Hhe6o$JoyR7VYvv#e0lmASLw>gW{X z`|quX6S3B7MbvWZES{1_G{41q81s2_a^_&;J2M?RLoDQ=rmcINQ50homeD|ful7nM znXP`d8v+pte;uBAJpg#8J z;K6yMCC)`V4so{r$Gq+_^-ydlTgAfcm4sa(*ul^X(g=yQf-P67QB!S>2jE~Ze1$4- z1~a{+Fg#RLVqF6G4n5*zan*k`UF}@|#nVW-oFq6XwLU$&V+*_7HVi=TOHL44D|}g1 zi8az6hhE<7mq*;c29MR+9}AQxa|sh9q|3b15~sP)}U!N@M$m+}-kk->HSlTTSz zx>~O2-|m8giggLZ7kbpkt8K6cXMB5uRdE}2mGRU&VP7n#8VuK^IS=V-A@c$;YJ>+W zVw=spwu_-@Y5QrfG4?M76Z{*MaC`^6XNEnL6my>=nG^$Avm4KVP_!}s>k=t?&I3h#>(3WMazU=MJ;9|3jc+x|SdJwHQ8 zaiq2N77{mGLf|{ULiLNDp+!g!jm%vYak>OcdkKMkr|q-d{O8)dP37dIp%MK$`)r+0 zVWAi0iht#RjU|u%ba|z}XRb=}J@3H|#Td?n?O(m$I0btY#oxy4M`aW%WMDJsDH9k&%2i^+v9uz}B zP!}1=gkg>8)o-N4p&O|w{OAADIrLL23a9>GVeE*jYvMk)HQoqai`Dwko>am|pk?o3 zM?}O%-%Zro_dR9A7YF*NACIRX(!Qby*BE02tECJ8yF1>^^aZtdpRD0vOfmP{dB+(n zp4)6Em$!r~?U6%>r6N}9b57+de;1VXPqP-B?`M$O*vc{70`SG8^k z8}Ep_r%TY#S|YBu$4=#!U-DV}M7+`3eV+r}GP@SRSoHb3aX1(bpP{tEQ09eyf>6@) z(&eER^Vo%k8GQ}-5x6XzUYEOTyZo%ERX>X_iFLev?15jVkhu2fNRI?UlFRh-)U(n* zdyyi5y&`Q-__jiDZk!TO{L`Bwosk!xPF;mO%y=u6Cn~(|HjcEG$8l-z2==huZ`W0i zeSTqol_w-{WqWMak(SI34Xs*$;u@gd|JM98^AIh|U|Vk)^0ebomj6&Sv5t?A1K60f z0qX9}L4Yr^>4Gl#N;%R6({=yr&`QY44xQZ*@!4j}rSak!EH&i+ z#R6=8MnOX}IbCgs8A|1exV^nq-j>=ch8`vf8CNi;-o>H~*I(VO3<{)==jRv7-O7_J zGg-NGST!uZK_g83hXHWeAwv;ND7~bi`Meg4$dy&6-V8Z&6W<2M6%dbF9vX@`>uA+= zqTw|^j-&(N*sJ28T}?zSEqUGRH%GJ&~_4}3oe{_9ySd`t?w}6VYfPl1ufJ%2WDkYNA-QC?VBGM%y-Jorl!{U_yfvB2&Z-07AU9GsjX5fQ>BX%pBq-9;moBYVN+l7>E_( zmL+VM*;#vh2Q0rX#uCl}Dt#}mh<7K8+%+ekt5

Rz&2QM#6DHJCCm-w+QuF*0YdI z3oF)c5fml|;;rqYPZ>Zqc7$xkl%o`XQs@k8LdNTrQm`GIKS)xKzq|Dn-k&Z#x|aZJ zcw$QTEkP-u;H_?L%JHBHvGKQr?@?}5ZwkIEo3-k`vGsip2|{vWYflT=SAA-F7JvCJ zW(gKdraCP=tz7cvwxfXNBQgLufo=WDZd(vA}6?8T;J3hksRVY%@3 zg>6Cc&N=%%jb_y15=e=^Nnft5OU;~MIV2ZR_R9EK`gS==fb~r+9=DJ@Q=#V(xi!li zq%b&GDH#M7Ihl6C1FnKHn)qdaO)ZjwPb1}5`?!GX4crteas)vTItVR1@UVDPcMi0CAY^eE3^CtwGprt_sKy3Ll12|$@8-kf& z{FCa(0B0XxftUF^l}dc93Vo$DV? zlO{2?!VYM%Z23^AY@br84c3!r1r7o7pkoKJ9vF( zCc`M+hPFmq6VJJDUOoqFCv>dxBll*v^!Ui8BcGqlK_Vj16t3ThQNS`R8}=G!N=}h4 zH7i4m_s94+`t1!#WR`Zfk!(L49+y1)Qn@bGO?tuBGw{BRU^a5svh9BQCA;}*bfW5e z<14m;2k4tl@?tDrfX?5^CA$hs$9qC2U)pl*DWin90{}Mw?~NiYnS%m5urZ|sy#W7l zd&bA--dv_nVFT)I$IG7yv9Me@FPe2_u5(e`L@o%TTuK46kkHRHknvr? z5TI-BxEl6l*gQnqbB2L(XQ9FAg%0oo4#!?}N?f`vcR#MTajqeA9cuwrkK&UiABe1@4Zrt^M@0+)$|Y_KNioVzc{x1UkTHur34 zaQfg7oXA&6*9`7os3OuyJcQ3UWAJ2n5E|ag8z@#vL-S(kK|lUF{VeI!M2p|t?rmy} zt4&VvQkdI*t<|wjWx*z@i=Cl;awOA4!h591XbLNwi6*}Cat7=4bhEJ5$^lJ#TkySL zN`JrE9L@5im${Ogpk8ESKq?Z3C{t}_h~2AtJiRD)eW9*mm^A(j43|l(J!0V?W|{}d z`j~UgYtYy8j^rQi5cU6qE*8>7{?1eQ}CdGt{+RgeELG72e9q zsB#~~ejN7qGs~p!3TYU%Eaudg=)1MIL(-qKwm@UhtPFmVkDmCnM_}=C(&x~MKtRMe z-sFc1kq;r)*bPAjO}Tq>qh-_MTdy~qo32j%>F`gm5v#m`WtT|E`ovhpqP*hW)(40d zq+fdO{%>P8&wcq%r~>o zeIYL_+p1wtg+0mLSao_E7IuEHczh{M138WVE8hl|*3y2+z6p81Vr+_BOvY$WAihM^ z!?XGvkD_k*cyuJlBfpc*joID(?2Q~t0Aec9KwmwxHmty7kxu_3%|}i3mSBbk+EzOO}JDS*j%sZ*MQOxPw~uxdGxsTuE=XO3cdwZe-{7TfN=u z+!jYR+T`yOvHf~Y>C=^Bi%nJvGvn{%e(POUE~}M?x>=MhhTsQ6$U&?< zIb-0gCJOKG9i6vy0-WVJq*`=5IT^uE%h%rBz~@+Xm-i z=t!KECe|-vo0EFk?}X>uuVo8Q-bfmb*P(f;cn4Q+cP$*Km5{8E3!}VN!>cZ+$3BOK=G|*w7$IziXedvzdlYG)6CCJ+$Bb5b^#_wf7WTOeXxY+Bm z!$W6pA0JA}KwzZq3=ENgpl1_Ad5iHb&prA-(w#fHr1F`GyvBn!kgaX!-dU8^Twj}s zO|tu+5Jr@}O~~I`Skfx5Yjmr7PHTTF#_symr(tRN+|2k-0vp_?d0BJE=ZRiT@aGqS zImHiHrf(r?>6kEDyW?9*{x@~Em`yg-y^CCm);ecbxGMB-p)9J->S4sv#tfq`-0s-? zmNOg=EB;ym*xFt#0#e#PI}dp4C=+sQ<8E3u&Xs;%JJG87NbP5wh~L!BGp?#nM?YQ^ zj6P&}0P&2A%j7Xk2Z@3;N;*~n<%5r zu@K;(!sib%g(j6buJl&0s0k7~;9B<43?RL?)o+LDN7j}LPQk8G7wN-=b6!9=(*6x( z2P_QE*{U5FDTOJyKph8nb-XUSlV=@m7jk+mCDBpTUG2K4Ci@2sfTj}in_w%?6cIW2 zT0&^zA6A+CGb~tr_)RY2fF!9wLHX&QP62P-bzk7ycjLlB%aRLIh$4yZ?PCj9EY5Xh zQmo5o4&!SXsy6y}a2-Uef9t6dNRTH7`SFZ1 z%!q{$9>gq7`^yUR zPVQ_d|1%EY2|#)u&4*(FT#*#dcl5@E%oUf_*UyVYV(&P|rxL5&!G1}*c{W)t(_$m1 zgd*2$BG^u4xaU&E8-O^AGHiILZz#6tL~ZGKua6 z{ugG!kYcB_<+O{U{$$|FrJYDzg}aS$`(WXrQ%DU=T}Bh^E*uOL7;Unzdgl%oB!v^V zcBJ`ynj?lTK~}6LYR3ZtuaGO5aHHKT1QtEmVkI&+$o{9`8y2mWlzy2SL640tffvQe zJ?PY|`bw%#b!@5If2FzXseXgx=Ti#G4Z65>4#P=6U`F5T>%+C#&#&~l96QDy+Hr<} z5OPKv<5p5dQ-NYpg2H)`#uRnlfIALT038_TOD2V*;#QtYB*p z$RF;amrh2oiMFiu;e zUBBO1`rb_SYv-p&FWtl;99~n{zEeuEn^a`5Ut^=8Q&t8&>9oMMyGtu(Vb-B8C)AO+ z!2O=DqXD`=JXbWTOv->2JtOhQ2R=M~v3B8Ivwlybny}BN2mI@lm!yR1@+GUxR@hPB zg@=_2rmaC{Eo*AmVllt?rs+*or;^$dp=NS8cd0!h2CM|0z-r`K5WvjALsaQ0{t~>@ z=1#Q|pq7NVdB{^FhhA4Bwh$*r;DxzbT$P^1Qanj^Qx7)LG~d)7QPk7DSt%v~<95L5 zulHofXu988b51xiGqccRH)m&Ba4utMw+wqXsjnSb@?y}|aCO^o42^eR^&OT3=!B^~ znQA_koZ4VVH;pm$zujzb6G7L~CW zQ7{9^<`56-hL16Ei<3UsQM2;{YVGItGfP&FHe9IjT%pU`kemwk;YbS*1QDEFI&30v zr)AvIo}W@i83On0z8S5m)$`f$MXQFiGI^YpsRSPFxdy_3mYv0~l#Vt1OQ|^H?8ghq<~}M$Q@Fkf zL4wSP8RT_WZ8;X2)pct*bUooox!3l)MbDFE%f3>CNOf=ueOM=K?(I$UxPwg}y|Why zm8Zia938x}{gk;>6;kdq(wz-r(Y~GWVcLD_YGhw4SEB{bmN->Y9U6}1IX;C(`Y&ek z$!P6q)IyHS9)`LqCF!Z-9a%|MJzG+cU$S6j#??`idHg9!SqQ!9l!wSItOTUjnfAio zF98brp3XZp+^TAI`f>zuNP3J8@@5OUkkClvK6zf^Ao%;7b#8eSRy{wSMK^ol^d6_D zGms&o0XJi}jObE0i)yv^LGARefLcAJ!6>z40(Ulkh1?W)o87;MQ&x!5HE`b!AT*H{ zN%}V35lgxm@nyjf$+O{;kip7A)6Qxu>Kh83-c9y4A!qL}{f9a+VHTf5uvDc7MVMG@ zYZX3?8X6`&R3+hk-}ijZmUgAp_M0VdPMo|$k3QH^Ty?26P4q{DbI$Om$F^4j&wp?hL+Okw(d6qIKUCwOk()W?-_5GH^7j5L8gRhj(8vuvO-RBo=g!(~cU3 zv3@NYRuRXd@D$g2zLB#<$+2KCx;T;XI@0l#iOO+Fl^Md?GDZ-!Kvau}r3YPESZWtP zj~Y^3$T)PSTJIlhPei6|I*Hi;c6dODb0qlqb@|T{vO>MJM3P@zYl&R_tXj!v#l0W zukE>lEzj;N4%e^_t9o~R708WLHHTYL&CPO!5oUMN(L`;>XYIG@UaL3=JAVJJEtr#w zV#<>*8MBLVoQ(+>i=Mt2LGL?jvb#S=y$%tDHnNou_*#E=&ab>07KOt zA)KgbWwq=@kw-5ArTJfa3lLqRg>ZuANGjv)6A8|Oo9VI!Y@=in*hbUMtQnKI|80d3*{ozYOPDlu-c!x?F;=+2+)+_eN@@@L& z3CGnE^+fbHNdsGs1|Hj$_XdNm36+ zz}!tI3J^yuD`o-E?o)Pj5W;UZ0>kcc`!03i!Rduj@Se-_`V;lQEi&n)UySPqza<(= ztvwY_40$(P>QQc>$@zmd!XHcSss26}hCr^O_Iq7EeieyqOQ2=l8d7YFCm)J`J(ZBxllS(V)J$1$!pWZX^6UQDZjMhX)yH0F zaXJN`o|zy-YbBFt@Rgk?&-~Opt{aexqW+n+yG)!#+V`5vHU35(!vEEo9Pv%j(s zD3Q*M_qs92>9Gk2_^HX;h`l*r@9=!!^yJ1-!=~)llxA~7d>!pv2h}9@C#euD6!is< z2aLj-DDxsmC`ApU{%T@ka(|xY4Rm)B>e&rYAo~|1<)sc_5X}dA>5kS6L?v9?O53&j z6}1=hSU2TR(poPsr7`v}*8Z}UIYq7J``?!uhDZC*)jphDr$?X4R0x6tmN^wYL(w^m7-*si_%mVi9%+CbUP_G`0G@yAe^IuqcugNlke zP#-x}_I@SzwyF=qk^k1!;Xx^%aej7IW&`Kh7%z>=B*3PLjhwMH15Ea(XJ@G{l($-! z{GHa7^H=M7A8kKuT$Sw)IDEazUcwjwPNXb%Ldfyh&B_3ag%)siBDjD5{yYL9IaBWf z`~Ov&%JIldHEy*pjz?hzgO1R(H# z5pt#f(PnSQY58e95PUk6Es3|~+K_Ej_Y%1OJ&c5v{@JtE!OYvy@21<>C@j4*;NDjA zt@jd`6i!F}o7eGy0xla03JUXUY(Jg=_k~SXm_^x&-A&nT#z*%Yh>4V*00@%PI=u+@{K1R=V9}22 zk9cJlDcoT&vJ3R%Zc|*rX2580o#Rq1gH=rLXZ(GmC)@n^JXZ!xFx_D76~z&y0xRKAJ-!QzQtcG%G~+H-%rW=7SwEL()cBxvpcD*F?&_?^H zgIsw*#?h@*e|G2bxob$*Fk272>5E$0Z08K;wREXwZ_|Hp0OcorJJ430NZh3qMgPx{ zHz&*E4uO6a{Oi7kiYps$t)i?0|Eo}xuORxJ$AreCAqC#8eHZfjS#u;8MJ{&UH!lz`joaxzKE|PSwWjWk#`XMdOKfU73h1hq^g~AiVwrlJEI{4kq zqvIFZef2&ai!cOpTkdHswdFIs7SAfrAk++?yJc6uC-=FZa`sTFkm(?VrD zYdezK?7^8D&oj67(iap09p9z;Fq&MS(9+iIuI5UvpU*RM9kFMy1+;)KKa!2rr)j!}k{%bRh0y}b-H(&nQn8EK&Ov5ZgH-|!nSI-D? zW5uPK+~lbw$MDB*F)d!KC$UK88RO>}lU0W@8XbYD55y1pX)ntb@idRk-`YqEw8(YLp81vLXt}@iSOH zI4Q!ANva9^eTi0-cFZSwakLP3a~aRdOF@%9)a7Yd|8)zaFOg%zq*`*iyL~BWP{0m1 z8v-*hE5Uf+z~pXupPG)xWX&kbQ7gM$hH{Syw8P3Y%#ImF^^B#IXB1VN-4VB9XE@j0 zQcgf^P9XGJt-j)_Px2|}oZLlp)PeoYG9E6 z0j`lr_GN;Vp4fG&byHES8 z{?{E@%lZG#LpNRfL|w%td3^R4WHXj`I*FWY7C>TCiuy&Z$^4*eLrZMPOR~OhdK`PH z^B9%Qq#-BoN5qQnC!4==uPU^@Fxf7gzH%mW6FEVx@z^%HuAp_FF=JUOym&0QW2m&va63({s}#LNM3fvZrPGoMgeP9NT(J zGmEiwcSR4t%px-*W9Ob?x$sSAl(Tj-G6-n zkT;e7wr*p5h_njdbjVFp3%=EW!L@ch=0SCQ9ZT;6S5y^Ej!QqUHR6TOiOqqp(qGsw z6`uSlwjjdJB8{z$)G{ksjpN}}AaAYVrQM-?zj+U>1Y5tm+^=7o8gi5f;`D*I2=TuP zeDC%QKruwlgXi#$>AomMq45aSoG+v~J&@JX7R^AZ-ey?j=Hy|&IS{h-E(FQ87eAg2 z+bpH}4b%D-QVsuwFpfczi5d4bi|G~B08q-`w9MhK|1=fwZGSDk&&teC+S1y}VW&1o z=MCd+&KEA%cpwfCrh%+2e+@D}F62V&L`d%<#Y5gW1GnxL~?P@jgOBfx#P+SCurzJd`O>iYY z-eTI<_OHv@ezvnl76^YJu;<9`#81{jJ}yv|@43}Ws!~9x%8=X?r1V~}F=`}fVPuy- zZiV|Y4W&Xy$%isO#&1-%SGb)7l zRuB4QY-N&E6FJd#;almQ#Iz5la?hU&QzL#J?=|xOz;lzm{)`i}{}TQP^NxPsJ`~9! zWqwF(O?)gky6oj^wiL%;eJ^x9MLap;7YzWJCQ4ld%?|?&er|BjtToz@CgU3KpG=vI zY>$RMieFs0_b|}oyAPPkU`$61pW^9zeSMXZdM{!N4gM#!lEdZ6=zYA%7kkK~%hK&5 zY)iGU*cK#>$AyHi)of%}TZ!28E{#&d&dM2;%^GM&)R+G&o(a>O*IVgRGTYOK4-7y_ zo;1%j6Xf>svD&U@-OnB@IC6zlUK(LRwTEJqb}{#V_Imu@4Ym}I+VmVMHeyT?dzj|Z zsL(F>Y2(G$Zw7)q5IIvzni1TN+#lB+rUD`8He$+05D4p|Qd7dSopg0WqbOOhcTe#k z;zLs0|( z$lg}`rk7VS-*#E8_-7rzBby$FcD)r=FKdyVwye0 z!lxut>O-v^&6>%pIa?Ti5RRoWuzS;QoGVJ`P$E`EE#|+X$8I-lQ0}NWS+~r%I(acv zTt=;n)4=xf)N7S#T0+s4Cj__(NNq02K`HmV)~L9k%1jAA;YLg>T5W!%m z&!PHq99kitG=p&zKF0<~jM(S=pxoCa4RAR5@N@#Frqi6G}Z5pBslumw_hWI#aK=Z(i_zdH$M_52ZaX z*lXb>k!EOib=4@#_Aii?m5o*LO!4THChw?Rm2KghHba%i3ix!UZ13K8Kf72>JGh{& zi%)ilN%r8Jg+XYerl-BSPUu@PPJBS=u*5m{2&3i;v=Y7ne}fm_V!SY8-R7X2UKhJB z!nugO7jnJ34%A9C?P(ZTTl}MlXF8cljF&KNm0=B5Eghr`(4{PDqVi>ixmBUk3KJjD zwE*GRT(^dk89U+-<}`Qy?zMnUWY0tlt5E=wSDSB1Syi|`CWi+vw_-jFWF*_KSL-@R zVY-qAm9?5P){~{Z&hZgCi@-_*Z{#ywT~o1~9d}ZYkIw!Bc>`3WUC&JA`=GU`mibeB zwM>bIh|AM;3&=nFE?e=65V za`P3PY-fIzv!d=WBdp&eeOb_r3Q{@3*B?H)%xpbh8jF>{J?m#7hggo{uiXsznZgB) zFi>8ydkuJ-fFcSHHXXwCdSyX3_!TpLPU1Q8%-+y!K4i&J%J}NQQx17uC?)vfe$9wx z2Ypwd@*J6aIq|`n9_w;Jl0dL@D`j{dC56u{o`<7>aO9Ui(^EZLu$JC)Hfei`gICu> zJ8wB1UL(A>MdEbSM6)^l+|?QoPX+ynYUcW3IxZ7{n~*;i*RG6qcNIu5g1d^F3-W@1 zWTGbK;AuX??xdHV@rnWUPRD)2{zRKh9%I5pOIS=`XEy8O5QTa$MLuCk=7}Wzb6VpWW z5xwO$q34QBv@|qBXiZiNaM3`{$mKt~m1cs3@hL);zlSrKY*DdbsdAd7*$)3LgykLl zkA#w2g#sG0cQ!ZLXmm?eA7u150CBua{4=!b`T`tI9~qMCbTtkdDC!tIYW&Z*NeDo8 z{IF1(d{RD=4Kj_qtU+#D2X1B6pZM3Hdj%E+2V?8_1Ho$lVS_ZHY6hSuS_RN z{Ly((3h>Q0_KK_T?Oe2gbEYQBj2r~GDV$$cFog{bDL(kGB^v+fYfc5Ua<}a){i#Y{ zP|0}tOGmzQXKYR|)^gh5YV#jtIx?J_Z>KI(9`P7II=U?}E{=Gc8@sl$l1qpRkB*LR zWNb{ri+?BpFl{a_EhX|f82(QSX@o~sC`Mkw-rz96)#Usbo8&o-#l?(`9q1Vt4vyh= zoLaGqjq9Y8{j+tHV7J=NuZRag3{Z)6EIMypw!zpIUICge3T`?qd3{Tum1=zU!&?vc%l4ff@p?7m;6qi zReG6|4e_C2zqjI>tkjZAft)?%MY^d*8AV}&Iqg2Ga<-){LBK|GeEDAxBKobGwl>8! zUHDU7J&nrvKW{TIxs`!4=W&1h2^|)9K}tH%0Xar)bCA-^x-a1v8XBH^-#TO5CJ7c! zur!cMLXA^av`_&alrJj2#x&9@q&!Dzl~wlwAD-lyHrfA`b}*S{ zK$4=a$ntB2=icOi%PZ;3-+#)=%5rgYAD#W{FB8t<*DJN=bE-BXPG_N4nI15ug+|mI zXth*$OK`K3QUB{Uioae}GId&=9zeGJdSt*98CboCqX3j0JqWGyI9N3=1w0tU#EjJi zSH3G{H31fPpjJAHhMIStkm`y-W#c4$4FhUq>FW`{a+aN^<%K*b%+D?T7h6b;^<-9|=6_L7-- zd(hVi64|-5$L6{OyrTONh`I^-3MwJcE;l7YY^-O7nrVi_@ z{8CljliHzI_CEodi2Tzv?f}ENauosEE^<3!0A`lw1k^AzG{lEU0hYlHCrn7x!Xp3O z-&jk0n#UQxqi@$3ho|_+@0v+Fmvg{k4}7HH=HjwHo-{LpyOxR!h+J52Y;I;>{XL~5 zF#LU?LQ}PHD`SYZIr-c>HHqEpH{^PZ3~G0Sk#EbWF!!3TpH+8aeBDS-Xz8U~%J&Im z*c})}`u^w7pX%GDtlZ<{6-Nx9%)>fFYqdW$sdPNY$!fBLrx0c2!jUJs)8yTHFnCZv zUz{?nOP$@#_K+S21iE3l$4ZMn@@y|$9D%nzCBIk$L!yHwQnmz@e5Vd z)1egfz0jH#bp0ymK*Kpal#m$Lm4ZRIYYp#;)Vm?m)6ucN^G=I4cUZQII3^INYFh|) zhcj8NHBPO0?p@=aRHX+1)HGW@9%bVIj{8w_8|&h<&5{~s2O7yHJP%7-5@b}{_m8K= zTS+=@9N;V^;y6tDF*)LUhzYpbj22yX5P3VUR82e1NqZ}7qc?m$(e;g{T$uq$H<CLAG@Hph3|CVF-q2#t5U_jw!` z-_6Cy_1)U3)6n2>IRmtjf_l^Ht)smG>e2e6Q)86;fd_%9uKNN*K5!K@0Z}*NASecoxz$->cGN@bED^$ivt=#KU>H0`WF~N=8A8EH^ zTg_7GCpY_yq}4rd$Ko4k4xJ>rna|9vQPOq&3c5T8hYKD#s-|!~obxMgJUqm@baNw2 zbRu?|Fp4SOg+aUD+?I%Ev5f5v3we^T24ryO}n+lw4)g%0I79B&9Mf-YIf^}xw) zB1{m@D}h3wo&8+a21=S2xencjL-kmaMEN%VM%}_ENleOi~2hnAlyJk-}Gx zsO8kfO!qu>&-CyImS8KPE4duAIP=+!F$l!^h8f@rNyE`!h4GFV3v9#eYVqoL?m7^0 zkPg{)Rq{ER89`2mFg{1|7I~0+yQ4W?@a@<9?g+8jIXLf~y8mfV;pqbQXj?+X6k!Po zGIwt(ZnDgeKQEKnn;Tt4%=i%FA}$LfalJq7aXWL(^lvEdT)&MPi{U#78btcyiXUhO zM#3TzP3P3O{6o|Gq+u>%%^2!cT~T%}7Macyk;t%RG#p8Ac@G-&YO2zIziSLDS4Xl3 zte5?RN@&T9!%C5&jL@`9e~(5kATO6(z8*>Y9Kd!;El|MeVkaP=PrxH zDc$)og4(bls_V6pez^&1;4}7jSrg?cE~I--^r5<`Ewev{?`BxdY3~Q>&c&5LXtEZp zXmHx{jL$A+wQ_B-+41F?`|lG^Ma!N_W_6d4lf814Yo6a zEsRk$Mk+fx=5n&|guG&4Hk6um<_O1h1w7Cfiz-f+xzqJsj|iu)w$Qog<(9uJF}&G& z;RsCaLXktq`N_eCoo_2+N^kEb5Ev|pTuhs5>b)L#?dr3#HHRgc+cm6yNDL=yVp8`d zQe%-`D%KO}Smhu$U$x)!+_~uSZ;Y`gAklVsm~VF-S!MU#$jFJW|A1VxrR$dM9hTyb z{;0+&E9>Y_cpKjC2j`ONhIWRAWad{s+1xewhuI#+%znv3BWesBh{ds4B7gJ|U=%3) zfZU0#0}w3ve)7KYmTQ-djScsCKlEP(p&nas62}{A^zbZfFYx>HW-_;pTGHk*`WpX7AoY&U+! zIH>7|fwC0W9?025Gx*oe)k8%mQx5(cO3VVL4a_+cw^~NOlsPj-j5pLS8G1U6u8=-hSe+gV^Z9P_9&c`IpJyG= zS6E+N4My$CB%(Sva8V0yxT4W)ELXcG6d1BCK>e7w_?dDV5xeqWQk z=#1~i9HSw;nKR+*L<}9T!`d76fo#Y(f?)8>dU*1mR&tY3`)TFXNO1TGCZp73U8+T$ zo^dsjWtLG$X0gP^c$vkh$U;f&QZMcNU~W>|iwhD}np-`YGf47C!RWobTTnndA#w28S!bF%=CDGZJwNH3=}}v))^nq!(@I+jVHk7L z?=M@PP~jToapo8w&B^hmUZEC&sIhwNcF#CeoW9dvN-*w{OK9bDqu`ViNiJlFU>L+u zJ+d9UGGe}&vSnMZRqpj6HX`$B`=FRRJh-32=D~3`32$1 zgU_zhHg5$^!xknu)mN8-2w-!4!6eT>)%H0WwVrKE%*mmj^+F2U*01Nx8-cGj^+G~I z7JzRe*2JKlb`^Vn2vmJcNGDlZOU$}JNaLmBCMH2>$6La;fEoWHcTg($HiBGHgee^Kc(Ru;k_{OWJ)*5hl_{b9+EKsetB)$iQjHd=~923 zY6Jct4=T>OSExtiw2BAr_$@=iZFiM+6y@UiP6*?bd*l^UOVa_3#Y)kRG)B*V7zf*^r7vCz};66lkFD-ns^%dLW)<6C!K(&~3wdjpr};~vQI zmYlOXL@>zyo}$v87O{j4^EJCso<{w5!j?1W{ITWV$Wu}AXItc$m_d8wIPjW1Xo;mq z6W^VV`d6t){Kf2z0tDODEq{~#E#kY^Ny2G6T^lT?TxmlavO=otYErpQfz1C`-l&S}f*u!#6Ln>Y#J@t|B4sLWtuM zQJb66%Yit!w3?Ar=03A15o|4)LATi1Ah+hVug&sX{%$<2N=b)o?5V!e*%{nEKtmh8 z-?B0;bgS5qI=n+93K$wC`p&qFFsrv-W)d$ed%~AWp<5Z8ICssnGolQ=Q+1>9 zOG}@d|F}4DP0M$?r*-pi>NHUCPBF~y!&Lqh1-@J|5FHA@B9ZXUvblM+^n)lS1Z&pl zD~AgUXIPpE{Q4)8cGVXss0r{lOX**aPw!cWfS*pY*sLa|99%}7E{dOg^EsltTpr>) zU5pT+I-Ma=|2QIco)T8OVHMB8S+=rBu_+u$cqRyU%H1sBG(u6VfXw)cj74pq&wbn2A; z=Zol+BpD-7+Iu)hIBgKrlLsPU!QFpMg@7nWn-V^e^eEtPDTm(}4EK=-7gv0qZ1);# zigE`O&@x@@Ia4TxF8*bB}Z$LBBq7|<-UQ zT%h}-AMNTw>{`C+f6T7{2V?l62cDSS3W~@Y~ z?}t>(Jw5JDJKlcP>QFLrVBS!ak`(nXP&R>GcjosAs^&JwZ0&di8|M?xM&De17Fyy z7aT+TRd1=ZdvX3|-y2hVea2T04aM>Y895nIIe@=>q%7eAZo=fSu&`*{?`3pv(skXL z?t$C2K&R`R@=HqSIXMZVAZV@4J{P}il7+pFzow=}*uYc3*Jn+-;iQB?443{Lbd`lI zT-qI-F3lb%*ePkJJJR-|{L>u}w|YLqMFF3ClGdmglFc+cBGa5)4iJXQ23RW*NmL=a zG?$KpbMv=H&gYjD9bG5q$v`M7AiH}A0f#A`nZz+^d>(9fYrMGf)%92*TJ*dDL>VBx zZ&^o@<^|+T=H7G3II2Ff`vHI}>il&!s~Ic>Ug@8g&wvlW0bZ4f@lzx_>byJZZt?J! z#zgo)q{^9rjt-?+stYlm(C)nkHzYkBT|gqI8373i1UT|+@63B^rXjwlh^e5U0O;=4 zmUVAm-zxx~QTlWTlyW@niXfMilER1rUGtfkm#FdvjpZp5B>#jB81GZ7JUT z!U1?Jux#v=*Lv@{qI~^}bjQZPH)aiTO4l$dh`1>oaho@NvujNHG?f?=mJ#@yEV zHytL8t4RQ*!XWEb4=m*2r^ny#5LwSgy&v!3rw{M1W}u$Nm9!lVU7@*Nn}6(nP2>3G z;JcDs$T8Wi5b-w|-(Qz{1Rv(l(?FY`s%-*9xj!0t&75QUt9EVCEiQk?*peh#}xJr`1Exx$6Yh`b>19EDv9BI&3^0)y5lTtdo+k5&UuHq75D~ zeqAmHb})s}Kle%0ElB|jc@ z>q;tSYe4_k7vQZ{5I~knGJWWt+{vJ~kLchp)rk?+@7jZFnM=p3y(mI)oyqma!z4{p zi0e5%*NBQLGcv>nT7lU!HUUt2?SHGMd3!bZ+pQK0&`C4{FaebCSy8p4;~ujLT|sd7 z`|NxF;~F>>TUlm_P3- zli|5FFg2dcg}l-m>?gwG=yo-DAK@_3DtZKNZxVoG&cFIEj*Cy4^BXE$<#(6y5~d7PqbjGpvT;g)y*z?HFT<8ohI0=lWmPS_?NQ)TvQzsKuG>cFAB=b z%d?uk82rr3GjD}`G(Uz(Lxe4s;4zpZ-)EU};wjFw9Gcw0yPN3W5H%PdMHxR{6}$t0 zVf?>1e z3k8%RO*qdAh`hVb{Xe6&1|x0;>P{Xf3$MnLF`MM+dBdSFdd{wH7oKHmp{5GW{6)<9H|KFuhpn_VEKdtr({=B?!*>Ik47||7Um}ivpo*UdV@_6wGK#Px?7-JZuqs$B@ML zYsG}eTU~aJC5E`U>mgZE5$*}Enfad^6MLv=(wBei`4n;6Mzd z_7<&k@*n?L@ji$y{*Gt*)iQR!1qAA~y3j(CEes#OImKx{IYb{hS@GPs`4pr^(O$%Q z9n(nqmqIa`)aYV-OUJ_o} zb~<<-59}3D9`2!io@iA&fBNL5dlI$ChLMym5e&3TQzAdz<3i}R-#^S+;c(EPY?{_p zuvxm264H5jbgZ{~G80g{(-?gMSt&nUM{l3p2;cbHKsv!yuKrDevjPi>O1~(e&E~$7g`6`-n(n1lX0^D49HMgT0Y{ zGlk%EhLSIAjWEG?TpAXx=RNbe-v}GvqbJGg=DDCFG6o`TRzJtGCCv=wTk`5M%PxiRSH6HzszC$)%7wzMWH!zyOVfi+vv)t#^EIAew^q9CFuv7>CLV2V-XAcHy0Q++G)K9yviLn*!by`s7i|CN_?HSgpl~n z8801SyaV*cCkjS+LUnTj1}}+vVRI6v2lKMTPWHt)t&20Ti*(6%mVnDF^eFX}_NHL! zPVE9iESCZ`GwxIvtlEMu^RTe?LMkS>X(yIWiuq`P4ymhOCS@OggU=e_?}KmMV6?z3mEnYreg zId;AYHmCuRbyFZORJqvjbmb0IyEe%1xDa5{OO#vjQC9CmUT8Y@YGL=lS-xMw)0{YD zDQ-J_#ZP2ye*Fd9?g@WE%J*%z&5J!V4Vq=Fm^IQWziA~5NjccxNTzQeNjDIV+(Hxv zGjpjGwLZlpPbPq(mHjObDtw`uZ5Y)6KvP-LKKN>@`Wdk~mq+ueG<2-$Qj#s5v3fm4 zQGkfwMOSs|EwI&*3?ijPIm2>Pm3o=F6ingH=O5Ij`FJ?4KDAwbqu1myL!i;Kr?NV( zJ5GA=7I!*(a9_KK)^&hxrX@IW#4EIf$tuitAnWv3K3m&5>ao)WH=ZbNBo7*I>0bG? zxz1Y1k!8wB4ztR6Ll|Av3LFN*!43)h0W#GP)`NuYsF$Ugwdd9M*;0qPcP3@}e4zx5 z1DAsuQy(9WSh>EzPt~W{EjcopWqQJTK+<|-s1B6u|MZTICx4G@?C_2_YbKnzm}AGz zs83jMCu2-95N^(FPAZ6PjbSeDH=2ry=Q%(&*gC%Tx}4Xkov`zZXnv@VV)i*(AI#(p zj2~$Xax$%{v#NNn`7jF17@XwPWtkuNNsHWYxh5lUx5Ga{`|jU?8W?fDYiHkF+Lh5& zUE5`1Pivy>YIIJ|gVv+X0w;gW6YANBPR!aG9M<_cE*A%e^0}4p&&j^R*p3f_otW9+ z`08V#I$6`IIU7p<7MQKt71#ZIS;Uy~OUiauMG2vS7Hf0={ZMp){A+gh_(6vcjko(q zXw!8ytR0*Ith52h1w*TP4{K(b&0(9<4^iOhgSCqCkdR-txE3UN=0tJ>ghYF?d;No- z2oEX?7%KMh(}t(u`HbwxMdFz^@XPubT3*NbwO*6&X3($S_KY7r&$Je#k|0}2VT)re zRh$kZQan%4KE5Eysmk*|4j)fW9_!;TEKxzK|8{&i*%&o4NXhOb&^Rripk{NoG8FrN zdxEi@o$)*)?vD&Sow&N*j!in451VH`xDYW#M_+E(S-Z2Y4ZwZiv;kM-0Sfs1bUU<&~hf-1r(585!8F{>*m*bRlhGt5~YYkDbKtMMMEU32ccJH=E}%M zo#yQQ1gaxO`>o;pbR$N;Ym&dLH_Hs;2dZhmW0A5g%lB^Yo0)jNhN)topr*3EyHO!Y zPOwy|do{zx(H>lcrN6ZQRGvI~~t zwS=J0RBckwSrxzaK2s+3xKm{^;CZR>t1rz@9|rw?n^&mBx@%dpbDw+pM@=<1I;Wbl zE6aCQf}@$*o0;PSjoIJYK9)bJ2s6lD>OS}90(lamt(7c(73~3 z7QV*6l4UktQpOM*O6(@C^*_OD`tI~w)G;j^&k+yoy%#^|e*fPqlq1FwFkYnfXu~f1L6@f~&ow-R)X*iYxQ%Lind&gq69i?aIn<{biP;yWZvh zMWe=-e`5X13PYV_DSnTGrqqUp7H!$Fx3UoMaj1Bf-MKE$kZYyrf=t0&h+?W%j%AOr z%Nx2bYXDa--m;?AxFDS-xf}w)%au{zDQd@ zh0sW_y_qBRJjvnWRMCF=;Mn~lHS#+bRTBOE*Z%1C8%$&s)TpQ)@6Dvl{Cy1wo70>? znP)}R5g48+3XNLdo~XUOFsgYtT~d9DHSK7K#=SYO?Zi_1f9Z^V@A4-mX_h@ zUMTY#1FO{B;YWJux#%U5mX-_xG8t%Z=+!AWU0x-v>~o~orS2A%vCBwDKpURij5NA@ zGRvDsV8Z}38$@<382*2$45H0R6f!_7V%GT?{+YlRflMIIU#9g!GPi)-0K~>KAZCpP z@|pIu6P>nU)1AG(9MB8+3bbsFR)~T)gdA%~G*sF?h8D;Lyy}!K5n*Z&0+4nN! zyqt|gKKE(7n(eq~QOW8+<4T$V%kwE-dY=uL{1zr7y+bKr<1t8(w6MvFq9Gsyhm!%DY>UZ< ztOyqy{8AAH#f-QQ>1pcnQ#fvnzkR^f797&)S-oCdr~?_wWfK&9ojOT8J8t4_NCQJ#oR+OY#SiA1K}poo_rPqNKYu*@2^G9?3z&s7oXsv$AGIHU zAL$1`9pcumOm^x4sO&73cej5P*o9j56o{>=vnWiST1+bh!5zKbE7)$yZfvpaFvuAI2Ko6)* zP7UBe|1KCv#t8sDQafpR`}`$r2^o97*rr9{FbI&GEFSFQqYQIr^c22@(WXtPuG880`j!2mxUR0yZH+byv++shncL$2pEFHxdtDWX4GH@jZ@Fl72uZ7!`p@3;^MA{o2U) zK+Y@a=FP2BT>JAo^lD_amZ|TG;~6km2spHy_<69MES#@mY^|JG2cWyJ@(_gD7gwyYfIm~4>p#}jA*0z4 z0gT^bB#(#-U;59Uo>f9>Jd&r~Xk$SMY-(yUXMXB?$WsJlY}d7ftboRei2Bc7grE!E z`9u*Q$pRta@P!lxsJE?}R+m}ZZpE>{>?&bj@&=c`w|S`o=4E6{S3j&A1x<*2L6QQg zh{1nWT_3$)@j=p(5a)}y+{vzc8jHv__s8wy;};V!&5elYar;Ad)P3sCB{=E9dKH{ts+%&||cXHD$v^1{X=8-6oZGpD!QK+{q>$U7q zss;j#<**XY7ZFjk4UJ|ji!;loa4sQ5EO6Dr1FgARLnQS|r%7)>WUNFJ{j9e6{kTB8pJweb zRL*YhrtV=O$7a+1wH#EwmynLb9M#+A$L2F<_DDDR*kN`|33l;)x&=}Oq~9imgi9Kz zPbc%~JXdvNO+L*sP{P>FwC@YTM5=WOdgA z(ftz%it@;`?BXoGe$q-G7Gq52icUCoROz3uqt~BY7=)I^I0>&x(=TU#+)J*su}van zfI2tZUmyaeAesdA(WyfY$%~;VjRU(7rnxdzi@hRxXK&jIXL8`&&S zL%2)(?cFx!B#2tzg=dQHeMxK~J+Jp{VbLMvQ$z887nzLYqufL_VWIP#_Y00`tIhg+ z#!)9C{%AH~?I=s~qy)}R+O+s@_w{mmIQ2kD-DL$kl@ zYgpa?$acvo zNBuU2sr63(;@)iHA=^R2?}FmWExTFCjpg2k;L9`4yQ|KF2S#$n{t*42+1gOAN`gIE3IgNbyWttC8wD8Su>yf6i8+pm7Y|HGF>?mG`Bo z7=k%_vZqrxPX<#)rz9a6etYXJH*S2i*7I9GqPOsHO2_W8Sj1{EmZw059#lX}OPlxO z2kP;TxFp#?RbffVMn?dgv8gE_c7B5CyZ%Zqs|p{(0D2$s))(kXcdMb+p$cLX_G*RC zkV_N4XYA@c*zJ!Dbf0?$Bvv^0MBoT&OF1~OK9i7;uxUf{R`?tENP&sXTVEPSM_@i9 zF3p7blk>T;T4{1}G^}|wfa?PFr-1&$2JfBkpgn>kkVbJ&bRUT%r$gz{5y~TXo6sKs z%>dvN0wHwHCWj*EnO2Gqr3dnp&WgjV31xzJ7%OxlI0RIdmX?||<`}NR^?>6U-rU-% zvemo1fJ5l|(9L2_n&q|=(Tjl=8kmrPO-E0k+xkSr$N8FV*=65(*N@_bJxY5lR*~VR zf7Q3{pbP)>e(8vt$`RoGW_`1F}Q#{u%y^^_U!Bo_+@AXa0n=U+sO*XixQvYs%&&u zG$RC~Sr)GW;}aeMp$mOHD$~Q3OT|S|LC%+_FnRDrYSBlkuBQECoEHN_B0A9;E7XrL zt|~$&HYU=#{bmk=gm1CxW)^U9KNb5BvXI2hgys)esKR_mXb33a{nV(E%lI#Ol99zw z7SD>Vli{v;`vBX#Y?~V;PL3~7d8^G1PoTgD=nL59{wL%n@DS~e9mQ=6z>R||1$4Bx z#4w!|bw%NOB>b1)<4sj+YD`=BS$Ozo4BGWEIXUF|R}%#lKxwZ_vTgRcw=Q&M3%fNEGkBGT1b(*D8toL6o$()Rx6*?rMv>CcPj z)Agg}{8pt4dWD3ZP*r3=`TWllhmkk>?Ohg*amPnhd{m&a!cULvzv$tyuya=TQf@x9 z09Xx!B}p;X3niGU0Pp$y*T(Y#139A{h@8)HF=;|(* z3Y~~(Ou6CVyIr^&(0`#owZEwIeHJveuP~T0L(KwZXi)d3W9u(OQZu&4zm84%8*ZYI z11j~LujBXB^#~lar|?ktN|aV4Agu7hnu#vxzeY3J%|sx?xCD}!#Y)f;28MDxe)?jukA(ei8J>R}yFT-#6K>alAfYM)0d>am z2tw^K4v@jV@;}czvorfv5}@S50#Xgl9X*JIRgF^?huL}ck@NTHb0#;Gm=3$0#Mocd z$f5Jm?3eS+!R6U6=Qn?uaR2^O{pT>A9VLymvSDzl97+vBS6@*i6tgUu^|iuy2|gd+ zt7j!q7@TSktefmx=6%-Pfl|a&cQ6^EY2 zZIn*oMl6f5T$s6hpaWZ5^aD5qm9ZYqhA!YNzfW{v=cuu@Zpbn-7Wf-NXrRCV`AF5w z=yh#auhNv>?sA4IsP20KNQqM#2B>yrRnFX8jIbU!!Fxk{%o=>_nm3nnXf&($Oqi}N z4jMQ9Os$MRpj|LDM~xk{51XO+24B&W<=5P;jtxUDh^CJF(x{R2uThuphRd(OI#gd= z8Dz_^xR!6`9Ao5FEh#WFB*s_85;P{qt>Hr8+`N&B`Vb~>`U`g{-*F095P!o!kDesv zb56cCMP^~qBmFwAA`@nD#lKh1Xyhj$X7$4ABcJY1YRdSp*pc@{f3JI@P;;~Kz9CEw z;inlbe#PnB-r;aO2h7E0(?yx~0EvBj`h9Q;l}({08)=H?j`a1nIan`Z*6WJ*uxf;;Fz2tnW}40VG_Kfq9a7H=^mjXfi?Hky zT8EZxA22ho+cod6;+^ozmoFsvOt{rP=x=tXb7jcIhA*m0xyZ9~h37>PDYAX!R<+N< z{0h!rV}JvXWJYB(C-94g0jsjGNX+*cd{uT-8x%FI8Tw0)^=Lo^;Q*MwL>C>`apq98{hNRj&^Vu)^Sr2U41b^0!v zIZX(MTjW+i$mc{uv;8#bcD;Z6YA-6eP{1JWP5Epr8Dd%T)Ku&KbCt!?*zb((Da&noatZ|lNRg=Q{Bp-V#osdlW67a~ZReR%k6XS0Zro-#@%yIX<{iT8WE6X= zI|pCLm^l{;dPC+9+zQ0a<t6-@SK?cEz(uiZ>P_c{Uzi#pQ1-|FmT@`czw|0%%98CoY-4RCBLa@eu|YmjVCx zJJ9_k9tHu*6e-ukE@NUzL;S=H&sOGSZ*+NEcde6R$Ku_R;p|x`?@whpdGiYeX^MaZ zIUY^DP;#d@mO)JwuqoyTy>~8~@6a@QUS)ojv}~dG?zPa-#7#!4?&iw3_&n0}Igy)j zCR&w@u3)Op+}84^*{}GF6~bP#zjIh%MIN)_$t@uOendui9oEEg88k<;9s3q4V5%$Z zMPSE=QN+W5Zke{tlOjSjamna1(aBK}P7Z0*MOR9oTF(|y2+QeNvNr9$Ga^U1`>z&Y zk`T$#b^`=P-HD_J0&q1~Z&xNKc|;~c^V8s4?^}6}sm}w3b*dSn^CJQC4t-Iq7xoqX zp*Eot-?b+b4uX%0j-<}9;$r0Rj%ba-Wvz4W?Wu5ZOz?*t@|wEE3q!)YVG@^P<>#{| z?X*@{#OT`O)0prSx+%GYzR%3y6VnMl(cW<|##?sVuM#|;vTek@wAIh!z=d6FGZooG z0u!BM25)vm2Q0_OxXbk_=*Zbp0LKH&*=O~;zeRgzxpE?1^j_`p1>cH9<3{GlE1qm^ z8$kAV6)0gk>JwgOJ}{Q=H6$)r81c?krmh8|&gi2*b2WJx>=K_Gx3x1mg(nI-@pC(^ zY6e`+Wdpg6S9o2cs&elJ-;$4$pj_bxY`e!mLD+eEIk9|+tF7xA5gfe(-d8bWNp{7}5b+D7Y#(kWb5Jmd-Zjz<>2FK3dJpFaYmryt5>u>{m+ZZw7 zleerWKTO3^<&7p``U#C>6k=$mOg?c=jhTOMFlxF!>+MKS7Pq#64@KjZmOozkDW#_d z@A9)q;&0td{F~8*dIC3?<+O4FEN=?+G^3z2R2eRE8uu zJ08>eA!B*P`Uy?dN{Cm(m07+0X83Z}GxSEh#omMcTb>U_P5e#oy3(vJhkPn;Ps>KC zHs)f@)9hjKO7CC#T@H$}4ep=g5tO2Q!u%j}s-di>FBS}+%(SM$CcR%~Jb|G&ho9OX zVcGwl4xl?5)}@K!KTG*Ro_ImyS3$*FtS9x)tPu8E1Yat^MW6(t<`aBVZ-cq}J%*=k znvDRmn6Ez@s%Dtd!L2hZyZP$jvTUV z;O+ar&d*k5pCOM_GCT}p>0X{$TBaDu$c0&ys-jx7TgiRAYUS5ly7$#J&hVsi6F9PH z)A$ewl_9S?laIajkcw@)5X)Q*qoNf|q_k#ek6vZ5AWJ87*d`{Kb}(S44yYM?uEHo> zx7uM{pG#qgB1MBTGxoQ{(4@BV{;^#Yh}GOP0r6EaZrkeI8E~5=SI$%vQO-<1w=?P; zjE8*q^_;Ew%~cn|^?^UC$IioR*C{z+>Wp%ESMr zP@q{pzVfV5^rPoMNx5MiM8V60rJM(}FDnu$T~j9@KH#`SO3&S(Z9bin+%Uj6I&<5t zp0J*rZRRi7w_*VQU74Pp8>uUw7S0ck!fflT*Zj@PF?cUj$f|6nLT9O!e0I-naDc0c z3b8EIEFByi%F9{r3J5A)w>x?}MIJ+FyifSALRcM=XF5GbFY2mw!NPs%AiD zh!pL95t5hw67|F6j)u5oJaCMG|LAat4<=w<>_=<)KT#2Rpp@VAUvil;1xb&fgXvjI z8ynzU^=y~hTFFlh>d&rR@bW%u-$nHP!7k(=>4*9NOh^=F zQBjd*Vz42;rr3&}FFD2cr-o%9^_;N*8if;00J8P)<}R>-FYb5Ws{KbTT+&#YIoZEH z-5K!dQ?*OykU@*_9k;cg;U$`tIo(25(`6(TToFXXXf0w{-|R#_`WDq^1}=`i#`(h~ zhq?#HI9Vi8L08LWoVu!1x)b9f<@J)BO-_7niMs;&QQ4obOH1f&aqy*hm|eQj(gvI# zO*mK#~o-M;wM3uyUKv3gG=x zKq|4Qo)(ho#D_mABnI$t9YE}jI(jf!_zE*ZQu7-jU8BqL#wh=Ma7zGJN47zzFD?cF z8timNw#qkUg^W8F)2Qh`gCxu#YcfgOP^RUq{*DlaGdIT;?MKpKk}3+@KG#{VS)U`)2`V5Wk6 zyt~$rHNB5dVN#t4i?S#Bxd9vvL`4JpKQ9`sqvK?`sVV<#;}6I8Qq%BKtr9pOINIOl z+FEZv!z1_h_vZlWHIYC7L@5#;o_RxkH67su(ooM3SATP74+rhGA!^L8+`QOYzIfPM z^zznmxdR_f%cSU!-OMc}L*Ij$7BoZx5-S6UUccydauS?b9z-z?gJ@jWsn+g4WwhFk*QJW3uZfs+Pq^QT6f=Buu&j@?+lGwzjFJE2 zq#z*7xjgdqqSK^08vM>qvn2K^?)7+qV(i7Mf2=87ORdl(!?a&uh{4q^ucQz;;ykFJ z5=|lSj+HU`z*B%#*p}lHW*%%*4xLM0PSK~}QI>j}FD^)W5|oJuRtGvNDwvm2S>Z^^ zI9b%RBTO?dba_zIELPH98a!A(ybpblwd0zxR{Dbc;YMey{fbzi22bF|Vy3x0#d-F~ zelyh`Vr8Fzb2|Te`sIf`7Ai!Ad9t>8c;ALhebv8s1biN03bb$YLA-~pF8nI2eQJNQ z^PrxG)^H5VXI&|EYn|jOh=*Ac4CxkOy%Bz^I)rY(EB)h8DZ3a$!o?vMRtqD%>m$@B z5F$--@LEkv<7@xh0K389;{6aCa3}3e7YCTd?YNUD_2a#-66Qk0G)(3K-u(rfc_~Ud zI*z|k;WCWVMR)};L+qbt?NeO=?b`7&w^?OtKJ~BMa0U#B7%KPg$->0LMwK_dhL$xU zNP2jRN-RPtVB?Z^P+XnUOmBK@-0zw|EvG@Z?2AWBsfde!7;w5|`g{G6nM1B>58E#~ z>z!7wnY$wHUOR=|xHxy9KssJ?&=Aca*jK)z6;O!^Iq;Ol8%?M!tgl%#FUS};Tlr|5_oLo?Wc4np~yud+7k{$ zCe#>m?@b){0X%9soE>BHO(G^9X?Q>6`TY_Gwq}Ho>2)d|Ie6^C{ygrv4!69E$mx;9 zxQtYamzJT(!5^qjON)ymdALEfwl&yU)J1L?!J7x2=rN%YpX}{|&FZ?9*+Xor`45zM z>=?aoSR1mD@>35N*bgI7+z&-+|D^8$J@eapdwGqG9+%M)#uGqEy?0|BO{fAc`m0lF6SKppp_S0ihiv;(L z_j50JHn;avE}I%TS%Kq1AUOdoR{{?h&H~d4C(5=D+#0am(P2}-9lIk z0!08~c4duRIuUslC-lH#zLh$IPER~zDC#mFS(`TB>0Oj=!#-QX37P#bw^cDB20mC{ zKMdkToYcyJpM~Y+VAJYKG9;1+zTF$t-0iE1i>2V z2!2Y|I)@g(rgQK_nA>Bc7K)xR=)@Qe?YN_ODf!9CuBWxN$>8OD7LGFKM$u2@`{q5K zmsJ?{d21{Ac@c}dizU%$nUb1#7s`bbS4w90y7DYP={wtx2DP=fKk5=e{qKbwCX_oe zF8a`|tfXp$0b8SE#2daPPV+$8+xa}mU?0>qNliI4Ci0U%WgN{N~2a&Vmq@{&X(i`fXmi|3&3;KFM84=^BU zI%Q3YubRL~e2VLOr4teolz@X+W!=!Y7y=U2gQUflw~)UnRw6!uJ>lIT8Vf6964=3bbgS?XnUQA+{cj zRyY6sn#b>w`*Ii|L!fJ7vgv=wL8y*HClZ+ZwnCrL<1;E~BgIsv$AnWFtv4P%g9aXn7nC6jTntQ;uB7^ui%|`MM7MzaGLqTzc zuxgY&g=_MZTv2Zy#6Cdsr1!+V^q*Eh3AFcEzJLE7wqB1(qZhjRTqC>8W!Na(>jMzr z0qZaXwssfl`r6#KnR3h)zXlJl8ormA$yD+K7CWZ>PTZIC_Gfp~^Vie$h_$e2ZH&N= zy?1w#8KRM^z1syym}TDNThNtY$h_vG`I}4_zYVP2b7|D207;@|AiDtQB)gFM%#Ua} z?7t9o1=5d!o>LDi3j}1mgom;emj%z~VGT3BlgJbuZPxx2C2rn!76p?m*2sgTj924cd7XWv8=zQ^sk4?IM7jH~F-^uaQm1pzzQHp}=R|Y@594fk2cT#v*RDn52`Rpn!tT*WB z@Yn{K_Yc^mq1&&Wv)SBz$23u6$jEgYXxBmCM5cfE#ozpydv7y$uDM|?=#F;YjO%9a zg!X}pWQt3u?*0yQ>zi)~zrn$*6ZZl2K0owznWr~R-yI~VSLqgFU}*RzI2c|ovk_e? z*38J^&LdU;=yybN_bj$JZ84tb}1tClI0I2+x%43aXh=0`}~0Wb&`jU{^rFp z-}gY%5kps*m&h@#LHwCFVfxR%3P>gp0xQc_rl2#6Lk+|r$VSFS%@{OWMAyXsOt5LO2q?7|;=%8i!7tpwWj z_74T|j6FRZgP9{uMIR7VofTYHok~feCl0m-WRUYShjcJjgXRFPN9&s;7?@I^pCo7` zdPk?`#fV#bq}y+DpqV}oQ?0p2`@v}Op&|9%!2FKw=4X2S^~?E(A$h66uBB5#^t;RV zZQefA4-Hr1rgQSHt;e$J-eHD3nr*RNtReRX9x_-JUpJ~*Vi^oR-EKq>l8ovZG8ZZ5Yp%6b~Ne23{+19XSm z%ov4v%Np867hVf;;|-wOz_qE2{ z=--pvY`KkBoKJi2-pa0&`)%Z4sUJD6M<;Jd2{>+U-#RIyx}~!cr5b|2+jW0HKff!7 z7{u!L-rx0Xh6qM_r-tj}J_R>L78QxDKs2{rgBh*B?$-*~P zRpxJLJ1-B#>hKY+@?~J2w^6gxQwCtBI2ciPZTAD>4A7WHoAsAEPC z_l0i=KkO0kZftJG+iZMjIDIaZe&V%cSqSrjo)3_9PhwY7qR82Sj4l~*f<}EZ;8GS>pZ%xxC9Q>fu*B0&2@C8PJ>|W zseN?Q(nckpr)VrhwV1l<%#|O&SwGHCRq#c&+|DkB4U2$8PY;gEf*WNH<~mS>URN$y z#DympRTr@tHG6gU<9t}}hA{`%*K@FNNX;oga()%Xp8A<0+`-!YS+4p_Paib!>9@&= zG`hBJs>`d$t=5t2`Z|YB{Zw~DJs7aA0Jm|fpm)O#>E<^o$l-VddCZA#e65}S&n_{x zi{}MMN>~}d7GnF}dsuj_KU}sCi(TH9l-!@>C6N#rYy{`f;`_(x{OY$Lr!zBpC+d8g~R-vvV)=3ywJEl$vXw21imKTRFW1KiWj7Y})G^$tf`>Ae~dNx^}X z7~_kOCcnOTw^KNOfdHQ;>1WQT9UxNvU`3}^7^CJsN?6HgpHN;Z-MOP=Xywkrzi>{@ z=1_8_s0N6OF%eCtnY3pj8+p%1aU{{;#|_Owi87l5ahFxMc%gA_Yd2pWy!LQniu5H6 z^W*!mJR3}*z$YNIr?XwzOGG`akzDCr`bBHh0e(tB)ylq{z>=VUUP_jb*3+r;>na~1MCz~gB?@PM{ zN?Id4Pm}haJ=Ql?e}vt=8EXX&i%B+!{7e1g%ZjsFK7KjTe{vmP6--R1fQeCWR<|`F zd?YdJMU$r`g}@Ev*=0_{na*m3oxh4p%MY@;S%E8gSqPVjP8wjZyH#=!VNf0zTukv&k0Q7(_eX`s*Jz(RPauAv2kesyx1#U5s7;By-pEPsoB|fwHO6GLTjr*l>YH#`1YqR$REwiGbBY7Qlko)vf{-X^A z3g+<#Vkz5VXuB=FU?f@DJs%?Con-#>)3|JD%P@(7CF#90B69U?CI`F6REUKa2x!(- zqEiflz8gIE=k;Q$;YKGb#Kj3-iphbuD}jeq3zI2qqM(o8)>~X}kP7JRo_QlSXWut< ztc|Hs(tTD*%seKH1IP(v-T(+zDjfFG?ni2~e|M65L+(B*)5AtK&y8Q1*UrO0$~7GC zs{i(kqYZJJFGdz)23k~zSs~Bv8Gvp^KV)?!6Q0bU3(Jr z5tq^GsixTIuYs{9Q=kG5kNNF{y~zjJ#Mxg~Bc)WkL8))u_O1vj%;bO>KiR?`CkLKx z>!th=6k32aTgCl#g-(@T1pe&_$N0+IE)9K*>Poo;R`??5&=)f7un-A$0SheZ`!}*Mo=T`% z53Q8hn4Sm6ro~}hqgm#6#Ps2B;LPDz^(FaL&P=2BTU#z+9~$Ay`8M6F6%6d4TP%1u zdL`EE=HOD))V|uLb3!fbBsm(hTfS}SFXkgp6lz>J_Q4^xXtB~XFQocs>&wIXBb(mx z=N;9~yfK``Mto)AA8XHoE9=iuP2r2)1XybGB`-PfOA4TBloD>&g-Nq110B3S`RZJe-BD{2I%FbKZh72wqIa_+H`ZwSL7+R8UIE7SXaxs+m{lue zCG2~;;iT(Z;kzdr!B)k4xmV14!mMEr#*)37H8bq+_>`V$hPXJw6^NxF2p+4^-3z+Q zw#n>~5xyj82RcH^GcIEkAe;TRl{V=3DGVq$P&CPCWFe3GW;ca6CSYNX*M;G4b zDYED*Y--}mKS@WUQo#YaSlDB)rdPiLr!=70EWn2rN-2!84$eBU+UU!9JuJuA+=KLU z!KjPz1>`Po-(=IF6l%hYg4FA0tmR^7|A>qKO8PxFN2s~S7%UNBg9h3djWv7W`F!`_L0pu?j2<#w z52wjkNj8cJZ_tMrJF?y^?Cm&wNrj61Hd`ayZ$X)!o|dw*qGvZ9OkRnL9xBnQUK4yA zju@w04J(l}AOTEdYzbx0{>3i9NK2dD)I^A{18;Q^F@N+;Lut!mtHt#}h>%!fVc8%! z#bJ7LW|uq4aygvt(!+ki-RLLK9#29#*TwzbhKm_`{_cMG;2g2254#Y}?3WaO?_MU{ zq-CiV;VExeEyI)zaJ@=SwhCn&cFq+pR@^&JS0=A5v8ch-!5-E@uCJOoywlDK)EHj4 zjSA<3nRG8@AgPb3=1(y|0H~&>7BD)z>8PxuLsZ{C{!tyr@+qzZnaw)xx#?jX7%C*6 zam_c>osp>IW3i$x97?F@dfn6X-Z&UQE&HpADwG43lwEXIZ=js_%` zx`J>7DU7z`2zOM*{Lg_C0;$n(V50&gd8`nehOUlL90YWI#%}nE)p_wIM)LSaWf8Wr zre@d(q?-lByE0||9i_yqHJ7&#S#WT0plz;`3T0gmFZ1J~DSb<>-oWcP{R23%3Em31443qe2lOt2_*E^5>9^;`lv}` z6h#4WT6#npBdtOY z*c&r*EU=7s^}l&(F?D{Y{T+vE#H!W(A@V6=yKhut1Q>$ffpbdk(lE`7x{KEg|y!&~}x=BmmCk%WabN)9lmM2H@Sd}^$ z1i8FUTR**CkYkEN@*Yogn6zW^-YV@SFqxs`aKx=?iZ_;OUp~Pj1x~H7?HFl+TTu3w zUJ_6TPqCbv*RgLD%F4|(84(Q)l+b6+ACk1V4WT9{$A~&5Ltp?-%wwqj^bq`bj5~RC ztt>6=8+9FsfBylD^*QKYIQKu9+tu7n!%If5HR~C15UAz*p?xihBHvw7Ki^k9JM*bN z-Y#V$l^R~;p3+hS-~+w>r#}QV^})t36&X9#3NIiUj`|O}h3d(c!G%-aMSX-huFf^$ zI4NlPi!1;kNO)tXb0VdX-}oRdu9E)W{(6kJ0KR}gbgwd+beSxztY}=^k+RhaQDbsM z=nbS>U!9fK>l4@eaL!rZmuKw&DpMKJ|5Plc69C4iu&fMi!L?C$Vq)T_gZMgq1JWdt zY@pZ#Kw$&xg1vt=$#3@NJAen7oeH9XY6Y;^r+#XH!UEH;&K>apYL+o21 z@Gdx4{RYIL=+ERh$3v9TEoF2Dt+Od2n^c&xYv=7y1BXUaWtV|y*t&?ax4UG2hg3f>$<(A?wpdzyTN1yeT{IvN= zz@P~#E(Wy7FBcT1`p2c&4w_&`#x?`&ImTKFI|p!bfP35gaS%dEIzPir9@?vQ7Ki11 zEre4opXQHSf9gz-;khPxx-0+yr4L*JwVH;1l-^hZbqyAcM+9zh!u{$ojpKk{8YN*r zO1OmNp4Yhx<{}cT6Rdub7{lV6Uiw8{eC_Sdv)c0V*s?Mvx$&RC{Y+=dc)-Dpqcl#T z&bJtwoRlyyFlY&VDpNS9YH7&;pugfOFOSNUL?1&DktzLV2Um*qZ(ZQSmW8RwIK@Jy zflOfTi@(1Y)q2@L<+NQGWK@iUi!0>$8k-O~d^y>?_2~?hl>{s;rafSt$!rRS4eln7 ze>VZMGg0)x!qTz}V5?$}&;=iDC{FX(vlSShldq6Yc<^*%m2?^qY}VG+zQoG-Wkn3c zK@KHaB*}OH_a!bi(^3ejovxhXWmftzSG@+|$6h&Nm{p;Dgum{{fb`1PwhsdBDRzV@i@;-F^W;)<^VI zytDh;_kguXT5s>tmuCUoJ>Zjye*kCsx%hk?FRo#kO;_yWjdXvXuN}a-6zduXC^w#1 zb4SM#t?2b4!GJ$NWpauS0&mL<92oq9`I+v2PM(sARv;Z8I2C;jyT=_+ zm*J~`4(zPK@xlIlDIhIDOuXu+KLm;=H~D6FrT%K)ft_^7LwX!=_VW$< zs*siz+JN1wtKc{F{CwH~=!aPfpI@W$lne5)FayEPBal4qbim4K%XyPXq(QL?&bey2 zC$PGs2}?g0%exR(KfA~G0u(F%>AICt`Ztrl2GwgnP@%-O=$m9a=VJ}F~ zH4cZygWsF}#izc$9%#223bj8c341hxbyR-m^ z-6Z)c>-^~5qEXF$z5g{>|D&wxYK9E>=3!04O3yjgH3;jM@pQ49eb@ zu78JJt=RC@j%hxUbh`TXDnt0_C(&X8sSh8-Z=TCEaE{<{18Whna59TLs?NP62 z7_(Mag^zDb1}=N1@z(AS3;?ZM>@lc0!DzTG`6M<~tgbP-z|V<$%fxSMC;prU?zP>U z0)sY|L&h7|R&acKb5gs&9qIX%?A02)!6%?uFJyK&@}g|5_IUg)FplrmWk`}Zlo^sD ztC)4VPSdbm;Ah%>uCRZ3u0WdNhcKOyITFu}LaZ?@i|#mbK)U*4tBCl%vHWmy9L*49 zben1Xui?k3YG`Q@H0T5A3^*=IIB7RfdBlNme~8CirP2roEd#fjR2xioPGyMb;PSyVD8!?rm!&UcxFgIy?%E2SABVKbZlz} zmz&>Yz8xOwgJ&9JI`yo{H&tj-pi^e<<=%EdrL(@!);Z19J+JUaDKF%>mCQG~XVGtE zq5Lkx&5P~3dPQU?nRhsP>xz|UH29!3b@IVIm_+ChI@6Jh4kh;kbtXbGOuhOXblvaJ z8;#rD8t$({-IvGx_M|i%kAN#rDo<6)cr4JC@O*y-3%e&>K_0@?rZYsA513ZZn_Rs~ z4vv>0NSeoejrWHfxlw?JcyR#Ay)W^ZF&n+X-$-CGHuQiY&_ll5h?7z= zcK0}FYxZzn9=N<{jJym&MPs-@up@E9L2q?Lm?qWic{knOp)+L0wz>Fl{0maHax&7| zF>h0_vT%vX40WTNRv7rPcS~0Jig|yllp|rJU?Zu#qUcO_YYS#@Wx}eh`)VNH=)`6{ zv;H=`we6avfVc&Z>pjoeL@TcsRL8ruBoNn*)hYcvEcd|oB=h#T9egA_k~WMHjIbvh zPp>bKs6*xzip9KyTv7cnt#O>rOd9n6s`~1%sJia$0fdoOco4~v5D=B_Mp~sox}>DL z87Tn?36V~vQ*wq*De3N^L3-$h-x+2^t+yr3tCPmSc!bT{>98ubXEm`>!tn?5ZaPfv$NXk2{K<-w@~$?X zDPFdh+_$@v!E`6PCh?tFb)5pTSe#+FSJ_pKky8g3okGZU9O}E|9s2PpA&i3QZ!cZ7 z1slZNKW=71XUw$CsJeQEGJP@vx79^rBVpSaBeS@mV7lU_4-*R7wE@&{Fl#{UF;=7% zf$X`s#{m9>2~2v7c<|CHiPgdRH`=bKi>W)cg}Z)l!9Rc+DPB~%W!+{cv& z&TkPfXorqeSndPWw(d)jWSlhKQbum`rP|#tQJ%;F6@z`&}RPJ$+G1ZimvO| zSf4kO85du-dUQ$-KE%0^1>S&4vw_(bX9;TR?b+5XSx^po*}QH8aQ1LkIHv5!^)5EbSEy^|R%; zF+iNU>)%|kr{MdF_kU?v$lT#_afvp{VZWVZb!bj(T4pt; zY>p@FU1{^VPHQ^rU+9p)Ve_p?7kY3Ss#EQ@t3JBDxkFVht$;vIW{$!L+i`iF; zv$0oME5W+<&H$Nn@9+ne+rf~9=yEbRwK+aVuLE-9N_&~Y1D^LHJg5skS(_cZj1ixR zij0re`GIJRpBx(gBsd@=eU@pR-luH-Y;FAVrk69=;AeDTpU`QpsA|*E+lbj7tU7Bx z}lPS@egN3;pNstek+*eLKLc` z)Do*5GVUctEa^=rc;p%^W=%g2&ns#YHt9IfXZrF4;=jAwt|e&Up3U0L`(v6r^n54X zKXHp=vrEV6e_tA9^&a|IJrK)qLD!zIb6BBeDXe$%3_R4u zFR;?JszrmnZ!U!lE=&ua9+a(8{|puM`GL6AYFTtzcU+lBGrmo>Gd~yaH=>ijM7+{+ z@D$d7@Wfy=UGVaF(S>iVP*h*y7GG`u!0gpVYQ0|+39f5&L+7+HOm<;QXE_&~n7^dm zeV6v=zjZC=0oc-&aKibYr@$Sa@@3J2&nIkt3}w9!hEDvC(k99zl33O6;m5BW@cfS< z=vOfI4&a5M?|dkJH4vH(W*IMUY!i`~H%e~-zz2JFTyw(*{SV{!^Z)}k4nT|rSYm81 zYTXuj%DcNiMs;6!{`&RnF&%4sv!wxHYN|;2K{-~hn1E0WqF>LQ!>L;#tmMVWw$sQW zEIKBhY|)*eq0Vh6J~7y-`6Xno&Q-#dB~iJ(?*XgcP8|}cT;Yl*B0W-(tk*!cVwM|t zr=l@UZ~MS3di}L3egVp5#j_kQ(%Pp6DzF1ZY1B0|REG^XYAnYJ9Om50HPZE+`nW;W z0J39giQaQ~kYnGBmLBe&esb~v;knhG5YDPk+ZRs`z#z3oZ7PLhcJ@8<&m)%5dRj?f zqpFkSP?Cb7+PT{*Qys&^KJD>a7Y-{so7_zK!?BRAm4DQ6=if~NBO-G)#qz);!-!j5 z`E>FQYlGh-D{_U}Lg4@`oF?vhVt82*otP{*jE3%7et;VUiKj~zlKGHnw(?mtH1j|9 z(p^8~KeDw*XC?qeet+{NYBm2}S}XD}n};tH9c@#4y*}ze(*rB$yFmf_I%EcSk9D?i zAGkT9aS?F-Ek_p$)C@lCFjx&HCC26hN&*bU4!Hl%Ba|c(2P9<|JOLz#Qice^G6AMR z+cZhtb1rIKe|6lib(b^6?-;;TwboN039Ms8{9;s0ORiHG@QT*a9r3T51mA^C=9IqS zYd>H7YH5!o?|smyhaOx;OIw!nmukW1mj!Rqwf%wmQQSiK>*=f{l(Dh*jxInxm=^X{ z2p6N%D)ix@4@IDn%R-gn@9&`)FbbqYF#|#0@hZG_3I`F`aR}STV zzZTy%bQ@y*(Q+Pkp^-V=uMe5Kk(5NSq5fUt(OJ=(z$G6M@j$nP@Yk<*A*V`2ZvdQ< zkl&!-@o-AsBF$5=_6XAMZClgYISNf4y0`A+T3q5*0OVd;B5I94?^+4KF#&;P(MP5v zOH*5e_o+sJnB8iegs6GueR(Ddn`Vlg8!?*ivfuvpVCCq>3KgFh2vF%Gz4H-{J}xHq zzUJz$r71SK`9hhttqHMN4ED&X=Z?4xWV>*Nz{SxLZ+e;w#tj$!ET6rY?50mz=fChJ z?GRk~BoL+E^^}9cah-Q!KV_W&!XARsaqH%TPa(K!IO*jze?vNXT--c(*mx-}T= zoK%E#<4dA4ym@ZO+}JaTHH((ZzQJ6vRDiBP$=SPo>0!&aM01`bo0Cbdix$ZYUpK` zVC?ibnJ$8$lkuI`$pZMk7OJ`I&+EXR@H;S0T=O47;o;d-P@dXy9Izhb$(?YXyHr|+ z0%b(}3!ix2$;bMV5;3k&F?Ufh*Haz5$Fc5IA4Rj&)+SfTB@S+5k6!-0aOCa=87;Wh zEeqqJ{tS6xYMNc3_?QL7-kVtOPo}80!OWEivvC)g_0EZ2lMM7b{3cyDP*U^)whAGi zTev8u7#eR2W2jEqu^y$7QbofEy)pv=q9`RGv*uF6X1=7XUN_w`OXecn;%BgZ^4gu=tC z=YbNoGE@5Q9AtYZwcYoS3@@v3iSHvB^u5-;zL?X*stE`zZ_}8LXb5yvJDilB;^5zW z(7SwZSDGpV-Es!7+W@ddqUjQK$h;d;i-g>RIM8tjsTGpCo3iu0FOw2;f-(q~vs>*Txhd;1>Xh%m!6u)D@1mR;9Sxe|A z`tOhI@G@g1iRA5*@fK~lT6SemNM9`r`)q2q&T%L@J<8KtqV{qp8(^Lt3WmjX3(MFd z8~@sxU0MH7`f~H|bU4s|W-1ySt);%={u~{YMZ3?Fwz%t#Rd?^wo>$p_4ogP)k-N@% z3Q$q1z%*?wZw8H*FBFJ#fX^_R7R2mIp?Ggh1y9(x8kdA+O8y?h7ym*Wb!bv8ZD7u# zzl5??vU=eg`Ktv<71?h=bwhXR*xoOe0OVONwH*U$`8@L4S;!gY-cup9s&N^P;eu(| zWwHXy1H0I!TC*fQ0meKG{zj8_MAis}N*GfVth zzDJE<1_HhJ0TlIhB8SvszAPRPasZ+OLDum=9i1Yi8a=@%2dW4oJ%1iB1f_QXt)kIC zpuMF))##&ZQ_PvUjXUtEdW`QvDS|s<6)Rn;3=9>5%kuwgDJ4n*#|Op)NvS*ms{2c<^)EP+T$@@BgA`80NN9r# zVq;@zBK=(SP~kXP%6uGkdRM%*kAD)COv3%2$}o5pwwUA&s!7t9Nsa9CooudtBf9uvUM0#1M85w3srj>5%|!L@Is!s*kHmegU~>G>{tpLL|or0atp(JF_+ z=IqXPOe{`uzxp`>HwOA>))3geHI7Vd?cvEewLPajvC=(Q3AmcF`X4@byv}=aZ*w;2 zgeW-iC^A`n50-2#-nwbiw0mrP*y|XXl6>XHpc?9AAAWL=NEJuPxN~AgK62s*+cqD^ za9MDQ7=zv?*3z4{2ENU%DLxs`2%xUt^?W_Wo7tZp;GAGcVr1GCHgDt6lak954zuZw z6DZ0S{+Ly}KxiAY*fwoKoWH3CtoW`K;(P&;Alp+N9i3#Zy*?oBf}<4EG19zm)Dwq( z`}WACW3IW$kAkj<(=XTeP`bu0+Qj^15Vm71(9nX5&w*>s!QCk`ow~GhxWMimJ>hwY zJn~ScWF+cu>w!Nv8TyI!D6FVFFh%8>DkM=p$s+bGf;>QB%!OgY=LnK3zt- zHUYa+jwB1nFJS-dZ<3>N5phIgbfAdehydjBY%3+={`p-sVzsj9Sa6@3!yDE@x@HmOBo+0aa+0p2h4mS*BZUuzre(#ab z*8dCSYOOie{a$B2yGUVcH?}tu&mJ?u$^&8j(H$$7veJ}kO7Ic~y zeF-%Qg$U}0o3@k1jBcR~&7%7n$ z1SAUr5m3lUimSy8ht*XDQp*rnG^B3tZnVh`d@W^*ccw^y&N=UHW)*fyq+2j@!lV2t z!Ee?TE53)F&sU%Ob!tr{^f4+nedy`e z?fU03ZEzGv30lXqe1+C9_~CF&V}dA{;$7n7)Xw^Aq&-@?}K}+YiptJ6o5BQfm79 zG>$M_(c~R_+^{Tsy4ev0r(jx#+i$P?+F`_lo?b>CZ}YvkqmB9U9gYj1*=ce^bsqT7+T@0X)mP4U5yl3JgotompM~iO zan&B%`b990m&N?l58IS~9>~*7485{a1vmWMBnlHn3Gw>1xMPw?le0K)SxLf%KhfUo%gCtJA$-q(14cy4(t{B+7^S6C5*Bf0`F>szZd zM4Q14#ODoLMBcw|w{E!|FXC4KpB2b?qd`Uci?vTeKW3Ez#IQHT+9U@edg|)!+!MOQ z2O=U`fI3AY*D~SDPd7cMe*QNun9Yj58)DeV3gBC!&3ZKj%AP{gU*F&p;A>1v*fx63irHJxh8f}R171CZHNb1#-a<&_ z^2W4YS#wzX(gm0FyVeSMWaVyU{eu=zH2Y+*5*Lm=C2j@qgG5ekJtbK%r|^{)*tNcnEo-H=zo23g*ARcC+1hkoP~02QjqBGetog=98OQXuMRmK=%r zS0OFw>Q*&lj|T&qhL1#>nXilrLYf@8tHs*xUI<`JlEDlhNamZ9=9Uu5DWufrNIyC^ z<`E~l^e;j8UFW#2bJO6-5#v0rr!SJ)f+p^GDUGSwUs+7is_WifYw z2C=D*%;xl|Hh1?3t1f=^9rO26`bsbHw7HwbJ3`P<1$qzAAu1!zFJ^sRa_WScm%mGO zW#cxnKxmkL=etcB8mzTpOcRIk zG(g?UVjhe~&6!mMJWtN|lBZF{%*B3%W?6KmbM_VsGq2%z^!gJ2#K4no1V1LyfBlI| zZ`S6w8IMX&PM5-_PAQF?eWdW^eq@+N*=21L@+>#kc>dxZspvsh+DWtTeRq+|cXLB` zvpZvgLl{f#x>%SP)>V0xPk&@nKIGZS*T?;RzDEOQmp5=F0@drRI0hmMK-`JW7|Aq) zkkMvHC_y$=7utbusR})@@n$&{a~6~GPH(HI;-vW%NrIt|?AZUzEmN5f@>6m%6)uf2TM zZAN^`Oa;0*v^ReJVtCGqQ8yp~?|j5L^0j0dTl%Zkv!jU=SDuO;I#O6%U%iqOr|3qt z?|d3ZaHSX$kge(K@DY}jILCgLrtwpp1efUwIP>*(wr3L+wUl`p`-|&gYh;LDL8g9} zyK6h~2H6ht7+r|Qp!w?!V}+~n#n-&AVbj)w>n&TD>*DE)x}7AmmkYEdf-VLJUa*6; z2ZEOnzNcCE@Yi^4gNkA(les$&D1&aV=ci{KIN*fyE)BIO%3AzKC2h9~fp1rj--}x- zOyO>vaH$3gL&EojAD#()m6Lyh-35{-hic5_w0F78{=tjQ5a{Z6TC$yL87By+e9ah9DLg`iF^NyOBM4jCC!6Fv zWMb*h1HB@%-TN zE6rctUITN(Cz)r<^M_+?0EA1~#Xnz{yhp{0LBZzI#7uCui$8mwzO3nTWu$vm2yvXi zCv`d_*&9majEre?rQ_Wd4I?v(UHQG_IHLUPCQ)uEa1fhleS6;w)ZvN=J{BQDjPu?P zP|K{U;w~7D-q@*N~9)?5`41<16I4-5F;R=t!fXp8d;%4<+yywDq z&ZvhzCn+hJmc{3E&MlGK>H!oAWv7k~58Y_Dnl7Ee;(sC!(I0tOia7FM#}{k~qkA3` z5+4`W0i>a7l^TlwI35r>#A5`+Swzwqa^z*rAiD&-uoPX6o$+qt;h7p-MKhKui)ckA z14TyLlogXZxnCI?QmKw|)}v!==LXj2H9V=OHU#*M+s!KWe-JC$_p*0NRzVF6AON7> zo4{`DFT=xAVb&M=#|W2xUft?2R-leC4hDOKoU~ZhYelC1$sN}{NyORl3@A*eZCLA| z{r)KO>IIaIytj&xMP>_*DHBuE z#l!Q`nH~2Aggc=Oeg4#rD{%j5X=w%60?Xxp)L9V&KwRc?k~I$nP^PZ6wG~LDMgdIp zG@6jt@n62=p^iJEmsyXhP#kfZg5Uht*jOnbypM^AnU%dUN}4DO{3qZ+(qN3%*9)O| zuz=o`uhBzx%2Zj)gLCit!+t>^>#N-hsI~zN0R4^C6o9DkMbg&*;viThPlW)&p`>Yp zXgi&xdMLo`1N`xh2r9vMR#usXg-;P}_vI{sJ_Dm+x0$XKhd*IuT@N4>Ss2qW$Oe{w zP$sdQJiz${T2R*4r~cz1fBd2Dt|N((68qdm8<{alyP9vKA5Vf|2)GXP_(kLTIK@^!bku55S%wY5rU^|Lku%V-EF_0Xk{D%C1dV+ zt#Z{ZeE@+g0=TI!ZuWBl=W_*WQ~x)v{2>SAvhA;P3a~;^ec{;n!6ErKpz?WTv=$Zr z6EAx4TRZ9ZmPdu90IwBIJ)M9tspf5)&gmw5tY&vtFUl>Y$8M+n|6YO3m}ICFL^@lm zahMkRQMNqc*FE*WxTW+(z^8U6G#X|GIFc4~g-BpFKX*$8<^AhWqvo1HOds*3n%V&M zhASU0H=r=@KOfNCpTWL`R1#%dlvBBoSKpOcp>wVvLDb*iy_LS$3(cCH3`k z{dBL&!B;zORVok!%CHl{zyRq^Xl!|Gp;^A%c(dc3+`aNRE$w}$+2OR@^+iqYlgEos zKyG_=5~Bw4qSfzQGf4(DA)A z*X~Vy5cQB_P52j;-u1(ed~<{Y=XA=;AQvw3cF%^09aoBgmJAmfpub_|&oZC&Jp3fB z2S*2qMUJ+Oe7SKQmVi#@Fohy82SN5BUsRqw2qUDie3^fIUFzT~KuKUML=E2}0s&7( zw#W@Z;`%_UVw!YHj!lXePIKnPGfBN?4~iQz_sQ~5zX8GR`7o+jM`Ao~C_Qf0+q~@T zZfy}V(2Gje2?9{bR}q(_b&st>CCuNyZjP+fF0Qp*Y!bm$q@(3Yo*<~@zn_7Q{I#i? zTQRkL1}j6 zhPn=>)>gy{rj~}!FTuc=8JPi_b(M^Ot+Zf9rme&rVn)WTWM5{c&EP-)<92S$?W6hx z7#J~_nBYeRm$ZXLX9x7jr|#41>I*^$SlBN=3w(S&=D^D-d`KaFr$Xg~3iS#V&zAtc zUHJ<|=xr>u+#A&VF;vqr_t&tyJPqe}em*EMDEy2*Bl~GQ{^`kFz*#Q!VP5y+q_wp* z1i?Sx)qcI>{-=6q)ZZa`-Ug=#REw`~C4W;(xb|##3`~aS=--CixF^b!v=3 z1^)pW429&HJ}<9C#n>J9(06xt1w}-(N1bxS6T2rT z^0`v0+uI^RNCcsk51B$?!I6;nO}3nQ1)!83-WAk8H zsQ@Fa%Xi@OoJ}npX4vNa1F7))8|5&p7qn1??(CT0BlQSf8|LPeT|QigXf`yJ+?iHwLYBHE+@dv;?8O{D0=!}7JyP?&h+o)o7W5Z#zW!uViQJWEFHaXeA$S5Y+ zaC>a|*4TdQSki(kA*H9hoiTXv265fklBC)M@vnt=hwEZv2YysCqxSYZg&OvL5PGoN z%v;|UA>iZNgMwMV-3H!Y&Keu!e9zF<{)Iy;Em!C~rGm>fn+xC4iv>F8q`i#|g_Def z9u?*vlmuK(+3TK~I}d}Y5^AN%vAZ1FA2`-#LFZT=OX=#jUX~R#;W&@G3UJ`FJ`Ool0o5_lt931J$LUfq$QmlBaskXAEW)-uH7S%KeGHqLHk-3QsT3U!Z z7q0}7Gx$4?0x$9nOU*|S9#4)tJDgwXb{@aAJL2|QPWRQWvQewH7V>mw1REz-WfQkxxbQGKK z!GHhjM|Li*Saw|q(*|e#^An%K!hO39QyUwbe}&FYzRwNxrI$0j+7 zk4PSY_uSvI z?`=R>5+Maytik@c_DaZgUy8Ig;tbpkMHYYIMk}yHi5_$8l{H`a!#Q?UTK3c-mx+?7 zj=qq=XIT;xOKDgB57Tb&5ie7DFyO1Yv65|OntEDF8H;>XqfIy`l`l!^!%=n)78e`A z@WEw2fKJ{`PHOCz%Mz=ra5jdxv2z~Dcwe&n%HQ^QaR8^m2)n*QmQid1ne<}kx9V>S!%HJmjyWcrh4`2~PWV?2%;o8)C2BxcjFS5= zFLT=HUa?^xhWREe44s{$dv@ND{|VzwcN8TPSL#?4FPxQ?0TH{8F6+8Y+QWny^RBYf zFWzG-fPkD>nEo*2sj1KdwT}@JEo=u7M}O#aDx(t1R>RBge=|FdJ^SRox3C-w!?_?l zE6%J2u+qvQrueJ?nZ}@&@NptR`(`z0nFB+{FH{&JnQGSncSY&a>8L#1c>NJ6ZfL1} z&WEBA*P_j=E_FNOlYY0cG+?BJWs&HBzrc*w1X}xrmr}>;z$SAY&DW+%dJaokg7@YV zFZ6p#A#=S!Q1Tl13353$1=>&dw{ZXH_h-E!wVJve*94N-RNpv3w@I7r_-^_5{s*p$ zn5gM#@uyVE<&Cf?;Mcj;r_)DY9s`Xz2r=8-ui*@Yb&+IuqOX8nZgKS^O#|u-+)`1P ziZ&eHKHnCm`lA%_oJ;NR+#pgXRu491(qYXe{1W-@V^9x^?m3;9&84)NIZ9vD-NGyS zw8)xanvyR|<>VoT{VNvCt84pVVKr>kap)4@;AAzX0v*V_Khc|iA^Qm&N(++ZnnlV! zC|{Y^vc&Hqn_W*@#MWi|lac2m229GuR`DmSC<1b>lp)lD8D|Q3$|uGjf$=0%)^^T^DdVCuEEnYVe1w5Wq+D(KtHTdnl-&sy7z_7ev;?pB|yhxwichQh?)oe;eqjRAr+tYb` z(z9D0qh!a~?AmikEN_ukSB1Tjz<@tF{UuZS(9 zMrr`ibdG9AUtv^}-<;u~Pdcp#w8&OVS6q#r?Tl}2#WLVMRjP3}?aRX0Y8O7{b#(>Y zmb4(1v}7FLx<1goyng{Utnsz3F!;;Ekw(|^Bt~5bFovd!H%00-&EEsSS9-}0;hxV=BVNL zH9R~dF*o;wzf9%YU>v~KSOlts3C(+z5TWnCcQ>)v*+FL^7VQYU%BU<(^1p4 z)(?ezyTcyisr*>Z9U`6KN)j6tiK3J;Lo!UFxn`(Ne@30t#=eS2ISdIFug za0D(3Hj~~fEiEl9x~Q-){rPH3TD8hxr6RS}wKcn;u&#}dq7_CfUKpeT5$KtZbFEVw zKe(^-#DDC&GrTP3DXq2jLuO{?&Ews1NJvOsrloj1bwFw=o?(Ano$zGHi)cNAs93)< z+;Vt0!ji|iq*OZRcZzpHjDe zNUi$2t6$f+yn-b7Un=}>O}?>}38pA07%HTvr}yt3_0sEPA(-WSHQg@fvvP%Y-ud~K zUqC>-9sxC)BrH5U+i)NOJMgnEHrV#l@V=83Xm7GWyxih1YCT`5jBr2yg}ay_-*)*9 zMjLi~a?Q+N)6jtYSBd>S3%hq8=ydyV`e^4K;d9?)iPxk5>gnYk{lpEGN4^sUxxdR& z#@2GE^|>I{Tr83FW$~^_eBQk9n6&S9ng8zUdA8b_U{(Hu%k@4mPt!sDIW$bgcMUFe zE|^vV?wq!=vYp>&ODsPt_w|0-a!^3XpT%0XUcQ6$yOY)tD3@gpc)`EMXVCdJu!TzS zg=1d;WG&;95>#iutyNKt*s;=ZS%Jf-k3z7&*dxNjM|+S!X7Lo5$f-a{_AdBr)6D+( z%dSOeAG8R%xv_-drfturddPBrRBS>y-~L`CskSPm%B8D!iXxSOi40W#l*z!kwlxU_ zZWN0)0{!Y{6p>0-Ho_h)5hLOvy0Grxu@YX_lyxebNl`uB{&?;=#!8IO!en^G;>p;5nH{w&ipjWtVJ|W8z%Ex6!ZI#68xUod?>V5tQHKYQJTDz!3|8DXBtmRA-|Y90EcUxQ!LK z>-$Q|7HU?)w_rvAZXc9QQ2~+06qY1IxzNsR`4Co)CW~2EJZk={2^a&#bp`CvDFC-g z(T&!7SNu=RjB-=wUF$?K9wXR~Y>%#LF4X50s2~iD@!9=C3~xq z%|1TaJlH4oBQkD^n4%yC{3|n*nj`%T9LHc`o;f+$)%;)5_;S~PLH~*g=wMW-vSz8$ zY6vLSc7P$Kej8fjO(>w}_J;J>GroS)s_raMl6T?pEb5-~$|+LXD_DKMdULjKKZL?3 zCBhtSZA~mkJ@x0suv(l`$*1Eo>r<0?x4853T)hZte9a2K*d;|14F&|Z#Ip&@u{a7x z0UNq^HSh6f2zIlxIZxhs(_HgT#X|E^3~tt+>~2YV%#vRCqV*EBz=BUo$B^ zd1TeyG?US&3Po{J=P(+VscaEP6pLr&4pcHv{@4)*1^q+pkhU|)>Usu3vVEL*v4>f< z9pf4rbd|N_@ib+H!My3%ntX3l}EW0TB65kWOyfg=IgFy8cGVu`*^lH4(KkECYitDG30m;-N&dA{fTJ#0U($t1oe} z${AsF6;6`IE3KN9N$72veaEMtMgnWK$Fzo9FyS%FdwCPvaiO0&ffSAAj@uDW>LUq# z1R zhXG(Z>RoQJ>n4}?+NY1kr$5qBu>T%sii1uG!JH$d?q4@tg6k*Js@a2@>AfxWhtToi7TwSj*0i*?g+7 zZilynk^Zjcg>)~lpm9+F;?|IKag%cCn$IK9!1GaStE#Oz;z^PaN-v!9-=_0)IhSQf zh&tkbkl|}jY3Un{1l)X8$5zVabikR4>9yKCEdfCcK)N&5o4(@V_sE}ePmvR!ip2#6cPzpn&(8)#UI@xb5V~+`r{r@nzY!a> zYn$)by*C*@2uHAS8uor&5iMjVM?s%)q~aJYAN}Mn5QKz^i>o$f7#xhQYG6R7tE*dE zUyo_#*{~Sdv8pp&tmz*Vq`kg(hJ~*&p(^#uRv=?YX}`wZvk`yx?8XRFyOhF>On z=>3+4#=!yTO7+&eE;^2ztKf^L>H!b~4z$oj{nYNNhC-S#3A`{qiMsnqN&9QDbzdMR zxChg@YE1BOVQGo9pxD@I#H}8kz51&UGFcnqlNk_=wi0e)K)$kq*?Hlws%cgHjYW0Z ztl5Q`MH1-NO_pHgY|;7WGB_GA$nT^Mny^sX)Qkqsh1mjU`Q)M9VOoNn6a; ztO&a3KB@?xA)uW_73k|(hR&x{D&3HgTY9VY_O5(}j|Tm!&Yc`zwlJM3KEB8P_I#OL z8a_^_y_vi)>eKi(%|CMv{!8nn!^?0vA9)z!r8Jr_+W|&Pd{A4`rqv?e8r+iHPFMT( zL0OBB?lFNDySVUJKgXhd&t!Q^B1aOQZFyf^M^2#aOuza`qL#%i1cM8ICM}c_seh&^ zRC~W>MQmjMBz_j3e>!A-*Tkvai6B9leY$#NEi9+Y`{VOWYx!t2Vz-Oe$@aUw1FE!$ zQlL|s&(4Nf5C8Zlw zOutQ8;+{UH={s)aA&-v;mqLg5dWg_Qz2294PpJKrDx;(UL#=H)%VgB1_#D0={n_LF znRwX{cW4CN5BqSnC?oZ-*5!3}($ohTLu@Sv?fGKf!p$~B@e2r2!r|)=`ZePN_5|a` z4BMsJ>KS;a=tcZ#rN_XYJn5_*b~msH%}2f46QLU?>)t*PAgP7JPn{5VmfdlmDzxF0WahT`f zz7Zrkg0t@tT^cFRM@s??ILQg9pS8wH|I8`o+vSO7S3phmz~e2@v}| z(Vd^;&q05huRPj-s|R}*OEn7TnsDRQZ0*uZf}SRr=9TU8ku%}#P?g@5jX7)3S^-c6 zOFo6G;nG-UL^zJ#=Hwt^(m3*lU@-Xvb{zA#3tugw{K$xQlM`?d-#}%)6~o)W_<=<( z>a-{GNnf|~6DxkXT*E*Gg6jqngk_}f-7A}o*~CPg_%w_mqKa<7Y7in>yfuHsgvH=z zV=Rn`#H>`2)6E_2ch?K=I0IC{{caq!&u+)g8rieCTM!38g)&@KK0ONx!RL2l+eddI z9lJ;Mp;Q%Kl+||9fz2Msf)WO6$oqYHPwz;z_V`(%(kzjm`YT6r%Wc$gztOofef2ip zt3A@2>iyHeUknI0%~F*KKA&jzMkcer<*GqD+Q^QtsP6826sgMOWZ)n@*7G%&;ACcC+G4)IC{0@j(CkVexWGNtDZNh!2+agf*bX*-P$zX+gC=8HUP~n$0HKxKCZ-a?kY@8n5fM~ z5nq)lZ*=%5E+5+AgWHU^55ndBH9RAc9!afTBLJhmzVnhC0MISX*;zSze`VEyS$Z>h zL>bjO4YAKFwIK{Jo93yReh!V?^d2jPuP-=v|7828?tLvAUa7soFwKRgO6a4u$3Q2z zB75Vz1T%u;%yRYNFv~06DcT~@0d-F%945i$yVn&wgj?%k>n`P=<2M|L_rWTFN3A=H zEIZd*>{`w9VYPtSr1Got!*OKB0SBTI&ns}q0;`R#?Pf!7rMAmh$C#=xr`72-Tj7=` zYC65{)4^=X><#?+vr}m%6FY8aB>aAXOYV?mmc-?#9334Sqs@j37v?ulM_Df323XwQ zM?HQ-g`}&@=Lt)Uow=g>ueXknSVo}N>h5TjFCzi!H=D?K zHJ7gO*TTzDhQi*w8n)2u%$Kqsw6_LCjn21`&s&|1jtH0{qmdQJ&S&z^r*Y`=7*2~t zMfcbw9xuUW!Gs}Fw>-L!#&lmL)87=ztmtb6pL0cR9}VWhob*L=K1Yi1dLh(!>9BzGTC0WD7k%S9pN6Lv@5@JHe=vqkoetdzuUhKH2zgU z+Rf2gqLeNb5Wp=RF`-ZUbRm}UNS)w@jJTe&mFwbs^1eD7!vhH~zenY<%ZB%HG4^Vt zrK49$%46A_7;v@0%LI@Iq zMIXnU%b3f-hhSWE`s>DROr2ZbR`t#FVy1XrjS67)GK}6+yq6{e* zGA&W|if&P!@c6rF99~}lEI({6rU}w)-jg7-7U2j8BYwBXpux`Na5-Wm=m9yNP1hpd zCg;vgwnHlrH3NZMQrp)e*6Yn^Mns4WSq zK;TAnzQE4h3>sP$BWvXP-8fcZoVIq#fQ@mkJ2tZ|In1q6&Zjeq1o}e3Yv2#P^(YPZ z{%t0<1$uX{ZP0=xTUrgY^Y<8XJm8gLGRh5vHMc#o;gBkOjeEoqSJW3N)kxa=aE>Z% zgP|-sD&s&mjG(fI$j8B@g|KP7X^PIS*s~heZ>H%LJx)u8!{b+AyvU4hgB1?6`rWce zytv-?@OSzI?_bvq9)o)l>hzv?RZ<)J-ac~ItvFH8ElV%|$g#T|qWIbM<`*}{%TdMR%m{%!fv$V$Z&$hJP=ZkP!MpwBiS+q>0 z`{4w%GW@%BHl>EDuTH&n9|qf^`4U#Wlm#G$e5iaHL=7SOM^Z8oYo?b zNq=Za@_RCPR5_tIdl2=oMP-LX!PC>z*SfIiZma^bzvDqoTmMgPJNxwtM}W*6L)6b< z)S+*5GCZ^=_a)!cAO!N;oFWCe=r#Fj@V<@Eew%3N@l$Lm+BC61_b%3G3;FH{>&Wp$ ztg&ERXP99yr0lmlkx3&!IcPjS`hHDr{3%5Bys!ktll({E>tD41$uJ^=vX4?FVv}DW zmU_XXehp=cbR%^dOB-4Vp^EY|?gxY9+k;)m61v0k#)VV%1grk=y9Su= z=dRa+=(n|{?;+{%*$JX}uBpA8G0K^KZJu?rR3C;!Yy)$_C>Xqb**{9O*Olz!lXVM! zGyz+3^*A;q6SikALjU+kh~?R4c6LGf(=L4cbT-k7jKprSSMNB*P{GQTrWuqi2x=PE z?L;}f>X0~hiv~qkfDR(S7c?K2JsQeUW>)C;h>}MdqAoXfaa1qTx#JQZITSe~%Xr(r zI%a)2x6YjM3B0(|K~2r$%Gi@mGTlZ`3sDnNg!Yw zlnb^s=KM29on$u!4Qd$_ur9OW@M`ghwHvJ`$3xuy$3Vv(&#{JJAv) zVj-V&vj|L+8lj*$MZv2fB#)wD*3wYqM-btGpjtPipu3e$pwpE8q>I$^=2MuKbJ^j( zDJ@r$s9C#Lf<$WflGCDzU0uF(-N)NO+q7llr+xwkkG2C4-^pe{lc~xr(B&Y87jn=D zU|_88%q|+rBdqiR=RTd8qk_`6s{jqYOdgF;Xh+;$M_}&#a!;W(W(5O%$V>~V%8j|g zYSiS0PzTbry+gNoBU=gYH5-k00MQm4Z_By+5oTlrt~1}K#emr4x-D!msGvA zI}q8F`93L{^{oSoNjT@*b|s_JEXI>c(>#WI2g&v?^q|@3q-R@0FK&x)fCy&3Q6uS% zj1Qzggf6m-bii~8cvqtG1jl$fT(9=a6mD`Dsveq7^T*4^@Xo^i1=x|#XMmq_c{Oi z)#~b2U;&V=Z55f>s85%N9}=0gZAX>`Ot9aGW`Wy_mAHt1yGpE3=H9ExGCw;$sLcXM!cT@^VaT+C zG+XU!zG#?Tu7~Z?%{+QQLWnD8p40LPOSuPZc~RK>5J=Re3pr3Cd`e*`-Ps5LY8Iby z)5*Z8Q(k^|OV+_fob72E=iB)FiIve+{_tw6vl$RbgtVJz@=LnUkY6&X5zpbT1P6kr zx6rfsV%e%Zrw*K0k(}%|k_>9}2c4lfiznhk?UUmK=AQw5I0m^CF=nTo1F9Ug!Eud$ z2e9DS*}3<1138yAQh9YbS|+GEpR2**{SDBLmWoxtMTAMjoY)!{;WFl`XE-9yIrMAOO6Fc?`fVWw9d z_ZJam84M$8etSC@tl2$q=tX?r6ScFlO*|jn77|eM(}3?E|Q{0q8L!KF!gHj7^1o&cu>p=!e-u#F5 zCd;-&q->ra#MR9RM>;Iz*5u1vTvzo1dwWIO+uLm%9qA@?=MJ6lkzg8}4oSGV8)fD- z;Qu?#+;U%3=>uDkik0C?$BckbftH~q1V9^=F9h$F zUQxSx_%Px~9{ z0Bpp4zrGefT~LK%EKQVFlFb^6;e5=!{1L9EZV0jjK9CbP#9g&{h3&b};%4~MW+a9Q z0-GQZC*L?YRFagJ7o*=zUy{9TDIEsZaxrQpn@(b+Vnl-7_4XbB@81>A-Hzn&;XTS&g17BBtmelHY#G=X39=i>JIsDHnQNL_>;ZDb+PnKM{}@DZ zqj3!*%f8iWgn&Ov3(P^vT(b)21q3;46!qD9JX#^Qvk9-u?<1)>dihzqFNFZflfUsT zfEcclVS&)dfX23#sumiBXUQH}{Mf~v(J;-1W#&ZCZLWE)WyY5zJP)G*`|cjU@0Wm* z{8hXZ+QTP*6B@jb^giI9=q#8rpFryGq1xcyA%5^5f4mVzg39}+r@tOJ(7*nk!wC-F zkn#B=2}Kek@IQ3YHT+S@jT2|K8|oTo1~4u*Vi%|KPod*q9oxCW$%Lt25mGE;wOe+O zuzS)ou*j*h)FW9^91%ANhN1m3>R#^AzVALXQIvzuy^k4P1>SUTD*p<||J5pb-~S~@ zneiN2O?(cWY}FOoZx1^>=a0Y8#jln%D}tO3oE=gwU$LYyXr=sbk-B_2Hs6{Nz3!Nf zxH@OX4mVJlSAXK5nr+G_o*=-%s@qKp7&CjB8wF4@rQ>^?%-n^0B>1&Ln;-fWeM)Oj zY+~t%Qo52R(dOvg{<^clb0~GQ(Zz;g50nD#ccD)M+8Qt&Tt*St?bdX$(2>T4u@kyOF4Yv;{)0~U@b4imAwU7y z%9zjDw0G{yvD}9)z-uhRAr{M$k7vUqx|5fQIJn&7Nf= z`#LKGoVk?FD7Voc4_x<}Rg?l5mc7lWB`1r+w5`NelPYe=iywPZg7~X zc~j+*HhSFhDJ;pB8(@k?18d}%Mu~y z6uR#VxdU|JQ*l@)r9OoYU;9d~kVX}{L z*xwTyn<=dBlyI@H=0)kRx_ISr`!56cJ|tn}&4c0hfLdggtG)l=;QjP&sI65E6SavG zbg&NpY0D_4LeQI~l*)j8jJ?bot6B{Mww}?dCFSAIBv0;hCC2)X_Hp~coVxww zZ~hWEBL^+%!@M)X2&mS4gYQeQl8HD{N0zW#7dOLxB2q9wwD&XGJW?G5evY>1x|LPG zAGA`~JAoTlw%qQaOiKc-3=Hz@)m9>sX2^>iDj;5T%&???hIAg)lY13L(b7Z1gSUpH zW7plF0H!KiM#dTH`d|Ek1C=+OL|2K%z!Trzh$CVPhE3Hel(VAUO@!r60;9~ZTJxZ) zyi`gahuM^Z%3;ggLLfy#!xgbZfHy<1O{{xIRu^0yQM>Epqs$ zuahTvQk+v@*47CG*SA}A&qEBx4owg43-MU|{9ZRZ($11De^Mju7Ro)Ya$?KM%F3JhU%BSqp`E>PE~+;b6wJ!+Jh_zy^%K zV~hFn#YSk}#oc|pRJX%iA^KlMF1q^eIaM01m-yVGOLwO`0ycc7fMdk^B zFm`o6nC;3X%1Yl-z23{egkK+pssGr+)wI8+-3jOl{!hVHLGV1Kh2fUCUveFJ#z4Yh zu-;*Kej)eKySd?Cw$NXg<&y^A^A7yDmI3lWw@s?#FSO)yOp@HfU689`R;0PX014W5 zTIp|zmDM0&|EE4H>(6v>X!lsIG;sPk-L5g_DC)&r4S0yp z$3K&Jdlrites6-><6$nlcmbo`#1k`$ru0Rn82oa;U1xY^_#*MC=V}m*7PKb0lyU;^ zJwIS8KEzCRfAzM+lR1&^aiQn5W$G+9A4#&nWgF)cXC&Qb6B}jO#R!ie!Qw}|S)&Pt z^iCk3*Wf8LH3PemJ*b8A%zcuRB?J=?X5P#&Afj8*lrzszvZ{T^c>v_26-F zs|SSoa4ypLcuPskejt_}sCZg&tTR=hpHyx^(;$6dyuK$NXQ>vyVYu#Ux%003sq!Ai`(ZgfKq)&E1h4Wn$-ylF1dXh{2|l``eTwWUYbKxb!NrR4@w76XhN zPTr9L%h;Qpu09J1rr}~PX9QA;qim1sZ;j`2fHgjMpTzCw{GJ{lW%{(e$jtuecsACF z#p8@%)b#8J|2bxrjeUW@KH;J%ep(k0?RM-C59Uw{rzaITp!_t4K3oGg0@4pavz*ft z8-3$U)OAPNumZB@BfQrk5aVU3Z4kq-dHK9)XOsk?#>1RD5K@${Dj?bK_Ux#6?gH=j zy>pz@R_i?oU(^mvHEs5iN8mQXAl}+Ng8;<%ISgn#7!%80XqY!&&!lVh_gr3nt;a@gPq_z%#YsdWMt_(e-9;=R4H7gj6&S$noAO>C*2 zqtFq4VEre(C#&2xLGUs#i6YILM|I|+wJmsvKW^4ylv2ATQ&D7EJ!&aR7;%^0gocS@ zI;Ot=X5{vYA?klhjwlt)FoVn&U>*kL56yHTe;_Z9j1c5joQ;l{XunjAIqb2T_NUW- zxLx%y(-=CvYk<_LyMz)(^z?x){&2geF{zpdFhH>8Rv^N|!FG;X8C~q@ZGK`kV=a~p z4x`+(w&Wk@R4RYGMRZr9&Y!i4v;3LT>=@Q!{D%~8WuCgQy#go|Y#s#579dg<&d?e+ z3>!GM2cR>ThjZ7QQ)3|X=!rFk4)}6P5$Q@RDYpA+*b5h_y_0XowczN?4>v)w{Jf|8 zd3)R?w^hchG@W!bV0Jf$g%c{VZJFbV&VqFx#AzX=#5@M*8#ZrJi()*jm@6cl@DWZA zVzv};$k_i?|NEE5O3MPf{BE=@G4VD}1{!$Ildk+zjWITn?_(MV4r@6aYmD z7&TWU8b+${CpqdX2=m5zQntEVlof)35P8^aN^(21@&C3!G+llEs$l=cmrn$6GS-|< z!-e-gchqs;?lpJHKuZPyV_Ub!xDs{{G^f_&%(6jO+}BBzPqbN9l(R)li-cxk$5Q4Ru1n;_sLYUg(qv!(w2atF}~s*4wtC z+C%#+MD5)6lpXuVF-BLd;~dJgyP}j#Z_y~#;exJ2wox-vPG0AKB==S)P- z`H5RB|3Whx>B}bFH3C*xtmU#*_4B|tu>?LcuZULr1TUANjw~;}pP(ae2gvmbic!~b zAXl^1;JlTlWC7!)NXq!B5-YR2K(Br8$ZrJd$@$qd$)C9 zeI_Uc1<{YoozH!DXQXsPpNFv7GiO_56zG*@vVs?Ct(q>UV(35qE2G(>=wFv4(#%Kq z7oElHLwy%tv;6Lc_j)G;g8%;F|E*vCYw>^IIsQHax!}QSwIIsR-;QCqet0O^5r|kK zEA(5-fWLO^P|cSXLErG$tQv(U|1~s%(KEiEG%Xog=zn^8l$cGB^%a_#JwL3tc(Nm< z>NZqjVHOLHd`o_(O(h{%tp9ALC_DV-+t(33d-h8>efX-?;aQ22^d+XK*%>NrF#=*U z@G1j@6_L_zQ{S#E5%ZTeIEzpkVgNGfq*S!#=C-OP=3h4mo-I%>is^?pC1-2P)N`Pe_pU_k8Zo zgxW%mPu}+|_S1!IulON!VTm(q!AXeUeUg>6x$_Mb*ZetEG_{AdAk*@o^iU^r8CIo~ zgNe29qpGT!n%dS_mNX1~mb~16+@OK2Zh!DNiq`*&|0_SSlZOjiqAy(b!)eJ9{Atd- z+Y);Hn>B#rSj$(IKG>;CwdtuDw=r;dtt8%~ehU{TBIs%;^Y_R{jdv`V463a>(`f^{ z<5osXSY0ZYL9}aO+sA9607|CATNoF8$I3^e5KPa$3TLf;oZPgb_zIxWXabnhCft%Y zz%O4uFjlXA$MdW%tqkPIyI5G~@hgb`f}ZSs8J{`w1HDz4RBXlvB*G+?jB-Ay?I~}o zo^r@Sw==t8_rA4@`7N8{9Mz4%l>WtIEL~l+nMYLXVul?0b_C4gl_5nTfA9t~E+QT; z7B+7A_EPa@<3=oioBiBXNddANxGAmCeW5Hl+-Q#EEKMZp;;t)MYj#X_*M@V?a>~3l zoZ2zj!+8qRMm@MW|MTs|(JEML@V?kGZ=J>5>h$}6j#a%7e9VxY%MEM{cXu#}Cv{i9 zsa4j+xUt>Tn%?Nn|ETdM$is-XHrZa7QpbkO8QrVX-xa>@DlY7L(X!vc>$)`}E!|4* zk|&JGe%a7Iq$}7zr}18p7m(2qV5%R($PU3}j8uXFIn$|!Ir&Izv`5@6!G++nlR~`N zx$Zc9Wmy{{9{59N15EQb27V4sUFE_}(D#tliBMQDd~39!*(VKR{;G@*4Tdy!hxi$z z4!xSX=3>QRsPSP_#s> zN`7tVkao;-;^PwhiXZca`_O*wW%d669|TmMrc}5lRNYU$^tiaA3zDex&9XU5Obl|U zFY$pRu-`in%Vv%oB@d@0zngd7?R;c1^eX5(9IlMkIPK*s)VO8Lni|{)rL=qf9dYIL zwOTVnAx_xgi19%6Tgjl(f5v%vNRNYU|sUE?|I3kt(_oTWl=O3A(?fGbcc{r)vA-F$g%m#;Z z9DY_oO{_0a=>D$5Hzgvv$m8T5ukhXLwIS}%^~fUuv1Fjh8lx0YtINE^bI{3~V}IEz z-Z_c`cnXORbJ72s@(B*EeD>xvKkvUAgWIw{UERG%y?OnuKzqeG)?F9ZG|lZgY~jrl zzWnVKnf^tQ1-mDBlqNSe8^tbKv9VK2VzNgsu~fZ2hrmcnQrr~&$S5!$nY$wnv4*i+ z8oEdGj-u_e$U4Me$-w5@BnzMxmXIxy&YRo8kM$B5W)~*8Qpa?l9fMV%#7cN9SNgt&7nfX zqjLA1R`Lvl%PFF^$H(~;oN_monNd?)u6draU(Xn!78Z6#&j{k7a^!7pZN$e;xIHYICxO1|7!!s z4_6?X2}oKZi%D6~TM3u8a!Xw$c{^JL6mfV1To|NV3ns1Wvr|H|mTUJSlomw7d_Mn2 z%Ei?%WcjZ`T~xGF{8bAe$eHp|(rfBWDjdGE^Y%CT9AFjweMIUXmXZ_y?|3oYe+Qkb z{yXSAA@^TFXSspdQAiZjXg_HwDWuKKO-r-&a}YL%-3B=B?+*6z;G8MZVGB1!kHvenk;*?`MMN;DZZ-La*RuOI?4 z;Wn=mdbD54$oBpp>#Izj`fzw)!Kco5<6{ZlKnn9wafz}qQC+MspoxE;cRNSKyF*n3 z$)J0=TKBzJ5#|pGsj)fYFH2tqOw;`Vvlw&0K2OEbliihR3%+9C)j( zv{6`W{62yJA|~A>{$ifZHBaYM=JaJA8&c!kR29z=y}<%!8JpJuW2&rA58wmR0G71LIQq$M zT2Ksw-mz5;5DHdzX;9}_Onc?>*az>$_PNlNigYADa&S#Ica3{{0r!;fhX%3x@+mFX zHWM++^DARw5W{Y+gP>UONYz0rAT||Ql+ILF^d5r6pcrO8)Jz4;?dU{hQB}uq9n-h2 zu269SafQE|xT4eFz^Z6$2!zzyJm`73)4kA$-a1^u-&@%+NRURzAA3csuL1QxEoT^n zH^(F9GOUz^!K`~U?WEIEQRxajTPqkj?of!(=fF5lVDbq_3z+U1HX4 zt3koCKdAX@W8T=XXd$pDNebmiHZl-yYr*G)_DaiIS<$Pis)8998v|_DI$5ihfzKyZ z4ym}fQo$jiQLwP4e>~`yVJ8@tIUTAAM-h7Zh)g#Q4h|x5RsV-gdfW02lT#e9$5RF6 zV$~7SPWvRS0UBgv4Oi#EQfslPbwc>IWHmq16a~FPpMPgX*vZK$b^bRNb9n!vmdB2S z!=HckLEyJ2=`4d9u>UOpRhgOh3Se+|-Z>h^1C_8A{( zj(Kvm5KcL*Ll=)v9HUFOZbeZT&Cx~FD-3|0J~isG>M zUh=GG*(&WsE`$5c*jKL2_}XTNnG!-eAc)2B3krI} zhf;FW6}FJpA|%qb_9}9%de_+JHTaiQH!R29(e(qvjJw;^5^%2DBe_A(`7`7;%Y;~vRf>h&6>&VO&>qB{5&otAE|spSKO7Tsd%%iuE+=zCjs+YpmgS zpoH}3(|@x@*uILa7V}jewF!j&udinMX+HlDq zy}k{KNw0y#R`lamSK5~s`f3JjcS|x|?GLfqodf=zLlaNR^(q|>t1czPcqodCoy^eL zs;=c#X&ueY&3{ufdB)Y{)I@~7*j`a$&9Q7u@}(^rA60RuF?H!g3TF@v2s?%fkXS56 zr7GNrL#T18Xw>*#$$idG#PNO2xC3|v&XoQ=W)$%;`Xjk-EITyDW*r2`0Ej=20n25& zpvKJ7&wSkmtCRdnZt42IcnR3q5 z6sA~3*@fO=209}}b22g<^z&0BI1BbK4HsRPwpF==p&XZ#Q9Lb3WX3+k)!JUq)0ItY zFVsHwok@&U9yF`ojX`bUX2a0`1zGKj0LborMV>fK@_1iJ(Uk25NnnMK|Ely!ka@oS z!7_ux*C$7*{l&P5iN>1stM|Mv=Xy)Y`La!!^Upda7eoP^`%&BQe6I!y8jieTzJ>f} z@QUn9-M{#;a9xkn-a+F>!d3O?6ZgTTxEly~n8I)6Mh{%hT~i=;8sH0LT@xQRv~`UN z;0$H^2VkafU zcyQTlMuA5toB10B7rtp)G-d&aIFN=4LUprG&TvLaX`%OV!~UdR4ix%?`u`&$Sja4q z2w`fMAZ2Ur`-zpcbj98yDpX@B5WPpr-<+b^`%%oHbVyxvtEgDB(FSl!jm`gVcf}O{ zGRro-p&#-1-u2K4h4M83$U{{mPyg1&|Tp;a@IctU5&6a|4TA@wkk!{$VYp{nOHAGvAaT&>+CtsA@4B0|k) zS%H}jF^EOF*4!WZ*gM8XEb$E`QkHxBQB-`-_*dh5HTJrQZP)p<98W#B)Q|aE7~gZ9 zo=-f$rebPe9x#V34yzyp9&(oULaXiF?URB!7B6ZEdzX!sG!;O~>tpp*ZA@Y;mOb4zXhMnf|3*n!3 z(3`lo(*Zy5X!Z6z)2J+o&Fh9$FE+|j+M069`qmhgYJzWPk4TqR0&2t6p0*;F&ZC`` z8mXEinK<)pr;H^FI5W53rL zdsk&Gy$Otzn1m^QThCH^;dbhumK>)o_u7+?&>0$H^B}-a)lf}6dp^Fp`qMpbZ0mw2 z%TQfEUvQK0ei+^Ev|f?Rdtr3sF}JBO`nQEn%e9J*j<%*IHjVLUTIX&*oa}DIcN>$F zPOxG%*oufN`H-e<3*>fw;25QCs8Ek%X=jC znl&4Gfm>{yNBZFH)e%qM^u7W`a;9Tdq>BX*O0K6fKC$h&ZnF1%iWK)L6#mQYmnZA{ z_k68k_Pn<+T(-Qukr?S?T;LZ10-IHB-^Hc+sQ*Uy`4ztVrznaGQ>~sMZF$gi*;C%4 zNAZoJ>*s~F=2UBN8#Xh1-XQ(qOC8#u)_f;eSUDb+S_(+d?Tcxeuas49XfKl5MyANx zv67$gDwh~Dk|JyGvIO|MokMocRy*B;MxC)N=1ZT}BeiiaFBg-Y6^M|=yfV>d{It7V zZQJ`?6VT_B%Q86vYBMSIM=J5x{B`l7^YY)8PK=wYytIz+zkUptN$)d^UhbYdzP%hS zQdO8yP?)n?{peEe9Vgoeeizx*jn?M&yv^IRFJ95~4At*4zFo;7wc~n-xEt=dYjvcxD99Yd1y-FEQxilZ1LOCr7vwu3k;BB%YoH7~P!M)`2 zdG6hfpZ{#+I0fczi#vigJp=a+C-c}MsuCRb5?Eco`A3rTKe5n45`T_J?PY0rJPmH& zodSvX5~3SMCm9Q}!cOd+h*c%(BQr&`w?w?v?~%I(#!HA(uu%la@Mp>2w)NC} zb4*E%8Lw#+*xYhF&3oj4OK#oq+Tr(M7H<38FDm78CC|U=0rL!@Q0RCH$>HGA5;k*7 z+dtx+G)jg(a5J~us@)OzKH6rz#uUSD0!9K8-gFM;4SK<~r|A6M&1Rc-ccr>lf6Sd9 zKZcC)N_|$g%)sX-E*6_fZC^3Ta3)W&!6xqYKiaZEhOc0^+e!D<}#hB z5{*&dHJY^85yhmp%~>sw!;YS_sTFvNDtj83N?;Uvf(1vE$^lAB+%(5GfrqPh)vYk| z4Ca)UhA_1=q7g%OE8U)tYPC8HZ}@a45S2lv62tZaX6gBv9&}JNdkqk(FMd0JVW%3? zRh4s<+4mt1W~+faVBz}G!Ns;jX~&`;C*@o!-AtVumj(h|YL}Zf%B%HDDf>>hZ`9&X z=0pTnbBvrVa}tz)C87njxt$YkwCl93a6)Nc5F5W(2t9JD3`5#)6t^1DBPl_JO-Gds zTH+manY+^IeK~_6Ct&k0#di;pwoVmO`$vAbSs)?Bdi~Xn4IZRNvYS=iG$_znV4(2c zy(L#xCSR`#v*vh?pfN~&hldD~in9n2{xhINoFdORg@=bF?o(0bh$&oBjl+H`E#I+K ze<6?f(QI7)=57tMmEmH2WleO`N$4yF8jeJX5od#Li9UaRXx>?BKu@aaRKq~&e( zTbxsah+XKLc2^n{#mO^tR5@%5qEOaY37j8e&bDYMwXV_Ti?7ne^~aawTmx_ry$(^QT_3Xgz>{QZ0YS9y?Q8IG?{%Vutz6k)L3k1$;^!lQ&_^}&O^ zGJURb!UN=q(VDl)mcBI6@!jI~aG9QNG#Baarft0O&#=5-E3ce0_cu>Pjzp=|!u455 zz`a>e}ybTXC*00d7;^;Y8lP4n1gvTr=J?@Y;e7TX4CBdL@od7;Q9CA z0x>d@5EdAE`FP{%itLyBvyREkEt;dJRb=@0Y&G(x~1dmFy+_{ zOziqkbxc&c;nLG);xa?Df9bx|#tl^oKE!Ntc?@cgcz0rse^fo&((SK4=oE|H`I_@; z-no6cie8V4%D(72JW;TYGcd~VL?Dc=-Ss_(Xsz09BWvf9VQk_!6Xn_(dBM>spuph1HY))m&KL$`R~g$|#lZM#Lg}Bz79% zuXT0qhTr<~&g-F1@Nc;AH)fz8R%^1$;WMAikHQZ*;`lCS{QhHfw8-rXxhwkw2o{7Z zLFzg3aNC`*9mvZcd+<`j1Ri@KM5Hv_p;Pc1L)5IS zOPi;Zw9cU#8(ISUd52p%tn4-gEeA(ZSsCpcfWuDVv^PjwIF-c#5-af;8KZs>kfGnd zTh6>xtHBS~sI|J#<%vb}|ID-0F)=X-!TVQ*i{A7NyaYGaCs_qpI$E&>Sg0{Kg2BiY zM~Z^Al}$Q~Fsh0LBr8xO{r0NuZjCBaQ65K;7GD$lXKT>uEaN#jhs`!AQNaXd#(DnT z0e|?9&L``aW|PwewJDCoVWd;xToU{&+se^$e8o8M0)T~wUT&xy><(tjapvdet!@6A z()D-zH#vctJ>0 z{&si^?`vc(7A=fjRmNC71Ped4x0e$ddK4EK$wHLEx;QQ)<|BqACSugd$6J;s_OHRW z8U6q}9cYlS-Q;QHa>XbjqCuw>iv;sffb^e|vHt+*v{11Ax8;dE ziQQ8zN&3Z5|5WpB=^46Qy%D)FVl5Pi%C6ytF@z+nPK1)NcR%u{al9^QGCFSD2G*vNrt-tPw>NC)CTMvp)OpHxS z`#!MAMY#DNvB{s?H>Y`DoS|GKJrB?9QOH;mJ$k5%m;9#Q2WE~u@f+R3kKqV9xsT@S zZ|i@*goGzxuvm7o}z{o(CD`XLFI&be# zfI{r_dG?9l1elvTmm;f*CXoux4vtM`Ud{lB4xQ!z0SpSe;a;Wij=7Of_v}qxOYCHj zmVHn@ukCSg{Bf_myt6Ae21o1H*ZsaUcS1~7{ zRqmUJnRg50h)L0lvYGLn9jya;#qkzmpdwisWw zV>EC=Pck9ffK$DAFDbzfe+s&}^#+pL>3a#P%GjvoIUoypg9 z)5IEF$XQHJv)OL!-lh`ME3L?^w+)3qWWB-t>P@5Tve>%ZiCt8Lh-4al(8C3}aUKl% zrQQ)KU=8!BdvK8C!QuReh?h$;U2{;|55@k*2?95sFsG{E!*~4#Oef8|_`uBSrtL&c zZZ{*~2{N+qBb<4?5fNOc$x_jeO`f4B-(@pD2ERi?`Da=m z#8L>7-ixTiy{&UC_G_8TMNI>*j?I$TYhC8UX2;8Zjz*QYu7th$44Ah3+ z?kHGcJ{=mWg8CAHW-Mq4Ja7Rb1Ggq#oxCf{X8r>McY-?KhTjG%PPv;Y$bw#LBi-NI zO;`Dh;9{(U=eP9&QsyF=I*3;uTVgxJOfGcuJkItzzYn^$4j%20&Ah`M)k^zvzfUBb z#x?#Lm{v}F?IgRK$-*4Es`7KS17V`QGFmA_+c)DJTUuxLT4JOE5^KV3?Ygc5A`1(s-%Kek7F* zZm#x$m5;AIK#Y=j@>(0vFghDBq~(8Dw3r4UF+z1*p>)JV7+F22-1d5V>fQjKjrvB6 zgTQkfu6372LibzuG0=qJ;|w!C z++$j)o+;Qw*yl~{DQf(}TaB+B4Sp@7GCT_7|H3mg7Zkb8V6yVab2t4>cvF$Skhb`lR zf}H%K4@38CJ%qsFemf~HH5GKA_%X(%&<~iXa{~tY`nWwlJQlRS9$OAO&$T#Pw&H90 zXlY+(CV4Nep2D?Iv^2Dgd-lwea&NpwW3PxIyk_jd->RBo28gQ`ys4k6fe7H|=QuHA zTUBL6q|iW=?IPDg%dO&{E`|}Mc`Hafr`NKdV)Vmj3#gOWI?*u{B@YvUfTKb00a;_z zTcwW`MlHsEAh4-edzzq1-z)iv`6IO5kcJ>cYE05)?Pxx2Rd>bn7OQV4%yIh0QeEUY z^+lKo4tLGMX-P#p4Sl?}`J87j?&xR5hpO3yTjy2p3{CLZ{^gGYJLbLkJooypn_S`m z(2_N8M=pVCBu;l$^kwZ;Dexncc=k3N-K04gDXHD-^DT>EKfKT5;wrPxlbdo@cxWBV zGm`!ARd(y<-pbL_6<2IUh3#sGCoknGxN_BpkF(NJ@s>^g)>dqJ;6dZ#{?nDShaKqg zWr>rL?+20jrf11{C(P(E1u--MVDsg@znCd1;PtpPi918iAl!t_tFd#!-z4On%$qI` zhbw%no9ocW1Mj{IW998A@}#*?&r_ZnLbsXkYmtBEwD}DCrDZe~m``ggZ0;QKD~h+m z)6+DsUL2wSmYTf=A_FZ{4h^o_V!e?!zVTM{ z$?6^*z4C_fJh|iPA`s%K#tP5zJ8MX#lLOsSZj!bORSk`)zMm@lpD zXgSRQA{`$QYxk;WVf@dwz)aZao3Dwq{Sgwtl7hc?1k78)Tf6VAG)XHCSZb-~L+=q2 zKNdBgP9dy5=AZ_L|3U)Nc#1XEmQ$g4&16=b4Gcw566=c$)ReOO{rk&rc^ip-jU`K% zoW6rPj$poM%EaBMQrBH{8GpsTQGYDj-rYR?hU;s_K)=$E(0N=pcn~M`P@z!M6M17j zy;uSI;9`rBq7x_CW1#5_Hz-k@KJGfF#g>a9GVJD{DJ^|yit{z)rIyu)t9Lw${XLVS zcZ9w2#W=5JWi^NM7j~CRut{D}P^9^{`AK&bcHd`#Ri*wQfx|IlvBb-w$d4X3hhra= zMR|3XE{anvZ&QuI(NtO*LzA(Y={{Dn1`r%dG<6i8E9$Z;Q=S|Fo)|Zw^4(Jzs-MAO0F=wME!adEK0LaZp;>a0q$SKa+>h zqdeDnFw<|H%B|BAa_K?HKrCSFyvovOz1ZJmzj@>K8e+z)UC}M~kxLFhW-9gSB4ss! zVi?VLr=K1jSNq6CdaNE?XiC-{UaBX@tp^Zykc4x$tf`C*vr~rTQ$5B__AyqOR%815 z;-YunLid6oy)M+>6QHqH`vwe+D<8t$-~4!4db-4a=h(RkLK-?yA+Y||XNoh_OiPn6 z_n?qCo#=Nmv^>@`{NV6h+~am50?C7IGR2|!Yejx0bv~@iW_>{fq}DjKv-HtBx$eeu z#r%Yq#z1W}qUEmDnm6@#)?pN0ch(mi;FD<|b5X^<8d~INvsT8Qc9*2{lP7SjP_5sK zYKrrg5O8S!PE!w-o~h7oi`DJomU_Tt3KfW8W;()j$7#5jWDhEuyv}gj2-9+1cJ{iO z5Cif572?Gpf)%c*>-hAnOFZiJw?T#P(PIMSmv1{-fJXP({Fz(nkNal*-9d22i?4A@ zK-w0Hcw3Y+&Xd&xoGte4Qy#aFeZchirhSZw*gXEq>yJ?<&OHKX_ZQ5ZS$1Zr2MX@u z4|BMa3^7iQr`lzo{g7Zu9+TO@ge-#+2?9dVlz&-89 zh^#t>_RK@L1D zouHgoOEp+#+%sBE^&eiyh_zGRD&6ZJy}9I{Tbjt516uZd@9|DufshAL!Eu&zLV)Qn zjC`Ru&B$nmS;3B|a=2nCxoKCgKa=R6^^eWQSw zSle%TDZKk{i2b%4P9^6aG*c*~{2oMH(}|i0_y#Em3yLjq86pjxxBV+q!{MP$+zpW= zB|KFEm)d`aJx_IPh@aEoRB=LZA|Ypj{ey)NKAKCec6eiP*l4A7D?H~0hdwEBL8y%I zcH|8JJ;vHvf2aTP_<%vw&nmaSiwX&Oa&gXfE*2HhRns~C69+Va5xoh%mq$4Yu`0VjnNkwJj_Hog>?YMmX9#UZb@v{hb<1>s> z4!NDYF-UxOGWA*tEfshT0v_|y#Hbr)tu5_ngBIY#5d>7wc zzq|)v6mYG_x%P4@w@lN4#yxRyw;q*z-K>p^k&DMbWy881ConF&NsHc~8WR|gj`?L& zc51>5wQ&*QGbe7v>r{hv?gV9*9&+cZEG>EuBfL-!a)ULv5!#MBgAttoPu1;h5kvI*E<&;#xzX{L zFFmi2j7(CWdRWyu&EeXaC#fpW9JgY`&W{&tbHePWBNw+F^i#fruxuSmBj$RCCx_ZI(EJ7Plg2MNw`w&BC4XM}SwTLjsc@GY|Wv$iuOB^aIl=Z zx`c)Xc7t(DZ0xti?e5L%jcX4kc*q{cDr>lqo-pghYrzs@^*cxish(^jRhY4b<3wwq z%5bhqAF`yRq_?kcqTSOK$a1~nvBE=!^!N{KmLSO@^kgRu^bnn&J2|#8(ZTg>6IZsR z=86YOPf!+`qu6tYelhGdU}MM{4=JsQ4SZ48+Pj{dDu!XoWBN{qhW5??orapa%DT#` zm7SzsA|jfk)K{0;(^O7HV+i2E&K_wF2NblmwLMqZ>65p0( z?h_W=BsCqpRq#tj>uIp4P$onsME)R$S4NHs|1nCW${GidzSYwr)A3BJ)sBqMgg;># zMs2Zq%gP?pUptL~C~A?WGId7h3vpCK;6ML)lzii80vAj`ch%(8=dI*s z(;xK81V5`_fM(yDSH>sKswQY8ih6nR%6&pbM@3ybcPp-_=x?9}B#$W?x@aoQSe-4$ z*m_L^!(~=E%V5zczX(jg!OxH1!x$x#_Dg}c=16Xkhr*b@#`ETJZ@pw)HbL*+j)a= zH1!;FS}AW6Mi{hn^cB$&%t!H;lO02ZYN)NTFd7mn|3AT zg7CVmmhiLwnKc9|R$!W~J=N#qkuu&DPcy{QFUw$YyY?N+8^Eu{u)NQi5MLF)ZS*-rW1c(K=BcVI04S~G?F`SOgCv9#X9OsCPo zL?jPVOyiyC3+E|;7v8UpX&RrNdPS%>Gqw0~pNs(l&oEh+J4}~{_gc>PsED%WVE52J zB@|nPth`iV14uk&{G8U6RH}e-$0R5J(jUMdRu91+x?9p(p`+d?KVHP*cA}IiinCd6 z`4}l;=gC{9-I{2|8g9M#EEexY|sIXEP%Od%J_sPZ0IrKJa2lD+7hy41u5$Wnx~chp#lT}Q8|E= zD=xV!J1xDD&2xE49*2Z@^W-A{Sbi>2u9Sp?gtDkU>?;KP=p;K%DRuMt6TRfrpR80= zf4Vz~V?F@(w%!oBhw;2=c`i|u61(dIrW+rAnOQ`#xxtLex`F21GX&rg=GbkL(!^PX znp#q0pYX24$A7Mi=VbMC+37Otsw!0t>WXHAQgwub?GBm5F87PFs;%a0o?DQxgF&h$ zCJx3Xg&=v+{3(qZqe1+`LUwp(Y$(3e4b`oXl1B{-(4^8~3V>f|fhaX)KF+`0q4^|% z?8&QJ$s-N@{;ST;eyoI6I*=KDa^SYb;|qDcH$+$dioe_GYgnV#Wqbuq>6swVW{-KR zu;p_>npmUz6H^^oj*{_aUSa1 zba+z+wC-MjamX*-Hp-VgPYXzGG)IQC<>9fRve^r=1bWF_j|?uQc~_pOZUN*1aBZZvjAn6>LEml{QR2`1#z{2%K;+$o)=HZSFN zWXCBkD?4!Pq6l~=QPKCt#>Q%i%DQw5a@uPeu4QaLzy1VFRWKQuzLH8!O$`d*cFa@r z3kr@urq5=C3~Uks()!_DF$hG=z<^|hQwi2&xwf;ex28nxt|CH@TzBGT!g<#ctUnDk zAyc-n??o~p{)|F&67KMYoYZd4j}{&JZ5cv{<*ZrcSJDHgiCSG>`c4Z*z_k7;__<~; z<`7_rzIS)mns06VBS&A0;S|~WD#aho={aXS3IPr@uWQHI1AL9tTDP?tqKf`d7@NPz!_u-uC>86w>CE4U>s3E3wo{I`T z0skegcZF{6^mw3%$qopAdtpEjI;f8>rdPYY!GfgxJUbsNn_aSNcsS*UkThNl0G`moMGq*x>Zq$@RjZW^Qu!ZtE9zC+IlH@aB^oo) zQibJxLQ&IJ?mGZc18@+)mhayBKU|7SNtGe_Xwzc^>oc1D&Q7I@M9Ay-2HrfMR!Vvs zW0x#P8Q9qZ8?sLbbdGRK;TA#`4J&uDgZ%x?F>&LPe^paaZM_e8^1SBYWM8OTEE<32UE>^YotNC{wH^35MX?8*ft zq2jv$9UjN>7-@O{^E%8k49n?x#k``!8w2!|OWfB;AE~{-Q{*qTdz!8eK2fRNu5|-d z@{e+VcTO3Nca(3Gm%$-!cXz;yg3T6YwybrA3!4?ivsxdI?}SgtF!Sblij}>=4yJ`u z%aD5VEry@odxyl#ln1G(5NWEQUTjZ#+GDj#2=%ZqmTVk*X##{UP?r3PR(7so* zpmt+2BCBd(yYqYvRbzsMgQKFS?q0XEA0$gcMhsE!@Ve)(RR5|JNlmP+yveAn_!Q1s zSzs{*tkeQIXo}>=Dfle_>m<`TuZ>Q8OsQzfUDZ7nl<*~8*N*?HXSg__=v>DHXG-Um zYJ%%y;w6I(dHRgy_fBn0C>W^trns&uFzy~Q&q*5`*q2nU|E-vzrfYtrE5c|JD&KM0 zd-!fsoo}87hi}8{#C=oBr~ZI|*KTy&J$o^P*GbY!+bqh*{mKc$RWEPgM} zRi8&XDk>`Y5$vBWOQ&ZAg_C?lIVSCsLz4VJr?7Td81A~uRHv!zi@Ji4kkDHI2mttD z-J$t_hUT!ay1aC!O!Ki$riYLP8}U=*7b-fszI~_3R##i#vfDkbiIG1{tNH?JOS{w@ z*S%oZK;^7>mRcwQOmFbME?hmeWsVP8_BUVdaJEeB@9P5sML?T@V8D7&38HISso#Sa z*LsnbmMW*EB{e)8_O1ULAlBu?je5AO1yZWw*BocsB4K!&{(3EC$#c%~QuNRjTtE-?31ep9+Hk*f!E7F+~S`z(W)o`^*& zH<+%r^J81;j(hr;j8C*CO%?0=suX9fmm#qzD`TKjTwK1g(-nUM$A4-+DvESXyHCfA ze^e)seSLx#xSUIc#+#sI8tz*!(jL@T%-Xo83Sl%f!gg85o_!C^Vjy=pQ!skNM^+m2 z5sMTtYouVAVRLYI+~{|K*hkeXw5%NjgCQ9En z!O*Me>DcBW=_S!KA${tbqd&w9gmK-tEcka^Abe! z#U9(nHgIWXz9s2B}SCcayu=BNN{j)qO za|(QYeSNP16HwtgXjFroovLr%eAC=g5jScw!HS>_uGT2O^Wp~t(EqcaB78tS8yoM` zOi+)>a5Myw0NhO3om5iYg|aeQ(W zK$|_CHNLpwKy!N6S8p}1mVxxv8>jiYRd>f}?{hS5*5h6Cv;anT z^Ht>2vG;4Q`f!qbbwl0cf~|(ae(00;we3#Bsdqr-s{1FJM%>`Oq>CJel>stVhlhKN z3CF|sr!5e{d8VsR0s(nvFCGTlg-B9Dur$YcpRdNCf^XE>C*6(kXuhu;GP5gZZ1_!H z>&3#xM1jacADC`aF3Blavbi6RYWEKh^Ex^*J6?R2lwX9TG6*BLSTWyCx^J^g!bF0{~mdUiIK5*9x?#E3a;ar-T#Q&0LgZsbht`|Aq`izp@P zAbm{ISQvu|OgJ1I`_^Tx<>}rNvv|fTw`>ik^NBoM^^SBqPOW5NKq89wj|&h8rQS}58->{T zc9RXv#w;QXQ^rr=f~KJTIPb|i_Cp|s5)oU5C-O^(g8uQua-|Vx`1;NI^vGpR@581U zKS7j#L4;MhoK)ALYc3i=2JELX&NELd1$XLRR4!oh4gd+>>jCSWwLJC<47p#7qCN_R zhSeDkAdU&VJ_(}Pka$yucLST%=73a9-LdDyXXQN149(P3wcSf;4^C%bTCLsFoqZx5 z?3xqL{@zLd;WbM106?nsZk~4^7B@{g)-H|$9Do~nQqSS_hD&QnX(F854K(6k3KR{>p6xLp#?ooaSZ+iTa5@uyrfa-0E9Uen5L35PO*op| z$Q{z%F>8$mo%2x&h1vsblL_#OhWuYX5CtYn^_6>4C^|Z_xU^=ZreedFelfMR&B?7T zDhfF{v1w^-1sFmAbg`%P8B}Le!nP_>>F8=p_wVL0#C08BPyYV>Sy)(D{~18jtEUX< zMU=3B#oq84anJfp#Ouw4PLrf5z7?qP{`()Ad{88LAc5~$Hi4A^6SD}5l^L4uL%lTawu@P%|O2eb@O z!(7KPF4LAqLcn&xGoh7xLSSQKbK0%F8BU}#6qG*BR!`57`=G20M`tp6#*!czBU8k6 zVrTc$!dTIpuk-k{sH5Y;FKTlj8i`xGM5A_YpP!&L3eV6rWq=SMM)>;o$2$#~up>9{ z&E`w9^{UmVD%|STWS%_CF`?)iae_W6gAhXu#Xqa#=BH*wn=(IUjVepp_vgrpkNdtb{`&# z@2jvdBw`3;C3sjEiBHLXx%!7nhfrv9MR|F-!Hj;ip3s zMibR{B^AnB9^=lk6`xc0cy@49eTK}b>{-WD^0!c_cga^EIqAG}K@}C8suNVML`+K% z(T%U@;GZqm6mw0XUOt~&SQ&#fP4A+UmYy6^{lH|J0H^R>^Z8`1TKJn1Q#mOoTEbpx zls?V}*-;p`RR35dIjmty9->|;G6>LLXG1oSNdwKc7X}9hKeZ`*4_>wzu&9rfEC5hM zzT`I^7FIe$`O?x-u4GC3iWy3?bgR-?x)$kGSlnzJn;1|QI2yEq~0o303K~BN5PId zr-Ts;6eFuT64>_!mC*@ua;k}ms5da?jWY0Ve|&I}wDO@&oIYkTNYdGvEwwOa&?r=d zc&|l@ZJ_rk9zjmo zd9U?qw92s@tocFit7#4*25Bis!;EIhtae-THmXLlPD|O6IfYiKfja!#jD@JO^5j0N zPG!=;fdw!Ac;NeD!g8-5WR~dhT@tOU!o)Cg!GkRpNI{r4!)g0n`yl1g4k zOyn)*0`}}v871tWZL(e&^=fwWR;&xhc@|tev0-Y4yy1`=lYTW?dL@*w1JG}GgIsv< z_MO(BCV$pz{a9FB{3^ki&$SYDRp(Mb$m;$;!6Uu#nEaE{;hcWT6(-^UG zMEK>%DUB*TsG2G?&w+^@{;pVP|f7B1jJscseUDJav3rde0+SYY-}--1+ZP3 zrlz}q-RV;<+NPFMRwlE-q?|u$x}7$wg&+wD`9!C}42kv=FwS7GDyQ~BMX9%K}k$B%(M-T z$16bv-e-V%B$};KRf7y0HptA%>fHs=g&X9S5i^&OZJ5Y6EqXCP&a2fTfccaccbn1C zhc1#Sm8;G=l_P>^jtdXhl{9rB8PO19Rvhz0QSV9=4Lg+C$NJY;aS<`Tz{XR*@TVV9 zpWn*}3QEx2a}{IXGb)e!QkuUv=5=HUL}m#Fp6vq>xfUfVwj(C6&w5N^Are_A^xi6C zTs1k13k^tl0=&EyeMm0lmIK$DmX;Rr0)?Kjqd+fXSqnnSIs~PtRJ8m}rkRH<_V>*so;y5k^!_x(?d%Gfbb}9>pvT{L1 zMbyoW3n9UdXx_v}NF@Lrcw}2!lgH`1vJRou*KaONX;daHvrxLRXr8EmzR)4c0$yNV z4(N>rtG2bN@!}6`JD|x>#0?6);rkdZ$ehx#QF|96uXhyJ)1uCi#QAen%2hm5MVX%u$9SweBGU*Fq);7ZXbuBomYz zK>9i3+yVDtR3-DQJ-{_f(^EkpIPzur>8g`Q-SyI#mf)e^`akrmuB2??D|sBPTGbm- z`Clfrq;V2}S<1#r?MsO36HFi826AJlG8iENeb#Pbu=>L(QRp4p03+ey;W4D6LN7u$ zt5=U$l23F`rBsUKrV+<_f7@~2rOD}cQr3PT(0!uzycPPJ@7ukVS_Kd}SWo*cI-J%} zemnLBUAt;MinR|8!*9(L^y>4Y-fv+Ek>DdQ!#_%ibR3MQg5eIM)r0G zZC6J*eC#9md^^&R>e=iD%XN1awx5q41{?2YqhCc-pWkcUPDGzoB*^Y_B@* z&J^iIp6qyLy%IHpD|gpq@wZY8KX$lSQV8fc<7Ks93t4PSGyOpt$Oiby2Ppuu`t*0! z*)78%AvQc0bten3ydY2zay3ap?t}?X3364FgEK2Y8vr%<{fzK{p6#8S;9puJ7O{#{ zuy)odiBXFNjP_UOJ}Q)K)TznJB3XKONFe-RlO{ohJwK`)-$=`+mcMkSb(HJ#QlS@T z8*Q-Ql+V29eemM{*0m<_-p<fc6;}F?pOll&-30mM z^4>(`1OF6Nxc`hrHYHT}+vap3@;pDKd{`z5aX;=nt`BV|D6_VY1l_wGk%#oUBi#@0 z#-AVQy!5~cUe{k=g}iSon@*pz`sL+)>fOf8@ROMwJyuhCjpffWhyiP6Jy4z(KKe(Bdki?6-)N@7es?q;>^$C&tgG` zV1&AjWBlES*$GCg3vUyWiVd-h})?oz}uI!FR zgI&9qgvZluSo1Y;T>F)s-|H5AmKRCW$BFIh;W4dFD|`~kU@9EFQLSOiY5dKqrOfq;Z3SNeCEz2Q4zx2|`n>tkOLe^#F7hFPh4q+7Iut zB>TdPXv6WQK?=%}@*U(1X~70PhBF^u6AH|R%x2K>qUi!X-l0r%4x;$%h-V_!+ zXKjM37Qfo5Y%3dG zL$>LhW*@RISfL3|1Ey$kRAw+#hMA zoOHH@{2{doAnao5ey2;`-^I43#PovUx`Y{TCdsmZR|4bkLpeeDmzqPF> zi+8O^rij_mtlD?9-Q%7Jj?b`P2=ykp*V7i&1TC;?U#_lbYQ=HyR>hBih3oN{VudRy;=4;n1P zr9*_qfexmQZ1iwwqMmj50xK(<=>$gP^{uxE)UY^>BrfS2r zE@_LV3cv(SKteP6NuiQqmi-JFFA=y~pHu|GB zY?yu-wHU#-{X)zRyXT9B*NT1u@vjj9wn6r&Wa*0Wi8@oKlN`2_Ky3u`+%0^X&Mji0 z+8G(T@lAf+zEvaCDPaM+-<4luz`vn#sUT#7F`;$qGW(v^XAhVArrb$$IVQxO2o95VFf4nBWcatZV40!0B5VpJCX8dlDLhS8jwV?||E_(wkwROm$AV&Y|VUs5R@%!#4Yth-O zXMJ#T5C{k3J^6tl+dH;c68psA7s?Y3Y_WYQVPh7@GpwSgV{iMo8beP{zMCfo=zd)P zh|Ev#lhcLRIx@Uie)5^Y(i(94JUm{hxdt!#7#js86p&NTfux>KuL`mYvI4x|u4g#g$NRuVF+3UHqvXt|ij zsOC~QvXfy7MJY=#Skj^v5{0u2AwWt13Vo05Fkw z6t7D2iwOb3mVGT|8eJe81tfxW>m*|Ujx^}~Bhw@4NyT6;;x6`B3d^t$6Y@Bp-hMIL zew&G0X4s|Jp|M}vu@TGYwsOQHBO^n?XKylU9vayvjBBR_b=rJXMf6I#}eHt{P;4^K)bMT!Suf9 zrNHM5x2pKpi2fTWQ?w^=l0w}6Mv!lGbjU&U16MS`pCMS3%khjOPcAV~be5%47~TO{ zY$SZMR-5&LVPf35U;p~meq*5y+O1rV#m_f-nDDtTjpfK7{){?WU( zxxJm{@nijG&y5mzq$m&eT|{GMWuzg}6dx7A)Y6hv`Ig|>6J&D5Tb`PXZTlNw0Y&Bc z)E_S1;C-G7m1aR-+Rh{@JnnBVX(lO2NNQ{RQyhvmXVL|QJnwedbOAKlM;v$+HyAE}W?Hjm6omOWzkVuH>= z%w3|&KpQBkqtl2s4~kbME6z;jhDX~O0ZK3wt&{ZI!3Q%fhL`!d?idVhcZ&V;UV8u` z)6yeIOc3dqI!QTEHbFke`mN8Fvof-ZSn9mX{c$U7XA-eh35^9oD6dx5On1~9Q~&J8 zf1xQ$LD!!SLgW~r&B)Iu3PUCw3;UcAKX6Y&;Iul~&Q@%S8z0w^bN!)1W&<8#+WPGHT$}Q9{6UG+sPbAy zt0nV7I~Pkv^M-l735GeH8f3lWbmPU6QHMlT21!rP`{JFDF|f!I02Z$&BU4bzyeLi( z(Un*#U(k6)VTQ!cz?c+F$LK-xu?99WKK{|g-8e@+CtCOLi*hOv0$yA5V_Nwf5eUIE z1vGdqn7mKS7^Mi~tHkao!3Cp8zYl+5IRB|%;5-JZa6_z*+*`jL)^P5L1U9>(3%;t&QW7 z&J{hCq20-4`H>sG=w4j1uI1ia_)rZlw`Hfg5c{~f@MmDfq7r6QYmd$1`?*%@+x##h zq^WZY3O=3h&%F|)G_d`kgkAUYd8MquSTUylK0Uge4Ac`19Kx?H@FT_PvAOnKW`MNH z%#={?4T-qq!DH8;4T_}!kt~!6hgD3eZ2PCz2plh5TNqcPXrJwmXHm|(x$v_mYdSw0 zc7-c7yEO)gugE_DEA72ETT>?gnOz-34R(WqPCpzeL8{jX5>RP1`UOF^Gn*j^{O7?P zZ>b_EM@&Ih2Tm=J$AW~fxOld&-vKIIL=|CA9Wh!r2V%14#2s##kxSMx+$gG?698Mkj@zc1ZA9>GG3wc#bi2d=-~NXJMjc_ zn^ol98o*T&xz+ZJ@SC3z#d%r7->+5hM^%qb|K!V5xEZvyCSRu(mmM2mj+y}B_% zX1l8!QpumWHCVt3)~4Qmv*!yg+)>qb_PQ9(Y%f#0y1F`a7I3!UvKXS3 z6cbzGlHRg+eOnygZTM@=*1OPHn+)9#2nc)*t9dRM(B4cq3jj;$c$ep*RTelQPynL? zDLGj-Ajtu>KQ}ig7ILpd-39=me0dy43;~P|^E%DKH(fDq0`3Ir?ug7MTTZy*g5&qqaR2CyYWmsB$pbY)RTteiN&$ZW3lo zS3hG~WI~BI?5L;+Fj+5#u*ct#oW;^G^A_X<3-!A^PZsViIGAMd zsf!b@Axm1gL(OmcS!PCsgC{D@aQ~!|1P8cX>K^6tKWILpKCv<3;t3sS!5P8s@CQ=7ZH?c4UH#bpub5)|rKba>-q zBsFBZ$zMg078i@Q`LfxwlyR` zS~)#E-MTws!oj!6Q#B(4l9jSlOmhJ;bl*0T;4YBNh(Kj`)MRAZ69-yZ0Tg<72W9w3 z9Hf%aar1^M)yzhbM!mN|kK z@V-XJ>;1#SPERt+WB~xu_ajjcjr&_hxS;KN3-yMW449liO-x3E)yrcdBDnHJ4`1X|pfono!14`?} zkSo`pUXC^0hFB5`o8u0(JKHbFx)ewECs3s#0&Y%G%ihF3!ZW{9=~HFk+H|4@6lRU> zCyL+SJM?|bMh&_`aA5)yDv%O-lJ!e3v$5f8NPW`CRy$z1%ccMn{{TtKjQk^v440-h zwXk5gzSx~`kS$T=X=+T;v3E=}B?6B#>+LtHy*-l8buMH26w$qaM(fW`_^Rh{xScAt z`a9R$XL(}v2 z^k%hOGHGg}rE9*%YllgzJA%2=uA04%lyT!YTlh8rg}L4)ty1{0_u;(MMQ2gb`kqQb ztCDT*{~(%ryN_Us=hXXd>x9KqlmfValak|3a3(#L18AzZVR=0Eo0z0z7yC&M1$}3{zYyIaEg-NO7L# zb%+X(fgb=%b9;LWuwDx;;w}5Q`}wNS!Z;$5z}8+t!5mm%hyI%hhv6-IJ*}V)#h6zx zT4V^wg}AvRNKH;>W@g;^P`@&s4cVWwW zr{l&SC7y-}1B}Zv;oknQ5S+~4muY_iOS&(jxMoy!ubwlVxvK4){!y00Q1=u*YxCPO zHEG61F43K0E9K;@zJ;{g^76UW4n=y+l<_|!6L?D(sSjMm$?0kEC8wfU;skwxn-8Xv ze#Usi+FO71Sn&L`O?$OLSWJ{EPfqp9h+b3f>j+XR?dB_;56@V8`vTx_JIT|oG`YqZ zN{4LE=XR&c{Frar8tU)!npQ1|qYoE7q0yoB9ejF5c*^q@zAJ=eDFoyG$0zFsZ#gYOk*BsrLals3#luSfNcTE>}d%>rss4Yuh6Yw6TKa z&_DNSO$YQhr)rfEuCxE*J;8l+qr#Sx&EschNY>Fr=zd$<+d$QMxVt~6>9Un+@8~o# zHU`Q0X<=p6i5K)aV4}A~Ij~`F4xr(GU(K7*h%}TjADx+gZvVaB&e^%$_iZJIlT*x1o zmSRc-93u#)`4Xu~&@qzSh>#-%E1l7zdwl=_8sEQse92SLm;^|c&nzVCUwS1#Y6TKo z5uqoX8;O$X3V=uQ)dL~{c}T?}kWwP}WM{tjo=~Ri@G|-7?8XnQ{=6Z9z`?0)N=@uY zqO7Z#dH2<=GYl56!#9`8vZaiy9C=l%zOBXNI%h@ZaWW)&y>P@rFGsUdLHiA}1DJ&s zKF2{aB(svRt&dW!fDwAQUq?%>W@YegyGWfdL%UoK zTM&oD-at>b@-Fws4{Rp1oIa0rQq5l9aob$)RoNXhoQKq>JYOI46B@i0I;Eerz9VqD zjr1m;cP5OsxWsl)@%S#MO}0c#evjeU`TfSBYOXi?{#GLHep~kL=xk!-p7~%s0;6h0 zXzf(fJ_=*P6#wWf3a^l-3?|PA`o>y^j%G_A)PIrKM=^=+ink3i2ktjy7Zo{cMC*~vP1QZhVLiOsfl>SboTG>9U zuANhgiQb?8(Ef1hMvUCX`=cw6tI5jKq|1O1C)TV7f!firtiSDX)qzJ~Ig?6!` zdV}z--zbmZC!Wf8JWr52gPNK>;0geTyVlUaK_b-W9VG#!^9AOdR^m4?3T@f!i@`I;uUy1MI_3T&!!qvB37Xq>?^?PUma9uy3C z^p1WJKEc8H+K$M6=;X`S3-@=`Z6gla%pkLqOtmZm$di9J&NBw#+-;?Z1)Vk+gqYe! z%I<@P1~G6(o)j#c^vv9r(;WT$@nnpQj95vs>F--iXh(Zdm<9Ti1QivSzG1$KWyj4~ z$wV#h`RYECM{HH?6>r@b%j|jCdvbDe$bC>3oB1Icz(CQOw%xQU1smSy?n%Tt2fj%{ zOqVy<40nCTE`zSbSEhUQcX#B+@3UK6P#zIgUl!ImpHm~+;Dy9{wtt$Le%5fSl`mXD zB&E-}q2>JORKhb^9wxU|U(svB`y;<*QIw1S%PNH~#RPQy*!{4l(_IugJ)tTW;;a$| zPyexWm00e`c91baLC^~$GTkE#GI3j?m2$E!r z6@}n(^#8DKLZSTeZuy8OK)f-yz>L5Lqk}~^MX)f9c9+Zqzs@lwac}=^h7B2N;XDVb zH;_#B8v!&41V%NQg}dK}mpG;^G!;~&Kp@G?&%f1YgmSJn!okPS?{#xv3ZzaTDB&Ry zPgh{TLjfA1-sbPa00J^Lrm3jl%uu{MYvYO!w%`f^?`btC9D*0bdo2D6ge5zCvC_WM zT)l-}mqkFc6$ey^x3w+UiF55rruK8qpUOTP*|E#UM|yZp^*c2lCq}r+;IQY(_Ok#b zB=w9lARHES#6SwJd)WMB*Tl-q(lT+vPNBD-9}seh6Oq;IUdj)`*~$J~xYIcELc$4> z(IWRXdV#CWbV@8FZPzU-q04SLJf`a{InThhrA5#ahNLZ!4ll^}F##Su7lUer`%sa7 z$MdnN4$L==Zqqj;%S4rdC?$nCTqe-MS@s1js0AVtp zi-VI~pjML!JY67XY2I^;c%KQ9vmCR#Dqm=PaF^0+Ag`)-SrWxV|CR$lxnF*jaZ&gE z?FlkwRWkqrr7xfCUpNb>NjLI`(Y~iZMQ|2#;6(dKKjKpGr?qkV2cSn$F2Dr5UOFC= zo>Vu&q^B_Z6sdkySy?H&QAw?3+B>hy!n1L3ERBb})~1Lg>w~$x+7}DwP`~uLc{uaK zWjl>f3x3l@M``qe!B{&+XmR<4_=0ds}_oJG54Lr6Msu58Q=?KIpLx+;{d*0?^xcSoT>?Sdmg5&m}3 zhUbshqDW@$)IL|Fw0?ggZ-yL7-bTgVLh=G92ztf%U7QXXtg_CJeqX z7^rB{12?^(02EB%oqbe)J*`JzUp=QeH2Dj6RjdO@9CZ&hm5$9ryVy6&(`db+oC>&4 z*-tFXXKKM>MVg)rNKaD9Rdh5F}3_;sZ#XCX-4GlDXsao;6#7Fa0ba z>|H$}VTvXW%4!jb34AnV5hcy_fhnGf1RVh1e`T_g9!l80StU*jLP^EsqD2Ku_I`K}YcLa#aih z*tzlXaY+^eP=ojMmx_@UkYf&1mPWc{vkxW-{_#Yk_(l*4GCx^yXS3Sl0e-bwd()}j z`P+RbxnGt)@eKw?25p_krm91Q2ArCl67qx_0(@X!73-c&hYpd3t~3WuSTd4iUi@#e zO1;zqmOL;(7sYs}D;`>WtkSezLs{>FbrA5cErpnJnx($1XdwMHC`+2F{~NXEK|?(P zrx9eN$wz_?XsN(7FqBt>FEI;9t%2Gotl#M9`W6Ivv+&12KPAC^;(o0Sp^BAG4a4~0 zpw$H!P5(PLBeDCO{qRSsU! zf$m$($0eHs5h`_|3)Cl3817_lZVMv1PgCWSl`GL+5unOmAK79lGu+I;tEL>ZC8^oIUY5IJ%_APkW5Q z>`G2P=_al37swRYRk35G}jzm(~sGG}OH_1roX4KYNo){&}PW zZ5C1%etvsPtabo}1|G!!`&5GnGvf4U6P~ppPY^zXcv0x(5{B&|`%O*H3sJHF&5n;_ z74SyCRNjN53uZfO#&E)N=}uAbP|KSkA`0>lDxH8H5nUu;PrJpjyxnIO-%@@}-D$^u zh=D-TC;qYpbPoiHHf^BdGln@U?%Kk1Q=-~J1M+A57`b$zw8#$Vh*mOU5S#(~I@5C1 zoZdB_@e#4v9f=VR9EsHFrDl1EfGlxIqtMr*CvPOyoCV%c#%FRzP$v!m?dwLlevH$* zOqZjVI1(UVP2WKPfERE?AoB#Lv$0WV*2-z=Gcc%=dyW8ou!=?jY{JA&Caji^9LrpN z$*J~2BuGzY?AO{4@ic|B@MqnIKP;G}_!2wKD)b2uNJ&ZS4`=N_vI`dDt5=MR(18B1 z=ie(H*UaOhW4NH<=zJt;2KLx`Z$w!bpTp@kTK!?`2v%B1ispxf6Jn$=HMdg=5o*4vp0VJgc>Nr!P(ww z79jOe(RKllLOYnd2|_$Fq$ z3nkCQe-q;DNie77)5TYQi%XF4N{O_N2iZ5d)9z zqRM(-|{=|F5VmuGM9^y_5)?z?qrEKkoU>XG~!2obJhP7=?m-7 z+cKe3HV#@Q%v#S^9wDl76D9YaXxMiE-r_r;TS0XPP{PN5abu}@F9zZHeE+6Zk+sPZ z*tEW`^2*Bhn`~|0Gx;E*qeHK`U)fh8gs>d|k$Af%Hw~S97pP4*t)|)8Q z0*K8QfOB9b4|ai_1q6P(3r)%Fg8~siM{loXe7ZeWUR7mxakvzKB#%h&rDLm2V_$U4 zt7uwb=`ETHG!rJ2)P! z#5joGuvuR@WYHzbz;>=uda18iRhyuKgP;cOp>_pe$1B>_bg0OI8;3h0&saTiRkB+T zz05!WCFn*eLi!HG*dTE7IULGgOt7?mVPa|;9@PMHp!Iqe@|1btPT|~_P;>}vr|RZU znZAfRcwM@*zJ??~_bO=bC^9o6+7~Yd5HJ6Dk}Zugdqm|$$&Bp*L4DAFrSkr2%YdC) zZT5oCf$^EQ0u4$`sIU3?&iO>K*%-pvu8V7&6EFYI%9BJ!3RoXMzx>}IQo9u zE4C`ZUDFlT9W-{U)iFe_S3v{F8y%3X75}m(&nS98!o53J7Y&MLWX?Z=RR6mo&n*A% z(yDSk2Nwzx+%{l}23A>YnJUQfz?vk*{zC$O!yH+E$PMhR-+-sc^UlQ8_Pv<$@v$_D z!l(J%2f^ms|Nhs9j4%d)T~HkOwud`I|35I8dIsip9TJC@8iN2RsMTOMOXW4;ZA+m8k*839QztZH=hE8A68e{pBD^Djg`JHR_M!tUoQVCOx$z zh^3tqd^hXhP;E5#3a~fq-U|oG`;7lSC_u!AsGaggQotTm2CS!#y_&(TM>QDl@VoXBsK@Z(8E~(lrICmb80xFIxekHz14*LV4MD(hXq&H<4 zLxMR0-Qwax(#@lw?FNhMVaOUjm%hOHUeihgM!`CB)mTt<|<7x6{MzhkXer;(n?x4Dro5jQo)Rq0e94_1$ZhyJjY4F3dOpG0ivUiGd2 z)@2Gm@Vb=wN(6pj7kNW2bGI2U zkMN^snHIN=z*dvb{4myYPW!V~`t`ZRZMLJ;-TryaIs-ZKBLBIo5NMH6y{II-x|Ju~ zcBRtPmAFuGcz39WUzaAJm;QM;Pt_(AsWS7XXVZ# z`*ZG^8uV7Xv)ubz937+sF1r5nD=@(%en~SC!S)HIcT-dXmAY?(*Of`pV}^zxFBg&RP~L&L+07uqIPR#_Dlrx_D7<)$Mk2YCV<>W&8_18p8)wQ4}-gF^(zFQA#jiU+{uwyy`^1H7KSk$7?xhI!apea(r8U! zU$cTq7>!E#e63QHrRC9n3_+L8(1a!ycWAAI9Z0Bfh}Fkjm*1nuja%q`^7h6bm~8gJ zXAqOv;B0oe?7A35TU4kh8G74VkWiPutnVCMXndPH#)Fl|d(euK6MX_) zBCsgRED?7X^i8{i!haG_D5y0wG-gspyhL<=lV`|r>7qS(TwY!dM+1$*_3LTTm4|i) z5N3k~W2VIwEkz(HJODj8mX+VK^|@F*=Mf)!y+e_t_ety62t5(BV|(@TvDX)O=7&}G zqK+;%+dr(*IK_yKkOfs)0(3|G64y_d!N$isCjyDogYn=dKpd1mg$&_yHba-=B&$Qw zqik#Cy!Kfw$270nqxa3W6K?HKI#}os9(4N;9z=VK{6P@sUz5))lAi+(~J|%nEi8^57(MDY4|jMtx$<5zb8Jf zT^Wc=7@wpX`SZn%Cu1cA#r3O_3}l3E!BN( zY)qy%A_Jn4CztjD< znL?yh@*Jf?!(J(9r%n^}b+Yh^nGkfxt=jf_=w>M}6m7zq;muPfHR9EASdc z8=8ZA`Hi0Zp4A?LXGa1y|6OZZnyqITGn#6@@D&C=+;`;?x>Q&UZ3jp%Yc%W&ZaiKKxv*!H2ys2T5u@Abu&j;EIi zWpLY0r(!}a?9`%hg+lvE9%pW^E%z~ZQuSorI{eKdxLTvxz@nbcCGszO<#>%}I`?f( zD})K&<7LGcfo_+ldG{jHM~fAChv6EsyETs3PC|d!$dNNku04Pd@8Q7wJvGwl%Zqj| zzm9>PiKuES{v|Nw05dvtIq#Om9Q9jd){h1SOq@F29m0s9csVN;T)Q4Y{djsh?O`;0 zm!yX#LzLmzaNLlVTFLSe#4I*X|NM%M-0WD<68?8Tnn4a%y^zM`7>Q7QB%TuK1&lO( zrVPYTFaD3v4_rsPgI+QWkt~_=iV8F&xn4*%@@F;> zeZ=H_pke@eS}qWX37XF#KyT9US$J%#?MA!CE=b%r_cr9_J9})n61(aK%|&0zQ?$E- zkak1*9Pi&H>#IkieDup3rn71T{c-|J{+_<9hgjl-DB@80yUOPe+DOtqn8zLYDDu|# zlTy_lwcM<9biw!wozcum4+W+Fxq1Gv&8U!md3$h`&4;)!@E%Nka!-+zB|d>NOwhyX zsR(%VR_RDGf3NrxxZ;0E(Z9D|pNXaIclhJ6Wyfali&5Lk3JNR)4E*LQ{zC+oCUjn4 zvk3iF7XHtt5vC}nsPi#bRP#A>g^*%p1d8s=5C6`~%=7`?1*ukCB0bjF%s1-~AC_nz z&HssFS>Yp5lzV-0L7glRrX%abGbRUlJDRT02fi}_IpeDcxC$U&QaN*%8Od^{`S0Eq zU43w9;N2_PD$41`>KkLO`)abA!vYP<=*IHJagS9p>DKhI;s9(5#D-DMYmq9>o2h<1 z+K#7VDt6PR*)m5VAUHa6x!TGG{SyrMKoiLly*A%>)8YT_zdll+wU6hrBw}NSsNW2b zcSL4q4pv;AYGNpOG{&_~0K|i1-*BDqH3z4+;@=W_S|G*&ObPV7ZUIt%bKZ0>*c;6p z{T@`)5WE3`x=|qL9$^K-{N#+ef1gzQ?5B^JU&}8Nt+_0xm7jIeJzaa)U|$45*^cQ* zmfAfL3;c+PE-xGqNwqA}Kk-J)veRJiv1!TumIY#7KCBcxm-SfV&7GY*XBSUTVL9Pj zj*Ud8`HTZ9;=K&^ef^flp#twj{nffRj?vs)ct|?8?DZ?uvrYaJ`m z)t_GlrhP9?dsDswHy72xP+<4{GdJH*2>k8=tV^ru@%>wFh$PqOKud8vl@}dl95|XB zzIun?4g$?!&CQ?Q%u)c|gYD9;&~(Imrtjcppou(z^6g_v=XV(* zq#1>H*R~o3R&1m*2K;k^BV_!E&IP+4*>WwIXmUqou`DYc9r<(T@;81{&dYSz@r0Ng zamBCIvXRY<98H?mSvX;^p5+`+YvAX4W4sRk>FmWFvN0vxjQE)1Pzdg8vI_18$`C~1 zyCm`#NaXHKO;5h`LN@jG_-h!UOG_+}H{0`(8m9G0mGyv|jdg75AWK8=))P&Q%M>O@ zmoAf$38ojI@;v1=kpm4N3ut5Ea3>Z0uR4jXZT4q*wLNbgl3dmafo`?hZUcQ#;20Hf zaH#0$Y@D1OWrIS!V|gmP4%?$dQqrt$2k7aMh&-Bz#JwU~%2kOgH3m$Y@y|fZcvivI z#Oq*^hoRpRn*)jb(sFWkpjE=ZgD$9A4b(0yiSZW^6f1-ARm&L^krhy=xuqdtwN;kX z0zUR(>&j`OSF`b1YB(*^l8;9$l$2IZ&a|gn!f~rArcda2aGy`b{dgv?w?hFN+<54? z@sI_hqM;ov2Qfdi-yQ~#F2F(__9g%_(g9^r1U=2G|I>uiEq8X_rFPD5}hf5SFV149d9fw&6*5@lrdjMa;eu3$|ULKZ$MNZ_j87puQFw;iTd5VEOWB^0-a2 zfls187n>u>l5Pz5`J>^n>}Y14&NbTy1GKsH(CW_r7uONv)2x9y1TwNGxvyt@IqO`y zWqYlT@?JO`bX&Ec5HGY1BaI~(BnW#Z6&4n1VN88(IV`>Xz-=Jxmu+6L1u>y}St|IR zTEwToCnx!$o#tY1;m#6JF+hZsd|i{gvKFng9?U(zD0jCicQG8@DE{FCisvDsXY&R~ zo;gF-vtDX`SZjEv2tniEenQL4Ufh`-TP@h*e)~Lx1VwQxZgu=yP@I@030oFxk=Bx{ zL|7O4)mz3s7EUc$lEGc8+NsL}_$&Hk} zD*yQOHE~lfn%&PRc&Qu?3%vaWJ&xz=VLJCy&%;kOR8<$}oE9=G0VmNF3g4S2*W1H2 zy{!4rAWl3mytmZGOuEcmM(GQ_Km1u?==+apFC46GVNzZ)$*(qqrreebs{$R$Dqpem zSCF?UJq5E{>hdxkj~0OD1T(VtO7oSLjb{}_N3(W=M{@_z=-61o#=FxZB^{m6nZ5Os ztr2sQewmc4D7phQBYHDalbrTuBZTIOUq?!QxuZXrC&Gcw-(qxC;0G!h;%PY@9ZW35t4&B9CE*q;!| zDyH5ji*tcGYc^KamIk+T0HU>Q9OwSi+dkvT)DPir4FAyr_&z%8d7j%_`7ZZy#U}0B zIsVF50uF|LIpJ?9l>%y&UWSibqR2jSbv=`FhH*8#eCea4_-K1W=)8t;&-==U+1=}W z-YwKwU|_D!>9Ui%F}!AfuWA7_Q2CR|>|y%BfTRA?MdIFFKCh&;=0@i)hW$Xg+0Vpz zeLa`rMn5iVcya^GZ%$6lF_;{=!%Ej<$7QpWpM&omyn3P@bPC7&t9aN-PSjfZszyB?cQ4 z9M@HhB70jk;tX7kj9qj_vNn7ypxd7Sr%Z&G*CRoE3310a-A{5f(BvKgy#knff`2jK z)EIGowUO+Z1k|dGf}QYO>_*Hgo#xKFTU|M4)3f)7Xs+Z}#aYD33&C}FID?hk%UX{9 z1gy;Mc-WIa3$U!RLR&Nwo^0Jp6)(4AFP^%nR40c{d!L?Yk?NIOB*g|I$VSo&;f4pB zo0=|x?#;9HE)gKYg8lncaR?FKwY{*KsaBi5w%?*J>=_X>sCdD7?pVst$H&L^D9$u) zhVLApX0bNoyj}dCtqe*&XJvI(fmTm`ha6SQ9M`jX)5_w8PLbkYYDt%JSMZ@r_&Irb zy>4@$dq=|^JRzC8kav6QenR^Hx+trCu1zcY8OTDW!4jjJT{^7GqLiBeTSsb}zYQ?4+i59UUA#FSR~>;Q@8p zuD7Z{9^<%vFC@_K(dhLRcu!F}z~7bu&O)V7Gqs_C6b>}|2GRkm^KF^W6YJ?`^4La$ zh&Nls@zWz4Je9ky-nt{t%@&#lIHhS;q1Cr|lN6QYn)?5?*`1tR)SR_7TpF|C^E^T1zOW8>qtCz}fUb9LEZSPXcDE3Vsy)1D9* z&KM%*%GRkkV`i9zjz&K9)_WQL5zf_(o9t%I*Ho5xEpbsf?Q!g_d=-CjP)8?gztGF@ z;3gW~IFA^k`^u2)m{k;6FH&BNmoH19R6rj4&|V7UGdCyM!T_9%1=3t5oknRlH~x{4 z5uiW+M3*TkB~`)@6dwLOEIU5QW**D}z~n&6sQrBsf*iBp=}{+0u%2!6#qv$)$Q z-b-kZv?yEWxS7I<)Qt%Lx1T4^A8og`K7N?IvT(D`UE^`h)uJ1QO(QG+@nh%VAqybA zmX`EDXcZG1+fvE^Zb58JjIM=+#TXneTr_@@b>t2jM&l>q_|90+<5U2z3!)w3sWz33 zQZy)`&BTnM^@(B6BhD_?sp5#?o%F)W-6(;#lNO14xmP6dZJ@tEKB%>*ns+sCJO5|u zf})oVed`}~Bya6a~eO5gAYvUwezUis+e{ zc2`MlLyIK)3;6mQtQsuc6Y1n9Z{N4iO=5835gVJCxr6dq&?IH-tJ0nw-AhIHpWh3- zvE%lgosky{GWT+)6Fn0kgvwmWO9AVTF~t6U3>blg8C1$fd@!8dqQ&$!b9e@a3Tq#7 z@Y*c`dw*?)+<~UGO20e_Hgft=6OT>6VfQ2b!q|ES_!Rf+gom*5wbjGqf`49yy$L-^ zRs5t$>L0J%n#dJjqx7olX}p}m2I^wC5><<-HF`+8=+?nnwfdN8Va3^-z0J*E-+uG6 zS`S=$`wi-G(Tv*BQ8}eWS~GBkn4YaA)+wUMRk8DE9q{5j58q3Dn7r`MtCCjBWqW{* z!$DLzdZ*>Qv3H?w3?aLf zk)LCZmWHIKu-2}T*$30%6(oBnTqCu5EUKm^_1wt8$;nv#GU=b-(Go+!&6R0r9*XxR zH}~iVl3b!oFS^_Wae`Hsojh_cuU|Z`XN^~#KTg!+Q31tV<@w$@tGx*@3FGhUhaBA} zT{Xw7=}{zErPpt%QTVyk)K~~W1C>vAv*?-X!L^Zx95~3rqn%Ftts{xZv!xoBtpmG$ zL_xvqoRLYP^Yb5OTz5r*y1nv!#;wH_pAKd)5?al&)K}VKV~3aaimFBhH`y#0-mz; z3yIShz#pj05jz(BvYe>R>@LzMv~KJ;dVyvX?$*gI^{ z7Yz~sB5z++hE6a+h}%ASXQJrfHyGIgUWQHtlvoG>-+YX>NVAoDnk$1_(La1?eaba; zZEW-qUm41MOph}XR#L)_9WNseZ@@5Vt*PRdxV3_+d42He*rB1Jsj=U}0_j~}NGKIAd(Wok7hm6=G@*Cnvn&%u zv#WP$p;;qxw&k@f$+UCy$5f@sJom*oe|^VoXJ%A`M9Spj_{ixizKK1ml1Uyx!DxSR zbtIp0@;IKV{v_|n))9SP&$^)=r=lLqmIMulT8+roQoC_JKV(^n_ZsgEWfrc+t1f0Y zgsL(P`UVF6fO%$rI+&s1<`acSK)QnoI)FT&Gn;#RPZy^v%oF&X(A!jZMk2V_+iqvi zNtWMgO(94bu(Hn%p1PeXk5)aOZb#&dP!gLBgxK&X20N`d=^Uin+^;)G3Q9TeI&;qd z>G#dnh|N2>HI}ln@hA@w@gN>E@0-}~3kI3gu7mll+aL?7g|Qv?gL`~gjQ^OJhM^CA z64RKrFj4H%?k*m2e}2J=pz0r#E|&^a~A!6|fOqmS5nff!jCTo%z|* z8ZEiM?&R4X(G_Q6o<3wyvo&@PQ3$x*?4aq<=ZyiY<^!=@UYE6S@j$BMtpu1m9;YizCaKbiG(ci3-jL+E^~j)qJz%*?yV zpt7J3_sg4{Q`02=+N8_r%$kRF2pSt2uBLK-ErlPBY{UoOShHyB6!lLQJzKr|0NA46!~!!uTsNq9O19CG*?3%B0MZTwTm43Xfoin@0GQ!u|8S4 zfb>X-0SDq<mew^UU1g2;+Jw9*AIPfA@)dWPi-bY^8}saWyy3 zdxoX#yUEw;JGXrpI&1HfYKE*BfN{b?_SxLrY_8ms7TI=BKIpA!tgEXFYXieiU(-d+ zw4P02%zu9G6F*jlG}iEgcgUc){Zt$V~Yg%!Kvi;+d4%LN0jZ& zwxq{0cJdSEJdWW_bBH`TmAT%1-Hd zVdgM=k}iCIzs%@QLRFLz>Dk7f;3+zEQvUY^=0C!b@HzdadB(>5S#5oGUIoEr;2Fil zX;VI(v=ck2cMEd9ATS;vNjF+TI5-cEc!DPdFaf_;1gBj*E;pEwXMZsP8!u)639tuK zkoTbtAIl1lcs=WqBg^D+@WYtjGiE~y)3vgVX*37FC1qk+m`)wGn8e$YkEUB@bB~^m zB#aBCF|$|DR+9Q1e@7ZmUu_@It#kJc7m)iP2_f?z~3OAYVX53?5ZO z4?USjHp27A&Vkkjbp8n8GqbeudeEvs$u)P4Stk-HUuSsS6R`;^RuHj%6cXS@1~d1> zDU-)ql>pVvkoQ{*SkKpVczBM@2;_^}SAV?rs!BAk-0Zk{-oTWWYVhfvqz`SDVq`ct zIx^)A&(cemk&oN}YQwU;!Of4^|O_d>v*KgpsgkT^wUxxt?J{bcB^QXd+?(Zum2*r0*eOVgxKI^eV zUg>#psbzeT$DX+WP-nOU5c!jlk#CXb?at`L#EN4bFX%oF9w&BAZf1|0_f()d5fL40 zaqOc*PTQMNJu^W#&T?UN)z9lj40JsV`_lcoq16+_5_{VUHwQoMvnD+sL>Ti4D9bv22|iW8F}gj`A<)JmV83r)LzL54TWv(OiAXkDDt zgYCefewC87tFI9trM-%KhK|a{HYfUN?4`lE(KC*OjF%BywX{WGquH_F@{dC>cXrf{ zSYfkbr~^JG9=p%bpf5;X@LsZ8p~+zLhIEqXv(6fZqr?6le8$Qbp2n2GuN@y- zGK)>Ly7`KRN7+gj(TK3#Ejd;qe!559?D3S{e`Z3@v`*1nR(?Xsp;mip z$2o69{>|<{Pm4sK@oA)opL%&XN&qy@UP92YFwU?pe`D5ZW(~7LhDab{tr-624n5rHbq`o z?0ozE)jXl3F`Wqyu4<;bT}79wZi}Gb8WPqaZ`HXHnN37OGEHL=!N^L7u_^=gj}Q2( z-_I$SPz|=!qfzkj=>9V!dFoB)unLoktB&&P1bvjHKcDGNOX+V1l7*W#&LlYdp`fPM z#9BDMh5^e3GYK8_J7z%n@C<)r_X>XFm^BDx6z4D;DjH;~-WNcFR6s;EJY8#4r%m%V zxPO378uzsx6?Tdhr@&JHH>^CUhxivRW#@O2J?~sVU)HJ<0*uMNm#ux9;9JX`~Pn+rD%ND zv7+m6$?lp(F{oXMp`eyBz!^Duu&PmlK*w;%ap^p=?*|xN82<7MNDJewJ+EirVwtE0 z&Y2rdu)vpMsxS4+mx}d@VVBC)61B)Iib!Fnce9rP+=1^gm|V403Oe#;Kg zx$x0RDJ*0`M=%P}ruWW-bp{`y(uB?W?}3M~xlfmvrkstVj<5X)J31KC&^ zTrB3;QS6|*Z?v|nsag&laH*z}JNk5aXWiHZs}hH~|X_no)s#;97@L2@q1&7Jc8A7^hJ6;;@^jjJe1gLF%XQUW5K z0!nwcbayj^MVEkdNe(^q&?qgb^bj+2cf$bl9q@VH@BP;L{q;LbX31i$Gw0l~@4c^U z?`ucOS0*?)_QQ8d1q~rP_9v|Rr23fZ8DblI#-9F;KQ|3XFhg`Bdu#?84Wv#p<1keC zSW^^SSNeznKkq)Eo&;$3E_yog6dtL93NfnJ&~DtP6n8e6PSCz;rbvQl_ljN8`RK#?{w@B)by?hV*+7Xmv_SdJ<36(Ho$Ty#zXZ(5 zm8AhB*_hj6CI95Bv;EOeMBXem_Mq<*$CecrYkiqk=N(yp+pL#x$3`dMa#PiP-jiL= z_W#U|mH&O93xq1CxyDyr#+`tR5?Z_uG(a`?Ku7Ox{au)wf@i3V>Udax{+=#5v^jSIi>uuzDZr5( z1d}-+0$BsCBQXVzE5*n?|2@#@(Xg2Dx(m_3Z4?C*!=_|qf&V{HCRMFOc&?kfJ5hfX z898}&Lj(Ct-No_?v4%@D9SoBASAL>iH}^)Ao+?v#x4OyC;F~i6YSAc0uO%T1)fXZ zA|yC-C?G1+L-J@!nLobX4-s1?%sPKq=fHtiPc&Sq*LOY3oyDTFJxv~cJNqP7Mt}9PsK~_^#6fK9J;NmA z{YKGEx$bZfir6r^63MGy4nExSI9TkWCW{KSe=n=?!?ElC7jm`3hcq<0DybFX6FyIL zu&1!HG)+Cwq0;sdxUoPDJ1?A+;WIQg3%e&&)^OMiS-?GNjFta4a%FP8u#p;LGJooO zWSo#vl3$EV$*Fab0i{RGhW6GKm6xvqqcgqle@o4%hZXk$@MY|Yy0e}yCPBL3VeRo? zYxC4{Fc`MvE-|L^vU$hB4~q^YHr6uL=fx3x1R#1sr~V%|H4s3P1=0Bcq1xR-*;ngDvQaS1;mi=o+ zOF*DIXoRU+jn=Szka8D;*Fdw_J1aaD-cT5N8lB3qB97LEIqbqp_BF!a0*jq+m^SuW zoKmIqe*;%wpUdCzRE00cHn3sA%-fML*l+zUh@gJ?p4(A))3lL4$ei7y#|U>#1|L5T0rTDA7i z@^8`Yh4JSKr_Rr#Y1;lA1{DHjm5;D?T)#A2_rj1hWF;zRGXdbCErr#!d`?Ze&0Xfi zS`PZOH36?(gY2GXcaIHxs2!RvEp;ZcD0saV&tN&&9|M|al5!Xgd^H2`QD8#%d_z;4 z_BH}=mBPy~c>uNt2D|tZ0M7S|PM>JOGc3mkwyvZ>5Y5NX(7cw5)wFZJR`x)Se|PWd z-`-OWJUQ8!GW+g(VpF~?K7gU>)&KrfWDZYZbUJj zPw*7vz1f=?GP^lE7uST?XvI*TB#3@LJ)O7%0iwzaW^n-Gd@$IHyb%36iA~@F;cp_eu(zv@Kqv|bX28qH`dwtD$;tdS39hcxM3Vz)i}#C zw&R%Jyw@@6@I(~c-E-1NM;{mR;Qww$kq;toi}lV$*?{4}I=J`?PO!@oL?mA)nCv?oDrXt)ZxB4>d)k4&++jaGc&UwikRL;faU>U zgIl?=VkjjwwS|jItPWe9JOd%D83^!!ZeswwSprwu(mTa0vtfR>WjJ}eMuoa;cG8;8 z7QRb-Blhs{u+TdfO!!8LBVIj&D!z0#1NJJn$=b!yT2fGPS|y@GeahhOQ7R8y25xSs z$znrgYyeIZ0A9(0fAs)Wh7WM1&CTEeNC!Y~(8h3q78@{IfF=px19|zF)2B@WdHw6_ zF9CfLAIM~5V#|9wJ-NSnTY9%HlnAMF(xyfbUh4JbjqR^ zjAB5ctX6Y?iODBG<+;obrVfb1yjNBp4xh9$>^I8gVb8ZN1DX~CXGL1N?du)0`nuiS zT?H&e)Yn4Wxh9VWx3&}(K#ARE%VDl$9^g8UUfmT z-Adf~RLsYbPh?{#&pgtYs0KXRoe^p3dNbGzaxEw7F1mC_+Sg%fF4*Ypw)Vh?fF8*9 z9NO8B|HqU8?~nta2(}~J&acvnm7&_6wN8vrb$Q!ZRlP68Tld{<{n9h#lh#|@WfzKo z1d_vLqaT>~FnR0_oynb=atn^X|Gqchy5(+4q{5Tb6{le^S;nWoHF5;2zWirGq8<-_ z{%G4>nl5@*>51d?ReU02?b=R8az(dy%=2K+2PPVrV<{<2y1P>) z4i?WXB;{aZqw6UIqk)04AF%EQ0qD9QXmVE@Rt6$Y2hJAUM};%L!mIHgLl7aLeA9>h z%S|XG#BF5>6=!^-L*4IW$&DJCY}iNMzxmsCW0&r_clGTo{<^;0fi=hijjVq5RUPC# z)6n%zNn|4Rio4tM_ok_TD<5j&nDmX~`)Tj=c(kM|vRJVDx6N%CV7|4R?v~T#=l)PX zTVGRnXB|D?X={_N4QCC1EmYFieKD`T1>b>A7!_WyD4$gW+(V4sG4PnhA$sS1?{%@S z|C0KgMnKQ4ApS{#SM_43!R>duf&0b{r{|Cl9gu?b{$5$2p#=|xjmZ)!|;V^mCqmkm~P%M z9(f8ZtTIU10=f$Ki>srpcAW?R=_rZ2O`6LGvZr{JG}i84Xs1rmALNUTU_Z)nCpT)#`Nt- zu6cQZguPqPz3r@@ByqhK?EkD85%P{H1f8r|OmakB)_<8(5kN|37pAGxrk%qpo6H7a z_bG5`vzfReeZ10r7t7wR9psO!qT$ zVb>$x``QIp8+<5QC(2OKc->l{dx=Ci`|NwSkQs5*o{T4-fl~}?o+QEsVsKtNTcr#1 zOIK6|bv$M{&{0p;-dk|MuJm?F4iiW_yzHP7B5IFN^t+_#U@!x~$@s&EHo|^izi86v zG-iRb!-GH!3PVkWg5Fg(8AJa?{!nak{My$waAw-tPn(&)*<9P<<%q5Qe)~*=P>gXi9 z(VE!x5-J!$0ZI(Kf*370i7qUblN>Ao!g(5=?LI^*dmBqBXqRjJO6ZFuwTSA#1>4AqLtlp>JWP`66nCKds{ zd?p?J?g`W0h#2QvU=Hj19tUTAkYvDFxL1B*Qf@>;PZ0iRf`qQ#+V$l0;cxn6^|CE` zWM4+eGF7}f7TKqJqE8jzjS7gor0!e?Du-jvfNQ~yBQ4*-=(Jf1B?3XRY&c)X{Pl0hFuIIU3`n7{ev} z$l^X|rRUXgI`O%@oo^W=-^bagsqEn>A=lH)dn-md%|N$8{pyFQ(SJSbNkHc;*Jq1U zTAwdAkh6_GcukFAy`NlHgB_i%rrYb{2cn}Y*CF{Ay);)JJmc_1JIy7E&!=a z#G71yO}BTZxL9OYAn@JvxZt;Udv~3-j}oyT925Ec)(YfvKv^|3$qY|(N1K?l_ zC5q!6pT@NNmUW#3z39A%82kQc-PQEU)k>P=!jA-8lfM$v$*D=Z??02IU3L7yTcq026<^!0#g zm)j3faO%yyAV=!_?Gj1L$x9B-rgGN&JL{SJzU^%v*_zToPD5FcF9)OA89A?23iOu< zPkXNfacunH*yTqR^50WP?5J*j=laA7q~KCK#^#pDfI?(^sck`b@_aXD%$)a6h^>h3 zm%;6M3pgb@Ysxd5ht~EEOx6Q#XSx*Dglk$<_*TwE#3KEy@&vd1kjHKkrLf%NA)kGv?EjK_-@yHNuRVzb@Zwxph2 z4|30TxuMpCbuYC1lxz$mZoPKqjrDbJYt-n!e3Vw)qjVKFFu!J@ogq_|p{JdL!>S9w z#d>~V?6MKNE=RsAYH=(H+9T0f%{u52%UqZkcyxnwA{$7HH!wWs5(z|M;LbJt*6Gis zDmJp^v6;a;jaGn)7_+ncKYw1A_3U}MC=A>zFK0khYm75FSqy6I`=@1K7jx;TAw zjhiacXq+A&GD6CdtP<*|L%q*N${u@p1NaQQDa#tbL#GP<@$z`tiMQk4{L^sXVmTD5q^y4oG=hll)b@ z&8B(N7qC)OO%mI#{;|=91nsZ3&sIDt9dQ#voB#CL0dp$qm(xLRW?Mg^sI=R|DSV?o z$`GBcr6}cwLA-*zyTGzyJN39Vu8vTOS$xhB>0~Hm*NY)@-!Awdj32)FEWrNhhSvb? z!$Q2LlleTC^Pp}12p3AH-u^FLHdgRLWdzBrBi?%!CE<(tD4%v z18MsNzO=JX(ds~_fnaG563{r63^K<|9??$%CwzbY5e;dp_;XF-09?fr*M6$(o8z~A z!ZgC~$sa32-3m>89MY-vTU)EO-pFTp{H8+e9Eh_h(OZ}`-H&5@N)p`jrJuL35M!x@ z_gAMmd3+K6ARV5k?MhF;{#%OQR)8au|1N6A_^m}nu*@i9izL&Tt+LAA$^1!Up}pgp zhM7{Am8~BPKBk)$`b#O&4S7jjDhc)}ZN)abc|{w*pLlYa<=?iASM%)xR_9<3neeC_ zO_RU1e82_DvPli1X>WbQ$@%T<5O73yxA-{t=snWJKqn5F$db0c>KIxDCnh^ui_JBT zLsqfPl|9sm@iKS0_IV)c{CTuU;78b5+b~`^V_}7Zz4q5?j?6{W`sJ|H@HIQlQQFnM za?ZeE&Vw z`hwgTTg8r1hQg?sM&^}*i<2KsTGesdt|Nz0fv$l<+_A*FdXl}9ChVxk*5#)r97^2r z#d&~AT?LHoVcAwKJH+TzZPf4MU%Wk2IG$T`UFvk7&@4FxoqJv;rdJ$n>H%B@-*_lQ zGtqzQ=Y{ysk>TAB>^!?^*oYKH=N}I&cVAN-sf_9c_1Dp2U^W~lNY64faU8w{YxpA@9?77p~h0K zU(U(VkrdoM_GZu`W_)C%%HH2{55}w?F9eOAbyMj(7ED+z{gN;t^~wsarS~FratADs za4iG+;i%Sk#SCfnh;F+oi82?ApwJY)Bt<I}F1Wrw+E#op8 z=l&$Gs@TNvU?#?_1sz2(Yf7e}r_-u*`O&W(#(K0dYR8oiL0J201Z*9R+`Z2J-@d@S z4uS<{6X#FM(vBnb<`32V_n*|_L{U9CcG+ry{!)L-uMrFq^(W2EiAK{j!#-~9_=dXo zVkS)>pmTL%#|XXwq{9YCD3(2BeXzbkSHjf?sIoa{l}Jh|Xwl~HT2mIyK`<8@(3f3ClejS7$1(FUu- zo@hURoN7nDrQ8Om5&R=p;t?^U4PQxo^vam{akQ2yxy}k%D+Mm^Y%c1uY1YlBsJJX= zAQ^G4Q&S#c1fVn7A5M{xN4;5s>Kg+XEq%)Uz%%;9DRN$mi;yr?&j4 zN`}c{mgcO=^P8vr$1@~}wXK*^8Eeqa>AaDaxmmnIp0kf|{UHfrDld*%$5Sj#gFa~C zWZ9o4@2RXklvH_DF2cNBZ-q-Pt$$^)!YR3-U*X_8@#gYg2H4E`S-D1ibM(W7RMRS{$rKthU;%K!0|P+#NGh4j#? zSx=*RfXPK!Sae)sIK6(vx$f-M+idAV^d?!koSULTCRV?Y6nv z7q$#(&ccV$l6vCZKxTtIFD>*YXL?tDbxi1Ytm=<8olND6+xZGL$h4W42kxnM?EGpm zgn;!X$y3n)dZFDJt}tAN@4k#)suVP1d*9Bn%kI=nz-dt$K;}9V3b!{$6Os#LfmCN8 z7dYh>S6&73FW5@(y)yN0E3SStR#&UL8PKQyaW7*To!xW-^2C8GOi(KPJ0hU2U)dr7 z3sNc8(Qo?WA1WdjJ5d5SKrVeaI&P9c8t&tv76&UUFiWo7H+3AS+DQ?xf-EQG8J}k7 z=1OK?GPwiE9;;M|PSOj)kaPi{iHmRMj;dWy!H~~wK~I-Ll-WCTa)v)Y|4vB6NZdg# zQs&4N^sI*Q5?DgX1^j#%M-xaUq7{tZrrs(N9Zb}xD|+T{riGmxPCh zhZSCslOqAZl0;U9+8P?A-jo1JCtp*LPgG`g>m15#^x|k`i1R?@c!aDy+BGx_NFdvr z>M!PX@oEp}(q}J>9EPeSZEFwMjkYk9Ja(nbIk=ganCw3Sxb;pJUzi2{(k=eJ1SM0L3r z&`#D3*zN#A2od=RsX{2S|U zTvg)3GW%+iBLJu6PKd%R#BwT|*BCFLR|`-44?R-_y@TnQm9{X{H52s6U<`fL5HJU@KEnSo?*Mg>2G%09(UsL?`#n%9 zaL=^zzz{SLHN9z2f>~RkS}JQu1H}=f zK%Zfa(!O1o?UQAVd4Z~qu?!+0@dF-ESJ*K+>j_Cq+1hR}+(3I$b)AlfzC7duY&3w4 z(eP%WM+SrcpaDkZ-vz@&1#K1Qdzq6o`ZV6QgcK=uw zu1)|O*7$UraBz32J^O2|L0r`ItSNunQ!`7@vr+B!Q=8{cZThc-c{G~=0%G#Ovqshv zP?K11sEE=k=J(K3FPYYsIu+8qqki}heuP=W(Em%<=$6rIju+}fN5>YSPcH3GKza<-7iK5z&pl0h-0wZZ*9VBHmtc zWx1eI8ee|DYzJ#1-Im&d+ru3EEX>j|;oEM@HCvkRnnHW~gvEfoZ%h&N+a(e!0yJcB z3!?c9-0ypZ^&2^WrPW%Q1kh~2yiQ-1(+OF_!#;3mzo8gRXRsO`I?*^Qo2cSTvpIG0 ziJW2giuN)U@dU`%2OB3tMTNxmp}ks#|7(%pITx$C>8BP`cvv(66jvFbM!B~HF|SQ* zfrVH4J9&z)X(;SHtUZ_`)64*H`i%dsUFNT`u>`fwse#r7G)e#Ry`DaFM<=LQ)B_0Kzu_XQdaB`xE&Vat20NhY zFO74UJLBD69u4du;0Pkl1jgkP%U#8VIf9&;x~r{7kBh9lS z<%3w`3u57w6+G&t{e_Mu0sGt8ZBE~3X}ZhXDc5-92$iv8wM0#@vSaD`Z}yfa+uPUx zM1y0a#opLhrzf71JSI<@?GmyAz!!jUwMsy>-w3FVn5o4alM+@M>1+5S_cZ2(>>$no zTz`^Gd3)ktI)1Olcc#_V^@}n@J7TmWKK4mWaECAj?va!m_sU+I@^Bl{i*a@JH5ACL zCSc|TI8WW$TN?iA;s{hsF}}U`f(&=`0BFqxbPaVsDe8DLIIskG5v}_{ZIv6>N@kS@ zJ5M-=sA>pSjviQy2Db`fbT}8F&CiK_}~Z z@K?@S4||T4R+&ogtc(yt)AK!{wgXD{Pz&|NF)`dgYNZRXAuYl{x zq&aE8GUrWwmykCGU%nZcs9SkP{L=f|cf$P!R*k`A9l8lVZyKtQRBha-TP+m|Dyc`8oLRb8M z^km{3Qtq8_gH9PVC_Yl>?#0R+iVvOtmU^r8b7i3Rt3 z%e=BE8GTAiV??7qQn1bGR5UMWxhCV$lOUGl)YQ58YbbogyNRf=aZ&(`Y>9I69B1B! zi`LN7BY#VVt<>60o?jzS{^f>Ei4EI8zlbHE>9$XY`n~?DdXFsAj(Dg9gfmy!{)bUE-FVu0{6*}rhU#uft z(*p1ZLqpl1rKw|8GJ`{=i26_0gHCDyuSsxz3{KhDG`;B~CRtm37OV2;miOK!Z(#R7 zQ+saP`oq12xCqv^^z-M>x)=xUL}qg zGaOF8*RHOFA+47zw?BZVvvrdx<=ESa=n%&na+K@tGtK|etz0X@wzwl*0EKKP8t$|Ppw8yyd?Utt# zX?{+H=@i47M%QAfZx>(`395q>^*SbDxcUPnWhU9}dSG_I3(Bs;v9LIwo;hfkJ2!mA zlI8cbe~m#@Fq}uE?2d2;yhJgn9wQ9Z43;rJ-jQjjjzs>p+>}aToJyhT+}SuBTr#5! zRFhpRQBUsybgfm{H1}lDd&PXUEkS@7XBF#P8ZJ23-Mi%sUCe21lVI zny;y{{13Qrd4M#R1D7G(EAp0H3o4ty&j)9YoVL%&nlJCiTrYxCP(QM`SbzOFIV%jP zihAGCUA4&8$=*j9?Y4Un^*O-^k$Wg-@h28RB3`;d&;pe;sm70SIp3 zKlw&Q+oQzvZ$p}M^pfUShH!S-mU*_s*6|Ldiy&3LrOvfNlg%GTXMb~=L#C3*BjMZE zyjXLuc!j>fIfx7IUhZsXu^{)pUY2)ogM1QsD(&)N8jawzzD{P=^g!gCN$DQmIXG~I z`&QC%ftv%Re)GXRHHiOVjA-}9CmKgM?c#Kk$+Xzbo0z%Hh3-znON9Kv*l$bW74XHj z7}BZ8cWLrskpsno+KAF0C=|bQ>kgfZWlO|Pn3?YR`jXw`8!y7OTifRl*M`1gC?66; z0HqKaBcSDZS4SNy^81Y<;QrOKxwD+&d(^UMNWY{~+KZi@mdmTHeK~U`NP~O5Xct_# zg`?{wDK9Ud9a1q6V7rvYAe=00F* zN%HmPKERHlIbE4;|Iu8PdN>-Gh44KA0im(HG2#lxNN~GbbEcaxM0B|?jrNb3nB2?) zL%Qgw{9am%pZA`u67>B3m++3^1HPNdz<%w33vyG`#pDGF9+eGkxbZ_uV6j1I)JdBbmhr7I8?9oUIF$%()FLis7@2qv z*rn4R+F=8&$ouM^>ww!4W^+0^>Q=OVDlj+>cxM>QkI~;Jr^@~Ldm#MlL;X(%dDa!) z*4wfH%ok1{^^A;$09nOO;795izRnrgd!pI!N7Rcfn!GJQb)+>ntr)={-4?&={#3{4@7PvO>3JQ!jC~GMijT(We|OJ5HUSzK$YO zV-RqAMS=D)id1oW{Dam0@VY+Vubv5Gw(8&i%>{@;zd3&v|oWz0kvobe~hS-O1e)in4X6P)bXuDyK-;s^EjiZC~*VK3!PveWb4+=X;tr zz6DvD-+cu%_5&n%96=KjW5s&ElE^3{L`%&zll82uYF@p%Mm<)$WO}TurmZM#!lcp_zFlFQyq3)wwy-j=xoj%&H)4(`zdc7LR&|kkU zyS{6L?9zmRi#vp)Q?r!# zmKNjN$HK-Q!08+?DN>r`Uqe7!{UHLJJdblG*4>R7!~jPCe#n*ZUPea7k+@a~+>|?k z1}Kp|p<~Ii1tgp_k2hl^v}{?>K{!fv`7vS%r5bA3r~E>&J2hosMh>6g;aMH8|1H#D zDG7Y0LsY95mGko9|UrgLUaWwkFDI)^0^hJ9h@FE;S&N+Aw_0$wJji zI$M>ki3YI{DuKAQx?++%r7TgAvo%1=nyB6oZ1+$@;Zbp0U=Kao*pFusJ~$0r5DW}h zLUqFLDjW|@(Exe*TLsoaif{w8TGyhAQT`-m;YTVk8|T>DH@F?fh2`Z=;3Vgwh{_Kr z{cCLwJcy5A-QC}2qYt4+IM~>w%LKY$F|X*aQ|&Wdo6T&+j0{*>vYQlqOwRM-v%kpNyCb_~`U> z6{uLeIv!OvXbWi3h$+*pW}=8f=ZL`a00!bKK9sfJvvqa8fCZiR(rxVzTC_UZ4iuu4Y8PLe{2aodc8la>R2ZAc8;etq8$yRnyN{C`4%2nfhiC^O-^ z4t`}pVCc~nfkfy`#(#P%=I9-so}%|UbO18DfCj7K3f}RL&7i`t%1Xx0Zao}TfA*US zMW_4+wZ*mjJlaaBlRwI~=anI1+5j-^)>K(wuL)p6%9Hh6dRA+*f!dyA{@l0yi$aUR zn9%+ICD|o0YkM&ngN=z<9LKI&7WAX5cCXBKp-2~4P`ks4zjQ4)wX;(yfkr?v*#}}5=176YgaeRay(pq!_zbV`g$*ygDCl( zpEbUZDjv9mUdZ06e`_W=08+H9Andyd`1cViX9>t;;<^``%8y;yW$V@LDayz;xU{iQ zWv1%ZDV1;YwkFzTlhmFTtz4I2`kOQAktRtvP4YNK;y#&cZdgRud~jzy#+iu!Bf5CE zx}H1}lH$?M*>o3tfQH8EBjuy3l}$3ydgl2=`IE3o3IyWxJepD8)RavyqbptOZ>@5K zsgHurNJx<8zD#(*=*Hn!FdZG;-JOXU{u#g9c?3p+UfbH*+A*1sh)82aLc@)}*u%5+ zpeg;{i6@5gV6h%0B2FVquRKYQIC=6dyMm@L(?CMcH|osPk~TmHQiJ;c(Lkd+tgxS> z1n#u4konw=xVXWgL_oMC{H?AF+hj(Wed1dmAeln5$loboLhnMW)=c7dnb(WRd;|vb zf5!0Tv%pZj1nZq`*FYs;=-4~dduO_#Rclj+7g!~tWyQxN?CD1uOxl$bEuTJpY6y&c zwg89{YdHMBPlEYp>qOI2M5Dig;|=3-9X9YT5|qaMXQxw@@d>Yk4;K^FgY?EFP5_s7 zc1a5|DStPi=?)fnKln{dOcflq#t>Ul?sBnbcFFr2r$&)AI zszfmJc*VM>PWSKMXJlg1I+aewmzX74Mkc1)-Az)s8LW@ActS73OOA4^&wk0yLG0WJd-Cj`h z)(@>9ff|D|;KaC_Z)gh3T)Xza4R&i3o~ZJypIi!OYgp7A0$Htt*B44yc`S`l5R0Ey zWr8CHLB36Znba&2M;xMhGBnuPzv7R-OMr+!DhkJ!_#Q2nU%X8R97+z-z?((?=gkaL zfc`9WSxVrNKY#kD*tGJ0ls0QKXz5Znq{YT={A?fEE6DYy3B&)MtaWOO-C_nzinf9sYESyK5#m- zZ2Pdv-SDCjiCG#~Gz~LL!HtcH zIyQv_{-4dH#R_DvM`RQg*(-pgY*V(QN1O~PHa2+$1+j@HKQ&TFmlVhurHmMO2X%sb zx(O~}L`FByu{#u_JHFS4;L+;;+|3&aDlF)%wnrX`m0N!A@k^Ewsfc7AM*WnPbb*M( zE{P49Dxhv61FR@jEif?qU2Yt^0sv|<$^f}!k$H7Vw6StAUA+JA4R?=VGM0@Ad#*O* zdcCHuGuh_V&J^Q{GHR|{_1S4xE{S&l#Q+F@=aDBAX@QM z0Snlkm#%1I8BTRQJw4!`t9;hXJ=h5XQdn~IGgio@-Cd&(M;k4nxfaym18hX(e%D+J zI?t@_2&eNK?nL_)Ke%R88yK>hR`OVn;y#`FUD~zOB2d zGeTuzyV+A;>*D)OJzxk`)re0oN{c)GD4$vdCPjokTRf*IsI&Xo!hw)xZR!*A>TP&` zyU}x&kA3}vpocB-lVUt2p}egY7#GKvZkn&9c%Zw3M?w)S@NmZ4eu0Zargk^K{tgmK zi&uJd{O%@MqsSa9wUL~z`~bhw=~|zp=|reLGIzE;(SKOd{W|xWT=ZNt+H*$@*5b$t z{=PcP?TCrzanMfl6Td&UwqLh()wq0eyYHIt1?NB;I&bhxTt|3FQOCV$5R6y=*nNc> z{PjMI_g?Zk^24TAuc1c?Q@Q}vw4pocAX$0-TUs(5XolvI} zC0?9C8*PjjUuNq`MpXyz&$mm#6S=&*G}p;jb?sdN)jE|BF$j7i5VpDI{cPQeds_9) z%aeEEf*h>~%!_}zMakAW6+=FJl2<4AWl3y+ZpuZtI>dbcXj|-W^pj_<9W1<513y-# zl2QcwXv?1dD&S~s59p)F+?aXz_}*H%@XfS_=P~j-qWi=mE|3D0)H+Dl1}gHfeqMqL z8g1Amp9l&vI~&4EKXx1@blZD-e=H1qVfGhO3+3~)>6P+fU-j8MSoMC2!ORhZe49}} zJXz1Z#YvcuW?g*8&*{^~;r*Mit*(fGx|iXxc7cJNJ=)XU1}$G!+TM*?8A#(gL6`nE znAP{+f0nT%*8GbF+2d1oZ3EYJkNO2sem38y+X!`He5S135%rS>I$8&S4SDd3@*mo9Hi5T zMVO?b&i&`IwrBm*>!(G$-8V(DlE`B6Is5Xy&~7JV(hj)*TH!OqyH!h7s%2GQBpR+SNJ z{5;uKy%Gj}@0MhEYPQB6Zn?hg;_e*u{V4F@q#ZKl{3b$haC0F?YhePZYgsEWbd}z) zv+SNuiz$?;!L%4tW^&N}!P97bqyQyD6X=aUSfh0Q`1HeYuo)xvLC$-d@Ca5}1qE!N zFV-{Ox_MG}JUqMt<*aBh*y?#C&<$XhjhOVw^t?s~;fs6EgBZkKnM5I2OQ{z^GID<0 zE=Wsed94uF7RzV3nVAFr>~`Ykf^dUa*)|#s`zu>+PrShHbhsx~^<@j>fl=_CQ+Kb5 zl@zGsaGM$2bZ^urafEMdW$BG(vqSiDq9gSekwD;=F_&$#>@?|OBDDU{gqdr^h- zQZaMz7_@!iaitL;oQ5IC($ne_OjEnOWh0~8YwNg85U8OAYld*T&vUWAq5xBus)chNR6xYXR>5DV!E~< z8*JxWEbqIdw#y$0Uk!-W$9N||jT%VT6qOIoUw~vebz40Ne=qd#!y7R?>|GzU^?oV! z4S2AZW%sLtL*(6A-HFRo)%U@k(JI<_-^f9E&&A@B5Qo0!o~1&H_KBYxwe*9<_V3{d zbEZc}Kfc)c`Z&r1S7jY!OK;gDBz!pFX)D5?hEk;dYGwMc2=@4a+^SE2?}Eu^%`?uU z4rub9^LyL{*PTAnVvSx-pWZJi?-4MpubVBlN4M1%Q}(L6t#aqDxEN(za9h15{yspa zRF1VECpUz2R9L5TIy#?h#rT^+CBdbUUEi=rfA*J7`{vO20(+}6RE7Hw|N&g#m- z`b-@Ya-zY@{%k&%>T2kNW(%L0-My5Ux*motNxpv$0>M!dX3(4ke7NfX!uMUo>cnx_h zv#dy4e;y$^M?Ko#ya$3B9RdWBWz*x%1r7aN=EvHeVekplXRW5WVTRP6jmA%XlPEhUIRz5LS*l(78tj#O zWcW&eIEg3axLY`L9g(7h7R>o)j|j{V$C>|}K%RQm@bE-Vt3jm$D~Hgn-R`H?Y)SK_ zGp!&L>xZOO;HF^XAI@i?Kg!u%S!983;3hQH-N!lVNp#q|C6;F!{bUN-u+up&YbK?o zqMQ3QwtU}ykM@{dx;|>kVK=i6TCU$p7Ot(=(Qux6DBMxPF{d1(bTd{q7yYSYR0n#^ zxFJ3rMqR2MlV{ATnAxXRYo*?Z{^)N}z=I~Jb@JgVV`Dw3Dv4=hdmS;WbE@zc@SdY` zNnHy$Pt}X*^t92KtG=}t()-7RBG#KTA9*`yKFk*(U>QFcerWnrQG3*EPA4=q+v4vp z&op0sz|%XoE?SwSLgb=cnCgh^LZ-*^d|ucc=|9}LZsxx>@qJX2GrErvx##jN%PYM{ z=g_Ll{o)Bq%01gF#&WD^O?g;!M@GRVyA_g_P;9u>6Q7gJnKB|P%e|0e*FP5{A}+4f zP}Db$2FW9P%I%mH(VCf=sgTCY4jp-ex((iE1HRX&KWw|8+q8ikeBhSWFb_;Zy2zr( z2#W+OMY*4QQ2jzP^sLzUd9p25Kl<>X-ENqRv5;Yq3YQ4kqI|bxHLzQZvcMLbWwvRy z>?=-TY~#0arq#>00UP2+H@P;4NT!! zJ#(BbMfnJ=0+yo~7Sh=k`+9GY*wQWEAp=y}#@y!O%1Tg@7vX#MXa?rzXcb+9U|c=@ z66Iv+*uV=XmnJT~;f>PnH~YNW{KZ9@5N4`Yalke9SJl>?yiie%=KubP4~ zhn;WzIC2ikIW4o53JJiy@}I|6?YUX8o)?*=UGJ##x2g|t38Y`sy`SEN?)YoeRU zik5duKtj)##JXlo&6r-0j&*N~`}tEha=+OOx2(z09<-fgF(8c}5# z?BwJrWRbB3!VeYw?abocjAy1#Y`QV%bB?qYD6msr+MYytNZl98ny#NoLzQKFv=NX^ zI4()qvb?B+bey&t&8{S0U-@)@_lZ4m8h-9KAk5@BMxyFp{DUkvl>Z4k#icp)fLq)1 zC1$uOnVZclTlj@pRh?4-eXoVTsWo-*0MALhMk+Zmgu)p0U| zy)?!{LK$G+PS=~4t^rsxhb@i<&Sz?Fbb|LKKV7eaa96s$H9Yi2a))T@LNeEU$H*n> zX!GCciy1JVQw7l|4`n1bo1^cxi7Ks$#vGicnsuhIDrwrhvMts+Tm0$7b0Xm*sZU75ADk$$nkF52t+X|nrG57!!%b!7Cs#xaS}wgD?rc<=8= zf~=mn?{S&_xHTp6>}7&$tzCY5B|j$V@1mS4O><&fkD}cs%`I;@hJz)R-CWw5C^1ceJj&goHCH^=)wl|2DfwFX4r}0GPbCz0R0XVvLAO*$Xq%M` z3=D=mgE^!pST)COR6iwH=xZ2=>@ToPF5w73DP<#D&|7(2YPk@o?i+=$zXpm&oimd0 zEiv1aZccm#Gd+nrqS)4J5skh6LVrrt#o|17ESGlY+&7#_2dCYoVU=lvsGXd*F%##7 z0}DwjZr_?-F_jN)%(6z5WlPIeT7%Pk0yy-Cp!5~_+Pi{f;c;TyXz?q}%WW|i0xn(E ztzoQOVGU<|Oa^P1C;RTdo0Ox{UNADn+x8)a6VF_1VMzqMZPiPE-g??QueKTuy3OEO zwXr;U_j|d08tQX2Vm9DkWvKK-r!yEG+K3g~{*EwrN{qGVS1}3Tv+SP=TAukR(ytV|W(G4gI`@8ZGH}|RkL)KTvMHO}Jf+z?Q(hW)q zNOuh?NOyNLNHcUJ0@5Je-Q8Uxog>}dFf`I}5Bk2}{eAb&AM+1~Gw1BR_S$RhXRYU9 z5SW=mc8t75jK@peg>10nm6%E9<7vX~p6y^hytVN(k}Cgt(}djc6XSPwS8GSTeS?uNMH<`P^37tgXF|}`M?8B|{Y=G>uO{Qt6TQTB zTgMC19G@lwvkqn5<^-oa#$KPvvbg*boRA3Gn5z{xj6$1QmiqirVSmTP+1}}SIgN7q z2g3=-!yRQzOp3hx_>DDL-EG=taRgSX^&9q83Z!st3d%P?zdxNOk|Je3dXD4#IZ5YmFI4Y@~PkH-XUt$9)>Tadqy>p7VaEHCVMB8Qm ze@+|>Rg`h}QkUAMVXA%*=TEmwS(=xcO|koZNiPr)C7*0_p+iy~wdm74)3em1nhYrH4E4$objexs!coSp^^Q6k5PhhVL2y7rNIX3tW1^;e7i4gE zwpec|m@1zIS8FU>B5_1G=<=~T>Nc4>2XZv)_eX2M9fRZ7l1KWG{T*8^ZCH|np`Ew| z=;jKd$(MMGL3^@3e*XoZBQziHE^N4hS%bBhd5Nq0NNaO8IKz53hXW?bV8cnDpXUH8 z-D*-I=i{iX=Ucct+aGg!_9`BY*0Gz)t^Pd!YzBjO`ouF%?&#z2uO;f+W`YYvj5@)w zZ#Svn)9uJ`Ur^`kQmK`_=nR%(&sUWImvZWqm&BFvy*kP-P-1^MYgF zk(?8qtjk^9nFv>%oWr+MsD038`|@nm7oNjx%#TKxT zmTvW=prv2KVOBSdwhUt5Wt-{v-JuPUAnqfvUQ zy{jxcU&t~N%hhw0nl18~Hk+~{jhm0%#+nFNwSQw}beuRj7}_Xz&X%jOLww(V3Ho=8 zooQ_X?3kL56G^8iIY)jKcalI5J6ad5(j!?|9NTS&`M&E|B-7=`ebae$38czEO|*a`p{X@lPx9}}dz zU#Pi?2EXMDa?n!Kh7Ci(Yin}r1TAJP#PLfZVny&`YG`#u6wb=OJma~s3H$rs$xdyL z-6UX1bnrs&@U8<(aH7~qZ5^3l4}>Hd9KoNLUTJV-IWWeDcpgqzqzIDBi27v9Izv*L z{-+i|YB7)FyaE9Sm9F2IuOX|_?Q24xv@FHo6595sWhClbPKtTLyU?$ChH1r=k2E} zXe-BTB6RgM9JXP5vft{FD0~ zV}mZ2+A_>5KLG?p!D#Za8w?~109Ujdw8~iesO7*o)pM8s7bbMgXoig;{goR^_!23> zXvZt0T+0qK$LtHjzLJPFh|~M!SAIovIr3%|6Xf|kv~;8ia|J$7RO z04e1vO+K5L_Zf=+dwk{y)BrVR#>(b1Ovg1(mJXB)Y@f=0S=Lff|9+$B3537SWro>u zv0B7EBUVO#xRP&t6Ikn80vs3$3K#Fqww%ggkOfg?^of#fmD%hDtC;!67yQh8p{}v$ zM!JjvshcM2n(=O%ZEAlV$J19JF#u`WcQ$2YWF%XsYNj&WzegBPMwVwRW+@)mOx=QO zYAKed4#oQvxVMTo6&{CC7zlu0aUNg*>D%qQEFFu!{)@xCOEKBkKzDy^dAmba>bUU|-<5=}9vH9vCCGMEOGH1nC!e!#JM;p8<6-G||Y;&X)sZ0I2qa zJgV;gcPIS<5Tems)t~ zV~eT+DE%7H5~OKl(*%N4i%VgdPx#zN0G~_yFP@nXJ2t@p5i}vXdf8M-z+>f3xj>UyyCqfC3YZ&T2k2SM8NR0R0B)_rm#O-wVdRacOBxoz$Q{6jdjqrN5d73_OrO{r|hYl?OEsW1m0-P#$IC zRq`(N38FXRqM{PnQUHd7@P7*o*Gp^6U2S=n^r?>V)}U&dpjS(JnL4SfF<&0Nx?^Hvpv%ko{Ft6^X^g!uqu{n(afppBxwC=RFIIfaKycLgU4e zDl#FyR3^EXq(nrTy25}(Ly{|A5b)UQn?wi$mj0GWyWxW`BHG`ZLVD+$92o#{8&L%u zoX_xm_p@{0w$>)Sn12f)EFzAnw7jJc;6GB&E>nb>Tbyc zV?y`;jES`^6{3+-0O)`f|%N;LYkYR-*A&Ln9$AY zeB=n(ZuLkxZB>o_E&v*4<70)sP*yT0iJYbg3Vvm}K8Ub;e-%$69m7xpSkADBxi%G` zoW;=aSv1-OTS89N4mEPR48q73wbMYwM&HbkOPAUpWy*`|aM(vNFw;NJb^)T{Tp9k!jqufdLkZr4RweewkO}}2mn`}NS-ju1_=!X z@A{rxj*UX@BK+dbKsam8o61oo2<(ybnf`S z+YgMr(3$@bGaY^aYP*c?Z~nvzqW+tJB$EWSu^-CMKI{i;QmPiwzM?;;cX>vi6D-;3i)Wx0R=7+pITDSj>^MBeprXog3BZ3>5sxXHNPw;4PKFwyM!4ly*r` z80G5s8G&eZ+M4UJD~WlFh^N{R^#KIm@^EQVmI4~+=rj#1Lt*|59GfYv&GMEbfIy%Z z_2A3XgTyLPO&X?B&!j03=*q=iX}*(q`GPXBQowHzSJ%sQ<;Ht3acn%ottqeOi(-7! z@FCdkm=!Ao^&U0lZuJF?ti}-88F`H{_3OGnv~_7=>tIS2r478cyYqKCq8B~TvhxUN zVB^pJY$RSMy2_MqVhAVO4{Q0Q22?n=Yhyg;f9wUScV0H#l4pBQf1gl}JWe zE_w)%dsTlkss6t1z?bqo*FnxkT;dI#-mM5VL!uu}XP7s!qJ(sR)^Cf{Jcp<#c1CNp z2C}-;$w98ykw++nlH*o;l^AV-zE?XXXL`o9U0~yB= zZz#76!NF(81?-2ij0)Atg7gpv_bG{2#GVB70#GwpAmK zLsHpk>&fiHF0gwW^^?i@(2J$ctP`We)?Lkx=^W!9F+aX5NNlVv>0Q|^YOI~ng6VPT z8K90v z5z)-TjM%dXx}@=2xyXzIsNeL~$y9WztqS}*0!1wGmPEVtp<1LIDEAd6Ps^T1(UJ7fT$u+nCSPf zYK=RSYCj{6LmRgn(7im*@dSz(URG0J4=sD$hV_zrFYH|agwwG*$T9o#S8JtcT{p7E zv%wKACzX|<-kYx;W=^>}_i`&tMA=&$S~XlI;EXHW+k|v=AMTEp9auA6z)yPf1H7;I)YSo6kEp~jqniC!Qb>tth@v66*PI^Ge zp{5=2_AV9K*c|cT7#S<#g~cr zA5!^zJY3!K5VR1)fp{}Lhwl>QnXKc|sP8|p%G zm+wVS(Ol|WkEUUF9W!z$Chg6PWp8M9CG}|WG z)O9*|N}bx6A{iqN@UWO|EwiDWt+dAaKo42#V2P^Q`}nUx#8@8$9@+UT1tPbN6FMxv$| zQ@3jcfcd}uP_FXJ_U1PWU3ylM#YSwS__Ufos?qMcl>!)omz+{$XPtvKs0{Wu>q$(A zXMuX8n$q{a6*A1@ZL>P4+776`bise1936v$gNA3@sjZ*mqlkk7V=gppuV%-3C*MBnaf7>YYMcl2INOK z?yH-RG?}{_X#uTCtqJyN)hTi939}X)M|zUfuER>tudYsJA}~KczvMmJ;!aXqN)e9` z)peOZ>TBqB53Gw4B9>z`su&3YGh1#n8G^pI9=p5X;>+lV&O+;%(KCYLk;rN-6b1)h zF*6JGJZ90lRd;*fUkk#qbXOb==I^ZThc&Aq@Coq5>&a4O>5HwSdlnKmMz-eX4vRR} zI2~wCmFZ}$T>jUSM*RAutkGWW^7+N@t&3_l?XF^ z3%Z=#eN0ZNbTf!UU7Ph0S(Ky#*$GojYLz#yrHsq4>6 z*URdAfQZ_t(Gu7_^jQK+jyA@$+&y(%`f9GuKmp+>|Osz5+Y6jK|+wUyRVJ zZe4I_#yKAn1cNJ&NOJq5ZBC|?N_lQOvKJor_{y$oXyoHNVy%!~O0nB*_Q{58Hx2l= zUqEQa`*N|Hk)>?&we}HbwnEp_<-ljcpTx+#O1PP5Ray2!4z#)Vc$)-Ml%Zv)u(gmz zr8431H;6YDLA*`z*a|c(gc7Z8q0VW^0~bWXu3NKdHM?WU7qxKBaH7&4X%JFRI|dBw z@G?q{TKlDKMI6NlCZk`T%vhF9$r|Y+1_g^Y((N`RAsBfZrLr6%wsvCgtr_o+`*|(s zuc5-iP3*^MZ(c5sEF+Z}{1VylVYCdZG5yevJ|Q2PBT5}D?KW-PMIb zJe(qXNq>&BB2zxE*fQn*wNhKtPaV0o4vWscXhQGxtxr%PQ{@Ts#egzL_~tlN(#z+m zp0FU^V{G?DME3Pg|CZm}v7F_yYiB>YU=@Ol!37*fBP1Jw&`kri=s3@&vES&hBy__C zd+c2mq3s3Tm)$X<%2#f2R(&~-Qq`_4lhj@*T;a}-;dB5>$7&!ROfe}wVnu^Wr;tM+ z{Z3M#8AR4QzD(@8Q|vv{qW?UtpKyX$Ao8t@wtV9It>mmWB;&|BZ$i2DW6JMHLi&Hy z%Exp|oP zlJeD51<*bn;Xt(LW!_QmJL4%Yr1U*S+Z@sW!)!}8B~Y6N;qPA#s(`bXH!tI1baest zj3k%Tb7i!{G|iNOBsBBp6QJj|Woeicm+te+JEq3A!4~TN zhgSg{V@=Gfmy`3nAch|>sj)waEwim}+HMH1{4UyEkoE;!5#m@)eE#Dby_YdK&irQFMNktAct7x0=56^_pz7 zV=$W36y_mooFn-N_=^>SCrQNk*>1Ud;~8Po3*+Ts``_BxqO>MBgIDEzK(z!+G5%W%&@;H2EWGB6CtsGxeWBIqlk~kw8&Yqn_rocqTS6qgI=i}nP`8o8S;i^v0`?XriJF%JH`z0SNQ|3d*WEdfJa*oduYOC#@!I{*dovz| z{5)bwm`OO5Z?qn%c@exo;rLHv!*B>)Pq;zq&3fb?>{|@$^&3@6%I)FKLtl)Sf)ycK z{6>)7(ZnrH73;6&>uaIWjQSQ4t!T!%;2*hDip80)Qo`QQFFkj(TcZ~yiNufYC`9L6 z9KwtvMdPdeRsZ}|u%;&ywT}fRB!{oIqrMIim!8CYvJ*-dtAk&Lng4@0!;sCe3!PZy z0edFw?Df|s**Bet78>`xOySbbhTA<~%+bh2Xyq(u+uk!h@I??V>*Wqhg}4?vmr``{ zD#27_seSW;m}?JE7Bn}m#ojI>#3=vb8d^^*Os@=S-YJsm`G9w_`?>x#laRTkl~vXD z!Z5aTvoeJtwz!HUX2#sk4o40WXnwlt?u;fS=rO3BJ&8RtjM;zsMDvksWnz`CO&hC| zp<2)Ac(1Xh_0cNM>l}wva3VuBn3rg5^(BX#t)}J@!(h+P_{2p z7}JoDrsrU6V$BKvKEo+gef?>K$WRhx8zY5k#5kn%X&@sbbH7H3N`Bg9UMWfu zC{&UQ$vaV=N{gVPr>A$nJ>vYP9U^Br$%Xy}F4~Y$M1FldQ%F$9@cMo*LcO~8r;ad! zndZu~I+V*fw94M-%=ClJU{_QH+G_)8N=wW8mpf|Y=a0wtMM9OklRh1(Zc6KGs%<*8 zseYQCX3G zkNhebR$9uapCh6XKY&*5rpaN3soj->Xd-YQiqNyIUxw=4@CEtqya!Z{?f1xZ3Ru6evff7{Svpe&xp(~#qCneXT?lc!Xc5Zrn43E?|>=eN+ z*k6&24x2K&Q@l?P1|3`}&(dAvg%|N5D_7QDiTp7{jrDVeM@8^TG#VNxl3;p?!p|x3 zlUy@%aEMBTnhW$)y3Ic~pQEL<={9VpBWUrHSal?%1u4J_n`22d+I&R-Jpduyp5$1i zjAeucG`ZN@P*m=cLhGegu3cVt!KHe$jgWV%D>tOrlONz=)0Bk9(1>vHZW{=BN#cNsk)a2pEEPX z)N~YoMABA=Zjr~W5l;o{V*JT!>&7*8Y?Vbtv7@+}=JYe0J8`PV!&xX!()^fBu)K=| zx`SDP>d8NAZ4;oA+O1}ClXsF5Cpp68N^3A?DjK;cd+Rbfbj;3c^nN<;XI^xkeaVa+ zto{_pR@EHhp4JrbBD!rmjL@-RhRJ6*9rpA0p@!(?@yFCC&-xATHvNZYjuk2%6XrU0s=Hiqw%>rhKkNgqrlTfXiCdmydY44D~=G zStfaDyLQ&>yl#Ft-diNnla2oHE;=1K8Z&g1cDB}uj<#LzGe^b?dH2zZY`ozjy(^fE zTAlWF7*sCjo7e?qs)V5QKjyVWs2=jywV;_ zT>TcjkyT~q8}8${i`L1Qq7R#{9rL)w-e3Plt8XPKyoojS^p+(_WG2vwlbp?s9g#o3HMgcf{28j2iUhytsoTc*Hqq zIS-_BxEo5Fanc-r_zYcWG>&DT13 zAI5!y?E^V|2F8qB75(D1;%eZ~Ro;n%>}#H?-W+%JLt|oklPa^W z-k(?GLWjM%oaAh`>u6ndiG5=GZCj1uQ=OmTln))e_egtc8wVoT)3!F5o$L$yYE=F0 z=kwJc_T5pXbUI=E<=7-bU+cZ@lT7&e5r`N+Q*$hJ;Uc${Dj_qv zF_fs3yxPLj7t*JPU%6|E_+{?o_zr&uyznyx0zJD}Ud34!`-N=NsemVw4viQUOsFSt%l-lc;}`GkwDe zLhjB*9I3;Lr;s6}q9OV{VcWJFrQZER(jyCA2929U5?h=eQE_dp-=V~(c?&FNKtaix zrmV$n{>5@LtN8U=o_2$+4z!`1=3$b@e@~qvHEqTMN%p^C1tB0= zt!|@rULUy@?7wemn;XpcwOIZ(UHYSJ8Cn)y`J&iC1$}4kGQ&RrCFXq;_E^Pu)2hDX zYihyAgg$ZUH{+FvWfw1wa*e4Ye;j_Dnp+@N3<`mE^=Bi7^PZUuh`-^|2n(^oLApq# zZ2TD_zdlyLc=tOfWA<3I4+5?kcr&gLVv%+!@s^!6j;fZJjLE4$o+XFshxz{ZAL6u`=Xq(YM~ zHGDK%4B;-ll^>(J^5K!^LBRCFlYJ_&GSpLzHB`{TI4Dp#idxG{(l4f5(!@-UP9y7! z!n?P#RdKmdi!S^SCAhkgj;;II(6qon?SnYyRrf!u z+O6dW(yyzr)0VhR@8qIe89;6RbFaCV4I36?-VO1%-fWExmk0Khn%dd+_VP#gfA=vs z3a(cp8+`S1X_7zQ+Q0@>9Zd`3cB8Dd?`TdK46`z_`*p^LRK>jP^YK1!+;ofWd;Ni2 ztVK`9!%vmdJ@2(vf*t$9xi5+N1Ej-39`9Kir%ZR^LyjL#-BqFK5>0ZvMN{O^D6_>cst@2hkA6R``&EznElh!; z=0aNJCzhbd`8TG|R3v`xEB(6e!8vEo-2+s?`tyLt>C^eSp%ia@zpu%UnhZYDi!7Q# z|CKkZRA(ZDSl2>$3qX2}q`rDqy(`I;%?mTGuhl!(RS$HYxL!8OV%Z~cad2WRen}!v zw50MtD5imdXu0c2h+QyoJ}8E!1_o{@C#)VlUH$K4odje0lDnepugT-8!%dz3S%iv~ z`hWD}MKfwiZ1GH+c3jdc!PQDhpITvX0P{8ZiB)uWTS+w zl@GZJECNCG)#(^Y)ge1bIBHcP9}8k zYcc5!1NSa$@2XRN{Tj9TvScbQvbxTm2|ILx-BN>4R2z?A`_b^>EIXl{;Sezj3lU<` zqtri%tA>x?;#oZI_R|>eFpz3}?KB2K=y>fIW0oM%Icg^GHslCgM)7`KD7`cgM+5Ps zd7Gu+qvPImd57RVXuZ5a`|y=0n?Xo={^wYCGx=ho#e5s8(>1g)ae=NqUK_Rol@~?f z_hITL|CzK6t|q?7T$G7q;r?ynX!|=Q9e$vuC+UD%9=>lQ9ja?Om5y9rXh$D=uZN!9 zYf31D1C%XJJ{@d~}^Ux=tbUacwt=+i6dH9089ksGk%E&b+2{rDYfMkPR~9=kd5=2BACz zn}Y76yNVA#69(Y1xhbMha+9s}Ep;!nLkN_nMf4g>!MV|^%1J06%cgiB(vIJxnab%a`@7=9iurPpf>w~YS+jUdRPO#X_u&$Q2s_0`eBnp;6%RWjj zKmBt5#$!R?okBG`RB%3=4PA}gjr&zk=xXue?pOcu;^mFT2>i3NA>{L;J2*kHmcaod zx<*>B1D)gJlWw65l+0F|(OJwX`kDjSBL;?wt8&|&0rrOL!N+`=_ zvQ7$bLyScEkV)@ux~oN(ylBfM|8|sY)t~0e1ePm zmZ^Ias#gFf?RYgbVIrD1fiqJ`XU@@JrK{0WFgoti5jS$4#&eknkJ>5EB6@9R{&w`Z zgNYzys_HWMu(g`!=Jpb1wj4I~Q8q!){N$%_$9t{DXdVPwuw@(X{ zg5sIBI2bpU>5Iigx!#H+0)nrN0o9AJkFm}Ek*V*89~S6bfo0!VIr_ZFe=HS|b%8B) zSIA#)(yII;tcUKLusMK8IPYw=OBT>{k1r%%V_}o6Hn|3QXrbzlo#UH9tm&ac3m>E4 zMNcKB+Jr(gtJl5=7{8C0{?qIL8AE^QIE}eA)0|(wQOOk*5Q}5l6#wOaZm~D3^Pb=l zQ3%WdJ}xdl7THBZ-MxjMk1mUMb;z>oRE>EsVsOt!3*Cq=xrLCkCjO{&ChJV+7wMBq zKOMbdijkJ++RzHClcD#qVAQ;X$w2WoA>oVN%=08)j%Pxolh0o}>4Apl_l;PXdN{pj z;FcEjd=9gF#=8XqOhI$vDe!UZ3~Ng6mHE3Mea>Nd-{nV6 z)no|w5RSh!a~uDb2O>l}vbobUExt9e>KTJd?~{!DGgNOEMg4+g9cD#9|4%+jgi7c$ zr@`jten@`#k>fN2O8>Z}WEP&blfSjT{z@+0wg+JTDX>z~4+go33}g1N=pph8`2D1I zKVc{EI95jzbo(`n1LxviY=<C!mboPN$FZizw%jOzg*BJ zymm6H+uFM()d5!xR7Gq3y0IkNvj(7Zij_IJ@J#R62p)TI# zgQ2ptE7R`R=^iSAtv$@V6dJsMe{e=2F8%NV z6*~>>hP~`sQaAmK+iV11uG=myyLp7|aa3PBH5KCI^tJ)&v4*82&K||vbR+m3^g9Xk znA|HPk8q(DFO)2EM738&~?HG^Eantu{N!@BEwFF83c zgFNw#0VSOmpedZQsVw4V(%G(_o&|KNB= zDB`W~#i-$yc^ovU=T+-rXDM6&qy*=aSp8^}%_o_o;wg?stcBGVTUHCh&IqK5k2?fjsL)wY+OPiDfEzg4D{85jjh{#*Uy73<1sQmxZQL^|CZ7&IpKs+D+~)M02F~ZDr*$0XFw*4ojO<)vADe8^&6m}&!S$Hm)+yI}3j9TK7 zoZYB8Vv#SR-?77XE+!b&2nbRbw{f4i z=MO=*93~#i{OSih4UNX>m^||N{)>ABs;+e7!8?ujg{M>pKz>%W=9)zzYj^jXNp+ZD zxI)g8kiSYWx7;Njb>!&oyQ@VfPXtEn-m+9|iG7M3D+|yxJZcxrK1xSLO@)c?8HM_Y zb;X;9ZLiPCz}1bvVo6#!mB-BKmC}K~9{~aJrX5>JX?W(~44*ZWQP|z`C^x1rQR7t~ z$Frzgi)Ui(cm!$Z>(PYIc6cu zNf(k5=`zb2$&Ze82_MJA6zMTlzn%CONNzAGD`S1t1%cupN3v0B-%-h(Wl`y`?#=}T zid$QPe1iL9H6y}IT*RHct1n^>K&jnYg-evu=1oay@F3;g z8&GfXG*e5~M1yp2aYEI!V2BxBB6O{EAN85jF& z34=V(Em1M1(G(?-S!Qch(rHG;5*nx*K&aUrTh-d$@z7Bz;AKnD(Pm=Cd4jQEu@oW< zKQfg&1qb$;jS_?g$j`Oo$n@U#oLnh?J8dYF%nV)-9pT))>~J9wGXGo{C6kcE8ij#0 z)jb*Wu`B)6^>MLPiX_7AsbIo|EVY+Qg8=oOKyM})JK^L6F*aVf$9Vjl$+s_@s~ECg z4+NYDdnZFx(F-mzt$)oqurGCYkA4DH=Ds;1uZ(pG=)O86s+Oo5)L2Z9%t02gM8Ry^ z(b6t1jrz{6G!iFtGwyCH$_ZtrVbW1pijZ^L-nYFMaX=+zwf3={eP85pjjh8+8_kCa z|37-5P#Zf$CNk@p5pPxG8A)Cp7`oYYToA<{hB9dJ12`f*i zw_W{Itb%}uh=i?vGJrCE+!=t3@e1J$$NAiLelmA?3uEOb7-(ovYgwu>!%pV5sZ->r zdkbjE=(f7)urdn>qyRMcnsgL^(;I-5w+A1v%{H$cI1WoMvTHc0^omvYt7!%1zSIF=rrfH`( z)8@$^9?o68{Wnf-7FLjcHr0?1FI&bmg)VFznRS(j4gAhWGr_-qPkzV2F);@SBLb3Q zuAdnpo3T>(KzDYVi|h5;ruRV=Y}0T)cy3!BaDwRn$^5Ld&d(jj#>Zc^csV$nGlq%+ zPuInT(=8HLeda%)M9Updq2^yy$^R<6C+pW()lN z={*hEgC)nH?D2>0tu19KYB)LpXlargrlu~-hzq_WJB}2Vwis`|X zWJ6PvF8ej-!`F6po0HY`hqdO!;+Md~AU|b&yG03-PD$N9S|rhdFX7_ExjfmvL4;tm zn{%euz@mi%R8;^3Td7pD_L+=Ik#eTp=D;*8|BcR-*Y#%nzemBr1bnGl+r@yOPZ7QH ze16W8BwUOYwY*FkhpQQFWMpKDU_)R&!rtj#(n|_TO5QrVH=HP{@8!SzHyJbDY+ESX zqVfs}q+&b$%R0_P6J^y2t!5ke0(o!T>jays!lvi#{RaBm*5t=f4r@(hEy;9?MU+}y;xvWQ$dM3v8UjO8@)^foW zCE`af0cR1nqvw#Z|NYNF`*E{*w(xZD!?(`p^ixT34k?gpL?Z*b0h5~lm^B#oteNf5 zzb;040a`^!e!975)UbHTA}o5I={3eI?PkKnFH3to6)283xij2_DRVNISYYeW+q+Eu zn4-pM#eLRO{OX{*=%<#$uQ5n>wmOfR`eOMl>aID=DSJ7u#_+mHwQhj%eR{`AzkeaBF7rP=e(J; zf4ezjGxVU3Cv@Pymx{=CS{V17FV%FPw!Dg=f%t)co9!|EriIV+O>IhvCj?lg;olrq z_qVrutD&G`Ye0QkM1+YRWnIC|?Pg2EGl{Vog_DtY)3AyY7Q6|N7S^-;n)goO*HE|` z0=D8&6C>ma591W@;Hl?T9l_5WG4|PqewMUEjYM3dz4aK6sM;gBwO-2XL?Ag+p(if! zyq5sGwe$q&sZqQ2^N{H%`d+4$g{y%H^f0{ra%=NXPXji^m+s)9_vwkQN8DLf(ULBm}?LLh12#K;lgVw?78|WL^ReVgN-;L@az3h?HQr?j zp_uTr@k81Pj<1uW{>=u)iBNqoHd!gcG?H%L#^10_uG6Mn1Z~e>YY|Sg zqHIDBHhLpKD*;?Ggfo>SxpGG<0iRDC2=_uEH~2l5S8(O{dh4zEGO#rE?>_7v>UYv` ztha5e*YVD$=Qa3*q|vC3cKl9zdW->e*EZ8Ibif9}tU)E_ zkF8qCXR>_ldp|0tFiHF~{cW^vrVTrHVEE>PTHWj8F_D{v{lMH)x+EE`u2pg0*XfM! zuUNvoLddcWKD!sp`08d3Yc$=Hkn-c!SGFa7&e4Y0YL|K`D@s0;_#F)fYabGPfGmfk z&dxwxq>D2olORDf*-nvmFIpwBQ`_Cu^@YbH$C%LpcxGw85UhzyeZ2eHHF6Q^Q zN`8pobAqFRk-*-P{!C=+Ze^z7L|eOLTwUj0Ue7;^H6uy+dF|jEQv+*FsI0H=d`@tI z&SMziyXem-a}mxHEu#6|hkEb%ZMG^~X*ho;(`WgVrMHFt?cXUBHxhl5Moar2)!Y7{ zrV7`cp5>`JxVBP(vzW_`c?U;zOcRB;6Rvsd&R0o_A(`-pq>4}Nil za#bdB96;5KLLSh6m8djBP#4j81bKE}7Gw4V$%9vk`N{!au|wP+6^a zdfB{w+?g)9halR7!X#_8ivU%vja@N1sP&LwiYu?|`g^@UC{6ZD%9xFDji@rswJVpn zT2~f>%$8>JiNCSbYTcq~A2y{}jCVDvLI*Faj-BUL_vIrItvuD6tq7B+k;WUG9QU}; z!3SIEGj$!($+z@t`gT3dF39w9>T=&UPcI|_XnxBZ0TL+M(-#Nx5C`SQt*6*#I=jpi zaKAYPO-6QBiQ7=jL)|E>G_WGYZ|4-Jk`v1u~XZ z-E!=Ek~aOGU*3U|!&H+*c-NGnfVP1bKW4&_zV7A$zx1B*fOir7md!zk-9*KSM%Ju z$A%qTdFb+tFp*B=@H+aw5^+U5_WOZ&3TvXAv`nE=kIzpx#)@>_pxpqi@roq&l@GOb zateQv~3s3J4r|t{>%E>F< zC0r4XEjzL=anbp9%ExbyY|cS9m=d0A>+IOwJsraKHsZ8rU_HnEJB#53&cMT1e3F;0 zi`w3Z76UrA6?}8>0paLAi*Rv+V%_DmA1;N4*{PXyJH8ZKz6r92xlqSlm)%0LX`v-( zsN3x9^qDB%NS=i&d5ed|n9UZAY!^f8Tf2PrYwj$iUKXyDolm{5$;%ETrqikx^UqWw z#C2_Sv24l}IY=76regLJB-j>XO7gEATRSr2!a6e7JZnw@DT-y@aV{{!h8ugLJ=ls_ zy@i~~A9R;utoS3l-6{JU7HJtM41Iy%*rtK_i83D$TjPVQ`PB+nNJ!=Zu!fg3gK7y2 zz@BY-z+;V08J%;50}~Xq9Wb>7QQoNa)I7%hI9kf|E%%p}BEl4E{g5oTSLLzDK2e4A ze;9kqs5rVMY;6n=DGF5@;*>g4W$oto_($AUtfTS znjbf|v|!@n2kYV{VC2qtZL%9OEY+IEuytVn^ALJe$}bBT=ubnz**DPz0lJ^7R7;7n zABOWl^N%0$PW>(XZdJtX0tiSC^^cn8<=`3oXZ9Tx&Z&U55@xI(v(dy&7jn{S-(56K zV|j7}wj2IBdC?5U`%u`hO^!hM&TiL$JZ)7o7^(ASz7o1KX=p%dN6$@kzS7>fHaX-? z<~M#KMUS#%%&ZIF3iZRI#Vg7+#@EE388QfrsmW=k`6nq^)Z9B>-g%?wY@k)U&Fb&Q zD+rs;48Jc?l@KYFf-}D*^K!Zo^9&kdTUi$wPggUCHkPIk<^yo!XHvr7*NACF3PtSa zie-ZR=t$Esk!kx3 z-5iX+ZzNj}20k$R)ZQMu8eKqZ)o?||XI?n9j>RSC%`<7$MZ|vLq^0Bk9WfU5Nkjyr z2`))YW&IqNv{P92E{^TfCv8Xr=mp>P;xbZ zeAzecv7P->)wY{dydR16#|sz7PkYI{Qt<}Ltpzq#g$ceMS$~8Z2OQg2lEezULf>VP zEA3U~H;KOGPQ1#(O03=FL=;i`5kI*0Yn5cQrJe+p{KX4P@He(=MlqS7PR)8m!;tIM zjAM3_+$b0Rn3qa^l>6|C>-3=cQy}d@s4gz8TJ_V$NM6Xn_vcK=w>E$0c}>R19;=W% zgUPIN3GmmM9=k@=^1`;{>WY?O00$AgWI{|m@N6ehV}l8wN0k$KVP2H18f9P zu@HL&SECKo=yK09L(;?Z&;r~O4O`-ro3|AL8~sC1C@ODi*Xz@Bg2a4qzkVV_q^Q&s zpAQ=&oJJRRyf>()y$LEB<6piOkcn}EiI8@R##HJf+@H&eHlJpED@9q(#rKYq`lyNj z9OywrxR#6FNnk0mWNSXsXY{BRaUgI$gLEFBI^QtIZIO8qkBcRKeMkgPAig7y4XFD(a0VVhgiMU61S6yde-cuxZ=9S@ZdPnweD&s;s1 zEKDA^JJ(NJXETO_pI_{3i*lXxVrZLeCFKz4u-u(ytPS7uI7xTQqJf^pWw@P2fZVs|5{s; z?xU71Qz>9ZHn!8qvNt-va)K(}hC)I1PTodj#mXomLu$0pdP{EP5p6i9yUUpS?DN*~ zHdd$Fte;=ut}Zk50sgGrtD}}9UySQyc;#R#{h4>jTbwZ*UTFF*ZR)Ysw-Jzd0&<=_zYbmDGp*#0M}-tF=5P!(fg3h=xbw6{qRuB+KP??@cY7 zu-8=llZ8f4f`H0OR6ds2;^m``E;_xbq)(&KITxFAt{%Jhl;=}6RcEIE*hzxKPyr=$ z67>TB^@JPgBPwDN*O9DF6!5C?6cL>EUCOs#mV9x(i*6vMkML8`Pft5XRZLyN0ZS8Mj-7^k! zaK8j=>8pYHpI=?VoXOq^f53j;PTU(50fZ#k@p337lJfuk*_VL7dkFovoEIlcdhZ%6 z{?UbsODqbC5o3`8-miH3o0^OFMio2~)ha05tdfReW~<7ELVCYjmm~ zE32!ACnvQ|xPT8!L}cWv5~3EVBxYrvdVo25ywGuR#VWMhK!BUp+vVkD4EM3{eD`}4m^3{mm_aUm)s_P+wb|DPgJEfSwU zXVw8pilg5B;@=GE2t6bW~%%Df8pUj~76$9>=EHsvt|*hli%j|NBr2@DL^j zh6xb#BtTb{g&4h8w9V~Q73v8|@1F=4w(y&+4uZ94^Zb#6nzVrEWo1M_{>mPrP5H-c z+}!GDX2KSNo(rzUL?P3tb%yA31@!d~Al3uzOR0qV6bIJ5s|Px~Hkert_~bm0oqdtI z3g80L_gA9&r#SE%{PMcQxNt={cZ)em>Y4ig_c-0lw|}UhnG0K_%vSZJeXs;9e*e-> z?pVP(E(E-e@bA!kC_l79)`W>qLj<0S74vZ&4!VYCS8|OiFhBQpb-%`3aEDX$e1gfKRW{zQ! zCnQ$g5dx@L`7w1*9*~ef6r~}JsFE#`xgRKC)xVLm{2q1&!5HlJ2PlJ z*AnVdragb9<7)*T?XA9b+1L4&Te0V|;?-8P|1`2My@LF(ZZ)R$#>O?f!DFC6ht|+o z{#6+v!sxg{ju1FLJMRCYeh31)GzFt)>xv9mp2>DkZadwvcqlpwrg+vcl?= z^ZIz|rj;fv8Pav2IfU<$1O(EqOgEHNIlP|a`-yGcg*k+hr$FW`wT)AMyr-U`Ah~fk z#*dSXLM#N8(4|f0%Fv0xUiC5VX3ms5M1rxgoL>h4Z_&ThGhi=_(>{Y{&W6?5E9KAb zXVL=qLMA#!6oByx%TKPat1)?19f95VVQc|Y6b@bcCB`mZLbTx@d^pR}d;9pPa3-bi z65?1qyWdwLBc|jZuSvQWasPH)B)$jX)jU5s>r$mv7EqDCl%CRuUF`3F1rkF~#mC0% zO<$oc*7YldlHOft{& z8jQ$(p&h%4$4{O<{l4ECZh30%bS`7o&(3T}_Udet9W|j$M2#V+cejOwCjGr6#hBL~ zb7&Ws$;igh3GDKf1l3qiRi3kXSw-e~{p$AD7(8WrwAF4%|96Kct1C`^6y;rYFvc$4 zwVxbMxDUTIN?$kv(WocCdK~<)sHae8q`jOMErq1*kBa}@751g@pG*XB#_x8`^GxFtW%Sg^Lg7O}3;InTf6b$XWk@YA9ho8Hz4}ZBu$}ya; z-$lw2?@jyu5xmD1XSlp29UbJ31gB9_C zT$G(*)usDv-u&+Uy?#iKQnV`9C1SIar}s6%c-DaE!5%?d(XvhQ>7}PLw*En`%GMP5 z7X(X^TrK}wLe3~}UAuxsZw}mJF_z-EqaV(b-cZ%M?N0${ z_4>;z#!W+qv>H&ih=vVVSBdA7d2s$KoJa}m@^Pz$uwOWnRnD?lp{J5nURy-PJn4oV zI>u_8P;w;uJ?O7W?OZ&Ba%CQ&%Zl;vvTjD?%98ILIXVS?rq5Op+{Z3E-?CC!iB2wK z?nS5%@Vvd_bvH%wa$8IY*7f$`bJ{?~R1j-0KzHAHF=A+@ zF#Eox|FgA(3guu?PQlj(Yw-}PM<hxD#% ztyL|V7?Ev?W`eDpa%K)xo`hyBxNI#HbJ}4*tI2Q=M)4PSetRiV9r?q4vIDzygwG=* z4hf~gkEcg@xVJy$1KOaeP9zR_wSf$IygV%S3%qU#P`lb6rF>m^FqHQ^OvwwvYn``t zS?-@X;Ch^?Vei-{e3#80zfWo`G~vBzv-zI>+i2m%odX>Ycf#ssjh0J&IzfJJYeZNy zy>R?&bsR1Nf>CR~Vy*-%0GYTZK0L;_GOLrO_T;SRx`oA&2H|s`=Mr+Y27UZbfeV8J z)@W_bpGV4Ml{|Hc-}~d&O;!^cS`Oj~aAGREu+E?GPQ?F}H-Jp*<^T_#smdoGB{FxY zabG>Uf}UdXbPT@2ghYEymaoEBPKz`NF|xtY%bO7q5N@XDQ%Ad#7yW2DX~iQ)Zz-^$ zT>fyrmf_auCjneR+Ro6>fPE;#BM6ePKF=vr_qysMDFq!>d|~hcrj5h=GUEg+i8c|l^>Oa-?0pH=S*?cZRtlG+ndrnz4`$yuOs>W z6=R77KIauACAGF!Zk<@u$Q#j6A;4n5`XR=75p$0Td%uVtzp?&1>}#DF(a#co*Q&v=l45qfQa`!@YdafdT_F;G;F zr;s~Mdnw%gw3(|fgs5nA8hw17t$ho>^W?cNBBerNt&VY`U1vbTa5p(d2J4G)vr5__33xcWZj>M@wuKJhdN&@ z%Nk|1^GGkgMF-?*Ksb5u__#4eR@5+n2N&>6g*zKL{dnJSIi+JN{n6@)A`x2rl!S1C5Y!`r3=ntbelL>;ZRtAUi;8SNa)1 zx&6-0_>V4NmhsOG09B(8^Z5%p{BzAN3P^=+5mY?+X&>3F|3QlX1IGf)v^MBS<+B6G zww-$44VZNSBor?uXzhmuyMC4G!Qo-AJyD&0R5sXB?dKU*F44bgX;2WXIacuW=tys= z9imvKjs-Xi4J3Xd#la5ohg_cl+D+Uhw^{c);fx2JgGTHho#R1noda4^uhJ7nCF1@G zB*qR33#&7ddKZmELPFBo+FGburI)^2NEGrK^3cnQH~)o%EvB&aGnI=Kd(~}&dZe?R zX#b4*k0|``Q-xYn_v9a_^v|`XG+$re(g*$KwXQ_wgFW}Zq-g+kJ2eAL0fC)*RZg@G zUjP;9U3>(~|q zcOQn2Xb|^l!URLWRBL)T0 z9iE(aj!h+e`~BH$yuuo012lSMm~kumy}7wAGAcg2b1x`HD15#oO4v;ufiwB*t@)GZ zy!gYl(G>MFuI2tUCEB^iEFoXp-J+Zc^6Bq__6=b#tCplN!mWQ>w{%w|L9c6^9NcLL zZMtSEkn0EVM+6RYc)7%C-4UXXx8{p6%E|p|-}TkF4KIR`4q1XyFJLmJqXS#baE^a&B>@yFd}Zca0oQU>XpbenU*!(K{^$+ zzkg@00Zu~yP|pG_BPZt)sj25m8~`drz1#1?C?sdtsofIW$sO2puSY*`0;#@Ox+J(J za9nR6^?BL~4MQ~&CA466b@NFJ!D*-WCc|a_~f}Vq*JB89(`Hcj~z{5PzXh0*}%6Hv&7{* zg>z?IM)$f8g^-zgWMiaY%Tvde5G1LGYu=vTjYa@oR=<99bpn%G&_l(kZ*fR<1a?c2 zoqB;FUPv+(<`jm@{pa-Z%9QgBkrB7Gobgk}4@R`^UTWWNGVV#c8u-)FT~g1K+A1X@ zKJRAF(5kj&{Q8Da>sm-b1gG+eLGdF057Vzna3pimNw9{O0-sQIBjYr~>81_33Knl` zBecHP3*q5x;2B?3C4Ll=c zw>TXcqs3t+<{TMY-ZJD)2q9x$s&4;$g6rj+%RY=Hv3w$p^I+l_Swk;tdu-LE+#J-h zg!_YsU`Y3o7*|L9<=Ev4m?QbzJ$<>1=;HETdn52YUZkzB;XT233*DUy{=e#Y7bltGEf=`k7Qr|(ZyyR6T0b_>OM zmnK5$Ru_%549L+-@>%YN-dss1|FTc(k4}pHs@4m*rTs%uJR&Zts#y(uBn0l5@2Pmn z5n28!<|WJ#Oxy#>D z9+PVp80tswgcLE!d;rcIYks!Qwkko#F0acv;|M($H^o<3$Dr7NV9$1 zcv{+C@m#J8g(h2Yx(U&jRcY?Sk4*AkUkdmNT{6FJaaot5CwoDi@vDlZDpkPVw^81Z zYTK4+!sIC1fJl@k{ zUZ2i1dU946rE>G*J-*(i`IlPKRxa0b=){=dy`*Gv=H!kvAaa?QRXtxKI;WRbDTq%=%aKqJsqlXyt4ZFtd{mf2Ojn!eQYl2_$E7 zBdK6$do<~EZct3(aQdqVrRT)tO;eLDdm_SUbEw{NOA0& zUAFS9OZwHb++}q)D2HYA5{admI=+eIT<-SnrOU|(`)2Bzy^L7@d$=e6((633^g{Op z>$~OldXMt!O|;mNc^%Qatp>M^G787jZ-jJrrzNwq?NnW$f9Rd2nw(rqi!9G<-7JV*2D)@u1UrNW-C ze|-VMNKz6~GhYj(ijcVa_6b~ST6>)p<%05Q51!^vWH^={ZdOI^!iJXNA?xpO)^4lTi_l!q=i;=BS0s`L_)fP+brzV_MOa$(p;L($X^T;6S-{);E&F5yTSM2mTn=DMV z2!-OXQ@+iE)^g|wv#}MInzbj4FbPu(I?`NUqScnw%4mbXw(A^+z1%UcU2jV`U3Ts~ z>Oz}r{QBOIfmWriVs#Vwp9y}$T-SgUci0BEem z9bx@cGsvY*!haX5yrxuG-mZR003F@HfRg%QbW2Z_vUyGNRS@RqbdmS-dK8DxIA!d6 z{>arYKvfEbs;4ZuDfhEu^`%6Xiz|rI7uUCz8@M*JC~W_a8ApAACXu_qa!&9 zhPTO!k`ow+CFX|2&zGKHO_}c3nsOiJgB_=>JqwPz)eRX*&8A~>6pw!Uxw&t?P5tsc z>sQ8|oQkT>WL}c!R?joZT3F(>!AHy`zWziAe}=?F{A$ci!&T6Iee2tf1ufFKk)I&{;PUaXd_Aw!t$f2|kC zzWQ;Y-Jw(@Z`xpwN1VlYVrxBGN}BL<^a!WAD6#n{O2x@6H4(qp~yDNP!CsHsCkqGDdR&nJ~ zr<5XEON7@Qt4YawEK-LpNc2};q@DB!I{uhgFFw(TGYKD zHeZG?=P!R|H#S&AEi9XiwdZwqYH3PebEe5OE$rJQJOTwVmX#&XkavAYI=wjaAFyUU znGpAy&y9J!lyYU#_w0PDtdvJl*;Lkd;Yw)Qgs{{nrJTiMV!9spH`rElvn3hdV zI_EKhQk+s>WF)CM=`&lAniWhTt5~wPS#fjv29hsbWqI&k>q{daKD}B`kcAY_L5CK)}(>Z21h|NJNk@fN9EsLD~fv9e|GW}7RXy{stUawW)M`>OH7zv z5C1%~ch>U~{65Jt(rAEyPBbvb_TNYN{QK8mIwMBUwqsM9XFdkGJvS(wea!%v;r?~flX}@}5RHL$)k&)4#JrPLABlzs!x;{1dIcAMQUV^r$+@!sC zjxP;Z&yvSrRiPp|9{d@A)wDzF<-hefy?OHt^eH4ijyVT1Zt3aSF0Y_~h1s!^8TD)P zm`Xq(1BCTYNs}i9V|e=*$+lkSX{ql;zO;n0ht%#q2L&NBp$5L6XLH~R?08!;QOxHK zY>m~-^XtDsKtot0Btu@B|F%V3Slg(YwKzjVN54O*KHInL&+Yl9~=AvsKT*p4$C8s^QMQ;9x~{MN)T~FrFyx6%G~_g_)U|W%?(e zS0D5O&`8SZH0miSC`5(PuaHV}2vGy~oLYd(#QXC9){rUrN&R`Adw;z0lW{SOMs3zb z5J(;K{a0`FzfDl7?|!5U`@KN~4A%B7E9gyY=raAkH$kto<~8bBulX^$&o|cAzO+0A z34VF^chZMpTR9b%bIhy*Xwx~Ca zNOiT1oS|`Fuv@XsND)Rr-Un|UN&+8@j8N%3`BUtZ?{E5XF~VgUrY;=NF!y6cP|z#l z2vOpQ%}6N1pAu~$f7s?NkPwt@l<}byK2Yi(5=;oHt&`QzaOZFdWdMPqU)KPiuh{(Q zz=??{k)z@R<((ha@qr`&zcp!)G8dd8tOE zhi8810x@)oi;CntJw02(C8ed~Cd`z~%*=3<9=cVFmSc<-HV2Cb{>HY~)E|RL(E*kQ zW#Y`XI9C7*Bg3^Gi%N74g!`reSPXbiK%gKDS65f*Wh#A-M<7f5Wexag-PI%D`pG9Y zHa70dwV3tuYn~I^qh5-V=4S5sf`@yVF;Ac8KlF>R_KD-f`TEtdmvdb+%$Nds99;;L zr;YNV49)uHX8)%7-E*JQiHWPFwsY$HG-pyMbUO!r*loT;*Ff22wgBe`97S7dEPw~z zkT#Q}Ngv?qfIz6zKI-t}-OHgf|M~PbyNsRIJ172J@F{V`PEL`}#HO6EZB!rcf{pwl zw<|BPD{nfg=C#w2ib+R_*T{PkxI8PL7Es|MpYYMm@@qsJ23?jI<3W>-Xj1 zwGVy&2vrk=PRFOI-M zu(zGz4Scc3dl!HJ)2tQ6K{`;;XW4(cRhD2n;<~x}Ls(^}zI$=3!BD$br!))>Ejjgn zE+FaEi4D0qqlT3WT&yaUx_(SZbxM}ufw9tQR*I?I?nJoVt-_T?$Pf!u;#%6rH}oQ0 zQeFX~R?6?F))IJ=D3gvy7QazVF#@Whv|5r`U!Nj}M zv-_d-81&}j7i3w<&Rrkme8Wt(II}6@5e*+e;&h!;=13j`aTP8+j=)c->!;?qnW8*qt=VycckN$_GiBf(ku0Q33~CO31J7? zPC1OSX}HtdeOG=wB%s3(wo_5T4j*9{OwKl&`I=`3WRD z2Tra}ZY3gN7i~mM)mjZz;dAzodUZ~@tq9h6+1~B zQ$>}ZGl=i!aCQW42@R!p3!2;R$K0*&R5C0NDJ_pI1_a22gfMuo_R|VZqAb%rdCe=O z+8;wMe@M=9I{08qgJVV-G@6E5vyOft#p=%F&Zjce?eAJrgOhSGhxoPd{K`-wZhxvs z^w^l5ci&H3c_N*7A&C~dbv$>w72vw6CznmG($`h6gsR5hf9$B)S)Sp4rl-BaDHWDy2P?9tc=~6O@ROW zmE11B>y?RR9PvJJSZl3evo*|dA!LnD5=-q){H@ng1& zBlkvW_IRdXR)J3KxzzB_EcQ;6}2;3jv5RxFI;vz z*DmPGN$AD#-`T_*L8752Jdmp{bGO}?0qP^k_H20UwOk&Cd@i3kR8el06^I|(@31ip zKb_7Y>D5}gm~M*LP7mZ)`h{-1lZxl32)z@gbJc4Z-P9^K$CgewPjf#Vy?RNt%s7y| zqypzXpx`_It`4KLPW^5!F;YpDGa*1P{yv{5hl@qDq#{c-h2NRRc167T;OLmOXpfBV zBEwoKWovwS6+zrqh|O@4a3FbF$98ey>cD5ov?cKu|a_kR62aQdkjdx zX}SJ(Frwl4Bak5LTt&(_JYi+UfLK7=C`KGRM-EXTzsH!pKPH1g$CZny5LigTSR~?A z$)J~@HkBUGX)9h4kkx@eNl7WMAl*%(UA`e5dg{P;7}4!;JixJAn=^WP-EX{mwOcVI zjH5Lk5Li4FUdKhvXXYF5bB5Jo1${QEru0cjUO9 z%OE>BFOJV-5gN|Ft4Y+ds{}cb4wDa%9zG}|IDr&_mFA$6@kz$!lkums%KHjRiz1eU z%pW@BE%3SEFVi@TqXSOFWsd|Cd{QBGFzV1no@O^>|D5Kyq$*gwg z(QsKsZfLqi$?)nmUXhU(L+vAvpo0okmXRW8aE1^rrH-z!sYYE$9v#VU9E`>Bsuz=u zlTEsV#mHQJv0yfGiF38Vq%OWKvTQTsI&dF)OW$V2BWg^PM1B3U#<9~k37>;g4e=JC z7pp-=!)bz*Z$b!1I~yq?rIbnE*rZD_r`-vsXP03#S$19e=*)HBx}cMctg9{(FW%a95E)k*JJ68X6l_d7SrS#}76} zBRo&uYk3@Ys#hC)eTjtRIFpBC-V^zDw!u0B$dci4AX>bXRhQvWAOY{c>L29DD_$sG zOf0Btkr~eXc^11TH=^C3hfqMx_3B>zs_;G&AEG8p9!6AD^dx<%3q~ffSSyp0efTN> z`5dlYisoCq<-TECd@N~;kb*#L8{o+gWPw(_Zm%Y}Ya_0qn{ZUnnA9raE4j}}&{ofC zyX`Vbges=@B`Z%lo|a_WB)o*Wi{3j=jtR_Lq!eZ#II+*gahpV5X;|QUt@SorY=OwS z#M-OruC^vD+Uf=~v-A}dRW}u&v(5Q3qlvf*9bCPX3ZdeTb*D$fYd66Akgb*(!+HrE z^*5KB)nz&rd^lRU$wWMBakX%P`>3o&)%Fs^nq)ETNu@TS` zTKEl+egu0!O40N!d(35;P4a-yNx)$>j>0iNTnhtU&iEON$@dYwqxsK^oh#&IMhLZR z7Bo@5#;sLMUQESP8!yNV@Xb=j?5v|)3Ed6PXq95@Q60hPRpNB22}oUOl$1>rC8DJf zVuW%~!Q);WWr|0$kMP|~B|E4Qww4G~s7>2GDA40lDh!afdFs>`Gqehw6Q;jgZO3Y6 z826$_W}mq(Fj*A#8U+_nlw4{UIu@TM8ZZ%%DP$vnlL{_tmWJW%a9PI?P#r&<@AkC9 zD(&K0z(iTSlv&eZWt zzHPTrx#3bzQ4=ghaj9duM+grKQ$l9xGSX{z01 ztRc11dBhbvC1+;G@sMJH;b&)4g{_SuX9g{_?bNWDgSg3k{@>`&`2>33B&w^jF(wR3}NH^fd^4b-Xuic88JCjtX;rtru6VT2< zx?|GpPP5MrCpgy{^9)C%*oigt8Xg*S`6NWIk?oF?o|!>cKBj zMNZ0o0`AI-m_Wa3n3TpVx+CvpwTaDFm#ov@Q_a&L^V2QeFoG0bTlI`$isv|v;wi8) z?_a-)ONotlZL%tcXh$#rA1LIJ=Y^(~gp^Ap*iTnojm&eLcGWoVR9QRqVG3w>XE^(n zC(h{PC-V34I#+voP5HYGuxoJ4yNA;gdS!SvY>{;$r<9Gc1QhA$w-ng^W=&(denQuF z!s<$KEAQ33`YFwJAgPJc!P^|$(|6B*%>i48TWtJ?LMnP0h5bgM=GE}X z>xMHnVBWpAR-9URSi3l=xWvz1x0somk%_ZSuu0E7Zg|H31oSRtIn8;|^lTrjrIiLG ztSRY06KLILub85V>8)M*o;I*qBwzNO+T4Q1T;h_qxVTuwqE%Wt<<_yd_^em2rto&+ zQb|WE&&|GdW!9~-K{<{ML2Y$_PTd)Dq^Q(y{WT%46XFU0SC*C3-}R!`l%(@S$y1cB zGqS;TaY{!3w}zQ=e*hG)qD2d&X4p3mN2TI3wbx74k*FCNDr|9e%<7iRF&U3R-jr3A zbL@tOhP|H|dp3`WZoJ=!gr_Qw%_ROK%Nj3V>P~yzh|2ktPG8fNgM>k`vwQC#&DMey=Rr{*y_HN zf?j2v?FvHfZ_n3lIBPvF?eYo=%z@}D4lxP6wO@Y+kgPBP7bGjj7~#XiGHi;PvI!LC zPBO~nK=^AMk{#r*>Yo&~jRTpg8m)SBa@kCi`I9uJe#%2bxs4a7ItIXqf(+`^Pw%eb z=7XtR%($~>fo6}iD^&Uu7!t}>@6jIsC~j$OZDK&G_WA87%fiBfhFk9xOE&mUGIibi z`c?H~L6^M*5@jW&?c5ldQ3Wtx-UDdE#ifQxE)_XoGzLU+RZ>wYNaJztTemB!tyKi( zS115kPFFVz_?8)sO7NkHW}$mP<1-#2Zo60sp{ArXnW_SuOyUNN6x7w#ag?3|Mc&N& zc3%WwzNGGpiI691hP7~aPQC}jlK%TGc$K^!*TmAuSfcoFbd?p&Vsqn|An#He<$4b^Z%+t^@7lB=n%ej)eh zP4FL-=AkY@v@Y(#g&f16+4@25adSL{H8_4%F0UNGt7ZIE-nshBN!;) z^S6MYYLjNUO~P=_+WNYG%NK1r9-bDppya41^oMe3VSmekvOx=l3kBjc4^2mSs1j>H;Nc$WKRSxFV(iK5M^3apO;)O@W(02J}?np}Ouwc8{{+zaw zrK#?vxLz-@^Hl{c%P=$E_FJn8>(jIP`E^vf79iY2f46_2D#5>N|C!`K3b#C_D0n#06zQa7^RD2>KC(RI@@mE3YiDdB%qPD>Fynre zeBpAVp_o55cJ#U|eSljE)9WnR3BfS$E;_<-YNUhpwxUF7Y4Q5RU9oZ*0#T6{{m;V5 z(E~UqumMDqCiDvfS`VM<++#(rxJiLiNv+EOA%R})GHD+6ow4qkHTNBi+nx2YBL~|k zX%F|4&JM7-maRUiDPf@kd}w4&KtPkdBWvlleZ7LFn@H@-E%ntAQCoe@)i50Q-(fb3 zWgeq124}jn{*RwgVJu-1LtuyN9J+4L}f^xo_R91&8J5TUX#!U3zfam&a3?U z*IEv{Ma2-$ukk32^3Y_CPvow(=OJF(RRv4K3I4YZ-e<0P>2?-ikAEiq{%Wnf5~@0 zEpR&6jNfFGmM7`S3)YX3jwZG41t6U&(G&T7ZLWNo=qAz&YPVYBbtJcwUXHrvzC5l? zojl16R22`3r_g^V)BAvij&9=WbT?)4gJY8>H4TmVj?^>I39{vmVA(>m2z<)eY&P-f zZR9!L8ZL)cAdY9Qqg94tog@u$izM0x`PM~=_1KESudDOCscnC2J`|!-@SP&`qA+9d z^0ciPmin6R`qKJzf3a(oxLtcnK%qE?{xWY6kEEg%%s))Lsi}3h%j0-D9d>nEp)=xq z=ZPlv*VD(U?YMwDe?v{{V9dC-sEfh1eJteOxt*9Qx!l~-K7>BiU^Jb` zF--JI>1aE{;nJFYyHe7#B#$FK_o|>`GQ(aH5B>*-1}0T57dRyzu;Zl&5&>r_;h^@ zBKMQgoI37%l1-D@N?g+|Jnr2>*Q=qOk3^f%1}Rw?3l3o$DCV@A(Mx94t;N*yMesl( z^35d`Q~Q}`-0MMA_$K1Rzr|Tt^-IN%aPDM7ts9hik5fw%+6w!_Ny=2kbIPx^@A=@a z>-5RRn54b!g3xA|L|Up@to5*X^4af}tM;CPUQ-lj-E>Bcg0hP+WsAXRSV}`36c!L(Gm zfcHLBSt8mx0_X-9rS(K9jomae)Nbb&OW@888pqabC~~vx18577!^?uPUa_SYuUt?y z=@W7THuE?fv(#5;i_3~oobf=zx|T0xSNBk7cF&4ye=u-)ie2BVclN0?i;&~yb>#`6 z_zVO*&C5-yZOfE$d}d`ye(8~p^5?ipw8sS&Yo9~mDP zHhhwWMO|@RlCLa3|0wtbrm(1PI_^839}_HXZyKvT5$-FPQJ}`e6!xqu(NHdo*YU$S zI*(?JjO6$|(XQOy z5cm8zw)k^~*6meSzfO~6iNJ;IE&+iOimmugief3>WnOVnp{%q`w3)=z2vWpIz-Ic? z5zMfd8bHMFFI(%0y_$`XEyhgQ=Lfz?rE&LX_Zt5itxWvwz@i*Tcif;f!0pz!P%wY7BPIOK{CD!@nI8{_PP z3qmI|M~+V$iiO=SCSzDLVV6Y)dlfMWrNcrucNc2^<@@1BK5QKB&7^=Sm&~C!{%!Gs6`DR9$lH(UH4aV#L&xz{QFW_K{HGLO z0@gMif$W%?`keqY_~fr?iAziIVDltFiKEHbq94Wz(R3nN1yfh+MU*O9n%OJ*>ig>| z5Tzt)ERrMs8^<{6bJbW}ugq@Fr|s%WiWdgb)%!TreJUlv)V=YaP1(}Urc{bb`wGA0 zHr_@&2z|4rfHt*E5A0N#9oP)ov_-m4Edkjuv1FTznVC5@DT(SqcLGG>@M3c=t65g@ z(Ex__t&{7)zP{+O?Y-#T*w|Fk|3lY%M>VxQ@550P5Ckho2L)8RQWXeQkRmipd!6V?q$Grn2uPDo=z-skpL_3jy??xWWi8eMvd`Xg_RN`i=9xL( zDvM7sO9)ZQ&q3`+iphh&wBzDp-+;{X;-`;6>w~Xu>TN2Q-xU3u;s2f!8It@f8nMw_ za=#-blEd|_<9*SiGwa_jGnPeix{+opT*y=(u+x&0Ta>4|FFGo3&hn287pvRUl5cxk z?%79w%dE)Cx~GrvJPXH?%3(HV+j#^8%0@*YGFEo}0Sqb)s_lGlb<+FlAOG`R8OG0( zYb?z*HZMH5mHTGCRo{Gn7Pb_UfpMxOTBA28{sdLho;F*yOLGIDM|H$nsurb`-rr5yd))sX?`B?nyRWs zMH9MndwP0UHYd)?2-~@mIq2%fQBY7=2_}LMy5csNhpiZprNHNKca;&VG2`MqI`~Fcfx32l5);M!ZnFt;nbeV5b8mG#|NHkxh9!FR7fIK_ul6H&0r7|!@98--sdK|~&$eXRyOI@hwCxge=D44yO<7piU(4UK|Kcli2?Ys}M!<7qpk;98F(Da@#joYa0&@M^;<6cxCvWVPp8e!*IQ$ zyBkjNBSqb|5~;v!@v+8ag11qD2+D}rC1S!-)+cgR#^KeO8K znEu(Ws-iMh794cGIM8>j!u(UtYmU)td(wGAr)o7OBsCImW~;H+%znrS{}<>5-0jyP zq1}t;)0U{$O8piBmw!!Kz(+E;`#R2%hTFtZb&f`?tLhQ>rldj%g;2ALw4zpDkp*7{t z=a5k%RJt!s5a<_odHMLL9@dC?^f;-S(j>7I!|^iX^5Lxf{Bb^$H!5DUKc}>9xv?)c zn(F16F*+&kRl>gXP`n@B%qP44#m^1V{v)3Mg60wL$~cWXWd;?61}}M?BY3q-_`5x|QX=_IZU!-?wA?*Gc%^n*w0K(n(yfQWN` zkw&k?DA#ek#(uFsv&8Ar>-^5nPL~HvlP1jlNBcffaj~&>fHBoG@%)$;d`C~u^TV+v1c;4_e38OUH(5Qlp&PzGUA0}J|8PZ#$ko;d z>10$Ycs*btuO#u0yeV>A{P1JTNBqz9JF8IK?n&`_$9nKCLgMk@dKy^g1-&yeq{{3z`elNyBpEFOJoLu6e!t`c>|$PDV1borxO~SLrOP8xg+>5CNjWBeC~W4E1)8SveY%77~T1iE^zey-A#AO z6n}N~@Cm0{A}(2~iZNq^T;aJ)T_bu}3(a%@f656DI|-xZ`ysJ^v}-aQ@N+u#>fcl= zSSB!kS@^J>;oCYCZ!_ux)y@X5iYh zdvru*2pAa&D@)7;j;8IxmzgdzK;Dv;yzyJ5CouX*Lw$Fg_3c$ZsRU5$-12MwmwT3x z@S@HHx~#U{!iXbdtQ>LS6@Wad?_(fzv!*Z^Y#@Qr@VasqL;iESppCuNs7LTT!*ySf z656+_Ft|R1san)A4SRfI5NbhS!44l(O$*uHyW7T;Z(upQ=NHknOVgc<(cpU77Vk|$ z-ny>ah!e=>QfzC(WlZC`;Of!fK@x-xB}{pFT5EqmDYTbQ3z*OTFb?{1mm!)MKOqv* zc7h*RdY;L!q$bKPwXisUj7Zg56qQ;%-oqxn#P6X`CTsEA%JIR*+h&8UuG2U}R>{Ij zQZdr>DJn0Iwb8EA)djT0G_uQJr+CYFDs>hHJ$zZi&-8m>ZylO3J#iw|h<1pWqsyKZ zXx4Q%YnHLRs_Yoh@3R$q1NEuO2=Av%8pFHUsZ!1et0|JvE#W92Es`fWYE!MY1}`(! zM>c9i%eEO5{RzL$`H|7=+f>)tRsK@@i_fS8lPqWwp6a`3r#zW-e?`1Im$k^BoXJ@E zl;*GixNTln#5KS5)aukZmkbstZ+amQaA==jR;|ho9xBJZ>FF(Znq}?p@L}~mn`5S% zRh^H2@is~c8DA23k}&Wzy4OkbJ~1m7ZYVxg#q`Q#`=qekvz@h)gl7-@8u5 zR&vH@elHg6LY=l9l4}^Y4tLR!S>H`z`Q3yBKypLqHK*LBU?W%zXcZfE7r)!3j1MP&)5c zZ@el<5wcrs$$dZm21H!Pwk&@v`K<0)SjLT;GE@T7eH!>(^nuZF`w9AV_Yxi-7bD!7 zmA8=N8L;e3u1D~rFLA?{t88KK-tXg3&64*$+;v>E*q&c{6LNBMTcm6;zdbBgA^Ml? zVtcJgK27_nLYbLMN-2Xgb@##9D`itWWl!FVh=s3JbKGqm{M~^UmeoZts2`$q{;$iK}qjG-Hb*;@4^*E=BfsjPmUu<-CuNTJ>QCRW<4- z9x;nlM4Y?d6g-R#rvCJGbUgTJly@!N5Hit$+P!vBBOH*$85&C zq=(BAz75Z6`B@jP@?@Po68hfCBb6tUd$ik`{ITHm{^tzjTX~eeV~K{MYKleBo`}J9 z+bC{0bgM8<+Gqod>f=e|eVtD{S!gpbM$j5Uf`Uon>c*tmALh>obPPoeGy|BotEcC~ zGFu$LhS5RJA$m>KDy|jr+?;)RA7UJ;_rFo0U6yAmn2r}CkFoRIgEC=H?CxL1L}tth z+nXE4z3mCS{NbgFvRX`Cv4J(`5zNd%&! zl*35>N|VfCe}5u0y>EcI~RK&UWUoxrnY#*zMLr#cHJNj|g1$mKkxFmmSAIHj~^p_#Kal@VKmzIU_ai|yh!fc!;A+wM_Kj@0~=U}5(p@sYcS}$J) zUc66;v$$|2li`D4B1bxor#XqN#4KGykUmJfDeV2bFx?Md3O;+(|N7M&&`{H? znxJeupYY;Xdm8RODj)7)5~U}N|2V}`FQZR=zs7(>w^u@w%09{UKx1bvYrL9+z;7D; z&>-*C=~8R`y3UEG|8T>z+iBbP?$ast-byyF&h^&SWV}-kHG5gEc;LXJyCT$OA=U36 zaS<@uxk@Vx6cldfav0KNi|fYG7O99T?hv1HZ^=ywHpuS2>=sMXDPA(j4t1b(|3gjv zLXg@3Y7ntPyd?qrzmfiVV$I?zwkJ}nAp>c_kJLVj=+D>k;SST8GJD{x!+d+wd8*-` zm8ZK4xomldo2YEZ2y>uU9h%=qSb3nCk+MrJGgWcf&sAKk}out{9nHOyK1yBRXV| zNj8(4oPZj~7W=al^K+W!3p{@}XS0cT?!S^xZ`{jEFUrTI^PoJ*UTme*S0B!{ITu@2 z{oGAJ9EMpJ7DVV+ys9hL5wSZieHKY8Sz$(LG*xPltJeHT)$Fi*t+*g^Iw|Kt%&xa2 zLZH-lPUz#WSj-)D<*n`oeD_nqLTiM>C;Y(E@soCj-U}`{oOfFn;-;TQm$wGyz4l{B z>9@`$#=9-Dfd8K-R&q(V;AJE5kj~{p0&K>_r^G%v=lp$UoyBz6R&j85X3?IpH>S4= z*MNOvK&6^7jJ?AdX;?%KV9KMqNwe*n`~TuVx55BUpxIB){a{s@`4OOD+jV2&~PcNcAWWsvnBbzXeuN+r?|MdfLi?w zWaiqUFx7`d=Mo+f?Y5(<8D|^GnG0n0W~zxHB!oQw=ch_Ob|2$#{fiT1KYaRN?xc!K9cNL`EwEFb#(7;qS z-)T3XW<)ho=NxnIcRh{ey&s*qd6cAr>S4oIE4O73j-^mFW?QO)NgSc5P>r*xx45{J ziG-lVfo$u0bku&30P5`npRvy`vw`a@w`N&wq^qr+H8*F~`h8=CZqY$1U4xU8^RH9- zRy-4}dWqIA*l0mGWl{$7FUC-fNSY?-n*nYCKl$?{i zy*DjQK-hnK810;o_z^l71kaUI)`^Jp^R7W?JIH@Fs*p|EC$kUXNH$~;Rp}DfL)#?9 zKA$-CyFwpK#h3?D%y!__oZS5U)b0;uV5-W>f1@WVMp~D23!H>%?m@I4;m#lrNiI#hvOHtGvc?0g!&a}QK#{?Lz>Mj;oMRjz$}SvAlx@njP6=yF z-O~TS32avZv01ppdCVnM=amjbM&pV@gYyPZD(0MMqykr{&f&b$68dq@q-*X_n-Z#= z>|w{9l5t*UQ9T#Zh+koGd0|l}pA@+J?3!2#IZ$R}XnlrZr}5#5?95QpLqsluKoX6&S$Z##{=pb`knqc@DrDGB>Rw1Pfn_PCda#_G)0<7ETDhH-D;4=! z7=Cw#NK^*nvN~ur(bd)EK$}J?jyRk8Ks{f`>ht@)XXQZa&q8*%>+0%^&LN729r33NROFIm}Wl{c_HoPPwbL#G|_!8^0bEzUKcE>o2oP%n? zzu0e(e*+jFK%qcfpz}~dLV_2$ONt62MO76jMZ<>oK@JIYuE_=^G2B8zmER@{fWRH* zt_&ir2ML!{SnD}gG?#)^b5u>qr1~Q7PP&Bcw7>_yCg(CM+W$r@CGzC3@6V!Gh$x64 zLs$~j+wE@*uUn*NKVIVqxHoo1w4+m4q>j46}e0ao^SwUqCFS4CQP&aP@JwG9;~A zvfOkeY@f6n9Vz3?Zxgm2Ysbl|d~j@nTEE&Mye=(bHqHM30~S(o9Q_39UGzDyA}{pM zmyLV_Z^rPyjOeG~?hle)!QPdE5Rp1{APgMv)r;C$C6*ycJ=zuvdO`Pq&^Zduphp80 zx3`kceGQ5l1#`S5<*QdW4*%n**3Az?2>iuf|3^RI0Ww|MGxJ7k5s{A9pGe>GHr)Q3 z+FP9gkOf+aWNb+7+Qb_`!5GLCnYo;l8%K>92FC1a&RH28KwtoXKIKe=iNzOLS?KGF zl)&YPgS<^V#W5i&s@&XT%TFB}diJqwb(|NBAfKC}?;k?bf&XJHi{Y8`f-xTjumtDNA{AsLUcfwiHZM-+&R z!8Z(vXH8Kr^@R%RCII){%f+X&>=BnzX(sL-&_9Gqov}W z3m^IP4Y|820Jrqq2xnRC@-)Du39HL1=D@$dWoO*wqWm*E)aP$rqE#A$Zy6h7rQUWL zj-kB0jIQ15#I@RzKPnBznX9P02e4wC=+oCWDXuXrM;;*##|}QJpBZY&q}rBn-Kz7> z6Qavq`c>?U3UdMnnzb5?8J&Cnx#+g>28AMg4^_T{#o>!wiBtyPKUlAyF{WD``KD#2 z*;>78&6}1ZZ@Q-R$_D3~hdPO=!}3b@c6Mrk+)n=a)GsS7 z=cTEs!x|}v?^hd?^bV_>hal48;Y1VSu=%UCtD_@>gl17~(QU;k42RxC9|buHbP}@p z>)pcCkGBQ+5~Y;#UWs_kubD4CKAoQOZLigxK4SG}?ey+ouMskNc=P7X%M}J^LZdVl zDXeK!dhNQc%V>>WaOIke$<4HjWH(k>UpG=Q*5o?h6|7Cpchy9cGxA<^fI^2$!z^Fw zG;76m<>SP>InFZOp>XJo}l z_$Q*iI0YE6?#z}ki zVRQ(-jFly$;Y8ihhhS#v)<(naadJt#)k%eW80B8pPxTmf(d{i`7Z-ng4^?zd?+@uL ze}A`zWg7#|#IeKW7_a?pr_%v79h+$*sKd)rp5lgt-4RW&e{WDk)G%0t%oi@EQX7xvMNgkOG2D9doGd0L5yGPk6RtqIe*^ zh9_=~KIh~XR)M*VxcJsBMi@3; zv;A%BHJ6JNw?E`H^i9Th>6{MFov(+7+II>2E_)22jLo4YxP}d?Ra5IISQa$=q^ZXk^I_(O#wSbC)|~Ke?qr~x^Lt49Y}C-wMQ^^_GUo-!pY=Z4CVOD>DAK;Bc$jg` zhZ!-zH2?Z}Eli+a)>Uetd3rjdGT%2x-<%s;v27c&TA8ZBvUkl3zGQ!x-Wr2=y(d^= z;8{w$8dnQ_z$v5VWfHS_-IL&nJ)AmSIu+j=+{7LP;gr)wefQC3sW5)|Xe~+k(A|$& zCPT6IzwMUZ-C10HtiL#mPE4Ad8@|R9fyE_Amq|R)$y>tOu9x-?6Z!_yVm?GJlxw=~ zNhnRNH|A=fBQQBWR4>)2hjE~udwZE@xk5#-0#-dfm1Nj8)(RvblZPrQqBO<{vzX>b z-Ky8TFPhC<#z?M6@{CKC3&NrPvpRtq22p}k*30)M<&7!~Z!mti6{j9wQ{~=?!qn zo}u~a!RhixdfI~<@D;Y|+Z zHu2OiCyBnGl0lgKzXm-wPa}KwOi)!@NgTnN{wdw_iEAZu8neZd!@}pI3xMv z@ucK$O{5TxOSR*Cwc~056joQ!ledlR@(q>l*vY=*=1YgG8aMm%4MEK7Yf2OH;%U0> z-W}lRCKYkN_-J>m!1MaZN$u+ zH#eK3Hid}JhgI-9mQhAEyBmeyX4qtyVcOcI(O3N+qb8d`gO8*TDwt|l*ViVSb7ir~ z2}M(BQ;$GFf3_Uh|K+bq??maoKMEh@ODp13JwhfQL4Dn)8+GrEWDGa&ia?v)n&Q_V z8pd0M#`CWB3z+*nUf`Q@_YO(^!IRz^*-m&pb-YD`CS>`-IFtz?sKc+*i>+}B_GPWb zfl1t-Z_jr66RZ<(cDqjA@Q8JjJlhDg;a=+JM+s{>yq31`^JLDIg}*Z_bv-eANWw(X z&f=fv_)_wT_FG3^<#i`FUQJEB$oexxdJR^oyWZ3wchK#O>G`vIO7^^r%jb2OFx{su zOR#;2Rcyxw;+Enrb#8h2{gE^9+VMNWEoyp>j=f(Xx?}e><2WJ~V!rqj0v(K1LwDZk z*Lgmqr;k4?g9hmg!HYoqx1@)ghN%t_ljx_KN!H0(xeF!*-Wv6aV(QI$w&G13@F5AW zjRi6IHdixdK&V78tkcMCtrfkFDMF?a#8bUHp3v<16zBUN@RUf;xTyL6;$ub(Qi(sE zf%z|_)P;_PJM`-clw!_PI!60AOk)Z(aE>vjRkSp^qqcrbqGkd>C^K!T}+{3#>;(By{ zn>M9DH9}GgXX={JwHz_T!U;9n`&xz{YF;f>WgRomedhltlUYL3S_Rr`bh;!?LzcJ8 za8US3LvJ8FY=Mrf+$;fzQAUze$AkOeF%9YR%Lhy@;;9#kIOEQ}!t~3Ci19q$^1Nn9 z3wfHdvC9PcK6+UH19L)o!|uzg^G2VZqWHaC8YyT~v(2Y{8_*|+rufx|8mj8`3h>=V z;L7%b!%R7@14_7v)om)fGi{P3unzS+^8ck+{+re3 zwK$8f7EisJGPBoWw6)RaryC8b>ca%qZAwYOk6Hz9^36(P7@e_>KZ+Ah9o~Lcr{%?3 zYxu31vxu|^Dm)fxD6Vgkl9woc;!rX?Al;}TopgXMm3Yb8o9zF(>C_{w@A#XVxV5^| z+?3XV-gHjP4YIyw8Om_9sk1XXj0p7)>YAFG8hC&#WQ@ggr;HUq4GAe}e?Kz1S`TOm zM!LG#igEY2UOoO~P_b2a@Q$Afa*sk$RaN!L`k>>)XDtw(b#*Z`*&_!lX)O6Kwk$q} zR&Xuv-Z1ykBJ%ftEQESVTy4#t>QhfV5S?F*>^t{yd3-oCP%@b!c!I36&7yoU(Kc@_5-n8I=@UtM_~H;cZktXfL0N( z`Qc$|dwuOKdkjAj;*X*HIH%g8(o*%oeZ;3=7JLy!W5i&~F$r%p^ z)-KFoTh}CGbtV56*ULs=iP)}yJ`haQkMC7&dq}#}nJ8Be7l0>i`|Jg`j0)Q2{qEl0 zODl@2tE+m(#;$FzQIJRn5P4jbGaz}wbQZ>T@PatW)2ugcZYrIVlS?jjuc~bhjS5y* zd$U($!erU*fx3Wzxi+x2|BZWn+FX)xHSU=z#cvocH8xI;HF)}N1Z`Z0L^A^Pk2G_f z>f-}M#@Wu06=KTwT5e5^9%!MlkM}6n5x*i=uSq{E;r3zad;mrPSi`p!)6)~3lQM~E`Tl;MC}f#mIXbnLg~9pS`$h#|HtS^;XGcdqhSdm; zOfES6Y>zc8L zm=>_(hKG40Y{OK#o=3MPF9IUYYygC&?t(OG=uUGJ^M2QZ{qhIHr0bC905P7%yRDKM3pwrM(I|_)BDv;v;WZrTYi^aYv znE}e7BlQANKlw%Gb7?96JjqP?E#dP4J@WrC=d&ZjXY2!jn^pRTfm}z3^O2*o^KI}i z7ypl3&;GP_Jc!+i^Aw%QpTOhzRmc8l?>f1L5Z@zEkAu4gM8p>OAKJ^N2q?!RiChOk ziupr{E$@Hbxf~xHTmaBR`y;|x$mOTX2;$R_I3g(oxd1P!e)8FL_N0@(udnaOq6OF= z)qhNt?`*=7fD~@ennns-Y7t@K*I{={i;8p{9UadWfy?^+ciE?OQK|Wf6|{DD^M?Q$ zNpn0l^8(QGA%lZ&&%%a;Xa5$#M8ftbiSgALBog_I9WIo+EzAIX3{Wqia>#TbSR`l_qUynL)95Y3SSBSzrm*`xvOO^H4AR}bTUZSoz;E|{84{<9yqpJI zVm0u4_|vCs;O+w*3v__PL8a0wbBWZxPe>V|M9}&JDA~7}$VsP!|7~_qS}`mv>{;Lg z2xQai_9!_e4ccA znA-Of2hJZ5Wbs2FzK8$vD$f(s$xXiYWP?a6hfwfCN~@#4Y}#5Wrw5P-;L~G|uv

ULSZfr+K zS9~fPA5Wg&ET+f4g#KOe*WsiRV4L0YD}M7r*b@KaICb0whnkmo6zQ*}k)9m@-+f!w z9nuiNQDSm{9ve??_wfVVITJGM%!_mBWFg;VKLVjJ{NM6|0e#dsXlULgSM6zS<=Vi^ z*}=@J>VtaqcJ{v-0Q&j>OZ-gM&FW(k{|`zC8~y{Yj7a11%4$NzcC2NXj>5aAURZ2{ zF7zMR zZ)Qob^d`1sVF9Tk<~AKNmKhmAg6}LOhqhbEjb(o^Lfm>vGWFo6k*6g(1eF$% zKGdjDGAQZ_!?zlyi#E8_@=H58uS)rgtv)GvFNSY+u8Fr@6RV>OUnGP zY25vRbck4${hQMPFl|tO20!!HA&)H&sdvU644tcPMVXnh0IYq`CdPKpsjjKX41@N%TsDQs%UE1pEuxSs|PS!Lp zNq8InV|gm>+C?2xejN2PhYTK(%Xz_W*GM4u(kxhKBsSieXgnXfAl)Emsz1rK2TEsp z4D}LA%9hp`PcxUd%P?9)eA?4wE@sUk%CpRQ&MN7@g;QXf{c>>L_1ZF9< z#x(z>!1{HZ&^o^0_s?s{-}H~+5z#D-NBQY1QNKunPOKIl&?@2OO!=pYlU79-{-R6GiRVwAX^TR9m z@D^cNA{2ukGv68aPVXN#6)|#KJ`mr2Ysf7uw)kdxigP=Q3~?~99m}I!qaeOnANp## zqHNX@>OKuU?51SxMvp%`Y#W`%JQE7F`snCINF!~O*oGG#>|Y_^4=%+u&NajQXI!w) z{S?Jcevo+CTIM?)&Co&{#+A{(dagpVMLihKzc0A?BdP>3-8{6!2;&{wiad`E|JeOaPDIO1FFt5+&1>Q@!(hLdkcw0wO zeQKGIW_M7rYu;c`9a1_JvxYpm-$c@TxY4O!oeBR0AHrp7r2DCW5-IK!EuMB31?~~N zj4%Fs+0v(noPuIf`ROUULXFZZ2*N(#kw>OUFYSb$7GN7a3%OVOvoAGf{%DLYTQY?r zf0!N;rl$vQr_YV=gr|9YmgkHMmhwJ0?^wl}=~{Y{$UkBkSK4&=%y&@QW9?4qz=6J0 z?w@b`7|zE(qW7@oiz(@)!%ntl`N2H#@SjbTJF4!P{eN8bU$4_**|HQx3`$< zHAsj?X#zA|8%`0PvF8B6G_X&9o=~;E1)U5ezmEitm1&r06fAY{R6X`9Kctp~rB5sk zkLkE!OXa89HMM$g@g*4+POR09?FEnscWx}tdan;&t2fWF)sR*)uTa{y_0d>o-SmYX z4=bZBn&c@<{dCuzp@#EC=0o1?rdhM*e!8qxEJd#_P4_c;GiC4;z89J8S*cPoLpqw4 zY1ppaK60KKe9V^*uThK6TYP=UgZw=cW4-CvZz(oiW^W5Ew7j7nqu`eM;w!&6vi0b& z?}M9&H;-_A3q$o`T3p1ESQ&HXso&P^s()HIw7M^>Un7eXYavD zzSmkT*_@Q40JBuZ0_gZe94+cOu6y<^258Okv7|fC8;8nWfJapdvs{QRQC^3xM4vUyG@-B2^?u1v2mV|||@_6glbCY?S zhrL22m9L0GPZdHx5NPd}_{CPjuxf=~lew*`&I7WIH)@r6+g-uo>*v$bQ z^wF@y&hw+vG5-X0*O^z7CHHp`^O0_wbK&GX5t?DE_Gu{Sf~HL&6)*!cR^x z)qH(ztGCNK$75n zu~(@J&IxpLoP4UKYZ&#Rn0vLl80POcORxLcZ6G?vedu`D6mbOqQFu%f8h`R4uXuc_ z-}J_0Rw)l_|7?g}C;CLobpQJ``IIsPnxP`Z?}*dP;Q6?jFL};EyAmK2Xxw2Jz!DSk9g2jkj?Pc@ozhIR|$h zCiPXWZVkprwaxycVUe-)llf;@e%z@T4@sk^b3BDz)L?I|FayX=Wc#c#>>VWF`n4g3 z0#?G&OGokLqQfpJ%IX(0a(pIL&Ebd3g1*NeRpDEA;D>VpJLz$7?AY!bv!fyC;mYq8 zC>2edMoiO4LEf4Z(kaGGVka52OFG&~z%^;w>R0MXpFAeCx<`kP6~TgCguSQbvB>pa zbo&FD?R@JMRZ8ku{1hW{JSlg~-K`XZ%gf{AEG)hoTenKtNcc)o@`pL=#R`JiL%ZYz zeQ!ZpH$MD~jpfy;`jbMbyL$vje4C!a zm5kq)jU#-7BXKz6ozU#xgPF%sf6QH97Dy3eL|2{x~2u1D71c3R!Nf5=_*9;7t@dufcgpi=DkaeS+v?bBz%6 z2RWK~#ZD{VMhEA0ozfD6FUh`*%YSybrsJExQRI9R!s13VPZ}&}Y+6M%a7>HZ-U$i{ zH4S$cgs`O2RaJ|u5cbT|BM+l>7k^A>p3U}SWMp(7sj0l*Qlp)$(xuXt*|pO@Jeaqu zH(W##nPg!^B0?JvR!-$YNQL)Gv31yo74T6C3X_wSqQ30zxS+aQ|CDSk=$U&KZKy3~>05dlYU zdknumU$BIpS~37FFo-Vtuwn@c6(#HwzyR+Dak;!a)@~dE=?wZWjxy@RtPKV9^TWOl z&45mep9UJDq=g1v4I0SnDHj$NQyjV9Jy!yWl>9G(%L#k3E=6VM>>S@-3DBM1cl@05 z3dX0xM)#T*UP0rM6Bub@+ZfW?(Cd9?u^o=DOCk5X{tI9R74zKFN&AuFn;>M+)z%Yy z{=!h#uv%UTEKfXIMpT>k49`to$o_u~6O9=T}PgOk3ixk27}!*ky94bn)PTj27}=!!g3d38Ga-INe8^%@@fPhVx5PqtZY^{ zh-hU#EJ`V$M;fdv3%QH3N<+A*nDg2sdQu8pU%$6b9W~f}cjK%X8?==v!)dfap|!QO z3pBiYMkjcYJq<|=h%Y=#%6l>d)6j^hc|Mx8G?ae_P0XWz4_MRT$nMV>L}B@NDkU z7`T9!w^v95)TqEfN9Wp5`8E2FiYmVY#D+8C0&a|G^_+3g(~AdnTCu6A%s;${tIc^z z7mP-uul}uuvLHeSdt6s<3DYG*ZQV9jtS%~sFfvMFRwe4E`_3_LCniVlle@$i_ni5sSc=VZqaIXT$vBX&N`bQprh&By zaZsK6m|Xju`iSZ6qZWyp*;eDMcA-o7iECr(AFiDL7qyFg0@|0(ZF)p6tGRRJcce#w z%@vGWULn5;PC!t4EwT!gQ*8A?_iQJ7BFWU|nweVLW{-R-554^O%$oEV;p%@4GGtUh zbo)gt8p?8MGN0TMRNKCIfEgK~t5I}XT$Q-S$1ypYd{U!5PFHyT-ql%VOxQf0eW&{F z*r`Z41tzIOnq1|PokZ-T;wVP+rGJs3fY|GY!A`}_8MhkG%MGZ#- zoM~F`w|unH&%BhBANA{MhTfCHx9!i)e9y3l4@K4zq3y=T#^trOw3hb)Ju&I&Wyi-p zp!MG>qPZH5E3B;4F|Kt=&FBi~5wRcS7=13<`|&>eKrYzH)0BHnVnUab&UQS?ra!~9 z-#iH54Efd>v~W!Ci|IWBd2AG58FX9@+yJGEFi@lSFKAj)QZfc!ArD&5F(K2zMY=4? z?Un{}uNgB%ewp%G;R8ic>h*srRI^lp7PipcZxSQkw$v~^4&n2W_HMNNill{6nHGZX z`P6sD_MpS%?d7iv0aYcK{55#{yxsp$HTzzN>Oyc`a54F{q0v#4JoUpzdG_j0tz~SC z8$8O*yq0o_NizTzQOM~)=;~xH)6w%Px;X^9<*T5W3seT$St4%3CP!yM{}`*cYimw% z2?^KI&R%O-!4um~rI!&s0P;fxlE5S5_B(vT_Bmgb`P}cwSWx*PZ3))6d1V2i{T)-)uxVe(o3E_zfj~PpxM%HiJRm87#WE}_;F&WkHfcJ4OfjimMedvu(&{`!fM2y5C~mhzZjB) z`M#1=)THE@K>QPuboR#i-}AQtPJaJAa>98Iw??$w)OHr>1Kig{&frbI&j*1PdINOr61B@=#zRd$f#8 zuH_$;#rbe^nI8zzE{&jt5K|AQ`_EuK1?O~TrJXVEtWt^*QeN@D!*{NV)OKzkZx7lJ zl=U{1urAi=R>Gu*or!Tn$BRHGI(zSS%IL>cr8@aT$^fzF;&++sZ&`Uc_t`w;Ta+GP zg*b?h>I}M$ofI2=7rMw1oB7;0mz$zC|9-G_)eP6*73P9#t*3PQ=3Af44!`(SRQctJ zv7(h1d@ZY;JQu~8MMtw9PWx%Dr^V+oh1SV0>~DmKS*r+UNu{5R3wtnXh=FwkAb<%5 z#gR8^dS^E~mJqiKZUIE#4bTyZlQU}QC!uU+s&^hnb63w+q7?_ht-iH%DLRRRATxMX zSxWgdekV4kmbBLNHtP9ClbLcv=d`0k6rw4IB;-M}>Y!;J_fYkYeCPOM~LB zuJ;Xh8bCNt=&sJ-0zAn9|Tlo+B zOKS2&k$VSLoqRBRlv>?@i=lIw_}Ca`bT*Fjj(KY?CwIrMtS7h60co(B7`cYRw2ex? zR=6+|2&egL5!BdINmzame@g!E8-A$d=~2}LbM%v#BWYaoTBBOC?=L9+#{uDhc6_Y3FH$7jx3O{S zH|-G#F3?Rx#5qQ6>$^?*SdFlKG6hT&Wzst8>tOGo&uVC@eLu+bozM4E_FtPdPq4q_ zcL$Ad-bU*p*vchG=x*O_WU`rvlv_1FVl^w&i4b>k#8`=$o)So$G}uRPX2(PhO`v1s&q?Y_}~x&E3z9L*&w#D@>zv)iQ;aQ+sF3=?GlF>BaCJPgZ5 z%=6(^QcR}@X%eIhM0_`orw+&oK*ll-7Cz1{sFIR@vcN8Nbfc6I`kue&^36X;kpC%Y zYLfbcl+^7HOj57uVvS`8VwH}9iF+8Mau_+(;;j;PLcb82IhGU;B(!jA&V9%kEo?YlScX$RT2M~P zZ*Z0>uw?PpHD_{_8!_}g*?#L+y$nB0H>Ms=kyMUpE@eO66K&i&5EFL2q3A=jR7y^W zR1j}pTYNxe$}U2KdkpAOcZN78%QDlkExRqTEq(_QYNuQ%*^_(N*k)IeD%o%32k!54 z_^!0$mA#BlHd`|JnGFwQ4)4dBnxHyc2Lx2Uz1^P>CM2ZQK3?T385_Q1ZEZX!!U_%N%YEG;dI}_yI%d9Yboc0Pn1tJ2o89$sNlJa<%Q{=r^?SC&)iMDuBRU!$;U#8hL* ziJxCkjVb;H6hGftQR;87AbqmGyV(-`;pg_ljCjy|xi_k!6Xw4$qW#SN&HLSYtuh;3zYxT*6_O<}bQ`4d#$LAqnhh`FWrog~-o2A6+foA1EAjP~wp=`PK1tDK zs;p9kPg1FMCLukjfmf}ry1Por;`QTI)~fGpo^Z#Oxi(Juo+vcp*qK=x)lzIcTlFe!3_2Ei$20@mlM5^8HB)Is4vQKZ`AX%!8ROV zpILss!W#VLGyq5rRgjl=d;ekJG{VC-NjXTd0U6-_~rXUuRdV^*Vx3Fac`@^{^SYj0=;Jc<&&9+; z<%6cf;q$811wVsU-Mh!+X_8M1Dt8Zxrm#M#yR-E>v+Q{tw@@yZ{$EpP9}QI=#_@}C zNOW|)rHIIBs}(|vi76Aw(8$|lQz|cm=$sORWZLyIDa{K*l$XYsY$zJ{l@W{lcdxQIqVO0%}t){`@f2v_uo@KDAK4>MvH?( z-TS9YyeqsQt$@6|yivoJYbozI!rIP|4R5&SaUZfDs?^`Ktsn}Dd%OGY>92q)tQOLa zbm!RYnVjC$vcS#Qb;3B0kr5 z=d;a*wUoz>X6oAQK_0#$g@(rBa(UG5+p3Byy%7yU33r>g)NLkHT~LLr?Wz2;v4+@Q zNoXFbBu6dS&?#c(CbFDG)=|#c9T{r2fmThGrunN=;|>w%hf-wy>BYs{!$h@CV77uy?iyi* z_jwGxL1`hN)RJBXz3s}vlGqMkS_-SHttDdD4Og57xnH}ocB9fRm?YL|RmHVGHGc&M`peFT~g7y1AcJz@(fJjCRO_#=lFt!;pmTZE)$=@wEdM~fZgf4 zox1uV;2{%E={&mv-=}#9{%VEKS&M$^a4#}2I!pAh8Vwx29|w}n^0~RU3AgMbhTIt) z_Ed}$8r9(jwl|Kpw$d7#ngX)G)0OgN5G^G}hXF)&HMlXjT-D!oA8yLmP*a2HDbU~Z z8~o6!Q21tv8M#!N5S4pK+!RKhS3{V0xrs&a??ULHM@!RyL;J`Lh07Ks_rlnx;dxt| z;)IpJ;rxgmccjb*7vmzqL26GC-W>|xJR9@Bfj$B*Z?3bJSM7TbHbk3IQg1qZ(?OhtYBhc@bC}Oc? zXm~yZ2yIHADMGGd-paj1%O62A8F707x5Zt5a_#Gl8jZ@w;61dH%I%ky#F;V8sW!;t zc96KTvVth^M|-|g=ddGI2ZQ!|i`wy_A}1Fll@a`-FT_r79JTmgeWUPHot>RU6NpLv zZk-+KBhW#AGaM;+2uz#(|_cXM8fStc@XP{t{``$bzKG80ptSyux%|y$blCX!_R6;|O}t z>sIjAc0F$uBuv1|yA2JydIie3Ih!`p&-s?FrS-%^OHCJ;JjH^u73))<($hIwr^M~G zHHE|UU7#}4cS-_I$Lv)Pjm_Ks6baSRq?j#st@rFJ)8G?q_r{GkNrD_0zJ(p_=3J>F zRZXKWAGe~94Lblgpf%oRwbXLTyEz6u-=Hr#JyFC}mqaD*?J{UP!~|?x6-MAT%<{Bw zTe~`acrA#O0mtF71|ul>)l4e)wA56F)YQTIMbm-ue0474lV0a^<0UE6{$~>dV4|$^ zi<66Y8&{Ih&{Fc(GQ19%@Vs{EV)a*>res9Dl8yn0@&n;LQ1($wxnmiqOqK5p>`JQajkd@f~2AZ$h%Zj zuZD+T@!tCFeEGn}$r;0@18Gw4q<3=YU0AqdyJli-ZT+v(*~<6W!7ny^12yW;Xr_#k zPkv~WqZkUAvlV}ta-Pv9#Ud&^d8i}-6A;xsalotXFK!0Ib-}h*kSN;sJWL^TqTg_P zNce^EjIVIr_-lhZP6IPM`^T#NRR-Uy;@rFk>8tPQ=wr? z8E_seiEQr)?tjoFQPJc!rN4!CjhA?l%AFox#g&C@J=4U)Ldr<^iz-e038{QZVh@gz zQ;@jm5T-XS+b&GfR#IX^uUwXBZMl;X=C=2lIV6Rfd#5oZj^~pte@H z7t+5c&*Fjz(saU8Q%~g$Rw&QecUC*Gspe1Fr(Ew zuPI<7}lxN?cXf! z-hIb)78Nl$Di%wjTwDu{%=j|1e1CN3!>zAA11V~g`z4H?ur`A1TI6|#r)zB8P-CAO zJ(pA@)<Ov@`fp`q2RRk0Wn&z_N0oA9@z@chJRdSdqdGiXgH z<_l&iyTE)U9*Yv+(`+_fX<-{@keH#z9VTq@=|-^_b|e8gXYv4A!ITpP0_8o!_kcJO zDspa6a?Te1og2|Gl?fT4M&C#fo28W;Ixl+SfMMyZ&8sC5(WQz4dY*klrWKSjm(j)S zjKxp>Wk{;BM;9eYS8l{k6L4)lA9|Y>gQpy$^||1RRsB(gA@h@zoP!?8v*oX0K&-5( zk-5#!6=^(?I!_$Hx3yUg3PlJkRE$n$%^eIvW4pe3`^()uS~@UFjsB(ae4T>{gRVdn zZvEMW8hyFY+h)&8$O3K;Dy>Gs>T3M9?r+S8TcxvJJB!%?{~ z<85i&-f7v*cagHAthQ}ABo_&D?LCE&jlMGm{oZLb!Z5-c&7HB;x;9fjHRX$dcT_1xT{MpiW38F{ zkk{Gie^t_qT+*C=aOHAK`}q8^v0{&|bcQ0F?F}`!oFp>nKtj+rp1v$nt8V({|7@w7 zjCr7CdLF!s(VWDY2wrnb)Jzu`>Ydh4RJSSDaK5GT-L1eVGvBXKmGn+Kjg_FWES|E} z`qqoq-W#cDsFC#p(GttLRc5Z-LSJ>>x}1vZF;b|-c?bhOr*pgMG9_8F74JqP8J6R; zGhFW1AG|<7fFkDNx>1c)dDGh3N?v94$mfR^l`?EVuU%&clER`>?{4zA9$dUwjpQx! zxOUucywLovkZ-&99l*J~;kh*rqiti`z86hSQCLifjUNk*?KG*rqmNc@1q*v#xOT5Q z!}vw#eX&cJUG?i<9KcgjQX(NGHJL6Wr;y**n!)V1tS)y4+s@6=-M)JYUr1P+-0j+8 zV=>}s)r7)vnO`yLKG)RL#HNi54b_{ivY=6|2vRIkU0zwS9SH4Q`yf(oxa5gR${&uA zc{kHCvG$$oTvz=2jvM{sV(wF0THa@7W?tT19|Q*n*JfIX$G!DWNx?Jdjja_L4}Mgw zhbAK0>jb|T7KXUsej+KA#&I^(%icWLe3&f#z?(2!=Is!#TKdN&*p~mMVXTqv!e2Nz zIZr0ktZq{({~GG)8k<*;i11{>|FYz38<`Lv1q4C_b#-R%)F7ZtW|-qY&z;PlYU+#%$?%o4A|cpB;P9(B(JokzYI z3AMAu{DZZ5PxDhjjG1Tx>Eq&E5_!FN5U^<8Y%%>c)C09znGltJ{fl+pu=kUJy*bp3 z#n<)Dwa!?U{B9gJva%iDrb{e7DfM)VZP+Uy=1*fUS}k5f`CdzF^Owmo`9Jbs{S){E zl+jEj@F=m54QwUjog7$e2huFBLTX>CKP$&!&_gBInFk7U^V00blbPQKBycEDlD!E! zUN^Nn_`GEv(gP!mVP+&@ux3@Ul-K{T&p>mkpi$x!Oq@fwabDH_g=B zmlq4RC`8cf+W zie7K4K2H>apQS+hGKBA?sa_fx(*p$W%m&)rlu!dkGG^6UI1H0b|`s9`($GNccv#juRiXQp;o~ zT#PsYN3#O#$i41F>5u*eH;7p^>2m5kH0g$Mf&)o}OOs(+MGKw?BWEHQlzqXp8vig) zJ=_#2ilf%@;r` zk!>H(H#6=hT$HMqyN{jl`!x6#8@t6=v2nxrF@W=dE_NGMyX-Ll*pf;_2Q^lT{(%e_ z0@slOH$5Lo*+Pv9gl4Qrz}2mi2^t{6h{A$oAQ#4oH6PN_!FWCkn_JayIUcjGxVC^T zDjDE9F0$5g;zMICx@G%udImXsHOZo9aN2VED<~SVRd9Y>l%AH)i3Zu{u2>Yr^rE z#YilL1HU!xo9cJ?Qv_St*&K&&yr?gDCSqWCDEimy4!1TW-KR-UebBp!x!Kbd%84{B zu~|)RFTP<=iim)XvW2=@*~8p9d^mZC`g}iX$h!YysUMBPBouTW^yXac38wUNipkL0 zEN>Gj9eG6M^(3R=urft)V#gplr-^J4dnB_*#U^wTcmBveI|bcs%z%~?$?|GCVv=2~ zc(J=_wk^X7I!vXN5yz{Y2fTh;fnleT<>6N3Py)B`#D)TDv_>=so3RkE%DQzUlfhl-2ny&Ui1m z0D7SzZKLnSuPGjROBBlgq;!34zn>^ zw@+0c)kUWmBN?+MNA}NT$9P#QONRIx*h-ecD=>sJZ`;qZ-32F*Fh^I8X;Utd?hl*^?Y4V&N^TQiSMiZh|K*~6*+Hc!B+rD*UJh~f(Xze)Y^`bmV&{mFuE`49wAxb{#-j6>J84VX#b;KYj2t!3* zpG-$br>3qB%haQOKB9eDd$L%=FECJRb^90_UwuqP>M2$rqfc(Tz}>bMe>mBV5T&7GYw zK{la(Ny1-ObvJmKlGiDMC?&r??G6{1{O9cO7teaWK89YuHL^fRg}?sv_caRte~6Tx zVv_%xK|TSo|!LKGwv03dia_n@E z@J_w#;3z|GHq_O3cfsc>S6;PIv0R)5pFLD|Gce)7bB%BB+gwypNz=zOPK^#DuYXd~ zJT12NGvpXoe;Q}CF&-`)4Ur}^D{Hm5<(-pfZ`E!lOMP4tJ(A%@{AD!QM^+#^FYI|0 zjk2GSh<2+Ln-G(5JngFS0-T%;2H#9Nd&AYKQDF$(H?}t(u;R_-sQ9|n>E|Iaq{-vx z=>}7&^Vu5Zfu~*ji_0kYzIGy(04e*j1jG1f!!zJEm&8d^B;ji_t zNUkQUe0rd*#D}*T!SkJ*cr2e{(7$Cezb26*3Cp&)sj4L>&~l<%7L%x9b`8el#GgtH zp+xSTY7EiZsa_Ht+BuAy#^;+1p4~EbY;z=tS7Mv28d?d>>Gb;WKxqvxwR#Mwc$I9Y z%get~lPDP`#VYzl;Ypk7cBbNFgWX^db>8p5*Pss7!C95n+DgCOO&?%w-fhbl^%82bCW@OwloASCz16E8 z?Xx2oHKGTVYN@5;9bpvlrIsFK0Q01?HrZSu!Zq%6uMPz-9j&^1z<|VNc3(9@+(BxT ziPqWY`Wc3+h0@^DSxo$kLWyy?LG2>ZjA3b;z!JFbm4k8d{OMyIcZtsgjp;ZU?!6aY zWT^JD++3FeMEme|K#_%^vV8PJaG#?bzuIw2jP%c(V&098ht%LD4uAxCd7%^!Dq~M_ zl_?%_2N>1yDeeUPXZXsk1vtO8bGA^WaH&-HWbwdsTeoVZlX0iyCQz;YlGS)3JL z_?UVBCnIdkv4pG?;iL6Utv45QZ#eu_p7~xnXdPdT95=9Kb2TINfeU3gE4_hp3PC5= zBcT0j;r6Zlx)7>zPs%D=>3}A86afkS6_lNxy!$t#n%jKLk*O9a_q`QExnln0pjj86`njI!%KDsFCN%v zeC_Nqj}g+j3m2O34BYm_Tub1~lpuamR)Mv;m@X}9FVMN6gEc^7!(pEUriU}3jH?n$ z12%GfUf4%@!V3c-lGB@JaQ7g1%9y|c7z z&m_H`G^B)Pm5S8knNlALm`?T3NIQW+X?%yB%-a)`yK@NosdH1qidSl?2#ln|M=#gUm9u!BC5Ho(Y;Fkv=sKMjS?grt25w+=LseqN~njpW@c+iFY8% zGxl3H=b1MzHrOg#S_it%+yN>#^C9~J?XOEAh8I5hZoRIN*`Omn57nu_lBXhL1tqs@fPo0@w-tT8Q zd+B3ydF=yzi3&-VnNH#t7(5J9DUQ=TC3^RJVHc$gj8_G)h+b^$BQp=dtkho9D4j(B z)GpUi@T$*T;x2?1BMpSSc+_oRR+-LZ-)n93i5Q-MP)=H$4EG5bBcf0g$WEs6PbP6_ z^XQL?MMSn)CGO53rXhqNQ#RbY_D6J{C(&IN$}H(=2Ayz5g7*7!VGnzvI3BV^?6^1F zsr!=kjEq&UBb$!jd~HVA7|4iRfxxHqG&BY+o0nX@u?lw!R@{=`Jf6~b)KBAX_krhwfs zTU9C5e(wnn2B>0-4AA(eJve4xSsmhL4=@Ru7q@s;9d=cD01gr1+H#4}&w^k|if#E4 z(O`o3Ad$NfryopZ&jw(fwR>yZv~@H=Eq-313E)y_eM&)_Db*z0{g~-8-nimc2&`>H zoOV2vai9=P*F34S{RLwgT>muiMHlj(6nW@}y_)!jvsO*188zAUXhqF^u0^(s@0z?E6~huoSV(M9h+12K~L?#ttS8yt{5ujgL3!%zb9q(qifK zIX*RFy5wbey&|vMC7$O}`=Tnqv^{GMQ`<*v=OuEsRbnrYv+m?5mo{$$^7(mYdmvHS zwg`PPrc86B-AC6*4+Q+JRCdqL0Os%3r;`M!*6&CVTZ(Y_g^<44VN$=!Wq00ZAOM0L zjwfqSu99+R#@k>Nh?+7oIHf=r!d9zIBhdHp+X0*9rM~8=*wUjWw0Uw9Ng+k5vU{tf zmx^$$x9S@nvKbogk{`vpJ;FRu!up>};rC{$o;f#7IVSE-@IX(1%Fcl9S7oemZ`Zl4 zn$eo$RWdTxqVoASXQt56D;ZcKR&ju)dcD{U) z#^>ShX=OlzX(cxtd0^{Qp0@PD?|#r}Dd#`=l8(o<`(8_>;pN-5Iyq7}X^GW#*}bKM zCRO6BA2pM!Os#KPL66!|-AMl^FlHj^ae$yTM|TOxm}G}=+r=^r-~G_%ma&>OZN~O_ zi1~ihzo*}8f&!nEcG>2S_AC!0G^_5>7yKCR~w?^^CFMBHSLk@UTdDjc~FGZaWZOP=4M|zY7 zdGt80L>!QQSC{1Tpm(oyM0Ii}0weotlk>@ z%>mAV{hnBT&ZyQPU4KBycWW$@nxC@YXmt49irnaZu*ykc391MA_kb5qSb!v0;eOdW zsS?rg&yWkilO1u1*t%ODj{P)XFO&+IxoU6QwuXr;`@v%SIyh15{ALhTYsPu;DzTKK zR`17*?I0z(q7h1WH_2>NSC4P~kB_uNwdxCNn(-kY<)_?s`^iE5ohTAIgYrg&6Ltj4 zeh6FoSnp;oRs!ijTGBUAwD@cUk=z$=J)JPi7@wSH?KIW<0b!efTnGw!FCVrK5^c35 zJNRT>LLZDF7F^s9Ovr@nn2Iny+!11Xw3;5DlK!*}8$Fs%up}d~o$uB?NH$QgbfInn zXA6KE2X#77kIvgAPF$nFQRU#>@Mm)xcZ=@zWvEk2blXHpL-mnoYg;%fr)gZV@ptSW zIU;`Ww0&{N`g~%QIpG~}daaG7HrX^}!3i^Za3Y!52xT1{LPEFNHr4GHXl24>b)Q(2 z^ice?3)LEIQH7RHdoxP?U-;kIkGQx(cgK0 zLn{@5C#P?T%^{$}j#5n#k`XxY{K_qz*XS5gF7$|t_A}a0ewO2Rn5%V0q)^Y~$DGNp zX7sQH{5FBP5E~;-KXcSbMsxcOCX+CtBZ_sqVqaLg)i8gwZEEe~sz?g2myU^b4yy!E z0!mbQXU1)N$EEZ*9Jt!Yf_V=?TNrY>jz7%rV01&yxeFh_6Hy-Cm3_S<-#_GsE*Kws zqydtCK%AR%21N0xE5P3w+}Qk}w6#8a=}CQ<8QuB7qj<^HpN%Cu?uKI0K7mejjM_%2yfA zyU{#Q{e}R2BRwZJkq~Yn#rHTjX-w?pls=sW=mFI)} znn{%}%@md+$JYegkuU7*yUZF`OL#6=slEJ(HsE=hPu%vgBEoTJ)2J|zl(v%(VR)*DB`aAR<1$?7XjSl9** zdS^zz$UPp^@@0mrER#pe9sInyW*rwv2RZw8Q>9^zCvEU+4wXhDWz2oZYbyE0o8a!V zc28%5zJ~ow*?q9wiCbFv$F-{KMzHQB#+_|!*4e0Uw{tyVPOsm|90~e3UfpfzxY`>h zaq->NWVzmUBvvI}v5%%bs~N>49J8%kl2NJVqlu-d?t|U^WILz2Fs!uF(=8#VS4B7( zh^9V~Lum~Rx1`?%PqPfQA#@0MmLl^6M!4Hu&Ubz&T;|YM-ZmcPkHn#19gvm4ONH9$U+U41E!?Sjeiuo5G91ZvyIajNo?i;8bdiIj`yI=G8Ae7&R|1{cQ z8Z(vqlz;Jjd3htCAcM7a8HLHPM~A7VVyHzTX=b3tVBiIhCa&;!1i#DXL2llf(x-Z% zB4Cyyl)3*@QBT1O50m`&35;4cLyP>zuU?8|J+l)naTfo2o=~pDwOyTMc6_i~lLe4O z7!StAlxYELwAfXDRyRFc4c(%hx^stu6j#bTq2U#ha`WHtq_FyY@+pg~3IB?|h@92@pVpyp>@5q}|6TkCoK$ zhxAvxJ;D8JnCX1cY!&V!dk*Xf4z^24dR4mJju4#rL-B#O@lgV^PkV&!MTLL{P&tPS(<=`&SR z>=DQ9S@Y9lZagLP%VJgYQdbKqT+t%=pd4Q7E^ulnAokb+<#i z-~R09OsS1SO+>S!A`*;)wtHKC%>KiCucapML96wk&e|bHP=djFWSEv zsITb7w`XU(XhTHG>hWG&&6IGc-CS-({)e;6vTi_kw@6!Co3(=j?U>HYo+CaoY`x6%h5v;$cLR`7OlEND?)ajVaFNJoqT zG?Dp&2(D@6HOqUqLtX=en$B8v6O|wlk_}~eDw`vHWp^8ZE_;m|HqdNdR5GEce`Yu! zef;?QA|`!C1Ma)kmAJ`*N*p6;qSTUXmKaQ@1Fppn@YS^gP$dWf9Js-5DosnQ4?v5{ zL9z7+Ok+e=fef5{qo5E;QXU@6UROOyw$_C-SU8LM$fayriJ|f#2{xCj8vue|XB=03 zz6{;2xNilinabtKYr0z1+8mmqjKXO2FRC^tZ$CxqK&LKNLP~Ai&o#;!8gZStb4e=C zdvu@V+ggUJgG^e>*lNK>8+$eOy~gDi1g9p?w6(Q+KrY6e^THY5o`TCY-G?M6da(iC z$@|r^nppdXV!Bcv#`{?tt<^QJVTKYski(#=FHc5u-`Y^1?NHuc_Ve*vlayk2umkq? z^*8yuK#EKC3s_mUjTS>h{9&4m9OTRu%P<~5p#54=kB$4CB}yBs(5n0nvZ{lpua(|9`Tx5K6rKDZi&`gSrR!o_+u0i3l=u-ajM#`oNCy z<@Xv+P|%u;_a8+ll4$<_VUW(j4~niFIMZFw7dTUZQPCmWSml3!j=u)Bb%B=&RXZo7 zSj29#XeVLwprdD&Q(>+{wxHN2t``VJe+udz?@>N)-ZxT|fls^+7+m;YcC9NtCFFng zirVpeOj4#lq*fCiQYRa=g?6Ap`-l4RXWF>sA59;@j=N6w$!E`*Q|UF6|96?Xd^uL1 z>LJ~(==RuJCx&)c@DI=4gnm_YUQ;`}oq)Jki`|^dlvrs8SJR$c3px z(xLI?rYAOB?bi&>*7V!pJK9l}MRQ|0l4QF$0Xc14;0Q1t2GWIFG< z`|dmas%Ipn9mqc2(}sSTw0Z4hIqijnco&0jlxx_!79wbMk=x|{hBIt;t>dB*hDlGF zLO)G^FH_^P(m8ebpjj+5(S{3Pf=&g)mWc&u7zGr**z66mDH*0E3!XwOcE0~Z;3hf4 z-w&*-%eY#SZN~-X8W|)~kLnro8uFY`H8T?h57=7kkRuN$Y~% zSXMVy9XrH;X!o16h-54Tzg$SF3r9@wA~gN~J8zD+O*f2(l$S&2+TF8Gm)3r86~YQw z#el6&)!p!ov$nHo?d*&bYczV9ks6RSK`L=m$Wj2y{6!Y@Rbm#^Tef2F)C$y?@W%U^w~z(et2P5sba#_F<3Sy-~L(T$$da#tbT7B zwd>ER-AVfDCxJ7x+nhGYGbMzGX2sk8t^_-Yh&^R!;Z@80dgxCi3VO)4UIyzss@;H3 zQFfeHvT8T|mI~X4@S{o=ARuLGB6z89l={Iqega)3C1G^H7Rr zAT>AM3bM9sSG@v+itGVIgDH3YV@J#}|DFP6&&dG&@R#V1v_xzE(XXCq!WZ5`I z)#9`5UE$Zk;t?S24uvL7H_Aq}j~yaG%Xz}Y1`Yk$g7-aTIXj}yT7q#cuH?-21-=!s z3GkVc2;V14cYGpF#y0p5iHr{yPZ2?A{dOG5h+yXmX&LCSCldhABSiNM)Wj zma=W&WAaX)=tAoLGwj=G>;F$YI*1hJP;|l;V_2aN6km=-dXc$RDuPV;O}kp&|AO_*01;7%_U-lH@?ddxCK0jTuJJyCf~~dz_-Ze- z+FAk*`=Fmce@4^s3uJdcz|Y_i5ZcGbD`j?Oe~VCVaFr68mzI`Z&OX(ey9YM6M>(lp zmX~8MbdJUMYzGXHhbLJdpSEsAS0W+O)Hu7WkE8A{q=OH-cf)e4Pd@Jd12cd0+-p}k z5NEs{YiMGR?y)q^p8QW6LkXRC|2n?(`W16kb^+=WQy%ZNo?9!ie{?4KfAWB4qSy~_ zAFyVG+I$>TB_4-rV#b7As1PG^H3^{(oJ~i(W$f96^>UT%lzBq{<#nz zj}6Jn^v>(U(rd7UQzjD`D#)LaGcK1ulr@_z+iK3}ERU*V-#;UfQ&?D7AlLBuckph^ zQD&KY0OH8`O@Fovrw9vObJc1$-vWMJB$nPCkh5`TMXLkQ8T2<`s~~8W(%fJ}+&8I~ zJiRY|FGzPUEWeOz|IN(cQ!Mn0v%J#Jw!H#AtfYh8F>Dem_zEp}9TFusaOdQznLbiq zVuA&1IxO`zgw2A=ur1tT7Bw2mbr5@cU~%uyH&d)`yiXH)Nm-1OcwX zgK1_iu>&K`4bGm?TNWgAN4iYB@=KX+?FstP(8Pp3v?u?H(Ue8ytoMgOzuOJwTu5C` zj56!;#|kYe5{3P+?v6vi^b-f zuKS8l=t8LD-(i-Ele`6sgD)?g-QC?G*qjfEF{u?BGWSBu!h=L?I3B(?H8o9{SMe2D zy@CnQK}ARB7ZK@ZE~fJ$^1Rdu-c$Q~^VSTr(efraNu!|b7M6Y}C9Evmxdb>l=_oGN zn=tER=5X)~^;yJRZg%#VOE3-=b2=fCQtW5DUwmyikpryox_Kvn9_o9#faJ-ewjxuz z{e$TkM`rh9f?<>6?|dg%mDY9z{5yp6CitnH8R%Cddw8&WnmE7|6#ufL9J(-d+;Avg z0QF)HFed8KiKz3Mw0;R}$4hvlO(4p{TvIQKY5n-`jhn+Hh}G_9Tmeubyp{e*zE{Wl zO*5x>SMQu+r8Zh_!1yAz5GtwDXWaZ(;rek_Zs`PIhEJgxM*Yz-Y=s7SvvrI*mUr(q zf5vFe^@xPvJOO$flUx@THmiV6RBy&L;8NX60MlhC7FUM)8bx3QNn<` z@G>M+9Lpi)-B&}`=k$^PQ*lJGXo?AJHV1p#FTZE11N9wcacGDjxBPf`$XM$UHDuP2+6}6ruhBUw)(hA9zY+_ic5hA59gIrkGh>uk?I@yCR}s&j{GoV zWQ$MRI-fwJ&bcizrlo15!~WA-Im{f;39XCl_q66LJ75lTDMh9cK+m9AqiQ6>QTa?E z;h48jS|F1JzkT}76aM#?#Y)YBIQwP@k{ElPCj*ml!kwn{Q-U8HZv z)SDMbEwdYf?-SF|e*}Zn9LYLtQ{iKe>y}P?ovK~NogD@bde?+Iml%mLf4`{k2AMBSTr9S~4iyhhPq$!OPudDV_k z3@U)41mZ1c1UhDlkeJ-tb4as>I#Sl!E7T=|zF>K{Y)W!l)6xG%AQ~>-zYy$Ca(Pbx zFJr~wI9Pb&ef>7}>x~A{=c6@yA*UB@VM$*$B9HVp)ZU%G5#NFHik6+CkbG8w!yfb6 zQoc4<-2}2-YvaHXaJkm{mQCj|zPQ|I1vJdkytpW%b>>}1Gi>r8YBelXumqNKUohq+ z<6*jb^m)2{VAdr61EUq1DL(~PVKs$;MRVU#E)#B&tbQ9`F#kIzgXTIULb2&tW~waI z9_+S_h}OUkGf^9t9cBBDQMBQC%P6}N&6Wry<7;$EHTb}DVGvqo^5Kj859D5Igq#fB zQj#PC+rhapTO&CtJ!A$Pt6P?;sGtLQd0*GoEDc3|9+kPnVxkUbPA4fBPG4BZl9 z#PdA}CA#yGL2HhG0kxk6g@vsZ*YDRoS;UaAFftk%L?xxk2a8xeYr}@WJ5w2Ycz9^0 zu5st%>nm=)_{3&b(nlxVIRsHytm(W_`E%DNp#&i!uZTwL5HFX$mMkx>m!LgwGlTOv zG=q*qU#>=r{z(gU$sFb*NXqEG0z0#-K(}ps-**W5-svGU$)CC)C4oLVJ0oXeIu5D+ zEvle0dDu`23Zn04o1c2Fk4b3h^G7Sua0JmV0>AS zNHrVYnRgPe3-OtM!TkF%yxS{2;MwmF{!h>4PmBNS&i>askaO-VmUAL}d~KK(t9yHr z?Ey$7vVy<$^#A3tLo^mxWdeX>`6 zdT&cg)n%Z_%p@8V@tXWvi%LSESnnZBQL_K-Y+pA_d23d>56q$@E&%T8Br zjpi4fLQw7_ERT?Oo%nigft0_n#%_3@#wV)y&s!aj6x!xsd=WchSW!M|m8U_<=sAaS zQ@Qw_WJB-SzTY2BC-E;w1q8AWA9#xTkoH-2Tk!Y>yT`%PYX)FNce4zc+f}aexJQPn zyWw?nA|(3gaPM`)>|_|-LzV<5PE7V3GKe^&Hh5*oAe<$hh`w1vxL`6^~eqNME za!J@8)Pm+Xoh&y!hCp*TskW_^T<7PCd|2=OBcmb zl!}{=TtXH!dTFseGGYw1I`xPYbi3;2T4ALZTIS@97_OsdU2H7GclAxCkE{rr@3^GW zJ#kO4d3!^K@ED*v8_wmB%cXFHNsftF;(TAkgzpdM| zeS8$^bMdS0hR)C=KqpjKC*VLj^->OPHsSy{+DxstFjBzgA;*D?yj&N;%6|7_U7hQ8 zZr+N;44HM&6FL{^9m7d8aP3-C$F8#H^7O*_{43K2_m80I7=Vp6!$fbrbJNQfl9!Ao zg(y0w1g&e+SgmI*+9>3f%!+l}y5tt*cXuSp=#o1!&9wdS?3sF(h6d%7b;JRuq z8J_ZA2ulr4wVtC$_b_BnafHdc(}(u*%4%@XaYiWN1(S5Hzvgn$V_*5%s&McQiMPG4B^7PeUOGxBb?z?j=hA)-)Tj<&G)fm& zRJyW5HkjD+T8fp%VzjYF7FNG``E@yP1*UMrur01n#kwEW)-J$qPz`8%PcFR5>Ml`x zj5bK$oK6b6!DP2Zyx(wbj{H;J@u_C^XpQuFSCpIFYnk=B!qN!??LXnb|6CHG1TZsR zR2jp;7~2~}Cq*;p6k~pSjY=^N%DGlCL};y}m`mEKK?f~|zmvl*J-lkHnV|u|LF3vO zl9`Z_EEu1XUIKxGO?bd)l4 z0v-@V7j?34s=`4=bIgw3o*4)sIS${rxOQ`W@g#f?_xW!|U(OvBxz#ki(u$B2rICHK zw`LnuUlNb>s7k6WE+;MCpe%Cgvz^?PVV;=bW&AdOQ1`+ER{H!ULOFXFz>N*sBbA%` z)xYFF6X=PWxt+q&1gfb&+@&=?c zvTr5V*PJy#D$=EPhL`NMbY$wxrZiO8P&!WFet)x(!^~+6Q@F&k;J(C1cg@cnnBhc# z5LvJk0WB>z_d@xs&~?*&gUiTz8_CILHFf!&Re>>*Qqf!ZgG68kU=Y*<++S&fqub`^ zcGUh&A_WA_-zrI?ysy(GKEa|l9K=9jz#3}cwOJ7tH0Nw0lD;nva}h6DIThVvWAod2 zyRdc%jJG>FwR38oE@Yo`zs5{u`PtHcPZ)FH=07k_u{yfAIvv=Xc+o*(C_UKG+Nw-_ zumTo?2o>qb{=wrn?DRawC~^UKP4}B*kQ|@MLT`HlTPAr?sy@oA{qPT8hQeWag9Hm9 z1%r$O-AS(CS6^17pk6!?Un75rn#qo6IIhS87rxxmx;4DlWutGmf+U`V?HZJ%7YPDB z*zIqwX7u}iNRY^otasgFu#CJWBtL9)+<4@NSh4n+9w^Xt+5oUOLp8kY@X zL}3=nxyyH<4bs+PcM!G|8UvJ+wCi_v!qGmhEvxi8N1u(7Tv}d4)LUZe4RR$E7N3If zdkbgpTc|Qk7l+=0@Iv1Ymq=jgm4n)!nxkeu?;V zvzH7&zMP+BRrQ6U3csoKr_weqANCxF0drCo+Jd<>eV!IQq&5k(9$$|@^5`XxL( zJj5Fs8vU6HlX=r-$_K-H{;jQzF8~QoNL5ueVIoq1B=K9%)!9zcJChL}LJi>Y@v&>+ zKd%{EW$qi9j_4suQzVHduvxo!^dzv)Wna&^O=TgJl=#YbBn6a+uNRUWTa4vO6Tu@O z)Xxk3t4Z0pkH3Wy)o6KhdBn~A{NIH>7$>9u6bl9Z`q`9!`vlAVr+WA@=g(}Q0GZf- z%ZafCxv&q()J3j`6k&E%Rh62>jVCWUrPQ1->EjQ9{N1*2AH7D|hGhH%oT4Mnz+}+k&Ta)h9<%1evKWLvZ$*8Hc%ZlcGm0^c`F{ z?fm+!h`-jI%_`$PGpllD?sDr;wNF<&SM5uze8o}{|9q1HJA6#$W-Tt2!4N|a1#j>} zF3rZh2i6q_EYkGFbCqQ0UuulW4J3oS20F_Pt$U#-kEdqU;8Y;cSQ?#am3WS= zwrL<@$}pX*AHbe+I(+&kTD5mwASzcUs%rI952<7i%t#LzQJMq9gC$=|EA9P!K%z&_ zUPDb4xno(y?j>uamKPzVG;cUKl*phHgv17$(N?m5jU)d6pifi5=Wt=VF(aK-`^}v{ z_;{-~@8{{qN^j02{}**{9TeBsZHtl+AOsEWBtRgzy9W=N5Zv9}p^-p<;KAK3xVyVU zpo6;ymxe~Vfw%LW^E>Ce=hdzE&#St1yC`;3wR`X0Yt1$19Ai$#LQi)gZ($5o`*St}OBISrAT zF7^-!ofj!f`QhzHnx48y9!#EbThiU77PAujocsJist(N&r2FW_UOG}X&DLt4JcooH zGn_lAYff(cgdW;B_Lw`u!E}Y&8`za)p7Gn1I+Fw7snrMbx;;n8iH75n7$WDBk3#1e zK95Fvq_TgE1to*Y8g4|2Fh4E|ib+L##6IIQCaTx*gZJ3d>#r5Egj-k5D?(!K#wgde zzeU)a{G{^!$5Q_u7h~S9Eu9hF-tYG`T3a(VR*zs=8S{ub`2(U=%M zHoJu5@rvRDS7=Z9(kNXnI~gAzaAm$|Tcvg*ddLSXc9-J|`0ZNq;uiKXE>zQMV> zY$-}g1jVD0>5D#;m}+#Sy0$R-P`RA>rp}(N_Qf6%u-)V)zF_VyH93i6yc=P}_1c)^ zkCc4~Z~I@G0xr2#|4+mUYHrZgaAC&v(Hqf+T`c0Y=HMw2SjJ3i(xl+OQ4X(PA4mak z32Vh5i~nU`>;x*W$OP3HZbqDFK!%(KWJFHBw|y zR$fzRN6VaoEpWS1XCQ@h>RlP*1Ai#T5meN1lrAELk1v#(#V_pFxr7sPkwi{RU61=pt?D=b%Mi{$$i|Xc zo6N^kror1kSlA?b~jL=fnv*vtub zq7y;qo{`n-?mfEMvcAdr^7@X4fu24$CkG(_2ogn#>2noOpBZUMQwIhhhAdPY6%-b_ zSv|B8itrWpA1UvQv_sH zLWNt;?*;gzGOTV}zf3YvtxE&g;Qs4#y=+kF%BVAK zdkS3dm~~x`$`aCid|W3Isz8anymPUpuH<#@pIo1$m~O{t1xUS$)8?vo@**^Ai>#)G z-csoSNTluhKP#Ox=_!(ZU_9+Hl?<_0niObYOCRv~i9Log2I7jnqrlsDNS{@87(Z_l zCk3N9%5-G}pvbb{+(+^KbxjhlRJy*FtMH$7w5ICG#YvaBb1Spzc7q4n1TZkuOXn{R zTN%=Bpc~`lc)}p0`3E<|sMU`weZTF!6aABUPrWv*X6tsZ=NFd@eS@9;iNM26fsFUN zIo!MTWh&%`g^eA#JI-3ox)nVoM)i;LkDYGX>*`8i8tztl>U%SXB_uwk)t^9gKfvG$ zK5L51KjZRy*p&GZH#3b(1Z6g1tE1E#vyy&wnw1e-&=e{0kEipl>K{rWsTZkFn6t%Qrre)CuY!oK5yXVl=r%ZGPaae3qfNT>uixc z^zU@mD(l&fc+Q*JShpjIi=BI}mCya8_$r+^&CXbN=OQeeW{%4|kAp_%?6?3yud=GW z#fIsnnPH{54p&}{3|}0&Y#02S2VZKp6LYkhmr3Otxk&qtmm~Yt8#fNs+`ogB``#_P zn-ZRhx^s8wLWy51jH<8n1k$ZC&>a-^e@eJN1&K|4($#>5wA55fmxYPTTBim3n88ZH$LrMs9q6+}+f8?Z5ypOG0L7dYL_GL>C3X7z2# zw#vb}l6qAE%&9N_%-X>m-S9RChvE+0mXMA>Yj!3wmOtBqe&ais&63_%7kzdSfpWHM zfl|4%{{*4qStdTL+`nCo;3k9S+x&Yd->x$oyJa#A#5X-Lf!wZ1%qnzVx!ZSLz0a6+ zOF?~7;vCaAx=6jL-A)N!@qeN!vW0Pr`nq!WOvd$MHjx*ZKgh#fbZmYR0Wk4Eo@FCi zF_i6QX)I-?>YJzmPkcHrS^tX8+14Sh?{T@6-0hdFfk}_kozVHp?Tzf!z93%Tm?Tl% zZoQ{tkoHz%T;%plw&PI9=D2=!3OI_c8J_F0VD@ZtVkE}R1wYthe0z#`-(}sz!)fyc z;dL$xme_xp8GGnK02_8L_eCV=uA|S|r-^~g9XssT-WXSIA(FOsXFHOO0NFS4X!ms6 zXKCb^YS{p7d4-eK+oa*bz9nekyu-{2@w>Z8O;jC(J>3$n-#yx0!93}2Dg@(U6t|f9 zLSmErQ{6DR=88m%dfiElZ{!o>-ggXFJDc)UJ?Wx>i%7YI*$_s-!;A}>VQZjZHu+%J|v&If#$XB+5;j?3z1ZEl&{ zRa-?i`)qG9K2WZWIIN{jDpF2bXg4AbQV!DKETtBuW%qp!nEWfVw`B#3-v*u0>B zgpV};YwXBTFe7OZ!CXCxHuN9S_k9|O`BomK)%XO8 ztH8BvmKdMY$uX%yto4A4c%wb2o$f}y9pX6p)8uvc;H*8mwofSq=JP#7ux@fNhLw`? z3ycK~ZTD;orjd62d`pzB&5NJRc#p;PADPs${c`zAZ^$nq%yH$jTd$w$)P?EubqAfQ zM1QPK7$2(Ty^3qIR0_78Jgk;K(R(2tB)>AOb%D{2LWWd+700WaBLNWY{Hlfe+*`;~ z$SU%76MS6iP+-OD>n4Its091bqWTt_ii})!#$@$(_Wxva-E1g~{z(K6Cdl|4Lo$iP z5%br&UlO16s_M`fW543JvSfRSjFFa(!NhncTv=^|?JR&wf*hq({2$9v+CSAtkUGZ1 z+&9#p**|9XtfSY5E^9F1s}jdO`WwhknC7ajk=AsTp2KBbP@Ddj8L=R=JZcbK}Vso6F?tA&Lsop?c?47BJ$#H|B8J+Lm+xZemsCR{kAatJO}?8~B0-5!(tNxd>p!#V~p zUN&*nnyiM}F0`cY%ouIFpkj`-7h-IPHz8l^JyPzJb@FaU_R{esR1#@iw1KW)5@>o$o66hg_NPkf2oqS>;Iq7k`t zYyD3T9y0slMxo26Lana1#m=*;U1q<-TOvnB%ooOe?sD3rrQwkRhkT{}zJja?MCh5m zSW{UoK?an`5=s8p@l~J@wZfjspieiB(eSU?>#X{{{;i*gmZxhfUvcAB>P`llg#1Y7 z%y3x~NP@BQlXQvjz5lo8tX+3zGU!}MV>gjjj*)<-$f@Q;JCj-l7C(+A3 zz8zzKCp;G`efXR}zl$)rSM`p7@&A{sHiV`lQry~{AX6y19*wNI-4BG?B|kDwRX9<# zVrtrwFRIC9?-kSal>g0rAY)Ru$bgT7B!_m{U4zII6jq^IVDT<;X7}Bg!xLVS?X2kS zax1i=bdcJTI}ObR$2zZORPACemXZ`S1hn^mvOqWBL5 zT!)Pd&-cvCb`Zg_T6b8-KX(Gv{i{E%!+v)(@i#!LltrzdS#0%(!7L@IsPs6^M)8=& z!jTG~HzS?LyHZk8!u+QHxVFWyzYP7bzJ`v@@(G(OZ~>Sl7r?w1)t&!-bmk)y7FPK0 zQ?Jm!9GEG5OkVGmYU=!0vglW$c0=#b*&0_{q{K5_AM%b+uRo4Ev!XtfYPQ_>fm@_9 z+O=x&zjEgySiA#P*ZO+JU)j0;e8sMbJu7vMm)aimKVMj%`_vUv+g)_%*4|nfzE|M; zlz7DI^TWfPMoz<|>_3y$>Khcx*~-0xU^LHGPr}v3R(yv24h`PAGM|>Re+K055i|kx z)B{&u9W;Zx4;;WZ>VrmZwPEfX!p3hMsyLmBuN0tXe*~ip{BK_u6y%`7{t0~03OF2| zMG+`lRd^Hn9Yl&j%&}v0AoJ|due*GG{76}799&iYPSa7yg#}J8N>m#wn#h_A?Is?Fo~?I91R zwYNRcp}Vkbw%S_XHh1Mf+mfQ&;B^R0v`fMaI-TKiXO`h)NtvOJnB56yyLq@!<7ttB ztS&-QpMsoB+is3m{@O+CL$-b7wNMB0x~;)HMv8-AN6g>JG4%(8^qSE82eVnzM-YiM zT#hRCV{00|&vG;KA*VZ*yBi#tTJyJQa?n%n%OFfR|%3u#*?yqYpq1jrIBW(J@mu zz796DU;bLYJ!>PjSY*`o-9x;s>WYG~I#)x(%I*&GeQ&!MF%fev&af`8a=Z2}ks=o1 zJG;7%zl`u6?%PaXG+oTeXFFd-Ws;@yY*#PbDWSl;bY)CX>OlMv%3VpN5QqJcHssHc zvzwpx&XO?@4l;|?*ekyMdDmZ+6F&e#?+=KDDQiTy%lpT1>3s8cG4F=&!84^&ukbOy zM|x4v>FY`kkzz|X;UwB6fIEm)%J79QX0ps<*!;6HPd^1LjRmWBb^niqvwNuq)+oUO zN8+6jrszU^nfN@2?`Tlxc5$2x-9?b~@emc+pf*rz`;zVbMtPmI<9&Ec%bqOVj|sD` z)}U;P6H(`@|~| z*2;|oI+=6V6_TJT_-jQ|1Y|%NwBZAIlWG7lx5)7(WMkNHC9>{29F8%k=Z?LX&bldb z^cM4i>vC=H+P3u!4|(lo_izo-{vF;kQL%6|3)f?N4~7>X>Q6c%hKj%s->yvU%B4T@ zRt@={J0hPz$#Fa~+7>4N=HR0mEwE~ImZ%4JgnflqnWzasq|F^o;%h#M$nmMHc6k2nshM{N<^Fp&LORb}+FGqFo~`rm zYx+I>q4YZXHO5CfH82_VluPSDl@Au6jIT1Fuw~6>AnFfFA9wW_D)YfKx=*EGX}{)C zcp?_!&goxt{-+l}04X3yDP!u7R?PVhJqnwHF^~Fy0M9pR4nN7_%qC))(4jq9L^^Ey zFhjS-Y;yI=BFA5-gpTJOF||A6HE`R{28VN<1B0D(92MZMRq`gmNyjbP4>ZO`rj!Ha zl<>G^3Yfn_t2-@q`!%T3T(A>0bVCdB+`lZd+e$Tr{qj3%WO#XAV~x&q^WSI`Eg))IRGt89zZb$r+7?_ zh=B?g{`|N8n~)g+Dor7>$4D^uuF| z>xz&G{?MWT+x?<+JHYvS-GzLe5-QR7?IBWdpAZf`okox1x?D$@+F0V04=ae=KuH>b@?Al$SA3gT&-lYsc#Rh)8(%D7iu0k zt*K5l*lR*K7>`xrE6DjpMvn%=zg3W6MViD0HRa$ItmkA@Ddm!r zq!Ny`uHmUC)oK5~X`BIaSu(fZpEQ$ZcUeRG#6Nv{9Z#!xSmU(+PtVKUJ|5eJ=|4Oa*v#^b}B$TdHY}EmP2c6Ka>)T;?xQ=^syXjqIdKaBs%eKnP$ zxo&iJRS~uPAV8{sx4KGAFZFQ6+@R0(0Vnn$_4$`O>qw)F_H${a(*q~h^icM?s%^qL zA8#_Mb%lQi9#`LQyWfcDDx#~OtiOvVsvOj?qyK>&>uaW5Dt~hH33#PvOG!dK{;gF9 zT2uL=?3dH5b*+lp*V6CD^udKxRGF&(T>+kvz(M>K-8MGyi-1WN<<>=ir$Mc+kF6lNT^Zw$gSGlxvM-6WZFXQ0F|1>C zK5k}4sc9A;`nYUzW|<0d3sWn*$Su+1HkXGlVt&ERo(9Sw6c_UmtHDJVYA4Vspm=Rw zDs~b~^;P@x{r>e8o1|oGc}pw$%yljnkQN>2YZ7!lW_@#B)$3~O$yk*E8R%(=ij2QX zqaAQ_BX5ksf*fa`RlZ9U3RfjUG&W7jiS^ z4`_(O`U6|=xw-9@mbY%`^g)J1q{&ms^^`e^24|;BQqz@s2)5|RsM1vAP?MWoHvtnE z7Yk>dA|=Ar*}8dl(ai~|j_Hj>%mAhqE{p*fNAcrnEiF%UYIn>97;w*sc{ZZNEF}|~ znLWO1mo}?N=##FOmu*LmRU;Zh#L?l>F*q+*!eqM+7VeJ`R7AYo_~1P`H5OsV_{be` z#`xG?=kKrOC-Sgz>JD?bF~G+}{6!S@qs33SP@mOIpOw%wH$`a6GM&ErFFXe5>F{f_o=^a6-P@?x8B}lIK_pPBp&PH!oq-dHw)T) zLTvnL&gi1Y4P(UjtIt?UJp6}0^Q)Q4#tbk+gYxpIXcg0bn`}>xfl7}UK=Mzkp%y*M8D`C(V^lhSp{qp@8_L+Rw%hI(wS3C%a8 zq9Sco=*75wo87yPzi?KcF89n!`;5X7zb^PqOik?8!a*|`O32Nt1w_)vo{2oXh>jj| za-q*4U%IkEF(`43&vW%WvFcJtn>J=H!d+qiIP)CD2F27P8<|;Eh~O>UCpuj zOrXblK}2&@mc2|a7|oo7@8hsMv<;l=X?SG`j75!a?T{K_*txbFH-hNnnSVUggi@kS zpdouXYSYmWfqr_voPjL5<7{gPFEUF;zZe%>`@XbdclA$0H^u&-;rW;gJuhLvSKs@3 z;;}AgXN0(rlAu6wXHt@%4}YlB`ZnF?4PnBsyC@qw$V=UC?$=2bQ#p|S-13+5w9TO7 z{R{`;x^ifdO>fWH4`CxCCpS?$UZ7Dm>W>0fE-$-fJ7UQ@; zn^xAs)K#bNUw5Tu(uTIX1&f@|G-MG;sDsrpf(>tabV2XZA7K6A{DLWUi_c{8tuAe~ zh(lqZNT|2T_IFY9i?^@3LkzJIQ#K$CA!gG*P`|5H$Uv z`)Km{TWmIw6iAD%U0@%<*w%F#iTW1}RkD{GZUV%+*Uu~V=fw3{rRyoFTm61HZ|9L|C!|1|=>#jpS%Q|4;4c zo_RRpGm4eghE<<#3QBA=J;kxSx2G$*fD>jyZ-CVVHSoHh(oC>DDGt0MD=NDo}i5q29iT(-Zs!# zM$DIKD*5hL*`DE)nwmk5L2}|-vo3)!JN-(ztqO=HHEheLoQpR2{^+^aB)ViT*=Eli zFv|0*W`V%c`0WGwh3CS;FR?W62=F(sa)71rCA6=`=FjP4BYba0ek7_>9sE(=D!MHs zQOY1xyyp#lkzAb-HV?Y~YHK1^-kB=Q?a)@h5GK?#MJMQ}Bs4cd<9AE_=yB1?G2rZA zfl?XQBB@1A9InWQxZfec2ovVL^9j5lWcEteisZDWO zrHq9NyK>!@xZtu5n6W27>D6{2|7=puB1@;`s&OvLXULo^>Qq1%JSGL}e8}a=E!Mjx zFd#M!rAJt#r^h>48epGh16LB%1?A1Uxn*R=S#u~Lm=e)tL@AnB zunM@u@ne-L0Wxz5w&BCp*0~bK{HZrrB*-GkjOuSKwFw0C5;fcr7CxOP?%rRbzISJ9 zDzA;pv%EG2v3UTYLLz^P|F}GGg1}%TDL(GQ%8UHpQdGboX0*B69dn0cMVti8IPw|y zSVx!*Fd%Fr;tRfcPPBVHLx%DDm_baCOF^C8BBl!PL@Aa(U$_#D3$uB1iM1KptLc&F z&wz;&vnX`@0ksHVtFEB?dvB$smUxrx=YYWFiE-f6kZD(!o~An4%X(CVlk1c17vv}| z7tho|D&`tUOGEa4`uaBSldut%o|(hhYv<+M$8iy7cqp~Mcb;tpwcJ94wSHP=XG3dE zA6)B2y7K~`2e=Q_=jZ&Ukb$!+H~N7{Va-`dnGUVhIzAE_)WNUVo$qVyFETjy=wgflEH;g%Q6k~7n( z_Qn!^4_)u*xL{h$`ZX)o@bjl^VhL4;f<~4_>8~%6re^@tgXTMnz|GB?ysqF3nY1xD zFTVd4EX}|Kuz_ z#d$5M?+Od?P@XsIvSj=#Q{`u(MkK>bvR$7%6bp!l-B_4EJ+^;V8yHhlL(ohLozrppVbjMD&2chW8JIi{eG&0O~dtM3HRcKettJ1Y$~9y)h7L+mDe%z}bYl3gDmrm}Kd-a@-Pz*#df zyx;iN>AOhs>SFupu}OX?r)!zqXN~Uov3c3ffkdR;?SX|1(I;CM6UB|08E)TwoUdR$@&VLBQve|}FB&W)mF0hTZ>wnBwYX$OF zTn0w|qV^0tuxb31Ov(IME;l!5rHS=H;w|#og1CzdCn;cS0J8XSzSY{w5}F90je|4y zx}P}#^ETGT;F#rHH)EA0@~~$dG*y7q+`^P{a5SQtFt1vHg`0)7KFkMzID)!u1^{d& zFs#`xDWo14=q~@lk$KXzH9ovkaKX=4uE+G$T+)XCj?WrJFrdz=;)*j3f;g@i@sp8S zZtYeGmi&=c&7SH*80)TS8ls^x(DGQ1kCpvaHzksuDd_R}^XCuN)`ud*$=`>Y#G%U$ zh<1$QajU<9M_m-?FxAa5ta|GHGc8w)+2D}j!S(J8-YHe~@gb!=c(-|f_vmb&vE zpQN9hkvU1WvHjNPUA(W!hFmUvOQU-h4=;$O64zKfI@DBSz3X)*+uN~guf8QE072#xljtC zB5us)o0o8dpJ8J5EX>Tzk;9WkrMX`}ga#d^SxcLn#>L0=T5Phdlk-IWj>Bm*HDfnl zU=wj~yHhrymcSDD{yY@17%XRP&CrlEAo?}-;9v!>;#R>;z^kn^oT+ca7Ho?_`>c=c zWkJ!ok^DE^rgW!+gCAK+a#Bb^dMrxLM7EU``HuTawP>&SifT~FqW_>^8+Mpo7@%FM zs-`9h{*XNt>$J2ql#oJd86u0Q>b$k$|;2L4_0s-iTH1II}5O#mx* zVplHkQDCX+5c_nn_Y0Kfb!Y zzD6fv3-GsJ9%Ni@ys%Wl%m<0+SCts)n$te4*oT*v3ScN4n?<~ObxwlJ>kri`7FUGd zKdhc=8vJTxsH7GLn*vj3=`b(yod8G$H%NeAg+_4K+L1`eon@pt`SN_gWZ>%GRa91* z2c+p}?~@afoZXc$dt?j12uq#%Q9u$pUmVRqzQ4cA&LEr#STbL(gF#?O4-n8k9URzI z@{%`@<6!6r3L;<34-CqFW6%zAYa10@bmP^6nW?GS+FJg(BI-W_&#AnJE>-@l+&hhn zn>(_k^L=-COjawZ`5C~Qyx5i)daL%QEcDN`tJ;8d13&@)TVp?ciZYx>OaRLug1aD@ zJV#iskcsioaa>y#wl02&;yv%SOH*KEHq-d{O5=E;r?$E4le;0Yzwnu*=$2Y=9{_>* zX&EC_VK+kv?v3^R(L>GS(5Vuoj6FVg_!h$#6PUen6`37)aUm{>(`m`j$4B^e|Df_b z3}9esE0h|#vIX3%%kvbUMGbcr?x%)-zrqASLRnQDwl=DP6IDYZldd+BQ5ocLN~!T8 zQ8Q}g$=}9vrT*v9sr$`!ch zggq~0FtTUc9pYy~ZLUtBNkGZVb>2nkuK=u$sHiB-B00d`Vt;?pWg#rg#Rk$pQ%wTQ z(D+fulzZ8434gc-H3|3;Q3mf{d3D_SiWHfdbFA#=FYZ!_@+K$!{u0>Ga20hLZ`SaH z;tp&Y`XEe!Tv+&tFpOK+63)q;$n_ldsfyuGpA|5x?QS5+lrI|;P$nl1>yJE=mZc67JoIhhESk;-| zIw1YLQd{58ft2+(D3!xJW_Ww;xoD88j^@oLR1d!y$@t}|#NwUqL*?eW{^!)e@q_yp z53h+$r^ojc3x#S+v-<0u#U>G0GJj`(B39AU9*I9wzdT!=$WOOj9(Wrq;LfLtxZLb* z_9FX{EdQ#qT!V~Z6)w9=}$C!bh>l(}H zJPL}`@58*{xS7uY{}_>%=sD)D%B}%`YwpMeyp%B2V%o#^S7F&{jht3WbgB=JnnVq4 zrMy0^(M?oZ< z2GD^uqqU~^I>f}pWT5k&@$nHOOEvtl(b01$sz~8mL-o1&__V}<;b(|^z@mN9X^Bfp zB48S$!h02)l{MLY11_PMtH7yY`zM%Ur z6+K0LcOJ!DY}Vw&zaKOrCgv(Es4i{ff%1~%#4JyEc4fmO(I4A=1$Pw{$+A*M0E_z8 zXEgVFerPZ;DQWP@;%uUCr+E^#(&U}3Z!us?WXRUf@lEVGHBR136;eex8oRM@Q${xG z<<~TK+Vz%tg5o>6_ox&7xhB)h`RP(@+3P*7B109Oz!!iWq?Ib()Z+z`2umtlywF*(Nj8B2d(VgkD zi>pe)`q0pbQdV$cIBn9}Ge!_Jo*hPOMtamYatMh|O^?FYmS%eGrr+o4MkgTjiD__+ zp2~i!1jO$YLe`Q9SWG!06UWN2zG;210InuVWV-f?m=`^=Hv0797b*J8(Txj#ra4Vw z>3D^>Kh0=}7=kbT#7;laNv57>$3!{AoA_ftF(aO3uLQzv+Z=)Sx({LcWajq8nID!W z>R3ij#;vb|^3*H3LR==?Ttl0$E!rmweY(qIg1Z6@P48~N6CKQLSlJ~3)SonV#$6Bd z7uFG}splG~MFbP8(hN{PFG5-{2e#EBL?qV{%2*{X_^=`)o1^9GPj>v0V}j5DrDu(= zHqgeb#TKxe!llt!%rYxlUQ>WBHxu4NW#ENqOTYK|z%PzdAL= zm{_pyQ{|KYjF@}nc4QI?2n3krEM-mA`HvBJa}c9do}Qc(YN9f;jQQE_42VPT@E=A= zq-O&uUVreCc;62$!IP+22v?bN_pqMzT{o)vhAwP$2Tzvph`8rSa04YR8Q}am( zp$rWP4P_Qf^fxo38cOVnroRpDK#E@MQ7Z*1}%6KLtdOy7`%vZ4@Iv*GL zfxv<7d680kSwyyuh4ba^J6gr4T)U%NS)HUVLHp``3;T^EIJ$wa$Vj0IqmTQy6f!MS zp|$Z)WSnw4hI9CsoOC^($Ld1=%&-u(b^=ycMbw`iuJw!y$Fnw+7XP4;SQA{3!)Sq^ zxg-2@mZkxUM?XZ!g=50ihR)y7fiA1g1avJ)Vz93L=;iU%Um%-qTi{g{q?0vyu`xfC zeDAqImx|%TAcY@vkYFx(?`|?oD@)mX(PfHu4ObR<KSxf^Aqq*T<>K#=7 zrjp}-gn+e9V!9K|DC8w)F%~VdW;A)R>KeG-*%Yy{C=a^p$LSADpd}>!B&V8~pszt3 zj9wEUJqLc#4Qu^~j*ia8%{{>SFvIG!JBrUp_Ith)%Kdny{FE>S+T#TMk)W)FI&JnM zb#fp0OWao#6coI0JkthqOD3grDVn&tCN$X0cPe$1R!#XoLe%^z!v{Pa4Fhf(8!m#! zlJ6c@$Zpgxu?0FntIOcNAVfsCqf_jPo!!GvaCp`<6RGNf|nX04lsVSG^OS4uE;>M(px@jpJF)Lv)q^&Id?hg(|nzJTp3h9dk zzKD@itR~CQlaPC4kVYk2;uyOQ(+uvbX!F3U8fwXv$uz%y6|+Bw#kyH$fSzUWHIc1fi_rpb$PihFYC{85GfB6Vk5ZN z%drpHotGD~*4UV~=`a8iqr!Xyv~f$k6JpaOXfb{gq$8B}cf*Cg1u9*BCt8_uDK?ZvOkFX_W~g=2B?UkSO?k zmjvvM?V(U8hZd8zU3g7|dtU5I;YB7L0)kuE^$|aK1)T{|?P67uZ(Ne*gU5i^JxVew zWk*xmVLe-3eIm*b+e{M=Y~bFz7Pn9 zxyX!S z+0UZ4=@6I+It;;Cznvpm*L&}5zqGNJ%dO(JVYDSl!RWBO|rX!t?e^5}4Df(}RDAtlEB6Ex^04g4B}|4ByPvl1_Tn zuKUvYtP#78ZjXQ4`1opYNf&yuJ4Y%=^qwi`*Qp!%%4>t2u7`*B{=$jH&7H|GUQ!UO zoBz>SXsYDGt5Z}@I{8TNck`K^aJ^o8_r8*OOKpmg$js=JYvSFSRQ&2P4%fsKq(fuR z>%NzYy5T7*ub|+H#F9A2TOHwxBKY>$LUgPr2<5JyPDK1Yp7B(cuqg*|C$ypJb(D04 z@B4sK;B@Ju2?Ui)eF`)p!%%MyzJ#7&c%GhLEK@RJZC8PN8RN|np}zNscbF}!KTW22 zt!DZ2c))S)mfmN&>@&#<;>EDW$Rh-VkByd)`{+Es8s5dCiJ#MjPqw(sp}7fmVOzu$#MPLhgh%9a8}6WxHtPAeGqO z#=(L%J(m$DcLE>>bH!%Z&OL<_!lgdszFBlm9r^q^X3xlkYc$aQ7diS24!UEJrm-Gd zw=r$sQ(C5(t9eKrCuhdEIs2HIHg}XmWK`^^c?&zX*t}b#Og@=n@mU{heJ_d@N_L+?fxh%)^|GruCdu1fws z)c2H8jvyGmeChQs{az;L1Je%#qzx#>D1^ zhQzOqDVSZ^K_(`)$A1h-Zclg6Z{c{ZnXa8;`augip$iEU&O2}~w4{-o3B^nP_oESA zXheJJ`T-NZ4-deDR;ZL+FWtkFn9*68&WD51xLv}QdR72egtD}J*Sk9wEv7X0)iiF( zVQpMY6*rsDExbcmcxHa2lr-oUFuf185o3_bCE`LzJ^fBh2Ib6aGdRsIta^u1zi!Yua?V z{!A)t=pTzl05ARBQ;1Ak(@~ff`mnhFSt$Mljcx7y_g5M&MRS2Az?S4Dz|Qpj+fKVF zs-J7+#K1nMEuny@Eq@?*bJK``kPx3s4e(Q~$ORv6_3N~0B z`Xm2D-%>N-dKv}ALt<80*C860m*NUeN$c4%MfiL_6J9DyTEO6vWPlj|P$53*=R$!j z1RGYO6ka>8 zMW8h?7r!L1E+#!X!K1!Q^t+a-z@vP=pWY=%!da0}eID&4d9q2B*=y9=;o3BhZ(r=a zi^PTh7Ej7j?qZRm=nKNQASUHrO^^7HP>{WyaGguB$@ec!Y=zH-!c>wB)>;#pV`V3V zYG6Y{R_pDlH>)7d4pI19#bx`g=1LbAnqH3?mq_I2u5NBx0hggAc>5jtewD?cUF76u zetua^GE|aVPFc#u#H`6cF~BlS`VHRmH%YQ8@9~H@6}K#pwVI*}Kfc`isu@{n_+vXQ zG+Hd+;J^y)Glh#wx~6kDJa84(06pbbpz9Cb7!8$AYI6mJx_8b z4wz^mo0^;i_T~77n(*-*M=JV&aV$s#t0-*f=-t`%D(ORxK)B2OWl z!m|9J3)AqpTuvZ!9>3z!ugX3?X@YPrGRbt_DJofTtjsPgsdV-}Y;Uj3&Y1_J;%_Rg z27Gta3%8NLCl^x_k|gEOhb zbR&5v#-MVVaCKMLb#Oy!F^y*Ji!ET^lc40P-TC$?{ zy7?*HvXiN+QWx0|4HKvY{&*}z!wQglC(O%0J>pQR6>bIs|OhDd!)Izl{;6BT zE-s5;jgD3i{uN@)+geV2P>(OYe&S_{RlM?@1l6QVdl6Dtirw|`&Kg8~6456t7MXktv@!ZipYVIBbP%T`{$w%`Fnnf z@<%4pIdhJnkCo)eKQ=D?jci z-^PpH;U>bq$jQkaxP8uN?Ry5jzKI9Bt=+G_sn>?|kcVQib`?~Cqjhf( zPfmn%oepPb02tlwxoig*i*};&6b8#kwZ&hkvhIq@ujla67?_;iZQj-Xb2tdU-`Qmk zRr9UBCR%`sGOn*LQA3%?hBvW~eVrH`?IOnZ=9qh6X1IAHj4S)Hxn*t%n=fL&BIDNFgaB*!-KTCnOrK}+_S2L28=iFFbmy};`embwgcKQ?d-J{@+M^YHhc>jnS+=kOCOS|3lPUheg>%>%)MAQYzAEP|`?; zfS{l>(hbrK4BagPBGS?&A`L^w&>`J9G!nzm-T7_b^E=;pF8-Jcm}g?Iz2d&_wf52e z#Zh0xneY+Q?rTuXhG1iFVn}7)n3#C`T)BeXa@aAV0x=HJ)kjA*2@30AO>R}2)Hman zYHVpe_l@|FkDP~Un^;LFi&SQQ@Jek!f_k-DT^Fi@Z+O3%okWcZ@_)rs;bI3h|5V|^mxcV zWQdJG6?emDXz&^o9{&u2!NXNX$C4wuRz~JwN(f?78+_c@_H? zbSJQkR(Er$dy{gh2dHId5Kr{k791vn!4og_uRfxkB>xEYi2Hds3K#0M+x$z`X26k= zh~#Bl3!>+IcybUhyPW#Ep*yiTw7yQBFuhNuV4Td0o96aj?D95s2x`*)ECRZll(zhp zVl7?4AlNW5*M>Zi()~5IxVu?|pRWZ@#$5Ryx{QGpD}{Ymzht}bTjU%s?B~zIw7YJ< z8iec1JFLZvEnJ!#XhBaw-LGmqq4jnN6vzW|&2-1>B&_30BJ(K)(^cS_G0!wh@_(}TB-juO?u zbW6+BSPoYIV9qug?1EtUPCr+ft-P!%&dJFMq(g@n4Oq%p-nSW7 zbDe|~6Z*iO#cyxfJ9`q@1>lV1lasRA+V|yEaSxA=jR1#4irdg!PsPaeVN+NvBk~t} z>hG?VrAa=>R1=g&(>YCP!J7wfgEx{X)@H;7uQEC3!`o!KjG?ZNyuEwS>9#L0o@m9R z1uE#@4O1e8v2N2>zsIaVGz~T`ReNxA)f7*fuE@B7i#bIdy07HqL>_DmcO_`gn?Z|^ zmmj8!9HYWL5H~lUQeio`t>$mqAX?^obbo)hNeuhO*Edo2VAtrY5r2Elp-1PK)#r}q zwmCf#XOu8`h7SpHzjG`sL#4Hn)3WUbDASd)&#x>pkVgV@!;ccLme=!0T&o^G0%cRv zrXvkiMT_ifEk>iEzIxY@)f0YazeiV8J?0nZ`Kszrfg0C8ds1cObWxJt0>6r2Jj9Wj zoL}uXa<^@0@I!hirKO%~{~%j=g7fE@*-E*cnZMB7c^i~(#G=!9tk~TK60_=JB<532}fguED`>$dPL=pPm1OtyC z)q#QQ_RABOSrGXa4#aO&(*%v`hVls)tu_n!Skr~w=nz*1ZP$uKO8ls?Yy$<>bx zt7U4N)rLZ*dR7vRHZ`QIx@U!4fGSYKXA4AvD67FxcHhS}qCKBOY&>~sqvDQUdoR!aLxLe}j}6KVy5%#0!=z44 zGn1nq9S*z9bWdf<$tg;Jh1X8K6#-6F1Nmu|DD>YKD(X9?@LM*!4k}irwA5z(rvtl> zvzboJFCCP1AW4j0sfzzXh5NT@r7NNJWB5h=#aaq{V&xeH?!n3of`~tDu_`gP&FTB&=3pP-zck)g@j;wf1 zy0X6f9CFWhfrRjAv9oIfmrX=NVT?XuC|bLBcz)s?JyB*hJV{8wM9z>7+-xx=eU0oD zg;;|Lj-iNOx+SkHW9&29$T4A&J{yMS#i8S4dyrv=N(RtCCY5o6EDQbh(3N&xIj1Qz z|5=?Pf0EpZ=<2%29#p)3@&x3TMHp=uQM+F|v{ufJB6)Z~@Sh?k)I^$Mv2_)8tvu5g zsyVz6)e%;JSH%$kCMPWod1GtqjD;ajj2qEq4f6X6k`TS7ESiDY4$6T*ZRV&{g;!$y z-`qZ>y6cLxu9=&EeA&sA>uz{Pxg3PCg(#L1@v45t#bh)LMnnfoH00GV5Is|8(GQB_ z8+4(t{Z-%f_r3H*#);1|rDuC7gOT?e zSN4q&7qP7=+f&3#!H|IrwAo052CXVT0j`Fc+%8;p)(}S+ik`$}=SL@SX@YEjQj}#xdHqD!H#X6nLF551C&}E|e0S~43$aSQP>PjJw|N!1Ao z=T?f5_XinYn&pS*8%Oc*A3W;o1`OGBfxTfL>axUQ7LW;rezh<9ly1hAimmAuF9zMt z5i)5~o*>r0yb(O^sG*wkz1mTa%2~*L>OXK?62%k_2Mx$E83o=u){GNnV|#d7S`pknKn}Ez zkrVQehwi(Ljm<5Lyip#rJh<}kunIkjvu`sfsj;RNrF{rO>KWQlx@c(g@>j|sWNm$8 znqAIEdD#^Kg;j-f)(E-}Un#SHsrS88`?fW3!9`gR;^|AqJU$l@(~pmiSHv;xMgpF;-AKqh>*?vS*1n8CgV3D=dkcMJKJK}2e}-z)r?NfI zGt&AeDnH0dN5tq9o!BLR*9Cc!#GoX8)C^_oA$(K+B(8ecn%=Go*(ZBlh+H_mFex9( z9J??UXZmw{wlmvR(scc5WvLXht6HD#zWhL1M#clatk>Y+UTbXt83?>zlfw5s_$aW~ zX@BbP(_9{k>bK8HqpJ6$z7V_O$#J3x61KuT=|o*^I>eAp<stC(V>Sa22zcG6kb2ELe(hKYsjJm^<`6&Z4`S4;*V1sH2mO`R%@I;y)Nv;KvE4z$}Wbis28NiQ73GR^{$mx z@`l2FL3m`83psM=gabudF`0m8J2n|>geY_+&{h4mqRh(5D$=h%b=g$+Apr#4N8~FU zmeSn#KX^9)wv!p%K#D>RYE9-roq~gdT@)3$2eo~7Pc}#UjG+VzO)&%8s9ZU(7rCZp zAb3PeP5#%Jzt0HCaQd75dr>3sx&}?+;zNx)JJjzPi>p&NXWF%(VIAkA>&$1a&f{s# z;FjmJ`7a%VTLEebn3>wa#X6U*^ZwoW)E;E5X|l~2uQYz(dwBm;KmH3%m^~m8Kjss| z^&&bt-hog79?+DLH?}_IeD~bO25P>N%!fHU3wOHl1T#yS-#!QFZCzd66o7!;z-a`A z7ECg|47=LR>84!W9wiC02v|0#z&_DSiqbMsh7;jqvm?v_ivixsd&YLWii!qyQj=Gt zFQ^EQ26v&aXdkw|{d^%AaD;qSBb|kR>5Z?XFp_I^oWgi_5~s;*T7iFYllmdMR+LAI zKZOC5%!;{5NlC`8uJHreL}@uahM=_m$k;v*eZR!?72AfeTV>r=4#EGo4BVaxPHApZuR$kNJc=|#<4+m!%x)g3M`Mr!h}0@l?L zv`U^Ep6TtJ)L>-wP&O$ecXM_-8eA|ic!lrk>^w{w>GVr&*@nN5hJBz91?2Y_^0! zWno7zp|8(>_;MaO6LrO$;0G949K{R+2k`G3(RgHlkxKKLoh`f+B#zWYn7%L}y7DtJ z{emN4lb77w*w_fnfL)6@Fh>Vb?<4Q%k$Vw)RkcjZI1oZ57>klfx6Abk@*bl4)*&%g zv>5SwY;JZz(e3G9+D}?z?yGHBX#Z%qTH|{F6(aoo5x-+aL;pgIq+M-Z^-hs z6ICp}mY>Oyxo5d{Q=P*LP`Cp6%OW{Ne->TPVHs1LF8pv(>-#(X5@DQF>V`v6>JPaW z0OO`e&p-`Pe(wf!q0S0(65}4!YDrTuy{Hb`^fh=rOG-mZn&M0S{v%+?+jLYb;FA{k zif8nd0o>_S!k@_&Hg~Uw{;ayDKD`U1amEP*@4fv{ zkfp17lBXiww5!m*i~sPBv~Xm3`8n8yq|Ev?(6p1>^Em_}*FScYuehm6Y`5{u0JIs? zg41!OpGTMaQqj;LTLSKZAy58bTy1IXI%T~QfQUY92uFFU79SV5EXA>IUv)WM$NP9) zzA{YHT>toCgGoC>WMjpUj-bT)YVHGxy1~CEOsp>*p^6_RR;~VEn&{14SJrg>`E`g+ z+@%-SR;!R^njL$>182v@tSf?g^rPS(>xlf(2z#o~gze=DU5~5tx8l~}R?MU(cjxXC zsqlftT>`56N($VmLr$ui0zLMLJavN)@vxw>^y`E{mJmo*V`Cb~9+`O)eku@Q75A+Gw*nq+qXzd4qMJI!U&?={4;(lcW2uu8jRK8_fAp1A zR+`!#9UTFZ`$;cS@D+FK9W9lKw?nj=utGD;$@J6bP_=Ig$(`5NqDaT2oVTCjjiRK+ z#@Lb>0}lkd%7s3+J}M!`m5=M2o0*drr0zr=EgfC#dp3S~@z~YPr7SBe&;|0Sv35o3?SGr4&TkrH`TUY zc$rl`=NP`iA|l$GTPs;^3lEIawhk}uX*zB6qS8|9M-S$lYU8cJ?=a9ua+C+=iU{HU z9jHvL{+V3w8y#iXD@JWcy3Oz&1A{LKBt%BCIV{vmC8_uanHV%z}0Jg5f(d%whh7aNP5j~v=Q>cC0;RQ>t?yl*^t%VzV zlX6e!)x#~sSnR+g!3Jwv_c!~>SAub~4xWSCI~!$(6O*3O(^Y;p-|KaBDZT+LZ?4_* zHNRkYW)K#DonW<1W;l7egA?GK5?4L}5i!K7MY{WfDEJ2+5w}BRvF^p?>CQil3ZPjG z5OQ_n;Mr^6Q)kz52I}fx^w)WST8F|DGeG-@`VpLx;Niogb>tt0XaB1O$coh2Rjo~a z;R3i%4MKH>Y{)wwAD`{%ijdb{r$t)MLc+qmPn1NBg*M`R9Zf%da>vKNJIvV@m6f&Q zc{er@(}uHg3x<4;X=_!mBVf?i)zkgGfULsmp&YvA4t2~d?4MFCObkIF--A5*JyWc zoS1WHKpkD`VrbVWDoakTL67a16=jD})aM)rH{ID+cH~rUlAiE%gkTb$dpbF3BUi4gjGAD3ILz z&|Rb9OSU!&x67N!rjTWa92>w}gW!Nyye=4d%6_-hv-vF_Jj7NHr4DLe z{C1wtkkWM>hHz>^_ z$@uGVfJjWbXEftRO;x+B|}AV1>Z~5+sgR|NbLv1>}Rk(L&$ENzMHq2Kd5csD72gzrWz*8fkx z=DK*W;(Z#Yd49Uh_BsHqWP4!%u!XSG5)60bPEwjk@mxa{>BH&P-7N;DD3-QgyR$V) z0GAZd!%by@_v}-WD`1;X{lRCqlkRSjXndji(X-9QQ1RQ3DF`@#ib!W>=KN1Q`}O6~kme4AnN-)6xUQwV zz;V>>M9*;2WfcuAfCPb4D?*j#zx1uH8uI7Cqq-aYU8gMMP6R^diUgVVw?O}pdI}|l zou+uS{AXhe5W2!oz&a>{U6sRxwM#cv)w&0QA zyl!!)FUKh8tz$@9jkF1~TfM5%%6mRzFFXm@O^O1x28U#kdQ3D0z+QyDrOpsK#d?pi zySuf=q|Q>zqPgCsl(u}30xc(H`06A{JKH)vUEtNJ%vSw8qjXHjfj(_5Uh8|hQB(*H zw$`XipNf~IaptCXd`3{)2`i^TL9%9w*TqS97z?kcXg?6XfOFRidZStN@67~o;7D=TkN`BTGpGS*?xe;j<aJTx^;v)~2oX^}oGwtl)G3 zHHNdlWBFA;rB@uq;n65MZ25LA}_6yeT^K0RzJ74KAaqef1 zkFj(ycMs^&Wi>lHvi>Q|OSrV-R9aJmz+GhJeN1?-FSDz|;@RVwvzPkKGZ8ztcJNHr zm701bvli_w3I@{>6fwWf_YT4jXaCsH6n<_|@n-9v%sYM@o5-5?b$q%QLE@|@DV zaGL<&4`MC@->8{Sqz^|#_`LO66i4-C;ob6OH77NZ$zxOlm3-VY>!~d>2wO0;$XOFE zw5=&3gZsPbmPkSwUBW_t>+dnUod;f6SQr}{TOM_x-B0{T^fxVdmT?NqXy!d{dE$g* zKWum=;4T3I^8a1Oj8VG2P11(Dc)4MX4KK(YJhaEYhAI50IIGgg8LNI; zMe;j;;Tm;2M5PGW{(=*2PSD{-!~A8@7k*;AX7yJlTnx)G<`vL=%1w;RE;TN@Zb0D) zU_Z8m-)JS!aw(O^qmvvIdcA{_Bv1vM^UbLU|DSP(<+GDb%{wE^vso%Yn)6G!6fH+j zW;}(3bi>NJZRJ3%%4{eUBuR1~F>;~|6OHU(fdS9idjmigR~u zT(Rt{YRtsNzifL1?U<#}x2rzpSRk}UmQA7m1&Kfm31ZXwFz}mi#-QmsUeFX^-h)<) zT?U0dtbT|)DiH%TZ2C%0_75^8mAEwP;E{Uyp%E5?hLCk@S6 zfrEUIM2Iaz(tCTwv3PV_h96~9Z|jG)=PnA`&_sexvD7RV5fUKx`NzFL5FA?-F%pLqj?sX;JOkC-`A*trhJ_Bbc9`#M-O|6fC>H(F%Y&_@8Su(CN58)E)2Q<)S?bysNXcO2_{`TDHv7*)( zua0*g_Y5Xzw9xsLpC6i&!3b%z#hzSh*nA>63|rR} zT^LSGb&Q?tRoKAnOLfew>)Cx;q`uHIzkw;JKO2K8X+3mB)8|};`(!9Cbrtr`KD~xo zjRdE>&>q+2&Y`r0zr!viB^bAah*DS2<&=9`uS)BqM`vHeAGyq4t-J1#Mkr9!^_mc& zisvWT>HltJk#W`u*FiQM#fAXu3j_;i@5JM7a%HnghDQiezxmK4XP{;)Dny%XQ`BWz zR8(r>x4B#ZoW!{|)A0{85ftvliKH=E;BuEmcu<~KBl;fd>X2{jp=J#@d)CbH-iFDMIT#8!TvqY z&pOyK1JD>0|8M0-Auv>iU;3UmN~CZmy#|T*pB%{3#qo1El(WK2oAZpyUZzopEM-Dw zg8{1V_Tye+9u^y=Lz&QIVZ*-5)xeGj#dDC&zn780dD2oBPYMVJBv8HpxeQ(%%|BHR zae2#2wtKDlpB|SW@Yq83NSbND!aW|<2+n~@sCB>mUXl_vPWw$0iePUjVS|6499NrA zWQ@(n$iz_m#@~_1t589m?W&o-ju*qKe(cc3p95q8l9|dRf@y5TMWW?0V;glQ$v@`W zF1%@Z!|~v$Cte&0QV17-mb~X=U#dUoEVy*+9?`+W2f>XNtrBDlM!xLuAXb+cAC=G4 zyEU2B8XH<9H;>Wm!N!{xs~a#JaQ!XXNf$L2S+!Y*UNZ6Hp_ix&P0w--*a8I*JSSbd zLCx9t#s+){q{`yqJf3FzS<~=HD|<~tcufP6owUWl({(zny(--fiszHs);pu0_vy~H zXMciFcgqTBYU-anAY^B=w|AX%xQiqp)YviPP{m8_^*mmFhbCql$P84#yqGHQC>-Wd z&W*jrULaM-WgTMChCY%B&aa||o&1*AjFb_#8teqiTxPe}RA4_+imyoLb36ihrRQ8+ z+IZ-~yr>js;ALfL`Hn!=pTpK{_#0(%EW0|W`s-p#d>{Wy3K+5{tc;BVbnO~l)Ln=r z{t?YU29}rtC4mVBw+dQ+X$3XA%nFb{bK&#zFp>V}}0TOZd)cpr$ z@1ZB#UP$W)`q`y-YSyfZh!B3`QcFokYis(H-n>w)RAU_*2#=MnNfUnIaaTt zhfD-lr=LW8RB5iq5Zo!{V}{Ei9ZCp-m_J;(^lq^HRv`$|z4l#Wi6U#+I{CFFY*3P* z$01WxRkcZt>s5eY6Tp2)h4t!}cgmt2Qsc`^7~{4wwsnYT+#ajz6myePk;PThW6iuG zMyj7y%%Zi=w39MGM?SX0vSQOdE3kOY- zTqwWeP(y3yD)^h%9bMOnDlEW>stUr0YiGo(DNGbO&}X0SngwlMBCgAV9-_3PF(MP6 zwZc=q2!e-PE)~4R(t6OUoN{s1gJO!Gd{%3UcuR%h%R8!6b|>8)+6P7GC`x#})+Rui zM0B`+a*QcO=psdnHdx|LXYWgpIAL?e47~dILT~3=^>4TxuUZi^-KpmTky=ce*|Guk z#_CnnJ78xgRVprWPJc1go`e!!URJ*%fiOL~Ka4OvocR)C7d!l)!FueezM?Tw)x5-?}qMq*8C5c{=CT2`Roy9}~b6 zb&0_}xw`Dm^4gDYaCf9_z$*Ei3lNc4`K*`834_^tw^&M|8Oswn>HMh3Ljk{A_QAN# zgntg=zpKvI%f*l zv?22!Ne&ra%4}Bh-)bz;L#PKIE)Oa;p*T`g{v1#aimwaUkoH>9%bkH7YU??(8 zA0^iz<>F?`+BQgWf%u?nF7Jf?Z~pwem0Kq6KzyINtx)&}e@$+`=lyoMi*`af`ck*D z88^x1aK5b|@p$w~@@DF`8Z{PxWPptDZI;S46@QU`cnRZo>lcVv8XFz7s(`45L%xys zi>4@3wa<)&0p{U95{y?iJ2r-| z-@x#X!UtA+yqb>MUJK)%J6b37T-J6{w^zyxre&()my*xY6I1mj4#dlA-xsLqxW);8 z>6r&MAa(CvLj!~i1PVt@2rKX#ZFiuvj&#Z!m;s=CO_@ov2KG>kn!BMXtQ_MLvcZBK zfIrb=Y%d-dD8c6?E-G2cEQn|;r(OM+XukZ8o<4^v+-$T3X@Diapbc%cbUAg%zN#(T(e7g1ZZJU`2nXNyW?#+j=ug|I`y~4 zwAOc;kBRd-s9j|?X|RV}2FzK3XZ*yCuR&(*&WFbeSU!ylb|RaQ%cEy!+0pg|+UDaAXYDM9LFm$3(mz4MPwd+UlHEU<#J!>Jz4qSegJ{K|o>W4u)CUbd|+Q^F_d25^+$0nP29-CAqRn^$2$l z2mdo3a(Xb*g_r2rUR3jw(zY>;0C9!FUcb!)cMX3jbhO-W@1$8XL0%D1H>lh^-lYRo z_jeZ^9G$5;wq1~iJJNziBm%gyncx;S1CrZC_KM{L7d-xL5`S|uu9#chmlOHykF1v( zuM}o}iX_?iAY;}Q%Q{s<8ykRs(CQa1NxNh`jNSz-6i|5-qcs$c zqz@|g&BOg{`afp^`sN!zuN!Krs-Tvi9xr>|oePR5$U0~tK3GzooqJ!$40S1aHL_MK z04y+k9S`}6%tuU2oU28=ej`Vd;4kQU^;iyN((qSvfHF5W$9#6=j?L(FX z4IYm2#!9q2B_DqfANRl!pW zuZxMjqNS|6gD}y<5smcA)xG^lp4Z#A`LwqiHGUaPoEAb?HFu#y40g!D*@fP#-6_na zl-jKq&D}B!jRBo^53>Ikop5fRf{pP5za5vxrUZql$%GeFXdJD7N(W|O21#mM09Klz{U?3v4ox+fCi#MG=uL&K zn2UZFuR?He@K@<9>f&uLIr>jR0-AVzo9I&T>xJ}m77LRX5ks0(o^H&vHEo~2?P=aa z%PbRmB$2PeWr34-Vibjs){%($7AD|VVm|UUF}KKAYbk5Xs!Dl^kWV!`M!jh_(HE1s zA-53Hu?Ic+^l*AMcHoskyY{qUfx%zpVcvx}UHa&CBblP`5#^Jr`qEM(TUV~bE6Ek~=n7!&n{`+UNQ)}~ZU9B# z!D_#J`_Lp%1}s`xWvY%P3Me?{^fd2ZoF@)-g|G~(p^YydUls2}-V3OMPJp^i%;A{X zP}nWPj|BJN$Ypn+3iJZ@?(gs8eg%$-7AfsRLl3J5v?dn-J$quAwDsN{2OvJ;rZx%d z%XRI0sy;P(gqwsJ_z3q6vndho%dZ8$kIkb&J(DdUuk$s1M`U`2V)@Ts#RZ2h?8=Kk z@6#|Wu~P&ca)-*N^nh%tVoP82!uwmsZPH!XV&k60#fe`{4(6s|L58``EgC;em6B$U{DLxFWNDwTF;Mvnuri`RC~h7g1)d8j2xbF zPxQqyCeY!Bl&q=f>DhEAX(BPcb+vYs(GRtPFRQ#xv0|u8j--^SnZN8_OSOf6aWW9$1-@=1(hr>YUec&r|!NZLM{p4P8J}n}1$x9R@lhZV-#i%a$+x zB^(zz?C$@uPF?Zw))5~#0GAZQgO4|?DC?wF7+JnesMgL^BqY#h7Qw-e-iMM=L=;N8 z*QFgn;Xd=dv*>Gp&g;w6K&V&;nw`M%S*Dmle;p!dmT#H&AC*6rxP4+h&y%_a)6hLk zEGJU7!&IB@8t-<9K}r3v`wg2=ym!XQodfv)NuiOit935z`64YxffW@5^Fvew)2v%p znMnRiIjnE)%$AxyXbPFkkT%t)vLgf;8QD0a#>m4Mgx>xi)JC)U}yl}PzQKX4L_NHJ3a0D`?J2{ zSYxZ-jZ3Fjj4Qg@RqF;-`88{{<>UOwN_E9t{mN>;!nVBYFq$bF*V6tEc`tV~++Ao) znXh+qS|5G}T;$fSRFC$dWDo?aays)RTi}>f2;oc1&7Y71as#`=3w#XpefO3vtah#2 zCqMQ0UnZy;Ru z^6GsxO0F@gudH!d&@m8}oHL^D@B^0kg6z?ZO|m9U8PV_#E;f7KCgYVI$_ZYug4?$g zZ((8a0Z;}0&(bUmo$XuUR_a0l$kI}h7OM~kDC)BC#^Cy8Td3sC)t47+t^u*?J_$dI zk@&?}hPKMJk829O#qAxhCml&({#6`Z6Fcdn>y00qaEd#3@QVBwppH6%9}C&9e7veg z&^xnB+Z@Hzm>O9PUk`QNGrsJ@0!$bL^dAolaKC=7@O-4T+O}p4;U=Z-F>Pf;4a~sL-F1vJF+MrJU5vcMuXHF2UNb1|aU~&TKAqF2TCa>tIBo zDD9I-oIiIlxKRaGea*lu^zT60E*xEpv_9akTcKMn8H_JZc$g#9vEntk#I1TgX6Qq4 z^rBhv4sj>4Sf}T>5c+>muTEi)8B--tje-#Jj7RgT+?Q`R6^I*BVVaHhcD#nhS)65{ ziWCvh_OJ&qY|>ba~&LfktP&C+jxj0lmvaJgR`gqR8@m{LXMu+I7cM z+{Z_ts8$?-zX%a|xQYr^Wj51>hGAO6m5@UU)%K^Qb*Oxw#aG*+yyDGsG9g> z$L?Rf(6!V)$td}_Z}zr~J9zoPY=36VME{=af1-)3NZ9?Ydb>q2tdIK6#UU;vOP)dX z#0Ubx(6WMr57SZMxi?sRM1S6ysOtB8YHci=gBE*5*aT%`u@XA+cD zn$ysRn6`ROXNAO|2bf`14si3A39{7b`bHMkF^=$lR9N5H_yE7=P+J=t9$v-wh;-zi z&~`SqeuqM0Prc*%`0cLF-3F-I$sA0X;C(x-(u6mRal464M6?Q~-IHce==ZC^-Vam= zPC+^4U+_-aM}NiSI;VA6SX}VwGr3*YX7wou8n)9uyt=&dur%_Y4}Gf+)0mE9JsWER zEk-pGENnxWXcdZ-w6q53h_}9KUgwC6w>>Rat39y@Hv3sHm*ty@D+q;HirOCdJI3X4 z1|o5NfSOG)X0ywAP)8V?dA|UFg>OKaxiz}H-C#%OW9aelpt|OeE`z`U(R{Ucy%#V;Be{BKxlS@2l zK35-n`56p0`0qN-QO|nRS_YHq?w4-&;a}eU;pc|Sd7;xVSF#y)-}X|tb}H3(5uhm7 zbJRViF{!YX19!{#znS<7x%3iwR+ON@LFMURqF~q2crvx%pHAKw87-BtJYruW>cs;L<1=StuuUUEn|LZr`;NewFp7xc;k{B%8O!2BC?4M1S!JrGI{kY9b`g15pqUzTv>AvV0w)Rv~BgqPD(Osf>9df>#__y=h6V2Eh@6j~jve@!bF+pHy8 zkGV{X856E<4;(=AuM_Z18m|SSSoFS?Q>oWd_z}(LAyl;xIf@ziRl;u7S9yeY|) zoE8@={G$~`&gSKz2D3!|@6xb;cC;zmw3hvN_O|f)%p|ryf(9kt#1tS<7WeQj#LoWH zr_{2IzU#l7e&IF6_2EObqCI4O)p!qo^6jm;HTk7--so|P*>UdOiElT0q*7b>pzdIs zu%^O#iyV}OT-FF*Jj3s3b}D))qSDr{9nV7DRsC6d)*y>4>PiPoZQVj%9&?aut4wzG%dPbWieIz(V9(jOvJQd9^(R^}ayuTfj zO52SkG>S=|^lv|}l2nZzt5CmHVeJ-8mE~izllUl?w@__laxb^ga#l}Fwa<Imd$sVT;bsk173u);zlU@!%C;fr|9v^;KB$*QXUBUgOLT20;dKH$qC|QPx zbkPUA-S6g}S3(Pq@|UWUzf9O7c4qFU^Afnt{`Iz2b9-C~aS&tY!^IS;2tPn z^Wd#EcI}#grG&T0)ti)mo;Qywd;C;~V;y=b5q5FOc?;z~+v%<|qyiUQA{v^h4VL~xKQrWIp@D=STd08%)m+R*yxKs%S z`H`xz^sF8cT{OJqXN~T8PaJl-T+gnH_-5np8TZ~X-}%eyM9yYHyRW5-AH2}fsn6SJ zFo{LH{lRkkUT*@e3+V9Hoh;1CTB+Kt{$~UFC)QQ=vxCc76CKrRgf*-#^~nLBJ#@n_ zo9DQ-+c~PYK0)|%G|=i)m{r~2@?eZUTVMZR|FGdb_vrV3{Jn0V0x|T@`pVJKbHm={ z9D4kg#ZnmCOik99vLZx6g3B~Y;XkCR9^dC{*N7e($G1#rMQ8}U9oYHm5c;TTna|7` zf$v+)p{Anry~lokQW9N8Vd)LJFq_1QJ&W0DD&N^GrFHG}HCpN*^7{^M7Z9qOJFe(r>onpW5rO{xaUVp+K(%uQ#-C42p&g127A@^*=yvU5-#lzw zY@sC9(=1!5eBWA1iIsU#FZe^!^$XaunwLfEF`mxZ(D4g5b$E=gpHICO?DjJBO_D*a z#WyJa`BWyne%jxLQIY+z-Sd<9JXv@-5A|AKiU5^ySaFx5>eo7avdv$o3QtcmqoZ@W z`ZJ|MHlMPnz1gh7RVm^BYhJIoMH1E#@0=u^1^FtCc!ckI`^D?5B474hj#|vi1T)@& zPIj=`a^*vo|Ly#f0tirM0Ls`-d-C6-5|GZj- zpmHYen*ljx5Y;EeZD^8jP_^_QDD!eeW{*-Z93$ z0W);Qe;%r3w!};PB(xOEP}DRwFXsHkre?gMp^m(8uH*P!f}Y9l1WxxPKlKz!l`T_O zr&^Por@T+@VNjDiGgDA-%QbkWNlQ{sUtRDz}m&=oGwIj2UGI{<&__<6%BS~ zOIqXFE93NABe9OT0-x~oH~4usz+mXuR4p_-T)YWnFn$Q#0M{Vy+IL?*iZK9bx&SqE z%Ck@NiPruH;QOy@PN0mnEQHEe`SK;ZZBZxA>R8K%Uowc z662tZ#d58oe8Lty^vQtoWTe6H3>c!2+*QSN-I<2=e1W+P(voXxcw=Uhwu-vu6Af|o zcR92rjoCsc-Wqi1z*!PO4vyH&gT>i`JGm;pf&%B4y}xclQ*(o#REA&Gl1ypMKISaj z;dr-{)!y!HvZc}aG2fc-*eGf~Fi@2DRT~(LM1`VYYuepONwrx|H;BMY)yMsH%T}l2 zH)B?>SR&tQ#5A(5!*4q?7(rua(iKtTaC0&XzrEaXv7f*$`WGZ7boeEz%>FNAP%6v0 zsXeKQQqJ0sl!H&{uoKnjtQI+?{A)y=NPH{4xsW3DQipUt(}kl&gM%M(A&jOHh${)= zG?)M{XTj9rm=rbEqoK}_Bu}|-&ypc<=!5&SU`yB}pE&bVG+}P+r?Rg(RyOJref~=7 z1e(lxu7S8y%(vM1MpOMhEI)t2y)$O@ah?_1?%;=nH`_(N{l53Mxybh7=GJ;K>|J#p zi*Iv=8cRpKgnyZ7jKMqZThe3>Qn*%Nhe;3pSP({yn+rNQmrD_U!dild*xS33t#t`b z(!z{-J!-}5%`UaTDqZ!eUAvLVCAD6(`a0N(Ykm0X7rcpFD@-uvml&%mH>5@`20f{t z=;=eY(xMOR3YpR^MHJ)2NGy6Tgg!2sZ+Ul*@&Yoi8*bEJ(_Yftp-6nS{b zM&`*cY~U34?cmI@{jA!05!b1nI4JccC!0~rTXZFmcwkCtVyk+W%a8A@;ZX@tUMOS= zM@9|~Jm!o`n)OXia8mu8DgXZs z$%P>AF&D9Q{FS0*G^B^xpge$;V8%&?-MVY}4-vAsG*`R1zr1d$2=7|stC@?8HjVv2 zCuSI`Bw9pvJdHEXJzvXIN(LwN!ebESXrrz^38ub&X%F*%HeUY`>(MZ8I5ao*BmgaB zY$I6NsSX=wadN_}MNCCeVxV2&sYb;iwsPh86aR7lY`)UzJVTAwhW8S6)#DHsH|koc z@}rP|~oa(^jEej@^fvQ8=s)K|H=y44JuJ|0JF)_zP( z;Sfs^lNkZ-*5b4@b>@b*BG@)nUv_P)GTtVA$cUseH?IYj6=37~Sd@ea>0ejvU*{#2 zb@08wTB>$hksh1%K9qFSLnvZYLkANA*?Y)H)agE{<=iR*D_uv0sheMEYIOo~Vv-gU*=9(*fvO{_Nfo?RzhJZ|q zr2dwcZg2NM*el_4GTQQN-LSjgYJ8(o_QTDLr7ptX~o?!17Mz}Ch7kF+Y48YIjkN5p{(7E3O{zX z%EZNlWh1isn}U;I#4e9x!T}k9)*n)uIm>_lta?dl+Jk0UrsT~uGr51{yDW{S3-;!! zs{Sr4Bs{)NcHm25#c8N24B-|b{|qIGyB10*AY|jjB1ug#u2cHNg_WfnOCU#!el_!A z`(@>IT{&wjx1e0+{IH-^Rt_%Qv)uvIq?x{A3)?|79!;+nYfPj>YpM1=-axSht&%1h zEcQ8U3iq;&=QDsBvZ+8y3hWSCl9B5nYf6-uKe~^oITNl~Y=421Icr<(CZ9sWVCm&8 z{<&N%wGj8aH*>=2^52+WE8!TVrHCabuO_P&>ImEn^?LqYU)7?Wa6BAxIodundptXf zReHTUT5=D_lQ{V-W1I=H4$N`IoAi1J38ANEl@`y1SmtGEL#H->k-;MT`e-ZF zxiLMmklcGV*7t%+gj`!e*IB`;z&hWUZzsXIETxAF0x@BVZ>%gY`xj?AvIXmLDT*1a z9Z!-}$IWEsT%yb?A8#YFUL-_ec?k{r?SN6qll<>Ik@cjszsh#9W^obCqy}{THFvEx zc$4B!Pt#&j@24iU(+!4GA~4tb29XovjxG$j@(-gmxQV@I=mr6F51iW$e4GTK`FWcOv9}vC#QYw z+FjfL)tbO{SBCE>;axYte!)^kB5rgBfdTWBrQS50Jm3x}nKo>@SGU=+{F!6n?o3LT z1;^Ts*kD5k0g-l~wcr0up9ZJYOK)?=>+pVbuQd`PBy~CSFxov&HJoXvvgy^VX^x0U zd#_rNiZEnZYG($;3CM@oX zaTK*TH=K#|r;F7X)fjORvrw?;Ww52Twsu^g_HezRjhN{#S4ai!ifUlGJ`nR#5mkm*CMH|9lc?`Ht}!N zE3zyztjWg?qxK){-XvPVwc&QGNa?zCWk8`(D6tyUks9)v*%6m1gaVx~ltfg+s=j4% z!6`?w-_R;A`)EW?PV3{_c?85<$N*Tt%*tgwE~RFgCNN+#!tC#uGwlXf>%2bsfh`O? z%SliKv44J7T-Xsg3EAd5A%la@#FY-0D{pSu44U_Ytr5##WYwF0`F@Yj#@aZ-MLYo- zUO{k-W^U88bxRuaA~T|U#_M7~7DiWIh`e?pu-%aMmh^isv4~%FQJIe5=5eQ7ohotM z7xVny8WX`a0+;}aoJi5r?xS3D890-vYFKZ(3j3+f7R_4h$#AJ|n@nDA(;ZYs&<`#)6XW zOM~63(PZS0Nhd|;%D>!#o-X-i8AF_ z7&m^kP%7y`oGtNPFMM6SA$LwYiAV5S2i^#l^epSi$qaV8GRINqdZjeSzh;W-x3{#7 z%stU=G)XS=hr8F;5Bxx(;p)nYP+<11a8F>#n+(pps&7swvRxzk4@sD7(7ZymUV)tQ z9MJ@Dwf&CCMZFV$iW#WeHwBxT`Ynje9r>xGEOI@tKF?vlV2_i>jy5$QN8t`k+4R85 z_SS4zY!<;;OQMk~esO8#dMq3J8$|gx@BExFkbxf#H1)6uvCeLF?xkQF$^ZKLb$B`Fa1U34EFq?=J85KHk4c81lk}{{0l{Zr1b=xL zB=tT!Hxf;i354NAirb}5C`hXuap0u8;^ z8JfbKARA*3jdo6#7O@N5wkc@n{m`KGPp(Q!_gGCDP8=2>UbfkpQaF9pEc3$qq*9*B z+@%SwcKp6VyL>WX{w-8Lh_ilHt88Q@1_^4mw^(R}|JBeXwM_dA$~}7Yl!=sEI7ypY zk)zWuuFSphEAGp*9Lc>ofbx%Q!1Ng78`y|UN5`-*BYqtJzBmx7`r7o0G)F(NA(}5k zH+|Yn+bI{NKJP&Ct7({IF6dM=kJ)oRT593pyJt{ic8&cI(mE{1Cj3>x=vxK1jM{40 zh-n|CYEU8ejFGp^Y$MXYtBB>R2vI=&J&DTCRR6kHta`UV?vp&~y|E)vv8Ulu)UCds+#7EEsZUN)_6oJH$3I1bzY6|vP}v~tV`&z7LndMD zC|LXMUljM`f}>V`&rsZ!e{KriLY^S3uK|}+Vscw*B)F7x;Ps6Sz63%j?ir- zoT=M;J$f8>)?^ban~sIK1h_~LoR&cbE(;5!>9B!-7U&{;*MmJLKNR{!P@T0#K|O{h z^k{fEhB0v#0+Gi@$s5>^cq2f9;j{%&2k``-YBBqt@s9kU=RNaqI9AOD!7T;_;Svun zwvi%<;Ue{^aZr-Raw-{Y(6a}6t5_3rRVUu0e*SY{6tpa5YW!{Oj4LW#2x_8BPC!Jd zS&ZcX-CdX-jyw;Ml$_yx`@U^{xLk++Z((dd&FJMKBBC|Mv)wllJ>07k zptTMdNOT|H`K=yM&_5(3Sb6x|`(qE_6+v)X|9gKo~b0M;d69mN_CHZrN>gpowTqZv(mjC5B zEZV3o-@O~)QJ07@ZS~yw6Wg0!bbBEk7{;s`Yl>vK`mHb}kZuV#TshVhG?81MU4xZZ z{c|CKOs5U|!yWA&(r!ERw9uv=nKm&iBR>=Jq9!xs;yHOZhG@Bap8J ziX~1%rv?S~Ow;W&Ox9s0j!QEa;10{9Zd->A`9dtGElV!olez~5)lOU^pshj<2e?GswP$SeS zD}7mM5-RQZ4>Yc6lN5mm%g9S1XFb;SwnY^ zTxwuyxhQJzVX@E9eN^Y4JXH+3k^*A_)7=zZYlm3l*zs*wA?su7oY-Q8$G@0Jr&n&gPkx?)TQU~AwaG?$#eMQNI z9E|&)cS)@|h_v_!V;?Ui8X8Qk{nKLX?wu;%0GjuihLpemIal=o5LU3UX^*7143GQy zud7S8=JqmueQ{y3rOVSnxeKdCt$(dwa3m5u_MAp*1BJylyHCAtZVBZIuXpq1&8;+~a0uD`!3s@+tvefQEF`oja z9CK8R*hwTsJ+MF8vDL(*oS0xo^?n#zr_iEb+1sHYK>IU0 z3#OH8$ zE?MT}JgVe8EoMiN^a3qr9`ATr8dnIT=#So)2tL4i%vzHYOu3{3`>vQS5Hy-y`F&G5HOb1dhRuTa(8$Y?K%(lv-4g+K>;}XrQHyI;`t|?U3aVz5nw#-lIA_~@bI+G zteE4CHK{wd*!12MTG%X`gEw2<=yVcO{6AcP$r66@7X-(@UWp%!nn7>>$BYb!GXuXs&A~?iCF_ly7_cUknj)%!V4`KJQ3rlknEd{W9KJG@aHS`=w2H26 z&XXr937QvV=d59_?h@mb8Z4hV0GhjB86FyDsvl6ST`?S`?brq{|3vF!tb z=K+KetRux6z&n|nnJdfEcs4aAm8xxD-ZJ2!q{x)gmqKa)YJ?O4ZWem7KeEl zeDCIa`?f<#WVBf8M_d&_*ACYf7=^Q=TFB>f#|PEJsMXs<(%ys?GmMOm!h%&ouV!n~ zV7G+Ki7{!4iiVAW6>7$xEW`39WExc{N-Y+)Pgcs+u6Bb^LAt}^B?L&vKT)5TU%F?h ztcvl3PweE4Zmjiu!UE&^U^O+?#rzuN$*JoJ_DS%d8NVQ=j9+Ng(Ptcl8DH4@U^`qN znVIe7q(Wj6e=Q%-l7_!cmu8QX1x*y!&($}!rpl-i6l-X)jo7hPlEuGmjbv=lW{&z5 zb>ad_G2mp;$TWij#$6{ulzwwxaX9{U{*r+TMo0`kPo70ui+fCvSd3xAgNwD}fF2{B z7U2%5CySJw;Iu# z_C!lrodz+n5Qm_yp+PLbEhC&%{rKCj^x)9pZHa45gM8QS@HV=)5SDI8Fb<1_kKgo| zyH+XShpTH%FShip&i0-2fSqrHax4hY5JRqkQ5V-!SbDnTSAhS+jFvPbHb-;}_Ss_O z&N3c+s1W=J1H-QMMv{hLbbbf-y^#*!R9s5roCwEfFnE z3DK@1?YlKyhjUvsl$8wneY&@;SFT9E{lRD33$y~Iq|mhlqK9+75HWEOa>*DEfL02C zJ4KxEjY?9IV1{^1oN+BTIfwc&*FU$A@WMpHgr!6Ir)~iQc_|pP?nPx$9|zDrBS}gw z4k(nf0PYO&!-wDiZJ~zG@q}3^N5q>xFTU6;U4VGF5hs5~SliFTAuR$aApEd+(<_I2 zYnxV14Sr< z>D2r^dim<*y3&CW^$Aw+Iqx?QpHzLS+eKS40y3Vo3Ltg?LYxI06hc;w6KqUR5PTtd zI0El(>sDW(|QELQyBIk-uX*HqM&Yxv#l zeDw9~f9_lZOh1JN{qbZt{=6g0%W2(E&zXrA*vT|_rK0%Zg!V~#=en7!Z#@z8ZMBnQni~;U*;P$FA_%4dyLam9x@*d&!027qbM}(n za9Ws~MrOrNl%=_$d8t3~W2|{kE#3t(&|L5yI<%|wy(Ss0Mv)E_JYtr}I&Co-AQayB zKBBCN;RosI&CtS-9A;Rqb4o)&Ha!YZxd5(LeiMM@h$c1sieN^LswTeR2a1uxi3aY7 zJz=s8*?f1k3BF8Oj6%x%HMzn$H9p^nE7MrZv`J3d_ogy~^~??(UivbSO+ZP@hSYBT@Ekg+*Vr zJV+LZ1qEI(q9DJ1ski|_bpv%7_>h2F5kqeAqcbi$ViM|qm$349CWotg@#(V9`qW~7 zHjJAue)|F=S4MBWv$J}E%cO)81SJaeF*hX71qy6tH6*gM4Dqs8YYqc7HO_F0VV#(? zbjhPz9$TBkrKI22J~C%zkB=`#a3-#|hrT9}%XeQ5!sl~8p#(@YaQM5CG@R`mg7v?} z+6bc&gqlrJ-OkR`J~U3@?GHx}dk-b2Yiz=#+qs=Q#(Br5h$<3qbCe6hx*<)K37X>z zy^>G0D5&|TPp|H*)O@%I^5m3fa6>B@us(rc;rEfzLNXlirhx`|frgF>OEUG554EY1pgMi_1*UkL(Z)Zb8|IHuSj*jX8TE z_L$-8Q_a4^hkKHrZ@Uj|Te-MvzcfunH=BVj6lf(GF#twmK$6IaQ!zQu%P+@U#O zz3C?jcTS2C5y2WHyv6#r1IOWj<5D4z%JyG0?(JvQ19;liU|T6rxw|~OggJBct8#}J zGZopj@+6U$Vqv1cJLm1`1*FdQA+)xci7wy|o*aAQSo<2yJBa(SxV0##Gp>xf=GFnq z-BVK>l06{19KVSYI{khiaR0V{{bVX=+d!6wuf@?KR$L~QUJhGAMyzJF7@)mB%3u23 zgnsl!Siyb&7xU;=#BI4Tw72y^^eTVeb~8E7Nq)HCn(cC-)AwOA^?G1^otoph$a#~U z(dpSMjWV5cOBdglJ42*5Tt~jYqP&(`G1@lfN))_PF&`hot*_HF&GVf+bQ8R-+y`%$ zddv3ItRKOr))^H42QrtH=xcJm3%cnRgLzSuAS!}-#(*!Km{3@yXHK)0mi03xV*ZKW zYoBWt{1I-F@bgoHws7Y0!#i9Kw02YGE&s7{3jRiWp^mD(>%@1}J{Gj zvZYg8YA;csB(3tn!|(dmSM_-0d^}TB@!3uz;^?lGnR_}r5sKBqCK6d=l9DOXhO4vH zjKMID2YDp!_%*>o#gm!t@NF_opd&mB)y@!c2@3`3*x*Ktip=Kgmp7*#8VQ3x6cjnQ z1;d-P{-wsnrS+M`P`{K=21@_bq!`{JT*-FW_ zEAfhhgWz|JJT^dQl+~MA@s}boc)(s)P3cLi->s7_ocIUx_!A!nZ(I*y45L1|C})k` z;E3v7PwO)&Qe)gc;p^Zux9{UXg~7Igxiy+(4Av}tmuRv86=GHRkg$?R4Le31ef_b} zW4E|4$p()1C|vS-X0BFYRVVkdpt?Fc0N;jsqDE6<;`G_V-V-@p9w0WMa#X`BdpX`YUet4~OX9P&( zrf0Q>S(pX`ae@Hm{(?bPe|t*u^C>@x5TDSHJ+V_I6ZR^oYvE|q=FppPmz9&2yvEoy zItb|MS{R?`+A^*Rj;eWHLCgdf#?TN~P&wt_%A(~y1*>5zzKu(#4?>DX zYMt48)C;y#)Ny$@LB7NUEAD(lF;r60wAgZz{8%=T5D5G(xG={QGrs{FNaKsM|Ii+S ztkHu_($Ak2w(?@Q^tbedg@vjr+kM;YvyGBLiLnV8i7#Q8=#Ao;o2HxFhjxaWR!$N# zr#J2X$;pjJzlA|!GsJ_0b&^#Vz7RGs>aa|P=f*mUT%^A+^p8F>=TTT z9$qGn&_i5mY#5SORijaN)frT)bjL1i$2bNvgRcXigEkTcSOC(yzK+DWS+GTnPCdGg zh)f*Up$^EJ=m(xbOJo!zQb7M!|0i5rs`|oZw~IWS`boP#e_;JgFzKKATA)+mw&;@h zs#>!_(a>`zf4aeZx-l;pQ&!6~U_w(SHqdrU2*f!l6aO3M^jLkwFkleBUzNjmzfE90 zY=$Ya8Z`HX_&m1U&9B1ly1iVFKN>z{Hm`1`(ra@0Y!ui&DL4Au*84V{BcZaLc4IzJ znNOlc-4BOc_nAKgp^{E>QVRDkKXyx9Z7+)`a(E)FuTsC3^65kUW46@58u(02k$ffB_rl|0Bbh2q&^IZd zFks;qcfY2{mBh$3p8G#l-_9kf`{q^{!Q<_bXs@B~X~k8DZ;PK>mj;jcf^>f3RUxK# zEI!imP=bLVEnu?M86^L|womX~P)|A6D_Nz$iyDEI(hYxsu`dQIzXS$XIP3#AQFkKJ zOgCMJjMyXur;gL4W8p(FXs{&-1|>&?tgc!$MueP}B?I0A-WLH>tNWWblX(V|r6&B~ z($G65a>;-M1DQ@S!(^~0A}u9-<91>KU^7$Gj&bD|p4#h|aS7CorpX`=H{|#HX$`dw zgjT3A4k3OtXqL`bGxlQdQ|NfZ9};jhJY-K9*Rg)0#27!ug|0sxs>vus81+FScY2RT zmHzndH+4){aFf=G)CpgdVdHPmAzY=Er$iq;xY4%-lQ-iaQJ@X&! zFf*%7Tdlp8(t{Tj^1Yn10wRssQpBqo*phQ7JhA*=DgxY=uFi z2_H0p(eO{n`vbsKDXzl=uug)DgveAIkgEr%{hk;xua!ASe4JUO{;nHEOv_d4(P|eH zDE;0iu;MCsbOt%JY<_XT;vJl%;zSZlJYQ@-ma9Msd*KCpNCQtw*VnMddKZ_f%l%n^ z$eSMR@4Szpj*UkFQw^T%35LNd%1Q69H6rw<&Kxr0%0I@+A~qF&wiLFJ`@z7-G5}b` z8?e#n8#>$Y+O5a9H)AaDBGj7s&1DXs!s6mU4$cww?ZdQoOh5bTC9HO`M1~0kPAZaQ z^(5tW(|$1Px*aCFze(As2{v@8bA=eGqyjVKHahwDWSv$y!*F`2F8_ zCe2uBYM%nqgsJG3y1g?xy88Kf?5w$!zfZ-WgoLv)yRUM-^Ycp=I+yFXJBvp?^(U82 zOXsXh=jCoJUc`;%PM3>rHNKBNCfb|*beYsMf{HD;;L);EAQp9 zuc)05ELGQz-8Wiv@k&FaY4`qaGUQRXWb|vyt;jJ;!^ZU0*dt64De}S1XN!CqmhXH2 z+2Dxpcc!g3(__O))YZQbpV0F;*j*R$!?&Rf-wjS)`4iuV`TKqTb0+TxOxH2|#m(?ZA1BNG7mFE)|=>=UZ3*&g+k-N!x}E@2>5tzS`jQe)jFE|7N#U zmP(oTa1gg}JEMCgYWS6$YA)((#>Gwbnw$-`f-zdXHS}~dh6KDWm_K~@04H=Y^Z7pl zrp7%}@#m*nZbbnGnNT0`(lHVh@@GLdnb@Z|m3P@2OvgOx=;%SE0*>yf!Y7n!n&0~r z>9W9&9Qwmw{4HMx1$Gv~xv^$GK_WCqDQYo|2~aGzmecGnf>eW|`n-T(=mxC$awBnm zS5sWMPlHjCeh}2}o2RR#=OKp=AcG~E2&jENURtmkSAyCD3hW6kQtI)5wIrRG!>-GC zGMf@tQCJuT@{o1*1@$noi+JSR;fC4J`QxxM`&mmXyzh!Q_s;uJ~(7>t08ao4EW zMol4O&zMTHucoyQd#lNK3dYw;)FXrOFlIH@yGQ1E6;TRIA$%>-StV*>4gw77jC#%j zCzs;KnIb_qi$^>|y!2UdF^Ioh%fF8j#V-@0fWQqd(v$JX#FliYLnO~A>*V2OZqeO&->9sHIn-Y2ZjGK*-N zg?}kjc{?z@G00s@vpGgL*cTh9n-HfVWw$l-5(2a(JzBy}3qVuFp|RW6TLSJkJP2re5@hcob>7WPW- zv7Ow&4|Co!Pxg!`71^?8&a{42UIZ0Oz}1QX_ub;`+NpM#p^cA_j>yJ32g`QiQOlXf zo9(CckOR!yrL(ou=Gw|G?j57THKs3`4jW4jvzr5uF(2eNuYPT<)=o!~hELzU4&^tlQl*Y_ zs(2suUk}FaAC7=lgQi&OP}zJ0zXFT9O}hu$Bacz9tABK&{rmgOM_xx>1Vlt)2^;yV z#o4w#m$|+@b}jvwHL&LEQJ=oBD51WJ!M2R226KOSF2-?1HC$BC|Ly1Dxe zyDz~$HlMG4p!V5OwAGsSr>hU0ZacwiR8WS?i*#xB*|YS{5Yn~vpb`{*_dqf>>U-6f zdD7H$19_Cudt|W95_6^PDXt~fK2I(r$Xpzj?k(Z-|F3=IKLU!+?mrj48A6m-R@kS? z(t%LKK6OU*PgUaX!YAp3wwsLcgW;j*yC_)If7YLpbmF^*;1NQrHZwUI5a`?P?VHr8 zt>psQcpwqu^(o6jgukltdV7K7bHB-?>AbN#;4-j7ASB;=XTe95ou909iVZgAkXCK$ z*Jlav_dm_`o+{TLyzZBIxa>0Ang#>Q3L=P;+ni&dDlco5-jve|r4D9W5T!O7*zWHC z3$n)3WI-$LUC*A_Fis`<)T*|L3}m{04wkATmZBEnfL_XUGxW8xD)h|G7f815eLA=4{XWF@{W}HP z|9pC^-@?RD(zjwKKbwLAq%)7)-<^LhBBImhXVK$ae~NK*%bPHwMn}asB=Yo(C^c8| zGP>rcz8ug7gP z@`E&&z=>sZ6*PafRyt5AJ@*ITVsk;2FacLjEpUb4GnR@O;~is@CrKfEHr0MJ=AHQ~A4!T!GmmU@C!o$j~x6q)7#r~S%!5v6W+RnLi& zBd3gJ&(afLs@4Elxm&ia$*|f3p!fTbgXhAmU!1ig&_8!RhY~&9yLagCzbiscLakYB zpFY~VG}k)iXE!=heYvjNX3(pj{Qoa7ykb#b%=bwiF;I~gm!~s`+eMf+fgzj!B@*vSdTKffI zRyP0eeG=e0^>F(#m^b)UBj6kY$}M;<;Pq=$<*XW>LM~fzGZ&64#Y%N}C+&BY{jK^ z#wC#DOeYk1F{hdajG8k;Qs-Z-Y=+KhMNM{=n=#=6CMY@>1{C(yR)N|h*U!WE$<5|uVO zQ33gBxz5O!o~DAc)a*!;{SIz+_09gd%6D;T^P0RtQ`wXrRZdQl@(!N1f~tbt0QffY z!ohAoK6>Z$uyR%A`0w~AXUGAi#l!i$Sf3Qwr2+AP?e-q&Zem=fkaH-gt1tF9R4r_) zS{qN62GAB3$uO0pkSpecq+G|?WURMiqoc=Y==VTvb7uE44x$zf$lui27PxBE-!PD0 zC5Bro(Hvc5u~A1m({G-p$rWxN?B=D7V&{Lm2_Of-68~6ZYIL1s_r}6LXL>`=Dd>=i6ZUn%B7PW-w(-27EdYa zPQaXZ8B@GV1tr#zedcQF6KnLFm%PRNy_IlE2x5ns8Rd2QsQye<=icN0hYQf2<*p?r z&DSY0(lgp)49p78U$|s~t`7-Zf}e|jIz%RuS||-uK&eQ|z1R^U7$YDg4`0bCqMP$H zzP;!^_?yb?Gl)n3-6y&(D!NkTB0Bycjo_H`ADKcQ-=<1z^Czat-X-M+>?d zsk7;+OOO3MqVxhii2+YJT@i#}1>PdG_dbYeI_CioK0ag1qv&Ajxu8!Ph%%P97x&4R$Cab8W{H zTu$hBBfHAbJ~oEsdnV=kyBAEX4qkp-C4ZnO(X8;1u=!Pp;xu7yG%5IEQ0abl>cy{= zzyGX+VbqylM<3;Gat*hz*L-1&miG`oh*on*~Rv! z-^YF#Q_M9gF%6*l(GQ>!049Af(_f;2KXikDp(Il4BkZBTN#X?PEvqPR<(O4O_=M!! zSKArX@vXR7oA&)A#?AqGsiNyW@T0}&d+6@@I|2aQAxlp!NyRK`l(PkXD^fb}lVRqo zKdL3?Y?{S?gN8}Uf)Gg5CoOeZ@!J+AKL23SW}Q$^oen@n4ev~{J-%)j*`lhjc(%C( zjV{?tJau-(7W9ZE-*7x@SR_eK@8;)|?mM8ZpqDq{c$Th+-A_HDmrWzU^l}c=pOj8V!p-{+`CSDkLc94ThhY>YL}N88c=|!DqTsGi@oXWFXud+#I~qQ;leKeplOL=o3>1Y3_LDN;n1W?ym5jb|zf`v$R~j+0qv zjGQlKS7ki;*4w3)-x-zR>)$c!q46BynG3!8K;s2_fi zf`6Cl&tEfSFGm6!9?%)QHJPQKhM-e8`4aQDqgR@HtaL&oZM62n>V_~mx#mYiR7qhA zJjCHA&|-rco*|dg1D1SAmpO~UnFppXQhW!xwUdWQrS}%ktcRxuC9|`#Q3fTxTG6Xl zwTK=bn!QOi&BE((dlP5zLPa9U(9fPxVq_~XH@H zvCUbu;^LJ&>xb2>NO}|yQrW1f@4aJDy2NS+9vj#LQ0q@ZhAjw#TqdyG03-1A28e#B zbLi1K)Jlt=i z9H{?4Nsr@Pjb;4Fr8SFC;R}7_zbwq*68fu@M1ZZ*tdq_^#qNrL1RuQKlXj#m&G$!~ znD<#gb1TyR)3KZyQB2ucO(ryvSp(xyG$wYlD(%CQdO`G8geV0_R-bR(#3>hEg~Aa4 za*~;svuz|eputw^KW2B6Y8qR_Z*%T|C)zK9ZW8ftVz4rEIk(~B2H9j|S&?Aa>NO?6 zig5r^(Y)f!kvSZD?hXdyp$%{tX-hKT5z^!BXrw(eNmj}B8(m%T7K$ve(CgbORvY-| z9BrDcS3CqYK~YzJ;U$E2c^>0&ZAvY(R%L?ioW4VpHswOfLFlYsIC@Ypx&h`W<&a^9 zQNLos0lY!?Ih9dnc07G+?sRR|Cn(}!fgc@fnv9P`Wy_(g#^AGTf8*)=V zQzs5Pvc~7=v1&%O5PiYDR&~+eIu3o^pvNkJ^SpjuB1eT{1#@geC7L=}w(5J=>KpC7 zJ?HFq#cE=#n$jCEYE=e$y#Dw>X$-nQ`^<`kVhrg$bRB>1NP1NnXzA$q0iP5VuP{s9 zr7}-J%WTroXx?!!wN|fzYF97Rz(RL0NJ*68K5xzv|I{F~{28t89`C%tbj72<{VX#g zx7!i=2_Nt8bvQtKK+?iZIlGot!t5Oy``?m2A^`5` zzayN;nvn5+f>Uuw3%xzp+I8GEV`}FTW76$Z`7k+ryD^*!z3s*~R2Cg>1fVYfEO;-- z)ku@PE)QD@KHTu2%vyD+K9TRMU0AkL;EOaNV%hEMQKBQd%QqTucRr$R=elh{6W4JW zDJV{&S2#!B$GT}}Hmi%i4-ya7nxY(Ik4{G$ZlFRC;r}>P&=PfW|LBc)sKe4bH-CNK z^nlz3?U35Qf5`aoSRx`6`?o6YQt0?&^DVyTb=*j*#}WC$0Q!UGQE&E>$NitPJFQWY z;f|oS?^ojF&8@A)Ge|U7HQDKqdy!z-rL#mL=EmR_4`tG7(5~;NlLpIap zd&4?D#f`(QanxYwa|dW2P+GJFRg;MwF5FB^{OA!ge$C<)`@Uxgj4Jux%J;To169$L zMm8J}LAhBCfPxmk9r?i!zhy?e{tZW*3~y|pdPgl2Xyriw2sB`zh&>-4#G+ww^3kTR z+WJi93=@!eWjCH`y=NB}L>o8~tMaV99w7lxsP^eKr8Gy7@k`P%mk8r3`C_%<3C16g zSn3+b?l<=jaI@BU3KL1m$rOo$K*@qWaS)6UTfe*=cS#4LDLM2Fi?*_1-%2*MRMq3{ zrI2H(SDpEOJWiN8@jL7HQV2>Xp630r0QozJSOIKWr6sP6y_*zx~+5fw8fx6;fx66yz zLGz-&WN$3-8mE)m=InwCmQz(;0VvajKXMq;CIYfs?Kq@k1Oeu#W7SBc(h}EK8@1%# zvTx>Nf>23>*iDLPn+|S-Bzg#on*T{h0P=x%;eT6aFXf2_W*FLfmd`f6ygZuNc4u1N z_TZV}eJb-b9@$~urv6n_FCh^TCDw~KGT3wR!!KRL-|bFRCd;S`taQ^&I$-AiTMVLryk(tS6KS;4ei-r(kf7}fsI zcK zH-)s_EZM2QE_OTfW5O&am$=5nkLaNawa!;ou7fDtgW;aF2vUN}|ApqWjZ^2Gm`bX} zI7eQ~w^w~qBAqic1j53?%_k9d)C6dbcUKPJ=+h~ttpHjul>us0t;GZ__`~P>;O*q+ z`TP%jA#dN>5QpDB#muUO%7i}~XpI}hX5|hX{HtPg^K6|C16ExZ;dZ98{_xaf_gL+A zG;Wi=m44Jl{N^1t^}Fx9GFk7G^H?icX0uIaIV^bNeix_rRjF4LC@(tCaVXHq94IcR zav%IsNa?rqJh7bMbetlz(n9PQYJy^Q5 zTliAfHJTS0L#S4Vi8-O7+C?#VH$J8G9ns%!R%5A=tY)~Xt0P2p9+`Q|nw;<{W`uqk z^Ja#mR54+{ZPSQysZ&qd)Kii>PMW>Y{0bm$d*ifBCe|(AG=cY4^nuIEaMZe&w&Q4I z)q7@5%e4~age4y-)H_o15x8}+to1XwXGE}G49%Py^Vpf)TxL_GG#mJc_R?2et4vSK zg=z0>Z)fG^cA=50KR4Iaoex7%22*qCSiFL;#7aHuz5Q;0J~G@fkXbXGtIK@6&P0wq zYM$a6zH{%gFsQrlWXp3eI4V(h*PrNaJuxg$fwiXL07{E&=h%T* zVlS%17F_3T(uBS6Qio|*i?NIihGg5+?Blg1Qle@85$8S~mtLQ+xgBj5t~z8)rweHx=1T|Q)1G^%XX*GB^4+B`01#SjAY~Ln{%vEPA!DszqK6JNHn-B`_n0Z=!**9KXX0jL0_}r)U zf6g7;9c5>y!4zxCS#Z-JpGDg~BL|#Z{esg73Ss0Mc8NsvhqFV+Or2-Dz9&FWz0RBt zKDi|x%Hoc*JV~7ro7u`8Kj8UbCK1#yf$*0QqQ{B&$t4xK$g#Y5u0t@KunAhUrJ$Z;Hh`DIy2Z|+JGc}-=c5G{lZ5_K39SBUSz^q|mrGuD#ffhM zu`F~xP}HQTt0(9n*6K}$PF*K{yuRo1YQdR55YjUk`9c}P%cmgd%Xoa(b5IY{WB(HD ze?UdW)wsx&7;lPB<)nNIzHhMRVI;-KXtAd_xJXDLA}fKcEr$gEsWVmaFXYB@p0$=& z=ypOXw6KzS9=oeG%gCjUTV8upJAP2mx%!EnY*d$2XVv~V|HjjRfFQ{wh?Tlx{5td{ z%nG*}!l>dhFUF+GX_^{t+42<{?NJDpU@L*0h4QqJ|5o!NCMd6DH>N@Z2icNaxE zFcfuOR`wVluiEZF$6))2_d}Nr4Gm{-A&^nFV`4A@(=eB!#~OL|syIHV;3}FgwYHVB zUMF$dX7W^U<7$maX!6NBX%i~zw~<+z53#AgzX6?#ADUc;Aw=pyhpeeKJ>1N_Sd&MW zHDE~1uX&BmG!1aQYmzZ=>i=`EpYHm1?G!uWX}Tzqw_PnmZ#XoMzi7OJ@Kk3j=}0Hd z+RijqsI1!CJ6iu3tV)_SBUoW*%LLcxFh~1F zjDcoVa5eQgxcFHlcmXxqAY^MsQEc+HS2dQZnB=2PeZW_R3jn>zPXUdFDA&@Jt%sN=iy@ zk_5M&Pw9sLB6@m0;HO$-9J=r&$q>%xKa(kTCl(h;=4!+7GDjE8(9LSp&A?Uv0(#}E z(t?WRyNXP>NMJWwTq<*vd@S4gb;zlD4nbkyyd147hXxkzx{r%@miDMu>$ADo)W!ci zw*H98B0^5r+vCnkFf>2n!A_Prm7*ogV^stZ`}>Lgi-zCQ5EeJ5Q2hU#RZ}L`cj+l9 z#+H_04-Y=rp@D=s5WlnA<;PY+2tr_&(P85rD;XGsq@CIIJ&J>!@4bvEO*yVxP#~7E z2ff_z#jF2)SZ~u)N|FilAU3lXM`7Z8STB-l#4e{NSF7hI%%aUk-m4E?XAn{p3QQ*w z6J1TEyE)QK?(!PiLrgSO&5*LEdVhKtSSh9M>9KHgi@V(4OnaDBiE;ctguQiGR9)8x zOb9BeB3%Xuf^>&~lqk|OfOHNqG}7IIAfVDEAT^XQbccY%(A}L5DP7;@zMtoP-|wIA z>nnB`1D{JuIlErnX*_N|vDxfha>Df!!-D zHkHQ6iK-794>XE&5@wp09ur+&#+_c8T_;p}G?koUdLK4=#fV?@iR6{_eOSBo@_L}_ zdQY^OX**9syFZhcLj3f>^{{To*T|Vy8!bf7{wLU#6clFbKk7X!`GDOh&;1*Y$Tv3g z5m&OE!80k&25pQ%?7k@IXccaqR}!#&7B9EkK2C9stV>?pcfd$2P0lw&QN3l?&#o=% ztwRBA(sxGD(D1Qo@GB)KDOyIx3S^4o{H>F=TRUbgXqdhf_F8-U$zkW4)QQp{c}B)R ze|F3wW)#cP{k)p4`FMXVAXskxB?TKB90NKI)#k+rBW&^!~HBJ|2 z%M2m;h#q5>%|vmB#aqyr7zhN4`nkWgrYXYNw9xf-J6v|+x+F5oI`Va%T#&vl@twYrXPq8vkf;@jOr4dZYHs#vzpZvzHc@tn4N1k}pE<}Uy0 z=jJ&$?kdrBdm9*syIf!Kc<$FuolYM2?WUg@wJ_-|b9lq)(_Aj1MwM*Z6KoCJZ;@Xu z6`yQd6Yt>*Jdz+x^YkmOzYr8Z9;f}rzOMQ2ZtZz@wbbx;Sx8g3yu4h#{+3@Iu8q@! z;ifl-T%;LTRStiqV$LX7o*N$gz9VuQ_r$>BIq{?wO;N$Ec{?cSR^~w2c@TKN1f%B_ z<35%6FBju@4KP2B`*dwr?Yg^f%CD%f7c-zD2`XH4iY#8Gj@0LEDj%NFu5TD}_!cd( zvag;~3oL?q%!xUrH?J_Mm+ZF%2qeA5uWJ!u@WU`kBM5Bo$!wM#Kb3LpSXlAcGr}ADA-~kTA2_6SH$6h%(hy9-jj{WM-<(|8hSKn?2_;ez3D)!U;D^GigiAeH1;*~Csd=|{M!WOh{ z>tF8^?_G~^9GpC(en+>Eq;KAKwIRL~ph2{o)#w!=5A63rbDp6Jk=}mdC%NsS`sN86U%F-9zkqoYbz<18H8quaNwJgHXJuItg;26G&qr)p^8C=I zk9fewJb#|Y@^)@K-i-#%EHb1e_7Km0dTRwdy2OqdFh+oz5656OH4-n1SOdDZyDJ9hp%4R`KHqOei>UpGv37)29)S zOGAK90*Yw?`zSoM`>?1_0tdU6a8^kC%k=jwFF7@XvGKBsUj*971knS2@vz1;Y?msw zj{e*#WWqUaL$Aoo>xlN<_e2fzCUa>_l~emiII!DhjlD4qE9Ywi36ovjFO5pNUnXY+y3w9I-d8sV)Rexh^@u1>_^d~3Hcb#NfF|BLEyYy?l01<8yhq0{lSLF zTWHK_!0pGztZ6Ykfb${$<_#a369$=MZ_kzEj}2rF!Nx%WnhyT06OcEBN9u22w9CG> zprn41!r%8Xt{(I69Fs>qH3Ucy?1R+}^-t#G9ciWzSF z6tvGQSv!{A&b?-Rp84h8Q{$n0t>PU>;7*b5bVJ3*Og~-Glcr}@>&dsn=&wY5b|)g0 z&9IG^%uYM!F8Mj=FWI&yz8x4;Z8?`Zc2kA5S0c}wZ|8pb3;8DvUH+Nuead=0(RldV zkv&k;ik6nvLjU~os!U(5Pr%^t{PNFKTyjR<6+1GxtJ%P=?UMG`1ym&iNLB`qqug8> zBn{pD;39Av3lqa}4iq@cR*JCYLZ%>9cRD$t_7hfrit}4dkpp61UVJcTXMGCVIDr%j zW+ybYTb7j_3?S}Cn6&xc>4}}2P@i5^lz=FXIVk193vr|yI;$E<%*Z=MSSGn!O%&;8 zc3{WC(~DlqD@3@Zf&U4>qnantlw%^)h3WS|k_#@O=E?oZ$;qC3P%q*>CTVL+%eU|( zwuL;+H^Xzs-iQ!|=(MQG^-4r^EE!OY z^Af&J#c*OVcE_{{-Cqx1=Gme zQRVldJu7fy3L$LBznLS9spMLcj=OP zX4?W2p%ro{Y%-fIX-GN_N?zSs%~;`4h|&4d3BUxbsdYr=6k0djQYbP1uNPqW-~(vb z;Md!W69RItuoW9FY}KvfGfzpC$G-|q-(W%FJ?s!*ut0Y97t&mkl3V-|0$&U*S~&Zi zuxB_wDlv*nmIm#Zyz5i*!|O%WjxU|ET{RZLMfa86SdNFQJx@%9FX&ejBAl(p{*23g z&o>%=fmA;j&NB)ucCe^>pfB@0aprT1pxW7?F$!(|pIj8IRf}Z_)~MCF32uJ(ih@GI zNc89w5{*B``WC7@ws?S|c!FS2j6=0|OG#OrYe#AWeETN|-z_qRRn)6%hY7Leww>?; z>)jR=cmDgrN>ki!7E$QA*(P4d*JcNzQRC`A&Vb2KLXOFw@7hfYt>*JR%otc&ka*Mt zHX?Xo6JF)wshAC&skNw;0LoBfp>XaW1B!meC0J(A#6UsY|?)ER0dw& z=4Hqg{SUl9RF_Xl+|0gP!V^!+=juO2UM!GTw;mD@+dhXaj~|~5aa_~Woi1?*Dfbo%N8(S*RNcrW5@Hp<{9D{7 zV8{9#+TapGQfTlpX;k;eRy|VZAkJ=4|0;N`xT*LVad1us?ioARy$IDnY?sg_Ssk(e z02Y8MwbdJZ`Lr1=8_1dynh|)I1iIByRWm#lZLrl4!#(_Eh%jzs>4%-#oy0<4 zB<*ourPYE7Z=zEKOCXNxBV#f1%qa!PSm@?iSw)Nbs4}FJ?Ds03(qqaft*PDKIN@!n zl@-xOFA5R=2)Dg zbT7J+TCH49Tuzc2&v{*HcnxmTUoYt|pR>6j7mle;m&vtGR&Lj*!b?i7F4GnTw9=MS z2j>jWk;S0F#h)K`kI5DP7o{(MLzC|(VCJ7?`7~e{WQUC;(IT{3TL9Q+3{a8J*Czd@ zHFa8J#m}P*seCV`2ItJP=_7LhKoA7KrKSpN&&`uP3%`OybVA|gkb8rtbr6r#Ky`3V z1YKnHkteirl)sLreAz3#F)amj&D`2_1xHu%!TYr*$QX_&vJ6Dz#N;U=wlOR)$EXBV zUIW2Wef-OzY!M5RgbFTVn%YxrchU*s5x=D{^szk~VA@lcG7Y<9pDUh*%Wi!`-Upe# zbtV1yoXVjC7ePA?i;kJ=jC5hvO~pEMe;T#~PU2jAqKjYCy4ESWU*jZeAMeFo|Fyj^ z=2f(x+`}8+{hhYIUp;5`jKbj~9^sW0Le^NRyH*MC#DoBXXLu%LM@ z;*R>%)Km_wONj|S;bV_`nhSQymX!zjTVn@uGC1N?G`HeM^)xyQAgI6l{rA|DP*&pj zWBHnnK{=KYh$p<-L99P2w^2}3A_q7V%bBCpn-kGoEr($f6Ft0ar4#=g6g%UunpU*z zeDQ{~PqBnpRY>8kR0OzYBbyo@ft|-G?~JbO>LoLvt5IS2%7m@+7vDc;H+z_Ipw7IF zjY+0eG{kCC_-<#V>aaOlKdf==6YWp785P9*P;NkwL{iz2aA__>=WzAgl(hw!ZSD*w zll*9Ef=c8AGnrT&8zTQhmKE?G5ULlVAq(zNKjV=Q6b6@k)cCq{4o(16k*TrP{wd1T zRFs^ccRY-L>_XW$w`d7m{oafV&%MZl{eIE&&qlB6}{fZ^Oh#mo}HO{P8h^;Q)%XVtie)95kl@x#69 zv|67%vRIiCTYLS}(l+TB`GFQJ8}nx>2x90UY*+z*ZBYMfx2Nw!7Lb%?2JpF~?=7V=R*3qt|* zl&a1M9_oy~MhB9d-DJk*Wp8H*mp=)~&}vz)iT0bjN_0Xkkvk1Zd(uzP!dmomI+|0U zBIUKVb`oVgzkooFSL7R47P79%FB({C;8KkM!P9tfnsbtprT42~T=Uq^?Bsy>#i8*3 z0DSP4e3yihhVk?9VV<%=l9G~8r+IbLvJSHb_d8bN~gILfYwNp~6qTcPa3wNh&=1--EdCE#PqD>#Iu)aOUD9DVVbu0@|NX z+a43~U)mK!?tDKyDKk7sA=(#QrmdC}0t_B1FSgaffvvvix1IJD@ud_7hdfNva)b)c zkMW|1fTR$bn6Rc6la84DD}Q(>?c}A1b{cWJy|h>61(i#53!mr_MY$CvQXz3l6Ll>K zeV|byWB2&Rj0tc9-kYKExTukY3XGhjlGAwqFG|&j@;7NNtXIBVJ*T3wa_(Do-h_Wc z&%GUxP$b1E+AFGKZru~h?>5>{@hc; zJ$$BFu+>AF3OK(!6w@Kxc?f%>U-CTikV4MLE zjh@0yEn!f^SQ_`xP^hByT&NQ;p@bAhZ8`>KU#yY{;v#=8T=D!6}%P0OocQVJ58GkqaSL#Nde^Fo{_D4T^jrXS#t?5`LjPom{^ zzouO6|>b@0v680b7~A`R#qkoQ7KMW=jUu5}#IGc2ckMiY00^Ljy$)O{2eas|SMh)YX*yH>Sqw~XBI3j9ECccZbB7$1bw)O#) zSsI$mZFkpQjh+K6TXG{?RL8MCmoCT6HZ@%ts*rbe*Dacdl&?b5KDCVjYNJxu zfggM)>t^}$UzU|DrPZL)2ng4+IJCxAR^dw>kp~lf-mz++i9#1^F~+=eZC+vF%6N$} zMzXL|*!gxXvBD5cFr#^W1xfJG>U&YC`RDur%6iY(p-bpDh;_DAwwfsy-(W|O-CgQS zJ%&V}wh06q?ye@;KKRt;da@9bRjU8b0)2!^@(|Dj`@tyI6J=?dVA`9eGY;I^7cGA| z4`p%k5LBc^At4~yq7+jXqyYi~UEECXj_sth@g}MwVZlU0Fj?Kg!g?gh0vtk1q0*!3 zRbhPJdkC1QXKZd{w7rt|YZ1L=^bAuwh>9k#m%glZ$6w!U?+6(g&#ZJ{xYpEy78ns` zBU9!Ic(*sw0pWVdQEwu~@6_1SUsYe90-_t{i}QOUOV4u(tQ0nv{x%I;nwZG7sFiA@ z1@zo(kswVzOqQSD?;ReF>8~}MZ!eXP=@}ny&zyLQfk}yg9`Xb$oW}ty^N@Q%lmj3uI^`Lv<@z~)WPBUfG;?0%DyHp1=_n5j)9R7djZc-7Pb2F`baYFx`Hky5VZ zaC2zQ{}u89e_W1gI%Jg#P!338b(G1=dv`b~A`gCK4MGcFdCdZa=lu7_(<b@R|Oh7JH)T{C_lq;e$@F7UKu{vwzNd(J|wqTm%3kcsAF1(_*~;ooK<1Su7fOr zwZiz#@B8P}2m8?iJM!2#6IW-!QH)Vh46~Yig^#QVAu=AQzf+!t}a?RapJxArtP7b}<5z9C`HE z6hEAB*Du(69y;+>y?jWhyQs6vQogmxJVNjcS5hY;4wJL4&~v zH#p%y*wC5hbs>*T+Wxs)ZifG4Mux?KG*6x{H?q743b@b)r>$&g8mw0hYKXv7EwuI@ znH(0Iz|t*O0zW`KLhHCZxI{Pl3gX9~vt{j0i90WQ|w8~vE+fv|O?-E}(1rUqJ3`KbIU2fIowbWpzZ|2Gi{C64$P;Jc-uB@26qE3}1S=oZ8iYht8N;@(|(w5Ji zl(@&m!}8s!8Na0AJzi}B(mHyQ@9g{>97}B*AKo7RH!en{TNr@a1?%8fk}S$`DU5k? zXdomlff%RA69qAZ-8=?=pxT!93PRBi;6;G(S-SAP&74BHJ~32xf_;5|nwa0hhs?66 za6=>*T2^%2T_#k@ndwmFv($ylD-fc0JkqMu-1V-E#)|4NSqv(;)X|?oCO9YwX`HiF z&tNBOY+MM&$-#IXIV-%7SGEBTh%6*nd5|-(n-gs^iS6B;^*YuyDxrvD*IfkO+1P3{ zx^fP5)Yu&<_I7#&AEuFch_Lr@|CYa|=(ycQar8joDBe%+hgscI$FM!~@L%O>b$gR} zzdWcjeA6{fM}+ zof481q7X;gxxn=$#m5Jm(uH>Bwe-tIhR9Y@$Dx87b3d+@a!6ntY0aDG5UJQHQiX2v3jMxzz*l>(X{ zfqMT>M>@diP-Qc6D;J+o36q7D)onTY^-Zg`QX3zTa^xWpTKz&rJQRdMDCYKD1KI1z$1Q=h_fo@+mA^4fzoQE<4;Sn_eY(zNWN#-( zE401#!^n%&Oi^#aazHSXapYDQqZp}VkFK>f+fDz?i_?Q-aUZ?^S;`3Bi02AVVHD$U zP+|&~p>I|;!lF6kP}8=LA@MnrT?qaP49%8y024j9mkB~pUYI<$dcIMLX-O#_Rzov8 zzB-GMx@z@hN{)^;h=HW>Ww6ykmXj{#rSiG0S9r7oHBIWPAub%ft}vChIZJ2PkT zr4BZv95(XoWMkWAa&mIK(pG=cYNYMXYRkf7S=nGRnv7Yz1q)bP-Wl@<07~`;g<%+n zvVl2WsV_Zp3krH_(6b&pDVKg_SjmbJC%w&*Dg-AzPGKd;ovXS$~Z-y$(+2#Cv?{c^~B&>Y+E;&Uka^ zDy*wWXCc7LE7|h^B{U;W4No#4&Dfr6q?Z$G#COv>cyCT>$>|Ck3CT$)7KoY$SSWT7 z9Eodi;PKerwyCh4Ba#5;BMOBYN1rAw_V$33g1$NPwcv*d#Ww3>m9z@o)}{Q+#rh%e zI#c4kMdUh=!U}QAJp}B{By!G&lj`Vr`v0^+hUc28Dyd!2&NgYn&3Q#ciqup@eeM+n zT$*a=9N`cCMPnR`nvDVH*qz47f+L;jg5#f9^QKB7oPrqUh!P`Etu; zJO;tDFeAfXA&DROo;gNtd}IKY6~OqZ_pE<3fUg6=fGtNh-Q)E9oW%ajf&G;l+al zL$pAv@h?m46F=h)hub~~FZ;|6WAz_^4FS*d=X0l&InCNwU2^tafKvgaQ=087z1GRA zMzFk7kID5FB0iM8?YyviuX&#G;;Q;u@zFo{>?pX%OsJDA8SB%&D7gIidg%S{?9v_{ zB6`JfpdENXVj@*<>dWp>5~lG6FOg`uz^<;hNY%~Fk^J?VUeIhNH!rW5li;S@XGOFk z)03x`Zv6N1H^Q8u&+YYfK0}A-iU;&lE*d0BgLZ;{%q8|a1fQOEynBJJLR31q9KsfX zx)Oq2I|*aWwmg`DjC6!D{t=|L%$DP;oY8nC^{!+4gTZYbcx5TF23ViJH@!Cy^5mPE z(@$Bszy3~v@uvqo_lptN<6l_yJ6=25|3laX#@~iV;f-NKw!()`aq~tiN+)1ph@)Cd z*ruly>+^*PeDa?2{C)?(9|Cp~I1^zKlRE0{2BN)S;nKjM1z|b~?F?Umv0>%dNm!vI zw9w@;D9H0)SEd^s-*x$qAAy5|s$fQ_ukqKf;R*_SfYiOoEPV!sc#QGqJt5sD&>%p@ z4oMELuEIdvSatg2>EDcW6Q zV*|9Z`suW#9u^i><$1~t%s@H~o;PhCnVJl26A0$n!HNA~fVW%$Vhx!fH0|Yd50^&RQsr;3HLHO{xV(nB`z)1i; zj`lf^NZ_g;{ByXEBqaq@i81gP?$`A2DC72Y=|O`KTE}OX-k=6XK|$fugGE$U%#J0Y zk|RzI%WpD3u8ZC*Rx7bMK@*9RD3|pVAa*b~39uE0dLlou&@Jp&BMBxDnDNnnJFSJ?Ekuu!TTyNG4z3kD8L`9-${;vchR2ku9`-i z6^|;pRzxCYhL$ZH=-+=`&GYio%ZrJd2(DJ&qGWJffkpuwh^xTJ*8pUDN1^N?m5)R3 zKfW~N=`aPio@&n^XNAbjyvDo9B9FPuN?@Y6fc?AB*3g(N58o7KPl^DpQPe@NfHbN= z633=XblA@IV{~*nrPS~UMd~WPqG>Nk!(NDg2}k+kDUiPu#j%6@bTeyPOk?7R7)%s# zotvKPVfrr%_fb1mQ6<{%>7k8X65)f;<@gNO>D1#?BU9A{y^7P^gS&GDh6eHq3R(t< z@3|}puV7NB3rL6Rn()0l4Efrv3uOnW(VWY2&ukkKGrrr}T&`TvR`)AAijW;e2SzRJ zpF*Dqzkmap%Xb5*Q@CJJ^r*(mH6GkRLjPeIoHy+e-$5dlKw*q+1BMeHaE`7fzqJFX zraS5X(w0Wekd?fdR01WZm#1!qj~N~a*Q6T1h}OI>N=J;b5MG@GC^$oJBuybShsC^1 zJ!>0qXn=?2AwbDk+kU8>SanzcAQ~71C+SWk9!WU9e?N*oy}9DFynLnLY}{l;hEE(~ z`cVe?D7m1V&K-{}8iOHS zCJ@Td+#D80^2``pK~ZT=SJ2Yupv*d-O|(9`*`i`i8OYa*|1Zbt3+2-NVVmc?(8mar z^QB`+DQJEGwydeCsRZ{)C+YMHn6^G?HovG_%z_15V-nFPu&R}qe3YBezL3$5v1izRmfk;X<4 z`oA>W!m{!Y6LA8XlgAL%1>r~0_fvtPRr|hp|Ad8JS`TIE<|(#=*v(Ce2n+Wh7TYXW zs0mV2$i5d^&^!O#1h>qW-TD_eGTK6Z`s22v_(reF=9io&eljSc8S8 zRDC9|k6g8L9B}T5UpEi-VuEo~bBk6%^+%zX7r?(mSgMDI>AJNJbd>{W7~qeZL+=7+ zgr@@M=$!iGo$gDeai@l_cuL3PPF=hKh5UmEMaPuBNe2O>B$r0_G>9d5AxrM^OUl2k zbffC`M5mSmyQPqxs`wLM$^D>BI5>$Li>7vT4^=>C4E z)&hQLv&9okH8uHK{^%solLjPi7p_lV$nqheaAs*>(FguoK;raFtxDk}>PG)Ad)xCa za%T276D#YuWi4GQ*0iyFaLj4TP-&@yXzG61<`BruF&foxSOU4pN#Mv3LmwY_kaK`E zd;@UD=@z1D%1x=#{^X7qpLxC_B+E;IhSio3LPbQ(#r?$!?)gV^jqv4>Drlf;;b>*( zjCLnq;$yZc>UnFZ1l;CZqilPKz88WmEX}-fYx!Q2}QpmP$w7$Onh=L%o z&;S$3_~PgHu$xZ(&92i0sez|Kxt7l6H-Imc_(OJx8v<=({06h5={Qv}39Ug~j?=>FKXnQ~>#fyI>a&YPxzh#B!9<^nQ%|hcUJxig49=N;mdg?y~)P zbU)_{$4700?-5Py!s0_z8E2PQI2xG<%O2pr0a@4&s7o*ZJ3#qwysgIs+6?eVaA}_= zHd`QA4ngt{o}p;!qp8Xrqe$JgPXAk9n_OUblrX)kOZ|(}6t3nf^YS|DUd}lwBNgU8 zN`ut@UF{sHf^oj}nHzLvgNNugpo?Knv_0@>6)(8;N-f2KvWB}WVwQ$etya$hRlC39 zLBuFXYUK3g|DPp~JN)|NHHTx(xhVEmMbApU(#~4m9cJCOI%`(__xA1cOWt(P zni^E&@K;ZsA*>J5S!4m33mi8;+CUY^5?4SUc)~??@gV*T!8|3oId2V4Ee5xWf*!FM zd7*pK{vfvS2tonU`AmmiZqgN@;KCEk>brR6_tKfRw%&JCnHf#BjHmRHjyR2(b&1Ex z>Eh0~s*Y%3BE+j+W@xa&df>~}^IHwecDu1fjx2m6<%8&K?x)PCkx~j9Mb^0(79@@% zY-9t4_)GQ)Ok!8|S9`2p3618X6?Kie0r~3`#>U1p;@-)9-bctAx?Drg4F{ugN&x`G zj?c8%^TT;+(=Kyf=9BNlDJaAB#JVM#aW`2$tyWQ`40M|b&FIU#8G&`J?#ZI^qQ%$) z<;T~L7vs-o%sj|&dx72l6|IZS-Xe3Vt!qsbJf`k?JjOA(K`S)hl4q8(Xbe@&f0NT| zZotmml!kc2amu7gZoW`8pe|{U*&+#lq@k@XQmm|4KBE9%NJ5BO?=eoTR16P;NU=*! znh=u>{8$k-0w_I>s}@OQ7bJ93cxHeZGp^feCuw6%{u4#o$NiQcy)S3^c#53Bu4)U6 zKu_(w#h)oy0FAL0q^Jc{?})zF>m^e#eo)oHIc|s?5aDa1t9@x*vGH72Nj*IqYw)GB zh_*F9(rX7hulTj9cx8K?o)IIX1zZhUTRk1F-oW~%0igy2Fj|-C5-WWlBN#GoG;SX9 zQM(lYEI*u}+~US7VNhm7UtE7g1qk-`wS)V3LF4rv0#lW?Ym054!o$Put}l-r_m|&b zQ3j0U$a9X;FIsL0^Q*T^b1PHNqK@|r>ItXnYNjcEJ=M5FSYX;}6dc&ju(Tu`M5-rh zb4){@IU-p^>MQ%cwO+K!f`4r5nJ)D|P)YE{%6|0e5nLj1%kkzbKX`btrFgy=E9Epj zJ5VA|!K+Zmtq#04t8O&f8TE%2mh-2ZYsw!D+@N)Dd3PpOq{D4_5`;` zhVe$+Z~e|g`fdB?gsc2m0t02#_L~TD53cBWkgDnCT|TDF^=6}M)JqZOYvUmbaZ9pn z&c`x_7S^IxGA6cA?;|EhM`69EIyVb0(|{OSxmv~HLMEh20cyUgd|dprQ|W4N6_pg{ zPK)mVjLS7@Y=ST%e&iM!oz>8gTI_SV1=e}DUy68OXsFfaOzAo_?doq1Kz31b4C6IU ztaBHu0&dsmb7^blTxWeWOBYRoUyYv<5E9&Tgf7*MqV}$CRV?5q3pz!+<|Uns93+c) ze0C&1qe%Rqy2{p^P8qH**17jd?Hjbl-kg)qJ(P#3M#xF*SAQUFW#z*hLJ2dY?;&4j zn1rSr6W~kye@MKN3H6MPjKZUvy^A*J5Tc3?GUEiNW>6cBUVkH>G4H!Fv-dx;k8pg= z&Y9g-^&vY6IYtnE<@i^@E%$>+KZfxIH&f(c^sc(H)^|)bf)w%IpyoG51DsA$~HrTb2y{VwRGv2>R-xp&aL!!QV zb#6g9sg{8uowvw-VflIQ5fSJ6byJ1V6re+FY$teIn^1kahc6&18a}p#GY^=f6V;ug zltTG9b`^d7MhbZnP-S#CNb;hm?}7l-^2nV76lHw1cj{^3Gg_>##7SY&8cZl(vE6u< z->6mUh!3`7!iU<=D&`XR=bJpY8u&kv^`P|kc zKDq?lQ3Wo-rvby)H(p4dzn*8yZ!l6{91l`$W)@hv|J*8&XW&Z$@#0=19XPYb@qo_YA@ve;!niqb!H3&zf$FHB~kovH|`U zaFp*9759IUDD9qY6(68&eUeZ~0tYwm!{})H|CKthn0Fy+YD>ln(ZOQ(7qt4`^hQ)q zC^v@UO>t@zO=uzwdHhiDfuawNXI%^!p`j|WPrfo>Je}+qaACj4TDF6M?|P`o1utfJ!h@k9ACq(gQu@vZ3RW#hkv zhx0Ujjzlkef?Q^^1Xi7In# zp^D?f0btg$hQC9Frl3lo`SUp!S7n=Oj1;2soUZK`?w?@sF*#uSC5-?4JULl@Q@qi% zw{)>M{|IFMqWu$ZGCQOIo&rvx8#VMQvvSOnZl~Tk0*sP8km_WHK)=%sIC+bcErCYN z1lb6M<8kyw#E^x0F3V_aWA%;wpgWK6RcT8FpcAzpGtnD!qN`O&f930{seOI#h2Oc= zKROyKu&(+zIq@5grZWx>N3 z{dvhQ5qY0>}ljo^OMRlb9>$`NuMat=nyB7@l}ov zqHh`uJ4+NlhraGAS63uHA&~98MfrT+QK?nQ6k>f*d?T?__QYR%NRs#-F^ z!xS;mdh+TAd0E3RI}NUxi#Dyl#am=X7}?@v;jDd)EGZ4#O~@4LTc|j;=hBjGO>u&d zW38}f2m5pdHQc!>oG6Z2oouRLvANRXugN277{7N?Y*|QCaRXk7(kYdO zu^if0ck+{$S63$hxFrAwMDd$$!>L`{qvyXB?Tx8*avrR)&iwhaVYsx;92Xqy%K9K32uaF_ z!(HG$7J?PV?z@n)+r4i%iD=QbyO2j0wM9fcvn?Hr#@<~aIwzS^M2WSCchKr6D zbUDyT&-XTkZn>whl-`)bb4^;?2J1@3kGh^$!MGQcx+1N{#(^E}7`s2T{NiF_XaAPp zeQc8oCH=lVQ|t1|QCWO1RB0Dj{D6Vtrl4-_Y_zh+`bN7U3JJLBWQeboxyqcOTz~gn zq{HE~MXxSptKMQeppZX(7-X_k;G&C&u5u0&&=YaGgn97Y^-5kBtQxJA^U;5wz074- z&8&)P{)&q|r+NOwWYd!>C@9vlCxgXvWlhk9@m-4XxBN^-$ZZ`r1m8i5vHx9J+W!{gmz>Bh+(Aq8Hm-ky?!xxDnO3|Z530-qnJmvTA zJD*01w%~KrMLC@VrtcjTI^y4JpVDl;OEDt_uR53&*%Kzf{oL4FVsV}JbLmByaWS6V z^-=kc%Xs6!yCRQ7DLcM1E5*l);to*Qf1&-*Z~SX<-cHzIy6;Wf8B1?+UCT&@y{tUq z?!z^>bJ7ltVzM)nmeChY|6!MzhkKe>Nkc-lwk_ifUxOng*AS<%H-*-}xQ_tG90_P< z4-8n`gTvFzNU<*Py9NR>3m{h%--_SC8+)UkPSx3Gio3aQL}(YQ9S^d?STeo5NJl~y zK$NxthQu5cgSJYLLSXPc5p4hu&>$NiCdTgcRY?I>Jk#s;2;hs8Wor4u;jFU6{Cy0) z$`=_THI_j@7$ju7U@x}x>m zoAnMcp}p1m*+WAm7CAO;<2+6wZm#9g29;|C6juWf14Hs62>1LBt?{#Z`n1B zb)R|*9Fod#a`niyNCnk?+jL@QKT63dHlp6r5njlbG9PJJ*6;uSP`KY1 zcXsZ@0$7NEPa)b$kh>@%(*PQQ1&HOxzX*3vmLjp^A0zflBE7<2(|hrEiwiQtWpzvpX?aQCg; z*bJ3QW_m%H#}LAz@Vxmi%hLC`J|7G~b1qSa+z=;<8^YSw6&Ap07*jNnOV-Nr+nO*) z-INu~?x+_i-TY8tW0J35Vz&T^M~FEbSxp}G_(EsY)%AK!UbJgM3Z<=y`N^Jf&0DgGP<;W{a@@SohFd)boS?aX3R8+lfSrlQlQCEZC`jTq}yR#ugX z$>)Ug<<8WGieL-R;(oa`q1?OaEZrV-7Fmf|Dn zBp>R%?{}QhPSeZLE&a+*2Rj=K~_DFRcbheOBY-?hc=>i8t7_`C+IjYG#h#$l3P;b_%up zq&#I3|2)gW^^y*{R!#yQ>6qP{3a{TvQc~1oV34Z=9RiaLjwb^ zI4O9w+W;FRRQVU`C|~%>QiDM*qh{TFWq$s!|Oz{0j4o+@2KO(>I25jGwvv756=2^v!STjoR(%C1Y#ji(H9aM<_{FYjv2kbJ*=D}$wa?MEXkFn! z1IZ;hHMuW_oZWq#^{8)hZ+?<>|7;O_mJCBui`Wmoo1EfKnCjH2u^5`%c;*Y0Cr-CMvdUpG$YK2wI=H<{ zN9T)ihkfzvQZ$k-py|CHOX;i2#6x2;jvS2|`8_{3c#F07<1QoFjJVt|!=gP-_Jf%tOHkI2=NRhNDe+LwXmRp= za+*z3Qe<^>qdMQY5UFrTn28Y`=bATB9^CZT-w33jfL6#-2eq?a~jdI)N^AOSH;RzNN@J$}+BqYhzA| zdv|Wxfm$Bx@v4_}eZeV7A3rkF^UZXRDgVkLF5?63TQGj-I_PjrY^fBLWg+gU7Ro;D zQg{}gr9B0!Y)7rVgKuTeEgTatSdD_?d1Np>srtfFJ z6nZ)qy3~-S-L__*NcSuOBYvH3%SuVJmawrXYZyB_lL1bwRiI&ykbr;y_{IG!& zw{?F0(dyb7m!ROC%BhIFyywheSdkq8dwcfb5fN;chK&RMgOcc8LfAKx7gkgq!>$h( zPtPF#Uv{0;;7W`r& zqG^ixOCFAF)w`b|oKhrX?I|MzFIjkwaWYgGD-tzfB3qxv1wNHznf=bfTQ+=O_m1Pdmx5ZDIWg^S78yTM=@PGO2yW|Ge1tT8WYA*b0>$AcL^lFnQY zl`h*ml+L{K?%lkJaVFV!EcwbER5r1SM~2D=7ZGH1$n$A^)|fjzcxWOKw8ptT@zcf*_uCl#ubD$?C+~mn>B*Bx zt5I%g9N!#MO0f3CH9GPY&1kz?`+ivWxvLrH$DJ7u4!zvs*Gj^ogtxFhReX|eS>L{5 zC!)6*8GS{%ke6#dqR|q@Ic!#GR^T*A68fF#K{LshZ#=`KFJxCspIv6pbQub#%Y>&V!#>GWJg`L31Qq*$=jR8JpNWR^Ucd zGVjwtWr$;oV0Es0FBtNKo{FNul1gxk2%^dr;UQBI@fpja4M(EV<>tc5UOozh;DuJ? z=UZqiDPc@=e4Nt!NYSGnLv^e%JstB4gM|;j@uTXmqarbhNedsUDKZ}1FT95hxmm*u zn%GUTC$X-Nz~@?pMp!C2+s<4S#;z*$ddiGl43&Huy-dIA2$lXd1* z506h&@~B@w$x^|$$bd`gHMmD>Q#nef(Kx!9aloGG4hj4r7J{vwd4H$4uq}y($a7&8 zm62w~e@XQdgdi+GiFSDDgnwsB*=%0xivREzJ=-zx$8=rc9LdLz+qZZyJdbPVX4dWR z-5($$50$oC>57SVVhIQVT7u6;D|Bo=PErzBJ~l98 z4oo$N;0ql>Q^7uihvvI1Heu?NXklXLf0Eu!FD;dU$8JigVNi}_-E3@ijm&A2mb|O0 zjFz65B3+i$4)A6Qz+m^(zGY03uRWbSu^DB7y!kSJe9qG{gsz#*d!%*DUX%8i<^Dh^ zg@8MTwDhsXk&$ni(0;vfE+Ha@q`L&9LAuW~etZA_KIhEEg}^1l`#$f=d);d-&nBcGU(}HEV`NVOEMLxRBk{yv zT85Dq*OX{@*FeVHFohHs6Y|L{76kn^3@*H&OTk7rCkDQ{L!X0A@W{Tk?+ZfbO*E(Y z2%u8F(Qr9pj*iCt=P}um`eAcG&$3q!b8oMdi9>*{=`jn*Rlq{aJw+YB`9JsfS4(J^ zGOc$-yL0D`t5i1l0L4nMUFbc!)9YjG^)(@M-A9S|UKdf3c5_%nhc|t0iyKCEJ_%rz#U19H_zs(xy`}2w zJ4oM}NTn|}U^=cAcjl2A*ABFt;A<`}QbxRDi0ea+ci*cp>DWyqlWA~SC~*Az;dFEq z0%;YN!e@r+#vqkZVtXuAmb`teuH@Y~zhdBW4%ax&;-li|>k||gu2%mz-Eido*?@}A zWb)+jgB`*G3p`y8Fujsg<96kR=>I;}t#_9fKdYA8&aJn&QpU z5UvrjNzXc;ZF^yI+#{%{%&5|6^xS)euD;~Ct^s-(B3-{R%ChY@#g2C2@}^ zksU74v)?$qbn}0X3E3ycGRj9;NO{BSi&7Su9l{7eZSm)B*$Uyvs>3*=S zJT-b!u~POL>fkjqUr|w!O`cQ1Oz7EYA~8Gdi;9tIWCi}uAAbJ3RqpFV1+O%kN$SA= zasi&q^^X<%PThsKa=G0%9|;5bWEM_1fp=HxWCZN0u+Ju_@( zUWrxF^LJ{eba8y8pi#W1p{{AQW_NJSqru>fisFYT zpN}{X|DWd(+aC}xy_1a1CY_Eeru2Dye%?&?a|#2qElze@{cHXl3|D^-iXe|mFD+}* zK8dMOOh`TA>%fx$#KQJI@Tlu1m7@+K1=Cg`W6wM7SVF24(T5mi@eyurylSmpE&oNK zAe@wGiD4EZ!Od%FVR*RdSx@fxe)so2g~7F7*rfSwpn{^}|8b^bq79YAuguN0l5LY# zR<=ao<#(kOdBwWPEp4LuFmk&>fb^n-n~%E-%y)rUI5;@;tVoSaXBbI~Jl-;97N(aS zp2^h8hXlBjU;znv^Cs@H=^lqR?DNJ$y`b+zb;ia7Fs8484hwP~ z^>ZN1LpQJ+;~tkajVY0bLQ8;TJ5KAp?u#mR)RdK?Avz2Qi{`}nKjLisQ1B6#@fqLv z+*~~9l;iCtPcC`3K^XCq2Hzf*$Ii|!v3QDsfgvF$6e=7R_Kh}bXsNyQCU7V1A=j*o z9kSEh5D#dQTWgLT1#y;a=Cn9sS{Jhz$X~52M27d9Bsc8%G`6-?+x|X!Qj)~W>Lt9V zzvQ(8Ec~XoBF5}SLv?bys!EoT!qlVkYbK42jjo_X3Mqy7m7|YlGv-K{RKQ@l>XBW* zTAbxPQvC2(IoKDlP!ByLyT8N(W*Mk0A~1)dOy`Cbs^k-1Oh<-;5BY|I7P?G8w?yxK>-Lv zVsartmgNc0D^qQhtBqSu17eUP>q~*-BnHfjKRD}d3amMD@;`*wOO<8aD~XsOPECJK zCa5&rsTPoz;S!)rI_dyLI@i@|SiB;85U;rJoXRbl;*sps>rRaAHoes|@+C{Ea@P&K zKUNbsoHAwWc~K*bkoE$-0YueEmyU(aSaH&l0L#YWhv;a0FlEwlqN2k>U=dVxF0qNC z?0f?MCgtW;RuT{T+;oCrbc7#=qd`(xcK9_~uLAtItE;O7f%tYVu`cQ)nl)0xz$;pb z@~GnqUhf7}zH}blh2t*7+|lyO%-DbF$o)1UZqXv>K~ZtB&Q{!-fxbxUHnWZkNBU^! z0EoXE?{WMzGf!|~l*UH%hqrfQf*+9RP=GY<=(}@I)1T%Iua*cS^k=K9Ak{GPGrwN3 zlARnetJJ&09WB-hL>+Z_PRYrCT$|kG`nI_&o+j$idke_`EcA!RzA2$zrZWTLe2%#Q zS%_6KY)9eZH#3t5-&B4ZWoHQX9-9T8uQn$P{rIu`^*w9WL`~uLOdT{1UeZzk)%V&UlbUtTI`O3fZ`tH;P4kS6 zvb-vT;ghZTWwLHQxR?92p8R1tECtEnVO0Sn*!8Kgc7Dppu-%8ljM`6jAwl#gA?!v8 zVZM(VuwOOvlZn+5Uw9moOCEB4O|ogQz?~Q$FPa0SFC$GOOQ9vq(DzfB!35maRjvKqU) zWd=#Gwzm2o+~x8%-Wl4eTV~kBii(KTDr~L?&7XFn!IiQ8aGZ9QDE=31*|mKAlI5=U z!{0JXu4Y6ZapP)*4&pZmk8VuNrZxoZmzv&jh{fWM?DCchAPV55Ny{2FTCae4Uxc%D zIEb(aNH#prT-fe=6;aZYrPJ2x_=58jta`I+CRq=4Lj7i^1_}B1Nr$I}_*?Ku|MxX~ zayL|ybYPX>@C!oY*tb9nD3|Q8-EPdFhaD%E5L1)K{dI$G+K=XP9=JG8wXmq-e-?T; zI*675SjYL$nb^%yCF=pw0!oJ^g5SheAbi_te6F8gi$wBH$)_)EgqkefM?D&8Ypvh` ze3EGuLTm-Ce>S1hM{VZLx`@-`o*$0?+-WmV47R66?C?C|T@d`w=T!pJG=B4)%770l zqf%H11l)W3S0Sw2$M;Jq9%LUxQ|`6frava76z+nRI4A+x{XT*%VV;bTiw;=aHiX0? zGzqXu2sNml*X`Q4HlDxXCmM!zm zhYov?ynrVkJ5D#Kzj{A9_?6^V{N|fu^#Ctv5Jv!0s}xaebv+`#PT>^6~(7v6aTriLGuv`qw5(xSR~sabj2ZV!VY={Y~^Z4#p@luUn7~ho_KTV3k{0^SS>e zagO}n%!Bv^U*kJM;yQvOBX5$-tCrt9xF%^Xl78?z`}w^ejkA=@GTv?UVgfNvQObOXaalaeTXEx%^Wu68&}y zk&drVQ97Vl!v~E1&-wYBVLi%V%6*%<-LWl@MDA-Ze9;S!S#I^eYZEnd2bfpl=97$C zz_OFq1>XSMLfN|6_ukQ17SaC!KX~MkL+iEr(aADEK9(M(a<88e>;Ti#1F}IWg?#o2 z`9YXZW0Ir^pNWKD3Q7W{mT5~6Ma*Z!ZEr7wT9|InBV1O*6Oz~FRkOSPobN5gTWiQ; zQ3m|XjU!t0ZsUphOGX>pceH^nc!uz=f24Hqj*o`Msv)0y1go0A|&{^ z2MNZt@Z?TOC*u~r+(v>1Gj&E-wIvl7b^9-&k}77tW-s!QjZ@XID$Lr=IlGr0U51^b zZ)%xEV?uJx+IJd`hOo(1c0~6@#0utrv{n4mkU9Gc5*X7g+BrfaBw|xVD*`lU44E}w{RrceFFllaxz`>t7ITK!tDd@1oa`T2$)c1y$J(t4U;KP+1F>lhaQ*v? z<6k8BI;)jSJ7_^$(X+7CSC{Ei?cOw2kj-j=rcje_^*yqXp(RdlKGL|DnSudWcrnWp zsC7S)bq}@T*+np4+Lmh*QoullU$7RqHmiO%VCZ=t^44DHHmMt0y0>!aUONIv(`!2e z*v^_N>b#0XvMbWofE%r>D}ULWnc~3UXKh}DtsbNfua?no4u;yoD}=*b8BX&({Fi7E zoAl1t`!4(6Q*UXglEb|7+(_KcsPpF0q+QI4F?7T5Y@gwMPazu>Pi6L5l5vjU(5jvY zG5CZ3+nd2C!{qbBo^4kqXT|Kvrb^1fk-N>LU~`hDfTUCi4U(QugZ$H`5VcY;*V=(D zuFF@q(OQuX8?@2$`-I=>1Y`s;3cKHC$lh_4j*E`JW990BK5T%_Va)rfg;9b$tll>O z)BP#d-$DZFnqB$BR@$`UD7V8kW)9nsFYr0L4-QqEol{PB>w{aW%MF>|Z4G#^+qEO4 z^l2g^iv<<%w0QXtG`@un^B_6q4KpK1fzQb7-%?XDyP~zuV_H(xw0bJ=LvTtY%G2@yY#J z>uawu@n<&NX*X_f>EdkDcqyrQD0L_FoE!`8y}(aP ze)?5k*77gr|oQPg(;aWw;53E+(NP1&-#lFn&jPYma=bET&v;Od4Plz`B>}wMxP@k0-!@c?!>K;FEVTu}csI z4|fBJ9{60g^{xAlolX7TTg0IXgr3eCV|Q0BO)Xr3$pJS{{V#|UI{jCS&#o4FwaNh* zAItjoqVH^#T>qf;!42Du>nYoho3WrrgmOC=x<=AK`Vj2}4(mb^S%vkYjE_{StOLF9 zha0#!;rLLlwe=#>Y(52TSpJV8O9y}IkpbuJscNdCNfPXeWAv1dcAxo89>ZWE=aQ;Q zFBWxmOZx3G`OQ1uxlw&8@=detBaOe8&*hGrpx$NDK&N)h#Std{^YutfQz3r+Ham4f zsq5%YXiGQ#%6H}plh!-cO?bS1!B75RR}iMTdAP8r<=amC97-j5uT7__Ckm>n{^+!r zizj0f7!IPDDB>Qjuft+L(3)-bh4yy6ww$=4FX~i??tN`Jd@WgEz7>ve>65OqjFUQjSXic4k zIUDaV?>lE7ZpncVaBLwXt?!%C)-iwQM=)n|3nDj(ByUP^Yk#@w@e z5CIqBo@UJH>Sr?PuAK9ukDO?G^TN!BI#=%S?wKQDyCpZ{^+HfQ6Iw7?C-Ke1t^9dq z5Jua4Ub+k_pcR>F9P`_mVY@@!JhUr}ljaBZ}`%J^Q~t#gO7cG$bYSd-|R{nRptgfEtmd-8j)k z9?lp$B+Di(q518iE9PQIc~n5gmFO<0YW&R-SUIkWPG>X-D_0@q6H!~{oc6DpgoW|ElREa{4w*gs zUpcMZxlA^_=NIn(Pwc7=QeDdOAg-rm;ENQ(Lws0%%y_fWWEv4i01*xdk8Cj$0cr*y z`26xOWK42FaxTB3F+7bQPCyhdmJ@fx-BNBq~*!S8OGd_pg`QkK;6Gqla#ZiUNtvg zXBg6mA9KZebx2(F^MNN>Lcm}!jSsrMZBQ@)QxlG#ytu%)D}^7|NU|^7dFShI0p}CQ z>+36LgJ00#(x`gu&Fs&IYe>6l0#ht_j3NtK*c4$BoF(7NvX%Gy!<`pyA4YA2J6?)e z$T3D07-^r{Pl&XX!Om`ca| z&>whp^zycISD9)J3gw!({RaM&XVIt$GVfP46_UE+IOM*rs8~TGg=Ueh0OGr4!6|)Y zjV$43z3;Ku6Vrl(0uX`rcR735VQ88ZoEwtmX)ifNV3IY#p&Ja z>JD5C3eFgOo7(n0iuL27&!#saUrcjw=4h^5Bcf}`ZXP(HTGwMk$4tnosOQB6f`{6+ zOzWMH4ySu>d-nI+A?mGr0n-6(zUM+e#zvpd-t$2B_OO5i)xIFkaeQfVbhdlsBd^E( zy~>vWNZ`avxSi!kEydz47qAE}M34 z8b9c@f8*%;mTxwaw$H>QqQ}0Y^S3UNcyr9-n?+JTp@Pucv#U;=Lr9*Y%hL2iLgZ_P z9%lsJoA=z_vL!D3JgpKI!BbY@RdBpMBY5?|%DLZrCsYJf+T0gS=7_ajtG%7x93AL` zi+sJKoIXWZoln@bClxAN`+ZtMG*Pn6QcXSXZ`}F)-$%Zh+HjYWEw$uA=67mg^~;9DKB8eA!_jmU z?6MLp=yb=NH#LOj_Ph2@k2bn=KU51BbQQ(488WSJswIp}pQ-n-S3SL{T+q0UptO5{ zfa8yK`m{_PbfGZfg2AQQu^4wzQSXIz$jx#^6QyjcG-a0)0^0Xj83I{%a6Dw(YUov# zkrD`gjDsyCuN#1i57{*+TXZ|>4(xHRd=1dky9lUgb#>Yo0}C|{fG9s#>ib1L5gr|_ zJ$71i14J_Y@J5N(|MgK+>bLjw?Fl)Tc=HzoLE)DPJCUT2(Uvs-q5CrD*Rf}lj{~vy zgagTfE{77V7MivMuPd+$BV%HNxFyN$d$*MUn^hV$zLh~~=e!ghAv`AWm$rpW%vV+R?L$k<$F_M!9%zwL zQD3_$vS93KOvIKR6@+83)nKVysap6$Ef}>2)8|ZjK8g72dIrL-O|Nzl@sRy2=vXA? z+8s)R@9kIHY|5R&np!CrKj)r@U}=3H9JHQCpEMc!Y|;{MF^R8XgE!j1iJEI$vr`7u zl&nlmF>HDHD7l!iE7e(n(bF=>lO4`2kBb$x_!1s5D3Y-8m4`k~W#z92z z(GbUDQMjtO0Ch$%avocCuGgYF4sI(Q2gf%+Xu^cz-pSnQ8HPkX#fm#0GHndI%zC9x zb$8_%`$PM998Xq#l4jAj11;*huvBZiKa|Scw2NHg%z{v*f-*9wveUsRJp(`46Het1 zhN_z6f~s%TE!4+aCSGjci>xBaiwTBO{@5~!$({hYjMrJnuM@9(a3_fuwWselB(0J}|=s$U$W+Sp7t7VmN1N0C^3SxEisKVh0b<4Bbm zk2fIH(9>JagF9>`%jsx`GAVyN`{qi$Cz`(KDv=^X1Zkdl-uaG%MqK9guH04AgK4bt>XMGPA0Hf6M+g4BtUse`i&*ekd$63; zb}c|8YZl7-;PhMlo-2)ZkPTOlDboeHzub}A)y2UB`N>1QtG}1TdGC2u?C+Eg8~a~GyOd?K}M0zZQ=s3M{51~CJ3Y9$pj5x!fZM{OtM?JvW=8Dfv9 zI#7j`V;`Rg&NfemS=h@GF&g{&=Wn3?uTTsiA-Njh&c2e+1lKk{&V*yM<20tv>l?~+1y|oXS3lg z#_yXv(-fQ52Z=>sDt!|JE~e0$GT_Fk=a|@e8GoNWu(T{6PPZTdXmF9S@o>N{J;Vaw z;1i%iZxmKDP}uO!> zneDx~33FnYsPkzlU8jB1o*DS|o9874Q~SYtQkjX#db`1q!tt!aa*af`omhg1`IY0n zCI3B+g5&4ZOicP{i(so{H>&+zNlVOEbtYCQs+8KIoO6&AQks^VBi}qq#Qkv_DhQCi zoAdPpK!acNzXDBM5?z?ZPYwNJI??rK5?;L(}n6-%!oW8#<5#z|u_%2{WF;$YL z!DcCvY5CpI|09cJE~e0l&U;lh%g<@3F6ed#WtVfJq`5CjB(A#)ka4A>ReTOBTf) z)u>#^Pa4AInu%EQZ@9t$I&AgXrtT%fo4p+1p1yuzWIWuU=v~Uxr6T_WRO&zgxUb*A zEGI6IHy8AeT@?z-JjE^ZHcV}x4#vdE-L-2#c)M3_{AYJp+0U=(q-l0+tY@LesU+>E zZu7mv>$GSw+KGoPBZTaqr{2Ae7f3>)ubM2l^~9uCW=)(^TL{rm4h}|876o@a553!W zC6cZ-E!IG-7Rw}_q2?1r9B1o3eiF$(RF&;!R(ba$jcr-0=*tSp7PIwvB8lROMAFi_ z@5>X6qG{g+%EvD6uOlNTf}^ADtfPrXs<|;Ewu6!R`FB^=O}=oO9j}uyEk8@_j;VK2 zF%QT{;Q5A&i4JP*MrlT>(Ol>~LcI5*~SjL!R zpxY-~uNIFqgAZntVS25mSTjtW_ba8Bcy%Jjfk!D~4mZ~FMPzCw8Yt3;qlz?ct$^C) zq&|h_==G-|>!f{Z28?mgQ+84)pye|^F8w(-S3XGfG!gW3=;@Zs103)ktr93Hmex>c zJR!6C_NR4Z$*b!{-AdOw7+;b^Bnl{DA2L;A(Vqpla&-=xS1y})JxY=Uw{8D=7qm;Ox z9&kyLlgr;2P-)l3UAy zY|#C%pMEQ04p5X@rU2>`euJ^72N$`9*^Qzb=0jHUt^wTURkyFuTLCRgED5iz?KS_8 zn%W{R@sX|QHGBp@C4hW2yrxM@d#I}Qll;x%a~<-W={6?7Kg&t6@raZ+vVd2zLDxx^ z;NG))9tE?{YOKR*2V!(2E|%4^#v1BW2*j_ z3(#@jT$*KifN*7Hg$n}amEJk7{fd=w-4JN)q@SQ9|qj}%#ALk$lup1Ww!J@a>Cp15Q{?7y*V8b;TJ)cYQDfw{E3 z%X5mE;E_VJz#6!HT`+#8dwZJ)lwBw6p97Xw^^~TWS?h0{zu;-ZT-8Usbhp7=nSay* zu>`A5-ADpDjW)^`UZT&dj_z*0l9wY@-<;X71pqdH_QQb_wNB-;Ki%s3F=FP@dt-I2 z74WA)`$AJ^0lOYp3SdnF-5#IQGclRx>vj7J_6{M^nd||XHa7c#;}(*Xb2rvU^a3GS32ja{tvD4 zVh*j}-QCTybU2}XSEe#Y4a!%5n$e2Qf@^Niy#T0p;E;ebkL~ONAOiyX9y!G^iA)6f94|puP}i6^zA)Eku45MU>g%K$d5Lq zP@Se+bg9)R_Iy)!7hak7{jd;N2cr+OUGi0a$%SEg+Ss5ftKLQ_`lg;-Ke&6{i;zeQ z&KXU;NUAPNNNEi0+KXj2;A$z#GMQ}_d;d6x(IZzn)h!1Ihj9P%A1g0#MokDjuU84w z&vTR%r6V@TbI-bq#eGTsT~dt@po6W8`{IJ{YA_8`hUez)7^VnHN~UX}P5u0t7ePT7 zy(p&?Me4K5^)BSm)eDJ$9z^HKDLZ$-d zxrX3K{$wlTK5kLDW|-29SN$C7 zo!ZQTWRZ*x7w7&jJaqluGR-tm=|mA(4p^bR^C?FWVk712C!G7<$KWfjt-H%j^!God z2Mc&0iyl&`&9yaRY)?D=<_{TnrU?LJ$^3d#|6C5-IrjhXH+kdGxB#3vP6|qU0#HcU zsAo#c$%c{13&RwowN$n`ie-v8C;TyJA5w}-j<(nza0y{v5tNPUibzReJu7QsTv=iL zlc3h+Am-Syssf}0(9@Vu80R~)i6cN{Ta>o8#yTBN*pvSF(fie&8H8ZR`$6C~brBEc zZ0*!vvn|?KtV4KA6dWOZ0%duR3lbb~<*}``HLqACKw~^0-c4VFny6i|6@fXb5R7^i zcmh^Tc6AHC@nuBVzj;94jbAgPM2#>~o{h#EB)>rLXVxnkPOj25WW5 zuA7gHKQO%?z&%IRwG`@Dfe&~GK-Q(gI^r%tDb~Sy!^uJZs{@v1{TyOw>7j)cIw19A zmB;nmEKh%l-^;%Hlgn0kGc60$9Ou}<>wBT3*EcXVp zd*1+J;vL$l6Bcn8W8dS`EM)fhS9I>KQ37;kJtJz(bj3?-ViQtie=G z^Z0EII%M8ad;g_3i}iyl(<)#of%kJruCRWC$=Kv!-@mWBji}5R%K=6bC@zXH&VS}V zeH{_%Ah-*(7l6l0?h-;d;_nRO%PS{~#=!1!K%@bzi=nh?76}_~6-8+V@bnARmcfh> zrKeB(;Vvj6fsz6p&L=j}jlMnM8HoI#xg%)Lc{Kj$_P%h6>aq$?Z@ z-1Aezhb+4E-K(*tAos;DumV;&7W^L|!yr^EaQG!JCBu01+y3JW4gOti{V0G%L4qHK z?ALVdjGv%s53K@X>`61=#Pvju)YO2p0z6vofH%>TovG1wBR_A$y#HTL;=tH+s#Acz zhIxSRy^4H5pt@@gCYN>`M(J-?^zw9QrTR((6q!#vFP;>z94WfEDBGQ{)Z*;Nb;KaxkDB&k*$?YWY4`t5 za^9FWC^fYKPFWZqRnB`G)FrNL+HaL%hfVK*>J!a6Ptl$Ie??yqN8tlKQNEEjGb>?23vJpV5>5T`u@! zNB*m_yp&k3+X8kmA& z^Re$AkFch24$MFKU#|A#`0Lf9XY}d)zDh2wkhep#+sX^_+9bt*_;* zGfy)p{JHHhAzxoHLFO)sH-ZmpCNibWa!wjqj{JYFqGG=wTAGfLFD9e3a4Wj10F)kS zJ|R%h0G%w{058=yMhy1(vEv06>k!x@-6ZH^;ri}oshYUp&i|t=#EG>&Gu1I_hoeYE z!p=vK|2@`dJ9}URV&T14fkDboo}`Z>E_5}_Ju?{0Y(P`Q0kJTi%zU#sLS&5mG=SSa zoX7l|Ulwq2(8QvN`%uNqML<2hQojcR>#N-{1d7d4(5b^5Bmop?X@!!YLPT^4Q0H$} z94k9!7KkCy>`Br0Rg@hUK}IOo6aWmvZ5B|uv+WZl_Z)okolnOTDm4#mfx_$3*Y5uV z9U1KH>~O2AtEm|o&Bg;gJv}-3`5&8_&N0x^00W>E7y;L6YHTz}FRq>+D-N}5;o;IG zfT=Rd&BicEnz*tjH>1Hz;))V?;Eq1QXk^f;A;tMdmEx=HD<#y%6`YA^m#V;i{jOnZ6UEE&5vj4V(MBANH=Yi~sboi~X zhzMrtw}{i`by@D|+nI$MvB;<>8qjY*IvlyNyBo>#&B$1X8M($Wr2%$Q@wS#Q%j{KQtT`RtJeQ{ zpJ_MS7cUOJvL-x)jX|${z}#2?Vd3gwjW8erUJ`~WZkwZ}ahn6>v%mBmoXx7Oopg^& zncvIluCQPJgX&fKgKXoPf5)B)oRIH`bSUBZ9A1INK}n1+zA=|Y!e zt7&sWelEuSQk`@wd$SU60-Ui?izk65`GLe*^~@RfVRYa6`#7wF=>~BU^|A@Oe;Sqt z`@mr(XmYkprRBSX?w=U`k&o(aqe(sJ-aFr_TG7+ zC9lkx==rFo=dX8RSfzBP0bC%g$u>`9L+w7sk;txKKfP4`6xIbiQ=p$Pbcc)+AE zI_j8DtfBPHtX7=kzgxOp`dzs=WS-sK*{8wfQ?&#qg@`B9Fsvqv|~rNt`>(7jhL(ltlP zm)cwYD!jZ1B5kyn-tRtDqQA78gdGJA{m2w3Mqh>85RTAvJm+JPfhOkwc#l!Sj}mxi zU?XJy3^2{cz($YGH7Yz052=wZ7h6ohB(JtUm*v~2e{V~?jRe94F z5eJeKbwybUQfrQCi+P-sJG-cbdcM4B;YKVbq_=bUyt1rI0vuhI z5+fnGqrcEg3$gwp9gXT6DGvOPx86Ckfj}1jQSnG*fBy#iX#xw!24D4JDF17nw#8wcL(Uk(X-b-4P*P^eqUA>T9Zf_*S6* ztaYTXBSq!wDA(UzkTsVToFRY82h*3_XQv5!owKV!-MK;i!3jZEffBBi3o^GP^JBl_ z6mKQ3Mh+Jg0#>@t(tBmoHiDo-ICP8R<{j=qC#PxWJqx`-4l&k?@+8%8OC_o(lp5Do zDm^NJqubbUf-H=kgIpzES@+C8y7@|IxvNXFsE9fX<<3%A#uZ)yBJ^iZF0E>W=5dP7 z`$of@;*#)WHaztgO2e>{JJ`_va}>gEWNa2LZ{*4a*9Lq54-M7dV5e3Q2l%3W-4(cm zKk+?_NF$`ERyl``vJzKt){d8x7+pnNTzdiMS?ZD{FClcMm73@UX7*H{SN`}svhiLx3;k`hDNqSvaQ+x88cS%WvZTesWca)M>c zEiT)$HQR$$re!(|m!2WnSK=q5JM!)`GsC`zkLx8&B8ym0nXjfj3AyoR8(%TLZo9qv zJ!`KkE%D+0renzw(jxUyL;;|+>T8f>~=M=R6&9@V9}zAk)n7uddOe8p(4v+F=!&AIO>_>T)yDCwP@Om*MG zT^5?s{~$QBe~^9si!3;~oS#e^_tpPd>E;XCQvo<6sPq)MGI-GEU~+~F+Vc42{BLAX z%@0$f;lL2~i6=00o$j_!0(uL^BTiKvJvMmc*@;VYac-o9rbsIp_ahlB!DFUze=nnqy2jK1n<>7t**DlJLS;ATFzyB!i_N?!- zS$%Lvfv03L$Q<(>o4qm4n}*JjL2Xlj%4b8%9?H5dLgfCwPiTKG z1oiw}SX(W&5LOr078Cn|e{rna*tMpL&5;0OfSXGzaH4O&XFaFyaH#m!f5qLqW*F1j zlVEqs9j~P_rw{9x(}*_Hbz&*D{%ljpg!W*mB2pWIJxRL|bGv^VfHrhBZcK81p>wvW z!D>-03IvVi*GT0H-=o(-RMmUlI4n(G`J)yO4PnrMEOmpTV#|{9o>2wjCAFZ7ViOEh z+*KOXQ4uWmQS}lV^8w;j0O{*vp9-KCZ_%a zf^2T4PmsIdWDGdcGAJJ}Fuu#vkd4G@6en|e*XlF8ps)( z`gLlKt&R5T1?LB0Md;F|_J7^X_A{}Ixq#yw_pgv*H5B&MX6w59xa|FA@hX?y$X)Tx_}Pjpmv4#(zyKV;-KK zHZ_L;Gs~>auAH5~DP<4JH12p$q=DAH^eTU6ZZFb*$7mQd%+?wb1Wo-N{L5K@1tsFF7I&3Z5|hZ z?u*{V>KUY{{sVya0qPnW1mv#%L{YV%l-=aHOg==f<3c9y*uN~_!D%)}n zCc!>jjU1WMIXM(C*T-H;^N>qd7Buvc`U5-&^n_?RRW0fU1nY*&i6CV&3>;p+x!a9>VDSQ8KD46qH#YM~Lu5R1j> z!0Q!A!~0MpJDv+QYzHLuvzhsB6vn;fMdfA2T3*r%C?t_l%NgV`99<0)cvuko)C!eX zc6J9Vyu5aPr%g+)tHk&dNv+yK`j>`=yCYoM)iZNolET>>LSM_esy(-YXK>Y{QA)RF zY_M*vL_&iPGzTv@ssx}7gXjrZ98|wQaM9CVF<_Fz=%N%vgqzYMuxr=qo$F)S?XY+rllkVkj;9v+i zBMgM_e7qX@C9$J!F z9#L76MdA39lKg68;s!G~tzZ#YX>gVjBhzrKw+|h%bpuM^F1MN7+aFe2mC)c_?~Qc4 z0C3k7R;OkCw9{Tw5JBrIX5XFa9I?+YUP(n?jVmv$kbm1XAJ8Wb+Y6!(V!!+0t%o)~ z?|lPK-e-h5Mh{6yC?0iVy+u&Ep*hcnE_<40Q9V*BSqWX1S3HP{3DZ&}fir80)zoN8 z*(GsgORk?j_LHA3BEY9OlVM7baek`)<2=X3O2c{n+P{@;=H>Ud@v`%4b<1mV9H-1M zzgEgdBh@06b==kD9<%6l4V^)V<701_fLBHX7fH~ zIU>MChd@L0>C>kbxpQIF@S40Tjta__n;TWZOdocsjBGEz@}W`{g#1|ApyiRH{qjH< z4o#IGaYMtZV}`TGX1c+zIPq_USLvzxTXG1!4u|!n`M32&wVg)q;8?|(m&fiqAL0H@ z*;k?He+lsSiSb#SyKx&&Ho_VdqI`32(>YK}??lwd^6*g;B>!hhbk4J9&kz)w_D%tr zWaaqC-aZ0+uIr}K$YRZa>mQA4)3V-WDg<;4F`Zw^c&z*bOdXRP9@&oVf4T4;Sif&n zEOd9B^CK}MrbVm1&)0@$!w0tM`Sa`R^O5==u?mpo?wfp5w$=_R`19BprAkUjXS&68 z{lLRxc4mo5*Yf*$+7i!&X(fL&qz?{;C-B`#kTB6r5nvx_Flkefy& zyE}e|J0~kMqD%X_EAvtfwPLMC2s5V^9gXBnBTh-T%M+E`@o|bd`#NDB3F=%vQ&&!W z%@*|08O`vHpK(`<4_oitS^bY}KV;SIx#_q+5DZn>TIK25`OH z#)NOnd*+U!Wzw887j2(7Jqv)MZBCKpIQ;tc%Y@h8 z5h1TuJH-WaX~fAjvM|&UExwfc1pXfPoc^1^-mQ=PI8kBw8yn$k#*#5Vj`v@^ICpT> za=3qUbHm7OS^Z39(!S1bzD+DAMqu)>`RV2>%A|hJRvjJfw1w(>*h-cSpw-n=(-AK3 z6tjm{{+D{7YozFCAr)+KfA#+*t#`Q$o4o}`iqtR$5L$B++cG1dzktdN_hDeqbg`Ns zCnDC5ZlTd`Eb{;jjcs)u16lX2d_Xqbb79^}=sgK(NM$8I1~DVs=TG4bh4_`JAA&r= zslui;&i(TL${4G16r~MzV__#gR%-cwxBxmv1JiN=PgFHdCHQzr7)HL>l&_Q<4Q9No zK5%KurWqXQL(VEdw(cuBIqc!#fwf=D+nT4j=l^Nfe|q*qdUq?gv5w9OA3aWaV(8rK z(vT)cepRgXIDMt`{{2r9^l2^4CZ}V_w?SzEL zn7y>9gCi(&#yNT?QVns41T0pR^))j|7%91IQz`-+A~p9cS5`7Pn#<&FRJi48L0TcQ@> zH(Aejf1`|0L)0i5jyx#;mQ^FNjDhhKm$+|vPvgtjblwVkQL%8(OWQ}Od=*HY2X}~U zb?i8oh;Sb4JahVa!^1%i#kC664~AL5!t)8eZAub9gQ=* zipSk;1^CF)h)p*)w~A9IBcqIe7uPL%PTA^rvfW`@{XQwly(o$$T!J7xJe-7tfrAjcq2G5wCm(08<9O7Kp7M?t~bS3 zTr;{N1;<-jO71k!@Y)*Sw*Cl9o|9rY_iEazf|#5CvNJ08o9ogkF`45HCn>OZ_=UC! zc7Ofc@E~NAIa4K8!gZsZYW5NKJKZf*h$4F7%LxwtcmH}hIqL*1N<6YOW-(e1R{E;F z50-^#3&x984qs{`<6Qzek;x4WarRSWOkrrT{knU=&@DFbNH;aBIeSao-2ZFMcE5~xK9<12&!m# zk63Urxj#Zf3k<|OI~Oe-Z<%IdvSX70%YdpClAM7 zyfg=Ehu68!o7w-n?&!w)y1x;^ZHx|uCoStw=td)J57bmO`tmtHL7_m`I)K*5RETam zd%Y~lMjx%I$v}uBQ(7KoFWDCg>en0t^O8miRniV@bqvyM z$UqhaU}G{7d!}w3duYQ7V91L|cJ^c1k&Q(&)2t64JbJn7fe9PcNc#V<_0~aAzF*uh zhzOD@EhQq|AYDorbayG;-7KrLq=0OGY&I) zUtFiIb3UJQPU)M$-rl!oZs^2PVIm(W<>-P6X)l}HSJw3Yu1O9%`R2=JY%e~+_tdDN ztbK=OCu8sVOqbxaMQ+|`kE^wHQ+k3Hv|+sY)?RTk=Nkoujy`N9Z`Up|d<922yQyzN zon+^O9I%b?>?6{&U_M$|hrCy-m`yB-5U&JAQqI)q-XN!0Xq}w=P@@DqqoDzUXRv*R z15zbSar=VPL+0}@Ius=NEj;`8x3guMWB&Lvm0=R5u`a~2Tf>7MKupi(XV#>=djOxp zBPx(!mKudlDX2C3J|u>4vBtI=-xuYgjhv!#6*54#(3>%O@F3vZRQ&yYu54eaOFk4e8)>=BlKp^rz~ofu-;Tde$-eh$KjmL-(L$QLh=Cb={LH@rt%g7%(}(T zExtGe7MJAQ{r|0;4Z5R&dpTfnVvP^2HmP92G>^)ov-gX$7eGAE0b27*M>KpDaOo{& zWS3Qlwc`uUg}zLhWJzn0lF^Fyaee7rq@``npioscOH8Qb6-@Lb+${h#l6w@dXM)Ek z;;yOEo;+QKgu{{)*5c!1?W)o>n2TXYw^j#6TjN++M#!EFIZb_3M#O?KyM?8+2fSpl254EvP zfa2eW`kK$H11I*af1qLc@o8Rofg;{($4_FW&HilQ?1B|`mi!LgTU?3s(&>+p>elyxB)r;UU2zni+=6tE%7~}}f!lK(-^NuTk&BRLR)+?E2p6F;t*YHRg9 zQhpbj`=9B(bPcM|l9Yw`tgI}XS^?>e$}^en?YYj-)t8TPa9)kT8OS=KHY-s67MZuN zwLTXHQ(bIpI>a2vH1>GN$eyhMWcqOOB0&ExCCTx;d%kO^O(wbHicvH8-9W7#n!*J$neo9XwL%o*bYOjtIk)PyW;S zMQQN?xVi5!iE<(9lb%7^()IXHcRJ&><$mX@1}6wpcJGttGnsA-=IIzO9Osd9&i9Lv zUPvsXdZ7o>=Zoy#%jkD!3IHm7hBM>kgP#_vdw-5a-njU|fReg!eY0$E`f<0Jd82N< zP$JL$ez+ih>Nu(R!DhiAPS-}myF#;3qwDaKB6Cmk_k`siY5V8rbGEh=FAZK_IB9N_ z?c8J>TE8Abx{SF}{z+7o&NN?6p~s^b*Ms;0PNgob21mnCD0gv2X2+JKyYjX-wN^}~ zYpr9q7er;F`@#D}8CkLRH9b|E>uaXw=gwhFb67xIwl2@IvHfcdKW=9i2g) z#lCHCPeyASTl=1Cz=xsXD7PO|&A>uK2WQMejvHw!^uocLBZ1fLg4{s~9Qed{RY{wR z6FhfClv^`WSj2J1>k;fz^Btzm9!E3x(W6xbfoJ{xjIvSd;X%D~Ue4r$=zT8J$Ab?@ z*)P*~6K?CzhdxGbKM%{^W$u-86BgQ~Aa$S`igRXkGq1NRsyV>k{pjlDt@s)xDG*R|#e42|OLag+ z)n$q@lwt$%%t|D;u8Z0H(c21}B*m9Q8JaGcKX0D3E)%9YnW z(CDm*IM{@@Gr@nY%-XWY?Ncisj7>K2T>DnK%6lVY#XOY!LU<&=$Mco6x>f#^-Fo;d z#)R|zTUL@i`oq3lHy>tum0it!#ed$kGbw{2>6S4a!Y11kNnlo#5t+X6T=Sc#da!eB z%x0`8ifi?f&~PFqvYwh{-VhFLlVb3_N;OaS9_jsqy-CVM3 z6}h7jjK5P$odYjSFD2KEDc&vVmN(feDG^jz489Z;ter7!ZEaOZ6^Q!& z{W~8wFA!d9(^^Pd9yMV|A3jpqv%B0CPmmEG5?lqcFjgB~0x(x{x36(2eWN)QV$qjS z+Y>kFw%^PD)8qC>>nETULUPB9!AQDycSjfX2d~pY{w3#VeY0`z-n|p3Ti^XAgg{8T zBfbl?0I>^r*=wc%6GWbTe$9*g{Z+46d3IDK0 z10kkdPkd4R%uQdXYF3e$V~WhOjL{evTA190Iw6nN4H;#Vm|oKSGC z`0D3_nt{eZN-{P)-!061_^4xVxKd)*hQ{X*=Mll4v~T7U_C&*WcWqR*A|D!4>cZ`pGxYZQ>(Nx~YwPD# z{vwg;nmvZ15x{O_xsf_1@1vvQLqlh>+Gf~Szs}n^5}fn<_8Q#W$ATIU{gZqBeC}Tv z&Ce#M(zZl=C4;rwu8aBq(bBo2>IPZT4feDKyP=*n*4k6)ss=^t0*uP}q@vl4b!Pp}*;D)wJ#_`*A*-p1pY2Ag2J*M{lbj)}*lDI1P&zifSljfvk)tvnPyw&pgp zpnJC(<*}&!Tdwn1zGOaIUJMX!Ioo>hl!U!$*g{>PhUMVBA%C8}lM{E0*fBO>dS?yr zF>pH&>2~%`@1wQL9rb$#?tS?7z9F|p3}iKT?UKQQabSG&wkpTNxu6$!2MZJ>Lc8qn zp&{=t*OCLd_rKngFE$I`PaM}DxTS~wv$w(p;H55<$flBgoHnH;n`{Tuy7K(|?vd!8 zhu(8rP92`q!D?qAua>MYbh9;2k*m^rs;bcCB1R6VkB)9?(4iAhBlWgJIap8&EmaJb z3pg;B$=H9uHCA4>z7$fvzc#(OI4aHj&$cLcc2|l{_FC6hF?6n0ElOC44-`IoACW)u zJYgw&iC33WL^$7*711zisqmnd@Fs!_v0pII5X-f|wb9jBTA-|<&$%U@V0#5!?p~t` ztNU?ZautOri?*v4$g#PjWzX;p(x*x8iw8Bhj((r@HgoZ9ku&IhYk4Wa5u&&}`Y~~| z*q7^_Qd3;9n&f)o9zT0s-bokN6W)`(pOcjb()PYQul+bE)pmtq96qJ*G49hOb%dk` z3&q%(&flS*B3HCkou_{^W~TP;wO@~-D%mKW#k;-h6LDZl+6J zT2mJLSowHuFmbG`Ab8=n;n`?g3@-ao2kO8;^&_NU7K6{*qRr&W$d4g6WJedym(IJ+ z4F}!uNO(%L8Mbq{9S8^b<}1p0gXwIm=1lG415Brx>Ci9gHJ!-W)xD0FZ7C*d*`7ju zct6|G^=s{AVKdLQq&S`-xJw$9^ZL|4ADFJXyT@w{C6L-z+?SV)^+JUSl}{J~7fCrg zt~0vpP{&4Ya4T$tvFl@W5<)Wj%amHr$kl~etWlOqaq%vL?y#Q+I+>1LW6jhYdP&<0 za7n|q2NiQi&tew1!-ni1U`K^BxF9ok`|N+uWQQbloS(gh!?5cTunOh}OyoVUqSHG% z-uC)c_|Ohr(ULHLaN+qz1K;2B1l8{KF(jUM*r0L^f5Af`hQkL;nwlyu;58P9Fzc_; z$HOj}&DsMTD5We%EIw6Gm-BpQv2KNM;|<}y--`EA(RCef3n7nDD)MITzZJqtG1b+t zwN2bvXY(6Et2TYU=qW1I5xdlsf2_V0=!ex<oiMlt=06fp zzMmF^SIjS)Ttm!XH~MfJ>iwjJk0r?w9Ph~wSAyFV_IHU?mE6ul`W zp#Tj;Rg6aM5v(kS(w4%GH6Q^%)n-}g;Na|~2k7o)S-iw=b)wJKs?PXs7I{B@zT%P$SN+N)s1=17s(s)Szr{phfPEdG<=CJ)BTqprACT5ra*H zw-@4M2){pWZ|D!Z`)EFJI#m5-C*IvgLU&t91P||5GE34_{%F(5309<|<6$}Cs%RUR zl_SU{_+!4wj8oEX6YoULyEm;Vz7Jpen($g>$Ja=zKy|4&@v;@ml`kb&Js?^)yJD5G z@x?Pvx>B!v#uxO?_he-jKmFM#+4PY7bb6LT^8lya%FpH`yP{@{AVbV7chA)CI- z##R61`lDtmv1md8X_U#>l%w}v%eSWIb!o|gfvVJ6(fowJha*IWi;5l-5Nu=vy^BLF z6}WUV>YgGPtv^7DS|8>%1GL5_4tvRiA5&hv|(0@7c z=?Fwcc@jVpN&Gi+MG$ZKlMN;dfohRi@g#}CP;``g@XuS;25%6ebe;t_2R5Rm-#zh} zSFDmXD@!pFaThkhmM#s%d-e>}zPs*aDawfU635PLu_fN<^Zsa+(f; zEy@esUMIRaINwy{%)eqfU>eRCZe5i4G#V07?>~Y`u77TR8jp2x(N414%hsyv7ulRz z<2v!!W>i9}i7#>8H@Y?-su%^njL}~=>Tijpv0aUefty>FQX{k7{jQE2PgA&)m_e5U zc}2Z;3(3J8lIfBXw_yi4j-RbcDpn#yF@5)+@)GP>c3&|x9UqR{QJ)A28f-&mf5{ccFK1Ycq^8MXDZj_RDiz2%u#tByj zUc!Qu_uT3XXLQM?A5n7{mTAdcZ?inMigyuD zZ1Qcl7jK%yBW?yb`~<*sEF{-j(YL*x@-wcp5hprLRs_oPW0{8=8mY503(7;eNS&Kb z+FvBEbIl7f+#C;HAoL=0AV1A^>GR%W=^=scm!af3piFF4H-0SIU?wSV>>mql?;>&( z>HB(nJq-s-UK3Ka(oBSoYSSzQb{tH*mn2o@7@XhKM-5c&Abwx@?Z??h{e8Q3Y`Zr= zREE#an^UfWob@^_fId>#HM;h!!58bjS-vLo{^uxH-v4kp-H|-pBlPtM=fUVGa{!^S zwFAIdgW7MiwI??%AfYrR03@rpxQ+v=`n!L0fMOguEvc3@RKpVn+jrMqbT?CeXJC+~ z0cd=Oa7l*z_Z{plR|dq^ICm6{Ol0Du)Wi>Gf_`5}dv$%+i)DiY(3-Ix(z@V(s0mfw0ZpXmF8b1h2HF*mh#3jC+b5=D?}c|*RRa)ukib5M1doLwz2 z(d=mW!E*(R_!B%!a$X-f>g|~`{6u_uA#qH!p}u=rE8Q3#!N_BIr$dE%VDX{0^t5r? z{rucJ9&`NBXl1^3kvCbFm{{1N!?r?Wi}K-W?2N_u7w>@+_Bx3~1XoPH`zgsl&0^cl zb|R6H`F%(aE``!Pr)@2aSBbyIUbi*q`m76x0cej%E~T zkW{|$3Q9rk$ZkF^JN7~G&yBOC4AEO0hE@>mv33>koo(!UT0FZPpFfSjD}b&uT9nPb zpUhKq|9V?@8Ou!?72Y;?uS7aaU*EHNkroA75mC#ec(dDCd-6>r>FActh~5xw6omEt zdZySf9paU=*f167RDRa}?KFC)W2pee^Lar&vhlZ$Jv`)`zV2QrzV^LGr^{d})iy|+ zzKJblY4Mv8+3oMOh?m&5li?#ZqaE|7RExWiMOsR8O8Cd)J z>C+a=`tO8A>-kzf=yThnPe2Jd2R*G3Y<72y@oONn=L-#)%W^PDE!zTJeK~_PP3Ca( zAQ^9VYVu)^|J+Hd&sYgf>6f$1|2;^H)$2)jF01c~m|&P=K$Q^yKM>HF)qM`PL5ntO zg1>cq-=#N~pfjsv52-!v1ZZsfWU9Kcy4>+;@s%~+=$}~)Bif&3vBMv+Sq7d z)xxry>*?5=?d9Y!51%%m`K|R>jZzH+5uVg6d@%{Y;m(|6)S@0GM)i>?*KFfuexU@k z>?<`%xy|CZ0TEOBxDS~`L)y|c5> z$Ov}+#Hikd0hntpV?83Z!D>!GDLbfe!H?En=&k+rzv6QgpG=QScTZSVCb)Iu6)_aK!g-a%_p{#w#8cS zOQbqo8RcO@Gl{Nimyb=6~03xq*b8CpqAox>P zF=h$?e>dF@OcoQ&Xb%u&n?G`1q9Ia#>GkL)LO8rZr|ZUc4C|Y5Nf|~5Hd8RrRo&Ew zbZSc6C7bKwThVEov$_OG!HIHMSfSg3%KfG2Q(#@o=Ipf^Hr)`Jd)ZfrS%tVYn?Be- z;;j8(^KJ{07sATw)1+|6zuz{}miYyO^7i(gtAP+%$5|W-EJs|6d?SG_0+c$-4uqMQ zzcGg9qNnNj=o~^uy36wLyqh+Px_V^u(e3;x{bJ%+?x{3hJb zKVmw$DPWx?Z}L13b0>FX}<IJk*BoF9L-j-mNQLZl07bv_64JAkL+Ph+t^IUIeaXf-S(aMNNXAKCF9Gw#4F5BLcoR znEoM}5;EQ@sb#87yR8wXb5?|b!ja*6=JU+A^tuubIqj$D>{{9Nl^cF+9ZM;A@ zy-Tbo*Hlb$M@*+DZ?y?qAZ_lN&FVL3K)CV?rf1Ar1|CUs7UQ%fCO7id>(^m=Baiu_`Frx-(js z{nU=Tx{gbVRkh_WBCP?+%Ih2+?d^u>R)*E*@C?0M8_mKQk6tZX7!P9uX3-32##Mau z!B$tPlsi~i?k|^avs7J2bVlgcOW-0^jzy)h>7KunaO6)L061X44$i?j{oxD+5*x$T z#rh%8!b^I3BpwncU5TABt~fvgmlR3#q5&&OQ}-W(D~LR*1MATbEe(Jc2T<4Mty^vK zz}i8103FHJt{n-Hf@1sI;+Vm{czW2`<&n0z19Nw_Ab&#u-H@T8$Qyhd94S>|HxcS^ zHTzKo0LOn;(!>LKjwh24F#vX!@DZnbN8c+zX?lN``l?o-^*L&Zw2-(IxU-9` zenfCFbkYGZ8-Qftoc><1nqLQ&(8(VRjhdFwqyHDB?ySbpZQi^=6ZP1AAs|4SuH=~? zN)J$@n8VwmsYS7|v4zH^p8`al0KWwrq57$RJhTZ;4i4xjM1}vE)}$k~20+p%Uo!DK z^#Pb>k2H^fPyY>{!g+b6a%%ROD!v!G(5SN68sH3{6s(vd`1p`w5=+m0?Vs`S0u-I# z+Ex{$N7ToEdUrGS3u6NKZly2E;YVDYu*WW-V9`%j*q;y+%K)bYBC6Q`Kk?Tlk&8CQR0 zWqFc9$=-NDmq5#mFdi;JsVf|a27pT;n$E!lge)FiMrYeI75eXWdYShTs}K!fSzG#G z0|Ev#?KMDQ`lsg4Q+;*ZU)uW(qt2AYi-yI3djRNGKQ_t6`xjNeWBG{{3;c41pUghL3n~7gj>`Z8@ykeg2?0MuPfGcrwtWfE zm+*jSIKwk1Ox#IQsg)NcJZ(YGL*EY2QAww?CUuZm|CQvxuipG!ZTr7dyl&`%Oo%Q5 zHHQ}soWNBI5n}?J(rLTDe7+MA&yDgJ<-Ff&xG%GPdWwPz`Eqgq=(r3eRQ#wCNE&QP zUMddsIALba2xT>`z(%%9-0yn@^z#y$^}g$=Z~0XIx&kPtL(2arkMp_Vq(BQk9Ws+9 z5pa}O^`%cHvzga^COnAWJS^h3HTb$7z-g#6k|z(Pv#gxNQCS$OCD1F^Rezx$mjY2; zJXhh@Q}=>6m!+MpnX#ti{og*J^esd~*=E3k&)VAhS6<%7PTKgut*fD2U;cc7P~fTn z7@LBWYIo)xF6aF0q7Cw=M6Dz3lJL*!Bn6s4fS#^o`y(kMy3_2l-t{>Rn-RcQuwA8* z$iyy^0C;jI+EskwX#d|00?AiB3k%CPfX9c?9XNV563`Zh|9c1%->{pHM?AeKUF7In zX!l=ez+q7WFr(<&lQWbjW+~tY{&|B`WKEVlnMX%w1up)UPac^6IET8n2e4Eih7X2+ah<^A#Se!x(keVaICNJmoVc}$t;!Oxp z+yyQnHa7Omfqs^aEkZFnyA<&TR{>T&PU53=;|Qpb#3Kwqs(-ef>e_mK-S~xIViD0k z`8{iGU5YavqLuQGa$249^4ZIm(Y1sQChJ84G!eZM%%%|$5w5UnMFxGSXq9HCj4*spdLhf7fJ4%-~IOlkFW@+vViSQmOkV_b}@8) zxtU49YlaPh_z?j(S1T;KkNi z{FDjE`rbc3eF^nK4-?{hw)?GG(xWV?RC(4K_~0gu^)f)6`RfI+V8I15iUs58+n<0d z1v&)0@qryy0c=GQ;`=h2E2SLzIx(b;_VX<(DV=Xq{z{rbUoL)8iq_E$m6t*tjdQ~OIWuvj&llmt?3?K<^SyYvz@ z^{-!Za40T>0(X<~Pk;V94R9o9xk*oI4OF)}z?C~IAChy|%&OtyFt_X+ZckTok(2*s zHyRLhc=%j@2M`S4WS_0Bs&kB#$ODd%?E@w&Y-IBM>F3ujv2aO%1`aqg+Gd(BfLCAL zW8DOZ{Wf;E2DJRpK)prMo?{wfDQxur)b=b#Db|X+e%V=;7u5vH& zZ2(NVD=6fLp`M%?kP&tRlKap%>$n~)p~yXXKD#*?mn_g=$(&&$^fW_%@TT1SEa%z({`hF>OV0EBIlt+99HGPRI#Q**|ki2qC%7Eh*;9CpdS3 zw`e&5ay?A4y2+{iK#}S%+wlku z-(g<=Olbf4)x!7;ijjdK{qV1ANV`>1{-T%A*+sZ-YSoQB;}OmP0lfmOo-^vWEE9l=4PU%U*c|H7&(L9y>LnW&vtyl&vhlevyPWDaH z>>lQum9E|1JFKtRhCDI1yEut(B`7zw<-Mn>6i_?VdAG2Td2zETzJ~C23BEaN1t}yq zVxGWid7JJrtHoNw9n!#dOfpOZ2Nmd(k{n+_a;2=vv}`E zk;}`e<=I=_(uk{AK~nn;Mlij*k$#O`GLn%F^4ADDzPS=s*x;f8W6BE`{m4ImMzdOV z8mW|XFCfhUs3>&-A=E7c88Ogb$F)f|*65e#m87&mXm#N2sz>I|kHAnR#)3g7P9#}( z$FPT!(>$92>CT;fwN%BR+-P#?(ldbA(iBD|kY4Y)$-9|+=#rD2 zjs&irPEbKIok zZ^EJ7`9@nP@497a8F{eUZpbrtwG+y&;P>qadT+Adk($)9^5M)?EuvzbY()b~HFrpI zz%{FAG})n0AicS)(~VLMpWm^Tc#UHX2X!GBa_cspxxyAunq|_H+t?IWj#E^BhO|9B z^1M0prxdgQSmf4qX^ga=z3=_JnNNI-5yH1!l-%U?-dI5dEuPm`Vk(YBkW+YIF_U8r zX+Qn*^~%H=XmH0>^U)sQs>TBs-PC1wQ35!&`A< z>(-);Sx0#M6Ckn!6w6mu=qC1bnxJ+~)ha~}{W0JnQ9UtX^EQVxrwf?AF2Np|?$O95 z2Gy&d)|o3dfQ@M6YNpsMLwrpjm_-F~K%cx6c6Jeet3iVsOYOWzYWM6|o;=bWjsIG3 z0pu)PAM42rUZxcDLMj3T9m6}vb@@nZTg!D*o}lDVZcAGVm4Pd=hG(Qx@!)%-hvu_h zmPyHl`U_^u$om|y1{ULuBjrafHwJbK)&usGUYPjo_~o6Wut7@yVnjYqrK^y=p6pY} zZR)!o51K{GQyGh9$w100nNg7vqFiGg*?hIGnoCm(?|VVw@4Y2#gF)_~Z)bY^MME*T zToj5zp}G~H$QZt)ToZmQjvliaF+X*H1$vh4zAK2Jv5<|%DI}&b=(WAykv2mLRPXta z4Et4Kg??tT&JR936f#;gz_TH^N15P#+Uq`UNMe?f%)ST8(2RJMp_QsgW_=Mz+?5Kp#=k>V3puFrgQNY*_K9ZaBbLXygws zFMP}n*@`KqG8o`cU3T-|y8lzPqUzJ>_NikI%&Z=Ly!X?pt*vd&!O+`VdN1$S(43h> zn$Kfu{aQwsHxCZ%nVo3O@DZ8p{$4lF^Fi8Zmzg}HW67afyG-lX!eXy$m|~$1tcfg^ z6Ka3-uw(QI9LpiN+ZrT>8(tb9mdlf{*h*dZ$B&7W@o0vNL#c?_>v82%nH_G~VF^nu zpBHkvPA*P7c?+eQg~=vJfrkWKhr#_%pem_@CA0I8PAg*r4RktOspyvw(?w)5Oo^`kR`L`IVts zF|(Z)SC#B+5#+|kQ|H^#QeJi4XR68}TJCz<@x`P$4*LkgtTB%nkwSctQaCtj(@;CO z=zn(n21xALO}nF^sN2b+Kec76jS5)Vxn*W=*rYpe2f35|M$m<*soaZys>Mr1({OYY zB}f{xz$(DYfpcdIsy++;T&uqCvea>e8<6%i$u}fJt#Ngh8hGangwAK_#!K#d;3UCo zf`Q`9r6GitvjX(bW`;}#=uBDa{o)Y+{IQM%QnzJpql3$ZJJDz@3d8ZrKr;B+5&14m zK*8;y4yU<>6^pO`LdRF$_<%k5iKzqj?fdig5-!?B)lec#l@r9t2E26rGM$tr`I?3= zWb%_je5a#f6ds2km$a6%vHhq9+S9lH}u1m)6?0R#i4P+s4f(WtZwyd z@GmcB>WO4_JX&h`H%h$7T54I<=tJ;$*=BxX?K4n!M3Wcb-{I$6r63my3VY61Lk0?6 zj;Yh?Tdz#}pVv@{41CQLs4VX2&E7*!$I*6t!JQp1`Ah|G;ZIjSzIHl+N*~U)e79UM zl&#^5f)<~zVs8(JMbM9mtoyi!Tgo8NTxuLlu2nIKnWEe85062F6|7FL)$@&{Vj@CE z*oe9H$UQf2U!7X7Lc|6Z8zSAK{o`ZuAVM`mmSdBIl{)olmUp6oqg{CljUrz?f9%B< z6ZNZ2SBQ|^JE&F{)!9IRNTp3+)*deh5BK~!!|glE$0b~=y# zv`v1S7M;A2M`YRK3TCY|v@txrBpKdql-Z6UP0j9o?69CznGm`c{9agZt0XC~4^b}{ z$+7KW4d&zys2Kn7Y`-zCb&s`lk6#5)$Nl?+%YJ$CyF)hzq<`2j&Bvv9V;6{LvQnp=dqt3}O0;z~aQYaMsT@ z#glr}*J0+yW&RcgzZ7|VOmc;VEi_ZF*QA-bH?U17j@EJ^U>fhFCc94gm&=n)KJcC2 z0{9*T%$VqI@;)IK_c=|b$@ura(k-IP*08bJVWH}sE-DpvCd49q9tHGMd#%zXEU#q>n;leOd30J$L!IgXbPn zrhRT^>J3!Uz+mn%wesIuMUf3tn@x3=MzIhS?1huHQf{HXc1Xwk3hjVs@DawN!;1iA zZ=W|$M8Yp`MZY`=X(|7%yuTN%Jgv3RV#kuaEXZf7;3(otq9$}G-g50iGMn)&_l9lT zV~)@AX;sK&1&14dfBx<#MD~N1T$z1PaLeEv?WaRH&1!E1o8a|0rf!{^8JZ)gIUG)~ z7zA34G4nxfEc@^AEVU%n%PEZ&4BS>x91TaBen3q<@nV^m%;+bi9Itmb0Y9qtNrk0) z#DYfs{S~ojGyVJx;pwJ4jhEv6J+jX8Rv;g(JQAriTRC-|y9M5Jti_H>L;+ueCPiY+ zpDqRzW2My~@gto+L0pPUJV)R~LG5;pz0mSQUz@{p{_AXg^$dag1!l;2q&O8Dvy||K zC@rV~6W%YmF-hh?Cnp#^Ra8uV@BLCzygbZEnttgFW;dT01!~vB@$)meFS~&qcnpB; zv$#)vd}Mv!cG7+c!SjwKe0K0^>Rh~DKH+3^l{;=nQ@;9Trx#a2vU zB&JQm{6^vwbHlIx>%;yh)o@EyT428 zud45`v@8F>8K^@St=<`VKgOu!+q#^y+(kMI=W^k_S~N{$QqIIEVWwkM3Fm-gA1EPs zSHbp2#XXhoE$Bf4TpOsl2gFKC{@6#&GvtD~HFdFTWGwqdrl|0Vcf8a90YnQ2@Uu0GphQwSuVdN;QfNeVzs z#fuV;Sfn43;mj=O%}{dgR}53LH9~FH@II%YeBL+YvDd@N!SJ`i z+gCNJ+ZWBa^`S53xSlqei7p~DRDqMpVADZ>BM7;1)6&8}%skvi!^pN59Z8e?6Biq( z_B88xuHd2wC|mf({MjMP>R9^KkthYTp0aamp`K zcI!{F_$Xg?sT#%|e+OnP+P?6ZYqkBj}{cB@mRfY0N*7JeW zW|t@STA=oT+T7`QlrWsQo44rw+I^Mh<|oxDByIO1A2&M&U;E2&_Ha?o!ra(zDS9d9 z^;B%*=PL5@BKDlqD;4wA;{gSoKja3h4QERRD&KG@>{zmFJPY7s!G1vB&O0!0KXYbsaXOwWc9 zss`#sJ*N~1o%qXQ`&)z)nIJ&3bzNlS@Vie*OQR~Gqf>ZH$OJ8i1jmla)wVeCblPlx8fjf>nijVF+Np0OJCb zx}!^%_!~<~bjuoBcBX;<+IkVFMCRzG7$}T3^{EHr*biqLJk8Eq3iP~uS?m*%R238` zigKD;j;f6z`yaO-u@$S(^u5f% zq*79*3rIQNjI!`DLC)s*sbgY*N&vsUUXTSdG!alqojn+lh8KbqqV=0 zuS=DhZj(~0`IfpUJntblRsN=|dcA<%2iO;%-5Z z*kMenUe4f=44EJs?0xa1r(b1%wKRv9x%zT%<;d4%Ibu>S8g&XzKfhu;b%w#Ai6Y_X zWE77%`j&2odCP^+si+puc@Fjh&*?)(5vJsi3n#pMeK9;ze!3T(R!8t=aSV33mEbX{ z#5yt-YskL|^>|os_%3gfXxEm$tni_4AkuMo$=Q@ANpcfeD{$m(L{7vdp814OzEtRf z26q!m=lEM(41{u$qO2E${C*;GAua2{8BBnN<$;(RdDn73A(GgBN)a<`G%(z5WVY!z z>wPb|itQqfjEYghjmEJPU>d?Qk`fUf_ciu+cxAr3-qmi2sh^jeSx9x5{HQR~HxV9k;bv zyHXt0JVghP>jx4RMk1}yK%n3B*MPzgUOtMHjG+;LQ@jcM+&Vb8bU0pa5-(zXt;S+N zoqxye)w_3<>`bBN!out#Uf=yvqln|asWqmL($STk32M5|-pgJ8{V**3DB!(j>hge( z)ib0e)MVpAtVT&B=1ZER4yskPt8}JkmlK2y%RfG^iYTXQ1%HPe~){srwxXUe+UAKLCP+xH`*dxAqdg(vlH zVUo6zH(zdN(8YwSncRmVjCMU{`RVYGdq&A#-pt-p!k$gQ*6YuKmZYu-nxovuY@iTj zxK)2V;_OwvHcLAwq5Rm?%J-K3^mR{}W$=@N591LPwNd811Dfn9WUblgvVKQ5o*D!n zKKBLhscOeO5k4C17i*~tlfb0(7J&WS7c^);wBpwUFQ^TbdS+S-dDhe;&)w3|Ag4&+ zPe+O8@98LEAn&GzwwC4ZiqgCBCrS0k#$qjpdZkw&9O-riJEQt&!-aOQwW0nnHR-Pf z(vzRuw({Oz&s!`QR{WT2A#-vce#DuF^ZTMq7w>xUw&`L->;aP}-SsV5&jg;uX#CLx z`TITUx2V=f;V7DwLQ`()9emNrAi|aaHay3Zj$6sxJufoluFwhmg+9W={kCgw6yX+k zR?@_}a$JZYPvVe?i)3?m)=+V~Nf*9je^->e_tLW3JDZx5oy~d;5TDKNwX!_{l}GvJ z9-aHG%Xx`Us@QL|EQj|6UKlgAi%gfQ)Tsls6?U~GQjq9V1mzuE*u(TB;xRL#K?TL}jD(_qPmU;+Jv_m)_Zp@dC$5@=pBL)-oTko6W&RewR-CZW(iV*g0x z&a3`q0f_LGX_O2n$Q!$g%dO@Hf%9iJ z@~-?0Pk;BZVJF@AG$)~fb4>uV#pjUI)~7o1C#GwKSGy{$?5?yQvYe>hrQt#Oar*n4 zn>NCI&GNL*Ni=Q;TfUfk&)r-NehL!}KMuxxvXyt5v-2|)anzr6*WlUN;Z3u83a8am z^yXXM!MWL_cH*0akc{hCf1jG;-QbBjrg_I&L_g|8{Td!&gBCt@wgZ>-=Ek)4=Xq7s zkFORwzoKWDG@d?roqqbp5`}*03%ai9nR|Wm1b{`@Dv3d}+FjoHLpChunN}@E-ludL z)6(^^Zs==}h?R!P<5Q9!YTaJ5WA8J8y+E7z&VSF%60dSXrI_2xU!Sb2ThG2KQ;>tL7M}_k8zCR}AKJ$q8#a*E4{&ELLWX1af z0qkO*AkAw_`2sG6<@Ft0rOPLUq0;%O3w$ZL*qLQW?_<2>nR&O$>ZW*=TWUHZh z!YOq{mu^p@qzI^q`}F64D`^!~a%JyQdv~%*`^))#d>2I8XvE)kEBOzptnM5Z{jSmd z!ud^B!{-wZv)sq0#MzaVu|=9S<<>K-)wT=!9yf>W=rrgrbyr>>!PJ^wMhwVfc!xs9-ZPGD^=c zm~-*#e_;!L!#APZ&5qX8@4TVgyB<2f+{H#|@J>04?IL4DcUVaSrHuUv5;A+mfo;UG z!B^@V#F0zpTh22DW4QWq25VC*UQtOoVYq<@;& z`%b$-sc`;ktY}2}@&(VKfJbotPxBQac`E#X*Se9RX4~h)2x}d}N*C~1Cj|`&qb6DT zeK-LSPhImhH+}d!68;P21$t3;OnAz%ryd*SOt)~9+l`1UpR}*qlTYxD8E7T0!`B|q3i4Wh!bOyC$PE++S0`P{!s zSh#uJq&wZY!Q{z$vVla275`Xb%)|dNvvSE)btGFcUJu!@?cs`J!mvnl(mfgAoG`i_ z>ZQs+3d@x)Cr1U{c|m_I{(xs`70#k6_bknSZK@>(5mA3El_H#4gNt=|snb9z$4A(p zu>$<&6!@-IT!ZCAv9qwo{-5vl-0d11)wuA!i^=hs9DDNhw_!=oQWclDOi^ing_{rQ&#r za-n*B%nBzfBWW8;Z`Ii)KC+SJLdNu}C4h;9tW6t(Z1;N21GZUT3hjmRZvN@JS8}&R zLgUDNf`n);_|sfH2w&Ixa|kOSKiIDqFn@ZA06Y0U`ejs8@>^E=M#@i3g4Ha#-7Ux& z?B(n%n*zPB|MUgh0d5@qmB{)d$%nW`%KX$-p;dR=2x(^xI%s>Ayui-yqW|`hU@sU8+Zq=*zYOSQA zqxShrhY8 z#~+tbwY&X206AH2Ia=LJo!hN*xs0L zt7-1}ILs^opXAJu-`Zp`aQ;d<2if>n(?LZCrtmovM!NskZ6_ct~d2hWbR9mQpw}@TJ$-}CulnoyLCE3h3nE?Q8f&Pt6S^|$lm9SeO^we zOtM{D+(#pra}7sHJP!sIP-oWd(aSlVHWwL7qv5K2rlzJ|w<{WJ?%`DoH?!RTW~O2q zWhtq2`3!xUiieGIa<*5P%nu!n(l4u}7KuAlLZZdO>*!FvcSe`Cl#fVz`7!{u^oEf% zyOn{p-9X<;6gOf={8gB>_f#sY_UNei zXNtAczI~u#iuv{VGd>A)WP73sz8F|+#t+d=9K)? z8#~;@{`4BM-cE`svR>5;he-vCnmV+S;CgwuPLADZa0`<>e_j+hOKG@wtm`2&JUv+_7scTnw3W;^jhjpA3@lp0?yUG^Je?Jw%4iEl8L%=j z^UNvlXC~(5<+;eQQ zaq%Ke%>%5t$0yU;4T;sBY=WTg&_jbyqW+6g1_2g)@CUphwyAO5dKl}k{L#AgLILGM zy>pI2DibCU8G>8)I}mtO1?fC!bu(<{1sN$+1DS0oUe*11uY-fuhV}a-UqE8c<}E4> zDtV%*4v%K5>(!(Tn@OFd=_xDlIvh=1lA4t7JmN-~&$1p;)?H{m&|ZJf;<&cVB|d~z zYI!2dj-VyAAXh?>F|MvIQ`i4VF}H1|3nyGd`Q&oh+pD4I^CafR@O({r3?j)LV=603 z7joLus^J`YSWCuSvaFBr8-4!fv8jIjoW8uaiHU}N$N!Gy7hZH)+8*+~MTp-EBbL6~ zJEzT|Pr!p=W#=1LMA0I5bF%Fy?0YLsLrrRYZln6Ge!`+7e$6;Kn~TD zXrM|#ZQbLw5{HSnnEd|}*xXcd686p1lx&|Y8$38?DoVdF0$Qtd_qr)qJk| zm`gWjE;?hf<=*se!uYv3J;X74+%w90L1UekdaZb@iE#Gz5l-%W>uAbJ;XKnG)}$BN z<}APGdmaA=H|AllU#TFF4&pe#`w@~ zV6PnhzPksST%f_TpoGK{_pO?$wV>fuMcsBiY|k}rTd_z(+C^PG?KbWd-?^T1$5~g@ zu*fTA`brICuJ|-*p3BWJ?&a+_Ho4IyIkzM{UP~NRDP7E?!F7aL#ru?(P;1$#vDdEA z#Sf$m{2ETMZx66NIyr*&&|QB*2l2YI)#WVY4fBJ|;YCAeH}ednAWHT zw$jZgw#%(SS@-pUnYxq90}d63#JvNa!2qTbgT7qFTGvaJh)KJmoq4wE(v@2fJ6$SJ z^m)bihtR~TN=+>ts2wdbQ-me`3=6U?zZG-8Jy!;IfYR<%Up?rY!(K@@KcA&#*YPxU zr&-^%?pnv??&8kdr@`q(4(CPoc!&K|Oa0*y4i}Y^f6q`#Z=O!?+L84jtoOf@B=LhX z6lP&pnkpV#Tu>Yk5Y4Tj7Jo0WG}BlsR+vh{#p~YP+=NCJ7Ro#d&Vx)K^2Kp{Pk$_t z%d_7$kTwLZ23hq(uPNz>3`^49&-f#pF9{x=XUPv?8wvwSqt&bc0|E`@lXXvIS7l9-i(&^ntt+dt`5vBoG}@|V-n z+_%~!GBX)g*H-8xWO)^4TTjB+&zQw~eY1Zd$?WJiyDy>H=*s{8rhZbF<(t2=9(#XB zmJz4(tF*bkvrrKgpTxp!+SLTbdvBf~Uw)Eb1$J`ZPPi_$a}ZAork9DZ#S>m884){LuIyAA zOt*v_qU|BdJ<3N4-wa!+p^X?{fY5!!Uk|zGKy_7_wFd=Ew7)n?Dw!C}8`5+vJx#g~(@*f(I)|D|09{sb&UyG_pB_K~4`oC5wNdEdMKRZ@p;b?X*V|LrK$>xMBcmtQMR{1m) zOE|H@>d$Ao)ec=Wc@FA)4{h{vw>y~Ak;BNw1*o1fA@-f7U)`jnKeU-n*EPycOUWaMi)A22zmmMikQd@Rn9~0xFjCxXG?%}u0 zH?Q|b;EAh}EnW9496}dSLvuw!ABu68l`5ydkS(Mz(G zcZCbPZ5B0iIs5hL4v@In5?$l&XxB@!?Z;OfC-3NJIq=?H2o1CTDjW||x*!l3o;s$Y zwig(pdK+XDlKd`0(n)CxKKk!5K%%!cacDl7sc4f(6A&BUMPAl3M^MZOyJw{^GS zecqd|i%-VBRxHa_7i;w>Qnl#eIz6gSRfuqX=U7G2*+o#Y4R6NWtVh+pPD_6O^EGo5 z*XaChVNTXH@>AvwA4C$FBwfEp^r2X)=f@5-*#3z5N9VXc7YH8mY6|O64EmaMzoCfK z<%LiGDFKG5lw#q#!MC}`N(BOR#gszIV6^)c#^TQ@4V@S_WI5pT)+(ohXYnX)Cn+210 z*`oDOe}9vZte%}>S;>oJ&?s}bylMoy88&8J$8OFmPeot4@0tO{$r*V$UO-gAO4zaQ zwEV+om7D9C_PT^g|8)E3wUi61ju-3F93|qd8L~C}TCWfB2z+Vthl|IT%zWsjOzq$M z##d)~o9VUh`K6KXUY$8c=rYIhRtajx#lJV)DEr`ybI^aNe_G{u`L3(Uo6;{}7k$HF zG*2!4W?52&r{P-){TN&G$2j_6R{hC{RmI)AWBl3@k{7=b?c?*2wkBg-T1@S~bMhCl zJA7UcG}yx3K65EPCWCtFM!aTL+e?4PegXi)h`{a1;Li|KxmNb!UgaS zuVFEkQc4iBy{>6ksEJp(eCQFpW`5ctG4V@kv6)Lkt%Vu_Egzu?##E$V-BDFJ+#^A$ z?on{?m83kWjp@lYTzwimDpQije13ni-Ahbm-o~QTDwxPR`1=ZB-?Zbr#c*J7!>*HS z*7vl@%fQ8N8s)jmuFGH(BTczWIT;hW?l*-zASG%ugf07 zeK(H4OIK|Pp>SVvN@1=A{WUg(cch6nM^Co&`9$OkUdHi;6{EcrJ(i>@icDx<=&(XbkQWY!lQPA$NJ8~x}X!=Fl=#?AtqqsxG z0$yb(Ujp!JLCEYc&CapGtWs#)USg?3(@7|&A&AG@KzvD-I_FQxveRT zYo+zRY;Q;UP`TmXFmC{v`dV^?kNte+*J{3=hm_Z+AJw;8L*Ka;C2MwK+z;kmtdbp( z<~W`74*SlBb@*bI_F!(p1a*}woco^k1S+y2GiPOI5pHcW=S%T)B065~&%CRgds+8d zc-s=wy>Yqk-YcA)uVzK+u8cQ7s-jlji=C02YTBjt5U!?l_-Q~*?2%en@4f^(RoG80 z&zSKv+hRW@YAi_{eBNT$wzRcEk>eTffX|4Q zgQeFk>vHyZMB8;GFS3yBu`f@T;#c7>ZVn8lL(tdEXS8WkhKY-Mf;qhDddF}43J4py zwELq?8;+Kg)66CgUY}_&*ITS@}apCdK4twkEmAF1J2EvAa z-kYy%RiRwmcvF#daECx;3H`@#)@F&?2cPY$PLo(fIC+Or+qT`9X6w}K4z;x>D7RA0 zEzRr6JoBm~zwlz>;)JE7r24}L9AsksSclG6?`H;(d#IT& z>YC~}tW{(tZ-*|c?phK+H7pYyfL>bz5E?|VnAfrt3P4+2!=X(64Xe2*n~J=@Tc;5k z82B_86;Hu%X1dC9P@P53DdD}4YmvHsa)mD+2Lg0GmE!H#?d{fhk#1^SmHP+NfmHkq zNN#SK^UgTuHJ&r)MBgYNKNPbzdzX+lrJ$MeHiAJ-JgxZ&l@EB|`lf5pelUPEI>DU!~! z@Cj^O!yB4!#||tQXT=H4Vu`%orWpA z{Qtn;{`3HF6(%$HR+0PkKeYS7`>zIfnOQk}ixhE3m z-jxKo zGugwFHQkdlGGxunHt{t6b`}!a8F~>w%g5&n=k?^~2zFJIPd&D~yNgffwUZP01wde8 zVPQtXB|31@7K1y}UDhB#*x-c7m$+K@ma2(?TFIkyn zJM{EuVUrM?QUkx`9rniu9W=rDS9bRt)m?8b}KGXcS&qFE|UGBEhL00{+UVfc)fq=C%NCSY4XQ?Ktm`Z%{ zTIWD&IPX~oh9dZ^{n0GL=%%C*Ctqu{=>0^uX7o}JT7gA1&QQN zoSMCSh2U)S8B=!1YgnC51cpGRKvx9O%1%j3XW=+~()NlIr#u)`Q>QElVClJN6~r$abS zWHm=7QUPEe4{?UiA0Ta3$LQKLMVoM!;9A5}@U2By!SfOxXv=WFPtyvk(GtLs4mW)_ z+vwM9co%xzgPNmbFtfq5HC4Y~j*-pcuo`_fl195#{k8vOK$HdvRH!j)>gl}!Z3x>I zTFm3%T^fi&+FQXa77Hs|36urpLKX3cP7}a87r^xou=KGxB+RV-rJf%?rK#ZGl7RDI zSlYw^TBTr;*R>Mn!PB|@1}ve$UmO5ZKuEF!5Y$x){YSldp*w^&84bD%X&@(inA}8(l7ilS>5%u$gv86g7_^@wB*&&3jQ_-7ahSTX(05q}f@m^5#VT zgFGyh)c*s;rDvRPS9~t%uUlPL;W;a6N-ut}$^*}wU#T{igZA40x@2f5YFy0QwLcGZ zGsF7Zyz@wQTd_HF0k%z#{U%rH+W^=k zy4UY^TNS(R-vYeqcO1zny6aK=mp^>B+~;R&(VeBxNgt273CphDxhG)wkj6yns&_)A z)t{!iVpZ%nMqES>s{i?&a`OigWV+vHtbI^G+vtd!wa*_U`=(W2Kd^2AcC7tFt28R} zOB4IW{*D*%t?iwsFqN)vWfYxx1N&><=wBS-Qkz+V%FUs1D7@`<#=dC2hnxgHqaO^; z9_P6(bR{Ru8?Cf5boRS{(+sIByb3Aoqg}Uj7^UDk; z9m|l*wVTUXS9^AgpGO-M@wD?D@F+H&=S{+1g!Yt?QoCU|4}fHa)n&+y(u?-Zl>7d^ zGR&L1tAHP){i|i&JVWeg6-V8WsqypIuV3Q?B;39srqdE>jf=Do9nKi}QR2?y4xh0b ztg~Wbr@Abb?HxLKHX9NoOey*!*;kNaP; zRcM{#_RdF;``+GaH8isgE{vlHu05Jh_kK=r#oOQBYfx$-)AKnNC3|{;XgZr8vaa_#4^u`2zSLgFg@MH*(E}5m39|_ATW(($+}_O<>1b=Jo{RT%V6 zZnZM2j(cgo%qBC&=SI?#?M^0ev#jt}5|c9(d+$)wVhb=w)zhWTm@@9{6>0G~yuh?T z@U_uyr@1t&Wvz_X_T*jW>S9i1=SZ(l+}Wo$x{A)7ePQ?coVflA#5u!G(~j|=cz&Qr z^(=F=EY0grixDp&PZ(Z87skp(joBl(DhX;R#uX5ox;t2?vV1=% zhzooNf(Rl@CmnOC)6dV1Tc%q}EITcojdyglbAXIJ@`b>`YPcrod{7CEUnSmUW}31& zu-*qxVaig%?FIFzyV1XFa1YoM<<-#rUCJgpMAw!ufTJxGxlxX^j~z5YAL_neQ|SKQ z{VC6l-(f-6?SZd&g;tmIEmzhlP0qrQKI&0n!_(^$lsa|;eHi8RKKJFGZC~UQv%%Gn z*ZSj=(65a3eC;21)lMAPhpKRhGH#>#ZiEa1;Mx+aHZg7L8Q_j19f!$gK6{vvOg#V7 zIz0C)NOHW4Z=ySM(YmqfN2=zy_8`1=Q`QblN*s3}n5e7POKV1DJVhOGn0ej_&z@z2 z?-*|;Qp!l-BE#zbkEe)~SC|;fu7ZnW;?&JFfzVv@7x7N9v0n`C4mcE6S8*I{=v{8Q z)D6eQkp6uzC-YQ`!Z)R-ct!O^sVUdYO7M{#7s9oU?D}Yy_;>AbgeMp*#xHtJZI;ew zN}go47ok@iu1Dd1*DeJm0>iP`&B)|J|GKkKc8B$hQnnjp#bglQ>7;v(Qz_?x?5V-$ z){o8o>(l9gG{D7~4EzTOIk&Sdd1FDQAF%kUnhU`L2PG;ikmAdk0l;$w=}HTgLDrmy zCMkhteG8Nyoi#33c2w2NSGDgx*ZcVla7&;_zH?RKJ9sHP^KF~>Rigoe&g&J1%LNRA%h!2LN<`lI$;TZ#^ZE68;segw*JGhd%E$8em$hpcXSZtV^BgT0X5vs zXDb3FA`4Ec`HFO$43Bi#uk}pdLxZxBDRb9))E|h-S&via@x2a3R+OE;_sk&hNxZA! zuwONfNjis@yn=TKv4poy;>_P2JIKPw?of2C{U$DW-)=e+$>1~O!Ykd7h$I`BLvg<< z6OnThWgiQ(b@Iy0y8J-cu^m0!#R|Bl34k_Q)TJ<9XvJc2Zsf4#qZCy)Ss+1|G8 ztz%x0qN22lO#YILOdR;Tdr@SxyR%8p-Q6LC>Gi6mAXx>~tFFhQmxC19?(N`$0Oq5O zbE)P^mGVK#1Ch)3lsT~R;Z2uq74ywzDx%dZ&KL|XDR?!@0^Jn{$TFMLU|D~N(mx(e z&@))}IHeE1?y!`VdLvOp%1}#J-#U2Y81xcSaV3B8yuzcwxc}6+z`~Z9xB24gYI$cT zpeCeYhxYQ5aSgZlQI+jUzi7$fs`ksRt*qoKMr!YOd#5pOj=pQ%&YY3uCK4engM3ho z?Dx)Z+bO~qufu09+-Ekd8jQG+_AG97Oa2d1$$hC4f3k}!z^u)2AFbDXxnx*vv(@&k zxoMN{JIaF9Z6I;8BGXl4v6+(3(<*DxbA%c_`&8~`qlEyiHx)8L7}@fmQPs~b(W{id z5CyY{iCj97Mpg1B7=Iqud0n0amMQSY0S8+_iULF?QbFzf0&?F9d2AFP;^mY%aPMS7 zEdYn3Lgsgp0c(uGhdP1r>5WfN^LMEZa0Uh zDkfk1dY!IC#tu!L44}PSD4LOKn_DO~`~HZ&>Y45WR1?#Tu!}Bv#?5$73|o6HH1liw zjl)oA^KH)2NXRg(ERF0kHx@VbVyn{4#%I{?Sir$CU~`NWW8+Kv?uEn4me^L~e(rEi zD~6c6Q{vZ}cZ>n+k-4E~PknC;1o#*tT>5olF|tqPUZyjA8a_$i$l^m|I%|fQ=VY%F zySQ~Q7;Fb|AN3$N?{TH*N6iy1T+_f~ZeSAZ3Pz%I+ARlnxl_43A|PcEA`o4?%@C$N zP44MQ_woChp78bs*Ou{oVW@oCZri+qmDNouG(ebh1O(M5>m0-3DzfTwB|xJ*1RJYPDkb`nFa&?rWKESv)wir`TNmDyjL1n`u9Bk&)`%-lR40kDhXi z>>QUy%4E9g!KQ9J7WyPJ(rWh!JY3RY0Br z?ECokVGXNs-gdBI*XH8JhJ8k`SmFa|gajH+z{c4XhUZv3Vei3CLq+wzL$jp4=F^nd zz)eY_=T-x%$ANlhFnhjJtl^!}>m1$fLDK~a%#G)ZnX?LEfd7^mdELFMh7xN3^eJXO z2keob3^i@X( zNg{&XG`qagSCNvgbK4V2HUY$?sR>Y3fpho_D|j#y1lP%{fcd@?U=a<+FDkSNdga!mqv>|)zLpKE^*#aixASNk0= z=M#wKhxmk+Pnn}m?@4|wg!TZ2;!;WKM?t-B>y<^K0RO1Z3x+(8!fyV%nq@1CcTbtO zodBKyo){F0sK3M!Ets3vL)@Ov%9p8zJef|Uye{DbNq@)kf2<*=eD zL`24sIOFUTryyDJ4Ly$k=+~-;Qy6QY;!W0~$U-T1nx(^v0>C(+KblBTAj2=c#l-$` zJ-6*r))nR>z)fpXuz6$g2FKaGAXo&nKXNVTj?Ck0%X!A*&pB!PWun~_3B#mA3`{VyNOK{kL8PYB)BQt=f)xG6dKY{m;d7NBXA`e+f><^ZQ zkO8VBmcs+L3vin(ytp5re=Lx)UOJpCu3?nu)iMsY*ppDnpDI^PQhX@(`=YP!bbP)c zCJYY{uGboLx>&DD-_oG?vDn+ItwrJh!Ah~fzH5K_AG!TpK}typfdyt4fqda#ko1}KLuQH%5FhXW zyB>(t7^qhn)`k925*PuaGXYEq6?ni=F`*VP3lJN_HNShexUp=I7Z~yqI{ZyhrL(HR z1;&0bO(rViF8y$v1!h4lFI^QXcj)#B2qcxR&zwH*w_`b~9FLauC~|2|VOD$F`w3i| z>*Rs8Ka%OynfJBhzO6qs{%B)Jl=`ke}fvcyDe%)`b*WcDg;#jYzs&F!M&fVi-|lw#x-E5g^Jx% zlV>VV-%u|VDMZyTO)^s49iss1X~$>?S{bN#W5t*5Px^t030UMW{QZ-i_pYW99{e|H z*wy2)@(l5$Tez+~9|;+A4)=xyeUApOh&WgT;zO>YQ~Zve__*j!hIcBZe@SqGv1yZJ zz3GH2?xXvmz)BY(y`*5!Zwus{=?W+4sE2An;#G>pK>9v~5KcF5Z^Ki6k5~{! zu{<6EHGWB6`A(LkG_(^=00r7Hx_-;p#Y-EQZ?I$8-5I+JpF6#eVa z=2kJEH-YTuN|kt=8LL@68`_^`H~X>|(DdzHR(}Ss5!UJBDP9L>%kwL>>q7KEyZOT{qweCQ&-R61VADpy`kI#Y~g zCt8-Mm~xAk6@ogOCvEp9NB2L&1c-g&D;xe2O4VM~-qj)BFh|v$tjW1_>I1&7%}ueh zz1BUC;gY;qixaZx$L$^IO2Bm4l}t}QdNUmvjW^MJinW7Ga<`sJ$w1sk!by?(aU)~* zmMT&wL1U`=%=gAgO*&!eW!>`48Oy>3kebxUHHhlPd5cb7V|Y}rZGHGou<*)8r2!S~ z#yJa0t%o+=rzR1{xxSRT?~;4eDj+|!At#{p@nL=|Skv%!t*Qe^i-MfCwsNL~-b3DW zKKcbHWP>%sid^G19%?9xf5Ldwis%`X&tyS2!KbMJ62}6m6ezIMB2E93^=ZZ5Nbm#k z_OGdt?Z-+={HW>IuT!oerA|lBQEOWWM(<8uq0c+{p$YFzk2bC2a% z^pDt1#u`~s@iAmN(rero>orTQCV#eE?`$${$-f>$UA&2~K(lsB#RFZGrV}C=xYbCN z0RJ-KMfP7P8rVXOoaxq8fGwAD5`G8l{yjKAARmIljKD-eH<`=HCiqf$&?VMXsZeF* zKp8d)9kb~I;YfrdIv+^=fO-fk>UVa^we>Rqey`SUz%Su{tOO3hRB;DI?$H=$z4n!@ zPThsb{#1E1<$ih_;Vm0?*3@9s=H0KcJK>hm9%9{=o@nxeW6?4AKaT728fpUWMGK!e zj?26IuKmexAJ?^4RnaLT#H9t{fPTNy8{B1~6FA&5-AxB}&Z^JZ0Vx}v(OLWhI*YO%Ww z=fZAt#*$#A>AkRK=|aPQT!4q<5!f7H3o9i+9?X(%Q=C3k8^eN;k zzO~m}x?_n#71%s5FCB!n>8|J+AW{%SeFoB}lS*=au%&$YC8(AoC<_4OB!JJy4n0T| z$M6-H;mk4q!M5^FCle{JD?e$L_f)u8d;uXLXvuXIv8y+2(ffl?)t-9y4|Pwm*~%~X z&VOAbs*bj?)*L zxV*2xkOJrlB*Op^w7BlO^T5t{v1$RTvcTxoV_9Qe;{oV(U95V(1dYC*d4p@ide&nW zorej0_IXw1aIi1NT_;lY2MmfhbDf*>m>1Z26^i$yqP{z#C9K%vbsfQrY09s)uq}BBbxn#L6j7H3R<&B_QC^ z7YsaZF1Wf|xu6k0upU8CeW@XV`Q=?gCVZ|Ng1o$t6B>QW`+2OhlMiG4(w(d|R65nL z{{DXGD3#&{q0B~*JO9@NXj-<~szDZogJl*{(-3p_LF5_Xs3%H?f*T)kB)6G^&BAxC zvD5yI6TFOgk-$9GrgK%LN_J6xk!LxI3e%OB);v3vr>9?Ue30jC*3t0V&g6chy78bP zjFy+zD}UK`=InR;`uX#2xQ~jKQ7iAhfzQ74;Z-(=n?nVzecNC`;wkQVDx3espT{;A zJKkYBE>woWXa>LV&JXw3;f9eGOor`y*?rY0a!l_dj$2>;Huu@6wnB$Izvtq+XrCF= zKw!E(Yq9rkYwvppVK;cF0QM7Z1R5 z?2w?iJK`_K&5)SR8fAwaJ)V#v6d1|W8t`;MEyOuS_ z1TT)w*k=K5glKR~+$`(K*q2_f>gTLYlJEyZZ+!CNW93#)q714&ST26t$K{A#`S3xk zY)Y(5qgzJ8KwsyzB&F11-O-A>@v=}l0bhEMyL%r#`w*%$BtEv1AieXLGtF(+#YVj$ zzGH38P5Zsd>IM@XO`$ofrR(Fd_49Y6q~$fV^i6-FNBA+LZq?pk{2adVbrBLWx@UGj zUgd45rZF*z{rvf}m@g;;>7T80e56)xgoK5K<=vQlXV?=<_3G6txHMlE9muHF%8qkg zqK3kVLBsIt39|xAZu;ZPWR0Cpr6_!ob>l+SC%QHB@O|H^e{Ya=nB=e$vd$dim()xk zv%3(zZfNTF(SgKhIymB`e*3siVC!@Rg23vc1w-0fTNxptdYWQ--zhTE|9xGHm@`af z!`oVlU_mFgtSoW~5K9^8BmMt4eJw2P_ilWT^B{wWY?_t#)|7-S)5rL&CRXr2S`pQG zTs#}Fpu#?U=BxyK#2nG?Q&Y1G!ixptO{AnFnq#g~LjS#1;a(BE!>^Fjw9U{}3GP~Y z*l6`{DU#N2k53y%)_Y*Z)M8vOXOJh&dMzt=Sg3WtraR&K>?4OD1-5G?q*)KJTSrc; zS)B7cNcWf8W*tAUmH+eFCCF`k0~CPsIS!8tR|gEX`j-6RoXN>@+NMsn#(vat!v8(75Sp4WFEQ2lneTHe zrBCtC0<>x^uoNXFYFn}&hxB*4hM*ZsOG}poMR)coMYi)>zik__p21B^o(9wvdo6os zma3@F>Kzt+I@Y(m;7vV3|F8Gfqhcknw6N4{H0h(TE@^X;6nqjD_*4XvS5C_38(An9 zjtA+SICP#_9MK!ndg7$Rqk)gOST>Wg4rLv*4o^$6Xhg@vjGE7eQ~uxQU4>I6Kughe z#ZLFoe!pLm|8vDI(b~7^eFB~newMM7Bq+a;G%OSfw=VkxX{~iJEpiWM@gR)AzQ!ei z+NY&IYXqR0l9JM&OIJ*|vMA$&t5^J*xOaZH3%dq5rw6LX7->7#ay4H0%|&`VkF zGV}y8(zHuZ;H}=`!vjY7Sh+TUC%EH3FBiL?fO*qC$Z|Pf!DQ1+s_S;y43|~+jy-#y zO09?(-puh|)>Rb}`c7uz zhmZPOqKR@|^H@_H%;i=dw*Q zlt2N6SvGFUKL862Y(&kB|3ssRl(U6xV16fu!NgQ{Zs} zHs+#qUYdhqdoraKN=^9uwxQ>GHH!F%m1g`_jcgABGH&n;>Z49Ga=*ok&B3s#gZ*G7 z!T0qln@{VtXy=-VBIhE2(#y|HamI!jSKfG=_2E8PziF|+9&ojY8_w)jvr$$#|D2Y; zUYtA~Ao}oq?k9{r!yfJ77uU93t{01;&OpFX?X?g7*QAh=-pZRZ{Pv&K+HTWdPl!v> zH{XE{o%u@}>iR8jTTpLrCvrKNg^-w;Ix2+Q!FC*yu*!(EOR}3^m-HH|G` zS%nC&9&nWfyx~Q=Ry@~Ep6`r;p=rv|)in_#df!M}T7(&9JO&Enhcz}`QecHBz*6E8 z4=x`cvrf<+U%qo{XlOzMAG&Wg+NRp_18Zx+i8z!H*NHy#;Uqqb*&cGHjRm)d$w;&4 zGMR*9*U!a1du&o_zH6(LkN?P$*02TG!S9n+Qr*8ZKfL-dv*}`bR^U#TfKt-i5#67X z1XdpE3}kQVOPOH-Y7n@9)a$J^LzGKC*34W0E94aNc+7`V!c3JsuIdXat`Vh92l~j@ z{T1F<)<)<17*X%kXzky=?J(TiVG(c1^{guqLWHpm;fDKnNN5R=9@R(vwP9y*fgapg~Z~d4>n#QYuFAW zZCUW*W;Q`ZIXPCVw-wCr>gT|z8F$Ci0YhVz${9!583C_n@6HjI^{p;q;MJv<_CB~6M_xid?y-?t z`CKMwUEhcy^UeMmd!&DJz}L&P_6R>m{#HR%sy^~sh8dqcnK@vgQTta-h-kq=Svt-^ zeRMA}!cmVk{G>ADd!9_sx=5j%kI!)U%KaNmP~T{2c0*+E1AEt}-1h4%**}z(-~hJ) zyhgk`twtlJXR$ADr3e`OR+0;O!d;q&%HvApr>5jXXGvR#HLBoPBUtD&a2Eb0!*k^Muq3*D-l$2^7&`&DDT(u z9{atE(jX?M=jrm*pG~G3_WyrjdXW?8}H|S zp7%R{sLT(~oU`NF>so7Fd!Ml_aOIyZ*h_Yse6*x!LO|CR9zty=kjgU|whIc8w(A|j z9DI%sJ*GLr6V($!TJCu_Xs?lar0(}5TCY{kxK8(#S-71CNEq2MorJD>{QMcU*ch4+ zz|J53Z73abN-m(^68u&S!(=(<*xkWbU?E^i>!n+;A0rcACwf{9_kMD0)!rqgcm-Rr zUT-X4!y(?RGg96GLm**i)``&w_OWHK-!4w?n9KF%oc`vTA$qBxK6(eHikKsJjZZ3;xfp-eOuEOojYJzC`nKE9mvYs zD&ODwJ`lrMzEV&X@$M^b&Mz>}awp3Ii%d*#m6R&bpy)G}ka&PZWP(V$i?iuaGAStb zVWtDkW2XjrWEV>BgxsOT`ZMS-{c6YGchP@kR$@0(1nIc%6tTAp*y!qDV2w9U+T&ll}oW4jIdc^OFa*{v(J{2*S zLl)0pJvg?(TS?9)7?U8jUcc<+C_t?@jfVQU1@2K5v!O}eiXvDSB0`|QpJ+y~Kd7XW z%&xV+O1@e&->DjW^kzP6v!e1^EyH%Jfg#SiO{z!2ErQtNhI)!pF1co`X!!!USCe<9 zeh`=lX?sBKn0RtOf$`zkuH?s?!k<{#l)@=;LL0O5p&reJB+4TLWfzyMyiVlRkr$nm zB>HZhHMzv@TrERM*(r(f3wMYkW}6Hu1Y}AZyL**FbVfovngz$$v0=k|ZTm`RbS|h$ zjI~}H!IwYDuXarYto*Sp1h&_Gy2ZJVcq|2ILNne71`c^B_k3ktwYe(Qz@6QHyR-BC zDGadc;#wZk57$22BCS+G6D!}$v6W;N+++@t^p2ejw&$s3a3EuMwbWV_yGZjE!W93mFq>BOjXhEuU{0B zzHdhN*IaI|L!9W6d>PFIY2rL6PiA-tUFI3DuQO&`kp%>AP4r2Ydl%H;J@YX53LSFw2XlY*{J<72r}8TFs9f(1znXNCnm4N}+41`Od)?bNull^!05;(fC}0 zoiHkSmCK!xIA|MfoJ$8)t)epyOAlO#k|P_GfC zVCwVL&x?IkA2Y8K9Tq5v_4^_A}}ZVkxPI6TCm`(k?1@z$7UoZGxh^cM?WK zo-T|K_Ec{XrDK*q)2s+6w&2wYB$shLocWgTbPDIUO> zsdviA1BOSQef&s0p!@RdDHc*4O3Ng8^*rbD;Q8fVNY(z)y@<;V0+Iy$)vGp{A_ih*vJo*K* zlejnPnP1_2&8MnuM<$jOYYu4_d_OM3y?J7fm2b}&Gw^%`VKH#A6w$Y)rT*puOj28( z@~o)X4F<%#>y*Os3{Ue6kmVmYy#^(ygG1p6on>+@q?bxnZQ+W!7;i60qqU@-Sah zve&``*(UF+eZb#6f)FH!gm}2A4^{9@k~E8|UAle!@SjC(GyWDwCx-Bf!E^_FpWvQd zO>>*#7APtdRo2$dJT30n@r&ZlY&Vy`6Vl>2wnD+n9Lg38(^z;5fQq5hW2rnRnAwMJ z#pXO@4nRDs++rE&pXIa=Ur$eGubzS^Tb(3@u60%HAc%JzmWE#6!dfLb-wp|;=1d8d zDrjgD^8y<$zI{O7@QO|QX|&CgFK+d5N^_6ixgRiT;b0+CA=uG38@vHreXC7!d%}6# zl2?j%9SQim_9^pqzq1C%ZwMH``vXWKlCJA6=mXPS=7?wDZY^j+F?3BVTt!+{qNFCqVrsCH^v6g2$dHhT zy1s1ZC^DQdu``~xu<{c=qBfRyC;Qi_|4qd+IY_P5 zvEw48;#6wCM=pc(TK^f*hwsE7@9W+We5$ZA0&6))2`9)N+tc%bcmi^ao9bk?r`ql+ zgn<81?O}%*^l-7O9^MXJW`NA@(C;7gz8I^N*68UO`hM=5uCH(0m*wy8n!*4acmDSn z)XIZ~qD;Hdllf@MP?t1XwOc18& zDE*KPiyyA6Yq$WP)#Yz5S%r14tZz`=0@2M-kPfc)#iPHov01$% ziNCf55>(WLFxL!6y*I5zl~PE=f)Td-48ov`y+1sDr3>A307>L6u_%y7|LN2HyR2+m zZ}hfl8~@2>GYRtn$v)l^YF(?H zqx|tOoAHx*uCsP~vr00e@BP0A?fI$Y9S@0T19iwYZ!T*>@xyotV4|I=X~vlRS2_R=X!AETZV}}_SE?ZG z6V%?(8pdqlcxlKR+D5=1(fMK_t3jt37_suO|1wcgNmb5cm@M?Xpr>1{hRx$omOtbeHTjYXI-=Z9$S`OAI9ngEvw^o_z#*!_@9&3{*{V2y8KAWrI}h+F zVC?dx`o~Fhi9Gdkm2$G962n`PYx#2V(LLKm4LuI!LJXrFQag66o~5@dMuPi(^m-2{ z^ipn1Fb{6WM`2H*Y_ok_iYW<0 zw(qr9nYAoneo#%RJ}e%|+2e@^gIv$?m2SSwNCqH9naZL(c}#~h>s9^y53xb}KSTxX z|Mwas{&@dxiR};?A8fa@1Ic=Slp+x;q-8+2FO#`pI4b_J7UHvo4Qy4r^aZ6C$W<9N zIq8I_(A8kOU?U^;^6FB6l}CTSU*^=BGM36+mj}Fq(rp&=@0b=AK2HHSK_6_^obzk& z-ER>m)#a0l+~vayT05{GeogPw5iUQ%ukGG(d0r!n@w~m!>7)u7<)fPZlbZHxfKPQ= z%1r5r&djSg`64Zi34+%2(vpbqa%1}c$9gLeVHAU8I)wzY#CaG^CTWXAPS4VG<7rt6 zq=F##_)F-Vm11*w1@(s)B&)Ceyy8+{v1S5>d4gauf>EtKh>+D^n8K|t!VR2Rxxe4d z6doNtG4|;%sd#@_PKhAG7xer*&@^)?Qp$-=lZ$^258@>*ZQ`_F@cfut z@)Vt;`S;yIXP4}G9Q;LB3n*E#K!7-2#q>&R`dtMgslFDM@&6~Wa5&*P zy#Ln=046sYph#o#pyWiXzTi0TZti3-=Tqe60ryG_{-S;Iz&ULlq<@@VUjR=F;`<#C zjO3S3mL8$rj@93eASQsj0BY9|T{}gg5CqVA?X3-zzbwz+KRW6cil(yA{Q$+fTdi&= z@~83CsaD#^4-OE-!&~$anWt${exMPWIJaQKuK?yk);IP({ucrXD)%48;1v{kngAg# zogLg-+=|Co^_C0%&qZPm7GMCLL8yr>z}uM)fLp>hZ0|A}g%T+w&#yh`B`o@KDOj` z<0_Am3hlQfYL+Wh4hWPPFFEkIpIp-gJ!yFXg$Ef}3uzUI{x_EJ=y|7skqX)Xh_Z!i z_I_T2?;0`qkYI7NXuLB`OAFAeeFYt#nqQh`WR5}X%&JNns+#&xLGl>9ZLcl}BUnZv z>6VRuOq}POlqFQ&zr~?;ivB!YBCsKP}?0MMtQZ=&y-o~X`y=xZ`g`t1Qd?{!5S`>_NGXV?21^8{j@Zu$ylv+I&C<+DGT<7*PG_>q_uWscee zM2{@h`^3t3N}+BeiAHac36Ea{q~3kgj@L7NlaSS;nzs2d;XfySJip=0h&3|YO8Oq{m#dg8Az=iF8}7(7%Ot+1|G zZ|WC}Kc5?XGd1X!5L`_QBNx(VEnukqrbHvySb!k$eL^o0%>PKHhU2ifVRzFWN5U9w z(PPI3U(uV6KCG+Mz=$qRNtko@OL74**= zXHz{*SI%4A5T&05{60&fi$=Z!@^^a|88^0=BL1DVUXS{*+TK&h7q+gR)p-bKVYBH9 zO3tsb(Si)!t8?iwjpY;hAAe;7C*5v*K)>PR<>$>M-p;Rem9M4}MwbDsSz4uG2urSr zl<>P0UtCYMx`N|-2l~u?ueLS%3aOvYF|`a)moM8Dhk1(gn@DhA53+Q0b(vb$5U0(a zaNIaulGm13C+NTv+I$EkjqIF_(q;mJhy%%T4UF80Z#>QC4EbhcPkE3Q? z6nhoYW+^Wcvbmj6wK|%iqDJo1FB&oHPK9NW*hp0|-P0y!xhkV{9e3k8F`i<^W_eI# zQxVt{y{Ej+ad4bc0l65u8(jUz)G$OszZXYvzS={CYdf3Vc4<>5_k4tXxh$k=6EEdla-4i`j(wRL5LMn}0;g^d>H->t82R5tr z`3rHha8{@tT_+_q>rzh%*R|}!2ym-|bsh(fdjmXO3AMk-^GF&uWAXRACe~`NTU?-e zW|Y@T+pA(!+^$vwq|;nxTrhT+GG4-e7a3PQK1{LLb;%{D1=logFi*VHmhDs)3*-Jp zwCZOez-I&2yMHUaf6GwBT>zxKP!{??K{k$kSv^X0V&XFeJxYYP(Dc~l(fI1_A((}8 zrH^HD95?@rx&W;gY)k%hX=pHNR9d;FVkG0SoCr|c`N@h*I`^%+f_kTKW}WkiJh*Ir zkr!QVJ&JSKc$>Sa4Ua+625a6Eo+#QUs};;!9n`uE3zX;FD@fGpbUQYxviFZa3TbGB zM@s1_E28WO9HE8eo9eGp!69LFagK?ugqGDl1qlrSPw$3+72)Dx(F1C87N^h7Z=Y6HRwpcxBJ$LDx ziQl0GP6q=G3)PEILn&(=N1ry;4?||XaLSFZ$et2<+g}TG^6Xntb3p`?f@&#S(gXglJ_Mh5{4)3?G zl76AF&_%w~dv0na4P{)z=p}7j{cf@O-GS`)B#UoYc&wP}x^OTr(s`P)I7W53+dCr)sozMx`? z=AdMzR|~G5K_5ydxIs6!*c2^R-0y0Cr-Yh~WwVsrcB~KVRQIjKUvPybzhL#UaCM-du(e*(LDxdZ4}^J&$skh^noA$% z-Y6Eh!ag9le5bkec)y~2vLlWam~0N)ff>ju;;X3KC*05wvX>%FYL%0WNod_jGn=SC zCl#RO3O~r;fgX6-f60R;h6TtIa=uQOhPbySrvHM#gJ^p+cL@|viGKTSxww@16j0rT zf4wVQzNH_zcTms#ZUmp+i)Bz;iu~Pl`NwSH7*5fRM_;yH*njm}eiISOw*TBP&YfsT zhRb&kszTa_UY2UW;+?mNMs#CK-<%&m)%44!u8xb3NV`T*a=Q^@bM3zP(PflJWS-I0 z`6~P-VLn+d-Y0#)LF@KEwhDOFXx&_HK=M37F8b_rrJi@C?p%L^YdU$G#kDbB5M>#6?-I`2S0^)hqN>MrJr1StI#;Ps_j2p#J)>~As*mxWf7Z<0=8|m*)qMYku z*Z(^u%Kg%>wqBQzK7yP3D(YEjz&wKk>N4iSen!I!W%&;EoscOpx==cB~b!z;)f}v7cSp3?H(Q^%BiSzAIl^lvj}WYM*}Rei*(E0 zbCFOFx>HXuj^4$IwmE;3;C8Msx|5r-nsWl(&eCn~rF}7WNp0P+$c> z`IO)aW6J*EP3-XbdVr{$bF{>LLeNQX2D3S zV!#L54!eSj!&6oR!Z5dfhYVxLql&c2| zdeB+%9lq}7+@cs(hL0iy<`3fK8oyon>v3JD%-N2Wq(t*kdwGZAa4!V9R4(Zd)5ws# zS1%1lXgS42cGEq|cw%%Z%o#nEleM<=;*HI4)#c{4p7OzgiX_juaQ?Xx>cMvXcL_p# z2C&ipavwRf>lrLACJ_;&HfMO4tYy0prO$xR3r*&U z9!YO1x8r`>qZ8|kT=m7?_;uyFW#@DxdH1H4)pBZ$M^ALiQp~917-MAw(|l>bQj~R9 z*`>jms6%ND3B4DMTVPev9OO6@ZoP+Nz*aiW_x0P^$zGkeQRTY#qo9MhzTQs)jSXg; z3#fvhtoUPT;Uq1kTCSZ{f&zXmILDWa|Lc>B>KLENn6b4~7F>!ZQv*#04lp|=zkCCk zQ_0BAa2PggC7aL?-r3pe@jC@PXwp+w%4e2nepN3?RvjTW7JEWh5bWdQLN znzUyl;I*6P9MbV!Ajf9S1uir|*D@MbwY%3rE41Gn;RTFEL1L3UVQG}SKw57Eo~Va+6|prB(&XhRIYTw@H0r)Cgn<43NApB z^P)d@^na2w(wiD?F@4a*wvY9xRrk?T%gp(mG3k~4C-&o*(e1qrXY5NjjQlZaRZ5Jm zdD4BgM%+f_PRyP!!{03Q88OWt$Dm0Zr$()-p?7lA*lu0HArtwk;u4etL75g9ya!4Q z{Pmb>s^*rY@KdunZRo>Kg|O>4h|)>pvXI3f@=G82f~mIcO195SYIX2b%4iq3#U*up zgmH2FD~Kn4SV;&n`yze6E=GfmdR&4z*aFED(UVen-lSCZ`Z>iwg6KDU^FX)U;}6_h zzJknGF)!E$^fxB-S0OuVW3mLfEnzXDVNydf|7G3Izrii7RJhl{EEzHnv(f zws<9^V$TkK*-+W+K}CD6yq>Swrs{FTZGJEAG8r2KB8U!hufP33wcePp!{j8wCT4G% z;|`+Daj$tg5j(T!M?}J<{kSn{I~2=ed4pA-Wvh>cZig))gVnGv#OX9HHtWf-wgluy ztssic=!4I^o7g&3%#3;QV@u*Thl*y8&}}-8G3!0$l9eSSH~y$9Vt*#J%XvK<Iz;{b@;V*a>zT=XFbs$ez%2kiM5R>c z!%+FE8*Iaoy#johzSWk^*GZg+O5DMrlT+=_$EWjNvfl%jjHttoV6I00?Tb{VmF49^ z+m$XdQoSA=MsXRqUc~{hxdIbfT4i+%fK4i1s73s^x;D@%LQRJ>-79C-cNPfr(e!-R z4Ni;Z4O?a=-dI4Of>nx z5h^K`=Q@=mL^{HEVQ2VC$WoW$NiVAclX}^AAa4L>6F{8zmT!PNZ=#Dp8~h9S+Am^_ zeuCfw7$29j0PtmYTfZO4Qih@d%}g9p;5H#hIF~X!JY28&-^50|L2>yYnpIRyDdiq; zYO3?uy{>82nVqZ(zvY4%*o7pQWB~1be7bs;S%eT1Ng=_9#dzEU*(%kpVnZV7RCyVi zHtd}Pz{Mt<~jH~s4>I`*j!jQ!}RIE^|ur%16Z)$BL zWsA0Hzzq-{ueQ&*_vPQt2(|3!>)W=DeI^a0m0LGM0U>HTyo8>_P>HJtSW)rul8WF2 zXIG5b%6e1V<(P^%re?GlDd8gSaiJf_5Z41}y?=LijL&mXS#K zTL73hzgFc{+#Bu_5WIDBw;9;8j9Lu-PZ4$re*W1St6VH9X_~`zR!KL3ai->3q_=5I}b`90Ba8KYYPhF3Yrh z(7viZAA3tX!gRCjj_()6MdJ)>c>GUqn)I~YTfCr<+J2V!oHqifIc?>W)=>k@8XL|f zZdUKXc`6YMYh?!k{^BpI9f|l6yyx09+H_R53=%%67f?rSYHT` zeFZ#zwyeKJ($gki)Uc&R<&oO021R?7P}Q3m zwq*er;J>b3#@3^wd;hXjst8wk-oPeAMQ5MLk zMxCp@AZ-NJMo7bGi7dUt=5LBsrzQ0wynNsx&cyI}{RCA72xmaBQ!X|LtQsAB_Z5_v z0KHiAO!9kRU^K6zWkK90VPQ;$$N#IqSSHReZI~UJS?_er&N&eXB3UNf326bSKP@HGOht~WXhFvq~?49H`R zgc4p|LDt^)!0@9y`nQUN4SI8RA|Wn5zESXR;GSfqqw=w4>$0DiSY;SE2L2X9s%&P0 z5i}XVkAulth9<-NxyZfl%>F2tlyuuD&P7E5uPhV|6qlrMVC!u6Cm9B6pE?Vy$Hc^t z)o%2)^$CsefvL~@`W@c02^q;~mNcb$5V8MWCcS8qj=n;|#tHnBBK|yOsosE!1_S=q zQUl`6q{Y=#D1cTY3JR-ZqlvqWLc0z-`3Vv z=kNwhdFy|^ij9q}zrVk5OzS_0uA_+x6y^_Yk=4wY*QpUcmLq%|jh7zpliAO*l%jwdcsy(3d|hEBi;8iB?FzHM>111(iMo?)#61N{V~Tf~BRlj>~Gw>J=?qLA$+U z{a?okV;Zkw4E*il-&tW0pnTlQtA1WUFtZ4zx2w4gCpEJ`##a3jM1%~uDk-~-IWx0| z)?85$zuJIoqM4Ts)#ptyv#qvQ7*5^5S+lMunc@87?3Pf^JhUD-UA^#{r;5dQ0k zez()Tey!aZMpfqybb&Q3TmZy?2=(5i8`#;$#!A5E$7H0OPP^J+;o*dQPP+oC(YFyy z9AP)&JPMeDCKHnv@BZ=(Fi`M;X)Q)OO$CGAh`kgs*Tt2Gmv>-a1s;@nF#DWiRG|hX^}761GCr? zB@?zFe(`WBx2_sgE`b%;O32NP|MuX=0b{$6V8N@yA?TkZKWC`I-~PE!G{1AJLz}Ds zx=Za#00`?&o5$&52legH&$&_!#0e35_%8HrNbo5RFj{ zAprD3tMYyJdtJ(+f7VR|u9KMcdirs-RTO?z$?WyTGv=H1iQ04Zm=RY`^>I2#wL^o- z2&!i^$mTSP{?1IEC$hwpatW?RYJO9ZwKcFkZj;t22L4KY?{;5N|4%Qr-_dHr*a~x; z2||Z4NFH6BO8It2`d4@J2Vb)!+B zv#`V*o6roiWxu<7TV(jIq~zlu{+7F5AEDYnb#h=;CSbwT!^hUx=vDL(7JNHW?F?UT zyPMm|J|>{<(gsiMeiCMd6}q<*R6!x+&GXqqY;>k-f352=nG2Zbl>ZUlT%=4|Va8P!wUIP)bVf>!f<0u9vOBHzfTj1#nHrrP!ot?^>9`S>`JLWb)eS z)u+vn*uV^x*YbFHeNyzJ+e-n)>Tk$7O?aM%JL#RVcf9h!B<(|1uBeSPu`N9k;=hxU zl87VGm(girdSnnPB#c^AgYoP*DS7u0 zYY-EK1o}z)H0Y0XIZIcbQmm6-66A0s1`QcdR-3US1g{0W47GZSKIA<;|7L(y_igL2 z`+36>H`&Dr9bJXhQqskz=gvK6J-y_@#@#o{$2&?+MsD{%P{(yd8%e(8%=5Ho;_r&3 zWvx0q)fuM%hq>>_98CCgtK0QF%?&M3J{v!Hfd0ntBVZK+=Zr?yna~V_joK^v47&=K z)4@UHcTMDNPuKI5PWAgqEP1SO?Gx+U2XAmo%H7d$G7yHVuLvY+awf{D0$%!Iv?n}$ z_=qyfb{5U}HS)+WQMby9)kfypQ%c3p=9~&1TD?vBeeS|vW=tV$Qy?0GjO*~%*x5Us zizq5Dj_}|s^jc|=SxhboY1LF};$?cX(m-zca;tHk7+K3~gw_N!1=b^%>!9w12 z+4(c#5cBbNl$MJ9hQ$intJEN=Cw^~DRx6^oZQec_AQHGZnNvpcc)rBzhSurh*ogHk zH*>?S#VOwTcR9>z*&5B=I&wnY^F^pkUI|sE`~Dft6HauCST-x5VrC9)ypJWTq$ujD zO5`n+%?D^dP=KxI$0|FOH60Z1Wy+^js&gM0XK2};JeYhCwR*Pc@R)@KKn;WPD|W-g zH?x&RZS}wdqV}Z*(?7%ra9jW^g48E=H3Jm(;cWuG>ein^9ALeWtzaP}m$C@FIK5}N zb>r=0QC`_9U=e&+fvI*{?TevZOYb>l)et{rSp!RSk!fV_?^6l)JNQG1#kv!h!fn!Q zz0X3)pjw)#MqqYni`V9v!o677^4#TT;;%#?<@7(-AL^3HoSwNv&oX9=orA{q+W&Cv zP;Q5bzwBfW{)Qtn|7Y_{@~@rGhb4X!^D#|Sk%`^jzL94WbxcJ?FGD3=7_I8$+DFlZ zbH?_L4{jEH@DkpSorHE<;AsA|ZYLw%7Ye&Maf|`s1z!>oM{< z>g_)et{Y_nSR!9rJeHOIX%BtncCsE?gB_=gM=|=KDC9EwK6LG*VZo}vttYZ+m8`a0 za-YxAmztZ4?dE|rPhao5Zp^OPoJN6dwt7e#N)Q%b@BJHJ^yC=bk_IQ~SZ7Wr){j@!eNToN z1TJUvYHRo(vtj2d_i1fk(Q3>4O6}B5JkHZZ>CJT-EL4Z}!G|^usz|fh}<4 zv8knoB78N!(hC1hLi_xb))>Y6dv)%6+_WRj{=|H={G5J!8^#(6A@$mKO(Phs+_WeNmm0wB&S9bIO1hit*Po#(;3|*6?5B?Mg4R z{W}8a4ZfZaK#Z(6@+z<~{h+%|4+BuH_%3^~_DW(d&OB~*ZuXi=jP~k?ndWn}uIRvi zgI8Q{?0-0F=1@5u>voYycggSuI+|8cVWHsYIq%hDF76ODfDvk170;PIn31?nA_i(a+In-E-ecNAoAd}mNN z0p$9OrYLLM;+$b3?mX1WcI-*U;CYY6^yLIN@!4qZ_kFAqx~|vah~?BObd^$TeC}ZE zH?<4SvmT=)k2T&HI)CCSED3cmdV~i7RjC4A`#yon%9?j-u3N267?wVebHT!maG8zP zP`+?nN0UB8eHdRpvbRY|>~yNcKJ7N;=rj#|qEu&unlL2LoKc|O-W(3;c*Br1Tm;kb z)I3n*zgRaFuo)nXtDaZy)6g}@Xz($vh2>>!TanBu+{Pt61qOUp!9_Q>{vj_arjSGE z0owH+F_P2klg>C^f;ef+^0H@wPSzdFe<2h69;G=6nK)61o8?I(!(dZ+6{4cdW<$+t z0a7)ttkP*(5DEMB>kE{RD^D@O%8d2?&}4A1jgmW&XYO7RNHt7jVxkg%wGq$E=ue_n z@05vBOcz3EMyRL^E6wuRb%L{-(7eUa)oFB{h=B=+n>o#VVQO|(dPrOFT$!O=@Ulg4 zw^PPFjCZFtd~{S%z`lismYzPPsw$ebk4tZpp48QEjN>|f`;XPB+)((_*-wZKSS@~K zRM?}dioC?~EB8U^g!jSEZVZ=MOHv~n%IuoIK^eH$bTsFN-b-I`Nblt>9Clzixyhi7 z#TLlT*LV|-a_QV?IW30X=s-?78ThjNw!Li5DMY`_DpMTpif2sSEZ$V9noBd69fyWig1-eWcA6aTc zP2}~nHgub6)%&H_SA_MpBZxV-NhnbcEPjZ;=QXX4p>Mdz&e@&B7&q*EHh=r=#WXm_ z?l1>>3BmFpQGnby0W-bC(4e^&>*u`jL381AOl;Dn>suTcY$Qr$(zm}-dUI631sIXJ zqp_ijK3-wZ)tf6VhOMpf$B(VgU01L11E~?W=%!;J4V+&u70W?2V^~@*#oax;)sD1% zVlttIgSOlF4P{zWQ~J{@Aq?fQ{n@aE+c&v9>wzJ`WGFrnksEUVh4k7MU9eGd=qwrh6k zZ8ZM;_Mk7bAlTny(h`a$^*<^6M0xrpC%!?D!205FIRxZFUjhc$e)dhP>{gI28O%QS6+UjIgR9;OEOaa z>Rh-79W4M`A?>&&9t3XM)t$?0x^u0eboTVUJQ$8WMcC8RlJAp#9~ybAAGyS9MF=qu zh~>$eDhx*M*Ed?s3E~mJ_>NW$iR9~pmns{ataDRtshwbzfIKIHIcNHUISAInM5u4> z)x}HBNMi=yw3=9BotGNjk&w}`2FvXN{QBGJXIuKVxqe`njlHNox!IME&pLPCsS>`! z*&>(N-3F%K3KY7zwv{G8lHR-)7j{H6k}PVhMvU>f1VSSa*^MC%Bh1~kj9M>MeFWE) zxIbOp*GFr$RAV|q_u|N01x&YkFx}8)zkF#`P}2Bid*LT|sbdIEozF*SuUGsuRrQJc zWVos)o;R}U0N-YNkm{7vGKH2hB)Jyfp{_1cRtcRq(JhQ%3P#DuHG|SWC|Xz$V$I}) za1~sMOKmr9$ci5VC*1!HF`-%wormkuuXT`!k1oB;v3Ed zD>+&0WQqkrJ+zxleT*5hp|_NS?X*Okktu{Lv+~TaSwW#zr)+TEy8n-L|BndKKXp3> zdz=jtqL%rF|4<~%y_w5wle3Bh1SNb-A(FAZ7}Pm|fht;ZO@nbHWL72%zVWQwN+1jWeh-r{JHzmqZ2m1khE zJhercEfezKZ+^-QQ}ujoy;U}rjv;{%yt%Z|`cnpD{E{EjQsa@K|I%m{8=v!FfirY`Ob?NJ)^+1&pj%Kfud_x62 z!84=WW#0nLUfr>GSE+iV_xct+##dwElEmZRWppGAe>mbZXe&}HGoV-MkC2}=G3J~` z*L?e=bRLB?7B8|T7E$2bFRS;1YH!h5qEB{cSU(z@V?(z(yEygxl&~D2HQRJ$#Ws*w z=D$K-=Oe=u8^Fkzm~DobcbPkT&;ZeFWV~^HlBj%m|9VBQfjaNZ@aB>l?Q{icu5KOHB0D(^Q5M!vZGkTiVKQ7#RbR zc=(}zVPS0-zbOFn33iYc6RV1Y);P}&DnS*$+KV}XkV2ZCrb7mjC4R0+F~y7v>N8~ z7XDV&;*RGI`NmcR{1KAHtmf~2&ThM#_eqM*>IT(szby)4U>WKmeua$*c{>xmJN-vD z^eul8MzJrG{@@8gT15?(S$eqL3MlxXu#I!N*s4$|GsOdY=O{C99N&GEt4P1+6!(Of ze_R~F(U8HkmS+)V6vDTBkVn+~yfDNEcki$(THKM0dKj*o3s+yz3N z;(n=Be4ZL$UL0Rv)OEEysWkjeR1iP6W7OjNL~r|Hp-zjhP1zp%z2Uv}jV<{OIttsL zL~@?z&FD-&A|v6q1Y)jANoGNT5qJs)m16I{K54-Df+C^^FP@@34S_?E@s6+Q=_$!V zAZ>U`lFrPdb~MphoQpkViXJ9KtY@Pa_=7AZ?Qfc-^t)fs)2}UxJ5tYl?G2SWt_iW$ zPpkewPpC4{l2D@UXsDCeh@Iy^)2YOQDY1j_r8F~LCBEfqNElgIS)mI)1eLqZ=tauy zCw`{B#%x{S+592j4d2~rkNzaz+uPf16eKVcy;L>SdoFVs&h?ndRBNL~#k~Q{cSQb> ze!=JCn4>P$k}ZN`lt?YW86#8^-!?Jf>Ie>ETwN}77|l(+yT0&)>tR`Tw&`%8eK89O zp*|Oj=#1FQ9RH5P=b_}jEjn-N4nLE*?!I@}niK)0Fo6V2?Q3>}!^6U_u#>W~0zj3~ zx26}MkBf_0RMphDt>+tG{zJ`Dh&A^_vrbf4k%tJJzXoUT;qa9I{(UE7NJ36-Ku0zH z_9Z%oS(|&;7Z*JhYrWpDfptv<^IYX*6&7n-dSVjq*$WNcvK4K?Jm$h=#!+CDs z6^AwJ|I{Q22fta$3d=?JK@&^qL3FVg{ZNGRf%`Nf9ZHIdZ9iMMW>9dk_sOm7&F^fj zfSZ5y{4tDlkk|O!Tz~DZyH}|q<-$c(AK_<)xjrC#I}B?lQ)M9#fg;XlihrZ$xlO4lYvnU~2{rT>(=mc^t5S{Rt55ES=b` znlbbTm;_4=T}uyh-3}qduNuUu|D^mOUiSA6=3br|^uP5^e;X>45((S3bVgO12XA0V zMThYq3&dGZPsQqywzianZZrXaL8(a-@(VKGwhXn}zsg4U$uu#g7&1&@$0q!|wrsUBk@AvJqd>LArE$x6AO z(JLy$#`8)z58U+8gPz9-kn2czeMwo_)>pkIf?MV0K0u|Dgt5m}7y>xv;0Q%?7uA%F$)0knWJ~?oKIb0qGJD>F(|> zk?!v9mT&R>*Y_L_hXc=f*x&B#%$+-TXCu3P{n%Ujw{j?uKI$|Px zhJV(?>uJq#>&(M9mgkmwI%^8go8;WlkE5I?=BlBr9JqX(VS8B$+!D_}#i4&5G8F=R zev&_(M?^21wDd%v5bbdPs&Q$8GK&etOO^=1-!HV!51psjSQF{|Fq+2}r8%*r@DeFh zTJYNUM2vH%oSZ9o8Bl$p8q?;30~6W&Aoy!j_F~W-;`fypsbwNwIZYNQTh5fdf94wO zBq9H2a+!vXuh%c#dlyDuuv+-Pcleo)rd1VwD~|u57Kw1spu^H2L-VwD`Rx@hIh$W&HcnBwH?e|&kqF4`yboYEi#_~o)W6jt8ZQ8UjXPX6tR+f;stjaJHAZeWD&Xag_z5; z$*ih{Q%AvrEyanK!;S-^tN0dM2TVCAlTBsW;V&BKr)PwR5mD~W+ZoI z6H>-8?Y2n8#!;{X*f4P(>{3cFY|Mz?7!fG-Dg|;giJR`61#*wx0@c;k#;|+9nay4# zNW=8zMS?nHcE*3jJ%Hv>GcZ_BJoI?Es)n2~Z>3^GfkXrxRAm|iazG+*+#quRU;)rG z3L}hcLgQWM;VP%*;>hM4@!yc^#iZZ(jvoFjuf_I7-Pl&dM~*D4sG@kKyS{=vEu7St zJOH}R`?}2ExHoG*n_@5I{}?1`FGA^b*z&P#Loxm9ER!-Q@T48v&cdN`OiUu5;!_4a za~*~R!8zGp{A3hWj2D7J-Dc18dv$0qIg|vPgI28-KA0=o!TwB2yqty~0k<-_T#9UQ zt;08(%`QuFa$mIs>j>QMYp=-q9Fu#C zZ-=1m?&s7Bu&>?vOJop_QZ28}9(#v?i*PSrO;h~!`_JF(cf#ey%?Ow0JDf6K**Lm5 z80nE%MfWAHQZeqHu*yrnX#;cl;kl3f?NvcSVIcl65%fWmz&ht_A>BD|BvVsBp z%vqoCgWIw0cU+6rQZ}9SNXq4`Z8?R39nA;(NlzKgbDm`Mir=oi88;(to2iv8k^UHb zCQTXfgbXLwkzf92$+@T};QS3E<;%^~KpFxTmpfZtpHU81Lo3x$ATjx5Lhh4R_~_=^ zRP9n0I}U5vi|+dS!_mSu@_@Z6_!KyVm0sMEsLE7%Hzc_ z1HVl1vUtFH)#D+q_wI6CwOjyF0<7Cr`*xX+BO!;!zS~_t zcHUxBY-HB?&CRwzr;)Zm>+MnNxj^HUu1;+{hw)wApA^+!*C%Pb9=}a)?n0R@FDiWo zeH@-fGgfSh15+O}eKvw<668#SO*>;fk5%F8UEPQoK!5e&;>x-;B%M{_ks;!b(R{R2 z78|D#9(Cp_Ts3M)n(6sQJz0nvOI~kxPFsgMuLZhT=H03Io~R3+>|l}X;r{5;%$3Jd z9<@g4*v!c;#f(cFi+f_;&(_|edEe>CDqz!ZcI;bc-NkSjO20q(i+TUrKQj>s%KtF9 z9p#B!sBB}vgF7tc%iC$Na0*lz+lm25j$PX6*IJwKHid)ucd{pF=^BK$FHvOt42+Nh z)zsC*Iq}|(S`*iKi@`C<6>Ch-N&rj?AcaCueQ+bNBSsv<`>R7xcY1;ILY{|*XLta( zZ!Y%mLa1t+YZYxyHPOxd*`}0h^*&8k6qA~kE_NT}4oK~mC!PmaMfO2~d%7v@_>rfD z6C)zGLZ9!SFI!d4yAu%Ww=(|3*?fu}tju^aNuL*RU65@VQ1wCEIM`#b8_uG|2DbX{kEAjN3G0^mwb9*8KUY*kUtFq0NonqQ#koW&l1x@o_Zu{Wn_+ zjF+3|r+>B!n`UqA=y@z4yK!ezJ@4vM8{6Pcr(Ccx<_8B`Z!nWG+`q}vmA0Xzo^8T; zKaB;?UX;JpLSCtlDfQWB@zf29Q|r%B`g6mDH>aN}&uSZb(T#o5o?x@R$)URHxo&o) zeJ_8h;px{hp^yxEvroYuI@}KO`bQMmGwtaJU1P`a|(o>>%MUAgu8P>#7m9Ywo@uq5swb93K#%Wj$vv^ZOkumf$!;Whm>ZhA@$f zGZb{DrT(UczOH$yK)JHbClg9Q6zRB~OUG|-r%YA?M>)inxKCUZ>7)T~9?Y(yf>NJB z)_p_tEj}I!dN~0jACavy`n`_LvLl1Ah~e)Z%&0+*}B)!9VlAy1Wif^%F2-oE=I=OsNOT^h3cZWMWH zCx7s{z|IDP&5}5OFi&gDQ zQ_S*%M1jrE7uWq~YB4uX7gz{|@d;LPT|#~rw(>w5Cp)I<_BY@?U}>1G*tblKlKd>Q zk_CMm~tI_?*B z)@A3p>vo#!{jEF=4xU;QX0+@{GH9wh<~vbB;mxc=nN8GD%u0BT8%kDs86LuwjcQ05 zMO{#MitcR|T+Un3{@iu)p0?o5BonPW$ntYJW*CN5)xAr^+>EPvWp`EvQ9i97F;&-lUSqkM z*&S9tyZ?4-st2?;4{6qqH5n3S6PhTe4gfjn4r2-JXp932@%;m-_x0#gM^J0au-}x| zgV*}#%}5&PF?d_3mdd5(G<%Qb({7LNVZzcM zxuPD}1Xb%I?kK(6$;u1sEhXrW0tf3B?r@@bm1Qkd;UiLfMv3>x5G*tYK$L>TfBZzi zJ0s=rSlBd~iSS%0_~*sU2c}HD)&y0Viwk6AQh2&3%fw=(a%p*&n3z-)B> zp{=#ksUFGUV+AuWd^E|>Ku&z($U2ZjN0&Ogz`I&s92=+Rq@ke^I=#I3_XVcY6M3c!_fMw_EovRn>`khk!T0>XM^G6GzyDaXKSJ;c&+t4~kVzKr&vl|8t~)n6 zYHqL;Au$u{{&3sgJUDZEiNtAC61D$_C!zYl-&D zO1eH*7c1fi6oF5(9jGd)LT0<3^ndP3XB$c>-Pnr%oqm4lBgbLk_@Ic5m{e@lIrh#6 z1x`IWLtx7;TRB7K+gJri?m^J=7IEDh8N^4Q0o9k3=@NP>T;^J~xGt<#v0rzRdL-9r z?$n|zCMZKzX+K|0uAdS_?*lpQhT7cxJZ1c9H<@EFsbO6zIhLuI%Th1A%HdYLfOmq? zmGznoN8~C3`K!ajA2eHChabuMtK`;6FI)n@aB3Omyj-RkX}6_ZG|b`s!24S|PXJnV z%5<6&rkuZ_LEo@}Cc;>wx0+7_zOUs3V|%-!ULrGCZ>7_34wakfOm$G0}qZKZe`lO)~mC%eOQtiB^tj z46PrZk+oZ4aL04`A%z>~(!E(2>Ik?z3}iUe+lCL>x*lIgBJGAJG0?cEr9BC9yJg}% zOkM9vIPE~6$C%(;2=-w7(Y#eE-@pq?mzWbrUCrcimOU=oE82x%8eZ5knxkKJ3Q7c@Nv`#uc{;bU>@<^tn@4XveEi|wFf6)`{mX)! z(l34TrfZPq)ap4}j+;Vf<2_6NJ+>wCGZJuD6LwEbu3CWSI=8X{h}g2Ih~W1e`?7Vf zSvAqw!8o9(<+s!DR;k(++3{0CLx-Gh7LNR;Iwd0U=^j9qPr7U^i~DB^21?jChsav& zi@8!d$fXoCG$fUk<31~a6us|TcUp~lg8hDN?w;kpeFI28>xM@M^Z_BFj>#=RgM?$6 zWD$_2IJPv!X;N`Ak(SUaU1{Qw*4wG5LL;jVzvo>t*uUzo1x!rF+aLDH4%gM0N|7@Vt@8LCde+dF< zX~kGv#}2`r-Qhl*nIn5??vHHL62b7_Og6Xd2V>r*qDMK@4)^ryLy*wQ}x{2qYZNBCut2}wA2I>{xX#xS8`YKgRhMfCJN%kxrz5ddT3Ez|W=@8??jUfxjWDlWe7P+vA{X=rQ&R1`>M zq*w-`v~a#;M7@xypXA!iWOCh#*)A`)F1_fn&nqi}hCWCmO96vtHef$KCUZxB?b54^#TM=_{ z*4Vo-({GjX7)3$0ifur>9?2n*NU5`iHDvT zlYv4LPR_|Xoq}KMc?B}U&d*FkM25Ut?N%U+&bLzz-SxijIf~MXZR)xvL&DHuwb)d? z*TC~}-6ni!bdFG~L>r>0!Dde{e4dr*UOPc8AvHv z^7wwE`zr|^dWnksYzGgrwPmaYc;TcZHCilMgeSXakB7#k-L-DFcFNh@+|0_s!D2C0 zw5uKS*DD5mtb%gl%to(l_yM!6>y#&-gcsQj+yWkY4Bj?KVnBaEFtg9)6u{|$4RO@O zi>0h`rqXe#(xtD38@BqTcX*p!qxgX_^J_0S@ADgCvI)BuKWLbq&A0(7z<>!<-_3Y- z$yI8q%IaE)P3-J`yX68l5_&tuxaV5#dD!4)WB5EXGc#~&=z;V7s#etBfyuY)m%l;@ z&h^0kyQ71Z3$U8R*q*7@6(EbJmbDRsvltw3ZK;k+7SuJxU)Iwz1U`*FAd9Fla~z z?Y)y%fL8;RF+*|XeMdzP9kggNiv`GnxvS^h-4`PE1ow>Zq76j#ZB;Zho(a1i-kxpe zs24=Rg@-#h3i)$*A+~nfM3|s+?70FDPwa>=+Z+UR-TB$cNZR0Zrn?w1LRDOz5F+ZjO zTPd7J5O$&l9FGwZk-@pE{Yx7YSfKk?=f95Z1~Nh$xL9C{o{eck&%|&r*su^6BH6~( zRDzj{GJrjx0auc&G<$ie(P6p6KNUAm>yyB7uGx7TRE}{RG@QdhPbtD}XY(6XugS^> zng^tZoNHqE%jHgng3t$*5~1#K^=kLHmr2bp*{t%Jx1)=GQS4u-k)}ceR^vHT3j08! z`kz)^vlS@$1KDD6C7^min+6GMq5ml%d?8q*K+mE`A>>X)6T!3c0wxAXD2O&bZvjw+ z0OJN#!fMcmZ|3laCM_6hNh*`SEvqCa)_U#m@WS$h2rx#ljILQl;T&{W-ihp2^Aj}s z<$h5W%-$2@1~rS)MUm3Tvcp^@{-bV$D4_0B<>Vsl&h1x3dnA)52b2ZE)W&K4nR}p; zim|5U6W3$EO7OA9HXsDxw*(tiY{iYu8I+=JO z0-l)7zu0|xVw%P0%CbqD!MoL`uUrgi4Y;YT<|Z_hl=ghUYNJ;W9lob#)K@WQUVo_` z3}2Le2&{lt?zz|Kzh3qPrhrlCWFaFbh(LP-Y)E4Gk#+9wIr|mv1_d3EgPpoch1HMR zhQww4X@B!OEg{&X4D-Yk49bm~ChXeLQSOt1P|G5UZb|!#_Yof4HiPkg7AQ6Qgc0CE z8a<0=+;d1&7aS0(0(?$SfENWdQ;}oiA{BIhe^7MDp%+H!wsYf$BE2Ht$r%&g`?vNc zji+^DL@aR*>JjRt<9gg%gXTYr`=b9}^^B7-$@eW2BY~Ai!PiO4IB+5H*@LGfVWgif zIMCJbx_#w@TIQ+bQ<()eSm++*2*eXDV+w(ViojqjhArsZTWA)U#UsD{AR*z7;V$-8 z19c#w?HP~+2|=uNDFV4~eCe_{lhx4 z!sx*8=2jq5{+a6zuj^OKlnAih0MS1GWgj2X8~~mN`B83Npf19Vq(F*l)@B%m)J}EKx86H z+e3BAS&EINFui15gM3x5B|&4<>oDAPFCi;y^1+6IV>mrx(c0usDCUrf;dczUB~xo- zBPpcgknWpFoNe|3KL2*zftuzJE9YPyt;}6D<-%+$*;(&8z8B?W*cBf?%&@0H>X@1B zqP1>?5SS8~#d;M-{X8Bs6}VqVaPPfav?KSfC5VS$dz$^+X{UjP8$5Mg`(vTTHW=v2hR~pv(WSrCY3@dW34$l##2)X&d$yvPxeG)c+1toBO_6+j+bSD z)Z<^EWTWi#{t?65!JU`RJ@`0QO*$Dz22bxfR)WGa;Qb-rEL(Hb%7XNzV|u((dX@1d z3cSm_Ws^}kBLmTPgIYK-IP}bhV~ICSM3lvEQVDpr{DJ~zos{d1?ekfO(Hu^KAlFo1 zaP@Iu;DHl27Zm~A%EIHl`pl9{+pZxvyVpXJ(Q1JWg6~=F(ptXhxA~_t>?uf&(X`G> zQ5H9ziT>sQQLZftD)8XNnMk&sfHiPbReI}~|=8grs@o`G^~kO32mCGh{eRjy2JjjP6r7(n5~ zl`+9lrF-lO%Y*IWzrMb28-TZ-ar1D3(fFD%+aM4OCRpBC~b~s)nXUg z2&16^l+YSB-7sfrlGgqi0UHR51h^rPJ125%%5moUJISs@WJ-jEzg@HZ_6<9B@(Y}0 zoSyp0k*spbQk8wF?LUJZqwGp;9}qD`-l+|DKDoQ6FOD`RQ z3lU(Rv&1)-Vkr?%C@$sMr3pM|CMU&HWYZlgB9Z)JdC53J^q(4Di!a`BsK4D85t__a zu2`#M_cA1;~KvCeC#PVB#Jwc&9obO`D33E9b!5T>8{_)3%wg&UILYcHgX^)(0Mh z)8<&4H!W@Ac&-~8A1|?0A9ktTxd|h`2hU2Z==AP!yCZPnTWoNrJ_$(9yvT!FFC!nw zMhG9h)?4+^xJqzVbt|S?F%Xn3EG+!`tN-w6Bex!R^Bmx?6CZ6LJ&<>@<<-~4Yx~uC|o^IAV^h-*u%d(hM z?4>%y9PMAms$Wdxow~1XAiXJlV#a zrB-6xaPorZl?bUslo$DHr4$`B-0Dk)AL+T=54XZ;x$aGpS9cvZpOv4t6%M#Eh5#2U z%%~v&6d|5ply#>n-|@`hI!E?mVt%j)M98s?8{=1#Vl1U4A^K0I#J-RNvISgp*Jf@0 z$Gd%qhy3rps)$I#kKrqAuGtIQ_IBI5xfqdRr`OjQk=+!YR{rwR7EKf(na}F7)I~09 z-g+Vkte++)gZd1Oq>l@~n{4{HO6}b0oKJ+`7koiZpuI>D-(T)JC)h9cK}|S?DFkf; zWPkup>p#%34RIUj0vIu3-w?7rX?U0u zm54kwzGrJnd=S8$fi%D?AG)1&X-lS`^1G06o}t({LRB0-X#pMZg;3cmhM1grmeapliP zMwlZ19VhJ9G;wEq^!sG>Djc%k^Rf%+etb)^I^;cHj#ImZG#a2AolfkUGDfzXvyO!9 z38z*)!o;ah-@#|w71gj7`3v};s>Nh*L4?6t2szpDx_^Dg{@b#XI&$4k-@ny{4vU6b z{4c{CO=d*B^oj%A>MJZX0YDyrr$gI47+L&fx{#}Cw7dKvHV0Ac2`F#q@N#HguO0oQ zII=PoZ-_!m=Pp*UUT&TT(x%VjT@JVfyhKeX@c389#4McBj#B6R>C{Qx(p+v3WYp3a z{z|?)h@q~Aw#3Rgp?#)3=8rtllFGx1(lTH{`p_`4cYXK=>ocrY3P<^dw`E6hTx(9J zJ-JCuHVb0m{YQ6DyzToxaGs3%Y>p4>81MFa_xr8p4mN(y_+tj0@$NWx_4aAy zYW`@oT=n|>Qa)|#Y0ARsBn{VO&V(3wHO^xuyM{l|{Xt{l8~sbPMTixObtx{;5GpV-_aHV^Aqp`o{CRvrr)kdQhFO)mR6Ve zJYtSAaMDW_8l1Y^6{_FL0R03E&WjMBeex{F0h<~F#en$WVC82jZwb(bnw6i_E)hA* zcOdtEc`PMFR(zIFeGK2qm!W&!cdwMc%T%giq@=sYDawqlm1DcuubY{yK)|)UJ~s!_QvS}@L#TLDqEp> zS?v3(ps?_#{7F!%0={rLyt6ln!HRl?QZqL8J18g5mv-G`WRJY`9Xvc!*5hJTZS8O4 z6bZd}?{|NvapUCd{!yYZoPw0;4O<705&Q%UXn0f3fy4IxT~XPzP@7+R)S&kNAbkx?NEc(HV=M8UuZB1hOj8Ei5dw zvSqm#QGIRDMT*bhUf5PNCHy48zZ)x6rqiMB^SN2t~m(s;9%i*`qy}Q5YlMgfQJV{Q~jW{erl0n>N(&M zdhM1$N)8cJMN@(l*u(e1NzWZ_x`CH=$hHi`<_JDLcLS!H>ubB>!OmKZt0?aM3%rD0 zWcgAjx4PQwVPsY89FxR*D`MVY+vMKf zTQ`_6`gW}Jr1vmmEBtMwODjVs)P$dGr|@I|>YF9)(Peg{ii0ghabi!DHVu2cL77_~ zpSkh`eC+tFkUUZ{bpmz6oa$GW))ag8(P^9FiNdJ^@9*yP)mR8-Fs`c&SNeR9TD-H! zZ?gl{0>oci;{J=_-Z-(awB-G0I%2+&P1<2yco;0^1jeM z&h!h;we0X1MC8B%Qf9qavqw#3Wl;cg?FfHR0~VAEUH`c3HeVIo8^>)=C=;(e*E=V0 zw8A1aLT+%7tr&V8V49uiHruK3S)-z#>hsnJW9X2mLK$~on!Jd+2~Qf~aKPtXL$C)@ zjARMzdknhtb*t4s92itJVuQRJFY)m;$_u)@~^FO)UZ&Hx+C3dZ;PofTnzDHsx(<5LJk5Fk0*}ksV zdS)~4Z?xzOq$GzPdj_}d(VXi|CCZzDy#ksBXrOV>(ou9ePpm)&ni>}?{Mg?21#$fF z(aU&qr&a^?BxOwj#C_yh%5rl|KsKwod$_W`-oQ%;20slUs$_?<*@^A3`IGFO$X!Ou z$yF+e8g_^wDPurScD-S<1NRL;fi&q0wOp?35KyGt7+}BrWKq8=kHq%}WohS;Y~Dtr z1HJGiPxFN+dW*oA_g()h2(Eu?0UFxDPE|_p_%+%yErS|3-Dlw}Y3R3xwv4wp zSj!q3Q#jn+O=~pZg?iT3ezgAp85ux;boPJ;N-4Gn$Cv#4u%0EYWLGR5gP`_{>vU*P zy~NfrzCAZ5Hl)Ee2T#cpe5wJ&Wu9~=D2=fX#I1y0&00J-rWE{tRQ4ft-#j!;ZQ?3a zC+ATTZEGY1e-L_Kf`_bh{O%oIMJZYgf3j_=-BQ;fDQT=xKmq8tq7Q0cWS^DR&rcQN z3Lum>V6q^b8oEpuF33x@9BBkvZfPqZNe8KJ7ktjvu0~gQjNmBeomXv+-tyC6_`3G; zUj>*{z8mGwDrO*u$tyt|X?fFeCp~}TxtYWX{}e$q`>2|}+?*(djj1Q^OC6)dD~3#? zf~01-%gIM{*D-u?O&Aca6qjXYXgITTu$v=r)HbAU(0p;_$HxPW{|dHj#;#$3^L6rH zP~FE$O-Gj&!%>0J*$ET{+m`Gt9;<<=_{c)4*nWH-AV>dA9CC7xt+N4`(@eme{sU}s zL9hn;SSwHmdY|li)U`6PQZ?IGJ3s7}_sl~R`)`*H^sfRj?{kjWOFkmSwv`o$^&M~3 zOqO-vyttUGCKpjI;$%XtmZvv@a++oBW|as5wm$p2srclsXGVp&N8{0{@{3Pk^rBNJevT&GNm zZH}>je@hv>c4YnFEpRlgW0KkV{0i1kDR@A9pQ=I=Ra=G36*V@+G5ZJP%vBp3;dQw{5$y5s=bM9UFQRO3 zr|EoSc59SYN<<@~$(f{$?C*l{RdnI;LZ}E~qT|pDmfrOA3(jmz+mhiPfCmo8cD`V> zf?0>3;^1tYP@YIyLo$3S{Y{#y$f+KF+W( zyE)6EG`6rQaq>+dE4}`Dn+u3BrP|21vqg%*-5rtQt>EG~UgwL;&x0(6-sWHiyLV@K zrx&~Z+po~3rM{`1n#1J$1Fs-|5k;Wfre5434>>AJ>7wD%ms7Kywqk} z%vX8%iYiMsx93Y?gH#~4wQfG`{b9X%bFNggvUQMFwC&34mk zzTW=ke1?iUH<`!hF=}CKQj~W*!eC{&`OaIGtoiDLK-jP!&$3?%XSpds*zmx~&cxc# zw&8Z4LGkYF2BuLgei(Y~Oc@H#ulP@W{ji*{)k1TO4>)DFAv0O5WG~qSCm|)`XGv4Iu;4t~x!O@ei5X z--e$rDxGP|bswJ&(mXsdwvV!k>F$CTpy7_j^J0ww5G@GnQJ7z#RxN(re-X{4nC z=W(Yw>qfsNGmm793cZxWz(ooZiMe#^b*s5_g3hZL=>+H6)v8@A9y2OCMMfqGNPklQ za?fa^!5AZORP#5Bw+Sl?9$Gj8@A9Y#|4i~V|M82&<%jfMXJ?WGIu%X7odHJV&c9y{ znP`ZCBLmfvk(mMsj*+ghPsB5X`)%Xi#d zw9UFVn@paUi~lF5?B^nliPvel5Vmi)0x5fYZPUi%27{9YoVN#U$o-T|r3luKT#@mc zy%*MLdih%Hd0B9KO)322ZXXJzQ7BO;a(@}A%dtMub~0i!7DCHe}+{G z;_^9Z?)mq_bq-Nd%BJ<vH+B+CO4YLTqRiyRW)O?1c1U){A?r*;(%H4~FD@enW+r zOBns4=Him7LUFIK9vsvvD# znO8Pz8^w^I=*$}19=mS9$(kml67%ceJd+P6VBTC*hZGV5Mx0F|)I&TLWQSG# zsW?28;BC5(&3NEBgY|irt%{QJqFSXgfQjS^Oe{rv}03%E(C5sFM`4y-Qj%0~{{!9sO! zH?A>p6_v_=l7~1KTbKv&=)MY{-(8k|lEFlXYeOqast^gv6~OT6_<{rTEh zdoa#DGvL|?GER@4WX5lRaT~Q|`ae&Ycq`&~l8CTch*BzU<>=(3cRZ6=f;55rx~G~C zhqljSj)~DX(hsu9_3_eHv$)>26>rt?Qs^LgGw94dAXO$D;$})&Rd4v$*M-)b+;>?q zbu^KemN(*VIR_)JNlxV%!Wp<^C!yXUlxke=EL;_cn%Z+3jVVVhp5mye&~<<%(=?QR zTfS8Js^5}50b4n@c=49Wx>O@TR!M2Kv&H^_7mw~$TFUuqOo|u(Fyqkcl6t;Zf|aAe zDy_sR!X%FA{1KZ(sOT|DD{8RcUujNm8)4h=hqG>08YR$l4iRs#Hh=BBukamUOn8Bb ziTRZr0V@nPhJ5(i7H2D~$Glo7hFnQWX(!&UUJLvUNF0(rZt+G&>d{MEvg4CWd>-6P zKF<7?u@AZBmXyd`Lpr{DEd(s0eH+M2Dt07)@9(2A)m~icEzeaayUET&Lz0stOdrkX zzM|uSgLAyMxVkkY`FP$WnO9gbe>(K*Rr;q27!nAJEO}2Vh6c2W<&hpS^(GHm0+l)v zDWmM^C@P5#NaemyZz#V){la{ExscsFPPKT_3ciDFueN=qJGkPT|4=~QpzuzI$@_YYk*VUfJCyqijlVv3+X(JS15ZGE4T$BZp-+$Wcl)h@$3> z?}T>Sk4(C1(YIE&5KTJsv{YE)LcB?KsYA&f59JfNb?yE-r2j;!f3v0FP~W26o}owo zb|~mNr(zokOOC-FT*#LO!>ipE8}`k2m-XuyqnLV;uK}cP|5JJ@Ob?x4HGUc5W(E4! zWXKALBK9`DlywQlZBU#DPSEkj1=s^zme@_hi0m*W9ux5VtCok92#q=|`tXQ|%%&y+ zB&-viUSyVO@YnKkrhjkA#4r>-7c-__v-j!ayzbV-eDG#ea!ZQx;iPC0bC_x058L0k zuh}Wh9?lRTW?EQ&BnrbaKaCiWZ&mV<;3v+FHxYSL1g%`Qp3T0u;4I!$ExXVI1tIjoIce|O4Z0C!}O3m!AgG>GT-fY_}>MOd#azO})GOpJ#pGu~0 zJb~L``&7c3o_=aqXT|Oq5z$ZD%qiAQ@DfG?t(*v{dMF3+anT{OPT@A>P;`h`2ZsON z$B!5l;*V&X&H|+8D%?tA27Jr+=!Ay~7wBeuNGd2#CytW{0fwFPVe+kh>$u!QC?$** zA4$69hQW7wr-LrrFa7R14s~A&N;Pf~C1LpIi+enK&a##Y1uS*ZF(tYdc^*P&=yw-$ zSigy0d>`2r;Y|AWDbEC&OI%`tb+D)DO+6iVo~9V#pW6H(l1A~`RIWf`xIIT0%6$W$X-S~LMrMk;E%!dpLB&{nidv|Zm)bV5tqHs zo!##AfB8~eJjQrL3w^*(UET|9(@@)vES@B-lIe|4y%QzwI!Bh4U3UYLmU$&XJQ>q$ z(fxh5TEs}fM(tIULruaf*mfkI6WJ*Zwz@!`j+K| z=a!CNiU5jdD^VgIR5~{Vc~P6!ydSEu--X@x&G|L~ffo-FxDY%m1kn7KIE;7fE49Q> z<`r#7tx$iiQra*wpsckLEtXZ_ANG*iBq7NB+ahhCbuOV$OB0>Sn6ZhZ66n*8Nf?pI z!1+hbrdR&}nCI`QZ^?s#gfc6!WI_~#6ZhU{dU6B{nQAuGz4`F-3$61eEU~cUbZCbSXxM?1pVt|0?Z^>q6`` z)u_YC>KPucOfHJ(=dcjZWgFEBC3R@jK;i|NlcHwv^u<~MJ%8T+{V?O`-r1*e9K1zq z^@(wR7$+xwO}yCn@wl_n(EFgf#j#}pnhiu!?2sR8-aiGXXshPUyTR(8d58WSPaH6` zJznh$Wje656e(Pex{QmY+odhFGc57z6Px{>=WP5wqIS>ANXt zxgh4H)F+vpL7qxTV6n7$!WKdqy9iC@tFqA_I2qntcddhYP%EK~&)xsHx%npm`)zoa ziJj-fw0&)(uBATDnr9bpgS!KIZ=Unp1k!Lt&Em~X5W5{1LO1s1Z_J#QKTuF^UR~Nl z72b2lwAKu3Gfb(fKtX5>4nhtcb*lJ`d`j=jed1x}3Q2b*ur9e%S;8~%>6BALXcprkcJ;c7qg9xGDK|_x zEjv6^h2Y0cpqhwpTns(aC$u{P5kZR`{|G72@HF(Sr{H*gtEp~w@47P%J9R;YCf-rdyue+5PV5eu+9u_Nu$b7hD9szf^@{ z3^SD%RXrHLXwuM>*A*d8c}ljPCgF-hc=Pjy^XRxsEUA*CHx{b|5TMWw9oO?%n7`4R zGNaof#wy(hj`Lx2ty@jETyS92$kG@NLE^X9uCBwofWcH5tt0#PWE~T#lx`6Ue=z#) z)H!HKOO!y{+Y8nLN{W@TSwk|NpGC+(%As8`d*Yv-{<&;T6C8JSVjWb_mKSxl-W85#ObxvD9;V8RWlaZA;5vbVP zYK@~)-Q$xoeOZN>9q^wjY>|f$+c&=b;JVBcu>(R$;#4kwkW7e*&tK`j8eBY@-KRdt zY*9mAynSf7Af#(xc424FI=?V;YmG^{_y9h(+_p~caD(etZ#7USyK2E(QV_7F(s0%2G>?;OX99{eE}dg0Oe`^ z{vd?`si_|9$(W}OtBjpYRq(UBE9dk@^@34bg7v)RY1?jYgHG{nRfoiZ)x#l%$7)0h z{1r$9f%YaE77MBk=hrEQZaEBr02J>rY>UrJq`ZHn`Tux0mgSwm{lmRIAs3fx_1eM_ zJ@=X_c>kHPWgDCl<(DD0S+V6aoEHnZex7yWXy`!`Zpd+|k76tWh4JIcgX$W{_KwL2OrD1J=$Z_TpjzLt2#=bKZZ09dm^}J2|LsJ< zIg|kCL)F2t;QND|grCLV1C@B{Fzm>wVe|^tpOcx33dx)>`U~lgQkBm zT^GR*&whHLqyhCV>5k;Rm6uTtsYvm=EW)HzrKXwhs@i80x{6MF>ezPS)v}-W>aTl5 znQT7z__Pz{a6PBCLMKyq?$04&mQK<`$m>%#+pEs$g2k0RyXX~fLwkjm9$?623+q(2 z)P=B5V85NEM+bUDoUzhtK-(+CewPs9ojip3_51f{(ABXB7q6oiTnR07bD6JL_qG-L zqN7U|bcF-i1MrEiWtos;j(9G_yzfR6U?;+Gq;OBBQv953Ak&{-o+R}`PJ<=|@R!sO zahQUxq%JIB`a3r;y64bH{n(%2CMKa?8nwL~Zj0ppo^_!F@&Bx&GnMQjKrySNiz~LY^ z8EllKSB%xa?3?gHGRf0pva2U}3jur>Q_-}L1iQApxCSf3<5F4CO-91@?U?uijX8_$|gZ{3=7*R)?9m}@{_6-OuHcK+!7zHO-a&6YKcy^MtY zvDs!9h$*(SmStN$>E*K^xRcXUc6=u@P0j|&S|{K|8A%up+b!Z$a6B|~AiEyb|A^%M46 z$Ip4=PT`j?)%NW5Mo$=z_+8~(in~unty5l(BEO`%jy>rJ3$$PJ_w^Sh^Hq6zf%Y4_*|tPP9ehRpR$TZH9e4ts!onwBW#jj%8=Fp%LKZseL) zRnhk{dYc|1_VSvhcv&@`PM9@~{#8Kro%`wC{wesZbX+_rh+901;@}4t4GS7LUZMrh zz1RGP`@pnia6x204+kYW0xI?tw4`LFQTpZzbDMigRN^o zdK9W<=lc_9AE= zJh;c}`w9owpn|60DmqV_i7d_uDuKkJ8w8I!~ug&tvT{wMqikCEo7We2j zpC^BR-$9XF_(S-+1{}XA6!xT~9Kqy{Iywc{1AnKda|r(5Hnuo#^4H*&sN2#5{ePd{ zoEEo89zarx1En5btXaREhpxV?*Dgca_r$!op;$W55B$yY;~=TU6mto+m|yCEG|jX- z#smsQZf|ct7QqjzEdWN-pkdJFihhiw@KNR*xNP6`?fows^-k*d@89@k>bOes4EF^` zU!N3`35OE^QVLcqhFdiBA|9rtq&B*&JrK<#s2nXdXpu2I;_Efj@$fw_Zy&V-$3UHm z{)1NQOTd}wwtgHB|2TCyN%Q88kq+*BIHr*F9EeO*y|Mr1ZqgvMSV zM35Q>z`h@=9Zv-83I&Y|!F>-pvl@2e7-x8-ec!VAQ!*GgFZ{EjlC9g2u?sl7FlxtbKLiDUAscmAmzSjO z*B@22w@|8jw7v6v!3DHnXR$&)2HHFl^3|9bI-^InsA%jg>+^aH~g@Gs8N>nvc-lHyyohO|{zX7fDABtQH|QLpp_; z&$zYZcLmBeA>9aK)Uct7&SK8#TN(_npzJqedE6`pp8Fwr45G~)5-xdDJ}Prb%P8k^ zX)ibJehb%g8hgVxc&pjs zaXZsZzcey@k1G6uGR!C%Aa_uNnY$iBWRXe+kqNYzf9kV7HgrOP($EkOZyey^NRLHZ zZi$i)nwg;%>!$RPNza$*)vCjfzDJrz8x*XZS`DFR%M`RTCdIl})8M|+x3^d2h|io$ z)`~)zcwbNL%B6}ep@|JBPL}95bImr(R<+$U;WHC`fltJ#tVG~831lna06TikaNU&h zg&o|kt1PZ3%Mvz_#LrQX5S=I-4SN9O&FQK?$QTR*i|tWN)O(j_C@`RwMi051UvGzs zJAh8FsR%7eAWiPieB4T1!8He3Wy!v*>yt5eiJs*atfACb%ED~*S%ooLh9U^%gZjub zAQyBx3bLY){dqM1Ybsx7)%Q}QG{JwyN-2B#wYM~e2wRMNqo0?{uR5g@u23hfPpShn zEJKnd#eDRtI{9@_A-#R4Qyqr3fc5l?+k;VnKGY=~G$7ON+wm)%&#u^hZ5Pwvn%qZ4 zAkp-N!`szI&qY!A4Fl%0S=8U7IPUrrOu9`#GA^GV_BJEq61LcCr^9qmPGBkZ_d(Io z@o?d4vYPta;Lv}9BD1#kS@YEd%ysx!r1#}U2K1cnzkPSZ=+^G;IDyPC9G##?#C4(i zy}dlOO?m2fi@AdA02J}%7+e%&9505ytr}>nn5ba#hr3f97YWeC01w><`yP*Xu>b9-zF3cGHA_VF|Gvz zI`HPT zDgn4sKvT@uK|kn>ZZYl4ico!Vu6vJ(NtikYmGy7-d3Rqm$Tc;;4q3RlyuyuFa0TG8 zF&vBZjB4TC_(IsWjiMRn#cO}D--PUw2JReuhw8;z&(`7J{iOIf41+uM|9uC81Nd)UhR-n5Ah+d^tmUP$WU(j zG!89Dv}y#k>mJmuY=B>Q3#eko$Hgu=ei$wD+Q!kw7?>+}KE~SzB&Q@50bb>%NDcdy z#Wu_j(8k_yz0(K_57#X)`Fi|O)yk-e{+Wf}(&w3f@Weo8fKiz`jdtPhP_MGj?Uy8f zT4<_(+Lra+BO*o=m%TUi4=CS+^k#{TWxE&`VB2)piX&fLyiA)szhA7t{VAs zqLg!$FFv{3j?I=_q7W1)R@MeX?$P$};Cg266@Uil67xmp4}3)vdY7_HyUj))2jpF_ z{d@&A?YU=w$1xg<@@96V0U+_Pu#yA)Y#7mx;di@(_6A@|#Z$@b9dLO~_%mj;T+w#G^>n$QX=BQWd9hg!P`NZ@m^q+8^Cc!MM#K6PYSk@P^-wiWn87GFRWd-?iPC2PsvE90>+KV0bhCJ$l7#7>)BpOJnAGne z*H~L@Si?pf4GYA38(b%g@kDbvM-8GV8I4jYJM)YpvKPj_E1Cs8Utk}p4X+q@K4{`vgZXrFtB1} z@4mLNHL2A3{FyfNu}ueKH7P(_8!~Ql4Fb|EG`V9wtascs<1jv z=gH8h{y6psNEDJiS&C<`1T2x8l4T&XCkSv(JDY|1b46~n%$MC+T0=@sl;3cMh7^@^ zemiup-?)Dr?SFv3kkDnpON#(d-BGWUxKD`JI@L?yL+6k0(6RyO?T8n}h$BhlB{gGG z{?~9FLY+4Q`6AdYj)Kvj$0E9)9<@Yfv)1;zpPX-mIB_|g`-lNJmdE|j-OZo2X3URE zh#r>|{BV`IKk-=|Rp874C)zyoaBoMtEr=F?JwcT+c2!zwNC(}fVfk0GzUt|#h$;Bj zcJ*Ba*A+D(8ShVL8=#Xyj2CH6s~AQDcC+^f<#TuT=DA-%pa9hr)z6-!0_29)Ma0_n z7unHySt7M|o2kmsyL4Yc4v^)5@^L9_jo}Lu5Yu5vTnTMCr)^JF9#}~FZ(HY*H99$& zhn-^l>2PjhA{6iq0`V}_=|wecN+a7Rg}F5X3MRGP!TzLVQVN~|b6UlPBVX?0Vh!VT2TVn$;DzUGO$YhnjMCWN?&$ag#I4P!UjzB zYG976i;1_UDK$=l)SJ;z1s4vQAvh|sjw8Zja0I3#xFu-rfFh~Nu`s%jkjIWu4hyE1K zvl{mOedkCcH$4r`=eEs6PWrdJ2W-&V12m3@Wk#4#NQL@Uau!t;tI@}9#XAwIa0TA- z^A5PJYdydXV@h*{ijM%5`o(?HN=c)Pyk(#*^ec8c)@YQx9(B>gc*(P{T818rN}t2l zZcpKh^gqF$&=21JLlJ-F!_8883?5;p`61WP&~S5mTX2WBGrR*fHChxV0sSS3IBUS3 zpm^LpoATv2Mj~>-`{E@io-Lr$&3beC9C0GP;Hy{kW9O${xd6V}pMF}|bXWy0 zOt0$iVtF@m>cb^*B{{>q<3&7wb2Vp-prCUkn-mp|{`kyqfWe7x-$|=Y?v#6hk?CsR|q)s{JmS!p^D% zyq+*2=5UytW^K0h!5&aX*HsEK*_{C#p%Jp8!I}5#a8h3wQ=+;l+$5QhAdkIVXb*qd zElrl3Dg~cs8DC?JZ*S-M8j}RaI3nY**g9Jg|>%N3PU_ISUyTb1j~4C45o)@HD-v zM?E{oI1-* z?9YDO++|3S!Ty}aYhUAS-}FvJC~^L92M6n1l$u}!qxAKqsSVm#GRya5jn>P;LTfX& z0C@dZtbcp396&Z^_qYRJ(df*Kr&8N~>`uHv!3GKL&mPZl(3sfziWKdhRoW=yzk!D+ zT=^dKe7F$`b;Ixc2-wS-d5d;swt5U;0mGm?v>l~*{QQq=n|UR{iE;z-((CBD{t9vO z0Drgz0*#>r=I055=q4dS2OoneL<6n;y8e&GC?d9CMkp;-T9pfP{6)ArCXQX#TG2#a z;)8@TQ=s&KqUO{%z(36J?)!qk^Nj#+3-C-d3oh*Ls8HRBZA$=dpYrfjc)T`WbNqQJ z!rsIW*$h9+t*~L}w&70e(pFCWJUfCH0US@uJ%4B=l=Aaj!1wT^-{@lVZiZ))W!Y5c zj^0X9#T6QGjDDUByuw8h7Emqw9K!D z^vNmL^)CKZ#;xp)+fG7F$v!7HcS-9t#SN8FOcY8!$H-|j0x_GS;@@drvl7X-(f3jP z*^@7n{`lIHw~Q2jgAaM%t`qodh-j~>i;)L$cXOG2MNgW$)mBvvjEr<1XRAf_uRt7M zoWYDGIiqfT)sn=NW$`F3%rRzeYMKA8%X+-2iKs9gUT%deI1bXFiYLo*(uiCvST2SZ zv+GCpOHgq)?d5p*EJE_AOqLc8+7lwrj%C}gM?HNWl^cr&yqKu1JNH3_nXQ{P{;O=& zezvl;Rj-k(ud5pYK{wR4S42rXOmOnUfBx>)Lzt`!)a2>v_oXZ$u|2dDCzDg5hHL$9wWfC`={PA8TJ%hY z>)F_{--OkgSndc6Vpg5!fyrM_R;!_n@3b%CLkyCZ-mM>y7()+Te)^9###P855-O*JMJs4*(SNbzBzO7(8U+4=j zcrt)?*lAD#7=twE%$-?C zV~*sK^KLsZ1N!!bw#7}$6oT*k4wdQdJ)fVyaOB<& zW6i=J88w@A2mao$p9UZFUK;;h>h=%G$yZwb6rSE*eSla(rMw{X8yAZcJLsHW^uwW7 zO7G~6qjx&`gML9-YV_Rrd|-icb&9^{lGWrQRODjRR=skH%?-a^?3m~xNrSY>Wr;Z3 z5_5G?toE_@Z?Q;!PsTv$>b;i0``73|_qZ7j^5~xOi@v-6cka8DVF@j>%7D@>q?=v- zQ-9pXMO(>Wx4Wr*sOW#gaa}@&-Rz*&F)cEreObUgt7waawEc?|HT|PMlI6VDK1Z(v zXypxjfo%lRDXq?v{Z-n{ke3t`(dSh1_X#i@7{dTC`ZLl7a0tuc7pr>EHv`?;u5q`* zz^@VEBrslr11sWI?el%T!dTuN+nE5-LefcO#aBx*xBMhjAy9s5yOsbnZr}(#oJi@M z-aPG((cn3$-F!Z8&S|*~oUbgpKOj3I=!kalG#@*d-gi&CBS3yuGD`f#&Ayn!iRhUs zpV?5~eZVD=GoANg)`se#OoM~MU&y1UUQBSVBmte&1+AzMr(PX^58=MF@qCXbgfDB7I9S(AP>W%X35!*SY% zN~f{9!&{|+4}_!$y_+rv#?R?Q7DDt}+d=u^WP1&5uKaSQ^B-4a5%Br>`N*XBL|R;a zHRDexD6GKSHQI*tX_!y@E?}ROr(p46q^@_ys#>)4Tun*6Xp~ zb91Ga9|4l|9^hG)sq+A==lo#_0Cv~+?}y~YZ2p8_37WhamcG`%y26jizvrbWL@}Ok z>^F`j<6Uf0`2yt&sGI=V0wJ0JYaXcADTMEypp9NLRivyie#X-~e;(DG$l|y@JpW}d zqEH(dm`ru$gJ{i1fxlTTc4X6anQzM)*bNW=To4DO_PeSZvCsv^OR1~AG}K*ZNExmw z90&x76#2anNS-%rz|3u$ld|kF(J;Hy4(y)0z#3gK5NL?_%91|H!+{GK{L?d0)C_1& zfP694i!AtoQ8@V@AkV^`5*qR?g!b9~0}c!)fc62J&jC8n)bv+Bqp1eSB;Kdt$duL9 zuL_ZmqPn+HB=WN5_E?c<62w*z4nYWAX4Q}dGST%GrpRIg$Gr}ewk-mLScS{u;MQaiYi}k5)%o1YASH^ z=N#T=at`En_|*Hc4dyt`=Z=crl+A{cP8vjTF1y$s+RQnwQ6hW}7zaL*ccC{kbq~HX z%46X2HpAY(!)ovt6Ev9h5pft4j^4n0V+c83lLW{=^+3{K_1Q;?o2PzUPON1Zbw}*P zil&D>ehr5=#~yc=8;G_nb-6wP#eT;zL;tYe{EYVEFkMW!S5OxQI@&Xp&8`s;rHVeg?c=_ zr|(vm9aY_z!P{T{sRumr-?kN8&wzYVhn%@!2}Gf=F>BXOXqW(bp|4YkmputpxXoZx z#I`TfkSud*AqlHxjvj=2RYDWp(qbc*5Q8Tzi^($Qi-MYA(^6^?JKR)@a5>a-bFlF1 zbO8_B?*}&LMZ)w?kw&bPIv;w}rVi%|(3g65SSed2Xl4*e5)}6n?4UBZ*7dEuG0?8u zL4v5GVnKo2_J9KGKQ4}qZ@U^~G>| z!oITpt?X5(i-4Yk!t&OJ7YEOIyX99t{89gUO47w!rMa_7Tc^Q1%AEaW)Wb5btBql9 z%)h%r7gwvFRuSEl-PL!;1d3>Gqd8mLzha+P#|DVW2G!G?p~Vi zt@OBb)izR`CnWCxPN|(#wh%IbRxO2w5!{G@=ZW*F&F@aga=qFTM~zfIaK15aNG z>M(`WUD8M+WC=;#IyjvSsP&NZR56um6(cU+@{q?13NTN!rK*Z~t!lzr0rcs8_yhys)FkDA+p ziu5))ADPN|#S71yKebPG|DI{hc^_E#?9FhHT_Rlg<9ncIi#0?oH|z+2-8@Ah7mH_9 zH@8WY9oMk(?CoLE;Nd1q0byqkdn|{m3nib8`o&K7=4(TrYjwU%35-U26nVUxQ*0w&crIW{9bmhiR@Ny*Oyo;AyBsd7IK91_0Z%p68YVVq_ z)BL;g%qK66tD|oIB{6_POH^$!AhJ)o?vm@4fIug4SQ8DBUx^zF++I2)cdL|Z z8S3ilHH&+lpgbv>S3b@k1DA@Jr+HhS&ZR*GefGgz zFJq_f>9Ku;Db9wC% zeo>9xT3P1itR)LF2L9?~-hP+fiXT=KEgmJ?J)*Dw`v7&}PQV9&uK&aH*uw61<@O?~ z;}fD^GVXJQu3>rDr(^F!5rIY2x3H4-iZxrusYK{MEFvRA>K`WOut!ghaq$mVYdk%@1u7v8dE!|^_26qMbDh!NVEh`oZ_$gN{vQ(ZLz9WhINmmrQbv&wiEbVZ&fj0 z$4Qu%b6ADewvNThbY>gRxQ<59|3N@`&_^sI zT8FtVcyQmP^cFnIVaGD(Cf{b1!tZ497)I_#C`5TfpL%(G?I;`kR9Au3;qK5vLl^;Rx_H;zj%dY^Qoeb# zcs+o6IAKgFb?)Erfpo!B=+5laro^a`q=FkyWP3tVCoy4j$j5N)v=~#xF z1yV3$hh`GH@~;BpvgSpHaTCfKS}T62 z1Y?D`^TRK9Gk2fPGh~Fh{@S{iQ~XPVQ)SYnr^7xs>V5D9y0fOw2hpS|ROH&5Z$;t9 zU<%~o+NbOn&!|;dYTvUN&{7$eKbbR$Gs8KZC_xFy8k1qwTO8X4Q{GghzFX=zAv;VY?Nb$;YC{!$7^q)Kr|1whG@M-eaE<}I^Nk!r7Y>5|D zd&w+(95kwTGu|a%b+n#~lSX7_L%vc*c`c@-sTa2K4@UfE-}Ymp;x6M)2S$F)_uj2K zCtU>-VaWo8*Nko%-)hUUHyez4 zcqu>Jw-pWPZuX_eUHtpl!DuFA=kJOwf87}+qGOU&)gA?cPFQyLoZ@;Yzk}h# zhY3;&sdIBmas4;!XJj=L?~K)juIU^Q(23}3>bnzmCo3lO=P{H%Hx?yLf{O>Iq=@n2 zWKaDEVae_+6eUg9T+<#$IJ-B)kDc9vw?%93-^8%3%FTIy9dY%+bojeQ7zN6!bh}q` zh!J;0XxQz=is4k2^+f5#xN@qMKUfvBp}ifhhWq8}4u|wx;ooAX)4fIUVOn(Ge?z7G z*S%uGIBeOZPSbNqf)=_y9ts8zGkY5OwSj*&ET}y&g~Vs4sQ6FCy?6k$%S)@XHHw+dJR@T;&Oz!XJ1Z1z%^D;UhE zpqUW$Jo(vJ_}yTt1l=ueihV;n*Xff*RmLk-hFKz5GsP2mCdP9{6$Y6-9-Jm^g#vX3Vj4H!}tB&86)ZOJi4g=OZ zhvJEGw`>=Sb~@Y8Z4uz#{cCqZUizNo+tb=NBdG(s`lSM+(?rB)eJ=;3QG^_a_|P5q z@{J{S$4K%k#P{@nBNF_tAwQKBpYI&CCTm+-z($c->h^CvF8a{VKA?9jB9QcFzgZF@?)iqW+cz26v!) zXVYvufJqUz470Y-1PUt3kWvI6b^0k=|wD?p|0)5GH1IDaSFlr4ny-wojeP5?H10{hyV8ml) z#_GM&${lC@q`1RD1k{v6HBL%PeM*y9TUj^;u={y1yv&9n3mEV<1T;_vtgzSi_&zb^ ztbYUoFmQW2)@U+Ipl~Vx%zW2|ye(gs=m_HcL{!m|6Fk2c+9>yIy)6i3Tmj=7x)EP| z8>35W>pAIvP4JW<5>()N^sQL)lgVgnPodDHBiC|-wwufZ-rw7HJ{4SS*kAE*;4>Rs zr*Dm;v~<)Q zBtXLkt$g~iS|KBMf`B8pNVL8%ItQIR3Y7WewBJ9H*Ed-ws6)OsPRB3Yxn%{0jkYdHa&Ud3~2#YB6;NJfcJ%5 zTqB%ZKSd)k_(i{#W<8_hd`2cut2o6+DypY2cMwTXS3js?_jKIW5N#W~FSlyBd}bt} zSt;)dSK1A4O4GpB-AIFvOBB)YOm&)-|2??0ELAg#rw{P=4OJU9u$wSko^UMIZd@#_ zstNr+!sW3%1HKx+a{KZj%9=327PyH1={p7moo)F;e5dkb_ z;b*K}^reKmaRGwpKL%p)l++6u8yE#5u8F(=BTD{Ldy1M--s8P9a!&HcvI_=@>=$dA z6V4^EEw9-$AW;=5TMT%5ojg#2{VV#@Z#n%zzP{IQV1C4 zwU}`wJl3G+8G2@{YkrOF_$dVak$+alck6pnH+^h@cFy~4%Tv|L;?&ZjrfY+lF`VV4 zkb9-=^YzkP0fPCBKycSP5O--4_nW=Q!DdiMj(gStS2DXF?CWVJn%&@jacZf@;$Ba{ zE+|)YWFZOZFFO+k!2Z8g>A&8&R8u)&IyvD+6)Ga8m*=%A(MPYEjE3M0-r;XzT{8E3 zbr98K=!Y5$X;-S=Y_i*&QD^-r?m7Y5;6_m+6ia!%v|jjR{G)WaKwQ@?x(n7;wKS>| z=$G%CX+Y*V0-IQhYtPex?_dUAMO}EFfnPbo5J3!V-2(30qbJ`LY#u9$ z$O+HKl{2-S-k&ECqfmNE`N}>D?p>MPBV+b&ty4sD7j=U{uvwN1Fr|;Zr%PV>5f7*k-V)pP^=pj%&+YVyYYlRD>4GO@-HlSBuGVvcsF|fcsY%)YGuTKYIn{74AJl zI^13yl8v7R>exD+Ql9vi5WSxStUc9nvX$%4XeczNtI_2B)09RdPgn+XKK#l>Z?zD2 zzRX5-dN=iVaBJnhf??u)?v*MiCM>bw zGW+MC*FV(~?hMg`r(Q>5*W6nd_V?4fagt?SvxeM=7i%4}(wRAU2}wIS6|~fa2|R7O z!rpzim$P8?kgizz@)5;YiT3cimw#o;T9{Kfq|{RBzS{!PNI_2C)zo1&G*P%b^6+`R zilHFecphgs+0XM{1P7U%k~LZ?1g-4|SwMTsYgobuZovUq!HeAyYiaV*qZJ)_VFH)D zGGH+>DA5y8hm&QAJ5U1R&x-Ly<~IMYs*W#E0lcW%S@5BQUczLk6TeIs%A~<6o)7$x zH&HTN*j*qBrEBDf+$)47C11m5b~Hbva4XSdz3G2dsBN_TOQV)Y!HKsoBl&TlBJzgg z!i?PNh(6XS1&g$!X1E8N?k1blQ{33^JA>HW6(WSJb$%W__*tiklYq z-a8y0QA#7fOLN^H%fVQp>-&JJ567Ym8(yM(>!WIxdEb7z?kW?%MUegaW*2RtTj=TqZL~>R!rJ_$N*Z&Y<6%3v!<=E zMv`;de&4XPgSI3Fm=`0Mn&`n1OjT;Phi~r(pNWfqSyYYIBU9Z7rajrVjgZlE8w^8x zG!U9ake0GS_IghN%L!A@BqExuPLHi$ZCwhQypkFitlbYD<33X`k(BJUa+Ulv*}x`U zg{k;%UM_&Jzu2&Ag*bA8r~c8AALrKiq|KP374*6L-{Q39+!J%xw5s*0T-b1YaP`-I zufSynV5tFH1gu&{fg^rwEO>Nu^pXOz-C!K7*l5`}&dSPqRgJM2hvDMK;bQ#XEIY8X z48>MP>cP}_z9Es;Khh2iR$x{@SK}o!#+FkVS%I##I~*XS#1{WB2B3|YW*m6LKJb5s}5-61dn5fm6Vn!j0MgfvP&Mgq5%-U`GyX? z59c4UN%L{Vwlg3XvU-=}XD>`LF-aTm=5#_-8lgiP<+pE)nzKb;Wfu#E9F%!rU|le~ zAbWn<0Zz`hV15XgYC>bW#UWtW7hpT<$-QTk?AYs(p$Dvv!f5tAmx`Kuk<^KLW~1Bv zAM1bjFapCM63I@kW};LHG&_Eh?6nhwWKf=J@=-8~ueBk4EjvtG{m(D`2jYwcZc@}> z;8ir=sYBOr)a2I-%d#{D9ghzdR=M*-c{z7 zR@FwQZVUt}*NyxQKQ?ov?IW4_4bPpeghvUocQXAR2VJ1fO|1;Zv?^pYGrAcRN zCv`e5NEBdkwlvsl0?@;UqKyfdq8xOX0%c_QABBe)4kU-A3k zuddRdY%~#(w}pdk1$JI~gyf)u0tfBHa3DqJ1qNk#ePl2r&<7$v13>`-Nt%dsW8*th zQnEt(7Wp$f7|hW|p6p9# zEH&F8z#rgq6gU<{B1dV7s?)q4grhN_NU}Pq`V_X<8OuOv(%7Z(C-Hbr`-($_;n?}~ z(5;9b8E8%orXDmI=l*ZD71PGk2`6D9AFUwB{O+ku9m`f-WLwSx@!(LzWWf4&x;$GW z)971E2I`F|@j24%og(e}CHF|10tC z!0!!0Bg7!Z{b_2)&&}sR-TA>t8KmtCB<$rXox_MoCLb~EwxQpUg=O6jrd!r_&&XPG za@v85*Ucp!7wnS}=HiF}$QkI}y|rr9+EY+%(Qz1qb0nKi5&IpR1hutV0+GhPKFCHE zl6T0TQB-Kat%;F8h87sn@l+LK0yj#|02f7DL7rDaI`bj}Tbje}|m=2g|Ma_JMqtO3~ags-foy+9oX$NQHj_sfHiT-G&s5}xX zA2-R@NuPtYQ{xy!qx_MtOsr0wLsN7glp3^Hg!TnF;m=4yud`irutc=0XLe{4+1Gzg zI>)nCi)aRL29pO zgOFBs*+8O=F*I}T*A%^&54$usoz{A%tVpZc5MPnYeFYSvrU!X~L^p1fb^#;(Y?{{>ViYEJD&uX^Ip}SI1np#9I}vbFX|rOJp~rXZ1yiN@r^sZ zzy^q@NI1E~rX~(tr&w1T+c+u$4uG@;!vrXwW$b9}*`L1?#vu_4n!@{vJEa7K%VjV} zkWGf(8e2uid2%TA-xd@0mw%OtnA9sM7MV0G36Gx=CM+0VI$l zn3^QPjPk6;aL%~E*8C!{TQ;C}Rvd|rCdX|eYgcRU3T`D#c_qJUDBHdq@%;ZzTG5&D zL%x)|yL;e=-;%-UTRYzKm+Bx{rYzej*gxor zD6J1wX?cfE*_{*?4uMcI!a7Lu72f}dtv?+fz(^;fYzG_BoMXnKFD1bauCE4Xg8AqQ zge)!EwuBFQp5#L}jr-ug|2Xzh7x5eSZM>%X_@r_w7YuAA%*WW&llw-56rNJ!_{jQ; z0h`WOT$>3~8>~khsY<3`>fhp;8kC_QS#>0UiK-IPO7#Z&>}={qs=J>$i$$*3GD5+O zcw~%3W79Y_;S*agU+V}X=Q~}^9&`BTLJHIJCab-w)Eb*tx(1f;Oaqpx%Jd#(31C$$ zAYKKkp7es@>DAVgfT~9tWxy$DG@j%oGVozL+e(hQVA6~D$+ymXETSw>=5wv*9kedB zhQ6KXnAQR0;fS+9K=~f{6j@&1Y>54JPodLLR8(wPb8fXUA58cs8`oZZp?v~|%g~9~ zQV+6-kKiz0`=;=g|CC9W$r6KFTt9!MIZv8DPw5cxz})MzdVXE*y!P4?!-a7{?Rq?8 z@jw>r?P*(n+4Zzds>w*oT?2S5XN!vokh{0Gwt@un^Ycf6xz2L5VEq!zCS<^h+rP=m z;#AKf5JX0RpbD^(A^9LE5e7$afEq!gR&I!GUrrY1cU8y z%;ZXQyJrx{_O5wN>sr^~ekdBk)ftMLocyt&>70+7I5MDGTYGh$hsWc+*+aLX)JjcO z$IqKiUZAck%V!Fty=ELDeYHW^w1TFQlt7g>$aFTh1*|LAK2~R!hn1kC`6~{2cXrJY zH@H&0x|(-|Gwb=zo^@gOczItk9IeaQ`%QEItcMUe~eQf*bxoKZa~Ht)9ON z*jm6_COwnR7)y14l?~M@vJ&2~kZA7Gxfz3ddaiqKVnQ0l>NK@SULiZR25Z7s)e!8k zI7da6cDYMe%60UY42CKJy!p0#iSo|h`c&Je$2+R zdWCr|P8PITBa4HdhKe2LT#Scp#)`HTe0#)ig;liwM*701#Oo;^XxwiE&3;Ini3=Xn z_NLJQT?N*7rnhzt>`ubhyOp}h-L8)cAYd!=vU9D9x_XYV(KaIgwKl_dje-ci-#hj{ zt-OsjuQgS-c$+gJQRwIhs(NyBnH)94nz|BxE;}{tkM?)vZZ8Sy4^=IW`WNo(( z8ZU}%7O2HhVnWqUc}eSnT5Cp17Hm50;cy*8tw)fHz2$bN3FvPX^@ra-mFfiYW+*=~ z;CyN`v04UPDvq>4KUh9tdT|Gq6zF-k?8y)l6O_Hk!DP@*N-)uhJ$Rfo5i^qtuafm4r4lCAP82%28qb4;6C}Tv zA5N9%hZq@KA2_&Ik?_1yDQgHWHv`qS^u56bL+jBEa_)+&_Dk$)8Ef%GRlAorYIwp z;4LrrHwCf>ygmJpu4r(~$<^KHb~z`?lL)^47!wPD1|w1O>L1G4`A%sJd94wY6c?!# zb;hgk5C$#Qc)J_azkxWle)+Mm6=ED4?>n9%B$Pwtt*O};ASL|nr@MPj>#|(U8v}iH zO&+L=CH=N(Lef^3DrIqD1+K{QORx6jkl7DEvsMI4i_5y!gHct%=_wc*%GkCo)Oho~ zFEfbf@9Rf=3Ji?jbDAi%?u6?=%fFLLrYe6M4hPrbb+pV}t-t>-I6vGJDL@GO!=uJ$ zKVL1VX@{dLync=}?Q{6{mq0}MxNRdL35Ka)zCwTB5~fT>f1%zp+wLP->SxBy;3C_V zluGLxQzq)LFft3nO(&8EbNrff1?ipcR?f|fHolw*U_C$H2$_n?>wDd@Dz8&pOh+;0 z20o)e#3IVp*VC&S!v3ux`HvHGqezuT8KW++!3|RV0H*#U9bWqTjL@fh^UnDG3*2$r zbmX4bvkS=*A-OY;RVTo4CGfRO>(j~VOdYniQ0Hx222J9s=o5BaQbj&+!_5#u>Zk^n} zUV!`W^6;V#F>$Z5RHD=eAvGi{c?g9)Lg>9E*4EkcXefFF?&CFss`2GD$47sg=_C?0 z>F7N6tHvOZ+4}kfY{m&u>H*yCQmtKsTFyGQ)&2R`nd?ckyPG?t@W$!d}=-kW`mlT^GP~+@$eu!HemWop1pyjK*gF{0nB9$~}r!-7U!9fC+ zp_Xu^&iv@AHuL*Ki(sTXIoiFm?edOrQcjV4a2qgi6EBfJ>n$Kr`)EG7170=)yd>RA z1-_xWZ5!|o9(3qLxO8FyAksMd);T#wDLrXjRx2NIg zzoN(HMgv78d-a3psfQYCb7*olI_ipwHV=$oMC%-E514)qpQJ)MLYGZ15C2bDUjY?m z(}ultNQX2iN=S>eG%JX-beDuQ(%k}5N=m~bwR9uh2uOFA)FLe*A^+g}ec%6{|KGD` z4~Mh+JoC)lab4HkGxNbPb`8F)s;#M??tzB*_6-v(+kQB}?JPv&ETrEPcjs^P{iKy_ zQi*0b`1q!8-aMWke+d2uV|!g!ga%vPQ7hw5VFicPF4*x?QcXsIz==CC-)AKR3Emu&tZ&!=V7=XF_u9rzR(bhNNhp)zpkDky$Z8xbD5mv+C6_SS1wt-aFPjqjihN`^@QCEiJ8j5ib0L=s~YZ;i8$&3GwvBX#QK5m)vk_k`m=fI&p#kZTN2E(oPo$0gl4~ zC=U1Un@>oqM>1^2^$C^~!8j7-dsgzX1Q-sFea7*%N~UV%?!yjMh-C^tekwjqe}RdozWQW=^#iyk zvHDrj{I*?T(Lg{dI3WT9O?9-^$JxA790H5$kB8o#vPDV;2 z<|ZbB!9R*i2~*#i&A&;pytmv}AgUgk94D)7&3jh$xd>D3#r$&bJ*#*hmTQ&X_QO72pH!=VIL;^^tklkO627CYkAGEDXE-yhaTu zl@*mLl23hL(S&T{hUR2zvSrN`>NKhooG45TRe!A_*0re(UJu)Ct*E^}e15u$5sF7c z#ng93KeI@vd!Xt=qlz|is!=qC@VM(L7x`+A(zB-O_AfJhv($AQ`q(R4A$Lg?q{-yt zv})VH7ax-ljyjs^r20Xsrwat^DRDKlni!$L;~eK%CbLt-4Jepu_X}r0+JAiA7I>CM zq>lp0Ia3#-rFWjth&3OR*1f4Z_Eb)fyQC}_mW_-49W4A+Yw9#n4IB$}`?cN#+D1otbE$Lm>?t5kea!nC${ zNC}TWh@VoXqD;?3ILZtYnx*PzKM=m5b;oFWC7y4K0x$LC**&dq-wA%iiBFc8xYoD7 zucH20{F)LDqVhWY=Uuj3FJi?OJKao`l@i@MJJn#_UudO+tiiXT$_Z>=RECSbTXvo8 z@7G(&oC?>>qvT8nPNGMx2^DrSI;Ij`bRj=DN>i#4ftU#sek<&q-e)S^13`*MUBd+Q z@I`yJlx(kxeHm`-RN+KCTn3%KOO3eq?q~5+M|o8L7*LA2+Fpl_IP^GG|TrT1xofP6U+98nqEcphcZ+hd#NEC8^6iP8&hJ z=o^w17DZI}Tb8rKdta2p(@kNHAQEQxWy~Xt>O}~Y;S=4wW2fim1AmXxgQcmZn=j(s zxlwX)VWI5X{05JcO}1gi{vGF@k}W~i&T(8SKFDY7lT_LED)$pT-M6_J>u|gKZI^eN#wV-WYZhDR%U4YT7b*`y+U5D{Cb2&WbX7L|;FQ&5#hp%<$jQR?U zE_8Vq>S&->wfjFmKcK65UtHU-A~FmDs$)Q!wUKz?m&wIr>4M0H7&QOw-r zhbhw$1556YRs|4y=Qz0C>TK3qam?jlCy`}*bjQ5KjKdVm-lw~#Pjn@igz7wtNO#i} z_0)8*!A&f@y#DeD(p^LaBx@2tzy$cx{V33X)7eJ)vE#gr69U@{;T8mGN3vQi;*%7SW$z?>}5cCQ9n)FYOBe zwN2=j%q)%P1UCZcz@ha@BfU@qL|Z0mMam3pThUCS`VS+zUi#fyh!IV1eGLP=Dg%5s zuG5p3Y8+)OPbBOG(#lN)wOxvVTOh|_-O=LSrKK;cg`O=`_c`R}uyvYC+=qS^m-ZO6 z(ruBEp+KVFOU{hWryjd~sz)y@&Gcj&9dk3aW&b5agNKIPKUbCvAj^nlolMX^iE)uY zS&3ZI+9L)AV57ifab)PR%D|k!84j*7i2K*E@qn(KA*@$opvnLm2@uH&Mt{BqodkLL zTOi!gf14NlZglfxb?o@vg=w|}h{rf}3-1QpUPr(Bd(z6YDWCJjq`fD1`73Jvcw@jg zrUsIRC9#2+EK2zO{nw$Ino7gsK1CHH3j~~O2{vd4!L`k?QOP|qZ&QEO7EnL`B8wh5hc6S~jZVOy zuC8vq-{S<_X%*1c!^-K1Bz5(C{q_e9ff77!u4}Uyv>Ur;K3C<%soV~Fs+yY}w=k*ik?z{^ZBTEL zkr;u<>h$WBgPkmvMp8od*Bq3)hHt!hAuwpw9mZz*m4*4fleHP)jm<(2 zTEPZ3QFs`oBKrbt69Akr4vAJ{E5Y6|8%uLC{H ze_%ae{EehmA~+-$f8U4z$Sp(}!~{NycXC+F{Cq<1lUV_fT4{B`_8!>;v|{g2^Y2P% z5Zg%4q{#5OVojm^{-BpbzG;U4KgED?cA|`w_xo5Z1m3ib? zw{uizt<@4vdd;~|4SI@T#QP7uKt`i$S84Up7DIC7T&`RC9WlyDs6ADV5TgO zuy%Z_O+oG9K~7E)uJPwB+;+Oxm$PUqsi3CBm0BfXVe=&W?UHb=4zE(al$${0?OS`g zn$kk;GN2yjt2yRTv5pE11tJ5_=szXfDzx2U(?Pxm@?b}8BjUtr2k|-se=8|IYjhO| z8p@l@w5p>$Q^nIcOICy16|ZCN@}vEQcR4wZ!1!ugvg>otj@A0a?}$C{%xo3b=3~2~ zh$Ck8oH-}3rJ!v@)I&S|LYA1x65q+abnq4A*e^DZ7(CJ@roRIG3C`huZ#r2V_&NWq zf^fY&g!7+t13m}e;^N{8l4fjT6DEFWdwu&J5+zxeSwGge&Pne#a#;A|6=-Ao2N0l)bSGf?jd_N;;27oHInrT_aGG$BJUf#fK zpR*VZ=yJbKF-WkU>3G05(krYwK+d&OPk>=Ic3nefiVPlUh)n%Q|FEo{PjK|NEHal( zJlX>3EKL1Rshdy&ulVG2cKd2uM)pGnOOlwFv$QU6&4hTMQ>y7mUNKx1{d2dmh z!lF(MB>#=ecFq+z}XnWIZ#0k0$5 zVw7}P(W25j(o+%BpdYbw5EvoGUbP8D8DP7wXP}a8vrLF%!ZlT@Da>fXMtGL`%M-v0 z%$Gz%jshRcraQ}~WpwGDQ-dTCPv8VH*9RPQHWoIhc&yRb?o;w`@mRCZrbxvCOfCu4 z?ir*MH~60Bj3baQ{*}3$J`E6b6A(SlyPx1OoIL~}^RvIQWmp4U3=*#d{)&7f4S-!9- zeRD8)?})~s)pW~3gYy#*1ps6*4et*0EK)DLM)6;A(83z4o_;#3g*enEcvuL~B8AMI zqy^mSj`*b!?`D56ecMZT!pcLwHns6fj!37WVI^iUPrpjDc$Ou4p2vQvVD}L?vP=SX z5CXHlx%9TAArEWBD=ZB-qn>agYR@OncQJza$_BD(RIv3>46L)Tlugb@)W~s_F3VW27cRa6-Dd`-5eEp$>vFQJ|}Nmh8RLSrEqOY=#tS4XJPh0$>ZQN^CA&=M~u$;Ba{ zEQ9{yev4G{0RCXNWJ-nI;YAkD=+OkbHgS!cI));GfK`2)6^@Z0K4_&L9fzO{f55JC zTI?wgB-%Qx@C^KLWNR1lqyl=a1&gWO)ub=MtHyBakCEh>dStec6b>~yd`F-0L6KzV zEuPW6$txt&%w?@!a#GRWKW6@aF;jf!-x(AYjsbK3l!4VJTrNoPK@FIxJx^S*j^ z>aITcnN^lQL1U#v*g-_-s*(2|l!`dOSvo3$O~QNR zofqVh2j$lJH-S9JWc4KTbiGQCnNPspc+3NKa5RAHfTbD_g{XEP3vd zx;Og})3$<@rXcVFyMn=|WzwU$PGde{qALnv(QWTXsb_xN zVkJLe#eJ(hiM>1730vOXnuyh;?zgZ&-^WmP7ndijk^!c>VT$OvQFbmadLQ9<8ceB} zg1REKJgqmbdZg>_tkyN{Z!4{57G?{Jr{Q=M-SveX@)D?3$wMkO(+ji7)t*FQ?~~(5 zh2XuYYr|%64xpMsa6;l^fSfe|~Y5TAM_{oyJ10)(C2LPyUBkJzZKZp46kyu$>8y=`T zy2c-8%Ca>&`ZVvA0vMuFRtFmqWm|V)iuN2LZbhfIZ!F3wc&7K1H!vmJxr}%oE_1zj z){icT>}SY{9FoiY)Z(^_{wlMphh4w^$Mfkm=SGfy6vI0)iav$6de78JL|DJY8_mBf z!Hjt0=$G+yX`j6tHpH%u3cNXztks^It!TNx0S@x=x{3#ckL7-^sYd`-t=5CD#cjcJ z*WS+WJ1@-LrmI8p+bSUZvpU6Az&G=&xix%zUQkWc->+6xBW1Z@z-knsok$*xBZ`k0 zQS;6$^;D(VL>|>Bryr4jQ#sYFw%OS)3v;AW^%pwcw|Ce;G%8;#ZXFe|T7MF?iYJ`8 z64p5rI?ALI!Ahh^LVNFUk=feQe7+DPV<-~ruqrEX;I!OT*Lv(YG20`iJ$u4fdz($g zS}H_$FKS&te1+NI&j3=|$)2N9!2hh5XF_7p22&|NcK&85c>4KZ{J_R*`0JXzgvmMu z^$0_kZw!HI4>a`iu^Wj>N(%5MM7JG`&R>#49DvZn#>%ydUF7q6E2Yp@6d%ylFE}dG zJyUPe5w#tN-J()y1@&YhLPWpv>Ct3N8Q(VrQY}Vn)znhn3Q80O*ut~-5Es-dJwNE} zm=N`!bvc3R+WR$ciPb2U&NI4|ZZB2zjz{B+lE29_rQ;aROKIJ1kU7qs`$i=BHex1b zH@p8ConEE*gcKX@jTo``(Rs;+xCR;;o6*JXxY~&Hps$|w9heHw>Pfee135_ zis7hKbx)s$X67Plt6~L~dU$#dPT+h?(|X(8c`=@fG~w-zJLPj`!d8QE*kj)sDyAhC zI?wqW$>TMX>%uv4Q{^?f_X&)WoF3z-*ULBhkDPr^cb?`^Z~krI)a`*Sj#@@YQR_Q) z4RAh|{WRDQ?p@uQ31oSD+8t>{}m2%+Leho@}E#!ZJO zp%0c1y}Z}g%$ULCM4{G6f@*?lqPN%4LRsC~C$h7S@;9WV7ajQ(@LEiv*&xkYyB?~V zOz7Z}*vcr4myz&|(~QH-ivqz*ChuE}*51|z^oor{JK>5S?-rVdqPO-bMaot+={h-m zZ%7RG*n4;AZrMa{`^J@r+Wr@6Eyu#e@%&%+3Fy`@UNN$Z`|OrzGP*R69}ywdVX9hN zS*^`+MsT^X=v+rzWy7(4L)+ksL*^sx2GoX*EIK=YIOjKwJtJg*vX>}J>Jes$uARtR zTN^*{w7rQ9Ui1|MGlj3L=fkT@NLO89@Np>gBYaV8cGy%qG(OBc258xbOB%w9w{-R3 z##jbHnPz~VAxcS74+OMFtz0dRq^`N!XfZSXL~;XTK@C0 z_B#7UTEi0k$Zv9DJ!A*RE8}jyWSN!KrdQ`Jk(neSA9NGc)cMzS-3-uv@7Z4LC)Am2kJ7DjZ(&|8-=OT*pVR1_rU#>PPZ zU>(96d9ITwJuG9_GbYI@X^|dtPU~!Zo6x&{@#Sh;SvBV|Is2-1XSeQ7s0rTw7 z@k3#sG2DxjNsDy>5r^ZB+m6zEt?!u(TB-Rn7s6CqZirk@OJDTuCmn6}wtg6JZ3(W! z;0W;;E^>F-Nv{9e@gZclB|?=jptTMK!#b($cWc@D;-4bNKwQY?DlwH^cf&oF>?AzX zt7iNh#EH_{7^(V5XSkBL38Coew0^x~Hkr>S?ldFCg;0URDc9?R0kXAdvgwsb6Pj`x z(U!~p-}MJE2S%qZ>JS_)*LCRy&+aE&^q6UGWK*s40pEH>{qZv@A)A2^MbR7iG&^Jh z2kXtr@LRWo1Lcbl+lvmk5IIuXMNN?VKG=TOW%6ykkxk6Q|Ix!-uGAu>kZ`qZPhp># zn%xB1jL``KV=G2>-|n;7S}+zVL$1X@e=02IW?kK&X_h$(I`)`(tsRp7C%ZT#AAuMF z^X|C~nu~mbDg`XHDz^)prB~v5<8fZtnxpAj9izi;Jpr_p}O2f|l|~|Ksd*T%&z!UUxRAxEV6P6TMg3b4aZi`;?`oH^N~_xn3gOeVXHna-8u4tt z=nX*f_$`fkV+{45vDHC%xa8a{w}odGE7L+u&2SaF;@n$hXgkpu{$dI60dqEYIxXZ{ z>L0Z!aT8LRyWc8~;BsLU-lwl_>adEr@_@5Plyo-Ce8!Jc%wOQsPbd%XP%Wvq8b{4$ zY13$c@-%Z}D@z^hb*aistt4KRb;$mP{CLPC>`s&MZm&~4iPA`%oRHx>?h_C41ZkUr z2HuXi7`j=OIEGPI#8RiH8VQ+1l4ij8kkg7=*&i&kk_d;(IR*g_BSPQH<4l!fC6S@# z-23mdHIGJc&)b1!bu{stl*?H-d^giqsLx#^p1q*0VLr2WGopVzNMVOd)OqMZ?e*UB z#p@dkV?t{$Il`AfkBENvgJv&)i5bP5<^g`^_I=^M&4o~RwECls14vmYmDKJSI z7{@TD@)Scli%Ii1D0c#dEXWWo4WrjA#*owHL-e|}iA>kU zV(kaZqv+=wY~;SbeQajkI5aYpA;H4iJGD7Y-;q5Eh;2EqN$nY~vLcONJb`yZAXEpk zPzg1pp@t?TzuVSjqkJ!dM~{%44}597Fy4rZ;cxjId6L{NOD~*USPQsU(>3pvt+?^~ z(VqVqM>%;ywmMGg*Je-WM=T;GC2-kedT~k|;c$vJKvb3thgBt-d~zn2xkNt1za*3u zD03>`b!+X72yHs_!e8OUzoos>^r5!U*g;CCl?HRJ<&^(7nKn)AnhnLXbQS(M`eo6y z2Y^xym^24v^kBIeHwzcpZZ0;$!AHpU#G^c~iUxA%u8up^!}6MG98i)N%}J=#T*jmN zoO5Q^kiZ$BL#Gbs1m|mZ)uw(IWEkBa2ms>uV zOr$$mPH6!}Ee7GCoPtRAsLDEPA2KPj%kw#*q$MqdWExHdd2xyo^76_#w3o!JMU@(V z8_C{|=QJ9aVq6Ko?T}H@e?QJ~h4)AMgo0;sKD*8rGA(+j&vrRbBXAQ;?67&6u65R# zx#E=n`BN!mvfPriRKJRD`C`R8?fQ4GqmgqU_7;QNYWD5V-Wbj4?1p{Q`ei>-+NK-& z@6#xk2+|AuExNUlwvNmET_4+SAbmL=M@aeWp-p8+Y?8K^zDE~+nPCil>XUYNZb>Q8$j>%h zF%7DcZTzTO#aw12{PzfPyu3etch!pQ+hPt4UAafvX4MyQ&pbB^zvbmao6V-`0QS55 zGpIi~IXRnw4E`Lg=jG*n(muI4n96iIQ`LOw-1#1GX9;6Dxrld-gBpPw1DcErz3V%j zrTS&^1J~v(r%oIcqlmiZW}gY$!a2x1HQ!7`FP%6CE0?jyPeX{T?#~bY>NaHywDa~r zI4GTJgDsYM{*(_BJitaj1QThfwHdznO(=S0(P8gYrLD8fCG9I=%sc65<$~DKiyCjJ z4lIR!kj;J+OB6Z&Ud}|L6zVNkxxQoknq4hj5CwZL`qv4!j?ptl@|v~}efA6D{~b#n z{;)%mw&HtAs)XtVu3oYWdpKabZy?1(YHDhD_dV#tu6ik}Q?L~dy8?T27ESMQC7d-> zWWHe7CWR|IO^CMpAK&O^XAyZa!UYC{3ts6{>1Og$5Kep$46CSF2fxEn4rjJd(D_GS z`FmF$;)3Z~`H2RXTBpYIZnT0b0FcAq{XK^^XG*%Hun_5^sQ4g{C8;r7NKL^xb&gN{ zbcb6#go*2qKaVOXYhw7uK%Y|dPp#`;U@%(Dty!dm=0eKSIsR+G&P~tSV9$wBMLFf| zH*5&$2C3sMV;r019(uWLBxwntT~9%y{>v{dr#|ma<_7|MuJfX6T57RTV%TEPx#dye zYQ2u%VCEw2Ld#8lpPy`(3V)~WHLo>~NlZBU|6c&PNHO2g%j@~i?z8H4vlkxS1s{3F zvs~B$iZvLKSf#Y+Va)#~eyrt}@$cG4_j4#hiV=Qsi+uO{BoD$qH?JI2Gj5aPd2U9X7A&s9)S+P|DL zVUq%0!!6{>hoV}NOnqohS3pjw8#K)ZMjt9&I}dUEKV!Q40Fo z){&8sHiT+FwhNbQM>rF+*l?E-kN*71oAdlR&PktkaRM3q7+c)QKHoh>*ZO2@B>TLR z&+Oo{*R)M8`I~^a*}TDBPo!91EVtcV|7$2{GmM8Kx+5ykP%EU=yvaJW+|R(Vluy^q@-9h*D?9~ zM>W*XGL11kK1yG@{oPD@Q>|w0hSPom&GxxS56Qph$sdD&0I&TzqDnlJm1teb^A`p|FUV=yVy(IMfqj%+*yU-yfv@W*6>K)#|-pi?;02T z4{!;);8K$*DJhZjNR439gWdkrvHPa)OzyF^x^1bm&9^hkum5ryW~M?`A1xmtHwJ8l z8ln&a5ce}K`v^zVc$Spao1-qZ)}$ool+_m!ziHiaFs3STha=DJSaJ&MBXRvxs{W4! z3xf2}e-6_L-Heu(0@c4{1U^eYUY(K>4swJ`s;|r}R~@~F$DJa zZCB@a>kH1!hSk-%rI<_exFsYec9>TguXcpYW?(5jSnBmd6Twzf9$F{=jj5{U{h- zSc-z81`{-KcPD3HV8Brd&y#peBw=7+(C<3i+}sTQQR&ZKbr)OBF+i8lfG#0a;BYDb zTr5QTnP$(oraIfIA+cBd+6630jk>bO{u>juJN{#)mOp1&`0H}-DRifv<0yoOF*1%L zCT1u0HEoM`zwz<$u}HAA{oA5nDkwx9i=fml+_jncs+ttI-j#Y8RmyGv%SUe!^;2Gg z-WUX!E}58u}Y{ElX8f z9iLMz6{p)0si$-E0OTtY4p$AB*z*M&?pq8lnPnCg*?J5us3C_I z5I3fJCGG2m!-!MBK5pqR8 z8pB?%p-cZz#ZQZ>9M%z%zc!XP3^Xu@7GmS zIBK93;wW3hZ9pN5mKl`v)e^7B?qMl33WKe}`ua^+&-7E}$Cw#MN_6_2UMK`?d6SmkJntJDk zVdhj|Y5_#}`gu^n3;0MS&m)kAUIAY*`h{U>E?0-yV_hXH>i;g%SM40>g26uq`GVA+ z7P5@$AOyi`6N3n&teno+8e%9@&+{W2J%>%^c|xX<1X%knN+7hzT&OEm5Ds+dQ*wqB zQ)f?<@I0oG zc3zyYfTTrid*+LTz0X>^@uu_VH=XyRZcBiiJtp^J^4EoUQ?&KWX!&J!IX&uEd2LDV z+bVWRN*>-^{RY}0frIz!kr7v?d7U`juPi^VhL05_)RN*uq1^_NYxF3AC_dzBC5~)p zL183XIRU$2WFkINVU`$)QismxMwsR#Nr`P%IN5;b5>z!%ywHFX{pLM2OxZ2TjJb4D z?EEvuKT7zCP+;u+-mOrev0&iY-g3_=P(nIm_IqhG*`#Nv(0>?HUtFCC{Jh32UAz!k zDEB67aoNpr=O=kidwIA;wj?!}VsA9AU}3ysp}DTB)Ex8D+2~uCE!kX*Ex&%${Y9$< z&*jC7wWG52O?#WpmJzj#=dBZle>*pIrp3+tt)-R;uwbEO$7lU%>17%ft4oM5% z_Jqe;wb~;wqbTFAJb`f1>lm}V3`5VG?yW`guYtHiF1WNpUO9b^eCa^2)ioELTEZZ{oYWIr_Z^ zu1Zh;N=7XWKK*jA`&5M@Yl!h4L^$$C47^_784Kr;&f7~eNGc(&su`43a}teGXtMPL z;%ptwiexEOEmA(GV45mA`ZFhJR44kC^%_~OV*YP~#2n7%myo4DNH`(>!a1~r6kG-H zyosayAtQfUW9Z|qPtwv4T^T{@I1UW1)$B+pD7gL4qY+Kg9L#sW zoTMsow5N>Qds{;@PjC458xG}v7`4a+kQHGaT8FoUD>D$F<&c*mpCcg@j+k=Kd z@`gP^;S;(9peF|GW_TjByo?}18%NXMowzjHQ_)`Xw9)8S@q1>fZF+i0{}ttp?YXX?(hF zgndTztMo{`W?FKrM?^^9^Swzlsaijj#H2^fi#ihhY{zSI`Q~rNq}f}unpc=Te#HL( z^qC3=ys%KE#lnccxq3GZc||B6ut4*^z=`CAsU*;W$9(?8>SCObL-Q0L1X5a*<<$}? zghR^vwJORA1tb&ILD=6AMJv+s^$8YqTIPn;pEnG>e(S;9S{>4;iv~s3SQ_Ia;hCUE zLA`c;RT@SakJJOLg1gP%w;o^$H3|Jl{?4^Yqnk($!D-+UmJuRIbmsbO!^~RS1`*d( zh6D|V21wjvDF)G6cKcwr+qeu>96x6kDW~t7;Wdwi%k@tyo@+SuBvWR<38!{wVhP#$ z4-=ZTtEo^fB4^Y2OZ;^?3}mkFVsy*(=XPnYjU|`(X}gm+OS|1(X{NB%@hK_kPsw@ZSS6NHWZoy7wg^j7tICc@2}p>5#v(T4)6Aahr0pZf zd!D+{YQ)Z-tozmeVxx+_e$=N=pWbE=MnzCdK&Lvhl#XHX4A3`=1y^QIkhLxRFE^oe zqZ0!I15z?F7zhM{Xz6w>f^!WP!4de_(RhwRmNsB{H?-v&cAP|$`m0YbP5K$@eEx0h0BnNj*c%ess%Cu*2B{-SJpUCHl~c1VUWJE8;oPm6x!v|X>eYss0~`G- zB@6$D>UpqnrY6ID{>V#eC~V%+e1)>$Su#=xAFKZb-+*)ksq|y}=Hh|6w%8TlobJ3? zrKAhU&-YgzT9#pOiH~g4l&qGU-@;et${585W>SJKfV%UY?&;Tn?NG)*ZGDi8KnAyb`!;#%me$Ds6^{(b z{ri%!kI8Y+q4b~r^3P}FIA9yBkdP4Bx+feQ?;p#K>^OgX{Fc%}hKGOW)bnL*@Y>qi zf0(DGG=aVR^K?axbRxph$XMo=wpLatQv?Y}fYqvKX@vy@APG?8{n$9lRpLo_EZYH? zWi8*k_znKxN24z>=E zWNES#r#&sIXmrns2vtgfj_F8u{no}N@~V+<_Ft;bXk-t>Wo@FwYtfGXt||S3;}kIN zJ97G;SIWjr11M=W58A;7(BZG>cIWk@k^dRuoi~*l#kDS+Wlt26kX0pW^TnZ6BhJAE z|1uoQp1#NAUw(m`eBHmZu=}bs|Gou`qNur9WM1`~wqpLXQWws@J))4u4gF8`+ue9T zdC+WXV~eAQU6jJZENfHY1TOMOaJB(r+P{mgn8^-XeeRwK)tQ1k(70I$s^u;0N8_Y?)2MIhlheHz#Z1a(lVs>J@Le)zp75-`x5|GUV~h%3_L zpM^?#g#Yg;X>-zo!D4{`r>H{J$&FB5f1@ zHtO$(X?(N1Sj&K)kxr=RE9N_W-_8D)g}^8Z{|?_vRuy+_h=IM~eRC(AJ82?i z7knMeP4;6{bGQFXAF-s44auL4jVOr$BbN92Zq;zJrBi13Egh0|#P_0a?OYJ>l6|2F JEtND1{6CFeeLVmG literal 0 HcmV?d00001 diff --git a/planning/obstacle_avoidance_planner/media/drivable_area.png b/planning/obstacle_avoidance_planner/media/drivable_area.png deleted file mode 100644 index 660629970514360d2018667928fac6c4f341a36b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 14299 zcmYLQ1z1#D7ez%-1OWj-QbJK0=@uyw0qO2$fT3#$1qn$3328~`9C}Czi9tYS=uU|t zXC&vp=zIS=-$#7I<;J<^tiASHdw+PNqCiAIO@M=gL!|gpRviZi7Y+RGbPEsoo_CpH z3H-oyd!eX#3mAU4EW>ed9^xpE$ss4PEco=1~Wd2*4A3q+E!jVUWxkk zh$CCVfw%e6O2$Pya$S4y>CWd=H}F~#uUT*q;@$~r`O*0m`<&(uNl(c&hiuN*AnTQ+ z@iBF!@$vlP@)p(yEX(xk2dy>2q#X;K3CRzGUrT1;v43}CQfXP|p(2#LfXruon2(UK zIXX1K`rrio&Sl6vCSkgBe2i(k+a4=ub#!+kQLtluuGwNDwrnvs!lk8=L`CWFe5738(hqo-kDYj=P8@eKsx$g_y|8uH1 zq0TOR0<^5`%2GzNdBwOrr#UUtzr&Sa{VrNG1J2aLSWQw7p0#!ZxlMMFkjAmAXt>C& z+AZ^!&L2&gF6236fP5;Zw2c0f`oExTvjwDO|kJ{aF>$d_VGF zM1g@$>~hRW%04Pme7?qyfos&G(X((i;Qst6{`}IJ)VZWsMh4mJr83O3(0@mNr7Gz{ z?6A0Pm-|5126kU))&F8E#v>_fH4xK=6~mD{*-iisUTEEN-H8#cfUZrc&w~x?L0<7Y z6|NcB`?_dgf+GE*N)B3@*`#c6wuX*nEc_EA11dZdKTG{44qO=aUFU8)v&s|??DQ7L zQwi*VFFkIl%ABwN%CId*zg2A9e6_yM;LYa;^Jl9X8Azu2zQNedCP~!Vd=y>Fu$80^ zy`*>F;m~@Ne6B@r;HU*1^x~_3WMwJxNn^nMlji*bku7LiVDRrb2x>ne>)bM~tLZ-1 zvNEcAKEdec)}Rm>_@Y%0cjBxZU=R)5Xn6M1mR8hF5Ja~CZrD7fL-Tw|)LvRi!dLS)N7X|Vyc zuMl{oaE<_9+&3^VU~PiU^`(Qw47UZEAQ-OZ=4RlY-58W)SF+Qnw?Fi)dSfpzC%>0t zlO+g!Zg8;A7#&rW$Cv!BZ|L($XP;;e#7d^6r4gW=-fn%&?sa)xGbv8K{r%V-vukvE zAqg`EPs)(S34IKLjZN=5azk!0A$zzl&xL+>5MzOjC0w&J_dV$;jxMOwc;RJv=9nQ3 zY1{xw!09#$?zjGxe!o6z3;UtzcEEDhIWzpwQ13nRLVDz@fUb$bdSPs!uOf4N$alP4s=%IAhcPjMvyT%!f>dQLr&$B5w!egj_Ypal zn}QuJ95>Bk`!v^FyvMYF11N3kIU_)P8 z9&Fn9&xfIJuC_drP`^DWaVMs@Sq=b0eo3zZ`k=o2D-?{9FH@|3>7 zKON*(sb(w+x@@XxiS8RUi2RR;AC4UW7x`!c_25!`tCM5=yl+uuI=8sXfTYjYUW@KXW> zsByQ|O*InI_l%17G{|H04fEB@OnFv(VtDZ^2<6n?UPDRvq%KOV`1IKFcj_up;klnl z6pyooaKE&_JsS|4m($;!_TmpJ&O8C>Td2x%{W$$4y2EhZ2EcY7)B?t+#3#P6Pu2g1 zz5JWPTx*|e#NZ-Lrc3JR9ei=${ZEv`p8X^o!~67|Jf{3qYDJoTqvRHZ?*ug2Zzl>D z=oj6S<8>kDr6t^lFTQgZFOZ^oQ^X>xCQB|?s)OJuc)b^q(=HN5#35Lz8UIRz=Y|XU z7{ieZ-0XU=0G6Ms$ZRhsRu;nyiL1ejyj zRzVnLr@4juxSdLdDnv7Z4Nie8h_l}DDbeo2IBU`L zW#A81rfexHk{;4r_xD1X59?XfUKo>qQ)`Vl6uh(`#P%VUd@v6XXNR$1Nus-F)ninF&fnzkA~e2 zn0j%oa75{2zefi7*4%AJ!|$?}ut$Z;_=*|DvoJK?#!fde zU&Kz^X?kYHJU!;a(nk*Vu43U2K9~$IJ7}t<&)qqTs1A+$mHEr$%bbb!AsnhjLe!XOFpemIAsOSqV}LE4{I zKx>9;I9P}I>ZS~inj}Oo=*R6tt}E<58|8R3z!${vkT7VnQPhN_m$yg%7nIs3bIewd zDkjuYPd>Fk*WxSEex?n=kd;3X-TYoLXxO!B+5k8Dacrifxf>{fU+IIt?7bfHIA-pH z8mXt2oBxu9@V>athk2xk4?*F=Trw>WBY4yXV*?K?5J)hvzIh(E3x}~29PqP73`{Re zm{FNUcO=?T)2ou;;d0@Mt5Gc(N>j;^!xPqTmXtkKd{m%b_6C~tBx=t)=i#@M>QT5U zk7vb;a^y}Ni=y6lYeJv6;m*1d=Wp5b_=GO$uRBX!m%xoqb8{}Iv#y*l;fSXZK~Ey6 zqU95+_(UXW<8~7L^x}kx)(gHYc#AKsMkW*5-;nQO>{=vwjAR;ctMl^W!INJmMd%Y+ zJLx8XghaHHk{Q3S)0&aod(S9MrB;TlEKs2eaR7sBM!$~P{@frAJBMYR$KlhLJ9|!3!k`eS(YX8*>qXjX(b+`#xcqH`GNilmAmTAqEFU3r~(_{52%1rSoX$ znW5UkUczSn(~I4=4+*GJ&3v$(BRlT5yKvs}#B6N4PwZ?jrL(6gzYc9AMe36jC)WF`-(K$nrQA<@fogFJ3yT{T zgnCKlktxX+^!0+f&LFE0-@R*rr@^QMmfNTqpLSJ~fDUJI@kuh7a`L}Wl3QA*4ebG# zWgqB#Fj;b8E+Y(p#`sIymv59`vT41zp=R1pQ{6+E<=<~QIQK~>TfYom&;iHS2)OrJ zL}w83exN!Ec*l1Kp5}+RHFTPlc1*oxQ4CK=Y3XzMY{5@Y+HGaK0b`9~YPqpar5eyG?4{z?U1B|L!6~ZP9+t%S_W7?WkZH}!D^fiuVhoyrj?YeKF}lOd zxo08z%ZLNXP10!JjGQNx($7hfK=<@52B0|6*DSsw*jDt6RmO;39EjVb7rgh8Pb!dA zd{IAbRyei@-w|{7rHg3E9(N$^CLOm=)Gm=D?{;u>+_!BWvWNC?`>o!f$4oh3Jb#ZG z5TA^!2f9raelWcDe|)iAyYOo3IWswZa0=IGgUZiACmyyh*l8F4ye`vLqa;eLR+O~0 z@p-d1@7XX!H8p=l4=zk+QPwS@0M*aeE*iD3eHo8yK^Wpjh=0Sgna&qR-;;9S31yQe zF)jU4r+z~mo=68i6z48M$}>lBu->{J8hkB71s}A-8{)1YR444LgyTTPvq4-WWWP!e zDtx*idFI*~9JxPKMfJj>=n=(SlYf|RnKnH)|2M@KB%!iuQSYih^rovNC4mS-ujvMN zsK?So^~x*>oAcB2(Z_z(0j-|CH+xOG;sCC93F(FO8hFi{A0w#ioo3A)9i!KWGszzD zDi%5f+zTOv<`q0`M1BmC_)7q8>Y5nk!b*x7TwxLo{#jl^bE_!hmh6PsCj<&qy4Nl2 zwCy!HEteS;3!6~^(bisY*L-DO%>XevAXRMl=k&M{#+hCMyKE(!}^Jdt@ z_C;1}>_(!Md|_O`%hiXeq|mY4NeDO7EqJc}Q5<^Xc6e?vm5~GrEl+P=8S;Kw66h z;$L+FG{UsO|4eY)o`Oaa zYd10Y-xLQcrSdLvBxrImRwVY(i-#lY;t+JY7rkV*eu>K&+%d{+B{zKrFY1641D;>* zjg=JXtx-sl{(r*u=1%d9fqxqR?FWUK`~$bTs%1bm>R;?ToLViHziZ$G=vulr(?vmn zn*<`NU0H4Ta)ZMq5Aus=E27M}BKaB(4{dTZP0Lf{_`o48_(@@=^#i-4xSie6O?PY1 zuyX9IE&t0gckM;WUVyN?o?^`jd?}@58)o9PYJw}_0J}=e>vZO4ipZI)H9<+Z&@M_4hTcdW zTHB`9ihplkCNFG95OmFAd%Hs;R};)QM`VfmEvc=biQhr`~-QtttR8L`e+%G(nLTK zIvc-P5a^ z>O>7xEA)#ho9cXJ$)dXwJm_u;*8a?4gUWl<`5%KNt=DZNO(7-GUaO7rir++^=f9Y8 zcxFN=?EjTTr9DlrGTHipUZD~RZVg`+9z;&7(R@e)?ez3HPm_3uT2C8*%!YvDq*BW!2Ty&ze!Er=n@Y#?PpTY@w;b z;^X=cBqak+a>P+Q-(HtXli(&CpNWHE7xzsdSbsqwlV=VXJre^PH=Bg!lKK<(iNNuC z<#MWjXX7f2!&$SimVlfhl2|MCn2^(q))h4;VT{H*QjlQc*h&=LDKuG#NFN{9vLAoO zKXnq4#mPQOFO}(@%Sjb|U4EJILYnwV;UN0V>bd1x-&|hEAd}mQ58N7(u+`Ns`jls(L&iULNota*B` za<%dAoLK7fJm+;>5qt1rH$rCXVzRHgwbhuOJ;G*s>sVAye_{F~r3iT5KW#T#Dai^~ zx{=Eis-5=wj;EE?qGd+=4qEV7K6<(ywP$(s{!%4bID)rhi#n=LE7w%@AATJAD#$gu zejGs%Le!Br;UZ7fz3m`r4M6>?`0Zv@QM*r7b#?METWDEKt~T z-Sm#$_|)8&7~;>{wO_tjX0+%j-D$(}URdU0GWB721%w?3C%rii3%nQRlHy{1c&3ie z9X%Y;9{Jjyc<{*d@p@D|r4^2C@Y`2!GG=<=bu?mLExBnMnG^l`k;e5(i~aESfM;0G zI{HNxDvz;H#<_&Gr@;Y0s-i16Ix(^EU6rBAGcdTc@2k$%krvd;@lVoo6^k0b0Qvx7%J$WeJ-14ssq!6nySuee1dn6cGpyF zhqk#MT#c9YIja(czF(I{%b!}hBjm`&3%(N_RqjdjgEq^t+!P1KIu{l6OpkiY6#2}1B zceqS04s-xTNw#Mn-h)TXFjJ^qLK;H4mM${Ax`xB~T z(H**CApQ=+@l2b02cL663wKo;C9EsSDu}NSZwiPkxhy;KZ|Q=n5b7le9JJ`|Vb$-@ z`ydWH8RM1G+J1T3;6)M;2N(BaBEgxsSZ1Asf7k_S98I5aSH`s0t=#bX-Bx9)&`(=6 zJ0TFrwYkecRjlc%lw9U;>YMHL*xyHc7CW=Q7FxSZXlf{*3(^cFgv8#d7!})G&bZ($ zBMR>%0dcy}4mV+T#g_OBGfLk2U7kO9Q%TSzOP{tZ_;oHw*nB#0-)V+c<%@wNY&0(DN1F zzp~6#9)H7snX;{;{}+LGSB99Eb3kBz66WLT$(M&H^Q8*ATS6!H0gf;`d_!T{R-ZO0 z2Y&n;oWao5wvkfl9@0Bg8SN#7yIh@y1ileWt*@ZZyk^@~3ON}bXrB6q?YfJu_^6~7 z=x7UP*X-f4j`ZO9j7h3GEAO^f-?x z?-!%`HH2xC(3P=W(Ae2zX?zc(%k>A@XG%raUQkzW0-Z^?ALt zduP48yf8oN>~il&6}6{1X1%UC<^g#@cvcSGym%C5D6>Z#=(FOC(AB<$$4&bWZUsBf zrv_Q&63Q$_=+J)p-W2h%;3-r;nq%mRq069XxGTl~b*o0R>n7TpdLWx|135LGl8<7_ zIbOv_!*9SpV`r9O^LLgXXF*UdW5dLBo8cCp@KfoX(Z^bSJ1TQpn2iz7m|L=orb4FS zxweA&h+(5%7>;`dn``~_wSJU8%$RjReU!rrnjZn%`l~|$P|!zIQ&lD1hGZV#6Suk% zy8QVDmi~DB#Jf$ZPK@dYFXidb^^#5D!I>i?)Id>z9Pe~sqRkXN%K5V~R9oU8RfjE6 zkwi@B=7Y6Y4+@FoVp2NA8x^S%jXa{CTI5Jqv}GTDj4b#+xZ~MF^~uZIse{>#tMKS5 zxh+L|&u920455NV$JSVtOEDtMTAIc7P4&w+RKl|;V$BklZ#zkgIjLaUbSE)t!Vk;d z2NBWuYq}r?^FP!v>bZ8ILKbEWyb{N;pWly8HTsi(O8Yb7< zQSWS2v-X!(-4>k3k)wk;H{cbCLI%uECZOmWj0|V%X~qkdGYw;_Wy1_38}3yI=QD)k zOakS%jG9%JcSPY`4ciL_!qxow^Qf`OoysZwRfD#JG9-PM4{^_M@jjZ3&i_P8%H*se zs|s(OPMT*kp5~E_C~>1-@xStCqgi}I=Z;vtouC1sLYL0W!P2zK_ExLd?W}@C&x-N} zzFz()fiq;f!4DByhXAv#TW?L%?-f|=%Cc6Ji+y#z=@YkT_)h3e+4!xXkBC>18SuN< z6A1PMs^L>I&Ze0EBFSpd1ga->Z{1q@D=!|1xcsy5ZH$BS+Tq6mFSJd@-xw2as07TW zG>%op?a}>{!uZVDJZkX$B^X;c-*$;;8cUFMMPkooQDefgDz^D+$}>j+J0We`p4(i2 z)^;dIHEJ&~>^JBjdOZ1J*EQ#r`_kqQE1X|?1|~PMXYCm7%Ek(xob2|}t7fj_nzakl zWGxa}KG3}Kp00*#moRD%{_dSqg+jio_penugqK)R85%)qFvMY+s=Z0KIxZm=Q$8CU z3_7T)w5Bfd5Z~FYp5CgQp8f(w==Zq{gHHX^jJZLBd2FL_50W`4s0iVU77R$O>9 zDrmBNqJ}fZqd9|%zSjY>xU7mUT>iB2oX5*~sHMb7SUiC9+vIV(MRdkZD4gPqOtnpi zLd4|3=lrLDaq+fIG+J{-7T8jKiDUM)6FZ(s5`M}7ZbwYe{C zIe8nY>=ba00a0)0Y4k`h*BUB;eK`xxAQBWqhLryWyp*9GWpR2Cp-(2M+(_J3afWRM zOha>TRZhB0U(9^C!!8&9daGiA(2l3rv{XIHwA2Q@D_f6*bpIxvJ${j1|Dsa8By&OA z`X1u5zlNh3cWqi|-64`^;F*KzhxioXh!61_h8Bqf|8Y<}wum4m_Ch0lgPt3`0_DO= zryf7Q#1ubH18-DEZlgMJf2j{VQ3ZK?R$)~OW8uXBaXpQW4~c~tXv zL3-VbU6X7QEIu*JL0Z_;@&|qKX(|zwqii$*vTEN3BBtb_$2&rTX{eL0cXRYU!B~Yzx1%Ca8D-RFk1O( zvMvrk@z?U{^~a&IxF%y$jT_HS>k~&dMS>FVa(6egNbFYsC#Y59>|_XTu`76;lQ%|G zbJ+0H#;rXSOwsP_s67~fs8VqVZqvjnq%i+lN3$LFr%HNdH+JO-^%(PXAFW;PeF6Xp zE$G=iD--J@fS3^Tu`_lZ^seD&&eGgeW=F3fX^#>>q8EM#oIO-szkX4>Q1Md7RK9yO zq)xatC2+s-`+pGqT-8{zV?C2!)dkLAZ*NA3D_x27T57Md z>jp?+kh88<*wAHrasc>{<+oU|bl-^a5LZM!4i07LRV@HrEhpcesAqgFyV#@(JAI9K znxRyf+iLH*rV$EIj(^zx?0BAPa};)?XPGy6|M|EtGU^YNYvcvYEx=;}B4OhGN;g@Q z0F_POLDUoRndcT2+#&N=l*o!tYsFKAGVSTKP_a#Ou{7=e#p0Gtv>jDLy*vYLRGauh zM(z`WY7VKhY)XV_7Ye%K`Y}!2u>bs2) zEN8kK0L^mgUk&g5qit@x16vF*)8p8`NKyaT^Z=yjC4*94EQKj2RSo@N`CMuxHqKSDMnv!-_-YWGct+(tcA@GO*?ck3*w_HM)311wXJ9nFb>y?rUEq!9#V$hz==b3Vho}-p|W1D*it4ei(LRW%| zuS8~>w{*$)(&~V+BzBuGzQM4Ko1gLXFx)ezntX8!{5KRZRRD=jO>2`pq#g#imFa!L zbYsK#r9uer^CMoLq$+^_kl<}o^wX)-tlfat^c_a=MD$aj{j^!3Ok7L3OtSZkBP`@}g_|7W1BXEmISR#9(-QJFQ-oCj`D@iNBAtmlR*IHz za&nH5y}!L|erp(SW_}Z3zP4a+g7wp`{g3)(D!C(1hKDp%Dvb95D~*7;1vAqe7`t!# z%~?2)REwu7UuZ)ux;Uz~XATMkjDK_Lshw?ef-apoNbI8XxAoYpy@gAO_$TSgvq$hO zu|cs{ZS$-}EI5DyH)UV|>6rP1@g6i>5-Mv?YrdUu?ij!Kz@o!DDs4OM_4kZ&W?et=ad+9MzuhQSLu9HH=WKx z-P8p5{JJz%{Q8&^G(Th3D4ly^YKm!?)=u&`)Tf^B*kq~QzFs{3UOV@0k16Zc&(C&y zf+xN_R3B|b=0tK>mcDL)o2*1B>P#4Zd=-9?Z-s ze^|1e&ojOuoA}Y5d{3@TNsXL8Rk>xKTu*I8AXio0p0>WM9|9dW$SZ!Qwg%P>xij$-ceqkU%Md&=;qt!Si09sK52) zDN@O>4XOfy-h7^~&bXh{_PbftZnn8wzxtI^B$)(w<<~!sJKP?mrOXd3mbaIcsyx*# zGczo=UO3Id1}Y~lg{k9X?>KynFO(^TmX?-(TKtR;=9u#a%%B%A?Hj~u^cFXi$P=}| zW6vF_!v%hM-~{nxt3MU1UgKgN;47`-Pg7nJwic(4vk{p!js+%ctsjoYlhm2iLHAbb zTJ&?Z_55()=S94!5VGZ`j#9AD*4C-)`B(rf>=irXP|y2#!E=6>c-|2$?GT}o14!d> zd`q8V@6*=t_f8KYl7im`)Z8t@+ubKCP;iAWURb6&-5Z;nUHv|0^K(m}c$^wRy(G*P zJZPt|^!SoBX1Md3nEsqy}-O~ZeEOd{G|#`O_nM0h$ zW=vCQS!wn3q}4JSkNsFwPYnmp!10aJz0(ZGfYZr!{xnX&@$|k7+PIvyqFQ5&v0ziY zNi(5mD@26G*?tE-EvTQoCA4w3NwY+&^P%YqEdtLwOW9S7PmdYAdzlc?^6-{55#O)q zXYD1(Ex?}Ev-*Oe=X;=#S`Zb=j2A5F5?=`gGO*A*yMAX~&+udVB^JQQ=Tp%@Xd{92 zmXUxNz)blzBzIR6tYbUz0G96fndaA=4niNet@$mr3Piuh@1+!`ECU;7*HV_4mo-t= zxr!A?&fZT2QKO^*hB0IMkzQk)qcJlSfTezr(=MifBaE^wtJ5_y0$dOt+USXynQxXN zV5s(qonR+xk~Z{vLYd9F-{bGk{>$k*>`OdEySTiNsJ*3=J5FuKg3}{pti{UpFNZuajGxUyYM48*qEf2uQN__P~ls=fZwti}&{owbAMUHUJ z^rra@v8`H2uI_=Su@=a?L4D_hUKfI(jeTG90rkKKrz?6FBJ8?UfV zk=>alW%Bpra+B$~eXe^}<7U5lyt8YX@67QHhFLCuvWNCRQFeiAkc-SgfQp^2#g9)u z6tUc9XJ?m9C~r_BkIR2L>y&IWoTX94NMrUI+Sr4|AOnXIF7KPbF0|w~Q_A3ott<}L z)&J&dQ9W(H;o{Tukb!1>y&hys5+xlStFSBHwgfZ!5-?my&T<>Tm9kY8|7la@{E2&IFQ2R9`ouEql!5Kf%rOZ5BRa8 zF0X3FaoZsZYUJMFO)m)Gpa50~CApl+`txuhYN8IFEz9O%hhpxt{+)vsz(`UHb&HV> zSaGR-EZ-_`x+riJc`viC&VOAj(Wv+ zp^cC;t{$q^2|xFo^$&&;Kz6Y5O5d*T4_^Wp6HT{XuM@)Rk%85od4hF~qSp^V?1q_yO z;a%Zs{49$1LW2RTKfIHowwNdsdcSMrC2+{ zx*l1mR#63m4b`ju zF1B#s^ZisZxs%!B;1OHFO5FnvW`dmRlMv#Uy-(F>;n(|eoOMAjH590D^OkvgsO%G| zaR5@^O$vvU5>4ouFb=ypr0!Qw1J3OahS=LttE{RFhvr*15qLj;c}V{5$FDte%ya?~ z?0Q^jFy-kg6*b$8;e9kJLwo?*#|XYs@H;>1Jr4$-6Fe@jnz9|;_56P5nrhpO%r{or zoBxd$4CfM`Dmn5+uRN6|c~ho+yR@5Xz*g8&oO;o(!&|)I32nKvH_D}zu%h3oIf+Ag zllW8@^fZ0>q{app0cg7Nag@M@TPc62#Fz8LoQLY3?trtfxiGESfM7#{eG|;S(XJ-k z&SRF}uO^{~9_s6el}jldpj6<6i!42PJfsdRlgE{sAd1H_+{lfz5~gow)owe&`E#Xa z%6cJ`A*6Pq);v^iN)WaJ2JW6>N6iwQPrjwNiaH4tk;s#(k(1(fY^V2E`Hu2G0&@4T zq2x63a?|=Tv-AR4Sa`2$rZZ}8I;w~HwJ9%EXs($^zDQ*)5Pk&PA15g^$5LJ##Xb7B zCavze1Zm^Loms)H66{!Y7*HpRMVbV}X8HfFX*pZ1Ft3ivlJt?yS7#2F@m*%r1hE|7 zS4*e$$FV@OtwjMf2KG?GAL;CcIZ0+|9X?@hG5m!6$E($ZSvICXg#u~sZE5oOXbq>NBM6)96tO`ZlnrC?x+{>{qE^w0;vACBR&9EU(t(ji|JpPfNX8}9OPtM z892<$30I=Lhmtb*PoA{ZA?|gP9?J*sWB}`wx^?f3cPa0RUJSdqneB(paN($zW1r0L z$)GSQB=8KaUHsytZN|FG-z%4|p+jI+itgLl9M)dKt%RNuviFCyHc* z2BGS68ssL_tFO%*le8gjt0jUUvma)ZCaUnUadD4ALkeq6+Y z`)<{=B*uW@EG6ku`9G*7vwzY#0HZK`W0SZVe;DTWsa!8`y*?|g_uJa^(s*U-K^ zlcx_CiFzl_Ers%I(zK^IXi0f3Hqv6P1a{9X{IF z0dtYAQqXSgnA5#5tK|=h6km8_UKxJTE{nH%;G?ZgP_X=ogPk3VmwQc7vz$z~AxM09 zz|A?PQ-m;-L&>EewPAC?)41yDKeFd#L`iUF4R-;IC7bly5cadebBnj%9J4)x2JIu*3;euXrY%;5^UITKk3%rB(hq(;O4w}~E9yXa=R9fGm$ALE)L=LU z$7#-(g^^)Mw3ZaR4I1w*)OPipTN+vrC0gH%?7q%O`rX%~u1&k54NYxBZb{hQo-HI= z8(1kO?8kaXx68#*e8u|z`2!QHx&bHh`__Gl@Gm~#o5_?v<3;QALoMNAo!alCU$pQN zcDX-OLcXSck)jwp^^6{b(8tjP3-v`tb(n@9#^j}b#PL7}RS{U3YVSUkQyYBc79vLD z6`mU|g)PB)t{obblxLl^G7V(^v&k%_`|+qjsS)f#5kxntnV4T*CopVm$q=xV#3!~( z&G_Z5_Q>}ldX2D#apa+S%|-n5R=ph}&HZdvgHC3psTwG*?aMjB^QS)U0ifzC2^P|Y z*rXj(Xq|@}*1^AaAw1K#=>w&iN9IFZ-O@!Sw$Kp%ts%LXKT920?JKW)x~am}yVoMG z7W?Q|b0B!+seqFctwDg19Vheys1F!N{Q7%xO4GtN88hHWnU&FhNsHb`*JuglZlI)p z;Q!(la9V0nol4}6mtC>mJ3~^KbgaDcu)>w1s8^0wF(3jmkQMd6*P3+-)3&hsbFCD_ z=!`)QIRQC|GD6F2Av1+ zD8M~{{(b}qAwf{DDSaCt!RDH241yWADbiPzO<6$-%7bpb#+kNzS8{C7l%oetN)51129VKtZ~|Qj5&72^~zkuSfAXozJ!UEdl z3~I6*Of1>3*TLQCaS~F!VPTY4;<__6>pB}BxZiep2Z2QRoStunz~b~i0e>j3&N@3C z=7smvn1b!qkh{ebyH0JcSS<#uR$bqEzt-7jqcxh(hYnf0Vq0llW3*cy$X#}mQ-Z+X zVS#24V{^G&<{E%XZkc z*1O1EVdQF~D+SChP&KvLq#07~Q#*gsJHM#fhAC{B@T>aDYvfaL#%!3hB{qL~7rT%B z9b4Emtc8_^6}6s3&f_keN&UWzS716=Yv2N3=U&EsJSoJkWF6Q9UfR@{qCCn6pv@6n zr&C4($)xEmMRT=MbvOZMCKrNjhi7dyfX`wWF4x-1z2vo)wjkP4{(anhseZ}rCS?9J zYU1$0APe?lN|mfSW7A&qYiVu2l`qGzCs|i54~^#c_X{v6?7=+#!tmw!@O@qu z(m3Xe!$9=#$u6dKVBN&8^-uQ%O&=Eo=L)V0pYDMdP2Ko>{$kGSWZdLr{BPIVbF7qy2<^f>PMlGoTMtK3PDQr-g=x_L E0HO(D8~^|S diff --git a/planning/obstacle_avoidance_planner/media/eb_traj.png b/planning/obstacle_avoidance_planner/media/eb_traj.png deleted file mode 100644 index 9910810920bff71f9a1798064597ff4cb656db49..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 15264 zcmYj&cOcts_r5Obu}X)LpjE0`n-T<%wyJ79XziV%YQ`pJwf1PK*s-gsR@L5AV#nSQ z#2$&g$M3`QzTfwE|3L=#=N{+2&pFq1osfT26=?oq`HPHb@(-MB&267p@5BA}9ns>aSG>%P$*(`~qo;6Kh4{g$X~M_h zV1%cqr-dgJ_|KB+Y}`@W6&_TZ87rR9-lG48_tn?uU%tM|K+)a3-S)$6u+RwkqgBB= zKQ-5@*o^**<#LDdzAzd4$#Ev7wxg%-&hY6Y-#zvdoMPNP4#uAL&A;%+W8w#x`kg3l z!_Z&@6W^`EGnLb!v*YpyhJnGst(A@s4E=(GgKNeLc#TbWPM5PfZhWCy9mnsBm22Cp zRZ-K^e{sq&QJa;}iPtx=cC+p?PafNB65bOhU3^LZMYFoZ)3T2X=p$L`8iM1zIi?%x zSBfn$Jb(TiMfu;)rg2978V294d{qUJiZ?yh47Erl+S* z`2M&<`+?yHV3vi3L&E2esyKfXOyKC$ldOZPV*+0zyCnR4_OiaAaSHIH^CrOhpYdJ1 zx%c0}ngSC*uRU2S2A;(jBffO`Ie*os(Q9R{M#SujxH|$H`e*YOD`@cdj!k7z7Mk6?J?@K*7Rk)6 z0OlwxwBwl)5D);^2e*U0zS6h3xqj90PX6xYgQKrRyOd)uL&J(q>c<`%(5^~)dJneF z)U#63m?GmnM~1yJU`|cBUQ1NQ8H_Fm$Hb0Gt1ZA5?CTG%`K%w+i!5mvy*!kco3-&- z!WmzlqLVoepwtEyu(!~wRwrd!%6Gr{{5{8}jeGrG39wM->+#zAFL#eCX#-iE0^Rk$ zcftTe0-C|=?kuVsz^(#gxKm(QhfXQ2{?GjXHGrE==1X(7yqxFzCT#WBE?_5bGqi?{ zyQN>t&(1kmu61WA-SC+E=<~9T&T4=qhF^ZRN%Oy^(^uLt3|LC*Ee zLL-EhymgbB014371gnF|{!V=GI`2uiKj*7p!pEgttM_w{24CHlUEh#qj{&jlke7&* zFu~TP=?D;almY{n37eo!Y`9#V5<>L!NXAM`n!S^d_Rn44U1`uEvFT!o@9 z#~wZv!>k|nt?Z+@ZL=p%oFjIs5y}!&5LNmnQ$EdD7CELVW(tfG9De;W9oFTY@?h?p z9~F@bxf&dbW{0&hbFV&qXYVDJ^8}fP!x}DG-dL1~yu$Ret1Z99j3@RLne!Mc6wmqz zkz$wQzKWinT$b+RoQtrwzv0H=h0kH%X|oMXl6+hHRkiS0z8>Fl4inm>sFF)bL|FKj zXr@a~6P2{*2^&07&^R>{XLZx%ew`;FZ(GvPb=NgM7h5zq@qoM8#c=ocYu#@Di@O0Z zqc3q^VXRMOIjNss##;V>%D3^U7a)r(xu~CgYk$HoV9>GNO9Zqig=9U8ZH(hIA zIH$@ee$>2v@DH3-5+3xTHnJ3{k^cd1QUz7XeceQsUG$NCUx#XI#{-JLzx~X0xBS2f zf3W+IcRPU0QqZ42^8SaroLvk*ORv@e-atp+fK)+_-=n<#z4P^@hnnAR#XkI$ok`~d ziM0=BKDABL$fK5dTqh|mE>-pB2KjcCG*W=Cq_WCiNKn(Rha@k$>~bvF015Q;PUKV+ zLYsu&i-fgm7z}eMGHmj4hjJWRrSf(yV!VTC1~nokx`Gk(1sm=wWBSLlma^%$kk=>t z-s{XQ_r3ALE=&$R0#$<+P6j?}fBg6A435o?J-=ZYM@l=iOK)lO{{-$6eyow%qo32) zWMb2vibuBEkSA~vcj1~8*o}ut!lh|X%ljL*t|T|yF!%liy+Ur9=+bH%2&0KyF(boo ztq1sNIKVMs@{Uq|O>%~}O#Od2uUO{MFf7A;u0BQjBB(x|5t+rH=% z)M1fd3Zr_r_V5On-0_amL= z=B|kGtVB-03Y~0wp3M+tKk2bPgT2f&OtgTb9^IT$s$->Y#p5Hy(FGeD4kd8c?N zIwrs$64n+|qf-WI0gim~pO&2~y2*V}93SqIQLBT6lxH_hryv!!sJTv2i=s+%U$-c& zJb7?S%cN&uuX5G&8Ub?oE;V_{QRjMwjue#oR=HUD;@;8M$L7!)4);!{S8^dn16QbZ zzY-v{kxrtwz=6T8H?&^BKX&oe`b6<|z@_6NQdHVCV>uR`!HKo}QdaHCwUJ#K{IxEu z!*uKG2lc0^zD=Ed&|zallD?bFH{6>FZf+n@0PbO+&0gEh7O!hfJ(*8!Zb`q50dH5w zzlv>TQbq~BNiwU_xVP-GR65S77`}kqxJ+lw2fss@4Scvn_o2*;`KM3|$`jcvb2E~} z@bz*ZXZH9?bada6>*(0n2k=A#S7_*Zr;CA!&6A%(Hgq@C6+Gi=kBY2%M*>rWc#-nr;UAzlTCU-*a%Cnjf@SpCQM%=+wp zvCHBEZ{qRs13RXfYnNtuv>63@Cvo%rYO>iHxsj12e%9b{5$a4w!9Y=!upYjS;F(}Z zhVU1ya=V#OLAMgwqHN5 z@1R4O*Sy8Q+s1!lrJ3v0xuJbrtV6p?r(AAw^>gIOfWf}A-*J|>lN$PlZOE&$c+rik*-u@b$ z&$_7EO^_2i#B~2fq?=`3ZjKyUO5tjby|a2ftAnZQ&ODS@qOqW{v=6F>cC>xW$;Ys}~J4Hi1 zA=K&lPCF68IM?TsG%uIvpWFuzoBLP=KDI|RaCpdIPmcCHtWW+Tom9$4Tc-*pc_n}* zF@N3-P392;NG)FbwX?fndIH&?{zG|x)H zoizG=KIIL5&OR&ioLy;_L@Cfj{qhk>T09AB9TolXS^V4OebuEl@w&g!#+cNh^(Q2G zCIT-e6~iRZR|$y{GWy8UZ5>Wm$C&CFzBftNZ63ap#Jpy!Sre>#&lX{%&;077~B!Xc@yoCES`sAUKICv5vI|WR` zW}-9I{U~?rmhXo48HW|LOCir~ghc%1g)=|ZNZ7Sy&l#TD!V*i0YQsQ*Ha4@)Il@3p zQi}`_5{mtyaN}!2N70A@c{f9sHog0Hm%=^+8cLe&Q?!Pj9Dc#X3 ziF_FP&Sftw!K>2zASHZA3yn*4p^a;cJdvKjbTc^^IJlPd`nZ9txvp1t))V{2+C~p* z+>My1vo$K2nsva0a5PVx(p#$+H$KiLn3h+z%z)S;Q%g3ip1NUg1R@V$n1=Xv3o;1EXVb^eSEz4#9vu@`Uv10bn1wx!vmUi;*rcs z`L7@pUTury8n2#`9Z5R%456!!OSVE!7@u}M@+B3zsCplJgcp0^=5Tx7GP9J8Y{_`4 z(@ZpEsSRq)D$t&U_NbvW{wlt?#Y8ZdO$|#4KQZbavJ;bJ#6-ZO#rG(DnIK(ZxN6c7 zFWy1zIHSJi2Hcx#zFZbkbFv?{W@YS9e+0_DdG?P}a?VNPB18?rkD6n0K#LbT$)x5S z>>UDwB-OGfFLkX{*Bf1h;?JaVWK(?)#PhfhQ}Y#c>xhv)f|6@1L-G=g3qt611F)Nn zHnPfV3m5ErEWqxI;%`3y%anI-2Fx#dp{C)`buu7^_+Dm-OkP^lOZdPlYUnWsaLaN?EH(3>_sO98?~! z$hUeRo#1S+bK7=dUGS2@vaF_H`YJ>sHcs2n>#V76rvn1f;?}FNH;I#@9BLvK0>in9 zEGX@nE$oo{8u8Jo92LR+*vl>DMW!56U}tx?M&97VPc7CycdFkCan|1Qy2Af^@22Dt zGV8B+j$=LiSQ^f%WOs?J)=2eM_8;}9IY~XqisX;YX^y(Qf0f>mJtH{(9vBu1d|&!1 zo5eIdU4x&1^uC)mZl#&m^$(>*(NMGnv+?NEcsHa0FrDSvSarJQ7-LQ_qn zcBEsGH2(K1>8%frL6ILTiZD)*PXmaE?c$Jt0`UEeRymH*s4`{wtjcz zz&$n0(K@1SQJ(nIp2d z>oXI;NkL0LjX~=-!|E^7g5$$aEa;aHeEuHPO4w{)-5XxoJ6c^MsxR$+S5w<4)%Y~I zDO|^X<0|a&R_B#CSYRW2!)c?;Nkx>9MUgCumCu5&s(Y*#<>rBmnfq+c{5HH`MS;E= zfyhj->%PmBr}b#tQ`!J?Pe}xfZF$@AwViD+5#bzGLt)L!n7tsDIcgWl_L3>^>kqbA zwWNx1z9FOPr-*tL9_o(8B{$$Mdzs^F zX5m0u@p9(lcYNk+9+ABk=3P&UTM&uGrp@K&0E4H&`xsA4z@qC-zAz-;OxV^4_6;% zb&!{@06Va{It8IMc^IoyF)d89@E7htCQ}F7P)s=sPoMp2I_3mNT8ghuwl`1vRF5qb1#)?3Q(t4ktUOu`r zTViN|?)&KH>`Jb(-7=nod!akCiU3x10euA5kQvnO!v z?o}WVK>}x+9Im4ntGTQOtOe+AAq4;R4{}V}AFcRuBA9toTmH_$p?MEp@6muj_p+h> z;IS036xHInmhN3KtLR%t{mdPGn|&kHVooDnLrhHMo@4=Bl?^&0+MNy{VtU*{i*m!O z%J2mb8}_*jNXd!*yB1M++-Pjn)h<|f-M;uQqG!Y7Zirb%I^rx^Gl6Eit{U^!ZV_+UUqAXbZ zC?bKpqUbF$6r{JfQ#Bjl&@I&cMJRB3$bkfbkrBd?YqW85Z06*{)F1v{C~8km_L<1( zU;8KjwZaaW4_efZnx z1nx3SkjVz6{x&_xvUki(*S_%f6`9Je;sXBxL0J*(#5VZsRU--t;1V9@-w{79pr-T@ zV^TMOym~w$dCwUlE#lk>5yOg3?=Y110>&**0I#ns!K<10{>oYqofv_J4J{+-x$*gZ zsZLFGdAZbBfL+CBS5XD5P-c(a{!WG|+GL2WIl&XzIOLW202D;qECUPmvvu$Mj#LP= zTd-&1VB4ukIgMO)MSOic*QXc83Ei8h$fPW~gBqyiNQ zA~kx!PytvyvI%^hS}jzi#LWR2^q4XEL#^e@BiDb;wpFoH6}x%3QrN#-7E(puzeB#W z#DbPcrV(GgC1tSbnbp>;DFt<{DSlp!V~eoubl4q#m=9u=qTUG{)@P%=wzgPUT=1)V zzar|#I}Ma5x4pZ{={h_hP2~EAnF-VN6O$W@{vz)le0WwY>d_O-scPnEz4UvWGl8p1 zV}4*`H`wQULKSj)VQtDG5A2Z$&SkXJfXgJ)F)fzLiEh1_jXoOF0iTz$$Ku3&!T~9JXDPUBZfpdHqC@rYmUC z%$<{fs|V=g!Q$`(^o}9CYWcLI)gED6Vk% z)iY%6vA&kH`vc4ssK|&?p;qn;liR@Ggmo}PLDeYv55$VnPph2fP9G!_{52sp31LL1 zXryrgrJUmf4_aI180+?FYrh9A9Q>}fP0XKP^n|6c@32Fb)zxurESA*LqQr*|EFG)l z_wWv+3e%TQe55*irFUNVPhCkz5g^JcDy)?qs^wc#(lQ49x|Y)^hx}KGOIPB+MZ!rwtr6 zNT61Z%GA+EQ^5)gFU@KNPIWq$Khg;rIvgtf3gHLq+!(K=cd`**ikT7fi@owP?q1nJ zRAFjjbjAH^$&0QFE7PAzjX|(*P0@A-@GofdR!uLp%+Hp2B(z+9M0`j$Yjo^VXm*V* zlD+=v$?4MDcy#mJ+*$)e9{&Rp=5XHxz@cW^6c6OROUG!BRe5 z>I#;tDcgi?jLw^?;cj>mH~_7O#;I|e<^Ke0+&?o(0j7ic?%Vc z=>{(|P3%uBzD=F)7SLuTtVLN&LYWbfLJ*>0kJR?M#)JaIx+K_?Oq_ZHEn5cjWfQON zjx-!8rd#bVKXkY2=DRPdprMW3Qdr={ZWVi9=cAUKqb1dh@*<7*j_9qTi+XfS>IdIi z*=^K>#!$T!Ifw9P6V%I9fhddqC*G?#>4|%R!Y%pCQG=7y%x5(UeCE;-6wOVXijk`^ z;;WHTY(2VC*B4iNN8Ouyy2G0uy||}kx0QMGxVzCIwc5#L>>uY`v=_vnO3`3y%nUXftkG;;Of2;yTlNbgGyX%xEpG76Apu5ljs9$$?re)Wt4b#Y|sjK$K2!)(URv+*EHX$ly3Xj2Q zirsf)`@FAT-DVj?i-3F$%7+oNE&w3#c3Y~pmlrDd)*}+GEcAFw@Pv~+iITEK1_9vv ze)kk(wshV27?FLC|MhlXC^rq_Ac|xT(r!iNlUs3bDT6w!>BKuhbcd13OQ1kMg*q9w zO;-K|)<7@r?j4k4b?tCFO#z=V3@{;a?Mbgy+tdN~Os(9$`1gV$gK1g?>V>Kzh6(6K zQ-Ip=*ODk8kxtI@S*`c~55h`F)2i;m z$ezWg)MkkMfIql7w_iZlOk2>5ELYfVML5`@yccKQd6~1(W}_OPC9OR7noCot9Oiz> zz@muO5J>Oy*#23Cp$zz}aU!ufJ_yUO`U z+EYDBR4rs?F>5fqid;?nTd~Fd;0K|A`fv%T)NW%8wCahNufG&!2bJ8#`8hwT4_f!U zF3aBS5I%nOcXdBXhp)N9$}6>IBiEHYGS$OvVwlaQVM8W#6|76n+77YWSWk3gpqo&lyVK_%;f2(%D2Mc4O)JOU(hd|_9x zNHUE3NdqL-DPA42>@QT&`HR|mZA5|@g_ZM@jAypW=jsZLY|T!4p0h>GmTK_wuie>C zIb4q}PNn0Q7OT!VrMSvd^!Pq1ibR1umN`;q$4WgIDcKeDl4Mw>38*X9u`e=C_I^kM zT8Ts`gC+nP$%eZ;ZmJT52=-^EZW@_UtL~RrrLjTNF}qU9*klQP<>awKniYR-V#wCm zPi70Q3BL%(4NN+Q0WSUSrn1chG?kehAdEk7Dz4v3m_V1WKAjkWjNlyC8amNfnnk|M?N{^E`DIows& z9RdA^Y+mt-$>DYH{2g^9YYt4gqt)Fedfmw_EG;fM7*fEL>6fo@iMfiaomKpg!~{H+ z+Yqs+zCLQflZjea>!+TlL9iR!!6du`(Gi;g$CyS1O?OIL{{DT3$=Okw`ZRDF|Lkak z=1gWa5B{_L9kwbaKZtL)0t3t$E}QZ`$}F`)R3*eyp}IDb^v#kY zRf@1;A5<K>5<2jnPL5&?FGi&b5gNdDy8NuX49OW% zTsG3Yo`z%LD`!1vbK3N>xl|&g!=25(bLo1(=U4epWr-!_)kgz#nnry8iznV$TT?x} zoWiN-0FE=^oseqV)JJqGs6|`w?7TQxWTZGqX60v;c0H?^w#7V^-kNf0#s(tRXz0pE zsApheyp#03mpg2)qS2+}H#O+9Y^FG)#@I8pKO+{*DwA75ePhkM`c^8C?VvD(i>=6)cIPm_MrA z1W)2K({vA$QCs@eQFV%mMniVuO}E)8m@F6+re3jQqCK(vE~-`&(xF_Z;Mp1I=eNQ> ztj;v!qn!Lehxg>WoAW__SMkA=Q|OlD>eFQUfNL10K2a{GbIR!?VBSOKVWr=NEQ6|q zDu#dhQ?^~o#lil>emqSwvFW{6KKQ;^umn9K$Us zS1D`7=vl#r5*W=BbllV!$McjQ0}X!*E`Ch5;8A4gCzfp(#ObHvC7Uz9Y6H31mjx4q z8{$IN0>tW6tK7buH_ODzfzI9Q6iRSlDgqfbTMKWUX^-2G-{a837LA_bhN2Mxl3*H0 ztV-J8rBn?KX5N@^37H=6KOdjb7D%A3s%IN_nVEG-J({iAGHHC<6P4M^hNwP5=p->J zB}f2?kZCSF)UJ8WC&n=|e!Hl=S|Q)S`GH;O_^PPegWb=7tf6y4{omMt-UBtXOLW>I zB>kQd0~ouOPc4m|l^k-QuEWbOwn*e1kRSw(#;s8*p}BXt^zi$A>uf#du8_yX(Ocsu zx7{G|iQ*#x_P;|Wr#Eq?iG*V{)j_eNBpZT=uTFOeRk@C4xP)DW<)k8V zn~hi~F3sZPMc4c=^m>%;U##T!kY?Wq@I3~XQ16WlpFg{kVv$dDta;)(AO%$DBD@U) zMu_}brNK9r*9rPMCieDGgM;44_7a=DL>r>bFVVzOp3QgvlB*nA!`cV))%Abam8$^J z#}~%GbB1|#NArv`#!0`bYdemc0Fi_#n8KQmt&vgz^wAckh=*5>3U(sa+j&*!a+YbX zh*AwfKj(~2%OHZ>L}dmXf=x4nXSQaj;FDa$GXKvCT+!KrS<=_1-^a38CC+%rhxf)m z(sVVD?7FkF^r-Yzgi%fq>0rQe`L~-Z?98C$8lYCsd-D56@7ok;WexKi~T{@nY=rN5Ep6-LDdrGO@5W(KufZdX!*H^Fa> z;Boh_Ujd?%gB_K2EA-Hg_=`_3;G$#fH>OHX5WF~t(S4rP$t%Nf2Sd7Hm(YaIw@PU( zUwGC9uqiS5fU61qppO02)}?>6Q7|%wG`+7mRFl zkw$9se;EhMt|#PaRhCq~`r1gG4t#D z>=!xX)7{H!>a6Fe6D%$*a;o=RU5v6Vb zTPz?5K6%nIFmUU{=XuGSV}-Z36aq%QF(j0mb4FVBJd0#*R5iEX z^w%p5eWUE;UxPaQZIN`{@=bDi&ytV+6bFgx@Ka4e0!*-c-7w+n(h)-2ncpi`_b3@3 z?Z-0Y4(E)@qz$h{$4paPLM=>tu<4>$J;(}HO#EAv!rbe^2o)3c_3dbEI?4PwJT)Sp zhM12>%^y+~~U}x``bL2It%%oI4BbDXeyH4U&Pxb zp!w)_hvv;BjYo0u2`PlA(?$H3Z#+XfzeHKrHZ0jzU8HpErSvM5;Kq?K!N_O%TFowC zfK+t=1A>U}TGsAH%53J&2qA!4rEZdw+J{Ql{0@Xf#@lvYI@b%pPDEa)`MJo=SJFY7$<-!1weIZVJj>*y_4(0U|_;NmUd zrk7yU*>Y~fa`b?$=DxB1qo{0MsMNRObhIT+tCw$<@Z%FCV#6@Xu26ijK!0G$gMVqI zMY*~Qr&6ZxRumQ(kRM)pv~-^xAk%NV?zvL3uqHDr-RX*!7b;kZUXZ}qF#@`+H|;G9 z<}l@AgG&5;>SxpdVuNueex8-Csx|Yi7gbHL?F2$lwUW^+jl3KCmo!VQ42JJrfA%W- zvyZHq?V5}Scxy;Xv-2zC0sd@1Rj67}iRb#kI)RS;K>8;0g4~8|M2GlxN5FYLCz}V# z`^j6Ve4#mAcz;mU5d`(rP?56hU3R_R%#gQ7{N;Y|Xz+c6YJG=leVdIirmv6Y5R~`2 zO8SmnVc#!_?zIP2ndnpHluw^x+%#RJ?FYV^dA<*wu*gyjU6IVv724{CgUP_djY8zZ zE*sDw&&8G{M(Owy}g?xBmNR32oU*%-X?ML1zSOw2|^a)b);graW)W&98;0 z<5&7u_CjLfBO+XW$i3t$|JiA17W&B7nN$w<3i7l~WIx-8Qae7m*?TUh1zM#;=sdIb zAoQ7$WQfW^ubS^4Gw(05TcyU?GgSa?)N4qJ$)e<=UF4+SikqA=aZ4duYwM0onp?Xf zAxp55@Y2#J2EzcC^ZoTB`FG;d@;5%x;f!UM36=7qpC9m)YD9bo3jxUW{O*Iwg=cnf zgSgRAUEuJ#uc$;FJiZ;R#xa({@zF+XPe@hBx^U2{xVBj3#f!rJ`{fdZ-jqw56ZhEZ z=GdsWUc|NFOZ9A>$G@|~ooOc>s6}>1dnG(~TPYOcZpSq55@~09-k0md8{Q2u+k|q5 zguP&sn}X%@U2frhjD$$hmcGA@$%2rF!&QXsvi8{OHyVicz(D(XN%ByRbkT7O@#U>o0yt1t5@3Srj{RY=5g1x7(GxQThu>OfqIUw%}2f9JzbTr*m!@3UVaEwXgmPkmw%^iq1L6r z5UcJy6N0V3bQ_)C39w*Qi1L|&U8y6{(|+jE_=h9(ey4N$CRbdYW+pSmtnLdtCt6A1 zH~G*EbCDQ3uM$5ID-;MV|7=+isl-%uRj&JW7gwZNxb;h$(6+`d;VK*x_Re&A`3(nq z?}#&p71@7Me-J#`NWMpgeaq6jkJw9mR;FHK89iJKzXR!CH~w%)lH`2==&=EOQXrn2 zkLxD=mlCPP-}_x>N4|4~$Be$8j8FTjx7#W9#Vok%0vZY3Ly}t&Ab2pSyiO;*)=2a+@OLZ}){Xmt4OD&^jq+ej=D`Q~ z`(NZ1#$N=CX{5Sp%};Gz0TcfD>(yu7_CX%#@crx0F5@vfH5ucD{yv3KEi+a8igbxd z(!1rfBRFe#&--4|4*V6rSjRzQ{gE_a#a+Vl%Oc0CF-ZVktywq>VC_HGCKjCb+;j~> zmYk2U1S>Aa@P9R!@q;^Ww2)dlH~`Y(0c7wKy44+pUMKnubbxffH396bcWi&QP1=w> z5%*2WvlrOhqVtIa&2r-I7*+lmYGiZLq|q|+4dX25gwy#!%OM3<0>~M4kub2xNK*H; zD=79UPkCMwzOS$D)ut)jxca)?ysDN>7x`s0T%+<&d+cLKWb@42UxO0Os|I8`Hb7t# zJtwcd_5wyu-9lX{_l=RRsx#0uxMg!t;NW+;(<4NSFN3aTXP1bF&)XN1pZUblAj6^g z_XCgljc|S6qn=$Fux&5v|qbm+peH3~j|W7b8Q8UQ3WYT@R`ODmuiuV06NemJ)D z@J{aifsR=4qWNMEp99H(^=|>Bs|8CBGV~>*CM;SzjrqpC{47ncf$FaB6y4icfD`&4RzObNU6%F-k@6T@Hs`|6t(*u)xl+xkidMBu;#87YWaBT4sM-+mt!vGbKac-fCHhf?K)B*K>8g)7UcsKx zpS3aigzQ`inzRVeD@8jCsnb2W31YL_n2R{%h-sWE;f{Jcvp; zE+@BJYh+?{J_bwrk`=)09#GWn!U}MWr>*JucHJ{bGo0FgWx6uZkta*W5VPmyT2@Y> z!cUz)bZLmkVs(u~npWYSu#$6nJVy-DRkuuxj)56G%j@R|4U?wK=RD6sozVGA(5q)Ny+yuCnR!JUDNIIW)M3||ZVr)MM7`)u+s>i*=> zoS*EWY3h#t=$4OOFaULX43)W+>&EMvsC9{)`vp`|#$%#!B7iY3*ySBxlC=gjbj?>| znE3hl37}NH(ib_SjU~tv&U?fcI=q^LEb!^HVpbDkV@0F$eO)dU!eq zX?EG`t((aJ7WrNy!$?`VGsyS&=4I@{+M|K_DU57;sA`d}YBcwNwM(7D4pr7HZx8)#e&c=Bkom6g zsJgTG+9m2t-GJ>#quYZF?S&NEXU{svPBn=jsYLe$Ssa{WK^d?K=n!z119dSMp=)>V zCe0e*K8GW{4*pk}HZPxfdBy&5=6IC!JfQ2EJo0SVJKJ5djIZ7L#NZ@uAa-iE&^o-A z;eGtRVNgk%N9D+CYsHw5dYtF$xjki;0qWNd+so*b@UdEc*du~5;^VmTZ$ZZw?cv%8 z;GP32bpnG8{%QGHdjUtqZf>MRRhIk2C8ZvRAE2TArAvx&oQ~;M=>M>l!O2Pb<+2v$ zKA%Jtg|sw@&rw`mz;>Yl{X~3f%6SFRCPSa2BH)Vvn=w2m1q!nU*WT#W-icT`%u=GS z>=A{ju_>~8znuU|R#x;^E@nL&oDH%(^Ie`>v83z8N}@Mi;v!ZKawAz$0f53w;OGE6 zBnwR~l?WP3Ha(bH!c;$8xEv}y*zJf1aA8e11bbw$bF;*b1na57utzw2%t?s&b72dL zc2}?CR`UU;s$XV_vJ!+xJ8e|>QgnzL)E%v4b4PAK&IM}+_!U6(R)c7N!9rNr`VAwq zl%WFzXISg-5--^o3tQn4D&2>WZdiECtnmDyue2rJ8*h0K*g=608?ErDVt-h71d=bt zpN&T?z1U*0`Vu23ABiijm)r8P7MioF}0;uYA>l0EWM?6Ur332u5rDL|2~-fK`DReHA~7!vXbdB!eSK{8@nS;Vh^=&1hiQj^5uou5jbA@!6d- zjO-D`MLc(2Bz5MdD&DO6T-Cy-42#yMm)+m!II>^sE41+1S8qBTTC(U54Tgq}ce>}l zy&W0SDx$txychRxQJhHTJTnJ&WS1y*fl&fgR~L<+2`CS9HdfH#}TK;)@bbrlHRzi6u#-`YDb zx&uhh2j{RT1rV45u&DA-`A{k5-1cj}0;ugE8^A0%nqFYcK*^DzvAMb8(Z6~jDBu4T zt>r#004k^6{s$GGeX3b;UcMH4j%L0!wJ`k;nhE%VYv*!niIGVh%9#>ydFKS$<}VG) z^OCvmHHwUPIRxr1DCqNokbh6>f1?sP-2Wey09_>*B-A_3I-QSU^A%z}LLF8AqO|+9 zM`-CmsbU-lwkOuZMaGBTz|j4P@fJ%2IsRad^m(=Ae4Dxxe2_8PDSM1{C&nsOEkHzrMHC2{)oEJ4Jzpgb}NIDfim}a*o<%JQ6 zLmfvl`@gEI)>ke5)bZknBZmRVh*jozu^E^wV?)QWQ*E#T@1*SU+39qawfoYdya8&c zY4x(P&r!$mIR300=zJittgZem#<%bV3s9t2<4v&j*;Dgz0|bQzI)?|hPY>!37QBu? z_@T-h^k1l2`awzOa*gxW+JQ-MzQj@ZAs@$g$Aa(IM53 XKJ0LFz5q&Y$rR;PpBFqe`SAY$G75_2 diff --git a/planning/obstacle_avoidance_planner/media/interpolated_points_marker.png b/planning/obstacle_avoidance_planner/media/interpolated_points_marker.png deleted file mode 100644 index ce69fa0d0fc2cc64064f67f4e0e9d9e265313497..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 82506 zcmZ^K1ymf{vM32bgS)#!aMutl5Zv9}-7UDgySonV?iSqLb@0LY+;i@I_x!j1pVe!+ zd-m>{s@m1%J5*L$3?3E-77PpwUi_!9JQx^6^2hZZG~~xO-R+q9$LWj14{=54kB=v` zVaUflwxfuuqk@gGql=!s5txa!jg`?i2LpQ}BWnj!8%H2`7yrj37BfXvMX{f1GD4WR4w4IrKE6}^7#a6Nf>_xPi{pBV+StLsh`_{! z1r=R0&N@b->BQZ)KrAeqB+MkFItQy|+AdB?E=o3*?8}xCXvM)oceafA{-VB&P=eif zj?-?^t+G&Ym;{dLK7wiS^u1sXNJOxFC`C|sp(KST6w4DE<{nBmBYXx|6XTAIE{M^? z!=AtP%RQCuUVS~0x5FO~4+uWBXM4S+;vfVQ2qJyi4!jBWc?fK2> z2wEj**yz8o{(`%mirhj6?RN=ddvh>xitx|TZHa#m*}cEL{;#1?q`#l4sjKTl^m*tz zMG*Q2n%n;#_Ium_b-JwolPV%jE|O#jK_vc9QPI)WJpUjKDS%dF5AZ?5*Mt8z@?rm9 z@3AEJrz zMbP#4TANGs>+1(o{%@-P;@3Zx!;grU&B9LVC2S(U2F+I@#kc|Knq3z2>{D6O?IJ$0p0s|#^ z6rD5hOp46BtC6=q=bMBdo3)Jg_>So(2txfAPBYfu3lu^*VzfOwQPlIh+?9Dt4GM<+ ziWeM8rN?RP!8vEEb@zXeeP|~#V)_>|x4D)Sla7q2l^oUZ80tNz(UVD6$S$+Xq8UPV zxqqSYnQaNapFiH2=T@CP+&5*tZFp{cf{uOqH(xIwg_!>(gxW~&89oTzT{}8j4rCu= zi{WonAts>F8!FvD*OYpU;5y05HuYtiru<8&s4Ka|AITk`+p&_ryR2}J3je3FJJz8E7kX0NO>A7p0HyGdp;`0fmnM;TXh{D zQIAMp;dE1}9F!~jWw1F1*`03;W}tv~e!9Ma3ZMS8Ey$v3rzUW(^S-XYdqpI}@Gn*5 z^_Mud6TLya`!%_x6JGkCB8dEjT=Dn4>+r-e2K)7!K~MDTYKu+E2B+mskyU`+>r>+p z;qlj|RgVEaC0?1ZJGIGuwfjw?<7@r znEmoMj|GDYo387Y*v2wSTL$-N1Eu@M?B$vbEA9IY(g_O=E!ED>36W~dN{=+qt5HW6 zh#+;|isS5gB}$9FZo+=-1aJqks0QMvI;_5(2{Wvo64osrFf`o)WLCRe(7M!gz*Np_?%*G?R~~=SFZ+vuOf?s zV^qo6cbp9Iniqh~Y!P}J^F?b@klBV#zOyNH<`2B}(ga56?K9sMhwlGGqVURWAfFOb8DEuTinvPUo8+ASQ^?4CG${u{yTVkd+9G4}R-YYyHIiI1Nw__9rMI$U<$eDF+q9|=72UqynIc?bY2gS>Z zyeAs#KjlfgB&&hR&?En{t$(ZfhYV7+#a@%p>m#Mx{7t>wXz`g8x`{s{aI*dP1QMke z-XQniER>7b7Yd}C(-u2sA{S%In`%h>#AFWt@{S;Ch6q3{KI?jai<0M#=f-*nba(gA zdGO(Smv)35q7OU}Pw8HzKwLDf$h4B_4Cz@z52fp%ItsD&X+0XdQq$$bMd|vBTYq!A z7o9Zk_#~F!i_2}fYHWMT+IGq_@%ZT7kP|D;2zwAK;d7rWn}yo9l03vJwhfuIS%pXv z%_jX%VbJ@;Qgn}>d)46y5}-8e^7FB|QA!r?WSLFQu> zQ`GATx;3nbz3#HU=HMmVV2>t6Goam5jz!dD| zhLcs3ozh*#O48muw%nH#JPki~w#h`_;_+`3RXk>)pniYd0W?ARB8@UNAkQ{>wEY>Y z#>HZLnQ_;?3A^R2&Vd}2v_MJ>UFT>lSAPmj10nMiJgkf*P__*hZ_?qrUZoN8Yl7Mf zLJd5DBWlX$!M3OuvO(qa=;i2rM;&C`KK({k_tD_RL=gXNq|M&0=ZPE^LA%Yg1TrO) zTAZ$8%=W?onfM>}4G}6d3HVy2krCv%LP6@lhDbQ=Hi7yXs(Ebv7HIdH9HZJl)Mba!aZ;KKQ)V z8cxGQMxV~e%66eH@#$i%A*?&tqsODBVRr*Tc+OP=B;5F;ocpH*l!l$O67{_d+oTv4 zUqOii#=f6m5=ttxtniAiqp--23;8@M(qA)wI7%s8VEj2rLQ&CR4SLxexG(s5&>5!I zt2={E3rh|ioEs^}M_YM7Mm~4_95a#k)P6c$FxaoUH}$Et!J^#w7^ z9F?3`n^)}Z-Fvrg1Nd}yPH=#Ha_|FJ2BNDR-5!v^gp4I7DVzt%>?Bd7opN5>qvOyj z!T-`o0hs-W4?Rx7e>JG}5?XeA_~ z7LnHdd608!NK8c6*rH-3y-2HaCB&LyRG7$OOkibEVA0WjteRa#hgG#8S76PTTtlVb zmERg;eK$NjOS$;?2A0x@1^GQJLVVpXQnRv9qRll6byejOAe5AlfEjX=bi!=2USiBu zRK`hEcUYA_At4DdvG|C@(?ah&e=gTUlo$i}z$%ks4=HmR1k2}d>>36!VD9%QI&T&4 zp!)5?77*sK6J+Kk> zuuuy41gUq_K{vo4LEUS1`7s?0Z81Ki5!LMKgDfV}U9Bl+r_#UuFS0!hAm8 zu-xbCBCDcw!v##z&3C3&f~H?>=1Jc1QE1D+Jul2 zqIg)~Iy+TV2ajwylyorl;@j|O(Ws4s8VT2-1Ng8ztG*qA0)d6mS7ZW1)0>F^WF3;S>h86 zCDhP1H*F+{Kx2`Yd;D=_ogqN0p12x6-1GNFXQT+Kjm%}WXJmRCPdg6v&OpTNZOD@Q z?Hjmrncw)*=%!&0`AUr^e;obnGv`}468@2U(vn1wO;VckPv_qpPR z1;lO!%J=0`knUc!QI;?xJY!4Yz<(EFgI@NCl}N$ID3A*ZQ}{#R8Nkj&fr~N(Bk`N^ zr(y`WYuqa8QNT`D#Z7$1XlZ~==Dtnab~LbJyac&XX**p49JW%(gFU*%WB1$W z6}V*!x;YK%7mWf@EcxzuGRWw>dy}=-Yj}*rAveN)3gSNHZ6^1nknK+dB51`OmitCQ z4w%OHELb${(QR<1m8_z;3Fa)deFR}d5$L{=ez!`n`=s@-PxBtp(>PXX6^4bfWElh+ z(g@#NbXr8z<_g3EtiKp)pT)zo+Tk&WD8V*H$$sZs6Fo%>`9qUy3D7S$4+=e4Ye7}O zfHg3;#E-q3nh54+9^A?V7T8)@HPcg+6t*H*EjVFqT~6+1kp2>~kef5q;~;0r_-41D zm*x<$%P5;yyF~GI#neA^hhAfG#n$tbW`@d>1EUW60mVdPdd-*$6Kme^eZ_BSmHw;h z{5)Xo%jG`9S|N?Syg*-)g5>q5E<8>WOs0@;K_TBT`Y8+vXv=MBa~-T3H75z6{i*SXQWb|V zpwUS|UdRn`GPja6Eju=Y^_(`a)Esg_UKza*%EkTXHt*vuh-(C;EK`GSkmGU0GpzGQ zWYjX;(1p}pu%ab8*mwRPWRFnp@p@Dv%IsW2Az%YSCpj5w0Zcvi2t|8 zkj>0L@#B8>r&nGLC8P^lE?WOHM{T2iHSfZ3kpBo6 z=!+qh&f<=cxgS5f{+u=TNzUbmv@DuEX&cKw&)yO5cKPw z3dj_Q8@=*J+otQ_;u?3+X2rqD2e|rm_J!RQ*IVTz>|5pXJ*>wizgd=n#aM;CaFfn} z3fE-f9EZ;KnZV;v%22c`DA@;I;_45#rIj4b$C?K1@+Byrxeh5S>F=a;D3rp#ntlH} zrL>i@`#*`gBe`sY7(6Q>{MgB0xFGNo@SnH7dqHB9X|wKwx=j5^NkhQ# zk$X4^i;POyP@zHsfpO|t7NQWcd^RP;oP^#~u37}O(nM-IER;fj-*B)(xxw6sKHa3> zW!m25GgRx+wa&jaJGVSF)Ygn?+J?6)w3n;VC(rNIPm8#J+q~NBsz1+YY|oVySgRR} z1TU&k>X@WNgGI~XFqag?6d;d^p3PHJ()?Vkl9Ikfu0ewV8S*O+I6VvV4oKM;@L`TL+$^GNGgw-ba+HBl`Fe3@0__pKvC# zpILmOe?qyPSCC7i)-(GKsRx&TGupc%77jiwx2>uUv_%r5gSfFUv%Eldm{G!irHExx2<}fxa6oz42oAM7>3d2XuKd+S5cSy}BHM>$C)#~+aF%!s9+jvcdY zAtCs_r;xYH1oF8H5qkns<*~eEhM9668BQ(OqOIJG4K-`@%y>crma!t3$ZCg*udZu- zD&^DzpL*2mq$#2AnDbrv7_RcXvLH7TxKuZ%P|Z&pu}5gnPmR8;SdbWS|Hcu?Rkp$l zz9u>sw%pao$sAz2R`?{|n2;2Hj(T!@&uri#HE7MOkVAMQ*f#vqOsbN48Afr13Q1fJs?LKXjVmvBvM5EJ2%~OqsGP( zjvyqz@JX>Ov4ijU43~BZyVIGcA;Gsp@^JsrBS9UX@d!j};k9z8c9Fb4%}L3wqH-VA zAr1*@(n=mp*T$V*N$y%_Qy8P$_a1x*)C5d~nOgm!@Z=EFV2TaJI^{YuB-21`|BBr- z&FDGk5eG-*P>--LJ6hK7HelN>CGS?`^gFChc52Cu2FOS+n$9?_qfHw(0HbaZA&*8N zufzcCD?)ratW<$?y}f>VxQ7XVKWt&Q1zamTU9`9$n?k1HkF_=T#LP1U7?}7g zghZOq6JpNjc`o0j zhWSoSkxW6Hp&rXM=llpJRx!gg_0wUu%B>4Z5WchF=%K4dBD=M2YdoDm0C$gzd=t+F z#15ALldwPOb)A9p3~{j-`cmBXL>O^n{LLfDoIHQ}{F>K#yfO9poTnWc^AM>46~FcwOKWrR^O`3(~PmaZo~;)nXNNzsVY7 zp!qw?D@2>O8{WpB#dQqeP==>7DJSkX6U53ab-s_2PyEY(5vEoSYd!4rn|yxhXc(VD zALnjG4W~&emPlHGqS89NF`CizI<1Iy1)Ls>)P`k0@Kx{kA4GX8OjI^M}Pik1MY1nx)~*#jzM>mjC6>UnQb{ z2a`6QAdTRN|K?=}?X5zDG z8XDFG)hOAKDUzZObM};vP6#t%s!BWP<1+@*u1I9kaFcs*fCzUB=`xleej_oP_|k6` z9YTqCP7MlH8M0I|d#LRItU@^n)Y6pU;+`(k#SagFProAG8o<8q*fiJyrRUW*~SnqPj_*t`g@tKuS9P_PbbdPMDXkK31Tue7zw2;FhS)SW1PYlUBn*|mS@~lQ@4s~iyKH;xXY`fI;*iiF$gb#y39(`? zhziewYqEAfnHC=3d(5xfNW_-lSn;ix!9^J&p}H|Po;0q`le2#<?U4TMZT zHk+A?p`M60b#aNP`2_>0WYyVD-Tkx!;Z83T0#7OQ94EIkhL+P>%Rcmo$7l~5Dr+P5 z^QqQFy5xZ~fnX&(IN?crn|6;~A?rr)CicbqXP5|yqWFLywci6Y-(Zy+#jGv|+T z?KABD0|q~COh2-j7IQc9gbbrx|MvYC-@bDgk6EHL8@$a;PX%a|sQ)HN18BEy$n10| z0M{5c8}CqS?za%~JpFXc(k7JSKt3`LbObKg=vs~NYdsWz9XG`dkE#}P%4Uxe@`~wN ziDA_gr)$kr1^;fp50*KE#}cy;n7lxDNsxhT}bC{f2)*##WWyQRY?twMM4 zcAsLpP1(ZDYqJWkKj>`l54)c2LEftzE%qOLuV1YrDOHZYW>cW{G5RNw+8{brrTMW= zD;Y~k#^f>VGEo<^3SgfE%y<5L^*1-S@jztH&fg)M<1%*g-39;9$+4Z%=YR+{p3RVEbX>n`%+Kk(Bb;0!@jsDoc#P*G zw)WJlc+6eU&gCPIOwtPHBU9+aD1JpSak#zz!iyJ4c_uCMX^HD;Yv(Jir{%wcGLN$> zcANhxg=d>l6j$GjPFGJ6l2ZMr7vSndOh*qZx+Qk~VEYw{x5PWNRV!`-dbwE+4LKdU z>t`r)AkT6y8g@g~rMLtErsA%UtnS3;{oK5QsKe%7h!!}@R2YvDEl6Wp!}rhpG-|fK zO1bxd&v{?p($BqypV~~HNENJ+TWT}oSRo@e{*iD}o5yjFpK#iC zs@B5StHj=@*&7O?iC*q()8(wydO3X-5C^llP;GFGA{0_BZ_HPJKThXA3p1kw*NDxb zO&yJl@Gr6qDYm#gCgn;--(bJ&uQGjCORklePV{z`5=t+#yCwJ3k*xNlFmz}dV;4WU z(->z1o(G*jt#Wr!4D@xXpE?+^n&X;71%E;dROuXRR-v-p%79ht;8Uye3N(XooTZMf zo+hYoa;?6U!iELnPpT!TxE?YM%6bF>h_NiJunaHDZz!vV@2f2CR-TOBn>GW!=W&&g)%mBF9q`R9)lnv3% zMI2co9#HpZ<_5fwXX*t8@DMIwQ` zl^h%WmTEIB{|F-w3S;Gm=BKbmEiW&_$S)ry0@x0}u8=2o>l8Zg$Xu}x@pqr_Jym8BcUW+bU+#}Ub znQ_|am8Zpfi(lG-+RD|*793ZH0w9}5Z|6D<)Zva-_OZPzG;NLQ1ohGV#t~&(4$8bg zm|qW-jhle!uNCkp4T)n_X2s8)+$9}DE8P7H{W*!f%d+adrr;Z>7E{BnC`vA52}P%qN}1at@U$)gsk0D&F$Sz(!}V{CJQPI;7RyHAhu8Jf9<5A1g)AZd}O9 z!WwSpB%`)@-?8JMer^Y zV<5|wNzdh;Mu+Py`tka9^^Dvl#R{K=1qx3ZL~Rj08>UWql&?|(hF+-noyi++Lm~Y# z#3ilJb)AFdSKv}7?h$g+AZTf_@i$Q-rgiqH438OlEFY6Kkk78DR6bn1kGZnP^s=ZI zM6s{Fj97y1s^#*zDbgmh(2)22p?$F`c9mR?>Q~seUt!#oxCQIZ#;OMG#btO^BN^>> z9^aXdl1KiSRuY+0oQE4k$VW6OI8&g;acak=+u>D)wNECorvfm|Rudz}8*Z%cE3fxc zX>v-6=89nr{0{zD;45LwOYj(V9u-tf=YGp4orygi^#V%>XE#v!O+z&{z!kcxo$aiq z5wHAdP?&bLTzmEW+VW`lkUjzBxH5l4SJ}62sQmTMs?TyG_u~CX?J4A!9}9;uk83f) zOzMRRh1N3Q?fND|jOkqM3YPF{qbj-p{F4W6ja__Bo1UIL0Vac+2Ij$vVHqG)WPJl1 z3p&7wCst!ObBHV4Wy~HWx1|ELVv-AzNz1sl&Y3z^gKMpSE7KsR-fYL2oIOLwTRVAj zLPsqr!3cYjPfc5=T1tk#&J(A{zmDKkGiG_>2avB+j?DL(d?V1F0X8t5kYS+FAEG-i z=i9biz5a4AGf(E6&08ygr{Z2sqqrjzP2NIke81kFF#++qq>M~1thKC7{Zh^lD_YDI zSbCaveihQOu0>J1-JsWN$zOa4t8#$1?$iA_1sAIT8x>F5Op)ENASdN4rp;C>sJaWg z^}85VK6MxhDka=Z3duUj;|fPf)1c)?rn(HjI`IXSFT%B?37r-BJAw0gr${ zPMEq{k!}8bG38|-`)Z|wfkm9+<+)`blb-Ww1$Y^G4wD~mAd2X76_ACT1^HLluQHCn z^WsaW`JbMtZ2TgoYR_AzPPuolPStji9hM7*jlSkj(ZwulmcnQv!c8<4WhsaVpGurM z+H_@3@((A_6M=z zkU39f8^p}~matVOCw^Efe$R- z!qp|#CDO^}E3k$!SC?Q&xqZ^jk`aP|M`c>mmNqT%1(c}pyLhRx^*W_WX|u_JJqemk?Nsv3`C9~#E;a3rqc6pNgd>hHrYhYHP2+f?0F}zpRNNS zT|kRu$}YDXz;ik%oCC@VLmGxK)`Wc7@-Yp));24g5m?Gu%WpTTm7dOUEwzP$v=~N9 zQwx-2F4gO5jxp{!msJ0E&dU%Si(Zu{F4`dd$l6=z9<2%JWG%Hmm#OK*E9soll7A z%(H>0mSD-T26- zdH)_DF=IBp+f6tpg8`kLC2YG&YVYZiT=PO%Q6=PFn+U6K%g8YCaA5KL zx`ldAuzY87K-`A{+Ts+u>bB7{NnBmNMqg4Y#0~ifI^JNsoDHqDyu!XO>rX!0O=MHH zy{u>2TxmS&Tt)KeAoqAe{M`cdS2sa(fOl`9E#I1&XQGbG8~^43i1TV_T>6_G_x5&M zbP1{uD`dP|*tB0MzxqW<62r0XlHn7CV6jtrY#W;0s&z7cofv{F;r{8ta*0<$hD5e4_psBf{-mjx8&Py`t9sd$wn{? zh*)+EVhW=Bg*$Czw-GpWn3+$dnOs`pn@5$_T0yR)CZ7Z$rZAlUF)a*)0K^ODHPHn! zE=kBeg-|UBYmn3U<;lnV0K_|7zVVM}-Wiqv@eIt9b{y;gS*5tJk~VQ|uqlV9ZJot;&)DysRD<`gJ)|DiZBAUC%Wvy^vkcqQW4a4e8S10f zn_1EFysj}f2k9DP=EOA6Yk7Yx;pdrCf_PQ><<{fJCSZX*91R%^F=Nq)qZ6mR-$z;i zSbTb(?yXPQLkBQ#X`pC!I*msM!5aQ%Mh7m>;J1q*AOD3QIw@H!Ya7ZEM@(5N7BcLJ zT+YJFEvMd8nLqu)a>8YFiP2arLtJ837LM_SXNt}C8(i%-iqgAU*a6JtYQwOB<|5BQ zZ_^V2`Q`aq9g8;*jaLtaDM1dv4v?aflXX{FnXH6MT+6FgNyah7n}gIy1b{9yFCdTV zk2(`}G}uRTYTlvTT?RpZm{BIFR*Oj4`%`+8~j*tSg4m2u+)Un2dsa{9g?>C1={AG%k{fo^`uWcZ&e8fwLi)J_G`Anu53## zJ+DTS7+GHc4FXDiV#TByz!Hg>>33(U+{SiBpCWSG6NV6rFs+o43Em;0tua4Ql=Ay( zyY}dIURt+AY2sOTqNIGKiUd|g{RPJp(bf*kr@pIRId0??Y4^ik=Gi#~YZi^wl%PK1 zx@)Yi%LI|oN+D5OIka5X?@D>R#0to1;=_1GYVs;d!$DH;3k#-|wipQuSe4?=hpGp} z4(#Ho_%tVO;}6!qwF;;j25hUlC#T9ookCk@f-Uw5*)JA3it0gq*Xosv3d*=ickCA~ z*Q2%cxE7{O)`7rLd!S0xdX-OEZTOp8%?ea!6Mz5W9G>#n{yE3iCDjlY;TIztBFIhD zlaA1*#wOH*o3i*Z3n)IFzQ?uaqM?O-;L|AuQ+s2ij?U(0Rb`9kG`m;qdQxG|N7hDB zK^>fstmcOuYhC}N-4U*WJx}B`eFCf;J@hr5c&H-Uh8VRGZ_zMj1R!AzyOC;|##2Y4 zy0l(@?91}0+F%|IQ#-S2eQtC`)7WW4E`3|mp$`i^jo7RYP0xZ8P|y1TuFYd_o`fpN=X z!GT+nP(aCF!nU?Es6X>>r&II%@D0;Zuc?e54t%8E##}fbF2N~m-eYj9ed41xp4ce~ zJA=J$`SY(*&OdDME20~`Y6^qgx>sTc-A<1`sAVjjBqjUrmK~L0&?Em4-hbm*m=lox zoA%w*gZf>1#`sjqBpt_x$LQkVd_TA*ai0UJH9$8W0V*TRmn4)RZIfVDEe)nWzdwNrJ6MY5Qv_q!cb4 znfb%?Mf2rQ)sRk>wSx$vugY>(xQUoy2J9rfm03b4_nfHs;t+^Oj_&z3@yp#MtpHbi zpYRI_jLoT4+u#lwUAz{3%6maCcDcz^t#-aSO+G}6`(?MxHY&`1Q*7?u(}VkmUrrwlv{tlj zGIctSD{pA+f>!&tWw+akePX&hqG z@TcJMDa3;wQw2-=l-F9O0^wel>2N-mRzBy{aoskJApPi!meUfw@;m?Dg%}P{QB}9F zqkeTpx3Em%uq?k#RZcUf*Timlif5!Hm$Yw>B9sJBr=Euc1ma9@1h4!N#|z#JV>Mt- z-D)?;!b}MF8!}OV6dzYktHs0ya1w_Lu^oq2ZteN*L@qWz2dcPUu5S+Vdj51`-=D00 zrp#mml!Kzboj-MTJ=i>? zy(5G_z_qE^mcNl$%kEmEMU273Msn4e;87r!27hg@T_@8DlZ6#Bi>z}}Jz5!A^s`;2 zwyDd!$blaF25ET6!4D5VtdvQl8`OpcpoDO%`An&`)B9w@y&Obp~R zQgd8YRKh3dD;^o{H%Nooi(oSJ|74a&jTzOEX(fp!VZe#WOsauAcQ2xrps0j2wTla* z<7$=8JB7P_kvd_#*6Q@t_jnn*w&ORpVoe9MTC7o+OOzql2vP4dH7Z8{cTpJ)MsN%n zOd?O8+AnU!Ok2@X#$(m$p-FM&22FN8YK_BA&10{r>H9Hz&2Dwk2Z-Z+T$n`*tLM&? z&a;h`m{D)N#(N{C`geBbCDe=9JgOyv;;~4yvx^`}b%Q)~4K3xdm3FV#c5xa8M3=X< zxgfYzN&vOgi@44R8}a#+*Ayp*?6gRQ`(~Qq5Pvywn%{9dNtIfa<=#2|D zGo6wmJJYKkev@U%N@0z#lsG`8GN$kPLk$jyC!!?3$hM$<(rR47>*7o~*H~0${&B;e z9@j6<(UN0TQ03B@ipOdw9t>)Hj;h~`XK%wMl0t#>http)E!(N5S{9&n6;V5xMi4R) z4>IVE&mxHbYydHUtJ5oKt$@dGJk|}hz~XiLiv%^0`=Sr-kk_XD=KcCXqif2e>ovON zZuULcke{62%lGp3FYDL*BL9=kqxEC9Je&#MMK&{M zN8pCSgO!+;N7R8BUO9N2T*S4WeFeRMv|vVoAS#=@L8{=1__{Al8{Et{G=g$_39kU9 zn@DV5h9s%pud*Eg7>VG}dYoKTGW(7U-E!FFz{wTs&jOw?Lz7$)OcA06mszY*!+=k$ zKlsGsE;{O>S`qRN=>&`uB81c;8ZIlGT)QeXtnxz0LhUAZGJ1Gq;uLeO5GUP(+7R~H zVzxUdaSf>;8XGfRKi4<~R?)=8_N9c)QKQuT;sT9JOE2R@QIBN+=zc=Qz$M+8s?<5_ zbnAk3^u$vBJlMbdZu1--a2pi*o;B`9T(vOyn0N0PADCsFwYwXq!J)FK;v{K#;_wU~ zEL2onM_+fBcMV%kImz7isMcI^FzoLBXq5a2xU00iutF`k24HHD@@U=U@1S#{pQvg8 zOIIQ`=RZ@iPUJLv^wNeg9~7t>mC&WEpd_;>YROkDrX6_dw0KVDsn#5se5=k({voIU z;uJW~Ja|Gy92(No)f4fdone&>Q(1H>DYw=a6_?af;XM4Pw-lmJs$b_3;lPC^1HVWFBM&jM(O1l*)v|+%Wh#{N=#G^?BaTF@#2=wl*Y*k*U zl|yK#(b*(V0^)&r4zXUpKC(n->9D?jmvfc{SK6yRd}NA8dzVZjx&j?+P+!Dru!*5Y zS`X1zrh&BP)U`k0WtcWvi&Do?VZw_?zXh307%wePaT6S-ULF!uqiYxRQa@!Gf|(VS ze3eQFqMPt8vP~9$sb4;Ny*U9oh>Kn+dFxCjx5}n#D@#$!fD*d5xAR8iwT;7!Qx9*K zYCAgAF^yTnQnT2XZ$^XR_U?ef0!vb3&plf8p0k~uAiec{nlzjN3#rPVN80zzP}NUr zYv-Nbxk+7u%I>$!NoeX-gr#a==Lc$gMPZ+%a>f6I!#iuZ5NN@#{@cL1;n8oc8XUm&i@G$;G z@a%GOJ8k9*F)A0Y{KkSXyjrjzKSbZ0Z zD!zUBFsWmqpc0zgv>>rlKID%eIu9qjSIs|4vpR5NRrCM>%3qoce65{j&_jm5Vf@em zG9TK?!1#u%Pp%$dg(lK3ht}H4g=lgfX3Gu^@4bMhyc>>Ox13Ohr)L#upEcW;W?2v# zUvyv@@8l5+*I8dZXFh0~j=V{4vA!vCUfI-Uwn{tM!cXY0o@CQ(*TV2#mb-b$jkNSslt7RC+7Pdo~KZ+W;=i7mitP_F3*u`FB}gH zk?8?l$pB_*C0-H^Y$fXyLO2 zrj=B@#1|e%<+82A0d&Kd+po*VW-Q321Nyb!Yw>Pz5tiRBB(d_Fp4<~nBT6C1w zo+n*gL8jSHo39peWW>^O)?f%|9zL%=SCcMppLRJqM@e^EZtmZuJSoVTvjYC=e5N&w z=G!@x zqp~WClUDPSqE>0vS@A7)RJB?*nCP@IALjeAs>#L4HK-}>B{1{4ldbr-5pM7@x^A=|EP)U{y#SL|Tn zk9n~(*mWWV3-AC@a})|B%K!%r7qw|aZJNMeu;brzQ$8f9wykHe>zIp+pCpVV3iRvx z8mXO9+A8I&dU3MITWxgUPW{WF2XG|sA@4KtD>Fnoxuef!G4*3Rb*p!#8Dc@{;g;^C zYdd$TPL{=>M!83^8A^Y>N{M#aW#BGTGJL-#SrWsur}Z)*D^O?CSZhfeEqgNoxr$q_ z-0>lCx-!OQig4gKk3xcSPFvw5B9P5ej9S!8-%4&pH-oYY)0Bo42c23!J}*&wa5Z}M zuFBq~#jKHG^m4U!7LF$HoZT=6mD#TY#F(9%=C`k;hC&Y0rx#QvFzQfK|Mp6LTFnM zWM*x3n7Htsv>F{=g5M7r8Z4IZAT z+XPTrUdaBcQvQ3>)8c4z=g^|b=1zIEckuNmUViSag$;aZisuZ9ZM$P<`O3S1pFq5- zMq#^v(0oyhO5@Y0b$TB6rq~~h9E5szp5#H9F49!ihI{b|l+!m3T3o;HRX_UP^wyG` zN-V+~*fs(!%?((^(U1$VVP%rw{|v_T+abA9?YMHKrhS%-xAKbBRHofQVs-&nI-Q3D z-gzy=MP}Z-3wYQxlKrwzIrbv(5Vmem$t-M>0e$+@?MwF4R#XU=W#r37M5^Ri$HgI2 z0cL73STMSrjA3S|q~Fd`il%hN}1{v6rN zXG3fveZ*3_c0t12t*w6Wp#D?Kye_J+pFjMSIE^~A_1aKY6WIh)M-P{yW|~DV>=$QR z85%FlE-(_>|iJj zEqGy$NR8(L%%Z~-Iy@7$mKl4)e}#JG`}8uOM%A0!rb%@Ks0~alocoP zU#AUh|GiH>muEV)H)BJ*&l3ru$=6#w;1r0R+mD9Q-M)c#0|^cZR2gw7sS?A1l0$Yi z*CV?$hqm`qdhUdq&`8h)wG^!M;*m;1dEAey3hi~|+j`wk#Y36r38nq@>{{K~FJpYY zj3iQZFl9;MTzfkJqqLeOZB-B->@YhD1x{<)tUcI6*|0?oW zw_UroMqxt9cU)Cx(6-Z%Qo_JG7@$9ptkaouI3?TCm&SXe1}3c^*AH-v`b9lfVJggi zrE=xXoynLkjq@C>9OrG*z0u?A`VHoD_O^8lhbZgLC%;aqKbzoRI<#X#7jFXg^#|VM zvhR5HYSV08n>UeW@d@ELdRg(mNP9=5dhlLCy#AJoYkstLFX`Vt(U(RG?5Fi#wv--a zE-yc@uR_$-6l-#5DF>NloYJ4@+gq8bg!QtOTw_qP6hrhs?!_dTB{~&`Mp}`(amig6 zvf8TB?TWUgom@srEj_d&PuEO1RUA!HU98;W{N}<9LDs;VpVt8Yo!XWJ4@ZVDioNqC z_}0=t7f}yS|C2G!cE5uqwqANmdGl%M@23VW0k;ODAJDddpSZQ!#ypp(TdvxQASbtLt1J&}yGy0JOS?O4RXsJ<;$spMv07@5{b(Vu_>v_N zsxZJi)sHliR)`xzUqtq?zoLx}uI`|J!+wXm>Jx-!1*xje7AHNO%2^A0BB?e;9&^^ulOd<#rBJriz{yvr zrpN%CT9&qDeu(Ns*iA8G)_FAUJ=n;kUO2Vw5v3c_YgUWLp^?5Motw96s@Ll7#}?fcnswo)x;9qTd3c9ae5u2n{ZiL3tT@XM%hEq*n9Z#@5UPxR zh~E7RGz<~~Z{H>qw0_PM(jx&wHuw@5G4hFs2!P&fV!X;*fc44scd4AJviY7Dw6&^~ z)O9U$Yy}}Qa0qSHD6uT+6>gkmsQ^LG&hD*joG>t=DC2k*^a8;cja|Ont|X~wjy>_(uFbh6@^wVpD8>SV6DiqPMWj05S{j?Qd<`O+isaf?*IW zBXd~(LaZpS@cqY1Ey_HoB3g*<-!?^B6Ko$p1B#ST*Y!~9A+dFoP{Ti#ap7!uOeV&| z*qQ>eC5*%Oq@O9Q>Ua1^q{caBQ)rA97w%Sdraex4J4UsqPAB6&<`>_{XDpeF4%U7! zQhs<&js#>{6H#tw6j~SfiMqP@LciBu3BaXIo5TAyWuK7ny8BMDyFI7&b?@$Zzm)LW zG*o!n#P0N*FE3F(8VhEi7Re$#uKOVbT$=CtaAF*q(D4BeO#SmQ%3;G{e_E}q)LvAPI(Sz?M@97EXiQN7TM$jm%_zIUH3+j-XI8@f(s|n7W(o2j4pUPu<-8Zh1MAFLU|shVp!|rdGr5#2Y_BsO zA)#wT=!!daZ@p;&zgS}N@{I!$H6aRqnMC>V=uvC5?nAx3LH}i%efdD;%}yHHcEn@8 zk#D9NpB`Nbl;n>uu}h>JJZH|WtNXQVSf2(PG&7oB*=IHIbyPs{xlETAI634dHk(wG zIy;z{SjnjR)U-{^vtH3`eV(ujiBwsJCP?B8v2>P*9fmwZJG0LEBpg^xX5CXWte3tr zjM6q8OU;x0w@6{85y6D4+Et5iDo6~^&z)f^8R!g@E)b{N_y{dBpMAgcUYwtjZBBI{B51mn#WG%`f}Qk?pikAdwH z?;e;sU;l_F#0j>khti%WJq!fc0JpQS7tu$`K;JeRuUnFL3fh&`avzO=kgs?sKC&x| zLr&EKQ*?-UZQrT+;YlL7a0u|P?)>j2-N`f9Z?;b%venQax;64DYH4BMOdu?NO^QL$ zMq@F!jW)=hj7oRJjT;b_NQ+Z!y_W#L_OXn6SXKL$?+1NGb#y^S>skFw#5x;&T)@1( zrsa7DYKU|H;R`Kfp7iDaQFK8K&4dmZ4-2Thf zyGgh1hh?iEV?DvI4*hCk6{2t?T_d{GqH{wgF*%Jq5=MO0v53%yi7!(_`HE<2V4A?9 z*DO@saNyHW?3{~{#CufE?$!uBk=W)_Yo3CEdu6O`FY<_94#O|0}{;lD?+Z2 z?o3Ps^OF{PlG25Z5N;*8WE$Klp?vN-2D&uAduNJF3#yxWZ;``7MLDy`L$`==YF;Q( zHVDb$q+k~-72!xG*>S|EUzK*Q*a7o zJ?}-b%}`EvhFg2;LjF0-YzA*wund#5@#!b)BVAf3gilH)je|Kkqt6sgj3e?Vc6iyd z;Wr%zY3%TXPp?efgqOVh39*TEXb6%ETUlKN)4^wTQ8<-O@N*mu?AsFN{2PTk92mGM zF)H%CHn~Qa-jFMOtFSUa7}M1BbSC2%g@{n0rB)pY_%0TUAv5*vTWf^rofU;v@0??| z$)c;*AJA6x+4I{aytx`~A&*Jta@4xTKn&|us zuHiV4JJ-J}(=XDSqzDW&WfnRv^?%%f4G?_VKgt+ycY4%7-A$)&(5~k}MwR2yP zWq@{NRZx-qCC3v;Y}`R!Vom7+4fo55fIMA%>^Tgg|RXfi5nY3r%fHYiX zOQC9;{Rm@dn}^W99#Bq@JLAIZ_(M+1J+caC{-Zc$$p;DZkS46m5(YR4M$)fNx7&D< zQL5aNaQkN8LVE8my7qSCZW>evQ=mxm(6G%z1U_Ydaca^}2Or@gq9_>aXnIfLhuAR+ zz*^@xIpu(b2z?5~g8+KW790uouFl=X=TFsX3Q0@-&ZG+v4oIp>v&L`l0jKPypGR8L z_A#?mgfNhi<2DT;IcH`WMqSI777WQ*ZWj8owc!HCx{TNfu->ZN2XEuQ#2xkSp{JZ&|qhfa=(L7Gg;+uNc!U@uO{=LflPf1?MI4gVB<=w*_{t(T4 zjYHfktxTfr;eMmeo44Hm`OM)04cW&yWq)E%EcH%s-g29y!2>!sbSnS)VI3mI5ruHv zCcC^dCuXG>rJDc<#Mw&#h$o?rLvFIzC)UO|l~h#gFwADTw{~?xuB-^112I9KB&NTt zY;0Thz<~W#M{CA2O>mxw_wZ)&sr#>tHSFjaa15S7h|j9#3QlP@-9(xa4{$;ZMZ=X# zO~6ZG-<2{6CHSO2c5cotJ$$n>#qat6E~S9*-s{G7$;N^09JrKVC>qPHGl@$OOWW0r zK05`{yN01KA&ScCSgET#_Oc0a%+g$5gA(i@kjrs8GZ7;m(Gd*SB5&Aiwac~_WT2Hx zhRZA|j!qq_{lP!5-(Y=+_7xWui%;6Z-a#^d7ngB?M}g7@9omR-$oOL`alWxmy*_~~ zwuu!7u`bQK?Z2@C--M4g=HwHO_9f3i+YGG+Gbw_hTyib=A zkM6=JL{|iMpx1?TnebzzXuu8(KMTSC0=06 zHWl;2;^#?VRWa3|`Q4$GR9_Iyff>b`WuWDtOP7T}ex2hd)~V@id$=^2w0P3Ym~i}B zcKe8KSz=k{

vGU=92i4!NDMrRHdyXnKVX*BvJ`6*Sbnq`c03f;%u%t&fR(xWxDu0{W=Liczsf)MqcE~>K&|21&#v0Sir{bu=a+BN*P zjbvtHHsu$P^~x`J`9nMGdGJbEr(gJZjc{V`+gN(h82W#Y&zMZGFRhg_!E zN>bu`tnHg&K@g6e`T;m;n1z6F@fCCV<<1C4TF1jBt9aCpiXO=AtdDrcUeGf~twI^R zzCTe%f~#aO^5kU54Bj}Z@pp90Zo=DZ(BZOu&?R({R%2!@;@*6W3$vjJZ`JcEM33PM zvd~E#5x@h-3gexjbWPsEP3McU<+e*8Ehvl?fGppP#adHxgvu&cPc#wyV+%x?7jFJo@*O>(5O<(GZ8u-I=%*g%~_h&3TE5OghvelDy*w5iVXpmb}e)+ zHHmWMvZgTOVq=O@k#?p+F}51uDQ{XVqSoq2`xR}O(;u3fD-Q1Z*0(lD)V^8biP2dS zDGCMWI z7ZMFe%Z`qlNrRM%{JmpKggTHy&0Jz_)=!x#E#70$dBTs^tWBTl*Y5e!<|Z(VTMj!y zJdnK?>)oS2&Jg{s4^Nk6)xz{~yW$1xcAPND&604XOPYo7L^W6ED~^zyf>#?&JD?i| znksGNE$yEkU*!#SHFyY5J`HYD;d;*%W-ClS>|9GAq4i$Csc`N;T=7dF(e(%nV8JNB z9g|&SOBio+uH39nG9BK*poq6DwjACyRD!`m@Ys|oMT?l)mD3;YBYCbos@AJ+iJQh4 zbJq$x>kPVt%bg?b$VHc%zD11}c@Q5#VwK%VHHHbHh{{UtOT`$%6`7!GD;z%&`rgfd z8^qIBf=f@f@y;swb?(QHUnvn9DO-f|J+_3XstyBLULH8cphBA-y7haE963Ha zb@6bHj-e_7=UDj#XXX=XNCCn^UVtX#rbcB;4*_vrH&kuJ!BaW{Zi#g919KJuvO42@xee}R=B~=iK zY2d@8*R3O|@@n?{4({`xjeIYb$M05I|Aun@11@qqhV?y$^(Fg9oMOBLU}`-)r@f5} zM(_#` zp9x_C-ga#hV)&9U)Rok`$4VCy2CW{WYF68^(4<}EUdG<^)mdU2$^P;X?rJ)>?U`%3 zr@Ky0R)&dj?mQflQXAbqhZlg(=B^r|;%-!N;6yrn#b3m1pYW~`2#f)t6cIs6kV&$4hm(gH#6%U>0 zy6^$b8(z4H2nJof1+SVcV2^j=w)aEk=?X?IS@4D7(G_g&1uq3f6Q=Gs(dX8?Ndb_mWsHpTC;3wXUq{dY=#ulk|-v`A{w5z2F6FY}*C``Y^zGT8$IL1Q}xX)~m(*%$|U7YX!N4d;$vU6D>1 zZ9~?25o=)ojqJLkZwgq-ad8$es$x5nUA@%vW3gucJL^z#+s(>K z2r+LnWdHCzGj8P9rW=1m=``FxUzA}_WbjAbiiiVdn^jDNE(cG?s;a;6XSzN1%&S-p z+53eG`csc;JV&;F=K%~XMGP@u8I|UeN6#o=yboSxYLhWRpBFl&EZ~7tunkKs7GdE? zPc|e^YyS5UF7kr(cDr*+t8%Odq3k+Nx`y6gHn>Cm10E?_2DLy(b4cnqoCV$w3xD0T z!ghq1OC8}RGnPB_8~v@zb{0C>iB;AWLZ~YDp$e<&C-Y55)-z*<%@ONSkU|HJyEG+^ zrTY*Ne#SJhEj3hxO4-;Y^Rog^*fQtqc3PqUiJM<~%rIft(x`9#5QkBB>n0+iU`9#i z8^({yf!YbZbn6%sqU+EgdZV|z+^+$HY^A70eOUZI-c3B35#elHT0MmHtq^!LnQM%M zFViCZozE{ovN^<<|4d7lVf1J1$p0ZJI6(x3clJAPbF$h-H|K#^e>@|fwIHJPs%rf- z+a~wIYoYB>pFR?Ys7|PJXxG$_Opk>DfQ@4E&$ZLR{vkX344F83xCEE*4P$X&7Y&Ol z6v`i}v#36N%|lk)HhUW|rJ}-HyP~<pRGFQW79Qu^ibh6f(mJAx@61FLpwxumoU za)U}eT(ag&HiBQSZO_4+Qw1A?Q_;`5z|Y^eWZ15UliGXrJ*5Z|hKC13!QC3*GW#WR z+kR6+%>{Vv#ONi7zd65$cHPZS_b+y1#@ym4;Uci!+sN1aKATJzw@zSfz7jcMbwew1 z<_akpCa=_K_0RQ*9}a0Jct7+26?f$tMoQ+IRp|09^=0}E?pn14)ew!*mHl=nU8L^7 zJG80vv2qqDmI*OvC8i=`M(W+t=Stlu^D@!8&Wl-!pGOghWrcaqj8^L!vNIN z`C3%m>UTdw(3?6!n_oLGxTPj<3?c$YN#`EvbAW9INoxOP^jo#PoU{qhJRK_X+clEN;8Nvas6zx785G?=@{d zAHnU5qVYf6lVf%w3e|NR50MVA^VL(--dX)&=<%`GIVIEqmVVSI(PA9819Qh53`t_F z;p&e_kEO_YjdKbC>a?+jRPs8qhAgjrgx}@d)jPZ2e|mCxcLHaYlMXTOGW|GxXqUaR z|2*>6rFd4|k`X7LFxC9r8!o1uZ~&ED+3y9}+i%eRXdcS}x|?JQc2Gf9z$F#+zwLN) zX55`Kg)TpO3N0E;C&12KWDMEGSZ9I50`dc2z1z~~*C-DF+ixzE9C7#o#wq<*HjF?` zq>o587;nGU4k}E$isl20KFt&Ss)6h)Z?$!WVwkk65Ntv?o*#>JZh=gL6zj0iY1kaO zzt9k0_ij=8ohHANqu*cN;gSoJ@{l~N0`0Ov2K}W^=fJgi)!gL_}Yxvx(UCBhjIku`F5&)^O5epCo@Z@wy|=Ht{;+Wm@VGei)Bn|HdgXsIsT8DV8OXWqL~fBTra%7hG|#=dKhKN}6cv3sV8Jk-CFbP45kv0ZPJjEhsNT zi%3kE{LN>QIA4k@$Q6fgo}{ravqoHg2{;enNC@QCp?EjJzoy%++^B)pQJOO9a+cu2X}#`~e; z;8cMDm0A2H({%B&JXWr;nbO9w+Wpjnndu;A>0p+pqoqo!RllTYFR~h6o#oDTy)M(J zt*LYGlMM9$7EZX10ApmwWP@ci?3WxxK94Kjq44uG02(T`=7_qrzE=X3oGEE3&bt5# zB#_|VmIB_Qbq<4+0G2yJwYL08oO$sjeH8Vp)iW)_?gvlO)*WW zSxo=a?#;p7zvA|FbqcfxKXcGoc;-~c8BOp|_=`y~bvrXAk1ANTW6P_&>-z2x|IeFtGq8tW&-BDGW$JjhS*nCI<pLRr!L~X2HR0anC!(uMh~Uj(WZXZorWN*{rTxUm9NaTAiNJAyPnJ@9O388b4!Vi= z%fztYC|zRK_}p4Z$q#vxEIJRnI*R;FMB$PhL* zw;qVa1rm~6niOe)jW}WOwd2yH(Ap(B)z~luS30k4Sd1OvtJ|)th3!i0)jhQ~F~y^Jj18s%@no?>MER|_DV9pV~f zuen`;a%zU@(a;)yd+~R5kpO`I;BAwt;q(@XxaR1nhdVsttjlv};K?buv-GKyJ!1}d*=5Ak$PZNqp3-BxFSfk+ z!iht-`UeZ4e1TFvxZYl!U21YfJ1v|$e$ttwkbT=`_6ro34GL(8ru-d|2DK%8Z*0KM z{Oj_qIvZWTB#BR%T?v*FEiA}#hofs+WT?|GG4<=5(07VF5nmb7h&UPQkdMavhPXEv z+TPS(wDeI>L3K{aNS~4GSo1kNVf)VlhyBjNpnDEZTh18%wUuWr4!(Op(F3pkKSm_H zzq+XykjmTc(d%#)q~oMKn!@a=?qa;Yb8ugv(qTeW<^&}?q-a=R&a062F&62d>gjlu zo;itjW*)yzpOe6dDy)}N2}abIkH~aY)83_)?gTmCLBaU$!&eFQ)3w}E#t2$$7_^pe zib?XLjrHJWK)O5kpb>OvU#;&uO0<1t4}`wogTllF)(ZeB{MO9!?5sn_2X6y~8{DwC+jo0kfrR9d|pea2rf@L=u`;_dcLJ-1h02m-*vN!8^*AG}=n z@rdZoh5B~Y6fLpF`Y(@+X@I0b0%iMs6;cyonKVXa4~!%l7R(Cbf_sl55fQQH#}5jd z{OquN`4?TXvT=kQ`TjnmL-QdIe#3;Z{0#ReXZ7|q!?v?DThp)CbM>OHhq3!>EzAkO z-GF1SL0hu)Rb*<6r+Uf;2KOvnt+wFxyj3^&mO+D-&sMA;y4O9?Ncy{u#g>MGj-wUT zGt(K4!!nqs<#e#Gd+T()8zN}JFA+R>rxJ%k zV75KaOu~1*W(QU40fQEIsO21?deJWNp zK}XMV!RgVL*1o&&AWKnI+_k2Y`VyYR80r<3j?tQ7VETcski){dv$y%3iS7Vg4=IhD z*Yl6|C5+s?fkV*~Ju0B|v$^9n+p6ytk;gt)fj+TT2v?T%Xy^xYle)6|HL6&4*^!Qr zk{(k5vXF~ac~z<8XS^f}POx(I^hrEqN3&*!dmZSU!Y@9@P4d_2 zcmmp9PlH?T#cO-Cx7ogkfvO5TLa_g5lI(AqwM(vE&kXD*!99i;s4q$8YC-U%i;Ura zz?O)9538oY_GyhhJ@_?hl-hLVOjpHA-y10O$7h^{d~y572c zg)$ODI7lotxPuPS}rDh>`{JS(?*8wS zybZcu&)Gby%GFAB})IaAG$1w0u^^pU0glQ zt}q+PyRmF(^jbtT6wmOhm~VGHH0{pfIYDY&%vVc#8APb=7^ZEmBjF39e5b69DqY~3uJBLc%3}Xcg{ZOdX`NVFawa33 zEPW&i!0fk^N5fb_b&}<1YQOINaps*Dhxe3fb!Ii&f#|^u$ucQAd3PgfTWtE6Ucm2{ z&V>~RI=Q(ihVU8Tbaq0f8Z(ZwPszaSaFQ0?B-hU)=LV0vkM(*Ux~`wg?VSl~VrRjM zEa}ZnUv*s5yZ0cFn>m8D&#RCn7M16cay-(&zd%q8uhi;Kf4&tiC&g@vfW7&!xygE1 z%x@f+A{ez%Oa4~Dy4>M9$P%pC{b%iM-G2Fjn!7b6fn8#21j!wPVB2x8lWA$eB2C}e zJ0Qu?#w@5NS(aB{I`cegCUP@zk5>W+ZamS^{nC+ z&S+3#MB?SkipnGNvS4Chva zv&G8nnEE*maj0QRyOVtgh{u6=Szu+8~j?QiJYG&sJfSBdw%bEfby= zQrKujdNF`{yNp0b&Hc!mir+!>Mogoaf73OTDi3vnyWAFK0q#9u@3)e=6xpJrcyLSnAXL;2 zGp5G6ss$6g;mixv6E8;t3tueBAgEeAoOR|A@TB**KG`UIJTKw1(Opf8N@Hqcp{ZyVGq8_@>8F)Hfkt6OFIEq$pdA;Ksnn`M|Ac{w znR#bwDCFOFy%|M42cx=j-Tg@W@+4|(ch~64U+ODh@V}%%eih!UE0YOJL*%+~X&seo z{7;9-Ai?JxlfbCM=m?@(kN;dcNvU<%8Of-FOeRbs2?H57eSXi?9*|2Tf)OQd^Kl zSE)#Nr{oOWPL~!9tYQ@Adkl(r$$*ZoO>&v=&nP!XF!_71`|f@(oqcsphyir(3zyr` zU3o`|zvC`0!^WOqn@Fqr@bRuFdSP2xhr%}p6BY{wT87~?)zz)*>$s)H3jb!J5{?o@ zulH=dc`*Oi)S*w)`)F!>o&i-o&4#Rv&4y`~@*5_o`Xz)aZDU(H-y3ylSE zK(EUro#cA&B=>ZQSF+Uok1D5t+Sc2a?Kg|dw?c~4kZBLKE%yk8nVYtO-)kPipAAha zP}`@5AJ%+)S{BtmWOR_NoJ?z6C>YGPOUw!iq-Q-0b93Eo7-Ox)$@E6B*#Eil zxkBHg#)-9OU}O;lYv;#2x2ElIU6e4pUTL9Hilm$0@OAesilu0_Lbc{jDR;7jJK$Xw z4y0Un;%Ql5k@!QhOB**YWAOP>m4E!~1880E(!mdPxGAE=3-xns z7-RUhsd4#hm-8xgSDIwob2FQiW%*)J&Ij3faA^VkQq*wSP8ptTkSdNOBkQo4;o!rb z`0cKEl3@KET`7{NnBVQa$H`moKaPWyAv!d*<@f75gn{#*_w<|ZI*MA)1BW2&YU-5K zJy(8Yq3NB`wrOQYMCAnTa;N}iYc1Yx;y2sRO^V&yi%$rKI{kGbE%94ffMXX6o&Hmqc6rN-)^YxC8=4z{WM>1Mz^!k$2% zlkNowkNl@o3i8^W4*iErv$hEXf{;OAp3FI-WLifgo4X}BtO!AD5g4bASxjK5|q&)0O&4|!w;X6vhqbB?DM$?YfChz0VFVeH`b8i1{Z zsD!$5W3}A&5wO42iN!OP#B)n2dd5*fv>~OX?s(`hR&c&>Vt3_sqa<=8tITNPuf`kW z$`7968iCuzH5IV==^a9gaMq-aF*U)?!lJ5g|6p}AW>07+TaCn4 z()y#%>RWX*pq1wabxR4+xupU%J)?Vhf@WCekjYCQkT;hvr(m}>U zH!xANBj`WCv!SYE8S&^?x)2zePX7(D&wA&4);b*B2y?r69zaSj7w-wC@kj}R3rxBa zTQ7f&6F@*Jji@Da^XFQT>KWLo2N#y2WnmZyx4V_+;KpcssWyoWTuliR; z!Pta_W6KIQ%dNvDct=$Y(I&Yoy%vG&o15o92sta*g!zV1nEF=Q1!OA;4k#`E$!Fj% zrGNi2g&+HnWXMfJbU&y(s&3$N>^Jx`cZ6nu7O{(3`T6^~2E`nE9kXvky{^Na{X}Y- z)_1b9*jdK}kF5Sxi`5yO@zsn!jsn>ZjO&wrom0R5W+`~09wC&TubS$ie%4j9HKHW! ziFVZ%sRG&b<~F3;!qV%uKVn>x=U-DVI-sq6@$C@wX5{^8GJclOT&Cac*p{gGwVtTo zN_c*@ZYKde^zxeBa23C;iL*sj_YKhbZQ4B%$PWyCs=OMXaFW}$2=$O@9V9=!oTtxs z5Pm&F`QOJi>+^(fC2l9DB!9n_@H3$xoH7M1zE(0*&L6YZIeKSmnLQC1yF{$ymBc+olzT-Z!H3czX=r zNzV|><036pUe3kXzF(@xRa>hIGQ-XtiqvLZDDb4`yQgMXPhPkp?S6#EC?z_RN< z%k=0g9N~hw=n}mX_R{5#AbRdhmL5zrqXvsttM1ASz@_IHYscb59TMx}r9b4wJ!uiN z@KA_2C9r^02%eev+&D=6@eI^;@CMs2CDu54W7*~N9V=a)KB-+%UiEr1Ai#!WF#xND zyS{zr8kgGo16gl(n0fs}kfO&wal*Xk0WZ^8EgB2WFjYOg{)C~W&9F@)BNqzfI+$4!lLp-|?y zRpha!sHy|FEDLU(=7NO1*=oQDBM<^?N8i26?0o<@EZzCc!S}jD+x++BC_KGawCG*c z!5-%g@4C9hjvA{FkNVG+LGc`68wP8K3R6P|Ud)cc!xFGHwCzt(tz_O501X=v(c&RlC zjNR(^5hrtAf~@$v^*AKY2sq z21SH_elcmVbXU!H2ck>B5f!Cm4`P;}B)m0T-}mGgSt-+vw9JCD9uUw)KuT z-Aij;VNp4cA1_@*QUlIk#vj)^Cph?bmouMyl5A=^y=}64(ccGfcR0N0sDFQ1yj@Kj zmez{B%mL6EZtJ_DJzWU~~L^j}gycs9X1;Db*rH zmR_U51tuoAhu@2OL7_NhDM*o4g6Mtmk;vLa_td7t`G5xXMIRFias)%b_1F0A_T&}n z|Frz9uGgsbWnm1@@6N*MVMMN0o3j4jV%QDL7-9$GYMrBsGUkP(3bol5KA#!K7Hfi8 zBq@ph(*N{L*57Z72Nh+qJgYt(9z~WM=preTfu*|s0_95C8d49^LL4_@ zm+S!8=--~8U>*f^Q34=-3hkXtUt3T9`mg)?2jt&x zp5Kr!wxIpCHi#V(gE)I}=)$2NmhX;@NkjmWH6yL~ochi>ddj>ChuWmF~d%kI0tbAxyF7<5_ z`EBIwIGS=p=8}FES5_2CyzMuWpgZ#(d~kJGX`rCVt8X^SOh7GN`?g8h-yFSQOCZN< zUEWlkC&k_mpRjZ8_F|ET_t0GMPxA-f(#Z#EV1DB}Ut!jqQX!te*ryj=n&EhuoFZ1bp6rgL=t7n;%{GE(Q*3R(JPOe(vlg@ z+K=yBt&~-q(FM(0(9ct+Udb_Tk3%0j#7>|#cu(r=oJtectBm_NFthO3jrtD(+y;l^O6XIG+q_rarPuyD>t>o!RU);4 zGvY2cn-b;D2vsZ-!wy#hpi+~Y;MuMpZ&GXOI+?Mrk0-&HyVEiV(1>jO)hWX~Z0FI^ z39d}ax_8aBS&`Nvm8nRm)@`O(Wf7W?NV%IFHamloPwjW%|5A4&Q!(PXOQq9RnYXjT zVlfXScxZF~t2eq85Lk2CGWtX$dLhz$$n(e3j?;wS=#OeD2@u+KzhI7WjoEMDeMkL? z)6_DljmCxXx!M2XnZM53UbDfF)5)G)X_oKZ%VH-8OcBwu{OYM~;vq`!{Wo&!QRpQB z6qGIe5PW_$Vw_}21_r`SBL1d17xlkzSh=ITBK-bY);U(>E#E!x|BE#!&_pD)Gv1x! z6Z>AlBLJ@{HvvSGx`vj>#H^2EC7e%B6YPmDv9TwqVMK|GfgL@UqTDPW<>pk4l?QRs zI{>VpL7Bk!%q*zRa@x*OX$>9iaE4c>vlV(4@ph|$ih6G+l2h5j`b3PvmF5Xuy-UL2 zj|VN|cD8%XuecTIu55u$1pbpxQP`2_`7jw46H(Qr| z(ZImO*l~9g@9aN}!94+JjOU^@Ggqni-c=xoX@I!%^y|$|CFrdu5cTaTzh{yl;Pbt= z!qQ?$_kSF(k>T4fIMTlR)FLk3kpNxAQZ?o7z=^gyJ&#ZWgk$3!V`LJ_kGdnqK`Dna zG!d#t2`Z>(Ew~Q`u8U*OP(=rO8A<34Sey+byG%W2>r>jasK{dW_$FMzZFRT!aF#QL zGCTzKwg}-2bPk5uKh=tI}7<9%z2>IrNQE z@3!Yv!#&s5+2~)gk4eb3KmJdVlfVSBWqm{atvewcY}{y`1h=}{=y)VivLF_Ad)V3I zH{l`m1mSn^@zTDikMbl9a!|T-V;6ALqVMRoC}7xXe_BpD{c;TB*yZzhb@a zi-fJ7Qr7v!Xj~KmrOAY|IHJqOu8EpNVP3p(-iw~`Ye5t)#LCHzW$YWM)_s2 zZ`w9g`$mMVTQT;x8jABn4Y{q!oBQR}NVY#_Ht5~O8_0!MCkro~|Hjtd^KP-(OMPgz zDZ(uJuEI!T9Rj**)6d~hu#Br*M-OJjNB$w05?h+(I$}MLqI>8D7!(V&RUdG)74245 ztqW)isIAU-f+(pFe=(96J;f_&N%fV+uJ@02P}g!bhPg&4avMi^xJGm~%#J0xp{g-(oEiKPC2&AU|vlv3CN!=+P+KZ6REO5$}jTm-- z#f#$U!=}-T)l`TPdUaT9Wf&m6bq&u|CmPuP<)TR#CuHSYf4ze%;EvbP87v(uG)XUt z=!Z{(FgdWuW0FZiQNY@ISR^7#=k*Gyfij{}31sbdKmz(0fI9tAWdkoukyNT6@=I?r z8;KIUMrc~2)MV?Ypf%Wy2cdIdk4GK2GsbU{Ga@*lz6Hfw%H6N+4o#}9@p|v%ImRpl^xZfUq8XZXRtQIeR~A%ZrOy!O!YB2EZSld9 zDH=l4pZKx16(f4&c8Ill`)FT~4~bH0VuZt4Y{W||iQ%@q6M|BFvJI!zy-6wtQ*CP~ z^*fsNu=6LOU+#;k*geZjV+ZxRk1AE~V{A`3gpc8Smpo(^1z|tH{uoAT_Ee}b|Jx&| zhTOJB$sLi!?odW8D)n1A)$SvFI*xS~%qYTD_Ai_q4#g{asz6@GK>!p|Ka?EN-^+H^ z%C6RDcO~s+HRUt zLqVt4!hy@m$_d!V6Frj*+_Xje{ z3N6>gpfu%J1t5epQ z_PKU{X9!zL8(o(}Kp5U*%|mVuE{?;_!5-!ZQR#98QoU%HsBg!$K6!o+EplFvo*ADJ z;)1UJYq_*}gSTt@AizW?!tYg=WG_dBBhB5{6Q4ho!5rlg$NY-*AeV9cm3JCI*3b>X zbg*?I(?{-Z)2cbMAo-bwXcZtB61OHfTU#p7*{{QP!5csh~L)$)1@ zPorm5pjJJys-8bwNH@-Vgk!V78Eq=&)gnyc4`TU^L06&#EM7kPRTbX*7u*eypRNi1 zT;4zVPEO0?^wu;tGO1fYde%%>PH# zTSm1Nb?d@GiWDtUXen-`xHPyIEzsib1d0TA*W%LR1Su4Ex1hznXn^1pcZUS|IPbaV z-t&#I|Li||ti9IMHJ>>jm`H}?3sNiG1b>qmO|3^O+z5ITbJj1$FGm{PKjr7e@RwA3 zu{JHXeK3L5i~pdzMn$*&c*+Bbqb)N31q&yX3agW23$p&X*jJX=)A+~0dQNX*n!3Y| zmV0LGCrk6fClzD;Li<8_Ku^)y`drl-VR74Yz%Vrf-O;2rawLlA>bohg~01hAYz*t&AsBcM5qdR&%C7Zvh~t-& zO*HL52WWck9e-CF->>Qns`y~gOtk@u*%OF&j?^NN`=n{I= zvkqlsYrQxLg)H7NrZ@d~Ca%FOBgY+EjyN^j*ke}egWXq07P|UQy6rrr;GVhrHYin+!c5cePngsCOH9tC zAjMNvH@yV|?5x&hZ2r~xvN;#^8IM^j%~h~l_BT1Q6vJRhBnP56j>J!ZW?$ZVhi#Mm z`6YQfF$c{E#Vy};{UGDlNo&B&BqgB|Jisr$cf4|!k_ADbvrkp6F!QD1az@ao=*au# z+-Uh2@$h>}d`2|N1}+LPUO`(yikx=7bwFwV;)_M)D^L5Q5L=DGbLW|nV>66Uq+%r< z(Gjnaf0}+2M~WXbRY5D4R)2W5e`4wKw*12 z*6oY>x3MMVc#xJteI|5k3<>J69Gm{wY07cP+zDWycCuhft}aMrhj-iT5=6@g;qQ9< zxTzS;{3aw($%l9NWDHQpKPX<**ZhdGb{w!GI>9O_SJNU;H+tFcpkGav^?+t_Pky_G zM<34<61K1(CXlHVjXTnW~ivkR#FgtB!TZ`WUHtBQZo58b-^j0X^yUmbAaKSJ3T1sD+qZ-Ld;kmNW)3Upi- z0++jEG29|v7u?qa+|P4jki7eHRh|#-t`t>bgvu10HmiQ`?h;bKwXt@Z>1cHx+m>Blq+(*_?qm4S7%9Nbj z&UtYxyR49Ocm6PJh*b*}kHXf4n~ibieB0$i95wtd_Z)$-uoNj~8E!AGerZ?R!mgAY ze`r9rw0pL6rNRcux)P%NwSxUyY^J0BLfFS0`2vp`QZakqS+tNjA$5Ack2v-@p#@=Q zdvDu=kRoF#nEu-^5@lioOeNEWHh%6Ca|0D&s=!X~fH*wN=mq}tZDLv9bt2teVW1WJ zXPYtPSL4syF8iIz1fw!nzmJg1IYIjqIz;azR!v(LM5+z-Ltt;9zKUjj2?+KJxg2^Pw}p!IaJOqcB;H0Zigrs{0v4l8RhrkfqMh1=n*nxj?vdZ z2>jDSp<4ve$N5;VI_s6tj1?{AEP$nv_XN)m)4J3H@-);=|1-;!ONM>u-D38G?BJZL z8FD@@wk0MsLa6Xa=|{`w@W{_5S{FvNP}tWa=x4UZg$0lU95K@|UlWnb5XN#0gy%+3OtKiG-)JDX&j9s*>VBaS(!uQb69;YbqpJU6G zC0nKK3k^>`$3EvkRpT6{ATR&x8~Dj2_=fXcU__8yJlU#y;iP4-qt8fBAj9{jmMrY4 zL6|yq5;*_hW4LS;Xb=CD8bVH+mkJjH3l&P!5k?Zk^APGJV2|z9oUw%Avj|^xVufr=BCX_Y=3m6Z1~4j{LLD1M}5x)$8lP&v`xi zPnqsakZen@yTJick%10!$rc1ZGVyerLyq|Gfx^%@>1pq=rYso215={)Y6B*qUYvnX zRELmJag7h$XA&Ubh@GwMuH6~=fg@<8d=q#!kkWr$Evw<=X3}DJP`k$dIQG;#{249McNt?bU7TNbh8Bx_~r9-w-+4;y2O#cBHuX$ zMUcPp%xjWO^%$^*pL=2ZTI!Gf^&P8UKCrm306nybq><$>FtHDOQ5?MIowzp0o@l(! zLPJ$7!5*pg?;Io-Fb6$YmfJg|2YeM}S`b4~<}QgoN69MlDoeI#5*SO3Op+G4t$paI zI$HUfQv^p&inpv~>6l;N9Nh$Rz=dQUUc9hOkMGdkwPZhKkbQgo!_%I?O80(*`88g+ zX;S!rx{na1889pX)jC7!Wl(IaGtD25c%27?U{+us_r37VhwPEYrjWefWjlSN><+~S zD@F7HI|L)v?H$d9rlb7R3sYL#h8rD5@7bfO#yXU*ZHZ$I2ZBF>9Pz~W&3@T|h zNix+=cw^b|JAc0=&d0hEp&q18-v8 znt?gCBmDgQv}wJLToTvc(!E^o6jbG22Nln7tNqWww{mQ@a4m^K${$6ZOnqH8^_bzJT2D|<7F%h3<-=?i-29uN(GZH%K+^G8rGfIbeh#lkTMm?%Ex>240k*R(5Jj`7fQ9pH(=rH?}DsU0+4 z_mj!WVc5baX1LW3Ykc9UkDrSIOR@qfUy-g(_DT7tIW65`FVEXvqs4D8sX`kJ)0ArC zSRBlCpupiXEUH7=!b`7xBvM=6#Ha$f8u#Zg)qlL*8>U=e;c<*O0pZ;3ypP~4P&NiR z`M4LcT{52)%L(bm$z$|+Uj9j*7q1ORo#?Lx zC6E{&;hRQGJxIF}1bS#soUGtjw&}eKCf+w}Y$zydHQFlkS+*;p#%zz{7fnm2CK4)Z z?lpxhgR@w-dul5>4mxT+y|!AgyaB2%r1aOfi#@DsGo%5~8OYJl)s*J3mgoe|X&}VP z`yqD~lz4d_(+}ZgM;^v5y6m0t^`4vqLuTBmJFir(nu}W*xBZo-(ap%sYFL<{jk*4* zjfvyP6rkj^_q+47>PNoGswm^7O`l=7_E~wnhB71KOHM z#(i=mft!9^TZPH#IRQ*OCWsd)8t0FS>Gk%MrIIHtI*!gM>tJ-}bUf>+T z`VZREJNf1qu~V@epj{r5U*T~Iwx(JJ7CF)Q@B{A)rxZw%cD60c$Orh> zotP~sGCG4clI5xDm*`YS8~~Z-y`CPU31kZqRW72E-fTan*5nQ*@`f=@C%pGZ0a6E%`?Jz%yFH>5^`2A5~>&O4sRK?LvuPD z9Da`pfgx3Mlhe(Weag5^5X>3pR|8J&2f8A-JH*LIRcS1#9`=KGx!jqqqvkvQENt+@ zZ6e<1rav(}_Ep6tkTigQ#PH2u2W9IrTcoj5(-;uxp=`bwP$3v@wHkiX0=I>U{yyrM zbQ4_`kM24=#pj5i?**70{}zD6TojkS8XAtdTcI}ji;3+zTXbZ!tCQzpz?)wZu7kx@ zxS(PK8=S;i-+ujgaC&nR2X$r@`Qx*ZfpZ+82v*s6X_0{?Kgk z^Ai{e+)1C#@wdd6|r^G?<@&VkG@W#ZwmI|-E^8|z zW8m+#sTD^2Zq?;cST&_L6~M_ZkiIrFuL^BM1m9#BEuSZBFsGUUJ^y`0p43Nx#P6n) zwslS|J_FfQ_qWwBpZ13!bIL2P$EGEafVvK@OrN^WoV`Poel}B3gB$VeRc4cFmbBa8 z)LiX~JHXB7PufI2o0tt;Cd-5LH{k+kOxDUQ46|IrwMEWaAAcV1_VMBLsU^)%m)Y)m zYBh=ryy`A0I?_%bUrHG^1ru&M6bv&ZFs-sOY#j7b_hg;$(%qe^AI$fiE+qTjXE|yM za>^mUCC|y86S6Q2Q8>7m%W7!9AzhSvI}Pq!*E!aUAN+e{p#t}Z*QYdIU7CNgV3TeN zIcqPbayP7APj!Q}R(3%1)>K!pvzp~D zxcx44<&vMnSjwxax2RhMd;u*i8x=nwhLd(LT?yiAZ`OmU+9`jWi9cFikFC82@6F!xR_S%4g_2GRV4-@t^y=Hw_4}gneyshJyQswvzA(I=1>=qg{hfkF zB=-G@>rFfiwjxffdogUgQ0sh@><;e8FeuiLb&tCXv#LoMoIM8Mn;NsSqD489D~(LU zq<#wAFi%*y?AY+%B0J3;v;%D@-DX|3<*gt_J{cdLGMW2(JPv?-VIY0v_?rC=cyIf{ z$iB0CC}V*Q4-)t4Vw8FQ&Va41@mub9^Ek!C4DMvN4J-gn7gv^|BPVO!fS|x3?acRf zs%oe@@y}#Gu(@pUp4*L)k$%t;Nysd-OgqOOUgBeUah3V@Z!xm%p%#pJyGnlu8S2G% zxyEvbMJOjD?dGBxu-d>?OebE|BqaFRoOO!Y7?}g{n^d(9Jgiq@$Y35f%NV5 z=iJLjPY%XY{qb-8jyxboqzLYBbtPkuwgWFn?hUB3wT4ddgb@_Cv5Re-8__$hdv*Km zI2AsO*-1MCOt|o=w3{QtbI>*}MVTv=0f57F>?-J*UAPbgP*ID_HAyh&+N264G~uoi z#pUX!N$}#H=zq0g>UvFSpsJ+0pmhV@2`attUT)f&Z9M2X!l=o|=B$b6*+=3sCnObP z-%?(vU;m9Zt38|eY^r;s<38)4-mHDY;*DJf|CuZjRm};=U*u$|iz8vzkiU{Noo{yV z_L_U4P1)!b1+gZv6iqFruKQd!6lKI~C)F;tN^(eA7{M9CXIMFT1cI1XbRD^cx_oZ0=6~RAa@d^`zG&$lzr|>=Oh+-f$A1>osmQ!7f4!_*uKs@$6sL30@Go@ zcl3vsIsT-#Rz6n<8=zXC;S7J661<6u!D-KR;-gsM2EZ)tEBY0ShrYE&cKBB z_JfeWpEcx>DqA|j4v&qPRkJmZv0$wtpMn~^GFI<>FPuU+!KyC$=uQ3 z$sLDL=InI5Pi3CVNiJ*^osb6aG;U>*yiAq1?;#l;bp=1$Gyxd^Fh}B-!$_lFor~%O zZ3BTlz**Dg^_A9^8M$ygU)e|Id(=UP<@J^|4YW+g@Zz{##m*q~=~4U7^n#YGb&o`N#Q8f24G0YdsH>Ymra+*>?>T~E~x+!ogwvrYJ z7`GI)4?npQ)?c9x){1P|MQ;A4$7P2xvXp(<$6cThz$I#@3H*oa%U2nJ5Q*yg+V7#o z2y@ZCVQ>9zoh^MZxEM7e;f_{?AIyP{9K=td`fDH;An`Zs-^}fUHIblge(`l>TK2}a zj7%<$Er(CyuM^n?*^d&9aU{PM(>M0zCyy!viaWHqMfb;qsyIG+pS1Z?n?_Ap+}O{r zSp0Qx9i^bMR)SD6ZOawps+1E=|2Ar(olfC4r!sM{dWN)1JD?@IzPdCd09^Rbh3%Z( zw`{NWZA;8rilR4MHu}7IxRQ0F^nX2px_F~|=XHH?6sdRX<_@fRRBjWz5sE*hra^yc zYD~>-NOtw66sFMyzG29T1H^Dihbk@Qpx&b0o7)P$?emI#I>uc&4}fj>b+T=H?`GB! zcW+1h{sOIpzF=|W5tGd9C%==MrxueS^p5ByAtFNKVyMe+zy-$s;(lHC(GM=0u>+Bk z1Ci=Zn6c1}=B4Y*{2sDEwVO?JC*uBC5JgL7qSIhsyxBW?WwS7-D3zLEG^F!(L`Ro_ z<;n{r)em?=rnto#)}}}jgwRra$L1xQ;T`VVQ_`r4FbB6|@6yES!fJ4;%dMq%B(zcH zN%+Sc0GhA?nP_Xu~U{pQL_Z~3~>k#Y5b_H^>1ol=bd zzsd{G%Ey0Qim9^P=vjP?vCI7Pk^6{%@R2?+Ki*WP)zF95ud)e=X%i zn=@86fTK8JMli4uVqaRLW^gp$CCQ2(C?gn|)2YFyyxSJ0gUA^=~ z(=NE96xmuN_SL~dX|ibOSYx$p9^JFO@yo^4+7L;Yi`mj-(6L9dS_D$1Q(?uOa@v^EP7!g0P$8vm+K3WO3MqP|trgXA( zT%0@n4lhlsvODgvzrdOmXfGU_eb^wc`y(xm;m9Vak`v?T=ok^Q={Nch{fju#)D9Q( zv{Ar5l>gPQa6-{fX($GCq%6m4>1O)zXMjxZvcN9WoE)0|!ZuCFL{}I2DT$bcVd2Hs z$M-oo12L5aRp%U!8%-c{g-kvEMFkg_ia?}+Px35S z0fTFZ#%)q3rR+f0$xxE-I^+#2$wm$6>E$b)8~?ew@`c<-mzFe2T!dH}9ke+7kK^Q} zfi|+jD-1e!#Be){Ycy_NcwVMl_nLd6ph&y7(f48cSA0kXh36Et)F<9cAJGWDzW6V3 zHIPruqQVs?@#e_nRvJ~x_e&x_MjdjMeR}jB>Q@34ev<=z7KZn0vsz*Wcl81ctVi>5 zBI7_-PXCmKN3r##3K_p*D!sjEn9Jj;`qby5JIr<%#`<1H2!i@pU9BGQS55>%3%Wvp z{q2wzpJDYYLN#+6Jb-&Ms!~Zx^aknHLF;FNfiN7ywHQewu=4wOCrI&cZ*x}^4F_sv zhn(ItrbFLnS8^aL7Zq3AKC&rSb+AuMJ6R|$bJhNR#S3J6cqO!oEXk3%{8vrK0da>N zv>toOXxwQ~{rp6BWq8#5*+2`NaHlI*b3|7idFL(n@@vJ3#PTtacA;J{5}|2FC&J$W zS@eaBf%EoSXFT-Vwm{}}KPre{RQp6O&bd)W#{(lWVR)&_n#f9+`j!5`+<39?7{QOT zKekotoY_8=&II;G%*qdR^$`%nRXxdNNK~^gdC@%8q1o*W(@Ma}L&PRI6bdEB4-bPm z1wWVY807y-6JQg0E{5FKc~Vi;iO)kt<^-DEC{v5-z>nbz0~D~5iyR>5Bc!YQ0olMM zyvwOg`$+r_p*;h`&!}b1 zaC^%e24gvjc>*HQyF6(PGn1d);g|&PXtS$w5d8mx1(2f&ks`F5GJ>dIQ>usL;9z(4 z;3S`?trD%)R22u5Su+5@p zq_0oJXRq~4;?Cb4Buv9tL2Tr<$ik9*=gk*L|9!IPLRmHAogt4>VMqEA2sQvpU0TkG zvbJ_*W7H(}ucLVnjuLoN>oyRMxeK;KBT9=^;krMaFu6oPx;8rjBb$iVmk5xkQZ2L6 zHnMBC-t6rIoJ|ETXw^faR8T{Q#uY`EIZkJHEoB#qLi0w&>Xq4Xx5L*w*5#;CHqN@F zA8$loGWO+;_>AUTwCp&4{(=o)P>}fu0?fF}hGu7jOI!NmfVM1bT<-I4G0EaKZz>*=p(Nrdxs;&hC%SlVA^H9gaLm|r?4gldtobi=iigD#96`%xId5oD{tN4bm1NyX z-{-n4=t^0>cYw#YU%&0RS#k-3Sth=>UR*9euoO0bS^Q~ez{m%0HQ=~K&+nr&6-&mk zxm}jFg@-WkY}wMK&M*8LZfWkfayAAzO+*jr24wF9xy0?cMlmS74En*1!NT~5>r+Od z3s%d4LWmLOuX?{}3L@nL{zw#xX6$a%!?k_`kk)7yx0yr~i4=0Au`D#{yxD$T1@yr4 z==4C&d!6_3$UvZUT-vvc>HWbvH>+7(jbR~nZlwx`p+Raw^N85id!y@}tpNTrk?(Br ztZglcLUi*0;`Z)gLFdjBtfsclD}prj-hngaEQCjfxnwEr}8rk@<2xcz-S zgLh7ry0~zixU$xDcrNW%yCQN-em4aj@j0h7B{`IFxk&AAfs$FU1NYFtuhkc(?3I6L zVT`XkWry{1sZ&y-05(>FLrUkG+$-69gtes%FnEIQC|cG^IOYvSQr&{mL${87Wr@?S zApW9rG$v%5qnJGBBqu7U$PjyVLyrYfl-WCuUCu~F4fEE6Y((o{||}oVLEQ=1|i*%5YG&zv#!R3UB|ABe0T>=&k>q{G0Ezp@h3PNI>A8 z>tadU)b`mTS3vUQ3txy!a0~7tPeX@)P8Fwi4wSPUJ&~bBAobNn^R8LVQ5rh~(}X(J z4BXm~f#VZXyMcFlY}=)IU|UEpt!S^2r3%N5I>;whX6h7NPtqOrGm2>`Tjwy{efe zqkg!-glbs5CTZw?G>7IM-fAP$@07l*svOB3*DnF>ibqFM!g{_QCG~DvhgyBNmz>8L z0WA^Gg>%%b*p(T8?}eN}y&xK5yl1>Xzhj-(-w#SocdNcHZl@*; zbyTa+bG%4BK~*I1Q3}S?oybQTC8-JD_o}Pz7yq6I(Y;jN zz`Y+NDA`a6|1^%SaRMdmS&rMyMKfXJKWJq^5ZY_(BqNGbV>SIeM6n=lhE32~Q8${! zJJ*#TW-r0R*Fe=(JJ_t7W|QE;a_mbl3#cXP6~4Ypy1j>Jn?{}=50q2vy#f6JqW1^P z?YYl{2^f9bsZ3u0Kc-GTGEX`}vVJDHoc-nBU&s2m6SuCvy@#&TFOdT5HV#0Oq9$CN zi}PrA;1|aG!q3m`*}>LHM97?oJ;gWHOE>}jI(bpc{Q~VFJ4?4vnS1bBLA7(Gb$(?< z>_W`7K;gD?P$dXze2aSBc@MJEpX!U-Jy|zNu@mG(ke||Ay)GAk* zZCdnCvQenNBpPS>Xfl7myPVYjvF*sKP zXwiQ%u=HBAFKb*_*1b_t`LfP!;_8k1BY&P8{|vX(txc=bR9vMIpY4}FRfDQRjxnac zr(;aVPKh>#V-jjR*L&g%yH5IJ`txTDi2)SG9-#S5&+Z1KndSL?tswD&Fcr}DO^-yi zPah)?4xw;4DhloW_Ez%TxdXjRpz3}Oc5q&Dg7kJO=mq^E8F`k400FKqA5hkoC(v?` z4bhxCnv(7I$k}!^lLI=APNdgb>d-MxZf~%|VKPB?>p=5!_(Zn6LW`W}E5cJXUQln~ zL>Ue@Ah%ZPjulCP=7z62MIt!Xrr&cy==4$ODQ_fLSixK?1(KUHbJ7{&G41d3u*50&=BJOQeCzlt_5+>E} zw^gvj>ma0v(TTGOz}=BRU9gmWb2y~F5xv?0#pLHY2QtAtOQ`8oY-A~Bt>6iF@*zN@ zo)K|XM^~$PUip%F`=OBIylm4c6cfNBY=Exl`_cMbzT)=BmM`Y%bdO_@g4Udz^sqdY~{=$&YE0R`}gNzi$vtHwJx(awBgca z;N;u3vr%3`B=UB$sWbM*?;kxN@RE4MD|)9kVsmOsW|o45QDj1z5MBOfz9-HnFK*Vn zb;7zK^ree#@&P_&?pLVN()0C#nd#t|3@vbUM|lZxS*$8akP`+=&=}Vzh9EAD>^&lR zqENlv2nMoL3O!U&Yg+dx@=YPKIgPg-8dZ z7yeD_9c}F884HaQj(YXn)9W0MLnpGgVf@sar5I>G^5_!oyjABjLhr>${oG5k|=k$&MoRd+@j7`U%IOL6}OemwSEq!XR%j^M)qc;p5J3-D%BqXTYDJ-UT?4saN1qA3VWU<>{nObJ3>5Z5&&rdDz6%#lun)!V_m-VDR1aB`x;V9d2N_dj4Q#&caFQ z*ceLWfp}7voq@4SjbIqM5rUj*xJrLy7zDKH@<+`c#kiy}eW{C^lpbguV%bPZKz)Li zI-539dC^&6_`b?~>rTxkxe9hv8uteI6`U=|&OMeRZAEw|Sh(6LFF|3>E_rgy9$Lq( zLljg%G_`3$nC29@){oEN2_hx} zWPm`ton2lGL9wwonV%B3{uPvbedg*Cz`hCLCS2rLcS(W(X;O-A#7#RLDp?Oyz<5J zo$GTv&R_6ck2jrj<3-0^zNnw(bMI~APED>>8pk;*#%Jp?g26?;DVwJEAAK9Rb`PcU z9(er$tvGyzyQlM>;OXtHb&6Lu7?(eRiN*4#c_?#&sovP(UuhBfADN1tJb>^}PM?T$ zCJy6VF4TZ~qSG^^X3)wO?i3pbtg2?!$69wvo_8wqFS?~}=@9;8(+Ap*PN4z%|IFQq z0EJl=AR|zFYG4+!fEe{_6vVq2P^f&c`r!s~rMZ0+`za;>lZzxIBpJl|;zs9@+t>3n zKb%-3UIV|@HCQknO0;|sCq?WiSX_t(=>Kq6?-rHT*x)lkAq$}C^BCT=jjF#pfp_A* z^L;_+Y@qPlCrUacI=BMQvmL;rSWPTn}Z z4_emli2YYZK}P&QXE@ZA7I075L?>_}Cs0U=TxDshNFE5dm1YRh?-OAO;#2t1`>co* zgddgFBR*Nsz5_5gp|UVE0)u`J5D~Iqw2S$&(8zAu?ATGMNy9Ao1*@#rOTPgf9_p%x z-uPCKNh{KjvIy*iy&rASe)sdMPHQCi#gBdhOY5>gy}rs!=JK{Bi&dQZVz13y{F2g> zmk?%8vY>@#=SoVLtN~L*89ufkS+xC$_^tjz$Q;{~GC}J|5zD_HQk~zX?;L@yU;MV* zUd$ZXuWoA$|}X8v&=?(4hk< zSBZJZaWJL|jS$%Ha91i%tlxFH3+1TXguH%P& z5#D#-S4_Y8!(FAXBB6_qs6q41ljF(Z%U#9|MqW>a(9jozB>;=S(C!LN|Y-z11|#MO|KWq&I6w_ zMF|| z9&%%ZYPL5os!%(Z3D4zk99^;PhRyFCY#US6@;EV0+X4Few5YF4j5AT+n^QaB@^{}b z&0}GlHhHIA$))viGadeG^FU7BZKek14EL${t!cr3>HjSR$NexgO1%~(7?MHXRsC&R zL8B-?2QDHYvl>n`v`Y(|#o(p#=gXNSpb71Aq25P}56sf4}83RW%3ARx=aGP;e zarB#`Bud2&rWqgP^~AswXg)ME_$;r{K`t-Qp`*b(%*vi8=C#Wi|3z3xZB)BZvzh)a zF5>VRHxA}bot1`D`~4^N(7>*GofGh}Y=ZOTW4K6dq#a8wq3zR1Rq|fpgS1k-WdiD5 zp!yaL%#_^Z1GD@zI*-&=_i{)8H|nk+PkcFonG=O`g;Nys3fPyN%EB?RStBB-5=h}f z@;CV9#a|hR8fyWoEw&Hr$yH%K z-;(@bAiqQqI%&-F$jqWh5?tmsu{Lt4W6!PHzM*kSr@`77ZHsL>qcdtdG$TZJ>iadG z7#%L8#zEDd_^-_8I*vq$EG3+S=b*-#wDqP|!cb%GjTb$7EhYIwbSp(YU9kn);1fm(?-J-M?{fV=0CC%ZJ8XYu32Edtnd+{0^|2ZC=wAQ@i(je(bV$e9B->4 zcMlos7Hx5*b6~?&2Z!F6DHSgA4)80tB#D`E%gSVsq2G&R(A zhM)m-k#w4O;*x~u%Zrw<0 zx4@QQ!k%XpQr#{2%-`@DX%us)*t}t zh)fN9SS=eMfmHw_ipZ%&dJnHf(M9w>pm^%zh7j0LascuPJ(~kU?FA4j7I{=#zEBeq75?z51m z!-CcmZCI$7|j?QM2L_T@6m>>mRzrOqOYLR={XcK)w6_+Szk)BTU*lI1zVXNfb zLohq;>{irJVN(No7aOqH3uJ7jbSV7v5rBR8B<%sMeU>Y~=W${{r<)Qy+-&Ki`**Q) zB7&Yc)NtZcc^&(I*OVp!opy4NMW-HGA&RyWwr6f6o=}A!n!qg~!-5lO1p7eJUZR&= z>hN1VUywN^+!uLOkm>V#hXaS8XG(-9Esl9Uuy+n4feKBvGu}jq{g0tMfSZAip4w37 zH2@*pb>Wc(G5joV!1RA;s)K2^`)@?CXn!zZ`=2iJudlvX5%8kyjztNkKxtgS!>tY? z6z#R8vh_+SJijakE>g?(5DxUpT+*zI*7?OKadzbOyUX)HzhFfeu@l-P!KaD z@}EslV9x5`lL0>WC#+-+*iemI8y_!?pRY`Wqm+6iC1J7AqRTR#+|wvnXEIN{`SCvL zw^EGVOWpjIcCw=c_HDWB#vz|KfT`-7uoRLe$Sk5My*3|{a$S1hyufDvdg?+=2w3S}2AjMV z4LW%tAS&2Du0@dWd6%u_`^+bEb~YvNi+B9xGX2F`V~BJ*5$e5Nl9fz1od)hHBHVU5 zl)C#I_HV5(ChG8*?U*BpL;a}zTJV?%}3gum^oPzm%~5KZ^ZRJ@_Cz^-)T6{B;etp1s-KlB7keK zl9BG)!yV3e$m*|k)2ik|nL4)J1j4+Z{W-~55(Cp%D|@Eq+1jN4&jHbl2WckyrWj_s z($Ex)hHe=MU|H;?zst+S_r{kreN~y(RFf!pJ$;j6zDnor4AY*VT&d$YSuYJSm5xoi zz@u-*N;Qm5@e(t76LeQg5QVdFUQx)Idp~ubxL9=SQrT86Rd3lx9{3BBiKtiALU;FP zgl0zTv4{ulg_1LOjFrwpi;I<+r8x1nZa zAYykdv9ajC`>{nqfCwO~+r#aUx4lqy@VC5wgTtDrwYqg5i$-swa-fWV6|EN$<$W4Jf3O4RP3?gw3sw&pJ z)TC47$XPYsmI=#UIU`>1;oRJ{nQo!K`{>NU4r##v(RrRJ4M*8u7wnoK2m^<8zsvE5 zardS8M0)x*`KBdovkF4fDkAUThS2l`(+Ei(X_2f^KQ$eh?aF@+QZrIZ@?9=%SKWeg z87J}RT-i$J<%eLIx7W16_LN21ul|=9M6|rgitF~n;F$eowIJP!PFRP9B8A0y@%8h@ zs4!dltmqs^@WDocfS~hLV~VIA1{Q5t zF|Id5fkYK71e1E5rnncxlrl0mHz#%QLehjZ8OKzI`nhJI^I&gUDNv%E=e8Mq3{U8{ zqFTI`IsYx_QV(*DZNG?Y2n+%}e7qv;6`Wn0`9r|{HkNJZbwrK5uH;*FO*v3H0lHq{ z#@T4P=*d;LrUlW`gy`i4N=!+4hu#xB-s#*SBiE|OrspvY_9v`hUoY7Ppm9eVStTE`AO(nU(R~VkV#qWe-@M+pf7t>t<>2A~~o+a~jnYWgXaAZ`y#rYBR znZNZ|BU}nD9FZ>?TgkTr%TwLg=yO6P$h@cpXDQY8({^f|ondzY0x}|>XDMJpVug`Kz?X|A#*NMf29;r|a7fYS%(}hR3&DzS77O8R*{P9Z!mYqB zGY7V|d-Hew)^i^P3Q*>V(jpZ|JGoLGfdhHmCU50?Y#`mXXb4SKC84F>LM7;lzO*0f zmKnGxs%lEQrFba?ywc%ECcVlLjd&3AJZ=~zA8-|sjE7Gvvi!gYu8l330xO07e`-K{ z?W;7!orVthJ~qaFi{8R&h^G$${tyS*39;42W zv2JA%8C@)6&Y=EG$fCqT!nW%vLD_E?3`-o z#4M1gDIR)z>2rydDA#+Gb!TwrAgA=P9Ty zl0^xseK|4O*k<^vvOlx3id$&%dYqQ8s+|7xL#DamNOi4j8{*x>zJtO{|Gh>|b@=Tr zq1}GOXA!w@)Aa_nvAac)5t^X#+f>ry@hmvjRBJOEQaZC&VKQ5uwhMrsNvlwcKb_An z@e6zFydSKz;?r~?X7KU<7lm&RjZt?Ua5J!Bgk$!<@qM#4hiNZ0)Q8Q9nRapR_y(9{ zV(sSHFp6sdO$A$xPvRg(*8`y`WAV{{$tOK)1j-BWEm#^<@ef)vn&C2e4XJ9_eX`pU zW6wPbPrwgSiM)7abK-S8Hl1S+>#+IgGbMwrjbNyR4;xJQOFLKhn3G&a~jpYoM>KEe>DQ|R>3MJ|nvAQeB6j>VWi>I>W5b_p1? z!{lNMZMrk>a*XgKgwvI1RNZ4NS75l0c6y^1q6CnT>*lNf9o95okJ8Kj;7~iyzd^?~ z8)f2k%vK15Z!ihm5Js|*1g>%CClNXwXN?M=rih2`{E=WrHubF-@RZSf<@obY!1{}Y zsY{db&0FAP=!n#`?m4#VJIk#XWBXF1ms=@UI}2Jbr1>0-S`rEVZDd{q`lCC&?yqYm zG)5uqkbfO3wVh@V)yqS=Ry2?-Vo_t39?3^MW5%N0SvFLlsl(Av#%>fdC{!$>{BG{e z7#-I{_>L8&y(&rWfFOcO?k9uECN~kgtY51Snf3Fm<^%C+ii5Wj|7FyAi3GY(vb%Xx z4RQZ-TpZ~j9HlZ2N0lZyfhLHCZ)yZict|Vaw*HbNjWxX}y`V(B_}~hN{jy|r zqL>LQ`x;S+Ih?F=f>Z6)+S+D30SzvfdLd#pwdA53cDx?B_oBRgmIkG!C1lLPvMHAK z14JSJN9uEpBf!3%pXGe~183wq*ls?N;CsYH^ed}(YKoyE$m8Esi!4W1ufFu3ev!Ls ztHl1_mJR33@&tP7OVATb`%}lHu2ZwOb4HpKAkhiK3=Ji;uIb?5(*9~zH)w8c^i!`+ z@vSQ4b+H)-THq>eesH=mA^LdzSgQfkfqcnE_P*$gkq|fRpLXoVNGFZ0s)^Lu<=xgV zM1dZQY5(#XmR*+rKeFB`pssc462*c$1QzZD0>RzgJ-9mrcXxLW?jD?lySs%DSh&N& z-L?7qblo)^&^)4T}2p$X5y;xW+UU^E0#KDMbChYl} zd6)Lzx)`yyAWD~+y|A59o_y0q#(|^V4G0H&?}_$xS}rldfgP>zwb@II;uOFWF~^II zKIYxl%<#~gM{fMeh@cbhew64xVp2W2iGPsEyEKk9Uau*exIITmh*$``z(=kXm?DHf zAwqIthUdIQ%XExgtDAN~505k2B z`Rg5tZe==@jjE1m>Q~aiqs>Xhnd9|e7Wzg_?XV(~MUCjKr)H%Z4JXZlS|L(i~%}9 z;k$(4in*pxz{wBtQs5UGK2WeXIsDv}cJOEDe@pQQZq3k^F^$lowfl?Lr92^#4{`48 z&8{y8;sjio#M=)KfcUsO<~^+wO~KuZO;M;#V#$Dt-V@Bw>T4v%=Bv3E?Hl8&{(5~e z`uO>siV7usu!36#8f54&pRlv~7B<4vP8PD{4r zfRw()m6hH{N;b4Aosa*|_`oodc_($1^~|DYUHeqO3O5wv;I0=qDJ&&`#Bc&|QQMGl zQwPxdqutE-A_OXfL|9#0gUwo=k)7raA`KYf9^PR_pK@TmiQbd;FE?XMq-I54_w6_) z)|38cxW?HY^+y_sSGcfzLC3@lHX>0ZCKi#2q?AS(zMd?gh>k{hhdVu^e5DQXMvn-@e42J0o5;*eDcn<&DER#8QAaD^Cs_ znbS#_Bu7>W6K!0weyPh%VVD&fht7R}4#)z6Mrfp?Z|B%TIRWH33h2d-WKz${IADDn zn}K^Dk1!9vwf~LV8zX$+_Krv`3>|>~q*}Ps2g3+)i;(6Gv;YfubmJWtTyiP&NQ59J zh#f*ch(YrZlJ`UJ*3bO0_a!rswJ3DNlT(Gz4L+%&S&JB>Mmtv%LL1K^@(F+~iLl_< zw(FByuT$cFo}Y`ukDM;@<&UnnB6ZbE8^CowyCD>{V$X9NtlLJZ`kzh;5|0amP_>ia zv(1e|F$$M|nF{Jnv^^R6WxHFN(8~u&J4X;<6B+cQ(N$h^^$+(lliDnbW`DW!B^eo! zyucffU>y9t^AQUH5dNu=6Jygv#pI#yraiuSHBA2s7Ff5`T&tdF@pouUxiJp+XGE0e zP`;*U=h7(g-D7z!C z-*cZYOO9!)T2n`j{gp2rIC$xc2cp{&D*^6W#-VG?wG4BIE?P{hew@5W zOMKwXQCEZ*kM4MCr8cbNjeBjXgE}0kV8J8ejUmrm1F|c7#yAK2GU7D-{VfKcjquSH z?}uIV3qF`1D#fy1dpfK?7DWk17N1()t7gqL{zIGn2Oo*R*SpPwK8Hm80_U+aYt6;Q zC3J9GH`f!W><|QCy%|Ku$Rn3lx#{|!!|+G-gCRikdxqV-qen$KS6Dcj^{EG5gd)!R z>0as+BTw(!>fvF}epYCD(3n^=UpY&QZs||Gg&zL`GE zVcyF^uJ|V8IIR(4wuUu`C#|Ydp z&klFN&m%p&jdnA3`w)R>Ob`S86U?fCocK$1(^CK@2CANE&4xu}yRDHy6_GOiWoz`>aNsU;8br9>w5}Ng$UI)e;cqZ1;&q ztaw={O07UMb0X7E^iZq>zeG~`gZe}&7`d+7t4foPZqt=7?1xSvZ%e@}a-?Nw5En5) zA4Kfut_|%ffBV|?IHDXwlZnTDK&0^mk-zjpDKArNHpi-U9Z+*8r{)BgzpkqEe#NN^ z7&z^4?=`<|f%-!^H0u$>CZAYJOH9HiG0uNN&3bb^I%V^byZ2?88DD#F3~i1X!By(n z{?nsPhxj82p#?B9WyU2;!}ME5v;>iC75E^18B@k7!-UNBx}+XnXD;2MjeGT#TV%%Z zRTOYQK5B_jSj9FrruwbtF$HS3v4%$}kD6`; z#x$$d9@(^f(7|{8;GoJ(-$~89cC9U>mP<$3GhTxl-5HW#|bWGZY zj`(c>krl_h(uD+Z@r9z;Js0wx5BZM7t#S3^{r?~4A3@h^CS3&g;z~%8y&2FGUe6VJ z{unU_xEg`S>PGI$S*F{ zo<>zfe^GsoFN|%QzVbcBhQx}vGHxKnmH{r>8PYmi&d2~mKe2d-!f zPn8^3Czt0J6rh9uSfoOzD*H(F`7805Me;zo%ys6*X zl%^(9JGn9L9N03nD>PjV1#XE(8`rtZ+c-58#j7c#qT8yx=|Ozy$_6zrX;i92W}#pf zMRLAptQoEQDMfM^>6if4I<}#M2l$;a>=tD&Zduw{!Rda(Nsg98g%LpKN6UYa-hYsG zO{jk(?IFo#QDf%%-|b<=Fcr5YxrlRm!{awC1M2zuNJ!rN0sOhfE_{8`9uOyk>7`ik zWav)bnn?MDtgREws1?VSR)d~anHEiZB0MG&S1_(*PG_wXzYI`g;B1*XQCApc#=iEj zOa>d_iOpc!%WJy=O9(G~(1r3@NDVIu_5uPI;u8tLga_O8KEyxgF`#$|{(g-8z)rkFkS;AM zvqn2F_PnOBuLF&T`D|{XVn$5FRtLh**J)Ef5W7Mq`f)!@WQ;h4O@6<*j1AYo|K0=m zZMp2a5x_d0;aBR#v~zMCR=%cJwlE*0-1Du|+2eGD(q5y0A6z1TvW#P}2;LxkjRK5r@+54{&E3@P>eYYE}rLf zKrQ^gU!;bg?v1bK>Z5KNijhZO-S=?6qvo(f#Rww{TZbi2^=$8A^@X;Nd&hk1gV-5B z7(Rhnj3W3u09*2B+gEFNUN?IJeyffiljGNrE^I(<`t@l$rOkZWXSpmIaw*FRSMLhI zFw)W@OF{u#+KjO6`?Tz78fMa-$Ui1fp}P8D?ZihQ zl;HokE3h!Pfk?=)X*r0yS9Bw+q5c6g(~Vag$#PK7AyDFSAro(r^7P(S6Zx24IKl`+ zU=#xyum~rKx2L|;8nNV(@u#NqEr@VvZbUPD+r*?A>b9TM`cj!AcoCXzM_-&VP(UjG%+Ub1w;`{{ z@vMDvbv;SGO2Jm&n>&MxLa`J5O9MbfN{Xy6srW))ojFO3mp=|uY_=+b8^tj0YcbsK z@){GOUNkd6-iZ&~pE~l$k$m}${UqC*!xyqKOlkI}=)Yr2a|th}Pe--M-ScbYdP&4OzTiVi8Q zy6PY1C#yF;LU|c;DJf78@en>D_+{dI++BQn7~ILJe1gh?kO+KDG!ny{b0bTL*Xy$5 z2ueGs8l`r?x@cCz|J%FmYJ+|7e77SuI92Ctk0#2YC&=2Zp#^SZQrWoB8BfckEpZIox%tXMQ3<5Pn*2tutjXTL(I@z zTUx8b%d~E|2t`ANExJGXfdII>=^lqHE(~EZJaFD%}0Nd**@0e1_NXM2;D@qJnZlMSnUE z*e;Fm7abjKYp)U`M7g@Q5st)8p4aZ!KN{-=)|EiaS7)trbfdM31jeB4ZNtpH*%7~k zy5zZSA=8!qzf@q}U&dui^>mKE&QCjO!-jam9}tW>5;%; z(9!yby)I~v5mW%l^Qs(-$L2O!73RR$yQ+45vqipVz8)g^qWyc2x+h!uB$p>k+?-`} ze}Oe4H~Q7me8&J0lFFvs3NORZ0X%5VmO`Jvlr13Wifu1;{{!j z&}iBf>}@(TIo#s=j=j-_80Fqjiksmz#T`0%0jy9W(@;Zi&F zBu!IBefV07afpH+cGd64K%EclQg400JzC^;KVz42#kE zbFT~Vy=2yws`~$!{VxK$2c);4o?XVC(^Ade6Su7F0P(`B`}(Q0yyuvZO?ghQuAr+L+pN5faRRI+ z+4R`y)79kCp?$!UT8Tjc zCpWm|Rr(3_HAQU>`et4pI^mYoeigt9SdHex<-QM*C;mg;`@H8`)D%c+N6yS~ooYb5Ci%8~&YfY< z-A%TErPXR<_Fud8&fkFJdUbk)IuA~`0K?G}>oMViJTx+kii$EpWC<$UXKG>!Qa;$u zj+a5kiO!zR1IjNEyZf2oG3UE`w1^$fV2SR?fQ6sUVT8l!oa1nQ-+hzwJ-*vJtwv#| zjZNF88PqKL-=pa3t51WLEex_IFB;-vTe}RJYvy4u*2YuUH^&Ux&^RXUyO9{7C5T*7 zv&;w%Y%+K50(H-K-1CY3)*%L8jqqpfL-0_R&6dy2P0BdAPqNCp%$|j`Zc?|Zd+Qt} zj=iXMO9s;rDT-ETyUu*a_nqMYjKFLWUXR?3(_`;GyNLC-+vCETBFyzoLjD;z=$hlZ z{O7Q;Wg#tWQ%+Ebyp4GNR|k7MHZN%YF?NH}YkW#htj94McDbm-CJ_ek+GfZP=jE(s zJfjO;G)T+pvFM~iM{Xn-SWy5hX^z*n(6YrGvfZp3sj^HYdQf4NL$R15nv#@Q(xxY| z@WBq^*vCvB`k&KIGZWAuiGy0|N?D;mrCq9zlZhcoU$X$33jE`qcVvkK1Vo`)2jM!WR%L!8bHhO(xp)d!r z;*2?W{-R#K$BVUkpoaO7xZv3QK0cAqh`uv5I=>PCJ|}fr`%|Nd9567Z#|Exl6U=;A zb3*d&R<~_WD|lXqD&`c}rpun}sF|;^ef=7O?t1-XC$q4=zOuXkWmJFJ6}za(03Phy z%F3PREI&o1M}(WX1*wBIzM#8k*HobTi9ml}s_>(M9ERcZ=Qi;_a&?&h*e!a@V~66% z35$bYp+~~`>q0lLqQYxLe`BD=rG;ol$5r?z82b^?<`q-(s0j0s-QJ0tb;U|8| zH*bhljOo*7PS;in2m2+vC))rc-2_MwS~`9#wkug;i4K;p-)CQSgb>Y+pWBxthmZ46%spCreQx4NJqe)a~B;BHbhv26|8nK9iXoDZ($_vcc(wT{++#*6+sk`Ek zP^wx)A~+^XNH8D z)tD7SL8OrmUp^&|g*XzPhfIk2hObk-hp9#4lb=FOCXc0;Xmu;I4X>My-%hEaRO>@- zK3iTj^PO-4z27-9<_YX)qKV*6@_~!=9o6kIIg*-AODtTc^*e^W7I_Z`%ZuSEG+5mFy&!EE#U>IdNCn>@4Uo>}PjSFbp7!TmFXa(#_uo0g75+ z^Fk8fA?I;>N>_bKS4MVIA?YM}#DsnQ#f2}H1HVQZEy^rN4? zMWvvp2fdoJ^gITWV8TJFe1_q)XlXuurukQ9*nRJX^=5YKHTC*^AB3dzxxYFvHNk<$ zTjIuS@Qrt;riyi;Tq_iv?7OFkRjQafG^TTGw)9;m0y$3~AXtXArV_mRF>U4IB1Sl3 z?=#gsZ5g9Me9caJm-WYX+ALsCOWft2PW6t5pdON9LEPQ;obgWB2Sw<1J8#roDk))vj=giKEDH zA<)yChzjm$>vip7$A)EKNPC&z@CiKri{eTY&e$!LKJ&3*iEncU?JiRC_A=SCe`01v zQc?5NJgXrvETN*tt_MOgPxR5fFkgBcl6jU(C z;)G~~i@$q|(DZ;H-jI#lSjIe6>YE|S{!-BM6+Gx(ivj0hFWgku(alW)9ft7aoHa_q zTIs=cpN=!%!;{(N$yTDyj)9k9bcv;<+3ceLeu0Zrr zOlDw}fHTSE&$`|r$xfKm@Od)GgSem|`9^J;2{`#|hLqa0$$B)R!waxKUHX&vD_yONdM~vKos{oR!9GKTc#0=mdiRX zR)HKI8fFD&Ew=XCOOG>sPQaPnFjeK^qKM?WcUQg*hYtzJwzuX^{2{@palfXS0P}sd zV%N}3K7r9wl>v6dU4nW0hE_S*%(f}@-^a+`@QLHKVS>bf^zAO(6qjl{P)y^q;pkx0 z(qYoT{TG)DLsccc;#TASTrTq2X#7nC$bzj;@fo`&+nW(g@RzB?ac){>WxBe$o8H7m zfO`MB9xQr$k^ZKU#!uNR4DH=*w{tTB6!1{0YS3xDweMK%^mMD56!}>(6>DG)QhJ`R zbg(NNY0n>w{A7(Hmcm7jrS-ddnuRPPzrUI9^-vHlV_spC9bty`=3n!i<{EK5sm?lm zgQ_FjniQJqOEW14(7D{24yorr#;WZ`ww}F)Xpf3q-?#f=^SkS~u7zpSxiv;T0`HaQ zpQwx(GVa?O$`*Xzd8P+5E)hJx90*|tMKfi za{%HPiY!x}WL!*$MJVHzjek?&kvB@vh%@t-S6{c3 zTL=G8ta#1Qt@ImSm^s>9(o3_l8++QYYTG=c4D*~_gZ5Nr>S)`#xIo{y@93+>EwkXu zSOxPcE`=hLxEt1GydxFrz;ioi5G~c=?P}UWdmXY_gP|$x3$PGZ3iVHwz)>HyyMz zS?@5tcMwooR&q93YXO2$gJ4TJ);D7g~OcGPuY?aNEe zG;JcMSCPv_@z{>*h<*^U-dKraiV z-`m_YtfVrajOrlaH@!Rggk^-T)h~tiv7Ito6mi*hih~8mE=nG4c~;4jvsvU$c-l9?oikcqVo^k@sv7bW)7d+6^AypN+&Be zB(tMQ4tk#Dg;5^un2pz>boa=3VKr0Rk_umXfn{Zd37lD9Pw`Os4%Aba*}AO}mW=)p z=3oN4aj4Zmhh-|nUo4U`-5*s9YY2s!rtDES|?&N z$H=>9MT!sJ0iF;FhrfvXt|UextMNTd7DK;_3+Cqa0vmA*AUC)bn)fJ zw6*GAo&}fkn~*qi1x1^p#G*+My{rcfvoT@9CgS=g@WQn0tG8A)iO_|rAO=fhw)>kw zr~PaQ>y{vh(I(O0a9F}PE=M(j(LUO8c~#{Lk2r+?b_iOCcAe-gQ2iNvbOg136yvS+1b`=oWjs<@#)Ay7%8?~(je^d=ooPU zw@PPYpQd&KUK8!!`HxU3;6TDrlyF)_I~#jjj_$+0{J>} zApZP4o#HhD>5>Y+Rf#czSd#F4R$pU%Ns*b8B7|`X*S(e5f|M!=ACVNsO!tB+&#~4g ztzOWGN5I_v#=dP-aL4Nra|2B}Ifb0DwX=2e=qQQ?5ieHaM4lS@jtgSA|3r6#!Ja7$ zbj-_CzfnnjOAt$5Q!~;EH=#4(kqh?|jb%e`^RwZR`kF|>2JAZ8U*-yds^z+`1NhYL zHG1{a)~C3(%@e~pEBz*h1Pn;Rxt0oNXUS!m9@x$f*x!pYg9m1N$$Xx!VxI388fYab zmV}@D)^zR_pwl}9{LMD9a$c8$juy6Tmak71ua}J&@H5MrpeWkU0m16>ulxZ^L8~}i z*Os+!&)cv9ZG(J(U=?<1wz?kN3sWNpJ>~%aZ#J%aXeP#X`*_|aJ$B2y-v=KtotgSO zJJ5CviRS+V=mi2q_Vjaf;!GzYjxvQkSwkkKNO46}XhTz`z5a-mC?7z!et6%Uxvp#0 zu012I`t_1Ffzn@f&Xg2ZqZKPQW^+P&x4&gLrRJSoWWOuo;}!kV=JcBB>-?40KjKJL zVMX-Bw)B`}h`mGRSOgC}`F3c}{r6KScJPLLh?pUIKXMo!aw$Ri(qEo}(s#mI=VBc= z4i&fFcA~$DalzP7igW^<&iy&czabrI%}&ix2cD{li?z7&`_#C{1m|RD& zUcx}@;($-|;yOH#_jb9q5O31?Jx61CpoOHgc;6c(euRR(vLh{ahsd6{(MKG)Q2l!S zeEQYyLdHz{r*7HBm4i6w!AR=SRG>5sLb-bczPwq>zmGfG#HrIxg*|>UPaA^9Y`4~n zty^Iy$F^V4e0UR{=I<)RWJ><_wsrmrzGN=DrrYjXX;3N)r?9iL3!JEGTZH&}s=2;i zzjXdB;wn|J&EgTK>$7NSryJLJY5t-ndW z_lFsDSX%UF_w(EvYFVrtg74O>E@m9hx9vzV#HemJQ8(@R9i*?WuRSR&D#Si}v0Dq-b!oCEh{WZY)=Y^=w}z~eqkUQwwlPJj$eL>{ zx>8BRB*ezc6eX{Nt`j4a?C2#*nBb{Lu*sxNqm&zrx|F%F)Db84<9R-RR=Af%iy8HZ z|B7!TXhJL3nHoBm_cp}+585x)Ap!ve6m}D%U26>fu@hHYJ2S))VY($za&)x*Eb^#R`}-b} zDxDqvG`p!Ir(tb+CHfe&%6Z>mo75G{6sjG> zGff0zo}Sk=KY1F7fRaFuHJqG&smhi-Q7ubT(y_A;wq!&E)BxerWL0;s9M#6!u?DDH zDRsZ9nl-(dlTH}>*w@m1{~1+5@5o>4$Q>@fqE9Z>@v5qJ8)5D);`$9`)b=`{K`z1E zsiVsrr2^8WM3er2dXE*54t9MJW9&C^7A%^A_-b9!!9o-O>jNU;%5jGT?^z8wwH02_ z6_>-c`^?lDwK2EGMboWSPnykKwre7{VMK39mECu}P0n>%OCFn^>6ahmyP^rW?=65c zESB&u?iu}x*yKCXiOb>Gm$#i%6@mC9#8*l`xVZbOou+5Zcfs6`PJJrv@@|fy=t(kC z>x*{^{4ydwZUeGd7v)QY*vxI99BTsOa0Dm$nmF8eU%ncfWPVY%+P2QxE zlc8!hOqEUevg4$*k7WMklH{7}n-<`q7aJaOdOIwbg`oAwKJKhOea+$iiW^Qe&Tf9R z-;C}bR=E+GCL|{PfWj#w z>A;LAc9s;<7F!?PIK_C6{#Q~I*4ehFK(_z{OlT)*oXIv9wLB(z(2!5uj#NbjIiph) zP>4<(5Z398;C@XQ6mTCO$~n7Z4g`r%?(!=>(_CfH`%!Mtf-~ zhAqDP%lw^m8KK@i#~xV4R49a>x5q-3+X}x!W+u%?JP%Qg27V>yhpmUr1jtwe}4GP;wdmp7OFu#aPBF?yw ziBgh@{d1be2hYQJsZN(q%#^NPaa#?NpUupuFyXjz2*H(inENzlDf3I7|5tfA(ExNS zy?30IN#@4&N-yxRElr%$V?Jo_%_*z?xB1g+^cZ!Eu4 z7*pJMgm}qTaq$vt@5dw#Y>JL|G9-!%2`pe1L7_#@>eAVH$Nx)rXg4BkO%@kFSPrv# z3ah^0fsRsMw;9g4NUmx9Czft$;hf@M-G>AE2&ZPj%uc(&viLDE6dqGn&yfWi3=rgDVr*F>f$6BzV(33f}^51Bg&YZ((RAHIQim*Jnx58d&{ zUSi6Fd2d%qj0T^S4azij88(hiUh&l;k(JwOKTQS-fkLf$DIhD{nTmV86O(!qMT|;__=pLucf?l$_F*|C#I{5 z|7^qg_i~+0uR|^vrq2e#pOFzqS2r8;0e?+lzYKIgj>Eg!${i(=oW?A^hr+ukw5eV! z+#f9vxIx3JX(wc(58v;=7P8XSio*5)Bpov%j7NCMcf)}Ga>iXYq=!lodhX?6hceKl zPE(Bz^+GzBh}vEO9}FLuZ@EL&y!@B$bWq7K0ZuX{ z8gJqn7h;W32vMGx6=jf!SQ5TZ3Kw7kufZ*09g-rZ7TC8L&j+RESb|-04oo-W8^tQ! z2@qFyVpv^2H+cSwva;T1I9GkJ0J8Bs)kclke+}j@EPs24ejMNEXzy>hMj{sU?(6Y< z_f?See%a{p>_aOfW8?k{_gLX=2YGW9wp}DR{C<+x=I`pIv$x^>pW^YB{Sa^F0Z;Jx zzwpH^@7#*e>~=8s8!kqkr(l^Mm3Ey5;bra{ZQgZ!IU{>tt|S`@gi?`nahoD3g$P!1 z#vZA`f~CCL&sIC=QmBD8k3LnBI>z`!YDzXV={@I0sdl#*iJ~)BY0OT>v~0ev;RoUh zl@v2!tyI&)s0^3#w@bXYoS>}u`1JLqofS})$zc?B-lg?~_!&%f8cl|+?X{2nCi=;; zp_lEV11ackT>hX#uNf`%Sz)C)_cR@uHDri@dtAikWX^_U#N_Jl#X$~Mlxl-Nmo^DB zJct(3_Lz6|XN?LIapi7Uaxz7dnhakQ)3SpP3tpovL9iwHM<1m(7gA&f?^BpYV?G%;2zC@kZh=W_cdMNj+dl9#p9zNmMen2(FmtyS zQ=U+UudF|L-pv!x?#e0L5Ll0vZu6XeYB1;T2a!UjiW>El>t#p!OTP~0wSX}BC#IwfVNQegx5RbgKX}SCQ>ONL^kWyaiBhUsM#a>~CQ2b&<9+KPa1xgky;H1+Gi93J+He@`)ZZlx5aL(S(m$VOVNZ!4%e&Bq z3b7eJu5Xdu`;HB|A46tVCr-T?ubt-!`c3+9?7YIAtH{T5X#_pj2vZ|ysW_%j1I$>z z(q={ypm3i1$@w{s2WPP!Yx{-%+c7?c-FCRu_@${5>ywQ`XNQi|TKETV&Roj%I(niZ z^SKHdy}7LRnc-=e&VXU&`0sWR+7u3-jboWrr$Y2=j+=(X&9Cs;2)Rb!VG_NhhS)<_ z-S$htRD!SMfv?ahD&-X)Kelmp%KACVM+$TMZCZpdqClSXBdtGJs8!EyE1BcOWAwnLzwM91(bxHXA*92z) z%VVo9h5wH9p6Yu2`KEV6{8E$O^&)|5<0f;G^cuxsn(j9S_?Lu+wtj$Abkry% z{7Byq*d`a|aB3WiHg0H?49G3Ti%tLqj5Mu747D26>hhy54~9u{A{Bcb+CT&g-NkFZ zev9n4#`D{en&0Vnx*UmDHIf`N&LSqHIvAb;%lFa)>5ka-s<2ns)!4vE$7m?AYglP- z=ghaEU+0f*IvHS9HE}hyDs|bK(EWDWBRI%h4)mcI2zwQ@Afhb%uN|=ie$={%g87!l zJdGTbGOVmY!AzUMU4V`9(`42<&6-7LD(aXI?CjcXIJrzwNk8EJEWVWqEiKHSgZ_+II|tuYX<8MlP8plHWHC9I15gB$$gHt?rxZq5hxK*frPkscd7Fmsi#E zKJ$p7m9gyQX~~}qi*DWEH3V)Q&JsI%h#jOzh`L@))IaSPBqIT%EJkUJsowYqt5+3J z;h>94mTk8-+195T=Ia?kLFnTfAe1n1UGwdb9vt4&el$JkNT@qP1|NjVrlBT%R(m1e z+o6)ATa)e?#W!;Vs)x?|jg}!dd~1D^JK`?=Q%YH;3&YS&PADIZc6WZExoZI9@v$(t zt9O(CT~BMox@G70Z71x6XnCjB$ijUMN4rO?2cIzf#YdTnk0CLu&N~U=({xO#X9mAh zFK5^4>?D@-H_ntvtVon8%o4jW_6(xRih6JYhzxnVDKUowy4CzPj&G%hpk7H8rvpq^ zvs8Z&-a$lR<5IE`vw$Z`oci=+ix zbBz4ucQAuu3mV^w$^E-oorFyde)BCm!y4zTxq+*ijfCq7#8fHd7F2{7lvz;T0TdLfBXr8~ih zY#%~HM8PtVK+WkagSk)@pff9>;|sIvUuH4RR9QJ-L5}!bDoJK|4NL65QQ+18Z!Z8y z10+@y(R=-Y!*Rt8co3omY=O!+N1lhPmFBa!)1mpP{(i5y25)MtdHwSJXf>d9&s8LW zMIt)_Z4s24X7dm zSrl=7jieA4-#%$d2BYi~!W>3}XqB*-uY}lwFP^7ixwfbe z1<+@Dve|x?AE;IWAH3B*UxD9mY6468uAZUyZIuh8_uJEXZn_)Kk5lI}8XbPXl7QtI zaLAfQn^t@jk<&AZf-slfI4*88DE(O(CFB!ENch7ZW=t>ResHjB_>llgppw$xy^dRy z0ELFn{X#~BL8RpDu$>WX(oAm=ztKh;g5X6{OQj^Yy>Ct3JOx6UkIij@5A>jMhO2sZ z#ZLv?v_|xKwLyDKaPJCIHiJhvkmHW8I)w|afh-A^U&K+b@QAlJ`ys$LZ$Ege&c;7 zpZZKiu*LP@OiA8ij>82>bM>5VY@Vl3D+~VP?4B}j(q5?E11i(;<O&vp9kvaNBJUVZ6X*n%|kjT$4H1X0lwXr zeQsdJt~C~@ttNV*J$P8eyeXv#^2hWXgqZRow;h$Wq|-W2QYE`4BP)}Hvuj0LTbmdi6QzgzN1(J; zRTJH<(W((XWT#m_sjUXvL_eY!)h~WEhdqX!FkfNqq%sM6T;g9mX}wf;oT=9WCR>R93EY_s85us4|0n;G3)wkHO2OkAy$ht8Ov{;pwdVoyxYPh~_%;LDMW zDf@EZIH?IsGcz1{TSe-{xL)l(zdFlzLD()ZzJGUuVR-;Rs*_lTaNu>tj}`M< zsN`4yUBV;?Lm68c=Tj~?c|&&|^?*rCN;tI?#t0tjPh;Hv?={GUvn@BLVU96xwy5Js zl541|6nc4P?Zj}3&Wd6eU!R%ac|ykAy3930!aOPXh+$Q61v&ou{Nv|P(Ae8-7&_8LubN4%f?O~d0-z?(2R>oa^H#@~EkAE~x=QZcT zXqD-qOs~lqRTACoKK?EhS#??~MfN)kmLZtgx^-1t?`Cyu$3rgHlDN}(_4ZJGPy#Kz zCL^0no~4jx_sXTua@#oOqtav=c5tx>Vzy48pP&_iOHnu#uqpbMQc+tereq3bf(^3B zr0gKq!)HU#&%b~Q=EUdG`vhAZZc7BET>mKvB}^W+ea`F!$LiTlsf?NTn046Z=ah4V zN#qCV{XPrcNL{ObN!Y%kwp9^M$)Kf3OH_TXHNkqZ zDpD$;5=$!V4#d}~ z(V%oDlEu(dgA@0VrkxA-t)nd8)*a z&L7(P*sl9Pl~q%`vneVl;ppWls~m&uuLGv`@ydi)XQx=Hv~Q+S-}i4x=fAxwVSgI_ z*sYGY{FmXZqT=XXkjXXfG3St2GFcjAL07_zMy#y%X^HVY@?x%MfG8fJD1xTqOInHw z@aaI2+y9;-&hOUwMbSUF#p979?Z}(z|Amj)yL{g5(eH7%@>E~sUKF!^-KGvVraVSP zuLc;UzlV~9hLBU6u*0~Ny7m78ib2F3vok~7?u+d6;pRCPk}xGvd}MOg> zNJ3U0kJoDX1Ya+SHf_9vA&idbwYPX+jD*l(rH(!{QPAR#BCAqmgP8K^5kETXQ2;oLtBX`nSnE5=w029)arb=g)th-4s0X-8bjn76W zPM*z%Y&94X*rA5V;qJpIqZ|jYF^ESR*Hj66cy`PZKUr1l#301g6}dP%0;)R6bONdS z(6H?cg#a%I)^*jKXD#}IYr`Ta<_Sb=Xk7qZ?!Guo7lw)3<`&YLuJk}*J%VHgDASD1 zqWGtT`Xx2{4eQ*pZZDm7#OH|>p=CgQ$BC^g+eQoFdTn$u#;G5QDNctTsFYw;(?Z9x zB(czKr;KVe%i8bqA!dxGlm&A&;WKmG|0?S%pyF7zXoE{|cS3?Y!QBD`8Qk67-JRf& z;K5ykyE_DT2<{9L7$h+G{JHnt_x^kT&+0WjYgTu4*Xi9=b!?wmbyR<-r=CzDPRrsm zisQHCW|HOaxaeJ8C7eRUjW2Z8ea}LaDVv!GPGwVC#_W6vdYDNijRL5aJD+&zHB>ZE zH~nW~VT-sea5X|;0=mU)0GXxF)@<)RbNXH0>|GJfZbZuzCroTXmFaKc;$mrslaNhnsFSQ)+kQ6pC?OxOd zbu&|SS<8%u&ij%uo1Df)tY2?{*ZfaMQ5C;rj=u`uzy)H-VODhIV`c9|ZW#FVBI*kly~IMz;WFx<@q=Vz8IS#JC-VJu8sm>HXUM5r zC+6Rw3biqxm_52MR8&t(A(q}`i?4)tBoQ#DTf7j2%tQS*V>e_a+?C8KwlB&pV5b*?zDIqil_S;kz?&>l zCQgX5_(zdx+`F6ixj9{H(Y&fZ~25CpCSi?3!7s`FJmwr<^!5Izprknt--J=kgBcFv6!fpJl|T&;?~y-RT9ZNUpLx)O z@x0(uNj_Gw_?w}{#-{X93M3%B(~oSSaok_N%~UE;N6%u4sAR0HEM{h6%&FO3)_7qE z@B4-`T5*##$Ufvjwn2+J1n#PS#S3Ooq_MRj;$<&5+4jvpWrBwH;l7h4Q0$vM$xgZsS#Nv2=ef;d|Eg^ zaFG1jEqG)q*{Vpu3*Ubh%W-Ljc}Cgr;;7e~kig<7Z4h;SA0N0`sO4A{Zu}DW6T8~2 zOV~JRU~5RyDR}Ck!Ca4&;zDa!Zv!!xSJW$Y8$s8pI>T`L;`l)8_ucqyHM~M0pjZ>6 zPJqBl(;?T6o0{_8oXxpi6T4@T8hEDCPkg+fpyWU~-7a9BsThx8N9!0u8AW~I1lM6<>&1(@COV^`~H#Lw3grV5X21w@MYAGz|d=JvJs9OYKv-HkFm1 zY$7VvbAa|}7CNe$G*wFtvCPh7(ffoq8{)(m!UzvF>4n1+PZLZ7=f( z`D@ha;phUzY+y%1Mm4xY-xGflgBK6RQv}jGa)#@Ty))gwfF|Xy<@;I`b~6|f+7-;6 z{|p9l*z9>KsMYTK4kZig7a`UYbr5?KkGk;g&=etmv%s^^uwu~SCaOu1U>Y`U-$TG} zq$MzG*I(@GsN`ejUZOS}G^_tI#KPs76)hu0UYhtJM_|x^H2Y}k?PimpK?!|H20Rsb zkD-2!sP$pWG0;r`FWFCoSLNqEkWIM^5-(iD4_RXS&a6bN1SV3V{bX|9!}=1nN(m7h zNemk6KLP$0eY#Es2QRh!qrH-NjL~5F-2a#E3f4@&DtjK?2^#*!8kF+Nu!6+q5Zu@Lx2@U`NPIQd%>i9LR;8ApSLe1Nndu0ar?do zX?{iCw{>01?azfaXRPq;TNmwyNNVid*p4^h@yqJy&l(z1I%#|f@;Z38o<;OpG!ut~ zVRAM5i}ge!Scp_AToU7t+JRX4@dGzq+^lZmyw2@-{H!n|RnAfothd$HvrW#`2yN$U zN4LH*iS)RVL@gH=SewBN(9XDPR4EQSFT3kjLt|IOLO54rp}Izpgd`H>9(va$mE8wz>S^J)9Mv@ zxRvCPg*a9?@F$Dol|j!_;o!fRp1mvhn_KUDjh?{ft* z0iQetc6Sb_FqaHktlZQ|l=~MdIHs4hadRR9Y8LOTa&w(q$5vhZ>`ORtMCmLPt1&AU zi>AaKoO3G6>bXQeNMhIFb~G>3SFeN{AL~b9fXq6g8kjl8m3g_RxvS~PoqMQe(wPa$ z-l+IfwAoa16x$FC=a9H_(*6pa)09%+~g54&HEign7kS zP?Ws_%W_9}W{dgU7CV}X%9oZ>D;>rWh(zDlVt!u4OC^W>sz|8tW&k_7&_LTcmBKIIek8^;*3rsZx?7HA{Lxu^8@wt=IPLbPr zt-*E8^FlYm)IP6ku~3a5RiXS0G15Y?Ss^oN?~=;r@*edgz8V0l@6>T5Vu0I`hSiJ1 zkzEeVKs}xN%+artl^+eKwN*`U@fJRg2OgJQ92&MlIXhC=h15tQbgdf(CURgO$!{9b zjeYAPJ~2dV51>_`b*cYcv_d`(wOu4&99CAMc;A7+6=#_)nY&H9BXT`?5#6^RKyA+IuAV9^16znrTeFdbej&0}8RS%}cPul-2@seV7CD;j9Myq+?8+QjT5uOK=Zyv*3Wg^)RW!l3 zPWlpXF&`e&-hoPwBPwH4zWB;%FcCs=8}2H}{o9`8%T%ZpsQCAA-tCQbHM@W~lT=c1 zxh9@l{Gjz_jHb#b32}p^^OT2U0#AT~unHdkt;9ET)LKOsjj6Guwrwe|B2^~dVpT@P zGH`BXjfua+uG)A*-1}y?IBB)g1^YvN1pDSea{;N6$b*T{^D2hOJfa_Y%83au>iylHHC`O`$juD$4p58JK5o9zM-QN-I)w^aLp=;5S(kXL*M zcgzU{Z|Zpj2I+aZLr&>KJw=;GjFstIR0m}@x8yqjg1h||H{}y_A6f=+v{n?MlI_cKgdKbWl26O zvJ)y3`Ad@$mS?UF>vFmlWzgUey&A9a+@VDm*ua4ZG7~xCBIU?YcydF6^-*~f^5jLC z-?V40!(RWTI)|xCU~@n_Rx7iivOTCv3EM6@Y5`foJfhnq>sjgA&?S*E) zD95MK;}zJHU(>95$IWNv!;T-P#`1e742XDWa9X8vO?@7~k0XVHq{eDgiT}u3>-PVa z-Cj{_+sKnWgS-x4!W7BQdQaI!SDz*ZjjTduCyDnJW-a{{HBiqGr+rQQ5c3#-#(0CbW|9bwvj8zCnn?s3k~w;sML z)!ycF#*fU4|Qkj5{_}>coRP|gxMEH8quq^=injuk0k!HaT>BJ4a=s)0j$GbVKv#7|r6E zFd5D}`sD=VpRCe+U}lwZjNQB0Iep%}@?dFjIV~f)>yg*!0pv~WC61tbzt`{%dBE)e z={Y!Ptk-|ejkh^)u8^)h*Cls=)m&Xhnr)xiXqaL>@tH!PQgqJ2)yy!~9wH z=m9q#HW&Hz-1;Xk1G#ScW_bH$vY9kMGTt_;zBJLFUE-A+o%)AtZNX=%!N8bTB*J8fh;HEV5?X-2_^nJX?yA1@6UGsTVhQK56s2Sm~)r z%jTD}ph_*JhxBD&!7gAC=^&1_!hQH8?qhC(CsbogICPe|4_AUDA!$n{tNpcvSQjA< zgIc;kB7x0B%cjd#I~<`xaXrvE+;}fEr+oR`o&&Kf_Iu4>rZL$J|HqJ_6?j3**^FEf ztt;Y!jSLSRC8q8>pNxI)&zZ$>qx;ADJT6zFlpTu_F3z7@S#8bGru~}0*6KlS5j#2u z{PAvh7Q_8vPgfM5rJ2J_ig6Q2r&1p6Iu)LSTTzd1Ohfm?$s_l6^j--a?iU@09EFlbh9#OHCy;4l=lgi^tZ+QVmgj zkWNLWxhEG{=`+@<;-<1KZoblhDHbxyoB%-hKm9W4lxK>P>)n_zCCkHw$9(6X`levr z1Z{HIojIIbV|{^Rv7sF`(9nStsc6lZ(&&YaCF2m550b@72TptG7Aj}<2sR^<@G zayX(HYlL}?b^+cLsiltOb%(cMRp^3(e!nmHWA@w)erOmkR?^xfp@+IWdo>(BHNC4( zUzxC3-rqV1WF;&Wb!rXptML;j4#t`#T-*(}KVC^-o2b(N&ZHh} zL1CSV4IeQFpzL?K!m4gT7E#uyQb*dqiaS5g>Sm{uFwU+<n5&XH`=MF| zY>%gd*Q~G{hfN*6({)(+bkH2}GA;5*$lpI>PZ^kQUBuy_m%VUqA3hs1Sp~wNg!Rc) zTj8GeQ&b{2a4@_*+)KfNoj6RonuDXQ_VyRrqH6p?6LZxs0!|5glUN!0{3rZd0yuVN z1dm>V=Y8>JVN%GrWn3D6?0O!%lkLE+@bxNw7ua0piTV(wXm+{_nZk~x$o^BBg}L7f zhqRi}s#$blCCP|P)%m0JuUUOo4vDEb4%eLXH%|My>UwXzrB=ftmQ<}q(ca-;K ztaEt(js=*>TYS!aCDfPSIyhQixo`7HAHsB`J8$!CoRr(2mKB>r1-|m!N zD3j}?>OzVEmVyrz6T0oVPg6(x$dny1BF3w7d+@Ci?XA6cB*fBHX=mC#G^S95fU6hU z7Q)CKi?ApWYHlv{ii*ti^l)!F9xwbIuCS0{2qtJk`n*40oc-1xV-0WfCYf*L>+X4)1-x^K1^^#f2E#trHn%TO3I7{E|_a!9pu&>}iE{0Ntab4p@4z6zJE= zOU_m^b+DD~nfiCvtS&E|0DbA-VH%QL=En*2Ir|o zi{l!M$=SqR5t-?Z1_>o{w~%fP(8qJ9365$A8sq)iS~Db0UKc^5GHz{Qr=_Y-)2+C1 zcqamu1Ut9ZQfi|H&wGO&Q%E**0dGlO7FPE#Z^|qclLLb4P4yaKO69JO(2-z z(@)?~!q(V4DxO`l7Oi=<1k^PP*)JR}nis)qjQB4)+99PTTy8C>b8BdP98XsOgIzp^ z$F5**PWf2X1u{7@4XEgxJ?!2lV6Z=!2x?>BjMB-5wqKL1T8I1I3P>|4#)eih-mkqR ze)kA)caQu*-{$%pr4kr?`HbzNg9X3K@Ai`l5)(9xdEXz4A@vvT!U-pD+#ds%Dr96f z{BE?`p31U|A#vL*uly@7ybPA3_g5GXu49Eh@Fw9?c%|d)tQH%S)(TQZ`+x3fBDpjo z0BZJ3A7zNG-(etmr)(c;y5<@9<#f;4DNJdo<|IYRFh6fvCG_g@q)gDy((-grbq;ra zA&|_9f65Tp{ef92MM~~=(o$ZB+Ray)p;%VU#MP9rhCeOX<)*NdvbMxU=SU-m?aUe@ zVew5y%VJNqj0t9g8&C^g@&H`sHvHfd`g5!zuCYS2iMlPG3`AJYINtfKn&i%+Ue_%g z_IMT0n&#&P*V8hW>Sz01pJBRW_*kk-eoyuaz3@0<$njDPrr?F{E}lgHB$b+M`gi;B zGpWL9*8Z<3-KTm@|F4EcZ}oGq#lkSdu77~c0=8F$#$I~FMRw`+Yee!UXoP+bwZvU8 z?{0F=#rHPVtZDGapI#GT>i5f4Y-wa$GT3A$QP1t#HBp^pPviz>IU2kMtapSIy)mTo zcHnbhZ1SSVCqmEr*?$~9pZ1CA^EwQ1b4>M9!n`ea8|Ux&W;?i@Ov5-#EW%BDu!cv3 zo4h(QGeNB9ER#Tc0J6Hr)La9#w~{UHM_jXtumSbq%yP2qQJ)#_B#w_&o=YC&YWvh5 zD)Te8I^!$1tbCg?VQ@l0NKIVM2+j)z<2g*;E9?UP;f7=?voYy%`(=W4+>#CsWnnxGKMqOkVzPncfAyZ{=^u0AY;|?r8zDa5 zPJqn*J&GBk8PULWex`Iji$`KsOyGMwhv}TK+i>rl_z{?D?;gV-{W~4}nf;fRlCv1j zNU_M^0YgVNyRBt#p>;w%KtfnYdYAUoRq0IF#w)Q;?|oF!GnJp-iZ_&UMBB*1v}Qg$ zJCg>XRSU+^nQfGdC}BZ{X6fU2L*ptDC2#=~HI#$I4r%ZDQmI|@S%Xorx%arkN^gN4 zb>GEc4Zh69;~jlu3*%8FLX1Vc8=MRIr6D#6pgoR`H=Zu1Ca*|OyAJnDhXrB)GFSEe z#v=Dt|K1<2J6jN<#*4duHNJ0Eu_3Fe<1Z{-DqXWUox`^x$%O47%6y@Wo%KcZ0*d-Y z?&KVgRxi3mkD7zst1Ldh9_~>Pf;~>t%1pg@8+kUH?YErw0$uOn4*%%v3s;G>_;n6b z!B z(m9*rnT%p|=bmmSb+{^g-VyAPN_)P~xn>$)zyX6s&!y22VWU*KP7J%OVO{;R0j-ud zYUU3u(9J|cV~LPuBB`>{<=oUCu~ z`f5(w@ii;+=;t?T0-!%$Wat%=At5**$g>!<47@xq4)g7|CshM?CKNGJyoz{yr6RXJ4E>ShByo5r#v;1gD zpd%Z6ElHOlcz@HTV`TXfV-uLYtS*pg;%S=+Y^Vd=JV0|1# zZ*Z^h$S!ihFi0i)5>9N0XUZJJaP7fa@KCVA)OiIPlC1Tr3nO=cq|r~Il} z_G=@F8ii*ug9quksixf*hwzY;P=;_Dd7$L_`+{kCP}hc$%ygm>s*%m>qbm|ut|$9o zozL(R-EvTL7+zlMEac;*52mzx7{-&{Q&&If@#YdGb|UWPZBE&}*?!{)ZDH@<_1ugk z5?Z!_W$U1#t#Gf47t)%*d(_n>6v0s~j>H-_D+sT?57P%Wf)}GSd3?eId5_S|b-I+a z3cu7iya0i-hyru>pD!c(VMVI)Wc>8MoG$Y9cT8?Mw9e1e<3}I*=7jM)p9=TWg4-05+LBnRhFDpDZlO!C*JOe5e_sS z{?lKpRKJpQzl16s@EWSAaM$BC|5(RLUws&L=Mpl2<*#2nA+=HmrU31yJTyLpn2|&^ zo?7$K#W0rW7BHd?r`l;oHaqz@=l{xc=UzBKxlo+CKTWF6X&cI&BiPo)n`0sOH|{Az z5ijtdGxiEC+&WI#I@ZOo6J7qryx8ium>)0JdSK`;T3$=2tFazgA8$K|vXnnRDww{1 z8<0Ie-*)x*1-agMUWeF^HObCNc^%ZA!B$RF4m4f%XnxS8^uick+2+C+Ijlj%Yu(0m9vbkqwhaUAxYnX>ifs=&C3eK!|mHpH=Z<}P>rqu?)Smi}YjlRsi7hMp5$ zE=~SWO53fAp7;H<%IUu<7LUJ_fw{eS@Ppit)p>8h!OXaM_TS_Z=ZpB>fxeFpzk@^i z%a(`raA*f1>_WWRes(i_c_jVa;}yRr+y_pNpNm9`3@u_j67IMQpqq4rD=ob9lL@C z-vJESeg;Tt@QZybL}7%%t308RflXV>dTm4nB1o3t9c$Cx&(``usgy0lEJ0is^IG?B zC^Ab6TmX3=c%W9${hTvG3bJKv#Du-wna2A%oNP(tvsFYypK5%VvzPJR&BG`PCysVaG>W4+XD}^sPF0iI~yar=%DG;b!xd< z^4o*$IZ1(03%5`;E)Q8tJd2*<@pNq?Y<)a)=yIUBsDe~_+2lumCnAU>PL-N!5Y~)T znMxo+Lj%kIoz24DVla0{_veRpD=L?IX$2_xEuXgP!61*R8M! zIdkIZzWx$nd%*}{(c8IT_f)DyjJ(!r&6FthH9Q4S5v_jDQf(9T@yP~d#)7;XnR`yD*tE;(Y zWvGHA1z8!k{aidTRi*tY447$N_fxw;1)elT_Hi7Uo7Hy3wpriSO}KKESMY~T6q_e) z=;<5H7`;dgyyO9y)N?*oEb(??C)~U428#lDs;2ZlLpX~QPcBwS~O#083fXsWN^zX zNf1)PGM08c3WzW(gb%x{>wihT++?9y zSbae-N;>4pvHQG!ITXffe(t#C-k8hcxBT7zoAz_KtDPbc@PX0lE#}?Q;PCl1NoZju zqk6E^E>y!V<43}zbU7=+M6MY*;n3( ziE-Fe)`C~LZJv-uprs5WA1_ZXmSRsu1o@n?l|DQgd1k&R_QndI z$t%i%gs#DCeHp}Ld3MEgV>esr4TZ#qMp%GJ)$A?Bc&T}g=yIk<%h%mJ9fOihJ%3(Z z2`5D#srV#*^~cdDNY*s2##I~-Wd_(R#I!spZ5sD8gf+)>1Wxu@9UCfL=famiIX%67k!jnr`Qt+HB{c`2wYBrPt%-mZr;QMRh+iWyDHvsxb!GdLh%; zJ52Gh;NQZ|FPeTvfk_&=lgLoxK=Ont;GoWo$)TOh@Mzz+=@+eUVHquxvEdUnaFwg0 zwou~@ozygQM+mv%2e}g(e!$EMw5U}bUu(FF>Wwy?emdeYh=}nuqT8}VC@);$;;tdg z!pG2GL-outrd*zxGl+C_?njc~WuFC+*6SZ&9bLVC#O<01Y3K#{pGgRdRIYBpmI#fQ zTU)IC!NCVCxN=-ENlLX*J2oMZwodDz9tmb zCin!cNXsm5(~azRlhWT2Td6=<=vy$1mQeTN?fOO+Su9lMEnN#LNb&F=TxFeAqH52+ z2-WU|FiwB0uJWEjPZ%0KQ`h4Du6KR;%921R?@7xLUBPhiN(Q-H!CT7@9nhV4eec|0 z^o>ULY(&%Ap-w>YL*2+ue2KoV9HASZRkSp*AXZ?fc(UT5RzOSQtxDYM2q|A@XP{>H ze#YysThJE`)a>T?ZtWi_5(|bdl&<5&sdoqUpo2yspWkOQX&OPd5FGMO1?fW#;3%e zoRX{zi7w+D+hkiB*jUe%D!Bq9MS`GnW}1f3rxEj&i)%!63EcyKxT-P^HvKfbGfnIm zp(DOVyAZ25Rrf@ikWZldraM-<9!DfHGJLle29}BL+V-la#U7~sTR#Tq%U9ZajBxyh zPDY;M{3XubPFBMvbN+JenZ+M@5q{ogu>O{e8IP5h$e=FOAiDoPHGwB?IXz+4{HjrD zy~U>TkP5ms%_nV$PJ9b_z}5e5;vidSDq>&aQFU#}^~#NLjcG%2xwY3FUt=xmePPh> z@zA&P=yS{Rh&ocKyhY*TOH2+o3p?sU{Y79_=#G7mLA7SaMM>WupL)10J!I4pHT`54 z$OS{ER%`uol118xO*RvXiTGxv`%9rCPo2JRlibhrH0t>EiNb;!^4MWmsX;xb{*!1k z5hZ?MhR(OW9j_)X7nP%b7)6d=5kl?Cv+mzO6BDi7t~_Cz-^a91bE_bGIy{E+7=&q7 zvtJ15@bnAHEG&8h*PF2Gb7iF!-r~YeH>3VQGE+Yrh@UYj+&3QOi{~H3)w)x3Krr_R zLA|2TJxZ|H}qG)^q%@G$w)b~nVLJ9p+EB8 zR_#|f7P1HWIF5e)#~9m>rPGAj>gZEf*c$tF9wBSFoG7_hbJ$ubR_>R<-NRH;=l2Up zknIP*61#9j0TZ2j)p!5$v>k1FZ67MV9w-^Q6G2Db0m3Li7}}tN?*cUE?fXRBZtQH& z1oiWwT%X?htJdSfG*{508zv%aLr{0F=Z-9hFsLfm*CBE>FSpk3-sd{O2p4uH_smAr zY3;SiqIK&IIIh5hh7so|usG#8*S^2*vM);_H7o=3jB%U80T!v_^4d{PRX8HnJIRh- zHJP`^^(3b+PawBRcGjhzG!1V-wb*laGYTfQk?tg^;?g6@XdDRnVHFtX5)-bge>~EQ?r1~cz1}8oeZWQe97@62@@s(4ES0tc=n#Yr zzeftSigEx?gVzh+O;)1W3bRBeVyx}JO{v!6Ewm`iEq{|_gO06bHGm(ag~;2tj=?)Z z0Nf||d`BU@B97!CT>bnj0!lPWp+EMCEFbpyD$u0R{npcRDvrj}K5(FG)X`g9F(M?h zlXL5DuF}?{9K%!Medl&?G!JVgC_>XJ%kA)_FCnr>&R{G__#KuL01n++q@yAHO_RHpU>z~>COYP+sIb9{JV2x??O2B0X-X#8N%rge}RXI@0J>e=nn$?wxG_~=y zvQKC2(_MEWjW?|fRYbc$rW)F4IDgt`=V`r;>8P|`+i%ce@)d}5Mc3((zYKBT>Vr#k z#gKT{ROW(@C#9%zuvjv>t;9#da0ep5lN!F~PISYM7aV>GE2|KuI=h}g%rCW-Qx)Fz z>M62zCObzueJ`Lb2y?!sSB3X32TBWvwSbPc3R7tjrW=>xw3)97<`ZhNCU+xbtHQM` zA`O2tQ50G^w>aHEUz&}V=*!VivnDip{*s@%chI!kthM*vX5xc(?i=`?E58CI6`VrU z_1I#aWtQ^N`<;~?#&}&djr9?tNY&DAFT7-zK4^M{HjdrgxUqZO^l@n6J#sav1aeBm z(Na}++?uq1?(QqKO;m+!=2mx=$CPP({!bIDw0iC1V`b2==XU966t_i1*(B0AvIzkG zqWQtZO%TwIJGicnpZvo{O&=cT>@oXYZSOqA+5U^5qCT55xVHRTW9#|PI41meALub%wDQbroWGwvfCu9ab|(`tuvK&(2;0 zyf&3C9NRcW;0!iVKWkcC=>|c#qY)-zuTzFF5~_F@0RI!p@TnvQVQwm zCz6C_Y}W7)r`xy2bXPp`I+yrY1T7_zfu~PDQY=Dhe!iQ%uI)mLvaB|n4L>!4fG;XTp&8dAOl z9m2pF)JZGw(ukz4HqfZ{`B5-F#Yw;-X82R!pr?KV|---79J!*O+Upm6SZTaxKZ^PXZl9Q9; zpP0eSPALUmCvR;!#O=PmJas)B zWd*EWc~1(0x^5z{(h+uV4t(AYNu^b5h+sN>S{ra~ zx6$Sj235YhcYZ?Ul^Z`nM*T}0{KdiOV>Gm+@4qD&UMny<3az~sDLOC}O-TObpV80Xf?r7JAX4<1 zs&O^0)W-XA2gbtyS7Ha+@0Yy@oivWDDMR-*sC?LH{yPXP^s?k&KT-6Eu=gHerPip- zhNQBxu*NPSG0_L=HUsGg?#J^Ebwl;IO9rgJ+=KtQX*L$or_~ug5fMv~Jh+|gA{!FN z?VhQV69&LSU3d2sv>%4f#eZFn^6$&(!-9IA93c}`{~oN_(t06Jy;edL$svRMyOI*fP_S(I0CNb*OQ9pWeB^&cYJ|S?KY3W42^{ekv8va;e0>5z$>xXV=CCm- zg!2DNPQd~H6>r38nneAuZRn2m7Z{{_ZgN0hOBpDGp0ECKXF~hXbDf=?t&ArHQWk-B zpkCV<@)`g|O<7r4ipALO?(W+Jb*Lxwu)pW{&3}3f{UL(sxY;pWt=D=#DEcg!MBT3| zj~w#gKkY99Jetbtg1kPl2`E4fBI$_O|Mh~1-^*PUQNAFT;03(`gA^CIQY@mEGb<|% z-L3zU5B|U8gM&#aaxfB4$|mqHzXkMiJXjJtPOnE!|60tkaW~}W{abp_6aU&SC;x`S z4nYdyn>R2tvY*7&on`+&X#92PK*|5UCI5By|FkK@`Oob@9~bM*!?RQ*lsS5 zTU+|iU+?~X#{0;~$mcoAm%0D@s{AFp-S+>Qq5o;=pWFVwZ9p&apJx7lIY65U2PXUv z5dQ8G=ie<4(72v0v)tX?{Yy;$x!D==|9J?1JF=~gAV_1L841h*;_GjqA6Y5IPc;(8 Gq5lVFM9iE3 diff --git a/planning/obstacle_avoidance_planner/media/mpt_fixed_traj.png b/planning/obstacle_avoidance_planner/media/mpt_fixed_traj.png deleted file mode 100644 index 2344467811a836401be47740c68eb23b6cf33420..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 13916 zcmZ8|c|6qL_dh8rd&#~;McMatkdP!KlAXyic7`ltY>}mGA!Hlx2$gKv_ua@gBE~)# z3)dnCectEuoVQPPG^nq#UL_$Rq1Jq)_Kbw&;vVqc z^)fl|`uQ}|2KaN)^MR(pWuWt5s8FJ{0PxbX3WOZ zHI2pL6-%6;@ei9Z3yO5F;MXq;|2?SJuC$AcjFgdbl~+Z& zg}+X^zN3YHFNsLlo)H8*JUY$-{iukB7%&{qE@XKi7a4xd?{U zw?MZNgq4-&(gbH6I17)*>%!tfPi&zfUFM3Gm;)8;bf8{Lj0s z$-2fo#XU8(`Q!6%{?j~Y?u}lL=bPKg?Qvdn);{l4rO@0Weeasu`~_1>Q(R}>9{M_c z{I*65@HCMblvS0k+VCsDx6GTerOkkGW&Ih~pJ$HDP@OJkx(Rf>CHmq;@s@d`0${1g zE>*L-S1#jPbn%ok<3COXT?iL;hcGqP`o{j!a$rLPUBh!YRg=t zJi3_iZdRFEw&NV-{ieJI2Kt)dk>c;zv#8)RY}^^jL1e+~upd=^_BFCg5_TABq=tAC zs*`A1S2a2w(D=`E)5kkN^BPF#YnTmFUS!odo;!iu*+{XOHFmGFJcS#urO`h#@8aSW zW9n1E5&Fl!Gy%stZ}T-3fwq}36EeU<#^ZEy24~7d8dMa&>B8^v;L`rR3;jX+_x|Fo z!C|I@L0pp>WFU3VL#KN$M(($?z~G{J9-0&)obMC!A+% z=R;xjnbmj?9ZdM5MRRVL)@@kpf>z4Gscs-iFa-4OLafvc6L)qBbhRwG8T)Z_&b8;4 zkAp!dCdci+R`9Db#N~W4#~6MtXaD;doflPtr9>Z5WF6B!>c8`6`E2!0Og=kb zHCvLs!w|7f7Q^h8+ygC1M`{v(k>+hPM?GrHuETGLeTC_cpZQ^^l5rZ;-JOJH$4}7= zdFS#4@?{dt{>8vx7QHP~w3PSV^qO1UF%?pVRZ60?7d84={G1;rc}dPT^P`~; zDg{xRf-t^Y%hV-C7eIoxlq)?VP0?cEI!$febKRo11yBZ8_(v~9Tf1{av>J^RTXtRm z(~*#4h+>^jN4Jv5l$*sC?!9Ym-H%TGK!rCFWaN9L>C$Z_dh=?|=24Y8450#I=JOtj z<;U|**slFz%PjF&zGiCb1H-lXX!?n%r(GY5l+=ZKqzr^#RJq?^f%H-wlq7APW$9T_ zb`kFFg@r{ead{0_fkm}#?FCH|C`(B#K#9vJ>ss59TboI{ zVzR{)v>5p=g4xhU*>`z1LOjl7(H+d8INF>GPGX&(?rwpfXGP%|tBay=2S!)TP)JIU zN4j32ArjtKgHWJZ0ioKg+@nLWa-(4PDg$HT3Hu&Q=fk)-H>U90nwMKiLWKm@R`o8Y z++Zn!Y7Q}=tBnL560BbH^oaGBbfA-)Zj6K|UcK6qjGgiq0&++Qw^W;btx>{umwh5KfiA1T@s(*%Wj zXD@MU*7ZGW=r0af7Vtk>BWw*G_W0u`f*w8T#95rNqYaBTPnwQfuJ3>7QvYP73xq8M zEPdQsR}B&35!4U^Y=^)eS?iHh+;kw7(aQZry*>5LH??+Y$N(WxZopnLGLxpk?z-~j zds`Q*sf^>XH!j6u-`ldpT8GaX=%nS@z;qC}dG%OaUG>)}>^?KriX#f=D<~|OV0TZ2 z`6Z1t~`WivqW{*Ey$ z>)wPtb@=e`jS$h#7} zK5lLsgNKy9MGKfSnKO>{$;Ljell?mXy%Iq*LVN zM&O!OQ~z3>!mD?0PF&eg#Gg^@7^v^&IHk>+YHcCej~#o~0>aV4sb3NI&zI5GkHkF% zNqVBhe+#?|k<@%N_eM6hCt&Z#_YBx9>$>w)%ct*M0?uMIz0sca9TlFVi+_y?5)oyW zY#+Q(vf~ZJ?SqL*u08QLnC&ZQjE#+3Hrf4ATtzJi+4X4&aBM_?_nea}Rn5JoJk7@q zCXhfo&Zs+V>jX&jr&T8Jh#?PZ3nN3x$_W=%Pl@(W@Wc-;(IsMOGvIWgCjpB%CU^4) zt)3LwRn8yP)oKjtRODpjp-O#i(kF%K_3j5(Mb?Y9TViN|hl@I1M4z%Y5%ZgZy7^QP zGXHFWYHIzZnEh_I4fI)IlZtZHD`>UnHd%-xHQMXzB~k%T&sQcCJ8;F7n9lv`?2`RP z2?V3lU4fFkv z4@%~md`;lJ60z3yit-kJ)fOiP+o6!l5%%_=X;BSsmN*ej=m1%RThR+6e0xL#JkUk)~PL z5C~bg{|d_)ID=&n?v(w#$U0xt;ROo$%lUPs(YiCHMS`9F_bF+rDjljO_F*a+oxQ#NTXRth zhXup@Nsq&H@@XR?44j_JyK<0|W&4G$cEILTdR?nR6K~({(~aFRXN}2 z43=AclJS#0y+zN`jOXojzdlZ5#6acyUBOg{!wo5mQD^9kEOtfRNvIRL(I711E%*ZO z^*y!ap+vbG*TzbBf&XDBaTdaMoD9!gQBa0|#^1*E5QKe?*F(;lasOd)SnKJ!T`xfx zbf{c|Sz&@Gtq)RWz1(|o#>%zkyg9fheI_f{z8w&f){{F1V@J-0?veIPk-hsq1Gmtz ze|fmZ7>k>s-<}wjI~^OpX25gUDJrV*dbn%yLFQfl{63mFQaFW6k&NkaVzv7EXR3sc zI>l|nVf@NtO`&2md2*BRerCsARw=#?*>H?FHzqAAT+E2WiD}tef#eN1GG(E<5jkZS zHDFSkDNNEd{&+vJ~H$6wQ2O-;=54K4W=7 zbLzAff=R!Zf7QBMg&npMZ((8AC^O@F^nUcUsgLw>zMNCik1aw}LkNM^EpBfWuAnsk zcnX*MxZOi}Ax_}Z6bMVf*ZQ+ZqMR2T3!z# zVGUIR{rh{SCn1<=-2)W5Rl^Lo4V`TJzgfA;DaA|*{CM>VvZ4I&np^!oOVLF+-sQ5! zCgfCD@XeiSNeQhXu~!q?MXr;d(aY|>qjtqL5l5YnNW0{ZnVF=2NpFl5AIR#kw1b;d z1?9*l2l5HY#DG^N+K7dEI^-mjyNnJ#0Bw;?uC*4Mk4{jb2wmoUP!%J#v8d92HX%sd zjS6``R%0BEeOhSn#ek=Fit`g;uDH-j%pl_R7;aDE)VYO>(ze}bWX#ss_=ZDp?|nW& zu0lacQE0CK#l2lvR$y_QvOe;yr?Va>{sriGHudWDal(IhundT9Cc3i_kL(cI|uuY0vtAfQbwr#qfF(SfcQgA`t z+Q{f5E;r1$vfxI@P2bOGw&zGG+H~xZNrcel@T1?PMfm8b}gZF$cfgc&!d?(U= z#JFtzTH)^tOl&4P02`B0ZL5GXJgbnY__~ZE7W+<+uS~8dDZ|fzPh`vEBnQmS$Pe~9 zuKmQ7{ORt1$g`E_DHcr{#TbQ3P9)`~S)645M~B{$iUxJJf!tvoD2+$uocNbjA{>BW zSXlt-zdHnBe0PT=kAnrfVbD`?*FNmto{J%)@RZDGA};hFBf*3VEsb%yjc55o7U5mD zQj2@H$0>{FYK5Z&v_9ALoK8z4uH}c=6K+4z2y8G z-j_)E-u~V}7cYBGNrzs^n>saQw_{ijO14nDX6&fk6%+m>5;U|24Jy^P%%IXSZ+pBt z7g17OE$h0*Q8U=%@bGzZEvG|r38Gjc(t1!bXJRekjZ#@znI!A(=FBy$Y;SMx)8A|c z8KeeQ@SwPwFgc~kJ%+E?q|{Q9 zK=!XuhcshX##x)I-#Poh=!5^_n4wT|NSpa69^h$Ci}obE?FLSWAudH?8U}A8u^%g( z7GQN#!Xiz_;#p~4u?yz;oi11q>H~Z>^<_OVql1&SSCHXDsKiyLC}eVctBZ(7ryw!Uf&eb1bm z+1DOY9iGgN^?iw}sh8FN#BSl3urOC2l|d zABge240^N2jHxlL->^fkG)&i8Y!EMaL+s{soHXbyYlzc&v*T@sQq+k~@^|LpT?v#< zSB_^slznK^iq;SRJd!q>%b$O0LMgG!@`LAApM*aeI5Vr3O=X*W4P5oPgG+gs^fx&b znL$>B`}NVu{b#+ciGE}e`E5o={@Z7``<#uOP@cTJ9i8s#JxC8Eg)~D#>2yEl zEq{YGPWhXW07UQOW{&sH6Knh4-T}N1*N;7lru-k`1ZZ1J89Q+aCtcJ+d%<71SvGt) zcX-qNnsqbdrC6vt2L%!e9Mlqdt%R!FTrbQVaBB5vF|)tRo}tV-Jib+|Dopc#OW^)g zG1O~;fB12jj73mrZf-8PBBO6;! zCky#!=#$)Q;JX66WXdS`GY4SMj7$8ta%U{9xfvmq3`{h`QM<0jC#A5fB6?R+r22B(|Q+JL0 z`L`7ws@T=USu9Z?3)o%cTt;=w1o<>cdZwp2Lw%dAME^1=&?_Dpbz3X@;k)c0XwXmk zpMRjLo3~TH_6@`xT~v9LcKfzwx9mQY^Ug1EWFsgN2Sf7CaZ1o2cy%QEvvqi5@^upx zrz;icCs>yD;s{@Tb{<0e^NA7U;9!ZXqA{Ng3*y{TxYtVZej#M3z!2I3WuH4e;p6V<$op@0ScqG@DQ~kQWwqTiJy;!=?@G&m`>vq)+V5EhWKAa> zN+QMbVC?OY4rPA$!y3$H3#;w$r;5Y{f1>Hx*t1GLd1tKHZyl;LX3fEiSXnHI#6~Ez zW5Hf&W9cxa^~rU<1-Tslr{qOto@KW1AJzaM3mA9PKQCayGT7zNCfxPmuyrlO`7k)FMQm%c9gYZt<^o*DgEUb z#X7!$MamiY^!_W`M+&uH+AI@Aq&Cy0H>ywnifeffVTpxxy)v&E_>bTMVJ~2iCR$4r z^Ts-9$z<1i)$AcU7k&A*>-lhB>U*OT^55>6_UKiNEv+XG`{tZ%b)p1T)gJlM_^&#_ zUxhT&@~#V*dh{5YQ;2GyI~dDpOtDxqWJgQx1m44CcN}RxfZX%$SSUO_xnK-4`JdaG zA#=qf$bzx*)$2Q_a&8e0Q`L{-a=JkZ^oJZ%8Q(k0h=^XDH?P}BN(|*1Vs?K|PanN; z&aY?{Hdy=$d+ykB(jVmAh{x7&>d`$b9!dQw)&DA^!gl}p{G}6DE~W@s{(M@~Ro{}% zd7IhnyLYcDAc7~jcD@?$>-t~)k)ixQHrLFcLz1OMXoJw{>o0Z49lW!x+_EnbmtH4s zOX?UdWcm&oYwdA<5~>_uEBjdYT}aS|ARgek(K#SH@X7l; z19(6YW;}0vO?l)XLGm84vy2hxRl>N)wCMhA!9A+4u#bY>yizzq?-7`i9ofNQIJW>( z;za006DK6v_#3hJ>@4OJjlY8O^Vqke{t1?CzrRV@K_IDFrZ;1)S$E4S0+bZn6gPX{ zeqtsvujk2(8@N^TWwG$-Es!xvfL_3oc?3SPRC30>f=?akqy>CzSWx#CoJVNQ9o=q3 zDGbv&&IZK62Jm+rTBlCduKPTYeT4jEQ7|m;Wm3qs|5@`f-Qhg!a#8N!vK9aJ8*kbi z72(db>aw-ni-^n55xRhV=B-W5Eo{$aiJm`Peoe{o&E{RRt?cH-A!<($nrk}EK3!3+ z8e2}L(ek^rv^r;^%`oqJyn=0513%5?dHQT`3T20A;9@3HrD zrz1DWS=kS4d&_u23T_5A#n zW$;nvCk@;&MxWfLQ%ts#%4bRf8?fDpXQTOD(q`pYu7R=7QlgYiOmgs+C*YqT?h~ET zK4b4SlQiPE6lH5;ufJaUQtP&rrUs6LQt3St317R1*6fegOhSp>*@t~VMG4r!+G}qBlvU-vadQM&mEn%Wr4QD zt~Cys1okBVN+iX&yUBVo;KhC!${%9X=6%YAJuC#`}|r{{PeRn z8TsuuTg4W_Z**Trf=YL7lMnI5mWq&g^8_31(N|2*Y*CQU>{ z1cSOtS{{-@(7kfxIUE&JCTDzwIb1`PuiKqA8XEhJ_^^hP9GOaW8p~V9S%KBbh}gVN z@&z%9EtRCZbEAI+ymtaLvCR%z_POL(74`pLN4Lgv%x0Qp% zUk~Rli!mnOoVnK^0vq|`Q1OrvKu}9JO$Sa+fNc1Cs@gO3VUEhY#%BkBTg^9I%XEnh zQA}1?&5)(ZMsfA)hwrCWssfAL%Gjdhybz294>ze$@4j`qI9|enFs53w%!{J05iu*)c$Ot zAyWU~Rc*KqUys=vEz21h+9cBYaY3{Qj!AJc>O^Nw#gnp;1l)n_jfRGRh@rsnoB@5-0m!3HcU$Wr5}-Gr=i6`{Y#c}#p@^& zZb2+1_9_&n5i||<6?vV69MU-1qG#oW!-Tp9%bi<&8qYZOACyDYp7rzrF1`U_eoRI3DCxn^lUVf_n!Ef-}u~_&x zywAoXqGep%sC>^}w;F2Sp(lm;W#ONAw8?>ixRv9~5YrQf1fO0K5=M&iT!0H^1%cOY z_(Ht0B;DtV+6?i(k=wV~DEw^i%0M$$-BF6MmI`d)zKt(9vvAH+Q>_NK$Xs1qUkbjeb%|ysdV?1t($JErJ-k18`dznGKox=tC`35}Et-73$G|))avp1Z?~tW=LrNZ*$Q=Bbc^1w&rII2_H8wqT>i54RyT82=Y-(Dy z^h(}9;JHV7{O4u07X^3Z4ND>2?qB>%{QLJyhuXek<0dxChZB!hQ)kPg_1;K3Ug2DL ztI;OO%iF-I(9*7Ej+|kpKt}T}C5Os=OM>UmDZO*(>kW9i1Myfw2E60Rzk8L&ghIpR z_ujt2q+m~}`s)_%wer-=^h<(V{u`u?`kiuR!^V~Aao2;p)uDd=g6GOT)o6X)&+(P< zzqRKlOM7rC@&IAW+TNfYch^_LdA8 zQ~sf^Rs$3FjY5MMZ3?5le#2?u&FJjxXzSqGt1swoca*on=+gAPW+W!((}VzVvB1!2 zl5i4tp%w7t7x;Flzb>Ujd{0u+9g+lD?#m%qT3P|-#LxbMC~-4X$3?jmR+^)uBgyo> z&BhS&wy8{2?--Qp*?aFQ)iPMKg=buDuI)+;`EIyw)x@p0*Gb4jNu#!-)KuD^c!d*b zXzZoa1>aEb`Ds@Yt7^QL`3w8+2{mm^{u_KzxgNfqQqrz&PXP5CG6-_sN~8_yu2_Gb z{aB4oZO2b6mU1RG>qWuH`h>@kEcs^e-RQ_xd$X1ohD)iNMiU+(_@&DV2Lr##O?gA= zq3`V7J5d!HIO%~k?}+D-H+n;mW^FS7C}ZZh7htip zT9S3U*U~cIYan~&#g%Ll5s|K_jIjl+dE;0-hq>3R%GwzZH_Ner_vLU2Ey^mjkF#P|@6 znqdyb!@i4{&*|$lTkhXO7nxfN)54l+epU=SO^(%W-wtf|i2ZMym*WFe%g>ng?UjP! zISnQFnsi|(qmOoTUpP0Fs$T;qf}nJ41CeB=YJRX3vAVW)!IsjcSl_U5to5ZCAkjbj z`aulii>cPTl*K{dfRujRl%#G>Zc}E*29w2NtweVy$k?$TT$-h=9V)+%vfbV+c`S^C za-^;ChI_a*dgC_k{v{DUrxP(U5>ed~b^LiE53@E~qoi`j%FB(bY660nC}!85=WxCH zaV>up$2p-e0SNoqUmh^12iw}^#o}wLZL=R66u;!4u%3O#mHfCc#La*>(de7KvBKz*iZL(6Dz zFGmC&vc1t7F>+2d@?3<8R;d z@gcmVeYSpkdL!ToO~%Jjg@F(pY+iFL4HQX1H5Z+ZE`GYaS2`-LR<ah7=Yi^aB|+~?WX&VB`nmr^?5!sgljAlnwlRHmhqNyM?cBRb8^7_sVpxjCG~##R?BSu7 zn)2y;*R<_Hfh=23tfH&4^T0<3QGFM>i`;ra_lsHM^X`Ee=46FEw>{0oE~O;nt?mj8 zbgBx)dQV2RM%En2EiU4|NI6PQ2nkbz7U2`^n^x>3c@8GiqKjXKlEIy}51-o$7vX1R z7mXqz(cCCc$K6BOqMpHMLEWG4qIDqmCp;ruiW$+wu7qfveCiLlzU_?MjyoYGleC2X z%!&G{;RQZ$2+oh0%s34zFRYpTp6OsSN}==)CNAxsDLQ4zyRLi!$nSWb*2mi^%b>30 z&$a%mg0&HlEISNOW^YDsnE{>)94~4^mB49pZ)j+Q8(dR#ihFvG19=su3XaJSPn5zc03Fss`O(2IXE{2XdLJ$gI5B2~&hUXV zlRwHD?h_Fj`mrU$6U7`eL>~5}5?kxgy*@2GWs$PB=HjnBv(?Q{QiO}QTXxT?2je$H zFKe4oP((at5PL*!FyZ z@*BbLODk)LjouORsGQIi?h|%j-g;geLE*o+u4Ft@Qqs@^_DnhHfUyF*k6-5PE3f@n z?5S026ThPEtvb7$M4G~DpeZ#qu!P&(KAs@_+yQ4J0n4m!IL*>FH^)P+ihvk6Ngc=V z>M?`Af0`f+687vlB;{mf|0)6Sg^ZXN_DjxikH=LfS;WAYHO9mVNt)B~l2U{3bCh_acOS9%irm}`NaKpQxpDAi;#L%YImML` zlMBkt4B>tT9VqszsEBIh6BqI(#`pR6G_MVnCNG|no@ZFd?TUV8rurzwX}tYDYi)8q zy^q=gwrsn&;(6RsbvE-$S=NL5{~{oyRx=KB)KA!UvOIo%nj~^Yo@DX3Z*6Fe*aZNn zHr_ljjY2V0|KNq5x}%Q^>W3pTCR>uYy;CI_Z6-jjH*{kD%dmhxjJ}Z&BQWYW zB@9@j^s{ES3knjj%gIHSZ5AdNd?gm#b6w!gB{O-Gq#lXad zMWv%U_`I|-=Sb$|8$G@*A8WM@mQ$^DMIziJ?N~=!WAo=|kY4NxL!}G^BYxjwsh+~K z*l)Cb)x(u>Kz0eIo{^~`n#J8bF1zI7YfFm>5R&ndaT=IClt5u){O}rb9`-OfcYg#j z!1e)trIVwcr*%B!G5Dj`1)6|1igd2cGN01~KRxhCpRS&b9OkTtYhc+&X%F&9m>dXn zTWa5hi*gKOIX=9XRy_j`MRhV^_VLD8w zbWCSW<&bdA=WtS}S%OoCG*l-}Qd@3x41joBpj#sEeq2RCHx#+3Y=e_zR}T(+&p?>% z7O5S-0M?3V!vb|MtC=RsY;*g0Tww7F8nmq89g0z~jgR1r0&6Rnmv3DM zG%QPl!0U}((2`@fE@vnme`iu?>Bq5*)g;minL9v&kFox+oWxgUSAEq*$yx7&jVAoG+@`962cquZ4BTf`ucW8fZX8^GHa%iMuMXOT`dBIl{E#`!KDv-Dw@NwSk zd}(q`jP#F`r`+UW8ZE3#|6b_mdwx_r@h1RqveI$vbN$F*v_=<0onP)s0%No@S^|v+~u5w(jmbexZSKQ%5gk5!PRL76<@^-vXPr9e=b8|4| z%!g#Gp6e2oz;-Z9oWFu3$~G_%@%T{sW`@*YL{h zdj2bPtL`G%9o)PBluDP$X{(d&CK(`07ers7d|-WA^+IIxMbl~V;8;ym`fUb>#|a_V z$(;#nC6W@T<5uws$0YB3&8p|*I_lt`W$Y*cK4k3PSI-O&IyL4u^FS6B6SMMXG+xhu z|6_Ip&hIzgiyi%GUE1iQja^}qQiTo!6L3W zaI-*?NHf}4*LRciJ?@fb!h-}LsYbBJJzAAd%H}z32{Tz(1&~qsL-3Y6`{d1L85S6) z6??=&nC;c#W=xZ+H#{`vCXyIXS*H+p27dpaY3PAe<*ehNvk!!mgRISAnWol-nx0qA z50?DqHQ%v?+k}2dS5Po(@J}s~*0}TT-n)$3nq70zc< zUTDhr?G(*oNM!;-LyFUXQTlgt5Czo@OX|y?)J^cZ1N;LO-4Qg)(E#jw&4hHn6I(JQ zjL}L<_)1pZWb-!TZCLV4JJ^Vex#icGDCMz`tO+@9k=SFgS2WE?zC$@;aeZn@*_FUHx=6q ziIbwyO!g1SVwEHOM@{Ml9TJxQJC) zU0wIU^)sq4)4{l7@h_u1?8C%p2os!ZjJ@4R+AUZ804Y~ zGYBG=E*9k)7CtK&8LMyj*?&r7^l0d!HC3jo&*TUjpO^?{Ws6v}fBnT5D*C9&kWz-u zSb>vhvD?NWQ0lXxqkz++7yKF#99&fXmS?-b$If}^^~RE{m%-_jr(ffuK@h>BWRqGIrtR~_O9kB7 zR|qqDwq)tUQB%c<$C-TWUbeuy3!yEnTFG|)IdU^ZJWIpph>B#L$xn~2O7FQQEZ*ys zA_{l42Ehez#K05n*2e&%XzZRdiK#l&pP1K>yJ)|xJ-?ri_f>+Ugrg5gmaqE%<9`{V*WxE zQJ=#{Ck|dxLB`cDp@ zWJS)tUL0=qR+h2a{2LkNZC;YIt^6~OZUOrEsHLVu{MnteZOoCvpBp_5+EzXy>~o!_ zoI%HX-c#B!P${mL4rPPs#i`w1Ogf0nroKu(Q~vhyZ>}2Q#8xF^)byiBg>_4N&Po~7r9I}e*IYuU{&G&P}o1EB3;*WX8)}L$zuQGtMeHOFI2k0~Fw7$ji6doSP=QHW| zxJ;tkS+|=uoEq?^sKXRgL2+YuO7R)bnl~IM5{ai=N@+Um=^Y#UyW%Ewg(@pxq0E2h zm&QK@JHAX(R&?>Y7Ijm37R3VRvPQh;@_Cs_7?Z`H${fT!nJPB`ux*hzb|g`%1Py@L zvi*PpirN0X%<~G5vC$EP5)VYrfYNn+YJMcs6zCX~m#%Pl|L6K1z>r9nFq`_RL^AUi;0yeT zNQ|wglPB;jay~nlVu+{b5ie$cT;^2+Aec{X?4%^0&rIZ_<<3Rw5%kE|sDXL|Fgr&X z=e8D(RhaNGI`=klwfT_o`m&$H&)2BWX+9qD>_5V8e;9zbjOyyoC$;NRRcTGjt^oS) zav6z#%Y?*VVZF!R37mVyzv*_V?g832&izE`&y{#ju%{M$^=;Qs{wKicJP^Rucs@HP zNK{XX@cByjXelgo1Uws7`!EqGR#HQF{W+n|PgYlW0p&Dw@wn#BMe?StT+7tIU3}$? Z!s0R#iM_Ya2$YMFXsYX|6+N&D`G59(vPUPU@)T& zgJJaEz9Y~3zQ1q(!CZ5lIeVYA*IH-od);@;D~;!5cNp#v5D<{5yin94Ah>w|e0C)! z1pa=z$bAF+yXo~zMTZy|!NhN(2?$sTR21cP{Bt(YhVgFd9hP(;WW&i~G!>a-pc z-ECNGp{d9`39Pfcypj}3dNp~JsGOMG->I0h!)1VPB+{1o5Y>$};_FWpF(4@9+x|Xq zD`)Nh-hL1=>GV1B2|K%8-rwu59)U7hsGHIE8oQ_OfZBk4f(&JVV@1EoyuMzj4Pb?C z2@yH5%0yVn+}hrlWdSQZF_!z!eL!3 z&q|5i^Y!^L%jxdfTIJ;$l~n#k6&HIHY`cpwc&CSBeSMu2N)62XeEEEJ;&QLb>29)+ zW4UP8*`D-i(Ya*?J3ICj%t)V(gI!Y{W~Togu#R0`@j`6(gR(J49)5lb;Q1w@l$Dhu zO~XO8jRj1xOTm*)8>=B96b%zBXRRi=%{$ajBtn>%XMl|%nc0M0o_18oW8U$&@&MMC zaQ(B@ce%hq0gWvfVIfw`OKej0I{Ue!f0Sl^+7@XV8=a%DTf2MIM!VHFd&1Gdx72@n zzIonWrFxgLX-N82ir02(~%$~$NWQGY<@=VuhJ5`J{>DPd5r z{^Zv2yih0y-$XkDXG+J6!2|jZv0c<&6{OY!Y?BR%AY0`K* z-2p>T2jA*D3Gv261?qHnQ(9|Mg3c0!wtCn#LdjgdaijQm(hZmZ@~#wP)s#ma{`8)S zf4w?c8{1nXaWR+FCIj3P@SofMp$8Hv(l)+<>26_%_}N(*ZAB{4hUYAPaqzO&Y0`b} z@e0&R1m6r_<{3+Z$t~|L&_#5n*cf{7IaTl75dZls5BtsGCCm)&6Z^4Z)ImFzTfCy( z$3#zTf|x14XPe6e{^$<-kEJ`W=_rq6#~c$LsuG_Oz&!{es(sxDe4#hUg&EZk4i7z~ z70S?E%js43l8d;W1UczEx$lZPi~jVUGq&4VgJV_tIGZ2)Kfg{UDF&r+eJGO08glVa z2434Amh`ws^?|a0?GSvb?|&|27y2Y+m1r;Y{#J~>Bl7rOFAvSwC-AJYtjd4l*(%l zEWS)Sr`U28eShykn(Io0*mXCF`biPHdtg=wNq0pR>6MY0H7tt%c6chD{`hvThTJQm zHx6B0U4-UG>$J!zeuJ(VCQwR6J5VMzHJS!`mwN zQoV(0cnZewb2dzpxuW1kmBMPoSkn`=iIU^N(^<L_hd3i}Brfn% zP~{k%Lc??s+Ic>TO`dM9UZ&<@2@{7fBN?i{(2Qvbf@o1L8)a9y$1o5Qx-!7B&|y4l z=j0UkEmuIwFY9=<%p|X+e_E`yqj$NNDkQA?`0L-G)W~hhl1LAAarm46bjm9m1b{%u zYs`wFmo~}EZtXfk-h>QuSFmi&N6lh;&qNLm4w1&Q4@ngS<``%R;9TJ%6F%-R0-iSk zgfv>I3*vm1D{}#|tt@lLe1_@sw`3ptac1-xIK}+>s8#wNLi8?o^Q3M;^k(``iftEx z?-K{bl?M~WjKSzr2!xQtfG2aoV1#$PMChNpk#yGGwK>uQ*Sej3_s*imVTEEMhjX|0 z5HoV5|3J~jXa`#K+W}FB&m*fel_ja(NGJS!BVRVun9iEevS8J8bl;>IO!t;`$0LLY zaTxuQ@&T1k&BG!cUaBKL!Vb)lxX0%mZS!Nxe*4_bmQz#52Zh1Gr&JYfez{_@r-W&q zACg?d_P)E3NnojgcT#kBX>HxtS3n-a$j6U$9aUFeaPIGLLN^HWHm%R@nnby#Q^xDW z^geoNNt{a;*LfIXVq${mWKc+aq(Mc#LG%t{0ivBYt{wDX`s(@KBbMXS4;xROcUU1& zQ4Q!QbG-WEC)bgpMQ_4+BkRg{1(}lBsT6CPi`3;sqpSBKuc2pj^qe-5zf^GkI1K(N z9+{;obkp*m!eQ3Fr+WH&aUuu(!-5=7qmri0s_Yy@8OkflwHQkUWkeM6-W)w(ris8d z`L_}g#(TJfyfB}XSOcmC^B0@F7wIN=eXsd~6bjK@9w0SpEAS&t?U(XdNmFDsUCg7} z+VN>mTBI*QVl=MXQL{nW6XqegJ;S#z=9s{8JbwSiS;-)(A9eMzpp@8eJ!|6M-f!F5 ztZHc;T$>RMcvWo8Q*ooq)+8?{(lzRQgDiNKL&Yjs?&o0$!BfwjZzO~{f9SozhS}D< zm~kr?joRVgbT3je#Z{2Avr!woTG{uGuBqhQ<+z1@oyD#GRb4-;kJzH zT3SVWmy8JmX*lk+nUls;jd8Db$nElm~Np!*L2Jx&<>3g=+eaVen-um$gPW|5JU6K_y z(r0u=*g4~%f)44xEL8!Cn?x8GSN(n9LP8ox2lt*|KVT(W_m2I@tD+q|Td2b~YA=i@ zC)$`ZC(3uZROytdf{_WBEY3;tL0%?IW*HKATB~%sGevpo+`6&knI+CwOz5|u5!NG1 zN*>^L&%>tfS=p$q^PBK0t*?xJ+rdfF1KZa#^vXW854l2mTn3RVbQ1LZu(PL5WlrVm z_^l=W(3sf^Jj>3^^Udus{n7X0UPPfUPQ7srI3HSXp3jeY)6ZbW`3Z#|CM=3#RIC*cZ zH^S7bR@lbJGOdWhjW*YZiR5<6PVW<)g*y*&@1#O*f8}KG#!Q-dnL27SEb@MhMVO&1 z0N-OhoW!q>I6{a$^MepsMHA|NpRSoqEO|PlbCO;&K%3dL4bNFPZd9j&=tEY@W}N!Z zb4(e&ne{9B<=C_R@&LWGw#oTDrysJeVRrLtR}&5dTUM;OEfDn2#61o{j|SBTE|i39 zPSa)mBFlojNMGM-7`ZZB(4SEjkz{Vo2aVq*4alnvv&+`!lY`r}Ub44r?xf=L3(nqs z&52u}g7jV~G%w#33SV}L;#Q$PO`h{o;4nZj7r2UsG6$8NPsJpK zO>NuB;9n=@9^!Hjt@TsrTdVi?wO{uMB$@KVye6vMoI`TWL6=d7bo%eL?Ltt6Gqv#2 z-EY<<8?E-JRQkiOhj-i{=8GAsZJs}He;P-{@Za*~IuYf58qxd(^1l2l&6#t|be{-m|opEhJ z;Gq1~NK@NMh~6Id{Q9J7zrwM`I=-kg!IyK$$LRi^00i1i2ItY0vnx<@`~${xSJn)1?d=P>$f zH0K=;5G`Uia5ief;I^p2_Cydm>RdzNDCS(QLyrIQ@o>?-Le~VTg!>B`8Rr`^Yh}9W zaJ^$@5~OEkml@dHHSC=mQCR=}AhchPU%OQI#ptK=U=}KPT`?6+*%RT=FFg&6ZGH=< zi{B1MU^DrLyLzW0Kp=%84(C%FXXddjW1$IGd)g*@D8}487$-n3`v?i0xV(wpBqBqd zMh%RD{6^FpXBn}fZe5x|9p}GB5HfrF!WxUr-X@p0*|u%Xqcv5zfM1PYRhP_q&K&3u ztXHj~0|es{>t>1by>soB0smRaTMRMlj21jOIq@$w2C3|Mo2dH|WP;-RzCV98^o-QkJFFk!-q*y!r zMX$`VT;Ub(_Sb-9w3b~}h1sX#w@V2d{GK7}9oBx|{L`&Xe-yuTsEJ)=_O4Aca+!&4 z>uxAK+)}IFj#`v5;K{>kJL<=LuhE)fzUiE6`z%k=WX&wxFaz1+{)-g;0d*^$4gW?h z^ES=PGU4n5vqzD7B}#X1I%oK?&f1iE5oH@Opa~5>-qQ>I+^6olLqp_r%jmk?PdcQp zp9fQva-oV0=s~Rnw1-?*+X~3ta*pSMm2G>HEb6>9(@2?Z8Bb&hOl}hkKEP4P;5{lh zk_IDE!!l90u)A{?axE-AsPoXO`|!>4hK9~r``M87z*W=G%dUdd#Z-j5heJu|Wc%1Y@v)qT~L;|TLE*CJ;kK`At!K^)FsO-Grt0aPzKj&xgJ z>@?-`Yu0hnwN)P?g5WSEW4_=w&JZPaTy&@1fhIv`{`UY18ceu#Klf9U)D z4O;+*T~ON!x3egt0f{Bu#|oc-l0EXG?}}h8YagEkeeT1C=ri|e}k!8kR9x$J$ zL-5Hv;H^lPcl>*OS72a&wAdIZIbG0#7Z8N0PDSGD2DU7VW!gBNCn$IwMMG-%?<4`-R+bd znCFMB9hxK%0Ix%#Mliu;nvlC_kz zzy}s3lV7v(cqiqe=pbE z-SuSbvOzqgQ~BQgDA>8o0g@5(Za^@n;I__AucEO$0Iun^&_q7r?-0yF5&R|rze0r{}#I( zaLaQSX^O5(iv@5S)d|&2*&(Z1yZt~Qe(jg-uqrg41;o~0<|SU3Kg^xLnd)RbE*2E; zR~wj%WCO!Y`SiP3@dBcHw;XRewZ~YO@S9q-$V6VVeVIY`TN9=^2Id}nx!;}X*krVx z0yXwd(S14AUSFC1l@UQlKE5PWoDs(KUYAfCw8G%3VAj| z*)^yn<3r<90Clr4CAs$IaR-FFsOop9Q~q(^E)NgCbfBrH>wnNjz$c2#LN0WF$S17! zjsB)w?=)_C8kF$Ui@4)1T-MEJ$QghH5}>S3A#=JS2yww*$%?mr5r` z3_wxw9riBXTQX0Jk%CAMkO{oq!vq9pQ=zI#mukom_^B8Wzq;zM^Jm0aa}{Bp4a2>hLR1;Rf$ms8-};UBn;}80IC)orSX!!l z6lzgWhda$m45?7Q!JFf^^Rcjf!QyVjU`qsnWU7k3@b z(vN+4$k*}KBX-kGY*lMjJyqktx<KOA&^BCGDF=`~e}6Tcby)|!+&k~2OqH!eyxo*oqy`T`2kz3E?{DkLkaaSyKZ z^8VvBDowDSgz;a%;3{|LXjMvIK3y`(THWRXfTyesFMaO)=u;_awGN}&Nl?5vi10vx z)0$kfL&p2sjdQS2;wO9Z1R+AWAV##UtXMOjxo`Lj-V(aSEU*W?{F$mM(Jx6uwO1lA znw=iB$4t#aWcM;9)3a2OTG_uf36eg%#!0Y&M>`$&bbk8}=BkMK^f@#0TlFk}8kA=z zyV=1W5QPNfx?*2_e#0!C-5kXkztV+ORA>6O<1&dzujjLSArdZ(G^XrH6MH;7#811}?iHTKjsfP~F8b&*p z)6wUqdbpV;((?8h%8hn)F~L8Q{?Kzx5UaAiW3d3; z@F0&M;{q`^n{FIk&~uQgjPA*5duV2^NcpcEY3$s@!<8Mf~6qvqjYmI#kcrS-(XPlGauU3}=!)Qocd z`C!eA4OnI;vop_N&_W;GL193C9USyWi&sCf(*}X0f_`g%Z#%R{r!>sk&EvXQZ5mE= zDH=h55Ra_h7W~Tkm74QUYWV*->B>$~Ut>kz@&QdAF4<<%6u~8l(|D1e=+`FGe}5uwxuAy7c|5s#0;V;Q5^c;0>q?y;Qh*;H;TiyO94xOF#{u=DnAtqTeF);Xl|g}X zz&oFcm&;7W=`*Mm${2VJt%61T1wJ$pt2Wd(5ZL=k#wW&;kIR8d6J$H|w^n1zSN1J4 zJm$Y!12|fq_<3jeRgPQS4Pk)`0>FK`O@#gWmXSAnqDaaztC@qnCq-e@mEsxf0S?RL zI#NqyY9FQ0E}uBDskb;pJwqiOGa%6WIx8kQ1};nScJmnX?$Oqb>vF85zoMigimE5R zOmC2PEgSk)J*m*X88RL|z#HI7RPbeyL3)BQ7y-=<0!MJt#$0Vjz*oRDOun~)q$R(? zpMq&|S{Liy1p$D|Voqbz?=2+sS#!jP-Nelj4^GS?a^kth4gs^R5zohQ;}&s`tkP{R zv(G^>zJ(#P*jfG;<>_VdNr_ZrFW=mc+dO*j`c~Zw=#m`uGMX2RHD4Y>H~0edP+wl^ zG?n#j&pqDX9Iig~e508(x)=J<@?YGjq!(2rF`{%%Ru_%RzhGD43+F*hPEA?agrwO* z4ZXd{Vm41K`iD7tm=lXM47fMV3{9(V;j0aL=bG`UT=jNVAylcb=Ps4gTi?_2fgW&?j;sN$;!{4V9ZM9tO>)DdfrM^^haR+9`8spDh1QdX zDHwp8_D*VeaOxBHxpJz;60TAjFi4HLxCLcp2Vc0nIkHTg|581;SAt;Pi_guR&$@Vb z!CYBC;j9m;q7#Thcs9Tdh1|Rx!(r|@8eAL)aTXh?+k%q#LhuqThu{;&G80$Lk3{K& z>Y#?BRvs`T{bG%_fPUKI}M^=wXbGv#G8RC6rov_-EtfVh?KlwsKs;DaFEplP) zWVO%jI2p-(_S#oxH4O4@`CI|QS0m?H_O$WM(0@v%Ex(CAL#>m8(?eIhEAh<_aIIvL z`*@$HvF<+(Cl5|Wnf-HNg^c|(`Yt8?>e%Io+(Ry@7DcNjopz(3yUX+?N8-ZZ$%A4^ zv1wjn0w)KEQS2^;`2U;7Ny^FD#kG1CS)vDKUY8HbCszK{FBHe20wN{h(d=*)?y!sO0_O- z%;CwJX_FBCgI;mgAW$Xp%|ngF62sOU%KvqqGxKvf4E^iS0!op9n>Kr>HR-Sqj6^Y> zWrBmy2h|laqqxSx*#Nu5n;{XtwF+pvb1aLY#-_iHU!yi}t$TiAgI%Ajd&Z0kZwNf< zk%#Aspn}*2vx)7{{0qvJrE?9~*D(((XV6<=^`4%dn)vNu4^dw+mesVLV^5=txPOa> zfFCq?o;gHDq-kXL4JW^;_wvIsc3yF~M!L%{+N{XsGy(z!!7DBRUS4$2|Bt_0oopZm z=LiWDhe~C};`SDx7lNc+9^}Pn1|cLBaJ(OlxZOg84yzCFggjrY8J+F$L)@Wo2~2*t zZ9xY6noxb@Gjr{BmrfU>TBUb55s;i?b*cVMVbFoV21(hqiGA!8sc zM(&r~kT=R&-R59xkz&rBXQHow{DUtMR*(?1Nd0csg4V<hqtS(4m zVta~L=Vg9t*~YdYN2v6lxu6Vhj6sgIi-s$&L;C%8GqW?v2AXUvQd+Jt12$Bv!+itj z73R7|Y0uWn3E&HgE1*~-PR{)tE}E+y|GA4feo`GaTa&;8ge<4xz+GV~ne zN3n6xGkTsNf-#gus=cYKPQvbwtF5D>BSK~4+JSRFjcUm>+Z~1Lvm6khiJ2-seiEo9 zzS};tKO&VRt?};5e}dAMM3uyXG_EhMvEaGOH_`6C@&SpdaKG8mYIsE_h-7U?S}v13 z*q%woX+z!(ZBbk*BTNO6L)XdOhxiZ9%v@Mc_oz5^}>DBw8;9JZosV*I}a_sb1gPg`k5<4s3{ zlGelH+NTsO{}i}aT>5MuTgbFVP>}oVFbVe?8mno`+)!PSktQ+Bk>6}}-rU&pg>8gk zh}xFtwtrH@LCCnmVQ82s_t?F0qk{wAsMF7wKmTj6d%iRc+jMb7H!D5*F|_K9+*qGK zl_k2J$t5}8KabXB;bD>@CeTd0P7xKfjr`dlJlD{eD_{8jQ8Mkkl(<4V6~}GShKFc;GI`gu)-w8YR&!n4l0bW^R_o`&>RsaC$lfS(r%BH(|dKpc%_5B+~w>&4b zwqxIJSm>2KxtnB5+bfPye(>BcnQweRYUgM2Hc=FXZy*e3 z1uHs?Uz`&sPxNrlvGPN+uSlJoMddO`l}EOnc7{9_`evvM@&mdRp-_2Q1BXw$)gzEtfvu(sKWxHqgPdH=u*>A4SE%bgP$Df9tqpJ4-LO zxHQOpvz)MGzlzJ-qx)PVJ*3%7L$i-27@9-Fgg!*Y)hBKm2FXE;62M^I6PKX#)u#Fk z<*Wz;x4Sx7@jkylnEU{xQr(vIsc0Htk3%ysh))O>0NYyU`V(rHoz!GS({O7SM4RM5*udm;vP>^^7bl8nH_E#(k8YvSBgF&BRwAQ5b=$<`WY_-7x!HH*l5XBMt^=6N@8Qh{Vy&_KcU z;}n_b8K*MydWU5YmYe;b?CBXNPvY|}3zxPb0YOoDI*{>$(SIDisoCG?8laP>`#7d8 zxj`=cSv*7GajwdN-$7PZ_O;k8K7?17{Ok-dSu29q><%$H#o`o1qU!{CM3WFzeTrbK+aj$qeN4^;Eu>-m5yj&F}~ z4(LDrtQ~S~u!l_3k-nz3Iwe^pBg_t6_Tg;7F$q~XQyxfkamh*%!hIb4VjX_!+hJFI zrNp~F0#$y-uu-l?gAk`+-&2!`PJHotCJp#|XQ&s;gcrT}>>F>JTrfnWHTz6Z{%%!G z>#yKKd9p^YjXN1rK0N75_Q&0EuEGq$GeL>_Ww`g2(H^9hcVF>kxW`+vGuYKj^&PG3 zeOVl?rh(H{98WY#3YzEeMd3qf8`c(1WtXivp^t!uq@p|$rzg!YDv?M+$cGrPdW$l8 zX_F5Fn;PYc>ccCxro;B8H5a6Ku4eHn5)jc#C@78 z>VWzRop|R+c~hdetswH6Q-Iri$m27QaYr1m4<)1R8@FCOnJz;iFIFmIz*5H0PqqqO zP!T;neWJd07dMyWZ(O)(MjpTP)q1JmWeCFR#MJ3L7(spcG)jL!sMtWiQtSf&ZjinL zj{}^QvO!%(2&L@Y<9r^}?`@R)bF2EaDwHXoW|r*a@oPDE{3J5{?NjA)dKkguSm)O>n}<*Hqkr#F9a~> zVFe{bVyGH*xI2wvpFDXIuM1j}%0Ox!0(f3<*nC%Na8M6@$$tt2j5f7Xf2-*FQ%v}j z!@9fOK6#}Qe|1}frk<0KOi0%L02%kbNAD81$`ioKQi@CWQulBF9CGy|?xPHyfDr4LR| z{-k`Yh&g_EmMN_20g3{AT^cbtGi3{HQ7YB>YQksz))m$1W6JIDq6A&QNP~`uNCppKa8Z&om93EE68DNxIcb)m50V)#~E|%$zjMsyDViO`N>Q9fRnG z3#^D-o3cu1x$ri%CYN1N=eT8pC^7;sh?A#MrP5h9)(axW%Je7Q)~PtiF-IZ?Qq4(7I_}z9p)ML8iWw?T6;qZ!DR)i{s3TO}J`XTQyROF}ZvQ zb#*GsqXF|v8adO;zK1Hm+|Gv^m@ymdw9$VJDB+W?mrj=-F?ArPkW$5(RF=y+Z()u_i`@@$(5x-6zEe9kH zY$U@^vR!V<6L(ov*G++E2tlNS!>2_3!*@rSPbTK{kXC+X%~g=v1nkM5vck-M0X^_2 zki>l%%D*`c^{hmpPw}NcVN`<|HJL z)gLxYc8dzC{Ce}M*o4J0ASiVfb`fR5W!~u*5_(P%ntQIdNI4_pnfEUnH~INja!JZ$ zyFMo==d%MQS<;N-Wd3tQhHn5&&X6lwI$$_E-5LLckHqo7C~yuH1Bs7~Gav$ZE(*`Lyk=a#4uXCHtiT$KI$ z4_rCxb0)jGcJI=icIAKQBE6xeBRr2{sCr+=Yz(-xLibEv-;2cxtQ&mE#7Yp<%bEIq zAzpK?R)T*y9i-z-dufn8%Er9@JxI8EJxuhu=nqa&Jmh)anAFCX)4M-?m<|s7R7T%x zG^kT6BT;aVpA^>tD%m(1*A}Uvobvmq^|=_LXE(y__bTPF0{ z_mEVHQw@!2F~U-`o<=!uI?vNZ^$F=mH$T$57+^Yp-(TxN{~sjF*0z7p@cj?>*>8%= zn~-X*nWp2b0JA1D4uZY{&xak-S!?^REcsRw6F7jd1}NK%O1}8dpBg{VW-vP6pCHlwh30> z?P`-D-6xn>!05O7+q6cHu)P3nLE$?^$7$855E2koe8L>~teVf9>$ld;!1K9E|4_kt zWO+xC2^Yonc2?pS3z;#!H{Y=Uz2V2C&lX(ON=?2_I__wl-Q!2JsihZx6cpE-!quqO ze0mt;fu5Dqb;Wno`y*_S`X!{}Z_&}OKXqd1|TpV^v zsl>J)m^-yXY?zbcqy0!Mfcd2&itY3_hB76Xhd)-Doc!Ix}dUJgk zIm!B-x3kqyvN#LqfejvFQo9R-X?4A5vc#PyVZyMmyom^IE_ zuhHL912deX)ATf+PBAWOd03)cyS%8*1xXqXKY@1<)+W7{^l#74Lw=-jkJY_|m{>jp zS-QF=4iCQuOueL)gCh{;MFFp zHSnrkMC7V{WKVSuRP?mUV6Eu&mrMrSw8d7AG@|tQe#;!|i9l5IjfgKtyJ~kMpELWR zzY$;9RxB*k)HOzXd>K>euE|05O}cE<^w8vC=L0&A6S#`;RLT!{uOAKuQ%BU$}Q9>tOVZ^9^WBp*U*yS@o@Y_VSE2xbubO#@&AyC3bPN7Dn|quc9QM=-A=pUQydhe+uj1?L>p??R zZ2Oo?SD7=TxlT%bho@v3KSFGD)9gi&4&jZ8#e;Az)s<6Zg^e(srJEZ|+#~gSTG_)1 z)}IGxG}fq19mZ203g-Gojg4~?lnvjhSk$UaO#UWlnC?}0e4Fw3ao1aHVCD>@9I_6H zQx~d-LJ8>L?c37V5hb||+aMtBdwQztSA^HSr|MvQ$uY!e_U|~&$$_05)3$d`Oep{& z>op==G`$fHajp|p`TCxbM6A2#cErabDb+VBU3=iCv+EZ$6+VJAU$t&e&=lBn-6;*! z{iP+of+YE674mD9%~@rlgJsihDh;5t`C#|+tL1wa{#ow zu}_>(dZKgJ$s@fn*ZW@r5gZM|Y+v7W_~A^2l(76cDoj;1~H> zAxGe#6s`|tndL`2(}{^pF=yX-aG`aGNDh)9(Pl~Y(Hh~gee;HTCw}!@kijywf4~Ez zU>j$F@BqadV~>xxSro;puK~=HFEk(Pv@UdZMK0bQx3SfG`&rdU^Va(j~Zd@$i zX50@WqmhO$?(&D_vEDg8{F=WY#@*Htw0Smfx*z6(3$UeI^n+ivK@-n^CFC!;weHE~ z9yPaB?Mv%tE$bgIo5Dk#aYV;%U6*ic4ydXG{fsio=FU)hccclu7id8t{4WV+t?*EEQG0}o#$ zV^2Z^NBRBy(2K6HPDIO|dA@&Q!&K$=5>S*DH9>E5XSkYJZWKYN;GGU?F(1WwFTUKh z6J)6j?k}4#E2zVJE_r3pgA;0?ZKwYHJ6t24s-Ak{e*qRnOk-zS(O(UYfoECA**c)d zVe>2~cL94?Z$EIIY3aewkY_yRBZEFn_L2t<;8(*$e7AP$9|eq|v6=a@mR&e*HY6LJ zn`@czz>^OEGXA}Wv*#J(49NFBJFWI{I^t_3L=@1M{Dr$Y`~fdZcq>s1F4NjU;HD7ECVa;$fvb~L0c1ZwN&ibKXgQw+{esTBdywp)r2+)TSn zJMY{M^Z%t}-nOX%@GpHd82l>XavMj5W}9{KIJwZaP7xn9cpj#Dlr^xH@E`2PIh#J9 z$C*@-!?iSh%(xuE`d`w{Fh2vtNR+`Ba+i0)cI1MCfLc38lH%UOXlaM3Z@M+Py|c$bVSazh^?maT z_~osz)3Ec+DAP!wXJ@^Aae|tq^Ce^VR9DwUU-Nr%^MZK<{T%*1An2-f!X*D*!VEBl{{r(( z?tpa2HqsqWNEs0Z&LM!={GVV1XeJT4S@JCLizH4PCD^8!P*>u>v4*$zIOiq<^LLJkf!z{RQR%>}LY*&;gYN z<_tMKZSAd70GP!Tm;gA_Uv-vH9UG8oK!Ar=(Dqm|8KU?+AM=AUK_g-bvSgXzY0F#A z3*x=bBNbu{mrf zyHU|OG&B6?ICBPHGP}gk=s1wS*M>U5Oz7dpmCs^_`_D)lMBRW^pD^$ggTm*RI2iq` zJ2*i7@C5*^KGbY`_qV;)tpus6`w3|acKLV1@7evU0z)Cv=)puh?3xpRM6n++a3zof z^nrghgMB+wPXVIAU;Sfgk&Sx${VUgLqW#yy9C<5vp85s+>tTmrxicE`)13*R&jWb0 z!vADL|MP-mZFNA7*gaZ*wG0WDFMvPUCH-|Y2}rtLT^C?ZMj+n+Yi0-Tzhj^`uHPsf s67V-->KkjiQSsxGf0dIG_)DTT(a>DhU&ic!u#`YWNkg&XnML^j1M>b5HUIzs diff --git a/planning/obstacle_avoidance_planner/media/mpt_traj.png b/planning/obstacle_avoidance_planner/media/mpt_traj.png deleted file mode 100644 index 44a06bc1ef9f6d87ff2672cdda8453818f56f43a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 16265 zcmYj&2RK|&w>F7r5fQzG5YZxfHwXz)f&{_ny|>W@qa}Jz^r%5bAKmCgw8*Ft-Dsot z-phaF`|kbkJdbn6+0M4lK6|ab*1O&}{GIBX2ZXeQSXfvO6ct{pV`1SO1K%C-ae?Fa z>kM>OAE`*mamOlPQ=UG^A(n_&0n9A-l#z}U#HZ6m8{)$6S+CNY0jT+EXCF_ zGFTC5y-vH_E%OT_k=3u6y&iSCyDQ>`o z>=<&}5axHK0^HGuZgh=JPUFc(69FB_hACfMe#L>w;xk!B{yY8aB&7QxqjCXT5Q!

GJ#trSb)=lyn?nqQ-}MPy`z8a9S+ZK8*l&c-@#SkljMKDi?(Az zV=d(MfnNm_|8uohXf5J-P@N;c7cjOkun_U_sP@>zoi9`Kk-U1Mbb)6>i}9;43> z;D`6xfb$sWd^)9v>YE6-r68t7fzbd;fub5YX}$3kgUW{4?VZkJY(!-6nH=HZ1}%v# z@hjHS*#X__Hatdp9GL$up1*V9V|}Zq!6XZ;eFv^%t72!?X{vfs_1h}Rv7^n7XR9m4 zqT4FdWn<{s4G{E=lRw#tV-mx2r^>Q}%tloDuonnQCG>Crs=bCp&kn!6fQUTIY&tM! zz3Jx=f)*ftpR*=@tS?3!wAi|nIv3*=_>JDsoS zx{FzQGnRq$aY3hTZ-7v2W6f*(Lk-0`Ed`DX(|sthjLvQ}S4N}s#jy0Wi6cp)UzH0X*U_w#G8dy{NvhhVhHLkW^V*y9**m*?R*Z~x z8xGP?Hgp+$@{eYj$nw^7hSeE(dA|8aNoHeYL%&(?Z;YeXbp|%qSW;}w5!aY6LKyY8 z^&;yg1KV?dm4HXsh(vA(4)qu!^C0U^>At_wv2yS@1ARvc5? zdQ_TPbvs<4Gp^nzruElju*95WlM9Pc9PdOJZ{tm>&Pl#o6?Q@``gweRuCi4ol<0aJ&Cy}dmzHBlbvCIKJ9`K0JXNO|$< zyN)2~X1MDY9D^nT0$|CGtz|%G<~t*)NH-0tu4b;Q)1Gu_HeDPyg8a{(1_IhHEKE-nkicj$n{49>m27|Si93xkm(WHG1PG|%_Y8r>wM>?=jO+11^IQ#}L#vk4=M4wP&(KXBQA z19l$voGQro7Pp&#jTGCs~;&5nMf|J15Cd|_8q&eUt$eh2sE~ooONY8sUogH zF3+CpOizb+k)Sm``E!(5iGxcyw-q-|V#13(> zkx#!wdrEpG{Pz(%2$JYfK9^@~w^LLrOZqHflT>CrU%zz!a!DEYDuqQcAjd`Ry}5~E zI#vjak~2LXN}c_Qnv2$$7R}+s%SR>86m?5bE^&fwNBW;s101Lz3Yjb8$Y4I)S)MOx z^xY8NuFn=UnJZr`Xkrl-I44&*=bZa_EXF^FWy zAZ23tKlAw!)VJGA3QjWFr=P0iIJ4kFRB+u7s5JWN>hp)IlloPr#Ufa>cG!Z1Xb{M4ZSItKODjzm5iy!NP0ckWOCyKSda9ystC|Svr`bIA8aa#W|E4xlWGbjbNZ;M& zZa{r)&zmwmcfm~xrFGHmt<-w>-l)@2twvds`2a5kVCa}UqO7noLzV_{Kz zv`G^mZ$YCZlbW{(jwbBH{-oFJWwhtbxzcY?GJ&SkRXn?D*<{Hp%RlQ_tZYm$ZSi&e?R z79kt;Q8mAPW`<$OHk?I~kC0O}*vSX8p;`Pvf8eg!J0-Iyj!%MS3b|1%;Sha1RHaRc z2*kb-f8U-8PSHhOJt}uEo$uvP;z)`qx-Lp(Dc7*HvrOKsQ5c+=lNgNc5+9#`mhEa9 zB}TsdwI{>5PC?ZsnolfHlts<;d>%`XT{$=L&Vx*hDOfH*hch|S_c=Swt2ma$`s~>q z4X3}>wXR%KKOv7RL1u%Dg7QEj&d}nZFCzqG?}zB^8c}@tKOpu>Ek;33FNy0imE-a> z?Sy!7bAME11WqlAu?n18+~}m>hTcVrMy%ms$LMLUTYy78=D^m=RdUl#V7_rIZSIc` z>n3@hM*Vzs0djk57DA9o8~ZU-9W%8WKIi1$Do4*Yp44eP*!_nvH{xP!8yT8ro1l*Q z{Sr>i7Nomo^2?e%QHh!el3xDT{*S$I{mC2ymIwWCK~jZ7S{-_xE;jRBnb7I!f!f6E zgay{$ol^CFB^J(Sit+bB%pFbf|Mgsm{{$#|x-m<;iP5#;xO{%_xAn*q-= zCD0)w&uD-~*5I=E9r zwYf{i2{N%+Sy@p@mUOrpB>RoC(Fbkr>^uq?a{fb5o}P12#y9vdf>Q?mH+x+?s*V24 z%Pq~NzW4lG+$Pm@N;oYo4M)a#KU`dMJwK*|pRAV8=W^%`u+T?G$MADWP@F{sHCx6K z{pFDe@xNN|kPANCKQz^{QYBF&z1(j{?%>h^T!_IjYOt}GmS6)j{~9987bbKGP-$e=;)x~SXw!|GoR!W zg~{o$N%+l@!C)i(vcA87Bo;Ja!zEPVKI$W=Sjp<-7VoR>bIFxp)~YwGx-RoREsv# z^o^$TR^z5NJiuTujW&MKp0}q&zR(|A-Xc|B*#@$oSS%%W(?lt|{TPSS^T5%}Qb zPY;$Z9%_B!CKcD*wNuj{O zzVgcg4XmA9fP7BNsf`BQITDqE0G5a?3*pnQ0}zu%Chtr!^zP&-TpQGd##Th`cY}hcCfNS^W?0R~36-gLdQ=ni$l= zreq6oixx0#IaY*078!@v(?=kz6y0|w)3HgwP#g8sxci~o|z91&4kgF>NR zoBS4;jnM%+7`sI3qPtFf?NP5b=;24F<9Lnb*#4$F!kOAK8!1#g9zdvNVe=_7XY2rM zq(L;0`JoBJJYBkP+76Yx*&{-y+^3UpbFj{t z)K1sb=JjmWflUvqjb_+FSey~FA}Ir?4i(sK@pJqu^;6X^cj%x7Qm{;8JqGY{^b}uM zLz7Sat1@Zh+QdhPu7>s@f7dBtXq8OR;prvHTy#5K-cAm#pRJDg_HMdS&!RQ|hbT2| z-4bi_lR3nLP;Cj?)+AFRHwkQ9g}5O0h=L>{gld{W0ls0h1t3*&Thn;zh*be$a%DW+Sq<8_w zpry~+^SI^QBUlw{YumZZaCMMJgLr1oOsko{t(Zg0fg=*fpY6u=(@3V%je(@O#L!y~Q z&r0;x^mflHs1K9#VK}CmE&gP-n0|7bC3(W}Z$G>%fQxZ(4VMjhP!t0l_4rYk<<@j# zxYXf3=H66wO{V}HM%OAeP4m0K9@W@V{8b-fxW7GJ^HQdSSZbB- z9&Gm1GPw21OW|+NI2}cKp*UPOV|mvv#gUG@noOk>L_}$4R}8v z16Nw(eO_yHJEw$f568Z!3uk;2<E@DE^1918u!h{UN76tu4&&SIn?urZN|! z)?QUB@j}!K?U5{*Y0oxg(CM+`8uJA69au*F+b; zSsnTzgD{UfXy$nlJ@;_`@U=?psL|4%r&HamKxQ4!a6ifsIyvk6J_a~CjmC(apSXNM za{bxs@ZtQq^IMj2hqaM?_HeHw4Sbs%&ZGgkXI(kh+X)@tfJ(u>C02u2j% zDhLFx$ahcX*Mx4+fXeW%>`@GA-PN9$&c)O-N4K4a?YbFL3*o46M& zdz**WBx7&R(S%IgSBg=h69u|D|1wps5OAwuroGXy(;y>}=Ls6B$Q5d67nzvXtzNHW z$2PaL%#dVJ)l}V)QNzDZCxvKZeNW$R%sZn-9fIQ<2!HYE$s0SBvawejoy)A#dWE~T z0#AylB%kPJP|6J6g^&B3J(`-DVgVPX9E~C)xC@mi61_t$ONB6>%T_b*=PGhl&hMj} zqXcUdLQKZ5{qE25?5)l}#ftkoCr&tpgp@oTo9}8j=R^AX=zJ3tV&^xUX$<5GDKcVK z(b(s*GBb;A)i>&nHd}w0PJS}%t{?aJn*t=ASshZor_5lJRMDVonICUj^H5d@NP6EQ z9OoOjyEq@)p>n$^7^L3*ijs?C^?a7)IQUeN)VrB`10~f5hnrrQj2XkplN^RO4(l%F zxR+eQ`#j@4@*_7Itx?YgkRK=fE+a&q0%6>W^Dxh1mEZi6e@JA9V9(KhkCyH8>gmr* zi5B!@CRT%?z2D3_4WVRa_S+@1G`QAyX3L#5w8cskZD?ns+oW7>WTrsGrbhQgL)#tb zwpKkXzgyjm2CHln8;bR7SXfyZ)j96|YW>&As|4BSF?fDt8*flV-=edJtUp_F*d(cQ zf~#Q!Cgwvb;x8Zl$bM<_O7$(ZidI?S{1s=>ntC^<<3lb4_rr%Y8otg{q6M$%uQp+n z#tKy!3J5ZHd_qEB%o@wVrW&poO5wv+$Rp%z=%(-oM_Es2^5^(jT_@{6w}GchX5eUt z;_KoXHM4q|dVNcGhs3Qu2Q4iv8)!pNc9d(&>ZZt=$cx)Ks9@(7c-c&^HZ7k_a|z3g zVe0_Vxd9l4iG|I*+{ed8l2$bp9U1ZjV+PFB)H$N2e-)1lY-_yB^*M@0n8%e5;v3y2 zkt(TqK%QbA8fulAL7%nrL{qT+t7)i)GEp)Wg-mlT*&z=DSXn9?3kb8ONu6}Fs5v7*kz4nWAx@i9uU0- zfMj|C(+*}GN3N=|$t=L-h}LqsLM}O-T90sM4_1+r(?*8NL(LL@iykOts`VU%=FU*C zK40fXAszH@cHI;C+J}zhWfA3~;5RF3u&m8aJ6gfakt0q&~Pyp%{G0)R!Z$$k6toedz^n>Cm<9vx({*HZE-* zYVxU0{V8KU3O+sU6Ug8VQFb^)ek3$^+L?NDZRo^gB$KbavFd(+#|vQCx*S}n9I%sN z(<9STgND?q!1ai3=dp#yDHeA8Vm_ht8phNdYaDx=C{zW#p^MegGknD%d6~L- z2li>m6ZXbW+M~*>^OvAe6 zdCz}UfCGiD0CLl7^RIpJ-D)~|dik210_$rEp4X33kaWwac`Cr52}Tc_7+-2FX#;@m%_mW2_=D1op7nFjjmHulY_R)*?-sqjTQ z58hW8CLcHm%cWMPGVq`q>6*Z!aCM;H9N`pdka0?NcqBVbN?K0HMA_-Es{TBPByvue zoV)`P>{9<0uFgtN6!x=Spekm$h}T)Z&I1zIHveS6nALK6$=D@o{!`$3Tl}O+NW2w& z<|C+J%k(Phpm|JWQwYkZT6!UL^lKdUreQf#xF=LLyXM2?ck&j@!-0{uGmvQh@|;2h zq%)H*L>CdVQun$-jA@V}^7X$m2tLGt#=iNz+<~pHl-S5aKtm11$Q}&JrYXjGt=C>ky1juK=0<#PgV@-QL zPClj8T8pf2o=ZadBX(Ui;doJMbH~TRSSIAAdcuKzxB1v%-vg^BWPi~hf@4*thh35N z53&Nn&sbyM--5rr@p7#mU+mz;R%@(D7MKgEu9ulB7y=G?GM*@b%IBt8!u=Vv%eKo3 z4VG`;3wgSUkuhNiHdwVYMlT`vX7;krxrHuvYTN;E{yQx=^MO@M4FJPU5i1qXv(U(; zK&y-RPy#RCmyJZe(n(dS`Lxl%4!0Km{(PHRLSQ^ztvMI~&B@PR%Ds)VBVi(r|1HSW zv61lmgrJ=S3qfI%nv;;XI_)LNm*@cQZtzkKQOo6F^%Fkp*smB%e#o%7A`~sYVqcx_ z9-MK{o7vah{^A=Ve#L#^I5%x)n^FL?>=nWnA|u^CN~x=;GR7R=y8WPjlTBTuIfKMh zD&xrMTKrC2n$*7%m}Pv^PRir1A2Zk7NTKylFc4a)s)uCTluTJa@6W(nKgJIm(emeX z_uStGePk2v{=9M~6P(JYt>@u6qG~_6Cvyx`Io7QF_OCfU;JD&eaxGainsv723{k@- zIe#{RP!*f$qH!Asa;&$YMQ?aoDd0uKZ(l&z*_;kBb?4Q^2_HGyIdc1Jetm=Srn8Qy zdDpO86q^@y?4ih`g~zWo<0*Xbj)FsrZ({5PQ1dflELLx4<}a>K>CM4fI3Bs-3JLOd z?&iz-yvyG?Ng@m17Z0zw=K)p3(vciBQl_#Y)6pIl zM$@DojD~)#QvDsm>d^qE@K{ZC2EsN&vM>V~V=Ww&x0;I&lGA$hqLLnO8N%w))?_SZ z=S!Q%+PZQUKI}fesi}>QU+q28wJ9+X(Fy)plkqCvFF^@zHWk%%hb!+_K%aIR5KVD8 zFgBpAlZ=h^_fl3uZ?=&RWQU)|W*+k0l!C_7^40CV;+ca|gd(M!k3h}x)8quJfW?|K z+=0vaZ^e&IP8E)A@lgk1AV>5o%a$^d0B#na`^uG9qD<^`pkk^?xJn|EG;=FmZ0S5w zr6>@8%wyLe%jmk=z2$-0e4`Yt9Bux0h-~dJd}ra$u)Qg5%V z6F*JJ)Y?zSNL})e>f?~86Q4#Mze(X3=&}?>u&a{G9`(~*@^>O(sWwPk+V?m?>tb_m zu<`|fqN`}|#|xwec)F;^^=zZ+d%CA+=xzn%*9bYaX)rDNmuwW^wBfqdUfQO!5U zj~BeR{#?ARO5hFuRm1f3sQ}ID!c4XJ3;mPBCoY;pbskn3w$0w`-!wuU-O5Wu-8*%= zAw%8`iD?VVy>B~bEEM5cB(muaGi+_1@mTx(0~4g4guqZtXTF1#9QogUHd}Rv4Lg$Z z(lYEU8mp;Xo^;gMibie{R4p2oJjyRirDx+YGRWDQzzLK}n@T%H4M!;xDN%H5zsyYf zZa0L5#VB~o1xR~E5vjzHASK>E)3Hn#=jQpigr!}_&6N=-@dc&47<OYum$F%KeTD7=K1t(=US5%^i8g>Rr4hb6{k73gj zH320*0%a5g4!zv&Ogts%Vx4D$G$iKIq55UkSsqgk(RoiCD`K2 zRb-CgVstD{_$lea_-1}gPH01fE>dt~RIw8lYAu*cx8$Wt&u082>z8D-82(X+Mm$Mq zr`TXaof=XvJy)s5Mdd`k_YT3a<7c8Mo({KPt@m!%C4R+fLQF-7fkRcv>Zn&@qHg{c zCq6N>^KoAUtYCwk&5hB5eE;#=6o{KJdO<$4C0f_DWie8`l+@wsj(Dwt$tUQ|-|;)0iGXgZwceXNyYe9zcYdn-F3M3uUB$NGKdpYw0t zPCjW1P)VBWXyHtHW2f}Z$3cM*m#%|_LpGdDUeEwrQ1n&X++V~#h!M9iL{KHN;!!jc zs&Y@qyVIeUcUZ$3p)kz+gDzuOfOUrA{(qwZrVjmhzWI)vhP9q&+%V8r9E`2OwU1@O z6+bvBrqMJensq?5DssCMe7hz<)%NVzYCXX#b@gOSB zX=tr?HzjBx`X6N^nT5i7p&+fa>ud5BxAIRi;6*K5PG+d-80bAy9A0>?D5}Y7*?VT$ z+5BWms%gNb9`ydJRTt)m3a$^HUH5@`)RcAaJa@;NS6sYo9()XV4g!2?9UFA-Ig?fO z9c}D%qP2tEnhl+N{JK^wP5*pZNR#1^gR4iuMW~4)eCOt1&(vdLgV`xVabOE6UTdRl zjxiwC+qD81v_o-mCv^6p++pM04@*(}0OFt7#i$=KxFHy0C(jblKu;g9IX$#S2+u%~ zX4Z##GD9#sgr=6!Od-DAWW+P7xt;FunICr9#NsB#z^_{|o&H<`jPxaOTo$wROTLSxL;Si|Ae5TCfJNdTxNxSi}XMVAQxCHKfC-gxGE~f#undwYe5j$R?P`e zOIK;6kxfstsGUGh!ABg)LYTU!oAwq-Y!Cg7b3FU0bu;Ysv7tk!&m~Q?^aE^b#HG02 z;i$Kl+qPyf6oKeoFvix4(8lhps*cE<%;eBI{29T6I#s`NJw?$Qxoz&|&f;B3DW*oX zHvwhY#Kb|Z#tvC7^{Wd#A9sfiwoI$<8a$?M`H-(pDs@sp(@;8weXZorr_!D0w*hL7q2C#bf#cq%luwy>Ug(x zl0KXq;V5-Ikz%@8|K3$zb(;Zp$AXtIheiD6$}i*oGAzHw-3k^e8XdWfIxA>&**m%4 z9`*!(^&a+>OcpP_vCFHt@6*k&vVySbsaz_YMOLf9s#V+zZP%NQ-iGrp0szrSC{rrd ztCGpJ>^?+K-|B;A@i35g0fZdKMNiYcUl_S`i~0&8pMNDDpbKg77 zojdY%%~($(FBieKJo@dz6+q$eEu}f8w0^`k5sgL%(nU26sXA)m_=Xmpc73pJcW384 zd#(L9-Q=w(@!dBvvx?9sF=h)Lv@>miiw@KNOJhY)s8ILLn5~V*5bS7tj8y2fqJmF%%gXXh@{hnHK~CtX)6*6 zgTh)UvaWS6z@`3m?!1dt^Bwl{E5KDk9Pr*u2_~mDc^-Y@B?@n+mgpyl|2!gpkE?J+ z*A1v8F?BqXoN!)xkWErMJ#0nLR9n|gwjexZxAibkvVz^QL3v9M$nL#97}Byh??Ow$u1HG}alw zOA3=HMp|!TSDmgXw;X?L9}_D-M^y_8ZF|t!VPqiEY+Yo3mB3QRKm#Amxa&#Kxj?G zP6|Fw?n~B7009;kwL!s{QXIY}D0Q}|u`l=(CGb0uKO-a(!!FiB$coKwQMP_Ei71(D)QGz?>m{EZ@n1y@Hn~d!VUW1IQO5 zK@T$#bjJm&{Aqf6O&Y~R1zOY{d=-3xquV*dVUD$OlS+H^RK2)+$volfA3y_gX8@?o zp3EsoM+u;Q-KY?gDPC)h2ni@XuHs&;wQwrdcN?YJS-5U+BXqlR%p2ea8TXdkamp=C zc=A7pcX30{bcUVZ@i3(l$LOe5p=J?)MCVVnF~58SP{DR3rwZ)fwXOdlmiFbN=E+Qe z)4)!Aa!UI9M}Xqgi8o4Vx!l+jJg}3THUx7qHsb=s1c8n6yfkjMGJ9@Je{j4nL6~g#4UD zw=*38QrCOXxAz)&CoA7PA)?P6{5GZN%wE!PNtkVnP;RNFaSeE0u0ApkY5Valig|!P zhYRot`5H}(w1;@(b)N%wU_cFqTJA6xJ45yD;Mya3CYz-BdWIzAyCh(A5Ub{XzgnQy z!y3VitVOOq#MP;vSFM+?d5`IqzKSiG0k_o{NcmoK>@;m zfYql&6)uYcHi>BvOna7~ zUQ${Tpzdk-=%tWtDm(0UXy0K6JRv+plkH*eb6leK#W zKnkHk3S{_ecAw%*okZjwHXcnPqs=513t#n|^bALV`kW<`1=S$*cxEmhC&ytJ)2Q}{ zmF(Q0hDs*o(=#5w7>ENc%AFo%(mEz9!B4mCaLfC?Z#nczi@-fNg=YoPls1Nmj^XHV zkMEw?s$NZO-mhyhe9usYM#BxA=BfopB%W`cL{u!x0u0ctD&6AYn=WWr<~7d4u$_{M zZCIzMi~P`r+u36LXKg*)sS1u{C2Q2r3Wv!NLPbq;gQ+&k5tj#nOcBib-GfuHg~=Ok zjRxx|IXQ5>{_JJq+=yomC6F7+lZY(4DvnaP}+d#)V3_du$`v}MvX@p zvHle8G{??lM!5hEyYmzl;>`P_BJ|2}Wbv{&o@se;FQn>#n2G~FNM?p@X@gtO)MxtR zX~fUHq|BX3AMp>g zxy=Ez65zSkpxpacB#d^oTG|?8g{l801AHT1Tnn3HZ-Yt2jM3WG=$fi~Wx^kst0%pI zMB>@!i;isOaPmOImq`{t`NwKtVM*(Cs%2eiB!j9OA2pG+uzrrH887>tJT%(iQVC!- z0uSL){3g}nyJCcTM8=FTa)U&Usjoq~iN<(B*iz>MbZ*e6KKRw}MiHhaxV-{fa#r$h zjTVqh>1L}}6ljszqgZ2}+IMGbazjoW!y92tNDH#gM}V)z>h=i3gw--$Xr>95uDnNR z^(;go`d%ots3qvI|3Ge;bmjzFfHj{})x?An|< zlcruaUk5(K8u?Vl+BI%Mb#*3l)C&jobvf_I4>0#W6|FCL&sF~QmPQ?^+yxX++-kFP zw!~}1Uu4=hby^KO{^D4?`;3V)(ubFA`F(l^%eKJpQSoP(irKYF?-SyTCqG>5`6-6p zyf@U#|Fe~$za^AOOr<~8c?7Z*QjzBTvO*@Hik0MGA|bb=UyNo$@yD^4@KS%a5`)kK zq^^5&?A8ZLQb^=3{e6VsGil5W8YXv?%IDcKko$nDb(ttFx9g)(=91usTmdy)3PPVt zo}kp}>22h@P;qGUI+KDa8!2d$UU@k3EY&^I(g2eb+iE!5xKdTm7!xZZMG^4lLsF9d zq|B$CWPstg8YefnHQykW)c-44XVcc`~GrBLCeTr$*DyW$d5tHpe z^rf=k1L`}(vw)PF@F|ya;GHd9W0ya#O>FKX+K9SKl;gfr_j3#2ph*xfh~$=1SG>4h zym*iJP^jtfE+ozfFzbC21#NCH*9$SCKNvGN>1k($4|@!zJUQ!W( zzni#*$CILmIvuJ&?TjIQx^~s0oxROu37nRzkNf^ehz)h`Qd%QcPwqCLiJuLyh0Bsh zaG|IVFM#bl6+Rvl$Z-bn=0-W58Rgb6541rZlgmLZyZbA+B3V?}y`;pe6si)uYkodq zcvtH6-Q%@;VT1+MmZS;!OUQi#ug=USFcmO0bT7P@&^aH@37ASlajIl{OWDIcM>f7V zEhivIAtdh#wQZcb>cW{(Owj^{xUdpLiSYzO40l)HMzsV$9LDm|&Q6p!F#!|C)A1*o zxCEL>90sO{4&b+c795isLyMa5;zQCI23qZh);ib`ykIF+)Z0ulFUpLoguX2tGxFax zzuv}}P1Pl#P}+P+$gX%D(U@qYJ(opxH7gPSep8B1jy|^lVCC9MI2i!zkSK>__T;_N zmlc}5AA@#u#~ziYq)|gbv|g$ce|+}e|9C=AZgxTwmJ{Yt8@&RvpLRVv9p-L!OuoAE z{q=xVKyc$hl=^t-t9o4-a0I(b!HAvcvoy=$JhCGW?c(oVy1o5$@_)zl-MaHynqJqA zb+&cZDqD90_F37a-gU(Ci>zDmRs)21LJG-#kJ(ear!MvVK4 z_l;fXc7H&!gv2;fj{N*`0Tafh(z8!5kdD*7NOP3h6<(1Z$h$0Xo!dB|u?3rqY_LeH2Nr;y5kFpD{k!0-Cet!)U z9uFPMv%#~gei(({=@>SaZwQ%nT{+$Mo_U|iSt)8(>cJE7ODMS6?u%q!PbGdW3u9iy zK^1m`Ol+B!ZMW9%`=3Y_iUe%|=~Eq8-2?!olG$W5Wg6xpB2_k$O%pJo~PCmF{!1TV`aXuaT|@7_HgqxIRB zdrfj^J!2$eGgv6+DmjmGRJB38{Y-_O@`q3mH16!_)4h?*i3R^IBbEIQUst)_r|w;9Hzz`ppzZaRUS=MNLT}8 zzh=MW@lMl}ux;VKm=4svJcSg6G~p-Da~fYu;D|jB@{Q zqLa*iLKPXmHRIEWqJ6AZ$k}&(_jszc;S0uKqy+%J+mNlQNxtEH{0B&qh4qPJr!N*p z#=VznxE}FiA7#13IZhvm%s*2D^p5M0+_mm_L_?QcQKYZVsnz2&O(@|1aB^t&BK z=d-tvJnR@jA|l_QF`Zt^=oi_1OofS%tngf(uTkYHoxK{Bp2G}Ce{rk_f+fqiE1nyl z`vGNAHoGo%Y5z1)Kvf@lawqUEQ^%o@9gSKRTeUdpHIR$W7{X$gmgD}T zaQxG;NF!O4IC-m;)G?0M^#vmSTSU07ym?d#_24T&KxgW(|5Mf)P9od%RaLF4nN(Ik z>q<4!^6Ib+@h@Nt($Tzyu>ON212^-9{x238ra^ADdFv2^NUCh;H;+DX*C@H)QV0HJ z82=9G@tVNRj;|Z1vJDdn1cOMl%SLP}Sj>Qnr9*~xYOI5|UB>@!m$x^W68|3w=D6L? zUSjvoTL3BshRXN9L+PM7*1fnjMqs7oK+4A+c>m?Bu|fWivdc22Hws`am})6@-YPfU zyd7wTzJgxiLyiDOn99Fzcg^oSxE*;{rpMj?KAq|4R?Tr98V9)i3BEr6u=*LGItsgY zFdxde4=5^|_V%Y1R`2Jgs68uV@ki0rY8s?^km2m7pRlIFac@@jZa(uEN&OS9k}V#| z^`@rz`NOZTZq9f5R+BHFJ5`OX%H(n)qX7qTB1Oq;E8FYMYhoEAR9O$DFG=Rced|^M zIb_dLwEW%Kld~%6i>j|)Aj6d_$$|Y1(Jt$YFFjLgrLg#=WSbk6jNxI1=lh_#)9u;T zf$M9jz&7Jal}8JcJ+6N@47v|sg_@=o7Qrh6Wg_E^;TzGY?F|(M=y1~vHKK9*;`tZ_ zAlpp6v9#K|TC_ll+0~!7OJBA_%1_w*_t}8dBZob;kZpW;rl5a{ZhT{W%s~PwLi0Ht z=`-|CZ)k;(u&dv>xIFEaUS^X%>#3MxL@%@Uqis$$ine#ar~z0jcU4)j%U4%HWk8S_ zn^-(OR(L`u6#+}>LMI~IhmVhr^_;3| zYu^+Pi+e<+i9)LmpZEjD=hw>u|xi}r0~Mkd*zR$8v)rdr3)X%Vrn7%{&b0c+N9n48SxlFIDhIQf^&+ zZ#dY_0NzUM%*C6_^IW5;_ZH&M6J>eI`K z6%miOOqLTLq*{$S?UtGA90o2H`Z!KXC5Vq_Zgyr?tXfZRMblx=*?`1&f%9?mD!Q(< zZRe_gXOHoELHcdQ2iY*W+crSkoXh4vF*#xC>)@*k_yVpvV2mn_1b`heWtrb+%A0@V zfAzHGWai|SN&%SY+tzDVS^T|aL&ui%Tj=LM-XkoS`L;KFrsbIfs)32RR=!(VCgt?X zfYi!fd-s1N-hBV~Ai(92AYg18$2YZ5JT|O5d?Z*eWH(!DjCbFq?Xr!(+*Y;Z96uoy z{w;|mzmFboEVIya*u=&<=y?izgM}5K&V3xfzh%#0jfJHVDG3_HGNz7@#G0ep+{C6} f&V}M&c}iZ#z|I6F=4=3MJ(i-J>g!Tj<4^w&@Cbq9 diff --git a/planning/obstacle_avoidance_planner/media/object_clearance_map.png b/planning/obstacle_avoidance_planner/media/object_clearance_map.png deleted file mode 100644 index 199c91c0e49a85afdf3d51b6ef42ba32c4a2e459..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 329688 zcmY&8Kl;uLo)65NYxf#Pt}bI<+O`ks}* zO5opqpV_l#X2+^3%b+3?Ap-yaR5@8mbpQZ94*-CnM1+TYgYSeS2Kfc+Augwh2sr_W zmNAgegq~8mo*FLJo<3&oRsb7k7bmNa9v1FaR?Z%_E}oY#y~2=x;@_>;$Z*X-opOrAU}qk?;xw30`fB_jDzQQOcXcQVPzW7;P4Rupa958 zifQ`hpA`i9k}L*Z_NM){vToI{Ye}PRV9D1FVf=ywT{$!)#j|c`{wpHm1Cq18tZm-< zCS94_O-sh-&vpuz^FOh3GkEP>B<98E1+%Zx1~K+v#VII5xk7$^Aq_jlF!(j@uV>e~ zTCj589XvUGady^~&*@?9V|8#ND7egNGyPb=*?hWjvvGL|#zcf2r`WHqsqbIg{0pSP zLR$ZP*`4dua~mlLbYg;{9TKaCE|{2qcf`@Tb&PG`oQ`mO4}?DAWHWb zKOEG$q;BI_@?7RKxv$?ak{lrH;9C%|r5eTcVg-(c=AZVMI$iUteu8}P z_m6HshJx?o`?-Yun{Vsb!{r;ybo*{;_S=2(&TaF%rC^jlNdb_Wx>S_V>t@kOg%7_P z==}s1&}sL!RQUZiHBFF&NtjaT1K{=BrGcJv1B77Y0m;BD(gGe|&m}gdPrUfgsZuE; zK9_UL*Op_L7@G=5ouAg#c5gc5SfT(5j0&zkzb*}%z3Ml%Ps8XKqwY)+BF<~v?qMYH zxbI!=y$HOMfr8)hUtX3(>i>cR-{6+rE_LSS=0frBjYCT)2<~MF6@YnCRk|D(Gvi&i z_0%sd-cw>t-ZT*ps&_L1Auha^djV0wm9$x7c5iypID;L%^h0HJ*ZJb@&NPMso*#|n zy25yxTmZAi4(ex{;ohXDj$)_n&RW4IVC;|QPfreXp9em(6A=x?$FrF;aask1#{WB% z2n}<5bHyHA^VSB<4wKV!2`cl2-_e^-Z5zzkgPNBNE{X8=49>%Uub&HY7T_G-JvCvc zYYX%{4B($j*`6|_RobNR`Y*5M+wC^3_7?C?7IIfw{Ic!LK3Pco_`TxjD~xDG&qi!! z(g|Pkv??krG!%(Q5Q)JLXWH(FxQB7*{y?#a=P=#GhNU7+r$%2vqwPoM81q~|l9CkI z@$hZmezsX@VmW;bh0j>bH4ZV(WRk%qYzMH1y$gQ)o!i&Gs-yS-K%_Vn1Jt89RAd0! zqxe$5G_70A2`)XB)rn-QmS;68HArVQ2RHLxmOh)CY=0vfPDY(;ql>; zX>Ox8is9hTBD)PD@hjw8(fGX&#+G0_waKR7ZmvNM?WsCK;w@#$#M2+2DV1_7LViB{a(fS*4Ttq6?HT;z_i%e!<@MoOw}WRB1~?nT){ zZ?2uqkuVJ?F}5|Q$@Zc~uD1eA+@gc5XaOscZfb>X5QthwQ0&;?<<$76hl%ss!^>Ch z9@1ReGQ|h_6ltQWdd-1=Rj5*KtLud2p?cGjXy&pu0`@*7)6bXQfS=u!t-&G3yO8q> zR^E19R4XXyLbX+^q)WL+`m{5Bjt|c^&}KdlMpXp8uH9jX(Zqr#tTD>68|u9Mw61mO z)f?*HNxj&Xx8OypdTGw_teCp`)-rR zwor;l_KCtsBl>cr!nEqTLwS*}Ac#%)$6p(BQ0yKrV&+tiD{sO^r_bKwVG(_I7g+&n zx~?PA+!2MpIAtw8aqm7ZvJ@bb?Ta_iSJ8aJ(ml~!G#(?8#{5Rq^M*pYq%<)JQ(u18 zC|GT>q*5S6yeH<)%kK5&k)=6NR}80y_zF<{I(~Y7?GiR}DC6&!>o{rch~WTvl&aqk z{m@FXp~k-+eq1RgA6Z-mAs3&(6C?%uIP#3H7Vz2bquIEg>&d&uM-0_F7()|)g;7-)Y6X-FTuV87tcj&e3fSHels7y{<7${= zBA$uXDl`zKWUiKa+hB~k&29|?7|ny9kSyPCBHBB@aby|x9JFb_wQK%54k>pS+xB~} zbJ2cFVQ<@{BA#pA^_=vM#Jao7f@h6P!M;knO55?OhZ!0w56s@CYjl`rousjG<#lUY z+-ZZHd@Y7xQLRJwrVh|07ngaK@#o*%{^nWfyAg9yK(1*$T=jgMxCG#~m2OPDa=eju zBxcA(>&|UJ%P>8zG}9rr3_5j}2ix@HRI)5<P*k-%C~?qwSW z%_SRqm=0Nv21~HNTTGHlqV+ZiFC`M|>#jaDg|?(*GB~;L0^qxuoSDg@m%x7r)765> z7{lNHbvK&@co*?ZQK8LEWH6Xi8e8)5^04gP!;pLG>kA5D>=&p)FkW5@g|BwUi`dI* zWl>avK-fYK_|x5QV$}urcdaL^y-JE<70i1TiI78L69FK&-6{#^<9Nz?lsrf-Q$7`t?9hKFR{@sLxw`|yS!9=Pb; z)MjBtY8864ZUTjcNbzCHWyPP8) zB)&;CG5!UkmK@wWO&o{z)zV%}K%)C_svg#0o)@7!3YOkbFj+fp>J2^n>(7r2)*4Zu zr0!=Rii!J2WwH)z8)N?kSCj!?ob&yb7|H3MbiMU8x`sA{>;;l^Yc(s%c)1)ahFY?z zMoNqNO4@exhv{(A-xI=ao>Rv5F$9`5FOeNM`%*8pom5W~nB!0UuQg2&XwPpJy^RyW z@tYp2#U4qPPM)g_k)(jp-&`kjU$~NLo@Ng0-|KG?IzfM4>08%w+PN4COv810(G5hd z?N~_pV>Is9>pmO(9c6wv*6Izt5xL=`33`!0yvDsU*b1vJAJP}1kGmES5SUw8WL$J| zhYsg!uAT4%&a?KX;mw)ifHZ3t%^;9Ugs{x6p>5&CAX55Wv~OA z$zF>rtgVat#B5pCJU{EboPkIjPPf}s1Wp}+J|m7ECVuO5Yy7g67mGl@0;k$gMywJg zc3yQyK3=7vckQx*;sWX#JU(TDLFU=HblUq@w*ZG`Ozq9_h@zs1!t1%z@-9jpYx|_7#t7p*N zj)iPkKw2P5|I?%qd#IfDA#nA6;F1ytd~2?5giW*(Rv1s0!Y7=l`c0>|cRaeZz4w6= zAnNPO8T9)nk1A{C)iC`V!XP&NZNp+LTdE>e9>+IM*;8A0xC$OP$R!nYbA|MflhqWZ*`kdXIN#Zr)=+56eu^;Om@;T zTo^e1Y&qgpF6^SFDn}xO;(0by5o;tX9hG3DOrz^ZcUw=1Ynv+iqDu`m#?o(@C(#pb?>lrxMx1`-exm&Sp; z1v1;x#}2p}rYzkn_7L4WxWmB?M)r!#CEs>mj`&I$GUXGUm^{5bZG*GbNcZ?e^aN3s zdK@%xHV*T{_t6W(Dr*!M+z3AgvYOfKqt2tg~64e4LT1ux>DQ zK$Zk5s(x8Vp~glA(E(Vyv>>bKY`sCB$g4O+SBK+2=#}T__`js~cCdQ?rMhCi)W{~x?djQ{-KNwScSMdg3VwVx;fF3uX-ceI-aU&3 z{h zG=0-Vw%d14JJ$~s72uUY@tf6_CU|&qR;w&C2uI4_ik2+tK~tmPM=QhHhDr32SYU^T zCYmPw2nDu0uh~WGqwBt4uXA8r;-Wq{k*rYst~Sb!?E|Yu<3D|3EW%PChZbX;3nmIc z#NgC>2qg0QVq5HGPFTQ`(?GwTe3rxc^!lp{-@uPlqlGzVtl;oBhX$GZ zwO}O!M{~Gyho-PoTmH|>J6oZ)pH7zS+}-Rv=-QCZR$D%BjuDb5FTV`cLP``L@3c@9 zeVVU4wfwNOhCM6bydRKam!;&UUpzXRIM0NS;AG!v-8QQ$m`ua%CripW6)s*LibQL2pS@zFbM zv2bdVZD8>YI&FeUsroIP4Z)aYL6&%2{ZU5PJ4wp4hw6-3SC!V2N7rH}U6UNCVDuL7 z8d7w;)b(s>=9`>Uv8rgXst_X#Ac^^}X;24btgIl?8(k zl7w78d`Tkfe^Eduo)NPtecUhZ{B$$WAet~^%hi|^Q1txVGB4!c5wQJA;wwVW*B#+i zAx=P!nB%MtUR<5?!>is++LR7#-(BGIsr6Ul#gXL2sRe$>|BM-dEh6UIJfs;3J5%K> z5A+hia*L+uIeAVLBi0Lmp+IuIhI0^4+`#c>QQziE?0cSm@<)D?HQ7U2D#2%@yG(t% z8QCExlm3IC!adTeZFW9JPoYdMW=88w@^wkIBqT@VoolJck7&%M2p)j4^@ouLja>ZT zP=qIO;PS4Y9Fc+(98)-P zwnnznU~UUE|NFFq97?xeeA&YZh+j%FhFW~RQ(-H*5eqnxP1&&K>B6w5^6w(Dtjp6Z zKe7VnQlpO((Z&%-v7_I5awR#?l2VSbOXDEJeMN~Wp&326QD+h@M2BJs-@~bgO`Hmz z(oE#P51zO{w-|A`l*!7HVe%%qVG}ZB<5HsO?< z25SMW{P>k5xGi>Rh$Do{fgh+kMbH4UWbbr%g-^^GO(i?r)~_-_ujrWTLAcsMFDkmh z=K_{s`^1si^3p}t^tpOasiT6COQnPWnTDIp9NQMDc+0M?eC<-@3{1#RYq=DB^ZDHC z>^qf(X(Z6t@TuxQK1rgjy+mY`)k1|W_w21Nf-qQ7tTfQdFR6c?OY3jfs?~B+#3ppP zQlwG}6-}b_r+u@get1?!IBGCG8uakqW9u6F_)ri4FnD`(-SrgbwlE zQE}WbMRzQ=-L9$)FJ*9hodjtJcNR)g6??#K-#n&FSyRT996Y-6qTJniIpak^C!YDv zofqwcCo;m4&Prz2N54~t%_8%`TjbQo4=tbAv#L2G+Yf7sDc8|9RQ>o&P&J5!+%z#_ z%gO@FTFH~fUAV$8Cb>B6SRl|XD9?wfAk!0hwI&?1eE){W+#o29m&ZirwU%_Dv>oO1 zb^m4tlCcnkc7#jI8>_Tu*QTnM@Ew`I4&iKUJovB9= z2&UkI0*HJHc}TUneRjbsyD8U$Neou~Ke~VLiATU<2C1LpH$mc6KN0+lK1eeR!RYDy zO!USux8)8UooC73KJD|wJU&#f1$~5tOad_$Vjiv9&ts8i>@s6tvOJe=)L4mR7%RC5 zrr7F?erpfAAL3=KAE}8Fc4gQ1A3fdN?2w!T>G1LKvl3%ps6Q&rjg4xV?u*ZMN`GLU zM!H+Jc7tBsVr;3`2j#QMk;LOop_>@~2 zxt!rN{5>&rFM!wYPnn-d1Sm04&dc`T!1|k1;Xhfp$Mm&Z{WfoGzxvgkl5xtAj!(nr z5+bNM91pY{R0vyp-GKYO{uru#k)*wY7bO42Ycc-Qu-45ZXu^uT|F6Sk|A(SZtSX(J zWDSwe%yBDR&3w1z^DzL~TDr1jh_ZTaBCPF(8aW{5nvZ^6{sc|}&%x_1 zEO~Pft)bveCn2YXQbr7jZJff)xj_c>+v`TW$$W9{FDzWNOGKo`{$POVp0in`k=bA| zf!8T;?x(EjqQjv`Fv$w1O-i8Az@jCBesPLqhIVPLNwF?0fJN97Fp(VmfmRGQc=M6> zvM-wb{zq{5!vH$B;o9OHQm_wTrRAgG3GSW1nPZ}4m;4t?L z=l@~reg8?Ze)b>1Z*rSctQx^00!8fS&sBgnxxGP5WwVprgb?Yawq>_OEx7LCnxYEP zT#A4am!@`;?Mr`5DuyDa$?lPv=OB1+S5R?6Hy-m{YvD+}!l2%puax1Mi25UBg%vq~`NY zSu(wd?XJzJ$2no^N-Dw7n;KwxQx4u6-1Aw+&drVe@+=oRQhNQ}qN!@~-vA%Zpt-JG zBJSICBkk0;(&rOhEv_LwskPy+H4Y$GYs=Lg=_AT3k+3xVW^8N!1!LGfU%NXB@gQZ! zs6MD4%w&%0!kp@(r7}+|`+Xv%s3badU|7w> zF#-2#MqIh{_2@K#{&Kd2=?H9uU)Zf5TGQ>a7)@nGicar^ZGkesTdx~Qf$ifFtfHS^ip5A+9w z?Vq7A2Zh`HN4`;vX4+KGUuU~2Uuq@E(c-pnU-1%_L<94ohzHptX%rC8=`f1 zZ7s7zCTw)-J5r0zJJARjJ+^F7e<3or2W-)^ZR6g_s;S+z?U0laXzcWks%Yl403M*I zqO#_}qlN`huJ!^D@8K!Sq?8U(98M(h)2?lKR?Zy988`PKbC+TTKFMJz_MRtj0~SK| zd2Gpwh95ilB{SH0=`Qp(vRilc=Z|@Q-k|my(NXhRJcuIhe5mi=y~WNBel&ya4Mdpk zdO=*Wh-(oz0XaGc#4A)%uonD6`vSFS6O$(1L&c&6T!x6@8?U8G-BSOE9b{lu5L2Xw z+$4bQmca&roCUjUh^7XLyLz0MT&+>G6T=c8R%%2=N3PcSewT+Xthq2k_+h&yQ*m>1 z^98}&of5_Y^uT~_ko>@6S!51U^;5pcR8>jlGKL0+?~9m$WM6<5Bt1<2EgbrAFMxPqURAdc zsd&)DFRI?7CZjx8TU5yxYo4eieaXG!k4PcMC2 zV*9;;s1U?c0f>p(=+Mg#0bfJ5e`(T5q(jQ&`~;~7>Pe7bUyAzJ!>bRZR-NAG{gaa@ z1+xpt#Z#|pVgCl>kDl`hYw>LX+r}x;Fx~>fJCv-w<%o5? zuNW*!Ns_-gV>3HC|D2kdGNq};$agIJUgAxd2_=kS&s!m7ge*i$`|3b4;%F$35YZJR zuK#ZaHJKRKB@KWz5PA3%km{i}iKNSS4YT^~j(z3f;8|ww`HRB#DPhY&2t}KU{oLH? zokjO9VEho(K0mvUzaVGKkP1cuF*AW|=FVEGFoVEL0cdOOCLq<0c@c zwHAjNK%t47yRT`3ABXdQS%9#~0^pQCx+(W}NT+_^ppK2aA&hC5OO7OOQ`SmbO!EGM~O#S?H8fDR*RKbG)K{bGD zBwbb_9JSaGBjwn|@})nx^AkURT$Zsvl7@zcq+4#RPEv`N$a=7ZA>@3U#mSxgghdHB zB;irE7;=+f#^F1^Xr%HcEZ~#}!-v1=iZi{W@aN~|;LSKImU-APM9?OYNn86t=h1mX zEyoYCFD56SwT0?mcWCdnw8`>`D1l;WA`24?f5`D*FlPsRH__9R;Np*QHNgmD&~_;2 zl`1$Af9?*qCe?L}$vgogSfNH^|MneZgeClX{Eef(+9EtOMLfK4o;gon97&Y*t;lyr z;hnVVanEtrR{V)YspS{bQ^2C{A9p3}T%|Yd*yK2Z-?;|*tc97Gxx^~q#fAN6HKpdm ztcXf+VVkbM0JnrWv#R>seEG&YS5?=t;RAl=HOx+{+!y^S4{mNffHnO2a^_!~p1<6+ zy|-B2>+f2go}LuFZLkd^@s7nH=X7R{Za;|VvjY(Z>_n#1aD27>z@3|suDpi0xj>ea z=cBhZ2=&@Ek9p$cbtA3x_Cy_P#E8pZ#{tJL+WYhA7st?^fEKri>v)~@)hb7#h)2I* zEV0Z*s-uigs_fjp;6VC>gzt#4Q?y3&9(`RZtS)|ken7Xw;Qr&NjBuE*pfOlDQ{F5v z&`3VfCd}~1KbFngaGUQGUk{lBKw6{nJtOVvb&3c`YYRym03oTC2=pdXjoX zckBMd;e%Wj{W*+nKY)5S*+-7Bedsy)VjU;y51h*7#^%?8Sc8-Txt6@jSVj=nDq*XU z{2F`4{O{xQ)o^Iu4r6_38&F}f*W%OqgHbGYnG{#Q9VqeZ#^@1)YT6(!_0x~SWG!kP zY^1Uo!Lbg_)hiMNR}$n%=s)dYb*swMrKNzf)>$tl{vBI$mLw+8A-*^C4sMnzti-H3P@P~T(xKJV6{VW-?jv0s2Uri6mRe=ia7_33wZ z&u=^&jp0jtRvUVJDOUGWu6C{>x;Tv50tM^W6)*e^*8x;O2m*OP%9H*V53fPm-*GDc zgq-tGt>SN);&GeV9Qt`+0CDjsV^r}OM)vdkMPRL3k1WHoV7wmK{ zh&)82fVhwU>Eg-g*(RpkbtI<3huSffG>1-YXM#JfZPPh}T0xjaW0pkf`?Od{fN$89 zRH=v%f{dMX6r+Tus#JNXQ9kcsnr@6SRNdT%r-Xx19X5YOQIdy%nTOD-s(r|z{=uJS zn&K|NDv}ceF3ln8R1Nq3jK7)z_}dF~oRJ2{3pk3s_&G=}7_&VKM?ezHb710+XcOd? zptxZ1c>2!a`sW%V!=33+)K4DWyF@qb5}s)AE&@|vs5m~sPG8p4%$JcF6hbURn9*z> zdz&}lm9OBh<(H%CFwRASRZ^Tr`UVQ zw6C+f4YTpIM@R}L4&U!6w}M4LaJ$$Fg5T^BzU_HEZwokvCovGQc1@jFiGtAPa$4K= zFD(2y`Z>@l=r!y{0oOyk?=Ls0vNTs4mqA%=en@=N}z$j7DNcjZ@&NE z#t%16KF`l5(tTJMI;-6ck5@k*CkHcQBl4^V_<6C>2?f~L*dQPwkpx0io^&``y^LS- zdH872ZgaTLpMZY@rV6#)zFERbA%oPX?x^DaMntr)$OlrX-zQ0(04FoUlmuK_zCb~2 z!2b|&`LKDCZ(v!r*E}-!4l#jyaj@EuIF3DLjv`uU;V0JTh5K#PTk6&;qKcjXn7AA+ z)hZ9GqhB5r=lKL8aO^?jZK%Ll73mAK5w11K>T`eW)3Oj{?Uuy z>QkZGvpHt(vJcGn05g#=e8Z5+A3}*vTU$|{>`t?giuPODVo{nPCVv!JI#D&81`<^K z)IcVis+L(mhC1DiXB#fhGLFm1Aq=?h+;Vz)aEd$)a(8octCCQzv#BafH%b8Z6uV8w zrR?5{bh1R2ShqRce!>a?d^XRTzo9xVqT?p6!dMz_@l{4N!^M(8hgptS!tPATC$4_k zfUg}IvhGnn8!pTK+-jYk&*3uh<)iOORi&au$`GTdJ9p%O8Ozj+*{4+K!z@??J>Qgf zRs^Dpbe>80Q|LvU%5h{jd5NF8dYQjG7y0OMEY!>z?R0g1#EJzk=$dHUIM&6-?416q}`V3TY%DEJp zvX6Bg`5VGP_v=wR3JpVJBNu}?_~hJ|BS&pWnhm5&(BW`AI9sIE9fWd&ndX ztPhyqNDEYTjJ$BAWn`{@DX{Hi>KGUI^emz=e9W#O^4$0j@;>R};opMv>7ZRJruQ*fH`5{;1vU*9PSGh?6QR&Q` zy`y+DF`PE&l5Pn3^#uEVe5I%-_$x-!lTurhIi(YomsXMz!PZ1xoZ0bXc3wf1 zzy-q;28kC0ydkf&D^1L+!InFIoiAX8y$ty>Xxa%R%JYRk5U~d~q)$LKIm^vbENP|n6-|wub951Bp`svlw zItaOvyr_Q`_Zefe9o#b@mk0;WWKB3YqanMY+ebl7Bq+?{F(dwU$Y|0sZjyVW?hmTw zrTw4~(9KJWjfQ}Eq19F~j{GAdyC%tMKjT*d63QtM6yogxf*s7ltFCWK{aBivms5Na zHf&{?>#xF$o85ul7nWX&OAvs+?!FS;=(UAEcf6Bo{6N?N{fc-M|I4G28u3$=h865U zqRT4kel>;#J~mGZ_%wWkI#%H%@i9QyhCgfcCkB85^d;E$B?#{9C*(Jd7PkAmijU1)vNeW`&NDVg{~e1w*yHA6Eu@+rmrm*vS7mY{5jx) z%VxTYC9X&7E0ldh(EgQ4$7Yl9>vl4yrw=u3J5{rF~eVV^ZV+_F!kly zZ85rua%;)B#lK<59{^afusv^g4H_n$bCh}}KQ8{c%O9w3f!lh>Qgw<0*82f~QK>R( z$AD9(U-QWSycGe*O_z)o-!k(rMsuTm&rMhBQ2z<@6$a}1UW5qosMbU{lwRv~oZUWM zs>UjXiUJ^NK*e>n-`nHiziigY=_Jru5=5muM!Wz|Y@0f&s)Zs?Q#!pO66h@SYHC zXTR8NO~tz;#?+rPIOU=4MDLP?U@ra5Cw-+D7rHSL-KME#EM^)_eD`N6JvF8>Ux z^9DUc4QVFX;8(80QNR7_^_-0)RThS=F!_()Vu2J?Jl#*oK%OwE$oRFOlW!mq)R>Y)S* z^Dt`+x#gpKcyQjmW;&S1a3q=-1y-f?=cs;>s_N?ywk(!T`f-w`EXr?ks=G=D}Z$G8aZ=n}i$WrziZN_Kk3BY+O{u6CsMN2aO(WBh&(YGi0xB90F;BxzX_KB6VYl|h$2&c4-R4AM3GCprJ+D%;m<6C@h1r`-6(QDBfG1%0Po z$ddb>HCmO^&tNspF?jx2F*P$GN$-)n}K`a-pJ8u46mm`<~-TSTUDrWj)1&{yKWIf+0xg5?(wO54_4!YCvF z{oVMl$E-{*Ij-8XW$ZEA_RaMZPDCS(5ZkdiQLoSby{qjp2HHn5Xux{V=J~_)Q#xVFHF<=yV-WcDg<{ydr_}P zfBwi$k&nDA4Cn@TzoE)uNKHLUX;#L;BHM(w1t9PKVchdh7^H0fn{~h`Nf~z3I(6uQ z!MWn!H};J@k!SQRXspjBmqYm<{_g(a2+1|I<^N8aT8=~oggB^em47x(b!_chCz8}v zQyKS>x!vS8ujmukVjmd~)L62%*#oe-V+Z;<<#z2kN}A`XkyM+mU^U?wCaxJ72KOMZ zCotbt=;Y*L*}=|ZG!y{r(nI#6$VcF<_SUBDE^+PZ=daMH@AX%fNi(NeORsK1ktJNI{`x_N1X;khPSL07+`feRY;sT^6?8It~Mpj`ix)?#$aK zkTul7jn??D2BW&*#-Z>LtSF<;Y3Pl2pn;oLTQRFKzqJ+L&IbcVX7&UYS(?#w_+iki z=wdTgx0Yw*?b6Cc#7QGy#(&gG)`F{Y5Bvxzum|+wVrq2?rblZ=V5XOP#kof=eBT(0 z6#-Mf%D8{Pn<+Vee7tB@yMnw<0O-X1E1yf~&1Rs$bmtQ!HNLLW6E|d`qB*m;*vJth z@(*sGe|j*94O3#;o^}5)^98r^J}wvV-t3m{;yNbkN^`z-ddEY; zjDw6J71=iUM<@)m-PY8SVA@y-GODZ=N*oxWk#=!m)9$%1uooyQ3Ln{9?A1QxHe|tr z0<=5g{dP}%;BU^R?tLUn2-?-qefw*X-F34?uv|X(e%~mxR*xPZckeQYk-e@j% z(Z{d*@)rv!PaRh0K1eU#=)^-=qQl2R#@8${^OdesoPZ_44z7;d>SM(5BsHf<=gGI*o68R54>P%PPePvR-*1at49RB^>N(vQ(+tm}m&>O;$J_ z&78wvHPs(Ef&$b?>Lp2y+S+C3dncsof8G}v=d10WnLMgG$_5SZvMJ&c#k1`V)h*3f zNzkCJNTW4!*1f1_WSD`hEvS)(c$q?+R2=3>f`Q}?lRYY0(>{+KYLn&c?|%lCpNNAa zz&(D<)+Q&PfjJP+)zl3`saa9tZ8t`bf@4>g>-C>cEfJBi+-?kJ18HDmox(P+(-VxrO z>VhM~-Hz8Bzj6YKEnoN)8LP{d(lfISN7B<+RV+TTgw%;1F4@^z=<6!PMqLQ9*m?QyZsI;%0H)%cchZ)j;0T-0>mFP%v#-{XT z2*RIZXwIW#8NpfG-2y}>yP|r83lgd;_%1}>Xf@yk4ACnc=g!rf<+7%$q+)f4>%=ls^UP8Va4nowO=s#q* z&Cr?4H1oGay!M_4?Z3go5g&q1S-V_kGGz<+k}kJ|qs&>I{0LT7G!GL%J0Z49!#*(l zTSnYPl#o@TgDpm;@~s*XD*NuJJ` z9BdB|(-Pz8VRPC~OZFi$4+e0%rsg3X?b-aU;Xj{A;4f#>aCz=$#yo5_mV+v(E2g?O za-!Gyiiz}V|L#%iyU4Eyc<9^LgOrH0P-~Cp4@*fh*E*FKKSRqAxYzK1ubP!W(k?g* zaQt}v>G{Glzo(!ScFJ(=mh;`kTjeAC-k-OU7Z0R;xH{uV^5BYzg$)QrQHx4s$?Lu^%sV> z>I&hx5qOU^%USJb{J~F=?*Lwwhn?`fbpH40@WXR&OsYvYCZN%8*FT@v zGa59j8D%F=Px+Bao%K6nXA(@fcUfyMiw2H zy6n_(k8Dg_gD#I6dt>seT(q@!0cqbN54uu+A;J4J;mTOg~)fuG?OuPsLPia#;TWiAglg*?!p@KK67xVV9epn-pshV%F`L)kVhlXP+zK=`lJ) z=2~qMB@HJvi{L6RlxV=zbLBrgNjAOC#81sBsvZ*c7a>WQ!9qjSBEy4ZG8Yz|sD_Si zYKLYzK+9MqbMmVK%&ah|kdPJzDNu#6GJdE%rLF8Ak>aUv)Tp>ibCA;-VqCN~fVd(Z ztLoz2z7Qur9%V*n{*loFM)NLqpZzzEKM{L6M6izm+DqwGO_?o#D@@vnsC)gX*!-0mA6L zV3$?pdxD)8n7nAp$)Y(y9Ts_L4Nyv@0fKfz;1J0dGLe{lW{pv{k3Xj8s!Ez`=4Z!d ze^(JshzNYFlrCOw&wcl$TD+#VDPbpG%c&ysQ_J}4zU+x`-94O62!sgR zL7_66Io3cS~kVtHG{KBfqyvqZC6Sxi6AOcD#C17A z46O2Ad4J94hdLV(2|g&Z*nVjnowXX_N;Ky0Ml=1{WtI*M|Ce)SN`|;qsiP_0N>to* zpv6U}65NF|aV!Hp%C~ICr14!GRm^YlqHQXxp3|1@tvEr*miSt2D#s*Mu^NyCR{zBH zXdZ$u{c_QwFkS`Z&4=R$9zPy;PeHt|um_c7(pRwpuGS}*wKL@NqzcW->0%_~tGa>> zJ8x!!B5sd3gTFOA@sATF8Zp^~io%c3YX(ia9h_cDspF2NL301eUAkh#YWWu39^=r!N3ooU2RfC7VAv+eV9q_uf-UY9AemAwY zb$$kq8H}5VVGU*8C&!GIb~p<4Lk$M4<4mwt{Rrx3MPHhq(HA;wlP@PcIg2zLl6QQ$ z$0P=AAm(_DMG>6?#t+IK9(PGusi|s^r`{Y?-r*S}TK6Tx-HBJZ+G$8i8j{*9{p_KX zK_uW)`(&e+q25^nD@J4N&;U;ES{1T_OT1KsCR54+ znq^5mNlYkZtis7ck%I>E@WdsMgY&>uJ;byJ3Ai0pCIhWJ3hje{8ufLR>PJZMH6wpA z6ODQVB3xxlA&}|7{)r4gR zf#_tpInq^bf|&;FANbEHD*6ph7K9&8xgR#~%}y(Y6U#@?b{7sW>I-bkiBX5W^3+eq z;IH?VpV&zZvIY}g1^(_;eB{~Lf`3Q-rwtvK-1&#N(8WQd<45Q}ktEFv;r}oF5+WDO z+W6bto*qASQ8$+lAq`}^XBX9JdpKRN-0Fa@TqL~VSsd#fROc-Yau?P+j>kLbuiX3` z%PbD*eY_#ouXKd^lu~|1oJJDT7OR+@x6_~yAZ|`!w&@*Nj#+tBsx}E%QigWr5H+Ue z8KT+LaEXMhj;lSl({|HMqjGT;X8Dw5Vd=LC@#pq0e>l4hnJXasvK}Z7LlC~mUS}lG z35{r;zG1S{Lm@3KeF|HtSaGl%GlGBe%&ZVLKYpTL;JP@^gKREL= zSCSDGFR%A(?Wjnroaqq!*VC(S?>NoS$Q%!{7W^1M7AcPA7Y==1kr4{nmt4M^bD`u7 zpp4^#Vx|u=?G_Q@Dh!^t$=v6*IB<+lD7pWb^%G1T8)Dqh@+LSUF&Q&@*m~-cW8QfE zFRhH^p&U~vXZ6B>FMIS z&9*%33LoH|DKQspqDy39DHc87ogsgg^F5yxQkR~ z5~y`jL`6n>`HW|(b#m|Dg*qZ%o>sqXNf#m5`G=)`D?rG3)g9YA(q|`-tq0u&(M31m z;%r#{m6iyiCz)4eQwJ7te^LyUIqfm!F4PG8?tfE=CsaISCnhDw97)H_OWVWkF=dtT ztM{apzW5l8;ZbM|w*Yc$NknY^#{Zl zr${8sM$rC6)hLljQ-%9I{W*w=5+R$iOs$EI=Jx^-5=Cn@VHz&o+cYs$kTuP!sI-&K zaq-kA-<~5WVL};cS#d>r$UKuewohb)GoCmQlHsi44KoI|O{D*zb+WgJUnagk>!C7c z8(X@vfHgZ8yO6Wz`)G1ci7T)2PtC#MiY~^#W*z+Zt+Z+#zFR);++Al=+n}Xhgepyd6U-g^-1SkC_ZVQ1Y92`1- znODY7Z}a2@&QG}PHWp zD&|+tnmqzO^r|C5$@leme~uJqI)77<$f|Y*_3ony`hP~dgRSbKzsid^|>&dS0coSvQYJ3yG(%R2WPrT@7z z+2ShdZ&5O6eZj`WUSs_twD;G90XAVV>XDBsgn5PQg85tfY@aXw$DT2HzVD>TG4wpF zF`J17FYkpd$WFoU@^8k=e#=f^{CT~{Ks0J*hT0~#6Qq{dpXrHt&^!(a;C{DB#44pZeC5KNPypgkmfa{;#iAsmVf+G^n^|a`jky0hMMv3Nfabss;zD=M` zfz|aNu8^!)f^cN%9VLCBGD=PX30Fh^Syt;+9*a8%7{~c6SG!enV`tdORe>uom6U_Z zTGg}1@36+cV7@k6`?Ya!550D&Es_a)R`&w;=83b=s5CB#ltVj*S;t0MD(LYQ3=ry5 z*o&n6(nM`e9M$qd=0gmbLb9Bvf=sv;xM1@EruW$a8~d(l=J!l4^9=d)mvOw$yN=r# zx{67SyCvTXvC{eEGIc$xx{J?{dlXtZWiQP6&xCjV(;F~Bm%U=m-2Fh;wc9urf16r? z5;(uJgB14&L6Mpq?qvVg4@m0cvszaOyIhfKvBJv6d-!(|{)pChWQ6eAKA z(7Kk6WAO2+e+&JBIn8hjO*i-DD@H*9oubvmuKHjri~H=qN+~UtDq$6ROgB&n>tGc$ zM#P(*viDBF>EYF9Bjk&U7-h3d79nU)?=(C^UTN(KqW?luxH_BFcdYCP!m=a>X4nfG zyCJ5q=LAgl+&`Cisi%5QSzY3e`~)@M2evy?gqj_-sL^+?PXuRW3gOBlc)p9Db)(K7 zA(`waBlQCbgsu13<=)Q`wer(BZaoCldN}%TvnpP>W;OFi>jpu(b(uv%f?QJCwPvzK z&F>5trO_!uD#sBlt}MfluAeFH7MeIOCQO+u3Zh!yKKiwcu3pFsBg++%zXm2cqKlzC zv)?v5H`dqSk-?Qz+)}^9BmC>%m$GGj1RumcrIfiD6+2y6G$&>MH7w-52O$nTvC>s&63GI5%M z)9R2!zBZ7K3$$>^ z#wS0lTV=($8HJeK7JjDNw60Rb(}?P*R;V-L--E1gVX0pW>}2<(7hY=^gISUCjx1=| zBB1Ii>iw_`N#)9`GF?mJSTZq|{io4c%obG)Wv^Gpj)=GK%zgLUcThJzt`5YUR+s%M zuH6u0##&n*cE(q-Mwh}LB5(aSL}sY-jo~4Aix%@FD5fc$s#x>0vp$6LirKql#1luB1>%7$vj0o(b7U-s{Y1tTs z7WY#F&X^ubQrz$~1prEL0qLYZ-|pYmMKL3H?ZF~Sm)lh=cY=ap!+S$oZ;M#+8&x*! z+>yY`mJ}zcXw&ntA8YZ9Lm$`g9vmO^iz95UP_4!!UAs{VF>B1Hw^{8dXDLqwC8_qX zX}&z{NK~r3?C|%ing*T}gL}*$7ds#Fw|sOQQBAWk8hsK{V-BSrOG}-K0dx|eMO_u0 z%k5X8w*Id3jcg2hKCdOka&f;USTq8X7yJvH!VZy!&AOPQ{ayz|Y*4Z?K6x`U10e=Q z`0!8bvv00;L}kD5Q64DZ#ov9ST)a}U4U(RW$SCr^Hj0KHb9?jhO~5+uUq z()PLAZeB_@=hJgF+&1->uA8&*A~32|0Xm37mP5lLd}=LOI<9kUqxW~>{qdI}KMo_T zHq5`sv*x4+C$!|rC`yC&-Avs!0sz(x%JBzKI7Ml&H~n$X0*~9=B{xTfKQeG9GjN zZ#docH`m*MFsycLtOrbA*SO737X`SYh!b;Z?1&jAY4!?Q`wF1~N*VT&%j8^@9v=2m zr78w>$#1Tv1vBecN6(JykjSRsTe`)_b=RX+p^mTDM^LQ? zt*mx=1T0lsA8=!s-R{?X4O7KP+?Uh`iebU61!E{)GVdjImao>36U5ag&uY{ zGLzm1xIMQU{NMbZ{AVr)N|0{_`z+#N``n-rUL=oKI`S$sryz)W0fL3U{D%eMx2Vyr03&~F+iv9g`q zmv^|jf#1*AiY*r8qsRUUJ-dMl0)73MVetnO)$jeCo$_8LXbf%w=hi;0dfNJ;Am9na zy*l0qo|=|`PBW=OrGT=kj};IvoOe*4C$qlMY#z{UzgMsJSgD{!gHtm9D`-D&v2%P_ zuDGhg!UIGIbbh7kbp{QhJAnq#2?pQjkRSk^!M<64%R8~B`eoLI?tVRgEvDnkEJ&@L zkEm3Yq2n*vpYtIONtOI$^2&SHbSX(!9ycrPNC(81RSEd!FVd(No~59opT0sS-}!za zCy}^cH$HLO?GjyXcZI?f0Vg}4jv&3UNx2`J{0`9H?Eq*jwG>GmTaQ^4BWD3tYc)&p z;&EzR@|u+(P2y&~N`b(=YufELw&4tDH9PPFG^rdODCPNz*C7?##`QMgja4!vvXA6^ z;=b+}IUaprZPsKF6lpT5hHLgxNwn45cH+)ZVW}urvj;5T$E#=CLE^XgT~Jr&_d)Iq zNc6>h-}teG;K#mWzYoCxVjpMLmE1`0bDj7(vI>fT@lJ$518;_ZTn}h1xmYpj*6l8= z4!H63M5{-N(>iOV^eX;U&ZFw1tYDrXG`hQCWU}i4%Uf*R_Xa0mJu;fvKU~Ds%h_$8 zER=vVcC%GHE`?S@Uz0wRIgN{k5w%25PLAjwLyMr_iv%yoBg7p5O)pNPl1>0+J3={< zooo+EAz=0>j1)m_@FWH~&Y*BT#CsR1+PalIWuEM54rTe-=%RqU0=LPIJR?{W3$$Nn znbpDc*wmrup!^B91YiePlPmfe&~j=+kiK;0_U50F^sGr#`$Zl=Y|gf#&n{7@R1lFv ztPtyL!ULD0eoL_?^plI}i!=xddPf5mxqIO8&>B{ngkKK4Owzy9J`wH0NKk-PBGCI> z5+&&7O5Rn*lQ6eq06;-&p{W)haL-~0iJv#&S9kWc4@^XtTemP*58_qlnBFFWs7-zS zD>ed=9}BlEO7x_;3I~T|?!tOJp$+Hu5Q1Dfv7d)SsRuyKI8jHRYxL3WI_u8_mp4tn zSB@VL#pC8p*mLHNH|MDjoYXHg5L86f_&a51pF$TNbGmMT?*+s@QarsszL@saEc7~c zdwbCF=^MDXxS3o`_=64O#Jtbi?Q+tr``0XfxP!i}B;t7IQpDa4XP^eFAOj=uCA0^Z zzHuI%x2c&$EX{mO>RFi7V>|R@-=jpK7us+KF#2(_a>ngw4^7o~hjT@y%kt2mTg4L9 zfRpn!XwmObfv?%RW61q+J$dbP)V}$Fss8GX8*gFKl<|6VJYXjPqbvAux_;e(lk>8; zwJV`EX8MimKD2AVu7cpWHHP#$ndo3?f#&pSO#OZQ!r|G))gTk}yPcAb__$-ATCQ)m z?!kEK1o`UtpCv_~YoJfjJ9;WZh?{z!p59&B*|PJ2m@^^FOaEZ#^1HonfA8M7F5CD( z|Bqvv*#@rnbHM)p24%r=A=_fmlBYs6lERSnrUp=%M^{hJ388WR?)}ogZv>@d{zvPQ zuT$0nouzH(u{ zT1@ce>s|NJ{@L}~QJh6Tj55+swT5gWBJxK`?Y<@S3X;B&0S+?mYyptNT)%f7#*( zQ2hdlE-t^!@y%)ZnyMGvaSuK0(UK_Mz>&afwx&k(CDb8EHekLPs%pqBi;7^3%qx|N-8Us%k|qRCAtR#c`JeX>SH_BvU6W~mYJWT}U% z+upZ)PqsYa{9I=0zyPz)yOLF9z_{L+WWyH(pLdAZu|6g4kFKZ#NrTaecb>7nE1V}% z2(Dv^*^~4@e9ca$oBnlcANS@K4zFXSTU#m@?1Z9{Q)NC zph3{ri_jGmt*+BfxXLr?NqI*p@Kn~ zm&T^RSibmJd|o3aKZZhS8k6R1BV&tNh0;+|ZgaZObWYhVsPl`2%2ro5iLxi*2TCA-BOH^LE#bY~ z`)WP0K!hjbfX0L&A2+lcq^ARKGned=toGbv{>>rU;Z^{M zzO@T30g@{3nD`4Qx+#SbUmHEq#_;Gi30Y&DvGp!*vi2vVA!k$v+iycpY+a^LvVSUZ z`s2<|A4N*@u!#$cuHts-Drcfe{DxnG>LVHEGNjG|Ss)+Fpbo2JSsVR}c+Ojzi=KpD z+VD{FPB&U_!oG(OG&KYj;qyl4frSF0xVlo0_53<7yKR4e0tIrN|w*eER zu#lUp0ng{OAQ{G=x>h9jqlG3rgj1sJ@ad%iYdcIvrv6`oAtOVEgW#Ipxj&%52DXW3 z@n1+)Lf5-W+SMXI&)o-syjuFnod=Vi3^HRDUw1(G1Cf}$U4>gWLXMBn0#bmF4_KiQ z(eJ){ar$u5Uj@~N$sWIb3kC|-SR2;jf1>4nfWXYp?A-r_Q09j7 z2Xe7CwO#pK-CfD_m!y-QC?ys0A8l{eG{RNlM@NenpvzXc%lu1ss&$kUriV_^J!Xow z^ewRrJV;s{cI?kAty80?;S!^dbnGF^X4dw7z;&n$K+3oM#N^P-hytCvC(|KqHhz@l zJNY#C=}SFbOns&DFlrZR2#!M653SM>n?SM}S}xEvz=p~{ZaS0Z{C&gGpIb_j7}@9s z?h3+zVej4j&<17_Fc%KWy(DeO67dl)wvW2G&03S7x?tL)8QXtWVyDov^@B5+Bxf)v z6$FhlxOgaaN>nMt#jd`*!r;wSt)n|ZkptCf&SO++QxVsdheu&b?k6Me)=tl{F=MuDYmfB(=QvRP_C8s2EV{L>)xaI)7?kd`yf6aQTiW=~e1V zF3js+$GA|5nzW-=BCT^SOh~z>jAevhy*ghm0F-Bw_RGmh0C6mRv^~@ID>Y}7pGc)f z|Hz3e-rBQa!rPH_g+cP{TaSRCS0{VOUgKeXwEcDnXm+PVJ6Ax>@iEVzhOtlc$hJt! zqC){~CZpNZ(&X4{{ZTHf*Xo7Y%K3TVvz#Y;C9Yd+r*F%RXRJqm`=wJpA;pkW&q#W$?L3pO&jhzp-906b4Ilfzj+YjwuaYeAQj=?QTBJ25R z=abfq&F@?!94zNeh=PxxhXvbIYi#1gH0CDXcG2xKzsEh^{-ASCTri0^0*nOQClZ}H zv(ajbl}0y-LHy_UP;KqDnq*a8h5Z!;U0p}tYysPQwvHLQ*D<@llRd|GzaKW6X8CWl z-AAa9=&mEb10zk3OPj5%wbSgxTM1jGCerRHX;jdK0N^adkz?;(wHjn~@l*rO$*2`|R$SQN&(d(R5 zIkpxJe934kGOY?(3@dTkZ_F>nm`k)f+G)gb%| zy-D3QGAFFNgOX{ExU&-PLVs(V$t+QwN!&P+ZM>dx6V|_q{_xA{)42OW+mSM$zfvA) z?~bXjSBwqkPXBvpSwO}NF4FY%WB4LR{XXLK!DE&}j)}%_l+t)Tq9%H&KLNq=B|&LY z)g-uryjW|i^m}tSisdyKZy#}u;nZU1L`(Fff1T1tPl*e-3?xRt@6tRWfnu|HpVDFN_>`RB4{>JB zcKl5SUx7IJnmqayxoOOc)5b$Iy1Ci5UE7w1su)^3s$RrRbe_nzGt1l1j1R#>E$c~aitL4k@m(sf2kTYEbXYIit;QTkd})L9-m1Tm(@OJ#H^M3LuR6f2m4rJj z0;O0EDA64!9y}AJV128AQk4Mq<|Q;X*KF#)rLom_wfeH^Xk^Wbsk#9f(j;_@%XX;W zXmYrd2N~R}MRm{lzU1;BKIo&vLPLqla+oqbo(A|qyjcgpk^>LJIhFDYk?daHzL{YF} z_aZwnGiz{v*z?S}3Syq?cmI7kJC}N!bZlMz2M=QuR)e=CC*g%Rx?tB$Q)AEeeN192 zN(rXQcKzHpkH%#MSNQne9+mL%%A^UpTcgM!x`wH8@uCS>g{s3pqy}fM`6sW&r^%R` zwb9x$R0XwumBnA&b6vst<<}^kGEQmF9xG+EN7y6B6)Jl2=TBkf&aih}H2m#2gBmJP zhu&8cO4IUwnxVq*VKd5a^KNL2x$l5nyXc7K@BmWXcRB{C$Xk0+mAdy8Mbo#Zc*o}_ zSxen}B4+mo&GG4+AYw=WtmxCOOq~GRY&YnC^&nG$V@SFE-THlPWjka zV+mNj1_J0S$^Zon=s|TA6+TgOn$Mq;eW}h7A)>NosWRfJ7+8~IxVn&RF875AGbVrc zPtUMjm6Xe@!UPv&A$g@>s07Af58$>~BPfN1UW!%6EnHGaz9xOhu(7|)udmDC%RY@} zGy8j@_Hv*NrXOacI?KP%_2t8kCivI8sEN~}e@r&r zP{c-+PN3yR707;yjws$^l`jcsIxGQ>!{}To{GB@A3)%0FYtei>1z|;XfmxPLq9d+7 zfmGM~E9`svj}tQ;OXmX1%8~@l%;dRp#LXz{?i2GW)v&lx7{L#djuEiP!5%Ko!hH0A z+}4o;vGNo+RE&x;*&i7(!Y+iyeVNr^vZ>qmr4cPTw@$&kjk3?8>;7Z`RZPV5T{v`{ zc7Yi)B)q;$Pxx6MvFkVkCb=vd6F+09Nm1cQsIlo(5R6GYXMD=6}s4)h!elcS0d?~V$2SK+E;JiU=MO$40to~1vd4)#CKLQ=g+|y{#snYI;O3G#X3F?)VS9k z#q_qu_A^EkYPD!am}EE5)7vd(BbK8bJCGLh?yQ<%`vRJ2sDcRq%`OCiBmda|T%RpF z(KpISsf@Q6HME!e)>f}inv?i{fq^QNW2G=J#hz*@(|HpDgJomdGJ{&N7y1PHMf`bI z)_Yn%F4%^V$+XTqxqqGFw8l{mnO`@z7A%iRugKLUM>gt}^aLu>8Xx%kY4n++F>odG z#tIm+FI0S!n5w}`$j%i0I}NkQt;300eSNj6dZv{oZSb?B6vs{kPo+o{X}g@+%MQI5 zC;E?l+@Ak42HbjQyt@nk|a5 zZDsL%!f$&R9x+ElaLtn;ZA!15c6=Ij&Gkr?fIWgE@M^#S0#@h2DC8=c2Os6``bZgV zF!JX|tbupUt;e0PlR|~Bn{eV>29QLA?L`H+$3a0NHGx{=ynKvDBe9qgg_65kxqj2E z;5?KyGnpYVPs%41iNerA;BYRklQKG|KroVO+CM3;`{O9%uI=YdyxCs`k+In%qP08e zi=m@V`AH;Wrk#UylWgq1kltk*^1%wg@cv6kvegzPe1bZM35TwD)VSrtGoTP-KPPyi zXdktZ)KE9S56by=QFWssql7t9OyuNTH#kx@y>hlp{CP^;(Z2pb!q)Q*Bg6|j(QumB z@4*#dHk^>LT<2NZy7;XcXjY&9t%$nEp2IL1*m4Gn5eBc<(wg_*qQs*&XYGU)TNg=v z@Ps_J6k$Ostb(t&wWwTYWSkX6Z$btK`(HxxCmeg`preES`o z0a>e&R9)b`n7qPF%-hV#I8l(Est|$JcyD!q@u3VjF2YV6pv-F#CPBgCLCz z+X_!OyAM&Y;|0wf+{nW^6`BpshY6XAuiu8SMQ=*5`?cwN(>I3?-1taBku07<9serO3KD66-`zlj=Z#+Ut^CT)M36a%k(mh{QzhO)PzW8VO@RW; zNY79hV3HX&XH3^6Epw^OMYa`f)+9}ByoF!POO&P=@fO$SRMb$NC~tmHMNzv^#hiS! zuOOn3E>-id*ziQvIH$rueA$JXd>rh~0Gqep#7wHJsA$1(?(>{73Bc@M%exH3^+M%b z!W1#5JaEHa{niT;juzhVINM_>1W`NPWqNrGT~tWD9o=*6hOJ&-X<6hsGb{E}AJapJ z8vVQdY zE;*z$B3)Jn*Kf4U0?7h^&&rY&##cplWCy4egWQUWVk!Nz1x>ER{-~E|G<=F|w)0sn z`GO5tN5;?zM`GLy3AXjv3F&02&*%W+t2%jc>m5qiAb~ZrA)d*JKSKTSl*&SWg*<^j zs{_AFjVcdgMctX~x_^K*e0yd2m~HYn=6y63aD{pf?TG4KIwL=_k*K6B@S2HT*ATW~ z#Ceto3qt<_`L-_h6KxpfJg=}>Z)%na8)&yEY@vxnY7DNPyryH--OI(PNzk-^IWpoo zY+*qRsi9VpGc4D7w)td>y0C3;=go_8qm43w6i4j)QR2Ay#nspo5f=4f@Y}V$pwxMaT>Uv?@~>j`8@&puF)OQcD(BWvo4`pgNG2xbsFdlck_n>ai+kpPA-~N9 zvpXk9ahBIHM^l@q*j`n1&cKA2sZXdj5&s4^twDuoBJS1BeONTR)rdaY<&Pdce!yiu zaqA{!fo^)eltfP45*x*&?Zc@vjKsT|2`%KlHmTk1cgQ!4E zr{YCvcKs=)MrpoJ+1K6Y?F*}si;<{J&ss1G4cBX&EdBc_8WX9 zftl!AEs}qQMx8xzaI&{Zjh|5yQa5OPy33)oOpGUglnTigmC4o*>|FHx`rNK>RQ}Tq z?f1>sm7r#v1ts+4Q|V)v6%X3wuTy;6^&);A(!#^I(dobY!KwC%aBwPgk5Nd`RRr~h z;zSCCYDGwdWM!j|1eVM~4G+M`*ga4Tx+AgH+odA2LZJwf#2s_Y{ycj+kD(Q3h%vYd z40y7t&?N5^S;%#Pls*q^pS$HIc?i?`z;J; z-jQCN0kx#a2p(~^-~kIZ#qF=VTdO_BoDX9Url2aH9mHwu<=6RJnhI3i{U-}c+T$)F zvs*p*Qoq@+%C1#}GE;kIdSCOtx^jZlZ8&P23mtn=v>ZM`Wxl%rxv}x50SQj(t{I)=avykD2%60& z--LMX`9(x*9;%2eo>JtZ9`wj0 zq(kj0tYMyBDI1F)obLjAgcvz^X*K#UAFLWED0+Yw`S4idGJMADz>Qs<)yn%YT{?FK>`9Gb<0`xX$G6@N*Ot_$Q`3Jr>z<) zCe%(-0|qu?k)@)IQNEe%)HrkbNVfR%I>iZPd2H&v!d64p*E|&tXBh%_(oM!J1(R4N z^r8hFHBy_6Lv4p0lG9e=&mV2GT8b)OGYZQZWEsqL3Y*P=k_30@7r6izf!MKlP@Fj| zd+60!nx?W4SUkQbq^Xr%X(@1z{gtoyMUL$lyTyGlDVFN_pfyU0|04>6uKj*SG_Z(L zrMfyjOU%mJy6CUzub=Xu1Z_}gA#ncJFHzrK%`?RcI24MBevve@;8#ik+i_)x%}aF*7os6*W%h_}RrfcIG0Q+Yg18!;nrT`E)sWxyLKK*#II@EN5% zt>C7&v1cb2G*FSr@AJZK+tj(n00o*Ff9hOpZYx$^yTVZ|p6?9`IK|jT&B?fG2MG@d zG){oY#Tbh0oUuoQP>e(_uE^yTf7j~iV*=lWa> zFg8^L7h-IjWA^n*x2!yOaFD5Oj*n3Q%mM;&hd9z;R3Xi&V#31n`meP6?d8TeC%^nF zJ4GT(@kLvam$bU(caazCK5-M(7b+WCOsc_UyB0s0=ovNgep%YZ*vIZKwS<`j+J4hz zfV6|E($y#~tN;rhB>uYP4eRgy*Wr3`IbAP09Ak@ND`Qf=P@b8oz#b=`>0Q&58Z&94 zJXU#d8x$K9=Ck|#Xhb%Z6phAhNrhF05%lU9($FMoWkW^wNE5f7Wyr}i23=%W$g8ue z^(3g87Usr_A}B=TLGU_?MbA;uVyQckEvf*;3o70SES)PAvXxD}!x9huJvB*!O=8`1 z^+W}Q{s0*97bh3&k7& zr_%yUV`RI1GAi3+y~d?G&EKj0YjPe^V=+xv(;L>wiBAw*)*ZE^I!ZZoY$M{_wA1aE zEKX0)0TC(=sfoOTPD|q&Kmp$)#T6152qtHcS3!)+V~;DW>WqAF`DfsS&Oh>P5PzOU z2tQlL%B0fzX616~3o=?}^Cd(QH*ZAqIeig-G4KhYS%U|Vz2JCi z%=(mzfR#lP5qcoGFDHXVcGY?bai>njJ&Bu5-l8ZaB>EFuUywHfJ#TnpOz^|;>D}*b z7e;V*r3`4)YG9yRu0=uz>c4Cf!_Ei*EmIW(9&5u9bX4YSLhJ}!^)w6A=@XH~6@b2r zc~WwnU16=AOEG4Y&X9*^hJ3o7JbZY?E*tY#bnZd&1dggFqgqQgt6v$f z$97aio~*2<4}sWRWgHq365KCRO9h!;XXLnQcb-3k81~LAS=+YsoY+tj)IDiRrkZas z0e}U5tdE+M>S+CE%dqVHfC<49i2T*}!Xsh07MhtXICk`CKpQXL5+0R$iz05*yTJwv z`8FPvYGWuojIx>}?PiQBOa}}stgsnAs(?&-B&Z6_TKtgJZnIM0^<+wBh&0Qp>#Tx> z)O0XXWoJoX33JT`l+4BM?GkAMt&`5#PS+J0{c5!uM4BLSU~zeWyw$ng5QP8us(xPs zh=7L5`bOI#4E)K^{=(G9Ob|}RBI#3WkPUqyK*eO!Tqlfv1NBR+jZ6j~oR8%L(!k)E z^@IJP4*8a}*Xuy@dUBfXiTS;7qcF3mr3`~fvCp=Hh{UpJ_gU|rL`Rnor&=s|t%KEa zg8Un4Xqa51&Syy5Rvw<4y+JDxn+&G^+X0cJw|7@<(WzIUYFfMk`Jb9fJEY3JIPo%l!-mY=PZs zk!|T(nevs&xtVIh*GsW_+sUQjo6mJf7r%mZcH0 zd{DrhWLZM``M&3=SIQ_TQ1Qr2^y*<|TuweSPZbI`X(BEgcUcQbFB~o^C7eFo|A(*& z>%W%P+tzyDkYUX;-5=boP>ZpAS59V#nC94BpEtgA*QGzAW4$5Em~)dhI?{%O(vCF( zOOY~6$y5>(Ke|wN4GfT09Nqt{27-d^_#QW%(_UFc^ihQ4kJPfmAN4lX5U-m_T$~Bd zu3L=ma+NUZZoF@Ky6dWnze*aHkT0mxRm`dSA10uRD^T`&>XbFCpK60mIapPlF|`e3 z!#2UYB}A7TXBoZB^qh1^igQ)$L3UUMjL!Kg95~8BSO4MYdyX8#U=N96R_JwnLtNdo zjYpKH=ZF;}jTMR}@>Qn6!Oy3tP9`6+C7?GM`4UU|ki#rk=e6EKj1ozIvU*o`vUN?g zunSM@`Z6{?(=ECaIlvR;4CJ#*E(>o|sRfvcV-!kuxqDo&ue;J)<`fs&kDHfte5qOX zE^lgrp-vmeEcU~h$4}et%DhHfN4(nys#un9oZ_D=t)EsPpBctq>~M#~er_}Yut8gE zz;;IJ7%JAyYwS?KBalrZt0SY(Wp?!QQQP)&jU>e0U~V4nnG2(UBuK_?O7L&AP<YDdFLx1>=qX@b3mQneO0|24~m|V_RP{kVZP;2ET}~hf|)CFfsY(5pRUfIo6Dc1 zQ)qdBj{^%KY?=BIPJXI*m4%!#9`M@;sj;F7pe9!I6&%bzb;c;!FzVvwmC2aI8KcbL z-8tv=D1BjNog4*$cKjGVkYk^dyrpu2_Di`Iulc#u^7By#3_+uYNdpbpT0T#m1wyr# z89X;>W9SV;tEYJTqR3pe1AIQkKK>TkgUoq9$S^TX8Zj^GGO=aX8eQQXWAGNFJFj+U zqyp)E08b_5N;ZXx(}KLZX6(RJqyqo+(ec&O_1N{Wx1y1`F*K8Y+R|8!d<~)KxZVTTay4?&Kaf^0-v7U!d-x5Jn$x0v~6}_^bJ@ zZ_TD29`6pPLeTMXIzn3=+=We6IhvyD(w;z!Us*PPb0si6yKir~q1?3oMyUq0v}BJ$ zsC~JHbQ(@@^hnCLAzR#>gSSZ*f(+J7E7;LvmTz>ETpH3$QrC`TE)*M@n%Rin(Tc1YAKBtsRTb9*-3%2!9u~ zw7n`I?#GHDtx?KMvH44Fqm?<_`ZAlV^;zMtd-3@pT~aoB<*fu2)=1hB_KDXj0oGOG;3sCU4EW4S?0xm&)Z8 z#i%;PhE_aRTZ6(KE|+a&k+SO;kSz%&P!w+%KEd3BvK-YN#{dW-|GChwTo${{YcO?4 zOt1ms&@69m+Um4TRQ>DdGU@xlIX`nFgh5}QclpQmao=--emr(D&%DSHG;v4nubvz{ z!Bl*RZzE5|o1Adg>lt$-!B4@ib-c$O6coy(*Je+!QmY>g+BXMxr@!*Df8BpgI^WaC zC0Td$)S1-|T<*xwM=PVhy4x@B=s58`W)yAlCUCt9selbMOM28Sa_E-b1q274@iyCDkbeX(X}#CDW`O2W`;(+k3f zPK&A+MbwQba$caRNm~uIcRPhzvnF`Un>Lf7cg13d+hRa~dYfR#FI7V(H2Hw$yj%kQ z2r&`R{UQT9-P+{47{Q?UF=qthg4uxs=F}uvPlp-08A7SZC}u)+;o7U@y_Z|BQ{R^w zyQD^{fdLVPFjD(95eF8>icW&_oxMCp3+WvTp)`e6RGDJ>=#W&fKsBZ#KC-m zoq?B5IMu0;C@ae*dWm8_B;XKH&Ew}am)JBE2lA5jB19~>#wC8w?HT#6#sNKpmsvl{ zWzmxx_q`2wAH4jNH^@AmYqe)~PGm&!>$k((xR?={zxCZK^Ygn>gX-|zkv< z{q3m|JnxHh#yVZk>s`+^@CAIZiTs`lk63akzj|IWv_){#Ez6O{N^Zp`-|osMwR2-N zJtAHRw7oh{mHXEMOAQ_?;&|i=o0oo(=T(cu|6nEkT20CDTbEN*{NIr7KkC(h2Z0YGBlu3y(OP=VhUyrRA-iZi3EfTw zXDvegOo_IqljNOA0oomZRZlkFsBfZ4B@BJP97wX|g)q`raDyNpXnVr`!(qASBO|3B zq2tM>O)WiO5$eutrZ>c~T%_~+OlT~^!bYlXD3s0FqQ(*5XyN&J^HvsAV4)!+fGX-2 zixy))&Z-_Y*N+nHDDS<2VPy{`TOg|n)`u*%4qHA1O7y>DU zX^u<$UJddMxD+s@>?In@BT0o(uj$W{vK}{d^=31aW}LKtc5RdT;#7%${!74CNwQj- z^!K)(Ve*gBpz4^F{k|N6P&VA1A#Lo0`kl3=I9Mfckooens7RC(w+B}COlos%e91eKQx9u_*Z z(zM#qLVUtWz9NYZ%_|e#dw(OE8vI(TQEoNu9D_pc&n+l{Pb6M#Z2&pmg8}N!MRPrp zR-n8~vuUV$WkuVAxY8gZ%9 zif$1tS?g^V($olY*LbVq*Vw%f+XU$H;PQ6r%6s+asfjCxFJ|u1kMLjB1RY{eOOuM+ z3Ow8u)+S&K+{4zH#~j@f0`vV-=Q7}Q*L0CTIk!C^gpOKVvVA(X2ZEdT_h_+M^Y9b9^m&28xpX4>h@iZ4$)s$Hzj=@X3|3XGRyX}$co*zDJWysrJ zhxmOB>}1IMbx11Rr?H|vrQ&c#t&;9V3rEHNhf)pWT{BUhHAaf+=zJK0w!hRq86nx5 zI=`-C-+_c!ElED-vUphTOJqoap>8;|!tZ?8u`gdh1GcyX7pd&-fZY}U$4?TcTL|jv zcC^d)6S$m@dthX8YD1<~K|o_EA>iQsAaQ3fGbU^~ZDe)-y2SN92WQ&EOnw#3Co%1u zqa~aoC{AqIY{AKnrJ{b`xx7|heT#C0iw@`@_W5}&DyBd%FpMRr!C#B1wbDQH7>U6e zUCcnp!10l8fzo@Rfd6*KLB8XyDMCclA&9^s4$|F7NOw2SJq0>X0gde@4Uu;#@sr^2vEyF&th$ZW>SWvDtLX7jgbEIyxQbKty{3(Uh&E~6hn$UfWn*VET+t+uni zPWnW(!gHj1Y_Eax`S9oV@5qARj$Upp3Z@H|Hl$vgt>dh3PC1d?0HA=!fk3^%;m2@c z`S;*#FGH$g#5FW3jvzwR&4KKXx*v**)4>RYOiGtv)Uq?xR`!Z4BX7)%WL54pU%UO7 zZMVEfBgFkCb{Lp2iL)4GkX|b#fg5)P zk*aTB((5YVj^3^ZN_?@h^1xT+)n}(&aSg!_`NiUq2lEK*8%r|mk-kO;T-I!Not%-} z?{p-X6lwTA7Rw20++#U$8-DaNQl#u}bW!+D2_S{kbv^Cx+$ z3arET=31VvqBo59{?rm@9atm$*k5EZwr`f~dMcmI*p@ewg3QN2lm1a}RwHx$$a}7` z{Fsor_t)(u(sxu;_?Zft7D$PRBzg0st>iIbCxui9oM~IKrLC+IZqTC_nhy98L*Z(3Ug`9zpUK{=c9VWke??oI3H$2}2P;uH=}5a7 za%q`MfOiWqvQ^#>T8K!t9RJqrLUo@tsx(}Rri*L0xk~ABf*VE$?Ds#vy-DHcwqZ0K zboH;aB)JU#t&l4ma&-^Z-QB;bnI8j+26;;@{Nhl|gPB|Y!)L45xP6jUnlxg!PP>U~ zy2RQpF7uN6w`OuHwmPIu^DzNB3LYjv@cRAoAgK*0EX$1-4AwJxsHS=T2nq`b~kP>_+K#WA41JkmFe*siEe zhQfvP&>_Y?tzjd;ktz{;uI*;kVAC<-p(@W$tNoBsMHgG*EA%n7X&Q}I_Q={68mv`= z=b08PubqXURWal9v{lH|OMl_2?K$sWv2hsVuNupwIsW$J=$F?UD_70uzOwiwh?zB( zES?LuKTe>_Cdb6gM3~r?pFM>DNpwR+CV9}OizvQ!HD#FdrV%%s&cW8{2vsLmkw~&MbhTS$L^0s>zL7)=23rS$_{&$wvn)1)OtUbF1QFZE!cf z*GmsN7WFfc|7XI1^%8YCM7V%|mdY2k$}LOu4a*Gy*$jK;%9kBZ6FD9I!*c}8siDoa zqoXO!@pGaN*nx}E<7~57O3c63PF!HFc=Cb*&P#q;B#)gLjImbjC6z4R~VF=8?b(`a2(vA0wK4 z>D^apoIO2fZ+oVP;*%r^dsh*Bq$hc9q&+3HoFAQxS~fJ{uO-GnV2+nhZ_=Kq%57e6 z12LZlb`B;MHEM^YVsN%~a|(p6&B^iRK5eNoga5xd8aUMqUZ~hGF^mgLkxR?r{bo+( z?#%wqLZZJ{p;@j|vp;L66yF`HaqG~wRp3;#Rf^sDS|lOM)vbThhoZD8SG!fb;syru zJVaBl9IAZ(;4@oB9bAe*$K-u1uoR$@yprUM!U(r`PdAG>{f(Yt3ZKBY^Vhc-%%;1N z@gXh$N`OgNcv*e_?|m1V;G!kC-!D&8v~e%z%rV=z8``g|?=p^-OZ+sV&IN0?uK{!m8uQv(jQ45Jiv%D@1gWioNf zE#bAF5j!PSQIn3Q5>BO>B=P$fF+Ew~MbKZz7_0C%Q!%UTcKj@M2ESXpFI)ud9QUQf z$dO&SxH>S!ZbhlF)hr&FO`AX(f0g*5<&-%~(w}i8Gc?%d9kdo|7S-CUue!};%bzUK zj@yfmMV9*hIgL=o|BIKQCK~2z#t$~vz{wE!!T^32uo(d>79kW4Mlp_trkgWzi$g4a zVR4@G>enXV9#6*6( zm3MVXj+-WqGE8MuNks)y=kv{Shl^%^etKISSi|T%?JkWTyM(sj03ijDh^`6NUs~G# z?V-MCk9NssB6U9=D{V0THE>-}V<<|a#ap$c7y`utfce>sczi)vy!&EV7EdBDM@qq& z(Cr?JzUZzj^N7SpkR@j?SK^Mw!Ibmufd4#%+ENOjxW`;5q>Wn@M~c%>%5+!1bsACQ zDkOvDoGCNrCs!j?G9BZDg?p!r(3T)ecS&LjMo$K&@CIFf;=Eazbie8>7RNQ1)Nhde8Vnw02zp)9x}h4M#RxB5G-`2JM#^78Qm0R| zY@RB3ADO*wdhx9AY_gzdoupxafCrPUoDHwRke|{$&RcVR#d>kn>CjlY=bVMNS%XC# zoO4-J-_HX-E;KFKC0=b|JGzKo$;hX3`NQ>y>_4d>TGG=%N^sFx%wCf}RTHgEdLPe3 zOBmY2Q$Z-WGQaKW!^*ys_?yk(bOa`tKq4%NR~|^fnCnT>zH9grI)ILF`vK6pt?eCU z>3!nLyR_nPQSLAf@k{CypcV0?67i%bFFY&Gw|ND?t1tG&oA3fX1;I>{ni*IGQc{ut zl%L<9;4KRMAS(ys(}`v%7Js|hAX~KKH>k>oFnWmQ?s*N&d zFVE|s_i=ABRu)d}@n`&!JP?Hdb}#njoi6Wt*>_PC&e_(~dVE4Qs9JCiqqGFvP$m|k zGCUd2v3_=R(XwAWFYC{%>;3&Pgy(aHPP4_y@rccGuI(j6u9YXaX0Jv^8b%!@0S0gR zsS76mZk$*Di ztjnHbv6w^@SU^Vy?(HuL)s`q|As*b4yMC*?cFeDV?CFE%YSifjyZ8uEaZsqM12ZD9 zqvbPx{CWM4rw|-m;_BShI;fi@l;P%*`fBj8Sx;j|pF4^z;KZZzb_$p1VPsn0f8OG( zx%yYq=`*?Z5O)Q#f*&hD;hO7FwldQMj~RV~Vh>{EW)m?#lYXjp<_5N*R-kDsHGW=rDUI?tfSW0!mcG zjX4e&MupW5S{s+c5Y!DtIheJY%);NeE)gU|C^SijExNGSepc<0WVe;#3NUx4pniW_ zV0DMB(%nAaa@*i$iL3Fp!AQ9bMrP^#-$0PJ?>?WJq7at|N0Ku7!vP7)Gx(=Tt!jxu zDE9_$!Fxd;%6dXjSRxBQb(XN^ACWy3~0gkTy zLP)<=;+04<^t0M%yLVaYEWrPdaEzNAw2kkfL& za#(a!`SRte4EJW~kwV}F!9t;RIWHuRSdPC469TavtmM=O+?y)0p@1Kpx}^H%CTfOqd2xBJtY5@%DC>-=vZU zBFyjbra13|a-2eAZ707u2Kcx(%+ifFV1qt!3)!i7)- z2T_2$JM8Py6^i3PuxJaKF%@w1w=4%8s!EJ@Z#+D2oHIC7?R6*a;wV4vg>!ka89x`o zaue4Z34r8$z`5joJ!Pjz(X!Qht3k(s_x$V>uMF9D8``riz6jkm%&hP5A7c&;SmqW- z_%&A7(CjOGzN9Bht=4V6H~3hkh~7h4O`| zzL-f;3J06mJ2E*~|I+sOJ0}|bYvA>PwbyF}6ng9M{^IV(-27sHyR%4LZGgcXK#zU* z>vI&HdBi#ixODud!L@`gYq;-ICp5+7kFH1L89jq6EG}v@EM;iV)k4m7c-w2t>xBc@ za9#Cw0>;H|^Siq##wDCoQOl8(RYYrpv-q66d&k1WRM$;(Jz3M+zmN3UdF0LHXW$+h zwb(DhnSqRyXmMb!pmZdxgrAMc#-wY4l2g^W@0*Mc#ci0gE%h}k+8kmAML?N=Vw zMBS@;p=wx0K%*Y*p?$wWGJNU!3JbPc=$kOyo`9|Q{Lg9E>?sF?pT!vRi!~}-00u>| zfa^mB?+1f})Ym!q1V5sP$LWC`y^((K4hH@?bePn5v)`J%gmiqa)=-0$VA5;82&HZ< zgl0XEXrHNtp(6Fr$i%M5|MP~piQQQ70ej(#PCe?sgBTh2z(H>P<*kaQ{H#t$g>Q_j zV+Vn+Xg*<#`LpF?rwp~RRQ2aZbdzqA8xuL*i~lYB({LV=cm$9nwn(;r!7Abyw{IZ2E-8Csl`j%Sxm2Q{lgE2?~6>u5I@M_VcVc{ zy|ol)hk1!+T>GO4Hyf1tuI^CtQ^6o9tDRo!sG;5h$zt?%!L?w9I4Ckf^r+H-oU$U5 zei{t$1*Z3K@K6Z+!A~0yMdN%neS~-1E`32iILg_LTyHRK{B>baJOZ7N{m;>2W9`Tw zi*18&nweb6VU9(Zfu=aq`1E_Wk#K>ELA$XgKRe)_OCl1IO5mDn_V$A9hAn@%J+Oy| zuFi3h3iGJaYZA1qZsiUiM&EN=n^-He058yWr>z$+lL%#11rs zq7+Gb9x&FvgV%Fh3t<`5P!z0?Qe8bcd9P9 zw(jm8##Nxj4}DfwF_Jc2CjmJ#FUVADj>*!i?=%Q)@6-_q=oy~^x$C{b86;J!Zlf%c z{+?G~fkLk*@d3e1i%HjL?Jr^K#N9C@u=4wxPf< zCSmiAbidhs>lQsOWI$QZmA<}MU3s214|~yk`>Wd`;2N-W1BgC~j%UQ+L5uf1pFx(v zxtG8z*~>;z;IG_sF>71v-WV_kbxv91R5Lt4x}Wy1ZOu`zL5sXr;=(%SzUk>0n8>q% z2|TMg6sg_4y@?3fjeZ$AeQdp~2SYB+lT$r@deZm%FgvW!8Y#@DxwCau6IJq+U_ifp z$rJlx=enEYrB|NbG(@L&*7C!xQJjQa(s)&8i<3HU+gH6=PPBr8vRXsfN3%rwJ!@Ny zR(%#xy<33jtfX3^6s;*fFiijT?JRH59_0}6z^jN6Ls|E>Ywkd$^sB4bUHIcVN}sPY z&1hjXt&nS(;m)jN3sWl0?)iReO~2Iz{5O1EZ=4*FHzH@$Vip)?3^jVYjK8S<4orH;>U-;pCyVa?|4K9%`Ne zu)$wI8Y+3DKnxv%+o_0LR}nEH`QEp}`Kco3!9TG!w1aHx+IqDU-z~jt)$i4hLqb1N z_8)oBo5S&^Wx`?4{sfYjcjxwXcgkz!E&8wIN*nh8_kGHeLTEG_Im;(W<%_eXkw$d2 zg*xbW79XcF#9VDo5-;E}!Ki@fITF1cYx2mTert#Oo(|+%-t~Goe`1CEnI^{mt*_`G zCmraLC1PtJT!!)?I*z&T4O-eN36LsZRsRHShCEvmr3)J&EcGl8{=h~Ff0LMwH@ zVy{{}5H^B8>3909`f*m$lX+_U1-9k67%8-n9gqi-3LYmKpRrXaR_sU|@n@b1g_2Y! zbt^ekBmBO*s?x++c4xXL9i9O75?ydZ{RkP8?>++(Tko$?cpz9vE3H}+rqw&#h2JAQ zRGHVV6Wj3!1W^`O5uflY`Kkn82OQnkMd1qU$XcEjyEg=0pQoepeERNaLp_qguSqTc z`YKAqWQ($=CHt>Sn!go?bq=WH$Hf$jf%;A0Gb&N_E0<>`rRpQSA<%s{X={gRhFQF! zFMy7S((i0 zNAx)lT_agWGxg(JH}8wzF1t7lcHQ02<3aShSs51pBIzgJnqYjEbcJZ*uY(GCYZ(bD+MhA8OgHG zPc$dcoG!Gsk4;)S2ltO6yC5(bRQA?qd2gVy$WYe_C7sA)NQYa0&Abg+El$I!qQ`1=_yXqqpy{VI;e# zG$sEp3s6*t7``H^od#{gF>wC;w}+<~S&j2hO)=!N&PC-C!B)wcnY!cbR~1C#M!d?t4Y! z=@T|Py~$7M*ZZ{@a(j(Tq)O?7Ht(quktZ;CSN^cRXRFF&&X=-mNR&0HPj7rbX(>Z5 zl!35Sa`Q(QFL&^p=hdJEd0$^2(2hU2)-{C->P+QtmZq)mwIc{L(Q*IY8`GQ&<2R$; z%u84!R@z)Q@>3)Q0sMxq$C9w~L45KDxm@b@%askF3Y|6d+ALLn;fp`=A=+0QhTAD=kIKNK=Vo&E zR7$gghlfu-CjJ|cjLOgFzU#>QA;c~d8ugDGLPE5H(kHKT3p)%~mda#W#{+EwZ~<<* z`Q$2WR|-45=6UlKpYqD!_m@11ip1Vb4>KO6T|NZ>oo=ZTyf z1$5TGXI^B8?fMKEw(##+BEEZFnmlbS210HJx+BS)P9(Y0t8G6B>cjLVI;yC{55Z#y z2)oIP&2ZCJWVY;8WoD}cUD5`OjMYzXs)(^4lFW5rWTg+`F6qzM1p>Z?#qm{4H$uRA;w zw*`482OjFS>+36yiDW=_9lUm1YO+OhQ=22@3~A0fWgGlduOGaC6RxhJoUPLkDzuTp z>~AUC&;UQjtTQ#}BcFsiW0t!eNd_fBR;@yiY;Qryb}i|3{F{fOoFc*W-faXd;}Xj3 zFWK6HfLn1FqN!peShgBub__@nfT$|t2gNhaoao?SA^SaQ3Xq;O4_=}mjd6#Cm%s0c zp3BNOU$Vs9Ef{xjVpM6s*w8s+d_&4V^K@BFOP4|RJXRld|NeRA0M!@~%Tn?%P)`w1 zA7)z>u2WNQU}@-#PE&s3U};l<()SDLI@{LjMNu*+P-c3VeQYco@Of*JFlUll3A(*5 zw^;nA<$3$=*`TPxd%AplB|77et3=w0ij-S^ z-OhNM>ifFlF>m}iL@_{Bl~V{dv+M8QTTpJY;_aid+R;44fx%5V{-$EO`zGpAv2dJN zMxWx>oh5nE!}~M1xPxIELs6~7h0TxcwO&Rtt|JW?9e@tCl+bQFukb!faz1G*( z53{_~otP}R%1VA+C>e!8#7(zRCEK)$tMtSGnE?Hb)(g}iJDUd&JnI4oI5Xex8Dl_* zV(*_yB_I zXd%Z$BtVf+@uJ?nKyK@Sq%&T$Fa-=YO#9R;q0;MK9)@|Z!ZJ$XdhF)?ZnLgx6JKPf z77wWPbFT5_W<|V9*2E^)&t*55t2*e}87JVW147;dh=BvbVbRVM;ay~66@{5y`H0X~ z6;Mc=*FWrbxih+Vd@O5a#Q*~`f|GPeYR$eO_`M)U;Nz&jGN&mrL7j_46H0V)O>nM* z^)?Uh97}Q@()mj} zZrHe!n7agW)A|-(K8xsJA9h@!ql#v^i-Bi>RNgQ_0|NJv&+72)7vO0F=PT4mPOlRn zNlj0qp`R@zEq6vAe6=JD+ut^rw*+Jqt16*~^Pw#cWPIU06O_@6o0bo>FPjk4{E7lp zzk$)zUl^^t`QEiCctH_2NQ1Wgvfae}+q6F_K}f6!6W4N{KB%Je4QYq^usD-56B9wL z>j7C6U(nGzWsD|+=uQmOUy@In4a#4)XAKlt%fs94mzq$4R|869p8`FYh>Wa%vPk}S zouB_((OGpz76e$ba9oWKLdI5%xaxFYTb>(9Kgh0IC~V0+F}Ho7WCAuEkS|EFB+53tiOKc=A{D zGo|AC#GYw50CZigJOYV*85DNQ>0!ryLW)tZmQ9oJW=Al#d#YL^f)WF13Yp%nAXk85 zgQs1YPNc>d9o88Q7?(4T{`=%~``YkzD!y^BB>LCmRjkI3QJZ{ymmX4r>D&EYSO@JG zUQa!(lP;GiYwM3?jO^@MZ(9(2YG@p&fWRAI{Z)dLQ%65(Owg}cW24+vIb870jj~rs z+wQeaMAfoOL-H2Vnk^+VN=lr%M9kTMh|5`PE0s@duQ+7*9o{iB>y>w3?{)d|t`Fh= z$HFac>`I#a21kM`yG_miVxS?4P5dm42iDi(^O5C(;2_r|53!eEI6eL}2%bJ)mg2P; z-8lJiDi;_iVdA}kcOa;-*{7Q5)yqQD*K&}hra~}y0?blNp0>t?pH=tbyB{)b%c+|L& zH<#c7-A(XCg4VFBVBOEa7p*FhM?w>0R@D4MSyBe>a{kIA`bRrJ~RC)klBdqYUx`t-F&%NzGi4&;Nj<*FkhG`zLiPq45M;V^TzSsNQ~!@m4;vo>n||^zFsc5V&_zx=Eq;G< zy#8BKpQ9GUk?za?TQSEx+)Sg-VN=%bN#vvro|NBS($J7J8A_{`Ef~BtnD8OH2tOeU z0=Rg2<%1vMi{e37%@^<@9#i`rk-M{Mv=ot@_|mk_O9LvWM9NPFhrj&T5A;7ON@v;~ zw!~3M@>>bmpU;@-E@HR*aJ~8;zc7fd7mDx|N*}X6c>WRX8m>@F0Tg|kO>8kY^u_L^KI0EWfQNNI}1yNUfzs{h;hS6E%< z`^6d)+~SBd--c|^M5dH`^}43X;ME<`rUi2GR;bAEa~VfP{O@CqI4W^pm;zGXr98%F zilyKaN1O3+@5oDp5qFaZTQRs+6?Fyl`T@I>iEs4+ z<&(3=6)`Lq#^8h_yeOL-zdw0B9m6Z+k-Q%i6T#}xb$O}*{xl=_Qd;;d9Cx$KvTRjn z)U$He#(UxreS?fiDaIcW?+1LPiN{m%*!kp?%V!Cvl!wKF=t~UQ*U;!K9Ru#2&jtdns8WSc$2I! z7^;#1uxEifGB;}RUgMPvltq(_xq&Y}Fk{&4dQ$K0>k|z;`_;4)qVY^LrRyOZ{h7K3 zmw?no_RsPL!aCntYAk$y*~n&+h=K@P|CD~FaMI6+QQ?M_WF_bWR36r;|BU*;gxX088sctL_+&>1r+=-#jmPoZ8?ofv4RyyQ}BR03KhPjez4AO zE@eF&5w=1f`d^zAzO_S!pXt*^fcEs;*sW)~40qcPiE7yJeqy92IW-2ksiuL^x?(-1k|`4_^5MMQdCv%v?lg)@fNny1_TKp&*@diXt} zm0%20t#_}xQ|HT`W_@|g@vj%e5cQO$*Y?f3pHt@rz!z*!o!{e+Q@#XTpT|gWG_QY$ zC(YF&lL&wzYd!sSF!%xwW5yR0Bf)mv_z9W+$xrq%PdxO_PwUYm@Tr@F>{W69j!fkH z#_#Bxy0nLG3uOMUvMx`lR#+0AFl3}&W__kr@f1Qq@v6YTsfyl`2te9Ye#HzkY|WP! zI{6KJTgQs$b>^klJz_`#x#ZxN*>ei<&?nM5%FD?|g*Zr9zyp)$sYsdc1aiNCx2j3t~+_?6Yn+{}Q@T z1_Z@f!%Zx};OU-j!HwS*MO%{)6Zic6oi1kKFQ@$CT{4$woaWQ)*i)MO0~hLI;+FWh z*y2D6+~g2&nYF&)IKCYLH_U>nQ|0ERbUY;N*mZ(Sai({_z(<&2mTbqBBj^Hm+I4Hv z-)8Vkf=%n|4E|=M=BG>?I@w&|tLkH_`$1?{GX!kQ@I^#Sj zlPL#}vu0U_i;!*u+juq(`un?#Ae6ut(Uj=2k>olP#bTQJXuCu8=MF*CB5Rmrer4R0 z2}io&ugy(SpELSfpYsHhLBDaa;DX4!fdhwxp7{ni`JdN*+s}5fgg=Di7G`a(YD~0i zt7aA#we`k{d#%~{On7KucnYHca50}!<2d-Lgv;nD-D)^+aBxju_+?ypFwn-e69pol z9?$Uh1QDiKtDfgE7%ty93VWgUZK*;>o!vvHs3)E;(41 zD72eilL}vpO17+kzl}^CBpr*Tx=uyr^A45s=m%X1zYvQ2-W^yE zDB5hkLdKaa@O!EeU>>Luu62C<^7mX?4zlti61)38ZTJTG?ZT{l5GoNg;k7oM5n^wp zU?B@Ey0}{)n>rWRtlYBkN-#ZLXmr6OKk~=Q_=@yH&TB*RDX8QH?UR}KN>GGda-0b} zI^LW!njZY5wN5KioHl{$moPLtoTX^hyxAMko-9!pT)h+(M@YBBGC#~O0OM(cY=+zA zN04&0%f3na#j;I`>W$3-=&36$x?7-u0lAfc$K%iV)4+@I?B(&4v?YC`+2^8zUG20c zA_8gDzfK-+-xyy0Kz!E4SW@|zH}(^N0X2R&h5+dNZ1;2+0>>=AI*TO9cV^qBA$BWGzzx+GBG+W$@^#d zdSMYi;GN3JMbnk2no|<(@Mi}$Kd8iqX$c+Be1K6o>*Fs#KW(b9PCvSOV~*SS5k|jZ zfrWW9HjGn9$inDWX{#el55s(m!k=)k`&Do%eGu!2L~_U0qtoErnjCr9Qky!L-88bg zEx#)P!+hGWhJ*R@4f7EW-xB7VHUSKi!NO>>f%Dy3FAyM9E*6G^;TI z_h`rG-9dnk@w)C8-&s4oA$)=cPzgt-fd((g+Qbr9y&(qqNRRC!tm0Iv*VC70hvgOw zz$*4W?{^YgJ&>bj z=j$v;LFk1G1~uaA$XT}f`lep z9p(7zrtW9lZ}}Hgh8uBNtEw_d%0H&m^i(x8%Fnb#FN)O|pIOAFZq)`K{9O8+{8201 z2GfV=$7+$1zRUdNVnXEGNy_<96ROrJ{ejSY(4?_Hpr(Bh)6|UzqGen<#;(|(ra+=k zpA4a@s!8!!J#xvIc-M-?n%ASJfFWXr%(V+=;OFQ3*GhuV(J~d~a^kBE7ZC}o;eoM} zrFJ<}*ea>#R>4}N^KF)w#nlpH3)xBp^)6<@ia`wMD=tf1QWCaIk>=6rkNG7*IziPo z!OsE%hCQDNkM@>pe3gK1zM=#G<1}h>?nxy|!_BZn>T37ZwSk}L-zl|?D(lKLygX|l z+dghxk1r^oYHDuY0NiVc5>!deC~U zgo3+<#YqZV_R7HzZ{vkc@S-L%>8HvqZ5tLV_Lq|8MAYBGS+pg}K==@+QJQYioFP~P z!DE%aYHPnICG1lt=G!JB)7L)-7+7^Cbf*)v@jLVq2vU{uJC}Tl$T2~J0+D02$*wFt zW?dCLwZ&f!(!?p6bX;hir5zxoytb4)ZG6aGF09pVhov>&euz3OjSEG56mp7LOTcC$oZad#2ag z3}MiJXq7fPL$Z6Kl_6p|??uSx0WXsMY744T#` zEuUrT2gHvy+H9PXB~eKmI$9*<56(axZ=#){ixhU$V6hO8&Q>OHYvRg`om@GJ#L`Gq zCb9eW`!CDOjw~;jvBMn#u zhErJBw%q*TbVx2N(#0 z?MJ2zw)EPX+&hpH=(tTdVAlCCzqMv~tEc<^IVY5+vg%-M{d8^Fc=q=2^ik+qxv-YX z;Wvg|0XgCRk~wtR_Uq9=tU<p8YG-ecT~}#vYcO5rkmEa4b|AmV5<# zCRRvPo@L^^cvpG1cgW|THgj2d(ZVdw^n|-({uJ;1jt>RS8z+m}^EyNs_!Du$!_5SA zHq7dFHTNOYwyL38`oH?;2{}79Ji7w0P&ZPPDz;M!Q=r1!qh6H)`yEJV(IGm_pfJ|= zP>y^fb}1$T(xZ!5jc8frM^RfrNVA|DIfFzuDUC=V;k-J9)CW6IWAc z@L*#lV!a~52FZNDSJ5lqEvU*I8D?8LCE(wp?zgZnCJFy+3UAQk8qcsnphKR5)_Af( zwQ_fId9z!CPdx&!W~u&XqWyjEP#R~!k1Eo<_AQ>fmBYNgq(k|M*~#!C9{D6wm+$9S zL1RL?Z&nsj-Q8g(QLwrYby_Zt2Z6YFh4sa<^w`^`^UK=b+xR8}tkxGj=pj1N4r`qm zm1>dvN^t7vVKn+TZ{{{YCet&lr)y$G_mE95hFx3e%V5-gP?F+<1u+J0hxwg@7_v( zlkGyxw3x=S+@6V-1WA(G<$dCvP|QWheQx^bn1v-Iv;(*rfV5jO$GtnKi|L*z5c-^T7E?)>e!Xaem+cSW6q&vifFF}X;ciBR^)KE9<;X(y3s=Y#8pxA)VFFl`N|IKt?CbZN!Y%yNiz zrh?j^MZdg$Z`XJ5ldxYeRv6Cz+L;n8S@D&Kj2G&`>$!)%wfMg*K;^IKWqEL@ZiEjQ zT5fBLNGfE~oFB3vxT)xA!?}CByOTS_AG!n)uvl(!07?Tw7M>hGZ%(`o*ue{nwq>i( z_QrivQ`}Tfox!_Mktai=pp_!fxo!SakN2aMtjr>|NlSfG&Gk}#kQ}>Bi*Hl$bm$;k z^;L)lMn(d>y`=_LB^8eXlydTb11FJj%3zg%BX+xxOaaxf_p<3h^+Wf%{tr-IgCYzo zJ_(h#33Me>wjiG}DKY85ShqS~$;R*l{1nqb2P?ujczSyNszW=--yY;EmRYNh)BiX5 zfx2H1JYzRy2KaxUTt2~yL3KsM#-r&m$CsR*t~jT>j^tgR5pJFrZ91P!*J6$iISg{E z=Iyw9l#UUI6c|F;wv5I?n{#Dz^|tK1UWS4bsQqsPMzXz07MTJL=#6K$rNxE&caX|D zRR8wkXlKbW$|8zEi;vH9bIBF7j7BGGC?W(&4*1#F?q1ui2pb7E=~ODIa3;2gA3ycP zR5ICn#)$use1IV*_aWl=VhYjbQAZ?;$2w9!9rW_@Cj`|ZlwN2HJ`H?Yf6!Z-48B+- zF*lamM`1_WZ=R}l^{al+JX#*QTH@OZj0in_~L#o`7KT~@{ zNUZ#mc}aya9E-u_9jaffU5X!)TP(j3Joai~NEWnX_X>TlG_;fh%TfoqwudQ|gecG! z;;5n_ABu{!Z6^o1p)tHpJ09H)5l*zaFznRjBEq=KZI9#C)uP`NbX<3MAjP9oZapVRb^q! zul6(x!eSV|CmMXxbP~E|u>BgkfU+f28t~$3Ts3{wNAZ$q_g3$c!M2ePW%K*2z{ec^ zTv_QbVLHbCM3fM!C?nt^uK10OPdS#E+1Zf$%iU{l-U%FzPdXCK!%I^S{GoE1+k^fS zYWKxG4e{FOVwbJhZ&jGVL2#?)31RM2KMir1vY+%SzT?nHf$2;@*lA*j9B%Jj$<(!? zKa80?x|8x$Wy|8$iE6^{j0IA>e|&SDRY|4CkL{4@M%mI?7~EL_SMegp7nWr!%RrAH z{%GUrQ1L=bD-^MRIG;I|k@dTXg+D6wGkOCQu|fx@zxU!mRA{?!-a%;y(LSE*iZ`c)<^hPviX1|3~o#rPdhrme(H zF7B#PPFyMRk7L-O=?BsD$k?X>$<4ER;?2A*xAucPr(coOjeOxuyIyqP33|X>rrziG zHAIA0LgVy>od3YAeZ5o-mTDjD&2q+WM*V`XUd7ZVbA?@uGiUS&4O6g~RW@aL~z-z~Q~$(x!|?CkEk9LzA~SZ>0y z{179!uw|=e3wpX#=T)?d?OPxOJ;eUiufn}_2tyy}P&2X>t}jfj9#z2CFp2t}?{MB* ziPaF2&V`Zb+yt-gicLBEv2mK^%glpnF0@oc`<>Izh)42ypn?2PgOpWuHw~0aS5Ze| zFkW=RH3hfJW0}=u0$=S}F*bfBe%~h5nS@Bc`Bw~NQ@`Ug+h}X39DCvn9$fVyKWt@3 zg;C4>YEzu?JDAg~wzt1q3rC9n4_jXyRCU<>iFAl`NXMm1l-+9+c6VlHm|=!LfZ^de&pDquMMZd|fq$@*`nMKtP7V9+y1ie| zE0Mp-PlD`r#BRw2hx;gcC`cO|fbHtE49JZXFytwX^{OIw&H5}9xuf}6kltcp2zS=} zeV<~A)_~t?|H~slXz9qpEyg3u`hHUi5lK!HI@-&jC&cn?ph$23T=i@7v?|oRpZ2!z znnUa)$;En$T8RJ292!Y49TOL~nPHV{1D(La;BPfE6qhtUuf^IyGJL?Gy%R%MY0lT? zxeRz{4J6g7)&B>UM%MlAq<>U*X%>I;9n(gXN+PGvl^iRg`~eXvvGNit8EBQadC1@-zcUyW4^Zid7l`v z_bZ#9;&>c}BUIn{`t!>_+^jPnRUqT9`yuhdT{^4|eYST+9HiH755$hfz<`8Gwi`{A zw&m|(#m;ih?YPil%^dg`5YFAAPIBuW#>Q2KCW8h)k-W>Rqh9NEOfst)s*jkcs8tpa z-q&p$joO~>y=$x1tlGQ`eD*ko-oBIedZB0uynN>fc_J4`gWVo)er>{ck6?4NBh1KZ z^oeByHvN(^Xhlo(^Cja3eqhMeWV>X~-YCR1uY?UmnA)^eI3_z53^(vQA(VV=lIICh zg$*Dy-&^IYEDq3$igpEh(>3&&M-K}a#@N!zU=@%HvFPl->WMr?BNOmKRl8%l zN!Eianqhq7B>K8dVQ9XzJA8OjIL?;MJgf7K5w;v^3IfU-V;`TTt9B~X*Fdk)hyQ(* zlLMU{vykU#Y+ZNg#h2Ks z%P%^7_Lt^uC~!dRaP**5shAS&`8p@yue*pswzcYz|Pjl<7Qd8 zhL&=6*3kZ~;efA?$`=usb8T`n1={$Lw4_8@#ZrnX=SYLwYU%MT+Kn#cwX??KRIO8V zbN0Ws_9@?ybI-b94+rzGQ~>=>NUJ%`qFVujF>PSppY$}>|s8S$wz@XZ;v zqu-u)z*DWu)i3n`TL?A;Zxn4-xj*a?$?tHb>|d`>J0FiouKB?}f<6j0y`DHFmZ30A6IP&A~6cj={ za?7*i3{P+{;On;LG&9n_>&LitBOmh>7}ENx`XY<{yD3$?lcIO$`6h=~?oQ3DUu68~ zv+Q#%%;jcY96;IG`0t7xE+Qt!+626fOMpIKA)U5t!96TFXna44PFc4@92Q$@UJ#Ze zWePG?t(3*x{)Q;UB%uPde63dResC8p?s*J;cbR{A7R5g8CdW{!T{?WV!IPd5V_U~7 z;3EjCa2(T)pN}0MwH!U3mww}ie-Qcfh5wwZVNW(uNE?jY?29zXxnR@F2IQ-iVCrxMWPv-VItY^Wh*sp5zd?QMnqRCh_AR;?3 z+bDWWlo^z>vypx%=L1b{rZ@Ax^Ov)ca2aRlgGon0N02bX&Bo{fL&%#^lBP5w4`N<* zE)6`TzOZcpjt!~5w{owMIJ?9jNsLmEatXl9>O77s5iDA@P|f$vQBhTx=TsVIeALz+ zQEIPiN}Hxlr&urGj9p!E)zs9wX5}|CfThbFdm$wdU8s(p;sAScVFW_;k{1n`0f8dh zeP@2Gb8nox&)K)IR6}A7X2S>!mf)V#M{9hEPs+G`ICj&7lhIGcsP^Y@?~5wSJo#d?M54hW<5gYUE z75%OtGEl|dwxxJR?m~S1x}SRU%!ech#T=m{PN3jQU? z_wa>1UzMqm*OIqO6TQ}Fm7aeQ!(#e{L?83464}&dodZhU2#tG%$yZscn`%DuE-|~O z$SfXSYzz?E$1!%@Ds@G~JKPe(ZHzx=e4=&zgfu-MVQs(g_0^=v18ZG*1l13TxE(&s zM^)#xs~uo627Lq}JFpg;wcE|J>$kZgadbbvSJ3XmDdoqGeP{nEtM>!_Mds_Qdo-#^ zI>r*r9?hFk+4ni3fnDOG+n;p@Yq1QutAnerS_tRTV2^yAMys|G&8bQbp_s$2!_L?! zuf!N~;NX3QInb$bBj`cne;O-otVf8aL(}-*%p7S)z7y@$Q(;go*+pp^A@07-gdo1F z%#7JTIFKsofbS`^lv@xh$R9O--Rymz+>R@)?ZAvutjfHY`q4?k3KSd^L~Xh`V&_jm zD3wm8m8#g)^IMXA4i?7SeNpy}{|e9EXJ549{f#XW0s_7~M;~`lY@+mLv8r6L4@|U( zt_TNm9TP12m0Lqi#7K;bB!qQLj35Hso{z7fT#YX?v_MQXCS0zri5=-qz2qhMJ&dB@ zeR*qZo<3|KDS3?h;92D3_e2P2ok<%OAYKunn~2ze@LTtYf}}6@RAl{37q74M&^F|4 zsxDFvd5*FszL4j0z4PKOXXTe{V~wiO2+hU>+Jj`?^DQgG!eQPKOks+R0zSSk>)h9L8V5mlN#Oj3y)utspir&@-)*z ztD|V9!HF6VEp|hXWDA?3igvV6YaSmI7wjyxtn-%~zKGT+r{5pC`P+O{iPb3#fhK`i z6f?3%;b{<0s0LY%K(??~!u7AF6dFAp0$o82;3(xMV-2{T($CMdwu?rlyC_E6Gx5l5^W$tV-N~Ox(|!-sm4reF%6sX$!4m8_?u#fNGWoSq zM?9&n__{CZ`KMk}qcgo+`C#x0=(vnj2`upGfKEH_H0`R5V$HB=h ziD!u^6P%FL(64IT{E6%|0p63*+cq8z(P6XbcK*3v%bl$8O|y6$`i5dj&#&qN$;F_q za0{krYLC*PVc0lmxmkb3EA!w2+7K(6riacXDetlG@9&)tX6XKfuuR8$*MG1_B1k6> z&c>^Ho}h~S99F%RS_WIH*CQRj_I7CcjSw^E;~RdH|FZGUbr@A$vFS_#`OYC)rbza; z4y8OkG``cb)+j!+_@Xx%6%Q@9lBF*jfi}y$Vpyj{RViP!LOcoBD?zkDM2tt=F!jO;hK$f`S+S^L74_=9uqDTzI~iJlBQsyWQY>l^+lV)2Tw%TJ=rcUR zQ8?A0*_W(INv0I4Uw#ycLj8Evkl}VnHI=_o0%L11h}(}QIJ93L*xQ*-HurASoyHgb z^H1_V_1r)ghqe8a!=c}QK6@;86gg20Mjl6|QD?4<5R}DY@MBi{0N zc?l&$XpfHGLfh8)^{W`seSCbV7*v(f-BylajxEPQ-4G~zqCYA#+?f5ID*PqQqkL!j;Mx-BZ*sqltDHB!v{_`J59PJ8l04| zEBzB?8hqj zs@k))M>!nHx@_gFZL&ti`TP=&NlG$8ufm-S4Gx?AE8%%pLUktDOCWufj3b^9Ln0t3 zSpV;h`tFHo^)tKRCkrcj;n#s)1o3U$mQ0?ebHwvSq_c^z))`A+to6M)8GL*cQp^zu z!yu{-l$H2nWaUp)A+iZA4vP5#IL=Pa(lPkHNL>ed6}dmt~w@ zckf--x69oNRZw63ru7}Cq9c?w-K~I9BLORYf!S(hLqo+%WD;G-wdE)}NdGl>5kGdw z!H#?Jcgr%evzaGSRKvalUfi&-+Ek-tdp8yU2P$i;y3a7d@&@$h+Ig_-*rhRqE4(n| z@3I3v9x(u49=R7EpBRPsm#KzNcrow|l;IO9v+6E{yj7vJinZQE&*bOYE=V-cM4Wnj zc|>-6+{EX326DuV{4W~eJ`FhNseE%uWCG`CyNT~wcD`8<0LryiPLX>cWvK&dR3ZYU zl#i*XrJ_*mvG+ZuQc1b-S&IiFAu-I-lCPS`VA?#hbw`$0xt!$~v4i7k$^4>P&*)zia`nU4<%N7rrP-r4a6@T4ts z*1a1ZQ0ujTb$L2Y4NU1$v01w=0I%Tv!^1fMIZd_Hd|gzSrWwJU*9=OJz51$y;8XF0 zU#hP?TK4_4ORsK>i=RKz=y8)M?ay@6C}}bJ^t%a^uPti~j^+u!I4_PA&FiLoBd%k< zg?Gs`;ZSVHkxRNvQpooAFFZQ2$}(_dU3eBp-CYkJxr{{r{jA=$$pBQ`_56CK(7_|t zKhcPjE`;W7jN$gKi%l%)3M0FYG$fI7Al5+9!9p01Z8uC>R9J?9ghssqrv)ZaOSHj8 zUbxeDIvQ8WL^1=`mGnK-4B~dmIt>-e=7R&V@J)h2Kf+ey;fYDp0lcTu6_blo+RJt z(vG@6KYIUzp=NI4k{zC3Bk9vrJM#vwSk|N?Y61)^QP9YOg+u~?D!sA zo>yXRsuFFg@Rgrbi7>!LE?^qY)mmoUNZ>u)2dA)B9fl*r7jkziapi04YaTTak0QiU zl^3+}#HY?gI+JnHNHDSHJ3ZxS|IoJ+kYQro*c?QPiCgQE=UdhPlbm_k0F8UE+bLB@ z&(f4>n`}v+iQ6E5jgOCYh+9|A6BmYqB=zbLD`i#Et5CDb#C`p=!0E!D??H=FIzac4 zW0Bjpb9#CiCSZK!Bidp2spMW=P+Si~_|4aUF$YT@B2;bO=G^J62{vfwAsngu_O;y! zyQQnP&5RH{w?I$#3Z4SQI3HS`oPzx;X_P@fwPo36^{Cz>?NtA;;eOJ zz}F2G=>R8Vb}UuC)qt3kXKerHLUL$hptINcBiaO6A!Q2v<7BI}>NXEyRcsae=*tVs zK{DAURMp@r0brFOI>)x!7uyT#`i_Uy(;;9*j`R7Z)Z=BDXi3-Fn;PYQW>$Xdvkyem z<~cdcqZLLhbWCW!t>+C%9YSBVnGGi(OgT~Ixc5a$QzJ&ZJH@JGEszp21#mnf`B5~ zkTK+=pDK@pfx(}}qQB9CEL5GL&TQk|1*!;*Q%Ss@%P`aSvEyC4tFTHWdn;pm!Oq;k zL_H>k$;eud1DNx)SlR1pGqNjXFDes$)exsz0Etf1zmn}mMz?$$gRC2Lom6q%e$7)4 z9}&6*r$ExocG589YVl90*#VGo(|D9a7KY7&hObUhD$@Qr+<8lIk~dGrB)XN}9uCkF zmw5g@*B znpm`qMDx4n9|`t!Hx2Id{dlAr2~g)MPRe~`D_sWBk#OBv(im{C?%cmB)XL7rjGo^s zOOeR^VV!$$R|Xdo^pyrQR0VA#F4ih!?P1lMpn>pBZ^6*JKm~5Zlx4%zP#GLaf zE>YMVR;=;G!g`Ayb_DLDrR_=_=OrG23!W&@cFk6TDxY;L-h?yH+8 z_jasbNJkUfA1w(p^s0DlDxS^zIdO?o#WAlk$y`UxEj>I4l)n5yAdPzqdoSYjrSw-w zIjfd(t@^BX8p*s~NSLuOk6e__oQrO@NPKc&Jt-~LBYSN(6w#m_bOL?J`+c>QN81X! zh%j||ySO4W^W=X|R;ntuZS=(c(;$Fgu>udXErBXk9==(Frc_l&95ge?X30N|z`v_M z&$g5o?s`WPrHRtn!D~map{D%xOMEE+UCVMz8+*Sb;WALS47v$T!r5x5Wr^AL{TFIv z#5Y&;(&80y8@4)Yn-~2IKvwxxMHn(xaWvhy8&;86UzfiL0SmKUDbf7luWya<(VqLpCi~0PrMYm z`sGcsd|0aeE+lj@r>Y`@D=890v3AirL(if;PdM?=rQvE)pNpr1H61rwNJrK$?b$pX zPVPD!$E|(DxqRqduaDt_mlsZqQ}NsY58Sk>n9e!MgD>wZgM^GE5jZZyzsB_`@o1>j z4VpsaLrL&|ykXcJTuG~SKcut;WuwkA|7%>Va*pnXT4KRSl@#`iuiNmW#}bN(3&VX3 zqN6bw(`)SbY?SR$`6tU?mBS~F*kW?>*CtU+Yrj^^GuH$XtE*G~e!K2Ve+9RNB^p%! zvV-;R@+XSRb$39q&Vl*4pS5OtqJ)kvoNWm3P2Xqed?X@#m!L@?2M{&}t?cbl;^?=M8gvWPwR079`Cn<~S|3{jqt(42PxwMZr3$PXMd|S3LK= zEkNog!WbD;!yWFocYKrlDuWvZz*qOLb^5vhGa+CS9#GRG0gp%if}U#=bq0i!B^Eq1XrWoqsBdHP-t*i!4)ql|^FIsLoH$o1kby1p;t%cr@zYpV@L5 zxnn&Ys{pk@E>>a-Gyu;8@$4hdDvzwUn&e8VsajOWDCu`nyFp`=}4652dT2Q<3d2^xa39PVix#(yk=bj z*FqVs1)FUQw6)vcCdH>q@!R_VQ+)?8)dRkXPdm|Rdw;c0cezUv88Y-5za4ePo30Lg zr+VqXkTvk}hM7)UC|Dswur5`|5>)Ys|EAl8FM+Sz#3WA!y%jR(|8T8SnOV&f1D=(_wLlxHvP{Y| zPmegqG(G;)W7h%3A-P%gqO8?#3kE<*)FaW4gisSIo@MI+U6rL!sH|QMQ*BBp+2tnq{zNYO=NZ+tu8Nau0i??`Z#!2>k14Mrt~8ScGX-8> z9^YS!(sjrKD061NiS}j#($zJLlLxcOp_Q3_p;PS;F5^3q-ci>$Qi;NV!?iYy9lzcu zu;7;m?<}VO!%lAqF5;iY6sfcQPQBAQ3;&D!b3CutY>%RUCQ6j2LOduXbV?m!qPl$6 z6zLXil#=whlrrtMUyLwR%3!y7B1g~*9`0v0e}C9VbTtSmheMdRTN2OBSH_tR-Jf@y z427vmaNRc%mKk3EV3=boQ9FU3g6ULi48?W^h&V%}g~0M<^hFD=@hE5f-1PI$ADu!@ zsU2=(?)41#h0&12UL;ZK?~DRT+?@0c>2f;kH={usZ()q(5jjl7oi;E{nXWT^>nFTp~@Q zL@f~4t*xWWCRe_OIgjL!8%OLrp|ZnjX*!{%oy-*-C*X_LcpqYF$oH`)EfJ<-R0}ZY%hx07L?LkRbJuC-;}aIJ zvPq=*vZgAQBo*rJ!&F$$sdtc(KPMb=R%BYQEhA>V7>cssHXJMRBzB;@)hM0agCfaM zX0z=@h`ZHH=xYDW61m|Uy7i>W3?8`7{R7?2ncRp}P}-=P?~Xz!dt==7p3+_0{HqGr zG%ly&*D4qoJ-0HGY6MRgJ|gV)Ty3K7LmZXu0HVb~i_4a@-xlfm#vE@QKUSvl>&lm} zb!@bc^xNRdJl%?uUj|;QB~=;p3=HR0Mo-M|2vA~eN8-e=el<3*0@Cx;R9ifzIs9bg z^abWHZ+CZh(=8_o30HHnhv!YY?3W*A-vTxx9KA;{K!~M0UOvKK+vV9)Rpk`qH1|g2 zVa4JqY3dD;$cjfg74aUJ0tfg;fkeAUgg#50v$vIN_8O1?zc0(xq>x@ZInMh@2E$Xl zL=Yj1gv-Yf62|YR9)fg zJlT`xWLq4pWXDBXy45+7j9h3cCa=qn#1lMTY5N5ez(P$&qQK}Ac-BN+9^zIyQ};wH z3BWa}l9p`gI5Ifx`!^T>0)xjxt?t6Z;nz5Ah$SSO843wM1k&1-#zE0kd^lc?p|myu z;@dE3Qo}?+&(}}?o$2y*j?R~|TWLY#4i|o8n{x6<;^kj;G2zYmQ6L=)iQ;0n_#T!K zR77k)@#^e1Z^>t4Q&0)4&8n36+#HzI0x_?$?~??mlM*Z#!;l_)AcV44i_1F}z#NW` zU;OakF7=x2ckzzB6(w=x0CpszRbE*UI-|mzc}@}h=qupyD|=Zt8jg!6AKHIj@4sFb zjnUhCeiNxkq=6k7jQj@C67!4qZyQ$q|MZoR&!lroInFeLrXumVj#$8dnm)dTN+2W+ z#L6;ptuDm6i;R5KoaxHmoCy{2QcL2k^~eGT1FKZA^HnhJ%unY#-H3iD&|?TE-Ef<* zJ27bd`oF1ceq(i#K>+@w_8Prix|~0|Z5vjp3A3oj>ydzgN{|_ zTrI}zqEg{|#r(UtBAe%hGH+#+Dn$vf+?shq_OFx8_p01A?1x*tWa($HP}N|D=#3pg{N0VIh)YkbPY zLr3~2+ldVA6#kN$nwghij#jQ&|JAwbw}&8%2val4`#*(nd{#-Nsy6>i)=&??UO)U} zuXoz~1>rvkdh{h(zX$MIX&I+^xj6N_%Cui|p&6m9>FFvJ)zw`+2X|U3gawSz-yAN4 z86O`{StqF*zI^DTX$kj}kha!KvTfo-)?pb%2eLCv8V8HWhIbxm4Bq@+ctIxz)Nx(^ zf9@LfR0{;Q2iaB9XNq|1?nc5ZkeSea2gmzs%L?GkPyh4o_o+i_KEj>Hb*2K?BDSW* zXM*e@M(Zm)hZij2OKdn}TU+$H&g;y&t7+)=COF}~Lism0hj=a92Q(YR=t4&8o#ZyB z*2nC*M1z3c`F@GH*7IxW6TRV2SYOl?6{%|c@sl8r$Wsa8CQX)GKmyI)!g6mk8-?65 z)wekAz__{iM67_b5dF>pslxp7VsLw&h8FrAb%R$00B4Bs96S%Z3Jg=r2W^SUUgfK%8-qCWWp+Kq;+WO$1|N zVsY|wl`yrq(Y#W5R+_=Nqy0m=kwkSM0%6x9ac%d8!-qy~b=W)0B+qRF0IBp7wKRk- zrMfdS+mgDudBYkM;||=a7mwf0N2sb}M}mb1Ynm;FqNLauEo@#5s^-Z@a0+c5R+f4b zX(SUlKaLmB!=NFswK$m^MwK%O%f+0%Gwdnjf;}WBHw`>EGFi%=ep;-p!Q*JC?Jg6w zzfi+(9I~|lVkbr?75$sv{Wyzl$#CQNY#;`4xgElBCB#7H_X z!Crde4r`|?ZFpLBhJ%ZZRu#*3QUpXcStg+Hz9!Be4V>iCdSWWTZj!bY@4cLb?_U4W z@Zd3IcBAk+jDM%Lzvu&^Q;0Z6@d9euri+U-*cGpav`5%m&4i2{*Uv>(YS(AOWrUzB z#g6dy-EMnbfZ@?Uzt+{KKi`$6d2s9Q%VZ^T11%T*oQ zuUrnd8Mfe$lW&W0)oBjjK_2@{J)(%jZr}PDPg=d=5@N0X5&j$nlO8MFM55vJ(?T#K>Nupsq2=PuiZnp!i&HYA2C7Qwn$gqv1ZmTmA zY`41S9=psreYV7lk@3xKPtktmTjG&d<=3ijvN$c!z9`Kq8?(>(_{^ZAV+6`uxJnrF zKdNEg(0Ag>@4E{QTP6ER2sJjp-3FjQ7TN<2Wv8zK(5$K7m+KcwMIHq z=?IXKT@P%i`q1MZ;tM{y}#Yj?&tM_8ERJOEX$$b*>+qVNN*~jIse@zn^6>w8%IuaqZcIktYi=N z2wY{W8{t;0fuc%809YW+qYF%(l{Gw)&}$m!9FqG@6VK^u0u@Xn^({^?D0W38Sx2n6~KahPNi>B5wWflXI_b7`qdBel6nBW;BhTLbd=cQ&LI{kL0Xtp`{; zOW3b}1=ReV0i~qVYiTIzvN6m+9`ga6i5y2afdm{W=jI;YFER58w&@mV;iwc!sxg>0 zP2{#0>wU7Kz8Ex+mWJ-}n^uE}7WP2e#Dtl-u*E7p9x`&cJN&41DpBNm_>TtpALj2H znN{9>mB)t@Q(+Qks!R(j=bqoDo}dF%T_$q9BP01snglH#*-d~n8C-M@3(Wd+dFYmp zAFYg^oI^3pjU8EeO7{Iq8p6{irg#YtXKCn1l5X_;DkV!Rh~(>*k>4w~y6%roRazdJ zac$yBu%m2SXB#^ZK;bcPmO!h62F^bUX}sd^e3KD)Td`$RP3R`HxrLtf8Gh^^H%qOs z@)unalkq1wVgHt#?UJ|}dA&A@KJj1k_^s|#L@40d<)7j%ulv?pf5Zq?fR#s^G1EE{ zwd|rP7M)N7j|p6E+Y$3h>5QfsJb02`$izq!LXb2Pa%gZtJ{li@=Pg>@3{wsXKZ~TN$?z?4Z(3B%x z5-cjBA&W?}L4nKK)mdOy*1YAP)IapPv$a<-K4E->95}mv-|GaJ>tA$|_o&VcW{;s- zG>Qq_S#;Lbzu|6fL+JZDmayKpGrCA&PI;aB)8z=QtT(qq&~$bk4TcbdZu~i#D^#C6 zT!)*2C?e_V8&<5>i<42gVeF8kEn?E|d(M*m@C&(jLKmgE{=*IQ;^d!i0!FoL01gOXEyDxqb&5~$ro%SvG zJ`)VBUDPE|1oHk2ymP5e$+WZM?!`|}EY1P+U4(1zboMiTQW6sf<3}gfg$VFxw86?f zXPyOl)1CB_@wW*7d?!y0_IF@iHC3c%fRWj8-#vX)(m`RO9)+CJ4xewUs6`U60%~P5 zG*vcmf{gtIIpZG2giCl(lbuTTNN!Jo+vj(wd4E?l0b~;pP*yMRlKWpU0>+#s`f0H2 z`}1HxasIh-=rq`ke9VBNXqwKnVlGwC;D479ZEF+ zXQ3QcibydDGQOZ55hVnbReBYwQH2!$+;qE6#!S9sv1#{i+k$yyUVv!-_K%p|&IQyz zx77HW=+MWq{$vqJwf@bRQZw)y;(2e&9Y;_|0+e z%Go>Db;4rTLh6#fa@BJQiG&1U@$KO;+bN9R!C!>&mjbF9DQ*7JxHCKhP5>4F-Hc@T z*UP|7$(8+USSJ{?emfu};!1_};l}W=*R@5|LZm*a2j);UP@&S)^F?8#lhtYAr^ZyK zXw6=$%Gr0Cu^`W39uPXQj+k2lAPWR|p=3*v+W$()_^+(qm#46Z5ol|Va}Gj}Y3|?6)*VWTx<)FZgtezaH)Aj%Y zOUv8Gw|mG6sv)MJZjsHW7{!Ic&oNbOFfeKV6ro^ivr$80}+&!Ec^Sa5HOu{P>F z9|=SR{;KTqw9vP}!-+gBS-E&VvwG&ObnYI0Sj2g^J6~hy)(-^5x_$KY_i%UTa+tE& z6WrM>6Q)og(;TjL`wB8Md9B4X?M61w0tQ|+#e^M1xYXHE3%7_N^;9M15?n+#x5^39X!1}6M!9}06nW_T7j z|F@PC4iMNz9WI$`;ePfa8~PkB8oFBMx%If|E#&<7)vWFz1Vo{kg}SQ?VNl8iE!jIS zt(=iIMbUG}Q{#|w1~7gLUJ%1|pdNWhU$cA=>c$7t1k|6Dp-)8QA2((9yeBOD(*V6D zPmz!s@Oih}05p<738u}O*c4p9i{k(YpU}1wJnWO^!CwJW6@d(c5M^{m23UdyIfL6t zaTJZ=A;Wi`Y;~=)`L`O(e<)|0#Xq6MXU#(3QgJ1{ZE)pRHJvUf{Yji4iW1)5uFd2L ztx}kC*K!2P0ZU&K`=Z%$*Y6T4gF1AdB5x}#V4|@<;zA}0Sr&_Xquks5w-`9zomJmV z=>FIPwBHVVW-`nft>64a^krsn3@ZaQsialkk$KuAOs5lO0mEu_RWSg6QDkg_Wv-gND{ zh{Q11|IkDT(iB5x6 zKzm#VU=J&~zW@eTIP98NGfRq&SD8&%k`t!vIVb&>g-;}|)iA^}IzdD~QC7w%5ySEP zJ42InNo8NjjzEVk7;+*uCZP}4wIAVL3jt*9-?2~o#%}^7FCY?Kf%y~tgnzqlMg9L2`9 z#j!~uiaoG|`olGmP+Z5a*>tt6)Az>ozp6G|U{FEI_i%Fw(K9re2(uLFQ&eAuZMo7! zRmauiN)?JHQ`)@QHFIdfA>8irczxR={`zz^r0uGIguJyLR#dOJWdT5?z;J?#Xo55{ zBLZZgTyQrTN3H`$t27rjV4jRjd*Hrqon9&b4v&oH^p1O|9TI+|_o~Gsi)=&sllvep zBiowt%kVBmT}5V;{ODO`3~+vHj`Sa@aP^q_Exl56Q%3%4uFN_4waiSIPCCnrQ`EpT z6K3ktmSOGcYgmwd0eJ9$kHo}fIIiWz(MUsC+=9+*Y91-3{4yE3WOF%*5>@dwRdEY% z?lQ1Mi%t1kr>7@Q)~DrF=w7!s;pntW@yWuDBG2FmevqO^xBYLfpKpfUn}0!4p-IJG z43{gkb*1aS#n{>+mIQaYVtf*rivy_otzDNcxcy???hh5npI8k!up|tBQrqL_$e<~T8eptH^f$Q1cE;d9KlT2tk+h49Vj5o@<1>WPfMBXNF;;+4k z{f9#Gx7)M4Y%1m@g_~%@zK;K-i$daG`STv;IJe<0McuK1@~lsn9jv)HRca;2W7*z(g-Y z6!()%Dj-bqsgn@?h`tquOvR?ti^qjXRJA#zM2E^UD(M!hmgoYI4~fLZ=%0&EftER& z-!1&kM|6WbPLn>_+9cI(3Q=7f#sn8Qh~1MmHdmup59CuIb0^Cp%B7r1YrFlf34pI& z9}7tEP%Os6I%=bmbK^CQqZie~{rc2dh6!)I9#49FDO9fRIvii{(i^hySSK3WHkSTJ zL(wv!Ny%(Nx={5T&+zyJTG_4rA66L}JIcVFj5BVY9RAT#Qv>w+^+9N|V@PTSK`H!( zW@{w92nRYzxXZ}yF6aAW)z%6CNNwE7m~9+vHdLcY1cOLyl(}sZcKCojjX!pF!u0_T zU*lkQT|e-1xcltp9BNr8Ymuq)JElRJ`{|=K?7b_?)DS}2tM;l_J3F{3rZ^47xF3hO z=@f85a`4#VTr)_rfCis6MW4PJ|Ki*A76$^{kmxlcFdCr{FI`aqg;^${yS@Fck_G+< ztm=6fN;eJYU#SNTQuKoJ%u@T{0T@Z-IZLM1>~4vJr20BaO5;jh8J`i^L#e>ngwrZQ zix#(yI{!2!ldUlOIIIx%Zi|ycJV0i*Ae4qK1KJ-p5>@(8&vlgl?2ywLIc35uDh1|( z02bTh&Ph`t{0+)_!LB#ebv%MgStP$LL-V*SDZtWo5|T! zz>=Ql;ogrO2?mhianVZKWF-gfjovMK4?MA2?1qJRljL>Fhr&?oqrewD=mm?>CSEye znDP`hdG~q?wAvq;+lsXX3W(B!uR9YV-LS``MZ=mP_x$E<*LtH5m0XX(ir;RQ!QTu6pk!Co|qS} zrRADyXB=r|m3cS;(BM^dW-IayYND0Na-qX{xYpn_fT*){+#PrW9e`fjp4annj3eJ^ zOmW;u09XqbGo-@JSiBA9n8EuGNL;DugWMpe=BTo0GSfxLnCn&~?9WJg$ZZ2k)Z9W- zj$~jvQLhtzC0T6y_ZR1&q!Fe^)?XfTE-WO-RB=Ljm)r%B&|YTP+TX$Xj4hkxy+tz` z{verQ3Zzf;4NPlqWh!+0ST5=|Fn2JsGekp%e+q|}5Tuhhv%My{N+NQ#c6Y}I?3`qh zq1PK01jDu&4Cq{-c%p_ej)qzSR}ilXVBRoWFmTnT6xH#L0=2 zL>i1l>8iWN%O0t+XQd+(%cF+Abu!`8jiC_C;V+)yFjGVl8kt;$b)ab4+WVTe>#iJU z`_siZtF^n=x!*1kyL_Ii_?!>nc3CdOKMxWSUV8@^|CgWk6q0Fjpm4gipk{F0iWusP z_wr{{!JaNN$O5_j{pr>9AC3mV7yC+-bP+9-h>>@a03p{PB~$QP%3dTONIz=vPG>i0 z7_T94HK8^HC%>t-ma@o6PGwX&;?Mm`TL=ZV5e`WAqP_B!jOZEIM0 zr5UB-58i&@ORsd_D28kVPSS0sZX=SMK9m{&FtZS$b!`M797`BGX0H_5Z>4#lC<1^$ zxt@N>fBhT&YFX%|4<#)J91N_scc>jQ*O%Ii42VpE4g4Nv)zri7gKIrK*r3spmN&CL zkP^S2*Wc#iYHi=|s8&>qsmN>VkDHkUITo?Ijd8tH+&|i(>_n#l@ptFoKmu$Eo_Vd)@blY_VJr=MN+J1?u!KbFEsK23Bi8(aO4g@1+vIv&1D|U* z@c7(vkB4d4HWf1li0~2>%g%WNFL?hseD=to@g@m*2tsaX%qU6cMSn#1CqI<&Z+LXy zxEYQcd)GGDRryca^n1Ny<=)wmTa~YSc|y^`(*7f(Js`AfJN-=)u zUAAV{hYzyDhGL2a)7F=hIvfG>CnVvYKjJKY%r9i6P9H63q(zp~e3_}>5)d>~PNADW zVw;{0%QffKWNsefv0knhSl_(228DmCrP&9UsFvC#Uw)~dv|iyEPE0g`>$$w--kZ3G zio)fqzPI-z`AMl$*OELoQP9|km-+)eEe&1U&~QjqBwn=w2q=lM^(bj``Ho~0C8Ls- zFb3N*Qhk{@0DiD3#9OM!!ZqElak#x(XZ+ScP`>aGsrgw_0>R^1jAoci>mTucH0s zcDyIS0CEhg?#P`Iq-~%kw9OkzdmbXD?Kw#R4hKWb6~uEaCR2k@ z5_7?^Pr6k7D%BP3z?~#Dl|bKn3ll$GYbyEp-y9~ZMFgZ6<>oqiV0sQE$buGKukZP{ zb{?58Cwm6{UZq+jBbCA+(>20|SXhd~H9r~rAtCA9LkIqLzPU^-3u%H>HF}@J(iNAD z?0y+#nbU+c6mG0+@;`zu@boomO#xknm#04pkaE+-^Th49eJrC~DKP)tj$a6M<6t*k z4(;{UE|9BN_Qx^^cJxonxv)SCAdr-NxiWt<4LVq}J~)!vDh})LC{&xeFGCCX0cNA( zg*k)Alh=a4E{2PfZ-UmQn)TiFm>XVOQ4zwwrtkQebn3`7o@Rhi z#2`k|ZOe06edebS=9nuYgbP8^|yBnlC+@z#*hje#$cS=cjcZqb@S$_XG zXN+?vcaF8zp83w_b-X@X3QkN892s*x@EJRey*_e7vwY@oPc^9XygsXbXbM>XMm=^5 zSNP`ZRZHUt)=vUgY!gj7tMc9p0?UVyl)NLSiYfi~pLd=Yn5XK~PqP=WF|#`zOEvPB zK$w0`s5k|_J-=+}QvY09{JHv5tvt3f*GDF?zxq$s0jgV=MKoR_}iO=G@ zqjzz2+4^-uDH1$HCZu`5iy?S2UoiuC77a7EalL@vS?=v6Bl5)Rxfzm&x9^JaSLqLZ zEH)7A+95gXUR@>D_r6iv$M^Smujxk}T>ZMO3)U6U{2se2LWp;yjU}diK4Jz8X%;&? zx&IMA02gbWMn7c+7Hdk3U=P#+@^IVLj8I1ruih?fNgReMGRyt z7RygO&S3Em@`@(^hsGI`dZw9Uo_A+U0WDiwYC3{t(K<;l?-)gUk2#ffxRuV0ztK+i zM&kPbTIe2`%Khf{`BnBN+s-KHbt|qE5l8#qrpNhx-7)$T!!?ER`Z<|AVB zt)L59MJT(=5d~;gB#^If3qTwULm{VEh#TJ)zUSJtqE&7LPDQ`q*>u`6mhNG`zOud& z)E>xJ$3xOpWz|F6zU6&1(W?rD)fS|TRGhZrG_(5+-7x1`9G}$@xvK(%2te!~D!MR~+XwH{i~VQ^ep8`(LoN z$?+I30}|<+v_IvBVmoi-^DdI0pja-PQ~iNoSI1hp zEyQ55wj1Ig3@=_#>4SUi1R>PDhK?Q4n=)JkB9QM>iSjRBByVWdF2C@L=P&^;L@^1G zJHYbHdl~G?*+~qXt`kPql%(Nj&xJ`#mP+Sk(^V4vl)p)3no|f`Oo5?C@eFAB z7D5_>NO`%2)6mZ%U_gLa7>S4Qdr!O~MGuhEOVs4@M<|4ywgB#*s6}Wp25LonsSPe+Qd`7cT*s`7qMVcVaR8S3nc{k0z&Jc=?t;>m5V@=@$%E znKTWW!LMb=vX~V+A^qUB>Yen4-7Pe2N$V41Ofb@FE#rDNrfk*l9LEW84a z-}jv0fZWVMD8iQkEPm%sjv=EOMCQiOVw;6kT1SQC6QKCWm>Kql_b+d$@~ z1#+{m(+=*{&B!#gBFU_paQ<#XZGH8lma>{uI#~1vc6bWYo%%4X92*X7ZHs%v>Q{Sy zsld%U*Zc0jpGKI4lc3{Z4?FGg;)C?lEOPt)(RUa}a3UlrAz$}Xvip#z+tI&>U*Fsq z`S@fOGb^3TI8s`vga+**g?o%5wIfzkZ~c35|E8dThjq{hd^B!u$jS#q91KKj(t1ZY zOSXYfocUEX-kNY{Ukai)x5I^dX#)Nc^J@G zT|L;=*WjM-$Fk-Cm0ZoMNmh57L}!1c@&&MQ{Vf`Ev4-hh5tA1iJyzPbEbQzS8gAOW*cXVPwkgR1{Nj6xu&Xv2~o$h{gMw*BDz8 z41C%Uzb!2#oF04!TBG4Fla9G-;hJRH2e!j}HcnH+MURep57^wX3cmU?qs|?)y^Fpc zYlSQDv479{I8e6iNX@6-f68~P&cxzCbszLN#`Op^RZlZD9zt2d^G6dA(6!>6vbmkH z@wYly2RzaMx2OB{yG{ug5__?DqG2jytO(j+EZprNPPEizjohmX6@q^KXe3EXvZBCq;C-hLN!Y!GBkVCf{Cxv7|)SpiX?eqL0up zCJTY)FE~OS0bxLzW6D4*9D=tzq)q4_#*Kl?p*zUSF;WOWi%R7$&PR}`HwN|xn1{rF z6Kk=7s$<`-h*n0>V;#6&m*#+?V;GI0MgnCs@#<7?0uUEpnF<=eei52aC{j@+H|fWL z@iWBM?iPVqpIf%7N)DMSr{=RXs8dLq=L2%_&4B~K^uxJf4p2@lQ~W|jU+-Rc8SBSl zSW7iIs!8BoXr7GF(tp)DLjtjL%f2|19vFw#B^L1tH9@}A+v)by4aSc?RrH8fMRI9w zi2`y7qLga8H9lDdg-^CDPc`JWQ3kLVJ4LlY)M&UjN$|qlH<0ul1dbxQ1tNLYS&Hk`w4REk`KD6E& zwU}btmm8**0Gg*xJqC@BauUvc1tR_z^<_ zDXH}Tl~Q!fK&K<14OrhH5r6ysi{|}Z5OAIs7w6iJgh4d8#!Nju&^<~kb{sC?xP&nACH$;%+uRiIULc!mI*a6Qso zZn_t%D(woVGgi7Mk@d87pGu>tv{IkatkwN3KLpb5f8RPUZ|LYxR+XFa@M{c__DSEO zQ_V?matNWi+j+QGc7=1lXnsheu8X#Wx_5kxo)2R)K+)PKvu^0JZ`gt-6z%nc40}J} zhqc`rLMBKzy>VUBCGS40c3Z(LNYC5o&wg&-KClcw2(qA5`W|HT`}iEpwbuAMi>O^$ z(?T&3KT#e|Oo{uq1pM5ikUqBq!P!}?Bwp?mKDTQ;Q~ca%>|Sf{u)jlCf1IY4UE@k# z<(w&8m5Rd0-*94<^;2bxiyTh*iq-4Y6Q*DNQl<8GW6EL^s>8<}%i9I8)HRqF1G}lY zA|1AkizG!Ro5^d85E69$0OLN%qQ{RNhYE7sGAn{oYSBl#Dhin0*;eMo#aRS!K{39y z_(L}G6?%At&EpM{Ph#4dONi6@CXRaLMF^uP;W?BSD;DH{7R-P7*9IVh{rdH5>SGSI zU;5^dI195BMK8MownYWPY1D%p>N!3m1{)xgRz9cl4S=;3Fsd{WBhq1{uO9o5()6)3 zixjd6l|N&dF62!J(DSzBS%3or>Ue_k+32yMWN|ufZPX zPq$ZOgQ;~;5cT8T8^d*~kTZd6-fDC!U@N)06EY`9NIWQ#ls`9q9GK7OMUkO5eqa@- z(zB%e{v(~MQ@S-LQuBiKO*4nALKy?zxVDlS%WzWI2c5+DftKaPWvxR?bqfk3ncHfc zz?B|{3U?bFG?o)vLkGl?Oe#Pu@&`Aq{Ns3RZ9S+!-UX<2MdfcPFbt@(@-=1On&dy@ zBn=N2d60eXuv1yzA_UxYSPt%?l+?dREQnzt?fP7s49c%q^zlQM)?D4(C=#WC6uYjn z!UX7of`YJXJ=bI^DY%RvQLIOcZMJ_esQBxXfgcKKL}cXF%EoKs0q1s;8u0f8`uFea)9~lgUeO4M+W&BOzztli zI0senLNn|*23hTJUTpww%2>HihByxt7pJ$^vk>;tu|M(Ik6b3Ltk22T9GJn%OccvF zB2<`DSEWo<^S10?lGL0=iXD#sBdbkKegiblEyR8ex{`|;a^t2{UhLdNi88RDoL*6tF5xeal3J4*T(bul#7rW0GGYuOi(xK&_*7GaG3Z-!6WUo9F!MJ&KhanLs z8<|clQICNr5e^7h^4An|Rm;u50aVPMK27&e_mI0Ni8L_fGmT{ztJFAdOJ+fDv5RFE4sF0Ox|3i!eg+jI7l{d)M=niU}*td=b{EvvqY2`ppC z35c}*)wDTy{t&u)%#+e%%#T+eHi~AXA-psoVIp_{#twyNR5DG>T6>T3Tzk8lqiF4b zZtRyXtG`sahLTFwb}x$Ti{k<*po)PxFWxbQM?n((0uLuw3sHhWDjgR?6}Gm6 z6O_2Y@2#?N@~?r9%$;YV$5k7pk93#@^1;#|Mz(IrY{fBl16RDEnFQY&AO-w7$A_ey zK{BphrOT3|%TmHdP#G@16CxQvx99w5JzH9sZRjC1iEaIlIEVL#dvcsJ^_ou>_o_03 zpUxkE(mATv@;X zWo228{C7bQ=5)Ca`>fA&1+?{XyOlG4Q;f!(0^H@J!m1%>Wqp54)<*Dn4col$@p=P_ zOx<`=rft0ltSF!;tG3_hgjd5tdak}Tfdl0DtV8X-Zp5ciq007C`Z8Za?rZe_r4!u_ z51gvb$5Qk;WkwU`T|@YZbclWJmH>G$sP$dkL|FE$ zf_{PmN26hT_m_bIPum**{>w;pB~xw$km_>SAg;$> zK}7_qx(gLfa(g#9JS|9HXKMBbSvEOAI$}g;r_k8M1b^c&7KfWt{z5#utWOD|#TAPG zq!To2Es8@E()9`6wD>>q^~BrTpN^$?$_4MU2WC~8m{8FiMVUH}GP`3g&Q8<#c5M0} zFz=sagwZ<9eOMeUpITQke4q5tWTGwM;P*-PW9^d0l2$VL_-=IATU)x};Y?w1B)F_| ze;Qheis9f)jp+?ZF==B{cxbQ6Q?%CZ#XrtMW15e`#<&XI`+VoNL#(R!jmScp;=n8z z^^snoq&(}8Q#s*D3ispWXO&pA_u6k9dun~sVy!y};UQPDx8s--$+E4PAr{sNZ~<{c z5?PGUJk$BmZ6-2Di2qj$5Ld;x+(S*M(LAf%s~izd*1z6n-fz? zRBZ7LS5B;|q!izp;a%G6Hv15Qt4P+KT?bOtcVZq*(gBm1+|N1X6r9Bt4iVin>=H@p zWv-~L?~S9`dP0w`sFpf+;Mt7Yo#D~J+hTh1^amYtR^4|$nw_82%WtttqAB%8>C9|u z9x(0_qf!;)tcgXF<9uN}O%#r9q%^RUikt((@xHpIO;hZX#y?GT9^?o*FEm@r&7Raf zDx5^R!)|bp_8fTjoi~VE2~FiMFOsYF~#Ycc|u4 zxqLIeXerCRL71UWG6K^=hC6a?haV{cvP-`}ZVdPLyIl3j)a?W85}+O zp-1sC5=Tl>pY{`iwy+FyB0a{>uwCY~yI0Ti_3!WTUayFpH>nuZ@Kre=Mm--sqXniw zb1-~}YVWi_Pr`voag7KZA<3h?7hJO>3vx}%Mc(RDhZTx}bQ~7CNTrid@kPN0KV}B2 zmtoABNkOryH~d)N6hYKQ<4^4gEr*?7bS&lhlMZ{+%)*qpz@#+cS;rPEIpZFvSDT4- zWU!!X;goLG+*74TU_yBwS7Ix0(<|l zPM1)wx7_V6mnO~>+4?FCrKmCr?%sH1KNhjptj^2CDnn~)l(*-Jw+KMif%H8Jmn5;^ zsvVmX59=a8tR)K!m27dHE+0C}J53;Hu5FpcO!1NKw1s0c|I6$}jOT^fW52Rit~V+* zl%Ju?az~f9Gg|tq5LCM9_Mz$kig>L{(kdT?k}v44Wn3+H=a>9q7teb_;#cM;7Y`diGolq{7`tOIPZ%mo!(RzoIo|tYv48 zqtY0)9{O4~-I-J$EjL&%Tlt7JbTkkJ=%q|UI;Q5iQ1lBKPEvn8ob|yKEt={#Sz24e ze3NZ)lifH$Dc?~C{>XKpW8}cx~PwYHdAVIr0 z_U0d8J>B-IpO!Mg)4%;tCF!Bv%*Oq0AiYyjUNm`djN~B5T{r$`n)R`aOb<z-etUL(wH4MYML`ZG&sE-8>p>2 zgs^Gl(PEp}DB&sF5Qpy69dq%HzxiG`e5{(w=SO2<__8r2_3h`GJzbNOGpnBGzV_G_ zZg1yOD)a2KvDms)<(ICBV(3C=z4#07Pl~)wHyuG*C(3tM>K+B zlIsLR%WZ5+`RU(nsJ)*TGRy_J0)EI-WmTPF04|aFIz!D|VxJ9b1e#1>s8paxhkZw} z1TOJs_~`ZH*YO}bx)`A_ukI8u^j2r{_9T3Nyr zL~n(rrGK#$$26LJ2G-Jku^MU13STAk_OBfAKqtVY?I{#yu8MKPQi< zpffml_*XqX6_fA2|MYbGVmKpU8&%XNqSKux;+3F2; zIY_?fmpg?bz19^9A}H2sm)KIKlqAU2?L>~J!HP*;i7`;gp=goF6W z`iMy#2K$TVEK?FuA|j$gx3(19n&laKwV1?jFGLv_PGUVQ`sRA`&SH9>a=kC+tr%*P z;#lt0>q(0=+XeRHhQw>6>rI^Abw2O0ngEeQ_~l5!86mP%o(L<}xmH=Pt+rcvna6Yo z!Eyv^{=ye~IoXt0p5s2(T3*Z1$8sWZpeK=wCbn60zg@o%lSi;e8zj%C$3Woff#!3q z4oWvAk#G0@T7vp9M1x_n?6A0ty*x|gC_t|Dtb=Oh#N`mkTnR4i^;};$Gtiuz_{c*- zV0?e~C_Vbcck@mzOIEGaw`d`3vhCbUlMnLJ$cOpB3b>#}Ib3+{wlnD3_v5%7+%nso z!N%mySp||Y4O{SQpBD9f(clwh3bc$}R&oz*Yy_)9h8-r8V>&whl&Xf_{C{~HS)1$! z%J9;@WCqWBd~t((Ew~U$S8tM%N~mcd`y0F<^0X!NF{LH@nB^nVx`{mJ{d+{?hjZ1B zG~amwH}C=##r%Y)uGj~9HGf{X%dia;FHkY))wqNIaUrKHIL>FXUR6u&6NfHW$0jI6 z(dgh65B;^pe4*BbTq8~g@C?9ZbG;MaU!C_F!3CbS;UTaLFzwrF1ja+M(s$2sS>ysS zdkSyY3R6ce&7J(y`JOCdJhm3zGlShHLP|kg4D3f<&|`j^rX<^*jldL2fIJ#O)glyAGgX;p>MERL_-Ckzc0 z?LboWk`*e?ccETiOV-b#tT%1`;7NUg*!1_rHhEut`?5IYeH zry3vNc*hueEM?T2z!7zZ;2W4SEg*GzGe#g zM{syU>Ig9kmuFpEs#GW5H$05)LWXId>7^N;`e+%vyWTglaMg%rv)*O-;llyCm|b1- zwVSNkgmQ_**?EBBdK}lS%d{{sW&f7uqM_9EPA0z+-Pfs$42+W!?yyGFcY9( z079M##IoXZ78T38FT}u0pulF&F$-K*=Ih7OqiK6!oSrX``FZ|w_T8YAY{^G#6RhQ{ zIPaWW%{ZYckSQdluYxO~of>E2wH1VS{&0}BvlA`M!a*9XVNURztZ9HnG!U)QZ=g(L zJon3e4@!>D%$UW!HLI5EA|4ZtmAy(WHuS!yof1F(u$98ev@>WLbMc!f5IdP{y=;fw8C%w_hb zni%oSa*NZ``(({z>k}I8sA)1DnPQZp52>)TS2eH&$VYEa(&Kjg@>K!h?u%?Da3NK? z{%KAAO(LwzULV@!^D3OnSCPH63JZ!D+&OQ#a6k(Y59sN&)**`Qp6h4h+91nqm_j@z zP^yG7VF1~%ojBkewWi*Xz$i|g{Se1;rQPx`Rriyk3bW^P78&n0dh+W(Af6zuowt18 z9#ziWju;;$0)uaYzuyO=RMIH@lujKvy#IKSZddad=V)&xSfo?9pwYNKmdL1aJ|#is zcoVCtkCt1fY+lTy6w5v`6WSYxd`P#Pfe9zaKIN%|Blxr4v6v?-EaH{j-FCR1zKrR< zKb2PDS{LI$0v>)UQ-;WV`PoHsz9-S^oqMHAcF1ZS>(1oQX>y$48EYs9zUN);b0J7o zvIUo(q8zNpMZMk+Uh|3$n)~E%4g-m=hAJa>ekYZEuIcBZdC;^2XW+FO!>REHb;d2H z5#04L3+i=@49U5I8&*B;trf{iLLRnVw(%rEE^qAp+wefSgGFPhv&Dg7Ixkc z(?R9J3s&mN+*SJWPRmqTnr5dx+jSE{CVZ);BGqU|@ET&gKLQOM2vnxL2{ODW)r<4QXoUoEoDYrzkmxtyK>}W>-?g} zy$HU23`3(Gypt-o!;)!_HAmu>ER7HPV&t{%r|Ctiq}fD&e4PSa5qZ1~8T}CD8s(Rq zu+zlF?I6*cD9Tl4d0^dR#HG?E==|}t-$?m#k zp_1Pw^N?(%UH%w2Zq1>YgownI_4S}VyRDvsx6D^j0_ugO%??Uyx#pd9d=u*iLXnrB zfwfiyP<4y#63&NUB5R1PEPC{OxGqsS+s6W@4X``2we1toF;`JyT)l5-{7aKZ(*=T{BZmM9SgzP*)e3c(zAg0kXK&)f@QH@; zDFiuqDd9G2g_BE^&>nQ!#dF}Y1MJAn@Xxf<-;VL8f2To{+cyxF#0;E}!OS>c`l`b> zkL@dWJqrwG;(0#a--9aa5Q{7?A3Ll0r%Tk9Fr29&tRJa)xQeuy&%8LINBM;c1M;L` z!Q>!?D4fvEmC(<0$_U3kBj%88!PbAVNqFQ8?@~r^i5*HS%*?Hxz4O)M?0qxh*qx#l6rDu+E|6Pn8=A7qe1c1&UZlB zD(*jY0H3D&P4LAX*CFni<-?7)EF(NF7g5TE2k`tI(yh+hC1**@NOJ8GT2FF~?X#~A zV|#6=3VN1$bVlir7Qs(N74BnZG=ycz5vsC)D-I7K*DJMt7EX=?cG*h8P$xJ)TB)k( zoa2E>6C~f?vaR}{D;L`Gud{Gmcs7UmiMoCg=gu%^i%CFsno5s!co}8R<~74BiEMID z!I_PiZY_xAMH2|JLax8V6Xq|S5C~AJ%Gv-Y@#z>pi{yTClUK`sziox-oiS$8N)7!P zJfxYVDNOJy@5$?z=&yESU4b+Set!OD;2?V6vE3VYDk{RI`R51-`-<>O?2W{p@ z(Z)SIUxqx5#Wa#kn3M2PazOdYmxhgU$Krae`Z|_T>UiRCCc0^A^){x>o>VgHatg<& z)&l;@7&`mKf#V`NjU{DsNr5JH2F^_Ussi!jL^fOnTG?sp#0CW-=cy~qSj%GkSU#KW zb_rze2$iUB84;3#Nan$cv%HZJp8?P9 z>2_+X0L_!SGwxlIS~LpcfvBOP@(TYFh6fYIHzG^nKzXEZL=R0nssR?PgN}s*D?i%? zi&sn!TdNo5CyTI;;Qc53FCZZ|4PXB_V&>51X|B;^PQXu11jVhz5AM^mH?|+-cxHUc zv=>f>F`;N$0(ao@WT$JxewOo9H-XQF|8n0)(A?pIA1mctXG*=a$qXK+=f7b zjIT#h$yerEAaNO)%Jk8uv7nvP70pR|*Lg2WPFV@+COFtdk8ISyLzp0LExA&a;XYpY z0n3Gt#Or!WB1n7?W4Jf9w&jPZuC7@cOtzb?SxE?=pyl6B7!pdcmE=kY8rQBAQMv2` zIEB13wevm?B+Uucnk?`2@$)`xJ6P#`XYrL|KP~h9sNbAx{hPw^n}D?e2eI-|*H~0V zf3lM!msv}y@z7VXW5;zB$cxE+rsx{Yu;|I^;#jz)q^MKYo-e@(Hi)fXP*^e36?c*+Qir%0aV3y2v58TYX-a zFT-oqS1Q&+jwwIDn43$(z@+amRb`9eki#DJCb4~x>E<>&$0i7 z?h|R4wxou%q-lCwe5hJIE=1p%ePCu5WZ&iIx#1pPFZJ2Sxn)_nSkhGic6=!{Kz97xjhwN8O{1{zhL-6Re`l9xLew z5sK?LB1SQZrwal7!d8V`?;}_i;JR_%*}b_*AF>6v+Ukmu<#id#1<}q2FO=KtM3;ut z;B1x0E5+JDO}~w@c8$TMy7VEFuNmX|X@};FY9+GqEbZ zfUz^ODtT*&b#t#6`6@rsr`!oy|5i=DAx!E%Lc(cqi?<7o>1NhP<#{22blyv2bUV=W_-a=^V=gsF5xVC%E1={{_2sjp?lAC1-Bfz?FpUdX4g-p z+)hPAIGr*I2Rgm?@iT=YdC9Lk8q4>fa;tY8Jpq3f(sWTm8;6(A=M8~UV>?8I@*@j9 zX3oKrhaStYQTPI2_jn>GtB|B09>i--#gx;dYN zO+>s2nb}Y5AWoaMuqnwtPD%H(f&C?Bbhi*6mINdl4C;NwhXCR3m+x=it|=PQUoY2a zR$Ebsq1B4Q2LHTlSa3Sn-LCV6df}cP;ODidw&ZWuPo1K-0#usLyN)xdE`9S=y(JJ{ zHXbN(04njeS=O6QWxC;qr>AF0Lu%M6stS&^pe&w?@F;`v_+`xRRt3=c9_x1k&^hok z*ncIRBEZoIe4-x}`9js2WZv=vM9+~Kh-rB6!3n@&$TvTcXAQkI1>Nj896ZyK@DDRe44>@)2I%*S`> z3Q1}~wp!KY_YS&4JrJIL3yy5=!H2b`hLWBV^3q?6h_bu_0)9KH2RG@GUa7m^AhQj% zjh&%xKWpUuDQbdq>SXswDR(^AD-aqW5Q^)Nf7=yn^(J~4?EIEO<0x8Er1d%~BTRHq zC6#3E{1e6G5xIFgnTbugwi?qzfRRvCR?2Dy3Gw$w%jcd5S33@Wo;tfb(~CNhbM5i+ z71Pbv<;H*;R}$`YMjS57KW+NoZh8yZ&xR%k2d~!WK>bl2J8%dpGZ|2H{ZQDx=NmG3 zvnEu(?*(EHIBd7MG2hj3eh3qBPpGzEk=rwYB^n^f+&>h`%C z@N<-m?Esyc7EXiXm~yOA;6DpGE^h9N_iyL#Q6`4Vs;MZHXeG2v zSn4X76D=CsclI<-%eq;7PdAM_C|rdfZNIe25gcx+9P|AnTW zjV|g*tuTnL2E)fPi>4@xH}@!wn~9J(U*@{%(49784nji?!tOK@g-tBqlOMYBv84=nM|>uoOX?>~c75N8ojcrl76W6PGlfPS34n_6rQnYqn~&^Qlm z9sx-wd>^fzT~!PP zgc6BAH-_jiV|~DV*{P~`R=i%sFRiS~yL&iD8JYrNgZ}(p&r&NQd_@@3QG1LBoHl}cB9`Ff3C&uXwTfFiH52Y(@_V(5eeaj6!81D2Il_BQ7 zetfg*99XDh#5h18(6WB;zNs_5Rn25lx^ms9d~(-wzjI3(mJEj$3%m}lW^JXzhbbqd z0^t1?VwdH<0oJHbwhfCPN?z!c<64q(FSUEJev<6#auJQm zQLG{yuxHjIo}L_}=G@>X+0AFv(Upp%687%AayEyEsmcYm=e4u^;LqWc zE0LgW@v<6NMRTe2D4O+mW4n$_zj7ak9MuCe8B8Zh9%yq-g(+V4x0+)UEtvFy%+cx~ zJDV@<`4<@2DMU`hCmtcTx92Z^pW30FW{aw|;TZ9%Jb`7U$PP7^rEs2l$LJyj%WmEx z81h^C9V6C-J6}R$QtL7Lg+Ng$#{znp!rIjgxe_|{r>=IWDNJc*Gg$`LAME;`XZ-fR z{bnMYM)1Oip0o*4Qp-vjU8Uz-sgW^wqghF8kZ~S}HT+0`M!&WHf@Ehtja<@bZUbp& zhU?pxO<2e7x0bwVaT)kBd6_=jYzsMoPo9dYOhoJ~OlL2Me>r}v6=Ej*l#2kM7` z!yxx*WnFXVHJ4&%hrsZ**j73CN~npu>g%OZ+yAQtShrvjG9qjSFTX$G;!HhYX(Zb)^ZN6!A$mB;4A0fOr{xleMqCmt;|NnK(7 zEJ~C4WnAd?yXi=KdxQ+r53uPZckv^-VX*WZVhb^9L!q4NvAoHFM3$B0I0!!xc~sPD zh4q6~Fjy)IGSNeMoKa760=q+Lm7|Mpfvk8Li@hf$oYoj1;};FAJAQ$YuaXw|M38Z%)C|KBf?G%O~!|$BzzW? zG*pyNB54FRf)`XAc-boPSeoRw8%$v`sG%J#Z0*m+h|M#eDXxtTEeLs>bN^Daclm7S z_?i#%#_W9Al=PEl$M7(*+2tdp~-v8=CQw3-|<0VE;d`NGK z{DOjduT!|OQiv2YzXu25qoQihlxml~b+=zZf>DJOy5L+pTD_Yb2sNKQ$&O@eYS^M7 zCxPG3pDwrb)9SG`T6~E^@Qi2H)7R57tXoG#S%Y_7Z{CSHNK!7&O=G`lr}+5H%~%8& zc66tYL1qJ^Q>3&L7vd8~>CS|o$w#2++b3|guqoo8z?P@`ZfhMs%+?AEuB8UZv6WDH z)*#mFT$rbL7~!-}d?}g&B$$>uvjqjCbJV5j-G=Vza+Y_Tx!+;Lqb7j#_&FzSZ_{+j zHJ%+08Yf*lQEMV})-#Mxy?j~a+(Y8nE+OKPvvLQdLN_;p#3}Oez0^~7DSAu zZ*G1_$(5NL=r|-~P0B*~QsZ<>@zzF%@R`c07tLCA_F>8$8%n?Px`1^HFoOa#Dn7C9OcS1a<;__x ztv_nhKZs4h@U(H3Tl|gR-Pz@xCl>pV8s(e_Pwbw_FN0ROn>>Qtrux}x|5`08Q7XC`Z zfTW;^6u&(Mg=<;}Wq5O?cEtcE#TCt8{3%F_tWr9Ok*p!I4TXudaO&Je>cCsgG4E6q z!agXne{2|hh+)<;Si9d#S?M8%#M{7t7LEOzXzwLPdqQ&8hkI{v$^vnMth-`vdIkOA z55{vkgWejA9s{zCT#jnhaG)s^HYj~eh*1@4cGm^dzc3&20s9;hKu1c=P3|HZW1&MO z%KE;W8X7!;=nr{HbmiFN#Y=HKbdpO^t(`bosM-O5Kli)w3i(5QJMxnS0wjv=V(iSW zT)-RfMp6)d;qbW#HwfH7V!}~Nlfd&0Fa2{zK(l=n7I&zi%_1Ja0D|JKdpp9(zc(U|kup7C+4q6rQPh zx+>uoFx26nRjrN3`6j1^v4cvaNkHFI~Yz}3iM3oI$oB>to_qmaSPrx4~8ZRt17AX&AxSVP}LKoaoN4sHyqv}bubE-do7 z@S<3COIqc?r6w~a?Qf*n*XE`A@kkfYbeJ7Or7#01IpTR3R%HZ=oH=xX(6}PlzL&jp zp~7?{hxJ>b11bdE6DQN83)FM2ENwIN3X9ZjxO^nKmd==toEIbg>EVi*2W?|<88ccX zpZY&_h2ydQ$UeF~UC}+glx+G`_$!%fs#8lohP|6o@5G{ajfPT5QI!f++FFN7Kgv}g z<~^!0{fTZ!^Q6VZaC4k#0c>3oT2Vn`|AGf+zo&-Zfw~(1ZabOR0fy4C5 zlhNdzRQFG$bD!4rK;-p!RCGBRdaI`tcUV!Ze8Ocpd3($9F$fsk%hhE;^n9_I4cn$MESq%mO><0yGYFMCA0LQbI_42ms_}2rrKEEeAVd%Jy ztPc9(Rb?fGBn^p|u1d-(#}u3dL-&Ax0+Cuw@bFq*1aGRU8-%`{MNi)qzKCqQLoL=< zpLIZMX8AnQSL(IFGf##Vn{x6e0I;FoLCw-}oJq>m4=;%>?V59h9svmFFR3ms1PiXk zI|R`~=g*zZ&eUdWlI^-S8Q7Hs3l%y1gnflQK%pLNgD%v^TBO z=~`5xRcG$S3#&mPf|)1rgl$R9LN;yi3yzx)os;e0y-GL(pArm@xNJYIiC^6vdlnr1 z5HD$0?v%g$AWOm%mA#xe@93C|f61gLk_fcVoe&*xOP__Jgr}M}w+XFC8R10aj2i)c z$madIg*!;@3obAzWW)f*YOn56LwtB_K6(fFh>HcD-ow`64m*d3b*L;9iEPEXZ(`3B zZ{<>WhWFceT_I`Q_S=8g+Qzu##C^<;fb1dLABBTsRy^aaX1Z2XtjR(!&!ZVb{r&(; zrWTFGSE#G*Bf`=Rm!L2%L|3%LYu1I}Hx`Uj-X>UdIE-ArA@!Xw7&JaoF1NlwCgl5K z{}y)8^&sc+jf?H^dSmglNF=%5v1ClD`(o$)4^@N&VckHI^2X<$82e0mlM_$U4)4sC z>dK&{t^h&lk&|it(HZVD9?jEG;x1@SSSD|P(lq@(148Z875mJD2eH*`Dk-{KShVXP zusdWN=w;il?H~akVZ~YhIF8C8Z^P0&O;YTa@ z(QopJcx9eFK=GteZ~>pL)G$e33!15l!M#VeE{xPSow1{YWSM&0B%tH`=G5*m9{9JC zo?kxZKwI0uURn=N_a+t7ju>=!Cpg$+g;{Byuecx=+&0{3eMPKV*7}ijrFQ$k?DiRg z%G1Et$Tcy(u_AVMlCZa)?o0wq#7*3Ysa0m-#0*u{N$7H?9I&4ZK=`NuWXuqlPiJPS z)5eb>&3*~Kc~ZA*Sh=>3<>loT;WHzBE2m_YS*S7?T3;t! z_j$4{aC3<)LY?Lfu9uTtJ3T1Kh0?%?*)8~~-`mpz7b(y1ijL|Dx1z$D@eTtQG@Cpp~5(d71s{iulmo^qk13XWI^BL~SBan((2FEG^cv zk4TRIiT-{`J<7B7qOC%H=_nb2`|%5se9o#vVe)0V~YntUO#%Oy9+JOVrwk(n6+`)SR_s{tq z8a%E)jd52P@?c4lfxzu6-dI>#{tR+K_bhwp47?6^AOHY{)d2)}qOlfCIH406LL~c9s z^GO&^Ec~-Pk#{A5e{gV6?@VQt3sA0l0>5YI{XNdd0Anljs@OZPIke!DAVAr=u85fP z8;6b)Ic*bF+l}FgrLIQTO-$6($3(wTFiFmG_j#k~Iu6uy4F>b!F2{xX-zkyo(xLj<+q@XHw{8h|YN&Ga(f^&AueK1-fY<(@tRQ&QxPDDX3I3?DG#i z&8wD>p{Pz^1wb-Y8{f55h?I<(3+JjGZ%!h4z zp0UQ8$A{K*&F)i+jfXdDd?P{?bvHfrkR_Dx5po-sN&XXA+cV*_@_g+)fy4Vk$&7%N zr-yI9@6TZy_nK>iUB{gxYf{IVa*5+rYyX(4et>@Li~Hh<4ngaS--c-fJ-~tzygF#4 zuE@!8KgUo$eqLRS|0OUpMIOQ$6~!7S_(34JW@=8Z5_!(`xLDX25Gr8NaA(HOm8n3p zhqibVJJ9_mWvywNMS6MYzQJ+pS2H^Rf*?HSl+%Ot-OPy9dUpnP1)(y;<8E4NF=+?5 z(bullb*n1{D~ozR`E&Yo=~NfZIj^7CcS`}ofYIu5IP&QgNJu-TE*G7(XmA^?KCoj(Li{XZqkg1@MoM4?< zO#dd?ug@9=u3zvks4qF(gE)u~85sx?zvW9XZQUnFn6d~BSr2h!e8h1!hw_g7LdnDKW<4^;i*=9C~7)tj!_XHgFrYssMLQk4)A$?Uw=nMC*B55o+zi zMV>wSjTZ+`68^b6YkzYPm=NM&8-X+b7V(KeIS98q0i*a4{7I?5{y$=rQ@6D~^ge)_ z=*28a972)(aKg~V&o1uNZ#$8bKQ|}6?Nr{D>sLp71n%v=)TcG?8-KQuKz#yKFAb+0 zrun}oUyAV(x7XNf#yv%vjBB<|P6&$U%zPkQx(!`jImR$n7VRDu%ABt(Bkgj1;8+to zJaK2v-v!i3Q6be1DH8J`E^wzq8zjN;pz2n-aj*sxgC;@dV1XXLPoPsV;k<$|8$lF? zy|&MX_qB1wYmeU|hFvju9`v6>8?FXI8O~{wY^g3-ga_1)hAV=3)VE^ios45^x9RLr&}`lmzG5SN_#m^) zEKf!JjqTLeDAv^xqD#hjz>z-MPh)5kfrmo2kE^@mox9z>>okCyi87`QqRR5JiB@Qc zY5k}IW!Tou17N?*Zib;e-CuKQpe8DH>m2^tUM0hkkxU#BPNXb z(c$U9?Z)0RSo@Q}_;8Hj5~DeLocs23;hThMdwSe_=MF3wD2!szo~o&vrabcWgoF|6 zdXsF}P7PpI@PY#bC@m$VaJT5%<+I{o$NdN1$OMM!-eL*ERw8;s!`=Ixldk(?MQl!5 zfjckaZy)Z5KcNYV<_=o!`B+n`$djV#I$#yfO>BBtTR943ht+I@Q>m1~`hvR~=n&=e zj=wJ^J&I#xMZa=7eV}e7_l<2njd(giyWH`LPt8PC${d*siGMhV`5MW%Z2CyWBRAp2au7*tR23)FxLX zXyoy-UjCnnyl{%IIfiQDmJ%|0FrK$AL%(imlR6#SLRWCA7ID?*|8^ijd442Sut#D=N%?i(e33nz(P|>AK86h|_i>mL z?snQQN=*y3ERg?qCv$$K`0U1kU$g%b;l`xF|;;{nq z$-}R!GlWH3aY?Ml8|1;h`$!DV&*QzSMp7#uQ}>6xB=nbUySVt<&avtbqqzu8P_v02 zuhiSXk38wxxbHk~JF;bfDXyKr^EPeHM)ZUNDmlC)lX!vc?L|OMuIPHJSp0H!V{2j) zeQ3-59uxU0y_>F=#k&TxjuW9M6)tD)oCmiEtSNMnGV8%sn<>5ko*_sT?zd@^_y@JB zv6G76hJ~CQ3a_|IMDKY4%7l0C|3Fk(*htyFYm;bv|JNg*7;|6$68b`c_JgVEJ)Vkd zX5Ac&uMic{!sw9jNBX>(z-6&^<@&SGxqPKh!2`Lvy1GG~VDg-AV`O9m6J%Cq-FT#v zwa?s;mm0xaR`RpY#?lNJ@yM&@c_uXg7u-h^ttpP&WP!t+?;Joijr&Gfd6U{nQ5AUQMKtU> zz5Y*<%jj;;dO3ci9P0w|;y{^AkUYC)y?h)6$=-YBTQ2x{KW--L zzrW;AWCI$Y)KKS0fZ?>81$?9sTlgVL9-(1&OaVw2Zzb``xlz^|Tc%OwIXCDy%`_)A zEb2a*|4Mk8-nc<-!}FK@{j*QKAAl7J9OD&aeUK(XQMGFGd5kAZ#AwPR{gw4bssn@eCF z(1q*0>Z`ch;;Yi~)c8xgN|&SG-ORxX4$6*pT|Mu`eNow3efKaiyV?R|vHAJMK0E|E zyEdA3aU{N^r?EW=PPF%T0907b?IkVj$WcF%1aH%Nv^?|dR$D#ACC-**gmK|EZ?JIR z%6%CA)WWpH-<2T-AI=U_jtQp8awkP>%OG%Mx7v(&1IA-Lez7>aw%e!XlGYBj5u8mk)9AnHnhs5rqMGaonav02M4 zMC{uWKU^NdSY{a!WG^m=-hDjGP-6Y(!mpllK2&_%-SI@vJbsD-fFk9<>QxVZ$++4H zS0#C{2-v}dlk@ntKkYnh#XQewqO1bAe|PSjMjBop2%a9eKOo1Uv-spGCUnFhk`Sd2 zS4^kr>iahg>nz^i!g>;^g6K>Js?+u2HHR}b${NPa8*hFh(>b;nV`Qb^>3(wN6N_%n z!CGcmceJt!^99GB$H>$+-y|nYzYFc6q} zWA4TGJX2n9Cha##SAqIOk=|{(om0PZBCYMfqyO!UZ(^zg^i2^<2#J@sy0EM&E5}aY zmFt%(kVGC&zHo~-LzZZ1y6+=MG?o7*98}llN;B_>kVjpP)&WKDkp}0-rM0&Klu6Ka zQ^c_3+JIj%;b#hH^7xn2%v|r+kTlRg^nrip^u)-3s!&7{hODj!*1;L`4UA&7 z)JF$jFR}-jb-qSX?G}e7UQAJ zMfEY{;mmY#u0NWFGEpp)WisaQ5iP_JR47s6IQ$-GZkfJt)<}NB8L#Z849c#SzYJ__ zZ0z@Jt2d*gSp&+@f`e|$gZhDNVsbOt>eQ67#y-*XRztTi^2`(3uU<9PV!DPzh+GaF zTSEo4yj_6Z6qxO=7bZUsfh3MWY})>n7*Y6p?+xC|s{$5Hsy$z2lI{i>gyb0CdYLq= zzbaB+4LYkTW+Oo^B%0i?;&ig-5 z_(ce&`GS!1Qs|cMhHltZmo&vtA94Br5@H2Cd!4(1w&8iBVmeZ?{ZMsD^&^&rJH3R9 z!_Lp-z{?IZ8upXvktnRYMG5dGD+cU!37#N+HEYaH9njsprN%oS86w*yIykYE}!T1W(#?YnoyG@K( zl21NNZ&rD`y*&Rj<)If<;#T;BqEl}4ykv|h0qGk|O%&^F`-yf)LKlNH<3y3?*re|E zSCt@gZnMEzP3eTIwV)3jTk>*Zg__A4IS@(#hCp)6{xdJ>KQsdwe|1REN+rvw-aZ>a z6t&3MMj89Rk}uk{WPL-9{o|GrbBs*nq|N~S8l)+e>~|Oy162>sl*Nd#^38n*hF;|g z1JmeMPjAp4J)e?Doovsx+E_GphKG#xsBIJN_-^C^mptP*ZvsO?1@9IVN3lPhH*6$~ zf{0wEtH=n{v~v3b4JB^eZ)Jk9u3w(oH81KOM&0dRNdT^<@F_H4x8LqADn9+*Je z&PSUtbvUuPIG7M%@uRKZGOU>v3ZJ@vjBA(Rb?xxSB%`)*AIa;-(n)si`+M zYmLWjt8}HeNa~Cxu}w4rCuN-^36YujS{ucRqH*HupxucUUm5*8Dx2!kjMZOF(-YIT zCbM_!jZl5}wmHW7d@?{cNc+AL(%bl2O=F?QcwA@3sbIH%RJ#uL)0rDLy!4`uGHdt~ zrTmgQQk4J!DoQX5ma(DLKM8J7{0P)st{El=`^cB&R<{K_!u`hT5^#g7i(H|gMx#=G z1y{_}(elm^(#bOT*PeTu`^T%EVIYx2FG}H1S{(|ve9N(};x)UR=J~dbVOf)*K3r+u zrG!Jj$7o#z{vTJA>mDI7xktuLzX=j~-IB(hOjkQpptIV`%zSk8_;g1*5%i$9jE=NE zNE~M%z_U4L6xWSB+E9j7%gLC&>2Lv7gNbgY!=%y5;Ne0{vb}www%Oe|Z_WEQ92*@q zEhMOU?pQSFvO6DnkNzcDwSc275iErae%AJb4o*6|DLk|HL+nOQnU|UlDHR5I0j8nV zrmr>B_bv|~fV0K$p2_XpqJy0O(*p4K7%i9gkqiL0wL-|p7g)KjOplEVy&Kb(B}LL0 z=BWqsQ-_IJTbF*rCw{{gIWlfXx%<=->cW?9K7(j2gDcIeCgjxo=; z#9FIYb?gtmti!!J@cKC-$Wn9%ZfPb?EYrCVeNk560A=$n z**c4LosDv~1>Omr3u^sl;w1f+?0lb%xA(Ur+E+UO z)wr&D27-9y`5%cccL(O&1WeP*lkkyBn$ZB5D*qKtO7YD6P156T(g_e0MB4*EIcMn*`u9-g66GTt5)4cby?-<6X8IiST3Q|YxJ1aaz+s+a>$0&0~tsqKW zMO#>vR)%8Wj8P)&_#bUfDAY=;=*Jr;{l3k$(!+4qlw_5ErdjlA8M=&*XW>b~gcx=x zLWJLoI)tcnzZA-cu0=S|v#>Y5;5IFf@o;wS8u28Xww|LDp|Q2gC3FTS6^)Ocxh1yKW21c{lwa|lla&zRl8*_L9HU*Y*_@J z)vrceqq6N-6^PrXCN_k#nP559(x7UvK4T)m7cDJ38k!~JOg@b;*pxG*P+Ttvhvr+Tg{(- z>StmHpq%DV42>Tp@6%Nx7KKBM0G^!3GD)#qR!OhyC4tjp*@5iTEs1X~2g%Iq>GqNS zqOLB<&by-y%P`_JE(0PbE_v6_2hN;HN@bm%^I##Z=Z8^5Osu~y=)s9*ASFe^P&@5B z=AU}WK%jO;`xMh=0Mc1a7GTG0Tox%hk&kNJJTROb5otT?&TE_?ob>UO{}rQD7P!(< zP+=Te#%f&ZCc-Ru@B|=TzwdVr+D`s+*L_68cZ}WV=gO_E=9}cNOi{QW=_~sfO+)LU zHAasn>Z@CC>2uyVE871(4vs{SiiD1V&`$z{R%A>!02a`QvUGYAYiElUmc(QI8CFCM zEedj}9o&rzq;h~J7dfJ}ZmrfGU~8Co8Lx_%zIDp}iZhtuv$Waowk64VJSCMCP)%sACZEgx z{s+5%U^K{c;6-0ms- zx>S|D!6z$;cVCL;e)qM>^(3HV`(Ipg!HUQCea$|>s49n>$}dyh?QD#HuhDZ@zAXJp zlnJd!Rq$`7h5v5cY{WnilbCuJ#VT(EincedndjY=GMA#8cUd%sEXnEYep&=~fbsA( z&Gq!B4ZSzo5a~}IUIL!onsJX42|Ba3hoIA{ZUK#_Ef_&!KP=5D9QlCJl1V)<0= z5qY8%xr16pwwzeT*t@2E9U7~A@u+LVMR}C)>_BQt4lHmW#c6dGcY9;(g+OsQx6V0j z+|u7ra|{miK4-y;Qk`O|nw`}#Y}G<;A&hYbpY<0);5LgJ)12Hrp{@#Dyp#mGF&$ep z-(qkbr=we&-P4%QG>2|??zaN+4IGb;zdD zJ+-tb1Vz+J2M-;Sml6N-!r`l4?Bcd9wu0 z*$cN@UUWChy;q{)YHz7m&J7Y6w`r34Thi~i-nG4y&Q%1e$A@DA6g;R^WpH$6MG#aX zFpAdb(zYBx(T&!6PP@3j>oE!9u$iplpkO3}uc&M1h-&Ml&*e3V>v6dW{BuQGRHaSW$D^y$NIor-BAhKRf0 zGHpQMpmw+=FpmWAp+}%N1IG9PQ>UUMXhS!!fv5#f+oSBdiDFjO`zf%|yPVrwI`3TCoMJskD2W&S0 z$(g?{^*O68R>~Nx&UMZ8vo;?M1J4u14}J3Bx=dKJ)+WYPRza5wcJ6=`?Edmw&$xs> zx*^A6OYwg~MUGMR3~!t=u9$!zGav-&xaXWKTOrRfbx{|2$*Sd{N%aZLs$A z-PHA9J*n2A34%x6RY%BNKHEf?*kSf7tI#`N_J<-sDUk&I_?woJZ9akJm|06v7`@2Z0)t7TL%mp#%{0XDkvi%O-kUcHG3dMdJ~% zLq1wSv>dfOUxCusl)!V5HhU`-e|-4OBbhrc;@=h<$q%uH5(}``TmLdtVoANf-m{TK ze@A8;E_3jL0C;U1egWvA9YN?6P?r+FkgdFEle^yo%UY|Kn9qJckEPp5K2A3bSON%Z zA={}+tJ*x`YFA=Jb!%tibi>xenszJ2A9K1+>znV@To zha689q;B=Phb8Ra79>J-K2$uESUvbyfDh*Fo{U3mYKGpV_Vv(U)(fC9>#RDWMDN>k zsvj!ey)?(!JlaWennkIAnOujx6w77w>9P`l2{&|iqYYQ0YWW{DQEDo(7ILcCJpq;6 znS953?}m1SvO{Lsqq>__PW&$YOnthzmRmq=Leid;-btr+YcyL=gb=+p-2#5CZ^|+p zg6U_gok{G`nsC7)=yfB`OHT``*rq-_7C!f*+ZfnlVfXflQbO-n(nm*;Dcmpn+M5`moN zTX^zg7yfFP$HxBy*6Kbw+M6`#GN8!AjD#_W9TXWFs(8kOQ)%r|BX1db%V!l3a;d*z z^+@Y3{g|X!nz!vNBSd8OK9(d|1AmSFfIJow3s}Z56{8PC-W)P=2a5t9&X!31E9{kG zD+!+ygz*G@o}>k1!s}0;W};jScsDEe1`O@Kt(J(7F$^y?`Ozm*InyQ$TNzeY*Z<9S zHy|b$6V~TvFZai(#gIgX`X9gC2MI%(20a;AR;)Oq$r7J@mDcnbl!`T#R@> z=_O`#pzZ_I*krC@a50x@&$|?fWXGZq3J|0*ub$F^lE@az-;|9yGRM!%GS7nYV;4yb za%C5xyQ>vnD!(=ZV9H5A7PVYdRFp9z=6S{s!%+cOtt?7^TB`59$~H~cfQ)+>D0n+9 zrhACK6J!Bv^3~10H1!yX9p`6X0n(o)L*c@LX7 zU~rF8L7_eFwBC7*)I_!zgsbX3tGze#$Jnxq3w4ot*@v@Y?OzYa{6`fk{9|er91}q8 z^Nlu>UZO5(+QC{HYG2RHpdR?u8QmVu%$D5G$-`_w9{Wp7K-uiRki4k?LxTsOvD;s@ zP^Gq0pG-{U=NPm^S~r*FPcRpi=0Ec=tEaW|+Y`UQwhJ-p^2qTT7JZI%-@yEucE+)* zP(O{@t+PIs$o*QNugjnIoZ@HWTZ7c&o83H5cUQaAm5SXp5W7<+z^l@b+Mf+rR4tgM z6>0b%rC{HI$DI6WX!A;t=zfBD#h~8>y$5;ts|>T|do#D= zjkTEJ;wHdf^IA%`QnwyT8O0-@sQ;^BFjTIymSs^vrv=)kznwH=PbJ~Dh5xukw+?h) z_s#F<-;0cPmZh>Et#wQa9=&>fAk~oG($0qDYmNBMXzR2wujBKB7}tmHc<;49;Y%O0 zV3{i@=|=oiyS{t~5Ag$8OO}c_U1#t!Z`$U2UN#@iZ&WGf61)k-UET_h)d-$T=Gs5Fm zUo8m0jm4)FW_3A!e>XnbUgVg4CS8q+QIec?uWC!yEfu|;XmxVS6?^3rsXuxq&YSEz zGZ7W(q#^A*bMk^RVUpiyk{!#kUrZexDcQ@xL%p4Kbrp{R8DIRg+XNs&oo)JAs*Pno zo&7!bC*z0~C|1Y5Qb@o3$}6(#rbA<%)`e?Y ziB9~VwTLq7JA61eBlpq|E9HN~Qk-7JgGp!Y0 z4$%&=I-6s>>)nL7P(uCzn>lpYUK$+6I-I3=ACbtaOrf|h#QU=5hZsCill^!8aXLj& z#al6rh$(ih*^viL?%tjtd<34cKIR*dYWorUc>Ep>^bA; zQr~xNV`pl5eHce&CyhgAlFb~J6(Ymzx$wQARQ&wRT9&}Y(MZ>u48 zkUEEs{zQ3A%bn>W{`(0y#M% zQc?xo^Hq`&r#ua(S&ev&pd1ss)31+t#{=iklTI#xqk8|I>ZQqkbJ7kT`KJkEToH}e zWa*ie3nrF?VevOc`hw9{9yHXnv=;wsle!WPhyN`7A>!ktob@FGL$dE`B9!*D8EZ#CDu6Gif(TfM!)7PZGkea_HjuU82kx)r@ScyD#8 z0C+{TEe33?SL>Rp@Ri=+151wxYfQGri&H<+2FvCLit@4*4(Biu?%RK4GI&&DP^;FlVIBU{4g2dsal z1`>F+*8aXgZr4{$BU4$(#SReBb6J&`C^oj0p<)1Pt;9#D=7;~-^T8>3O1wEG`v_kB zE3$+M7Dh-bKE(fgPsVkx$E3l{y`F~ZqV_n#hf8gau!F~2R_T${y_L4x{*Y1&}o!q}EIk zINv6Dn~b=B+4|-kdQj0a9jwDVQSPzf&pm$eOB6$~DLb z7x}TXdnMS%C2?IfuW>$Ku@99m^!zj8FoilHW~E_LXoYi`c85PVw_RjfFXtaXDR9V4 z1IplHXGslwG?q3tsKpkz8eLh7NfT}2daTiyu=HI&@(tVRKQp6#xC?2%z!nl=st)P) zH0iMMsjCKG@x|v?L^ouvGG*w^w@u_rCq1V$4og3}?{HtJN85b{0vC0ur67;K!x?BS zYH?Q{!QO#tlgvLin20c0kz>_>_!cO&yqNWpp2!3xbOpIqN`C)kI%4C=;A3SkFG9tH zPzg;iT;%wq8GU27;o3T-7&e9e#LE2mo0t_dS+Kfe!}q~RynNX`x<=nR zLA$#+hw8ORZNk8StFvVLib)E5szw;j>&0+IkbTr(T+>@qtVex*@_-=J4iXB+%+*-x zco|IXA{F8Pba_1H%(A8I{KO{BB(q%zb(-^L219f}m;}aUhk6OtqlxblB%IX6?2!fHjLiU`Ijp#3r<#ji1ov zIBH+!wIZIw$m%gNn>!Wr>O~}plCDaS%G4S*rx^XSfsF+rMcN4yHjzdPp~X~JrkZ3({4qI+EbxsmFW3Zkt##+SwL`80z+eCQhp z5Xuxuti2?J@7fIM;vmV#=e=ps#W4&UP<1dozc<-Lep$>qu+j0b!sKWCm1)m$Vav2k z*O9G4Z3Mxm;*bOnxW%`Rn^UU^qDj%lR0$aObFYZ5gu|2p0>$k>{ntvtM5<1;f{7-E zsU}K5>04uUD^6owH+C_h6_4qKJh}HyA8xSx?)n7zRfaOSm`kV4brYfLv0~U$7XD7} z+1@6xxiB&x^2)5b2xK8#j{cSMo*&%yM0sZpn0er`t${$|gS}-7Knd6~kyb}3b$JEv`ZOsh9(l@n7J2e4CMX!iIH|MQ|fGwsN*MZ%QBsQx88 zX>f@Ztw40Y_Pm{z5nw=V8;H52HljM)GDzMPO(lwW<1jgLU*FqW4aiepniI_##r75} zGa+#wHaO0O9L)1(sntVA%@kMtgNsZ*$lGIP&H$@WX)hu`IkZB0N32x{-^uR_n_m9} zlFWL#vwZK3NZ9F+5nLsIH#l0BqS+NX#tEDo(VtVgh;AODm}vw_DGBfy!x6d z`bJwsF;hR4txd@ha5x{&rlk@U^-Q|mLa_*ta;M}`%>A9nGk4zKjULbp_mcg*KtYl5 z_qY3sZ%uwUuiRnFH^gEJWQU$X9-7m%khjwE6A@>Aj z!hkg5+%W_SG0s4R;qD6?wUiIuB@UvVjk!xu7Kv{r9WSjeCb&GN+_V5=mMd(ka%2!4bvk}*BoECmP{j!S2| z_c!Nleis~4_b0M7r;fl|ZRk-CaWq6(ZT#ydVU$Q?oMRK4q+4SlFY|_oXOC>sE-U_S zL;&*Mv}Il7;`d^`iL8-yl{unf@3MrP)t1j2!+%YYe~xBen-cmkXjDpo6Ekdzr+*vn z<_ktPLZPD!XN-dy@RtbYE*WRK9@xLzq>%yYI_*~d1;Nk(XyB=(TF_9>qn4GZ93G@B z`%qTI_($Xpw@;@Bd#QHZ)TR@ZdlpZun;dzr1-9co@DRKS7Z#gnw|HQ~}-blcv49pz>%gsruF3 zfTi%i^5Bm7lHpa}AyN==OEzMsJD9#dQQ`xd{P5mql}pMBBp zjdLLMY`7a=DA_XRZzszJl(cqv(@X0w^yX?YkxNS=laEs$3-CK~y0!SWf9n!yvpxpN z7vN61E87n&Whmv0Z80Rt-x)eVHa3c*D6Zqy{zwGdv^2(!>@mS`@75O^%@=AtdpKMf zSNOEBRZ4ABG)96sNxi3mkgzylc6*Gok9cf&XS zTjZ>ph)nr85cGoEYWjV@%H?m=%U^DY#qf zhHjcuFSi5#(HG!^o(Xhi*YWx;#BJ! z7C$%B#aUq&U)&B5;K}8(GflW64%&mUW75SXqQmO8j^4<;6~#_!PYl}_hTx8e**pzShl+q?OL+KbB*I0_Q>2( zka}~Mz6E2h3vEu6Qv_rqMJckMu&Xz>M~`X#3j~Xp-BM@1>sw>K+_5#R+f$x*69{(E zYgzq!*R7cV;%86^Fw-qES1Pv;G&rQJnp-z3kgiT=Bd+thIkUO{*>fLv|68B4SLv)J zh39)dHFC8qI1#}c#CiEsJP$VrI8H+Ce>R_V>AyJN`6`i|eHpd~<;G?XjE-VGJ65Vc zJj6Ot^8qO5;TQL!5@ncJSxc$`5W{_fy3+$@CFuWEx$}QofKte)6|z}5@t@m^gJG6T`<%;1m&E2a+ewqzn zA&3;{S1ey46PxnE`9IJ2)Ko@Dtuc0Q3VC=|cb=R%!Mi-;cLN&;14a&UfV#be5o?7eEGEQ#JwzU8Xoai3_A8J7lkiU~7> zXkG=&RP*z?AJRLK6T*}oAnh@kH|poJiwN>_`&ZSjzZt<6;2QrNARUc{ZOUV$awnw} zUo(d#ROq0Q`TS)wCorVO^ijFtF@3-G_U_1TVXOGR&;)W68j}|X)HQR1DbEV`q;;q( zLaw8rd16Jq%`(m$;4|V3wp}W4OkoJRq;oI`9(|)Ve5hm&1 zCCZ&gjMJ?UJ*t+fxb#sKNZZNY-X`>PAAr*kf&nPTvZayIKT%l7bR};Xg{W|oZ{1iIDQzf*}G+crh4wu|itBX!rmQ+l?F0Lv)^j4S2BgLQY+$SQ@fBgJr zEwMnv%ukNEu`(l$np5eBA@FQL2Cf)isTJfr0-ghaECDK7B#`1Qo z^F6MpxSV`}3}8c%gEP~z?)%dkQ{h6f6)c>auO%|xVgn*mm+3y8IU~g`p?=K=m3f`AB$CSe^45^13X#5^8vfBwx@uqB7{rh zybA$!_G-;<=!SbRV;0>$m_HS)Nn;kTQxDs8v(&6~!i%cObScdz{E}=g1gUQ+@E+=G z{Bqm!wy8yb-E>6`3#lY2D#K>ADFsm#!b128=r3}P>SVe;6RQhEefg28iejOCK_Oar zwsgUJqxz6G`Q#<;Ci+}6;PdxVzmw&QKKYm$;9RYGVxrW2+9Ki2E~k-_$6 z5ho5rZCP)x1>`BZ$cK){*C#fnF?ld=M@zl*Mg<3+byo88ls{(#DqsTpS8=q;4s)sj z$I;N-PdCVV=XKpaa(BqN_t_o#AlbGwOkWOCwemBn>u0<7aL;Y#!S9kHpoq7U2Qa^T zW2lGB64qk@*MmNXj19A4UCI04Z|XH}4Ki1$N@=Exf`)a%{Ryg^gmGErRID}Jiy#p2 zSUoF!-qv#;eqB{Q1sK!TYOAi%^n zw#S?UM~*o2t=Z*+R6q}1Xz(j~8RQLyV+W&##qrn$wbU_RWvCX0(o0@b;4T`MIIe4M zQLW9YJtvpsE>WPqSz`-Oc^d&aCQ7!K)GIZGK@K!fz2x&5dlTFGOogw-g)#Ge3)I}6x^VYPJDs?v}1xD_6C8_hIrR&z@bTEsLGyO~$9%pvU zeZc+od)!>xCw&zS*xyzM^*OJ@f{lso(O$Qi@_?Uj4pa0Xg{F&??H*Ce8=HNskT=m@c6=^}-}9u3!B z-Ef=XMfVA25SVrNMEJrLOu`j2DeUh-Jivv#%}vTd=|oT2AT0VCI5ER71B9HGQRVtGzE8)xao^zlGrB3J)huytaFEWNXWvo+!T3lX;vx{{F1L@v z^c}m)aCq;LG2dIFY^kXIwcKz+Yb#ok7L_*2{fWddR0>F6H3F1-?=e}JKBx)>*auhQ zASlU0hcs*R9a~zLF|49{gTun25O!dxwbz}1wEpPH?sz4SQS`{84?m$>SMV0ioTs+{ zQH9A?Wcv#V^ZQ1%yEpMun03~wvU@ID*I-srA+IYr!&c`Z*T3B#|4LnRyIs35UaB)G zlB@jso5lM z*eKNV^TmS{LhsVY9vYQomN*_1WbCqqhNnrDFf!EpTLx$wO?p&19av7q5H*R|y)wTu zJj~foH2Igu1TW(`&O3hBRUdoan2KhfOL<#8f=Cni?e(y5nKvXVoGN<%SkY@RkZ`2@yQe95*EOAjJ=7q%npmNmqqcoG=j zp9+Ko+ZCpLOhxxv1m;}V1qf?G5@YM`Q-GSJ7RSg>=RQmwEE+ti^GeS zPngx5s`fPdn}cQjSD?AAqkn-6=NV(X?;q0WO4q8>f=dYz1!Ie63F!+^;8YG@sj7m= zZ{~zeuT+=~yEVF`9-uL^-`HbNw;zr054TvFJ6r0LC!JRK+*S|M-vf=8ysHDoo>{4x4PmkEN_aE0nZ?ei? zMa(`F5uC}!V&-FpztHLXJesQRpdKYaU7590eHq%SE|4IjI;jwiLh4X*uRSpRu2Of} zmF{+4G>3Z=BCc`FWF?~TgS<*uZ;F4s>BFEw`I>YSiAkA7*FW6g@65s>I@Rd~4!+JG zKWZP;Kh!BLwsfsv&Ja*k)=+Oj`oG2aN);pgk=T_#;QTmCz$B>v0{YWS(Li#C!~(Uq z5!m+kM|P=8aE_@n-w)hPL#te3tY~CA)ft(8t4MA!a5itjn{vY6J+UPEe@_OEn6!naZDSaByyJp<(>Q0Ak{j zb|KG=7TO%+NU<>%$AB!Yja^gmCuHj;qp>k-=UMZNV;x(eunnFl=lR?jE}m93wC|!$ z?oB2Qx_URu+Yebeud>DqM4kHu)EvPOs5NH#V?F+Wz?78eV8l%v!f)(lh7yC!v>>f7 zvdtt~W+$)4#FGv#pi>v3|L!CUb;CIN#LH0Lz)zADX%P`R&nLud11%<^JVJ6PN}Y_g zd^)8xuqrCZzZpdjL?y^vAc-7jPAjeTnVXkSF0J5xUbD&lDNvCwXGw3yCwCz?^qP2G zl7j3r_MFDaWrX0zVtS*_@Z3KRKgu^Z-dd80E(u_) zL}tFl30{FyteVC_(`DOdc}r@$KDCGb4^3Yg7G>A9O-iYBNHcVYzzs+`oC0lV>Mk3(h$y@kS@tO#feKYvw@omdM_O{9@V8bzB183O$ zSAUX$d*Kb~+o4V&iDLmmQ^5A&ZUg)4uo4eyzV7#jL?yPf=oXhuC(CsvkC1nMuLO`S zW3BS6TwR5RmJuTfL|5+u(@YX7)z?h?vBAensWen3b zSMV$6L?ox8RFJBmhbA6^VRgGXy3=knjdCs159643QL_hPU8pO zc8=Z~!iib6wM!(&c1k`dxw-e_(6Tc>=E_vlltz)2XFK>b`r~H}R}Y zFG4TgjtK%ihJ{q?c2gA3AEK6)Dxy3|-=d8Vxcroy2cldY=>$B|4-$25Bty_W=%H>g@5F8f6P z^e5qcPD2CV)7_9*&Z06a8PV#%af_gWT;-veWI#RR?3avWRanh1p8GBa=(e%iXve2Y ziBt4ELS-HB!M@AGtZ9cCAe#8t!xWJyZL>uDHV0y9$FP zD+`)vjH@P@jfNEcN)4t)!~HJDF7k49vRP$?4mm(eJ!=nZJE0x$#mKaQ7kj8wn4JrGzxA`h2W)EaAR7FjnFuV@1V~CRXqC74@J|87{ z)=sN3)mzV?#U$6^y>UOTkF1=F3_^){okkZO)N0Sr+_b&B9D6P zp1F@ok7cl6;yIIDrjao|K2E(hwpH(gnT05T%<_!+$uERJK;$@DgYaqct~!z-fxuf$ ziY`>Y*dk8YNar|(1T98B2uKe>w(h;1>I+Ydh`jFR05rik0d3s zBE-Z`=mcHK&f>NE%V5a*$b-~CM74Z{fJhTO4TQ@D{T@u5+gJ4W;>}*JKjz>mNr-yT zC>hNZ^m~1xzEh&3=&n?nT`L5)UG0Go+i9}F&szo@f*FcTV~S9&{Go{K2_u|q|I#jc zP;z1SNCOLHNfN`#z|9Z@>r{%u8k^z`YaPTQ4Ee#LRN2b$;h9DNRy zU&N%3KYsy73)5=wjmkjVfc~N8#eQ4UT8q*_m*&qSeVQ`pL>8w0ysjbMBlO?0wZwO= zni)boywM|f6Vd`+Ula6_5**7ciXnH0wYL}#3JTrIto(UcLk1Ie9-CojB|1)Fd!LfJ5q=OnuhT)$Qb6@*xm z`2t%c=6Z-kmh=R(s%1vBc-mAd^ z!?;)w#poo2&hXx@`mxb*d%z%K^j;Lu9I|&7x^pZk)R3qqZ2!kZ2HkdasrLSCEe<OMc(C}o}IU45pU85K>%@umn`j|Mw$VagKiIYP*k=WxD4D#ymQH4hLGu^AfLqxwX{P$r9r&>{Y*T}ImR zT->d-tuTcZR#w!ksf#-bP)FaQ-&b7=7zN<{y6?MXbiLKKnqOh!^Yj_4<+~l2jt309}nPV@8b-OsL=P z2Hy}yG01GU`3qx!njd0Ig$y{YWo(jzpd{yC;^dx9+aGvzQ?wBD1M%ZOSC9gN)?YOt!Z!MX6-61V`b{(#qeE75*E_aAs$-KM}BpsrxJO*Joa9{qats*jQg2{IM%sDpKC#&`x}Yr?+y02~S43E+u&vUe@>R(!w#Sta@KF z4Gx89U24rpzDR4%#gjDsdJ=B^xG}uI+>evupssg>cwCLgFgFfqeN{TUhnK!R8&=M0k&0`Y-GH)B7aa20Et2{8te_v?}cFVKrT!Sxxoj8CCpPl5K@+YDS6qKAUuz zDdPRdRz0(;HfAd=SUVyC!datZbav6a5=t^!R#)F+7B~Cq;j0|6uxujBlYy9;$oj*U zVtSGM7DsDTJQZ_PZB=>TKk}kYGF&yfFx?^)wiw8{poVvhL9Rw*^dh|ZE0+M-`W#N% z->Zj?k(e9@By*x&uh@}s^QmiJ6rLof1#Xhp`a{#g$srJ!;6d(>apjZT^gyktv(@a| zDN5YdxlT)g5fb_K7X7zYR#tO&<}^ts%CgUdeVboNYT4OyR4NwD=WI+KU4g(7c$pkZ zZ6sT|=*I>qfdyuJbG$}d*`!?Zv$noIV9G<(WD2I&NTio5%{71QEzwWwEJv9ZczkoS$5n6x}DV*+07 zckI8<7ITzcGK`r|l)+B$&JQZK&{Uh+dbd(AtiY4jVC;>1JM#=to{_JW^ zW!l~dHsL65YE)B%T=7YyFf1vaXMdYBl>oSo<&8~8ic6o}Og|tnP4dMk+Gk%kpQVCDO~&YbA~nO>_S+=aK9;&^Q~c zZfvwnQsOCt=eeZA>pkUIc6vd_ER|g611-k4!?bY-2&-PZ6bJs((%>9HzH2{Bw1m#W z2JC=lq_BBn!+|%SIm!>j4%4%&e=@nS!cwE5=Ir;OOV+4a~dbGMtW^?J+iz; zYM9|rRPN41(kfl^B-U(7EIC|ex#CU*R=US`Mx-J=kHwXrjx-z^GnnD1hOnUg{OM{9 z0%bfqq{tk?R#CLRG!1A;5PT>9v+Ei|<&~G{X_AHveZA?c3(#gzBn&SghU7~MEMs1;QEecW*$rHQM9l-em?jWL! zH=6#ZW}7-6)2oSUj){{&AI4Q6_+!4@(z zCt`?_AR+8l(rqPr`HnnhMl3R3tG$e&O+T)dUGl7P!@xKuQ8iJ5q?di9*=vQ6#{cQY z0Fd1w{L5)$hDD&^%S!`j6_xe*z;QmFX7;Q!SA({Z(NLWKRYAA2TxnR)GLemurU(y? z=G58GA<0B}4$V##@iRXKc<$=-)g9lz(ncpuWg1e@U?-9>_$D4H z=2goqY4Op|{`UhCC88}uY^(WbrVO#J|Iy0!z(1gu-NEPQA`5wn%>u%9t-POq1_?Dv;1bL#}*ZOV$)4h;Ia zk_y9jNvb4V(2^*kz+=Uc1@0JC`I4udu{}4TnIRRLxE^YhC0CJVS)9Zt`P@`;)1paQ z0b$|Szbi*Cc%dZ@i69-AmMQ&r%Z=k)Bd?q-bKGP}6`3CTS`n5Ky5U4H-t8Oe^kf~i z?xnbolwK&AK|1fOaSQ^K6}OoU9X>~dZo6}_{bfd4e=R248UC!Pz-N+_dT{pNPRJZ4#%u;fU z>xG>Q+q^(OsQ~wZAzZstRi^mO?DqQthlbcdM22K#Cmec1)ghI50fYdxzY$%AOM7L!dB55L^^~+6YuvuBg zuI1j#HEuiEPd%h>Y3W_9AYT=Y8au(O`LWqAs_zo&y_7Y|HQPOQMNTeyBjLD~R#q*~ z?3=pOsXG0;F`rP=K_57K`_o?WB{PjAjhI(=cE;wuToqRy*MhZ4`sJzz8t#7BzK?93 zNiI`GabkXj5M^DaRqnZy@+rAwc&4Hr*G8<=ADrONRoYo1Ooif9&Zl!+w<@Mlm=i?` zV`1MFO?Vl|4vPuDiwO2q%hxr{M#C-oq`w>d!Cw-r2=p)^flS=Ja&{C?>w@|ZhYsRj zd87{*w25%|v;5MYPF(ONxG%1{wC6%cA5UEDX6v7}Tk=zG%N@cDm07og4>2S0@yurr zB7?|^cXeQgglyw+guvY9C9P!r`lBJQ@)}$%72}H z5e&B3s`u>{pfIwp1UjA()yw+NxDaK6D6ZmBI2h*;+yAX3W95~HFgk=6(X5NXFeRCd zC*63BVfw+mNy#sFuA38;@^dZ|V!zbfKbh(wmm$~HD#`_jn4cyi6c_FZyUzalQC!g1^%L zUSaXGHxJnv9xZJ%&)bN2{`!w>tS5Q367~^z;wGkBc2O)yj@_%L#ALL}yBSp(Dv>sm ziW9qgo4v9>c*(uq^I?ZR`4yUO1uQg;Fl3B#Xo}2QAHmE>fN6XAfKAM_mrL20Kr`mqKrg0W{_~<8{Nc(zm(i>R+T{$!+@Ul2X1f{oF_8*jN*I?M?i98hK`q#F}gb-~RT4 z#v?!C2#5D8TrJ_6a~!4I`*Ex4h6chGT@!})!Arj?qU`W=>Qz|$vW}Vy<+$l!t#~xO z=I!4!g6lO)HKx9_oz|H=roAfU9d>dAvu8WHY%tIRllc$ zq%vs~Qz_PRviu2xVyn%a-Grwqo~pPF*GMB{>++e4b=dT%E>j-_Zr6BIQ5raKHJD?2; zp4T{b-$b;Me_b($mcXDq6BK>xAGCtdUB2^OOOU0O{#h%#zD5J3k=e-@kCsUKG zfil6ukbu;71K^8%p}Xq;j%{9EyEiTCB*P4ZnU<(lhBMm4jN++5Y&dRi89%n;J0>{7 z@TDR4V<>NCdbTX*9(@hwJ(4BQdnTf&lU8eU3=3a5Ke`l__l;_PROwVoM^Tt%vxD@d zzCx#+Dm?uJr=3Mb^vPou|7`NUVNapea=(gk!Hc?8OB!{eVZIQI4An|-Y6mFCz%xDH zqWY^X_t0J#ueHWV4xz;W@6u1ugaEfy_FEBX)M5z6b}iOo6VkTAt}AKjmwZ zW5y8cVR*o9$al-20k$tgX^;R9r%o?puW1~fR|xLzH_fpPvj;KgjFu04vD*KeF1d-k z2s*;q*rI3mYlP#T)-P&6=2_isK}kmm7ZJ|&7Ou;SC-nyXQxi9o(aI}Y8`a%(u`<^y zg|keCdi!$(xA4vVs0u4BbM(C^!wPD>x#yuK>X_ALl0H`-lT38ZfUS4N6Fh={y&nP*n;2#?bhZHY|%S} z4EX)e0rgy?_CiCYS>p@_vA}PjP#i2C`|#tg1JpvUkW97>*g+OM8(TAEF9Od+c%f!k zR1?Q$OPDneJrNWSjt671a%vP!M(N$tsTY?uT0ED7MI3wAw>BTadgF|$3EmtmD7ezQ z5wBqltnaJj{FF_DyH~8lO#35xjJec|aCCa5-~^bcC$$xx9o#!2RFI1~T7@TQ|A;!3 zgF)q1eZ+5ws`R&z?_+tM!BLz3cYewS4BJX6#gNdg-;*qT;=o3vM8rR4vdxA`%fl4s zx>X*}WH7lPw}vJ2Y7?l#ts|#LM?E+li?mwqIGzy^+1VobbIue6!5d2mt(E7+Mg>>& znVjp}ycwL45e`YmDf3rqgxrH(PEJe8db`CB7s#x~1|-eC^;)S@wmOAKd?KblAbCzE z#<)Z=9R@4ABP!DL$TlFUtBz08KF)PExOFWvcn>+m2#LMp-_i!j$=(1zb5(v_QOOoF zdw{_-m!Sk;fmJ*#-`7d3EJwRt{kmB~|A*#$Y(A0Y7B>{P;e-)(Y$l%IUob@T|S|mrMV6wOiP=tUbM4RIk!an+@4@8(984S5=2R-!AIQm$)j4zFC-0T3Q`%7C{gd{;^H!%_VkCfG+1V_dT>N9 z7jDyOCcm=#TZ@T+;b2EFwjm}}d}E10s=azp_;rMfx6s6L;)waw=`Hf18Lq(Ut#OX_ z^CmC(A#J_0@NV$WRIPHpmm#x)zl>SR4w1=0irlNY60n`@ymD-~2F_D|@=y2Q$5s%JP4T@UK?pMu zN#+%CNWcq*60pKfPjhx>Ldu|9eu;&v$ak7XhN`o>%-*T=HrHC8z8wkJ!;H7pEmBit z!>y>^BZ%eip%zs&8mVV|?Nc{xt8R_N787!`r!|jtO0JZ415j50eJH8=UZBMctk;T0 zW@IHYk=0&0-O5n1JC!02mA5@nt;y_-f`-c@kr*(Tkti()Y%cvjp4Nx!(-7;&2jxi< zP~u5QQwU$9P)^Fd6}ee778ls604dL%v{Uu*#mY zH?Wveb3I$H-6d$(*Hir{%;rC)hSW88t7mY;553i@7s-5T#ksqADpzvOjm?EHYYNa# zc1Yyj`KmqK=G7pTMw|(WyoM+vBco(ZU1J2EGsvteG4JvxF+7JEZVa+0{izE$o{Z*- zg(9EER)gh7A4b5V7_`JFEu>DhHt6{S%KwmZ-+8UiM@No#h5ZdB!+YU|6~@RRcNNbUDBykhJ$bOC)~Fs zI;qVgh3~L95|me3pgqcjK!xR|v0E5yn@_5L*82D4GC7f*J*vJPMI~QV74`?>6zh2a zrTuM0{(=+mq%Wr@mZhz&-3?%D3*2(W15xGn4t`E-l%?(1^fl02_kV8=FcS_eW1yr< zKT!s7SF$LavqYxakl?0DF0*2rD`8ET+uK*jmIkov5~Nef)-_SXnI65>a#@pOtjH+1 zEbcLK#6l@JA=}41H%a!qaqH7UAGVmCgPwswLlY+(n82( zD@!%)>1*DH>}vu#E8sB(L{gInMEas`pj3>;G~YKy!_v`IxK1TYPL=AoD$B-O;iQV5X5R#d_4h1vpHJ|tRiAp zQ+v_6X* zB_%zsTs|?qIe}8eR$`hN%d#SJY4+T8dRXWf8kH|j7m(lEOH#(z~_@R%+bNHy^zKTdzRS#eOY!vfV)`dz8D zkw^4IsQ4YIBLr~zZeY0!cc-O+Mj!uM^G%wT5`^N23%k|K@OvMsTq&vMe{;L zS{!qShX_oiw{r)#@6}f9 z$W1pQK()_OSHh3x1cvfGPDa*8A0QlfRE$);5jfMWlrv4t<_}}d-B}40g$Fp`&!j4kVkO*p&h850ZZ8z#6>|1B$yop^E8ko&G^=`Bbx!Q6 zKz4*^=XysepAr9~b}cJL38}gj)#gQaLd@?;>`-C}lqf2&CTR6DU-YQCz5N@wO=~h5 zOx5ocr!>y$3o0(f#52qfqb$?IBsZRkW$@xoz#RSx8*B#g>L>?ISg$-kCBro8p?3oJ z%yQ4@ubuyDI&q+vUfpfQA(NEHqkBm~0aIugGhOgt($Ca9QJf%KE|T>>KQcS*--JsE z-=tY!f=}Fdc_M{RJ>1>Tfa~eV`gQXH@jCcFj#cg*nqIv9OE<-NrCZt=u&`{IukL9_ z+_Kri_6S@cfp-Hx^?*edgYfK9{N2(vUE1)v%H2YtaOfOL1P=*2%dD^hx!;Hd7878d z{5)n^H@t(XW!t1@uYkIB^$_8tw#p!J^}T**J!Uq?XTm#$N`NzY zJWW3z>FuV#9U(koXj|^2j{w%|n6(vbZ2IHo^F^s1Cbxl)v_aEIs%`_y<=n>xhA8NR z>7&5>0y0K%tjVIqCR7Q7ZU&e1qy0K8#39L+x#mB2)GguLmdOqC|4cv{NU%;d{~R@O z@8J@zP9-_XP>4KAt-q50I=!LueO4`j1B^TL+)q9ujeuST>>ILqQpI#HbvX9)^v~26 zl0;dh0TUiW-7-$Wl1i?oE>Ap1jxdtOth&S`ZJ~jYo`35A*jO*mYk#vJJ-?CmW4B`^ z7Jf{M}LrSTMQ^o#(dn8!0ciE^|!?_jN$Prf+Ks4l2CQL@C z4MA-C^`0i0D(Z?oU`g<34|YypQP;~WS6nysEX;fo0>g3l1l1MTSwCr{-OP1lHf9W) zOoj~c4`gL}_2gUO9*<~Xnfb}4fOrY>6(wv$r*WyCva*mu5AnTuJg3Q8YI_-6nziE{ z4PORYxIU$3Bk4Xh`SiA}n1n^Rjk{X84hy4gBNe?_rpQXzulGx8;juKUY09YQhLw%$o5B!4#T*2nRS&t#yE>Ay1(iLbX28-=;SC% zl|6_VzNDLF7lxqQK-h>3{7L+`!;CsI;A*#G=l%Gex4%6AF8QEART2uW5+_qZ?8Rq= zMh-);V3%|I?ltn}}SuP93bJic8vZCP*N_A4t)PaaUCROX+(ik!o5xZ)?IuvRJxv z@~dU5Or>$MOg5fLE)pobvnT(R9!4b>m;9r@^%AeeO2Gf!h@J z4__YVDU+p2ktcpvLZ_gCX983G?Vjkj(K3V*C|!GpE3GD#%#=t&+sC%;U}v|uzirz< z`u6SH>aMOhY_X^KC~eI0!3Zq>Z5TTD1yI5lZ5bF5HLDg75xzb)ef=D_;V5uLp9|iI z(WIXqBt=Va^`zl*sET_LQ!4iON?ZAfFSP&L`SMtah!YS9*B@1=zBYh5eTlo#?3kdW zB63ZD019sSa>Ef6fkVKokAN-dXJ2T2f%m2$$^6==H{)_C;ueiTjk< zlPbgF>Z)t8{%6X9TwwA|mgEl&c<)CUIBnC%TYiNcW)?Ke+m??3D%!uKOQtB~3@930 zS^ZVN6)D6o$tE<*h$LQY)-7PO0*hHFGRejc4YY&Ni&Aq9COo$mOE*a4JweXj&j-iAa zCrtNy>nPy`st~sfO|O293sciYi}2;0fGkeV0~mua-MzP;4D2otK>*l;un?@)Fj{U^ znCX2ddfkTuO3&JcuHE|sXMKK9UbXozk@UK@@%#v%e#CqQSAxKXaf`u!MwYke4bZF0 zg(HY}Twut?%?x66&Dqq8j>LbI<2e#T!s1(d$>+BbK*byCvD0(v6Bn75>H|`v}?P z3|PFN&&=^YU>1J4+iEm1DW3<3fzx)eGus1l9MXA5dGOGJfIlmRhdUUs5r$MDiYxDz z?L@4C&gPkeAE{Gg^N!7Z9&Fg{`SKBq~y(=iU@8;&xt zFIxS{{d#WHt}4953`^4x0U(uWJKymaF*Q~^iaK=p`EmX2a^N%!kpOJOBj+g*pkbw|Lu~hao}ZDg`B`!<|>K*uE_ zEV2K`o*4$cZow7rC8_F)Ufz1^rVas*4oPFsV+J~I&|JM{9OBcy7*E* zX{t)n-%j1qZ0%JGd<{Ym4=wfp$1IL_6vj~Q9s(HW|AABb+V^zw18hJM zZ+u{Q{WPqu9Rib*UGELk09ri4hFmK_w6xh*Vv4@*gNwx9O@l9A@*I*3 zo#WpMZ>`IgOCL9RtV~%^1(^0o3Eia>59~4*>|AQ=>ssa}<+oKB*>xUA4azW!ZE*9s zp5_|pNOVGafSB{53+6;gj@-Jx?zk$GQ)BpXbX`}>C=&z0hF>p4!VWUGHTeaTCF}Xy zuUiia+cnU<_z<;zfqQCQr@dty)>d)^CZt7C3eiw{?|IV)3#$~!M;Vvg!6N<|ptskl zwgR&&=k=U0YL?WoMn)-BBaK_lu;xTfWoe8hC%H@zGvElIy-4e)1FZdj{`}^+CORRX z$>nE4F;urs0r%JPlgq+S=}$2_5F|9tPNkL{YnxoLqJ+s3g&2c66&yOQ0mVX~5|<#& zj97voei7!!ell4?+(E2U?y9aAA;YiFZXbSfe!U+<2*@n~6fA^0AaH>5Hyj<8 zLH%o*K+rO_w19F1JdTk7-Wi4T9guSGOy>4JnyBwb+`KP!%EuM3p=ptfmL@u5Of&TN z@(o(}gkr1w63oXyw2KO5XpTtJuMF_-iYoX*-0=d{hy40fFgw_Bj9rt(EIE6zxVVVE z<5Wn@I(Ow&FTEa$I@UBIYKd_4YsHveM)d!40q|9hWw=Pm^p1PWf0-~@hm5|TvObDE z(9KY-5S+IlBO}{*5DijR7ZP}w*(U+02` z$<4zIgj?hInfppAe8zUS{qTJuq3=IKKp#;|VpBq=ac|MpPz_IuxQ5Mnn5;ubC?2nB z>$?#DOOQ0E#+K#W{T{r`fR?`n5@xzSPgFty$_T!{k}#IiDDg2xr_!$>CXEYlC|7^H z-Lq4mN0ybPWiz2(g}099zqX)5L@s%TS_n`mH0YmoZW5hf$C0`W2Tv>DCg&%}(QU_}t22Qwb?@u2ckE?gOIqgBC%A!sS z>&uTaHcik~D?8Lae`S9;I1Ka+m?kOO+roHM#l%LwxJC~%sR#&bPk;V9_BjLkqTf(& zu83;PVrp>4jYHWNp(g5gx?e&R`KScx2qXs&Is1H{NdNo|2WXMulhSxZ__b9{uxG`@ zGc48AQc1u$D!1XU1Z^597_>=U&4C?4phSza1`oYI5J(|+h{ikh1n51!HmKPJ$kYp= z-zMXp{a#CXs(I(z-gBp0E+|{<5@)L0m}M9cxcMbk8_!GVO#K9ecza^iFO>@meq-;= z@OA8N>rdIbYHBu?n*e5zAQ90>GXbX)LQ^xQ`L zb396^ZUNi(ac}sK z`O{7fP8RX?Y(3|T8~w&SKFaExOPQvW;obb{e`sJR7tzx7dNB4TKzMb-RRpZMMc?O8 zpW(eR8P204bekZ7-2`p++;;u-dpzv|OgvDGnRD7pZ_Edi36of^Q`vgsqioVXsAs*W z6OYDmn+@Cxbb|kms$+L(!?D&2I=e)*5?Rtlho`BV>>nQlM>|SQA84Rr$^D6s38G3I=t>j3%m+~ebK?mPW^`u9werw zT$OQN?eev9#uMq5sY^NU4U?GO5%gPnYv9run3TH-Yfa4!9=!9R`aVIOGHczYga=Jj zLIjIDsSZ-B2i$K^0s{mf_p5&!XV70FF*DB0AYrO`EAV2dukBuhWyg;_jTofwJtLJo$1d_V+ykYl`Lx zYgfy@eh>nbn((ED85|jL+c}olJDDA_7z2ffPfnA9R_PHBc+`BB%8v*ST*}J;=&o#F zl~q5Fhda`a43U^oOFRtSSs}o{BSouQ$yQX@3$?bB*im<#D2Afl>r;jXF{Z5kx>MOj z!s46H4tI1a%E}y}exHe^fW>*l9g)q>NUXm9URP+L|3 z2S*hgAu)iF9|3?07#gRS&FrJh5RCvl?{fXIpUk6a<@(wp66sTw;lRX1EDm>Z#!)2F zu8u@unZdO8$&hr-KNZ)Jl~`1LOrBHhtO7lo#uYt#NNL$6UV|;P*#29uT)!1F^R+t8 zyX{}MBP#xQ3zY_Snu@?pa4k(s6d-PAN$16TYZ8%=_gPT!FBG;voBP6haNRn#Hp2NM zM;^xhrB|)>#YU)uSwm9BON!a&tZ(;h{qF_)UamK$jP_p!t+u?T=bA8>lT*<&R=mL5T8>9QEoQ49HzphAok>hu1-vZ&&x zES&+HN7^eDu?(gY4UJ|9qW8h7=hQ`l)BW3foHx=xKyU3K19~#mMqt#zt4vcix=$>Z z)>PgoNtii974;EVm)}$fSu2l^l@vxGb;%Tp&hmJbb77PKplf{;Bg+W0b%|HA5w8>o zpE!vvLLu|x6U#S7zN-wa51{2|+$bcxnA&AYI)KyVUHqO`OSJ)bq=seP0;1v1}ZYhK#^?c0e#rfB(@CR0F zT()u3I{0Uk$dB-f@-`Cj40p zFyD-FRy)1e8CzUlP82odizux1OK3bLo>!g0vD<)Lro(#Z!|`SOa~aNk>o^ zxB}ib*NTNi*b!!CB|A&?FdL;QT{P)ORPfLh@F}J6zinGXM0h!-(C=RR`@FUV zfO`D<1f`sKXr4nl-y9XOB*dhnaWo4{z9`@Z&U&Bv%~7@uGGqol?ElW8>!B;-zzQx* zR()%312G|r&G_KCH|ryLfKf23RR+obc21*8M9kjX$J=VwMUP<-K5esN9()Dr>b_(J z7SR0)yl(;qSE0TnrEazKPgJRND_`lYJ%(dlxIIUvSgyvNxLQ6IkT)SrO(A7sQDc42RA_jj?6gewnm zF=)8U&FGMe-j~!QxCm|BlsFdqz{|Yx^pTO4?3bBC(OW;D#=)D6YgU7BPz>= ziorbyRqYp;qIc`a7UsmCb6JKPdlX)U?o0g|CC7Ch=M;sxdjmm=KsjNQWtNEBy#PDw&VZ&{M}~nwr%fPd4TM8qAE~~rU3Yzw9HouH^HG_ z3^N2c${7mnnu4zueCaUXIXt3s&~s zgHb&96A8onJ|~soor_^hmtl*#VM{B6q3eg|bxgXUWq~iqV+!B!;)}n+CPPWiyZ)|q zSNRFFFegg?Z!c~2EJa7$V0y-e7r|ya>a7NlJ`_tN!97ylXYeWHfTg3tV)b9DN|pl+ z)s*xbgJmDSfO=a_M^jh>{rP$5)Cthb*X8lbptH<(YUT5i068!Im0KiB(51iXn^G;u zksL8Y$=Kr9LMQ=emf08xr=7cI^QoUv)Fer<$zg3UinEhMdKmwV7R4(9H>V~J5{l2q z-CM@`W#(l5lhHtVRVOCG-RP%I(R0iG|pN%G@RyU7O%CRQG_3kNtEvUP-W~CO(k*vsUtm*WxwT1 z=lvsS80wN1YX=u~a{s8zL^p{pNU~mDU9R_wZnuw6)ZJY~!=o-(bnSR;;NgS5r>hog zM{083D-c74_2Ul>Kp{wb?65x4Gwb9sqQF=7InoFd21cH=;wysqaRKYX*%H4>?oWt= zS+*3EdYEa+I9T}5y`~DUTheabP&PA^Gli?o_KQ9j2ipsD`27(Z-6w+cAU-OE;7U{;?VV8h~5S=5h&RxQtgIw znc<+eA45w*dUHPLVv1aWS-dC%92N1Vr~+8<{qE79Qw@xXq27^VvkFc zlG#nAGhx`P%{Ea*70j$2~O_tr!6x1<6HuhCVpSg*<3xAGP~r z1zz9~Eyy)(LBx;v;vZLMrP!JX_t7>mtW}5bi$cT&-UO`X0ZLWmsGG-*v*Q}B z`ah-LlCJFKG49gHL{gEo}6*?*54P!xjf{q-EC8D3oWTy&Kz$VKo z2SRWOH#QzD_c9G7lN5fIkw`98iMy!@*27=@31L4XF8@5DoZU)=F-2xV9fKMLRAzP% zzfsNpgSb9E0?s{=FsX(Wr5|cK6s(Jt&^YY zmoNPZ7<5OhcCw+Whd%(KRi*0heo1X-z;=K|S%op+w+gCL31cR}R2xD{vWB2%ra@UW z^H4}*3{rPz0O^6A4!3JboN)|(AT$p54V@b>QH&Q=kL+OLM=~(FDoJ&%NIP_^3UL2< zEw@hu_SAV1az+9DKbp?LEzdV@w14WP+(N6?Xn$NsRp3uj8DbTS`+>tS~-= zP>LOZM?Vnw{8y_yhP+b8iDq=kL*|7i3&VSqVbXle>yi!7q9LSR!F7o|v(Uslv86ad zsVvmuMS({DnI+Z+R4||#`}YEX=(V^+DyG||r_}-?gvfnn3NKC8`bONzFdiF{)R+w>8o6I}B(Wv1CYIWT#m?jOw=^@e0yH$gb=#nR~EP%}VRo_aY5G}C7pg7YC6pAK!CWa_Pz}RiU zIk+znS-t{9A|N4m9e5>ojjAtPlJL}}J851&6>f%&A0@ui%jHQ>omb#yZxJ2Jgg2T9 z5M6B3#kt(Ju66R}#=i``TAk@YVk>jUp5{4Pi#hALVrUl`#mYbHiff*;`?7hOp7K*> zErqoq0`9oomPp>_)sn?UAc_;2iHCC7tS-qV-pW3Tb-tNe{?H=q1tR!d)HKbyZm4}+ z_OH^|WX-7~0pZVzW&|hURkUcj-27vljb9i1KO+zuD~0;PB;4JwG+55ixhJjxe`D8O z*=M9)7lIJt#4be=6XfP#I2)Z--9bC=7aemqzZ~W;nE}!n1zj;!bfwbQa9J%ZXww&< z*89L>XS6Z?(HtvUfS3Uc{WH~GD$CH?nTOjRkMtb%RX0?sm9@qW`l?8Lmta-;op4~T zfGk~?3{6o_daHvu@OJX@>sM;j&5q75E`S^QrQ{hIWeH|xgjQe+ZPn!8H|H-&{F%Le?UnehlxaYh0OUlT|^pQ}UK+S&B+ zo#$!L*AD43arB!O>z>__b##;ECevO+Lr2zcc7Ych{^-(`xY!cSr-aauL6fK_Omqb90KMIk$!;x8`YMQ+!+~ zSL3}>(WH)cKu__(YFIHDAgYW0O~>-xbWj3w;!*QosNZemy#cxs{y#SeW%j}^MiZjw zjw+bKHrL3rmPfKF&TmzRTvc|0keRp(tkDmx$HCo?;oUvi@5kAB%ho%9Yx%<(L-ed` z6xlk=s)FH~ZO0Zz^5;b^4*BaL6+frlT8r;TW;X;F-`njh090?gR2=S$JBM0zY+)h;K9)rFGm5$F0DF0~}ffW=oaiR9OiGj$(VzZ@T zteLZRdoC%Wy(^O2LAViKFE&`4{%5cwD8he5K0n>_yp)|0GGm97hT%t#8fraR2<$3_ z6iqCKaFaZ?#DE3M^0HP!SX<@KYkX2)=3z{yTkZ5IOin|d4&D&E_@cw(n{Un;;)Ep3 z8^c7xvO4Rz-YacsRbWqJjh<#$(yW^4fEUxM0G+jJAY+T0EDm z%JXX-tvqt-qGdS0)#dHtugz;!c7UvQYqjxSC~eb^CaXL7rThL3S>lPz(F2=n^%QIaWS9Ke}M_~McLi^o1AOz)_&EdCsJWX4WS97?2 z_Gb7n{Pz_e!Mw`pr9h40n}M^CMD;E{6*fHl#_7{6hoNog{u<0V!0GzYE~JxX*41kr z@$hD5l^7(T0TMJQnAmUS+Lj2VU7Dgxj!`mG)Lu;wZTx3=1i6}YZ7QdwQs)PEKS;K& zZDekEBewVl6a=->1AQBCkdtV=qCfBOepW|=4-XFqypaWe0oiCUdK`Ig#_&PiQPveTjT;R5@=fMk zUN?+oq6CSQczea}$sLc^Rk%R_th6+qkLwEG^trN#6C5AT4wFMPeA&xRgf{>i0lWpH zF9~WVT(QpTXpBZ%hr7T18*T$JgDqAqZ@p3PxQ%0l0nV1|UaTb8f4%uT09a{R38}O5 z3O_ee*_v(=pU2W5)I1d8&`U??d!`600LCC#mOrt$4HZYRt)K)g1hl>$@Lp8m<8&z0W%ONB(!wL z1FVQ%)VHq(-E!$4JvwqGp>#31g9!U{3fZeMT>CIKr|*gQ+$bdxewK8{2@b?c%kN|8 z-C(w|>{rY>|NARcaUVYBZL-u42fDTGOnpGj3D!AbG!4zkso(bsS7S8dzMZZG{~gnT zfp&VD%ZTGhT+YiO@7Ez9=b*l_f~jmlM7I7FimenS6aX@OxU@+2qahNK~4a+G1k8 zs#Q6^L2RSvpd%HXvqPO&w1@kqdz zIQ`Y(*&M|pup`l3fz2~}i>qDD7;&c5i7N~^PfyQG!AipX^TGEjTEM{nF5bmbaMq8X zXI^)ROfIn6U#il#qte0_cAk&COUvRM@l?8hv+a?tMr?Lt2nU6||M}bTY5`ouz%!Ln zrN*=cTf$r+i8&@L2QM!EF?}8$T-lJ$qT8jX42vy}>mdsLAe%cy=8#U^=tSUNcw^F4|__HSAfl`9UfpI`I7y1_Wf#3RWTR%7)lC0 z$A(*=b}p8kVEq6W7)4Uw;bP>w!0osj?wTwK7zHJ{J-nXVd57b2+8TO$69SSowvVWQ zZP!=i1N<*wQ43ny*P(1I26jtD%0NNAIqGy0F1G+GaIpGW z@f)F;WWX*@zO%YVE(KG!tZc>Qe-ZvN5NI|>L(V{sqFfEOK+-JF7Q<$TNJz;jEqY@^ zLJbBUZUHRad%(D?2z5NULM7ORW)8kmN=}7qgz@X)Mt?0wGPa2Te#0J+qXnDuG&2I- zT-h9#yg%bx3|+?IAKdIphc?4;>bUEP!k+8a>HSf_$V%CwMBn6iqC zCkC<>Ra_|Z2;obIrwP5qC7x`~%%Vhr&DVLgsjeC&c0dY2CDZ1q9&T;h>uJnj z=kL13=A!uXA-*F)paQyKB!49%iM|reL9{i#kqYYQLN#i`)ysrSmw&IJ&-X01L50eP zHOEQVA?npbYJsc|#vF)0Z&dyL6)qq78gKPK{?QpV9u>{KRDB|Fr=1Zbu6Jg*`9S2oWZPn-ntEZTilIe(7s=)QWyElp=5`=8Gz* zPl@=Yo=lK{w~peT6IeK~In!U4X#hY8dXdr4+|_33MYb2+#4*fJ;Xh*|0?FAbkOJBg zhr`!SGoyewxkSwhY!8rf_uksTEh7PPg?rE{3ATjEx;2&B8`DmGXSKwO<1!u9-;a@Y zo};m$Q7_4Ft3+ihe#C19MpNJI0s}OkX?9wnE$S@BR$YQ+Ys6OT1sP6Gur%oLn8?R| zg(2)19{XQE(C*ZsxA){thEIvVXK22KD`_$Lf*Urh_J{{|$=6*@e9Z=pVT8A=cj8-e zsg_6zWJ~5M+1uR25h(m4!6A-I9a)+*T*2}|+s8M1#au5n_2+C-PPOKcz0)#A!A#a* z$YuKmth69l>JxU&A$D>+<}Lo=D-o9KW1;MqGJ>iBH>VGL~?~ zjF{R3U1>6eSOS<#7&@xuEMpW~;n0o$Xl=(P)&K#ZHk&G=_!<}BOa~8&>Xb7Od)aF4 zsfL^Qp>E3j+>sRxAZIVGybgshqyg38t)zE=A^`k(+-LL-t*or-W;&*3Yoo^oO1>=s7yU67RIp%1$4+pNMvwqpF&K7{?=_x5Iv9mX zvPbj7os9~VH~?r!W-KqY2wMV>suaT%2B>6)MqGbtg`M0^KOOx>M8d?xED29%QyH#) z53b$8`dw5s1yY=k;)lrc&%#GJ*CbK~xLW|t_C-;A|7^}nTw zM6)YcDhaMLb}8n8$bdoN+#UHuE4c_0G8b0Q;=;n^)1)`ShxDKeShKL6QifRRmr~g6 zkomt7m7l-@&@ALd0ql34mk9fKGlrMGgC{EHBTUM=aTKF;`26Gor2h&6*VU0Ec!q3#f!6B$FJ!5hc{hH|uAqQ?R{2xpCH?eSf zX+{D{u_1cacwhaWf}CzAA-k_7c!y+@sW96Tq*888r6QgBlI8Qpe<^LkfA2Lj4rdEF z35xGr4)#AYj>ClUf4RE(O|=T0XXSp;`Cxo5nPL(zAX#Svz5Xe#=WXj{FR)@VcKD6E zB-`M12MYv%n>wyXX@NZPN2H12rxT<$te1Ie6#+U;&k#Tq3SAcvIQsBq!v!xh<+daA;-*wd=mIIxvhGK_qhBX(_8sRgO3SMjU1km$9FZFW~*Rs$V42N+)4w zPiJzcg`j9e=oJ3pPM&+wnk>tDtE1!@yf+4#NE{a!ogfaT-^?M(?TaVS)}&hAO5qCc z#p?e=llLWy2!?ERd_mN%1gu-+AKo6iIv=`?Q+JfKDlM^D=^>{Mqcn?Vq^Z-)&raW9 zVTdWj*QOHiMVCxuv^wDInseL>N#I=eDJg{kdq3|-g`@u^5E2~ce+ zAzc-$jn2)T1;r>C*=~VDW*cQZ5@d~I#(*Bz?4G@5Q7x_G|d?)#{Rwm)>TBjirf@T;kmZ!L8c$O?? zjvF*#x!|2AWo291p`aEOjL>&49+aXCZf6asdH*{&}CdOHS*=h!dK`e#XHEpTtX$9lJ z{qNQ-z|e~0VTo)UtfabXRV*Vrcw%R#4tx5yP`(kh9e@Oi2NrsCKgWgHxaVZwya*+S ztn>azq`;3lR?vE8?Qr+s0x#Jp7bL2J->^CP?!)herOkl}{^rpU*&qNun6CRZLYhiY zMFRt27W9StISx3P@wQpMr?PaBjaR?}%Lm9qmY$|m=m0WdD4N12*>%&YIWv?lO>ENY zqQJDh)<1+FWpsC+{qUCd=2IQXG|YhSU&B-& zvI3c=2a`a*(WeEv&^c>BX?#&4}ujP{~n%ei`mlx477Xh~1P(;pl0gqp(7ovM42;`Xt1$jDx_XdQfJzg<4Fh@ z8PzBSCN)bH0spVnhstvsf<{KaUR}{8+w=?47UR_%JKxD#6XxO? z8}z~sK71H{i&dEG6iK7Jz&;kjZy6MNz<9ZupS*69;(qyLV#qCGgolaTIEb z-~M|w5chbKFEciW7<8xqfQtcygGM zEVT`F$hhC#2>(yZ(=4|RpzYF%h~r1>ssEbg8fU!S58M^Hq;S1rGG~VLehO~WH6@S0j-j;Ba6Z7o!4km zyi@-pKpq&6lx)b+3F1R+2n^pVVrbe-4Jw+;_3KjBy_q*2uMg^A+2EO;z|B%jG7B|i zseg2^AE8-r1}`g%mz>@=oUZ4MijedNBp&^`gi;S!SR?u^c3-k~sVqw;H@Q*A5;KJgf^&lxdwuhogKx_p4 z3n(&_LMgz8KU|dBrctt;{i1BWqHKYt3Xux9E`Qg2E$@YC_^foCaEpMaPT!jPCL^b4 z^5(R7i|f)I)Jk;qUW9RtiRR6Mb2w{T(-)f0Xf$*9)LZVLtyh(&QVNd!#18eFBJURV zQ{LYZ(>jy9P>`Nvv}8v#Sv-~+EhPDs6aC+*D(|3M8uC$@bb~FITCjV&)n(6ne2oSRU zIc=POyG@N~^wtd$Q>!^3Fz||dKWOVqFWX>Q3^2B6_fE?i0%}!Fvzh|}v^-9bj6uXM zM^iL?;_OUfuuna~XTukE6oCBf941MA`Sno0Ivfb+C~TEBLpi4f23bMVuu|aEVZ;Ds z;uApG=Y1H2E9PzfbYR$Ls!;C~G9Mn{m>!qW>X`k4$J1F$!kRrsnmkUNKDJXsFU;UA z2OPAGIIMK4^Mc?fs%6~5UZ$+`pFAlBDG&T?m4aQs1fPkQHN4kw>$xvxEgH}y1k@c{ z+XwaE6Fu6y^x14umLXZRRukb( zS!ihhW96O;GuCu>!n{5uJslpexu6QG+xhLjaG+aAZ5o|IB9*bu3}qn0`JTVhK>FqG z7qB{e_`4o1KC&-1m4WhAw!3YIi&FR|OcH!&O;U93ZL2j%-1rhVp6US8M((XjK5cZ^ zEg~fEXoNERH((6)x+^ybRH!~V4>lkK!0uB2cDn4QckWd^p{VU%CsM7Z(Ah|sukQJ2 z9`z_$;3#8jy@5#ctJXfP4EtoXBmmh%Py$KnvoMLRG~?CwI+;F2B5 z0=~oYhDuxaG0Al?hDa_ikqk;FO|W88cy^%V`1?Hop%>W#KLW;&X)+>Vos)jEDAwHw zJ-zA&69U?s7glFg%k_7!t`KAAL6R8k0DpZv6jvzd={@KXwSe;EkWur&4NaQUqlaYA zc@5=Wg={R)s*Gp4#b`5$9@LD*8N{dZY@irOQi)_8D999;Jk%{$xdtYW%qeyzZqp}2 zJAr0w0@oR6GTq^AwhxraW9_qD)E>!f2%mtpLD{!>thOSkc=08Q~nl@SSL;<44)Qk!VUfeh^0b3`dxZOql2XXsgsc$>mfInlpO+ zch;#BPdenp-i9Ltu5Pi0laiGsp%|awPNv*(!gnM#CG1dv1|k4%vXmC5pbn?3d&BOM zU=O2L0tTGUMK(hb6%=U~nlslP5j9H?YX1~aRBBGS zF^P#ARU_Lj-oLp&PVFBok z6I&BZ=$r#E&|yWa$Yamq*d^A&@>_=GV> zOee;{ZP}@WZwi-1$?zZZ^~XI*LCf;gjx*wAF;eV~duz@2D`ZlyMKmN~^aCC!`M1Fn zNAzPjOBjEmFuxAB)5_+{1s%I>VCl*Ce$Ds~^+OTob(6m7x`KnNAGPX(@k*3vpU3}K zOnRkdTX^Tl&Omg(Rx*eGea?f2e|pYk%n$OJnlpONdi%#by&8v{S+A={(5^Xjrh@E= zQm+3`!H35z(1MM&(wlvbI|%wTRe*wYJzi+$n!G(pB?T@!GgA+Y`qur^kvm~J7RQvp zU*Y+>gO$;;)Zbi_zi-_LY|Mmbhn>>V2M_|FDr4ibq3oca^T>MAW@QR}p6@9T5qlD> z9QX)~`6h_s5lb=se`FF%JjXzf=7H~*IMXx2g`5Ej9ypp9`85VLx%zn+XVc4#nF?#Dk1{Oz-J)MnVoiO0_^1T+Pl!H5{OGCb+2{DNQ6cIk95I?fHtUHX%d+U zvW3UZ=y+c0xcTBVD(snhNYby3M+=Bs`R0>QDT z-^mjXLN?>09xVHf=7@zr$Z&+Kv_@Dph8gD?(yWDvH%Q3d*NOffrqN1}J?Ov)3tS4N zK+S+FC?JX-Axa(-o@Lu>?D+nLf>J6Vg05~D{#b1#nQrF`!7o(s05wmx2no`k?RwZj z;Qd642iK&vA&#TU*+g)V#5)x?n$JA^`~%0w)KSsV)2DZakNlq?A#JiU@6yDiTBuI- zG#!t{8Lt15uJ8mmKCH3FOL=$LPrx7BEpH#nCN!q?X$op>>DhIAijpSv-?AQca)vJY zZt_iA7c4XMXMZ@({~P@SPr^8gJl#Ey@ajLhcehA1c2|8Rqbu^Li$S7n@T=l3v&`=c z&q~TWSly3M`fmFex-ItLlY;*`>|SynjxjV~)Y2tQ=~6FSFiz|Y{IxMXPl|^NXs|v0r3P)}H@EN&nYoTNF53IT!Ur!o;jP zI3gl3zJ0dAkMI-Uz1v^dK+^NqY?G5I_Ti2BI*h82gfdeUm4$U#x}1tNACGwRq9{eY zf0E;$e#qehmZG-M`ld8O*Aosc$eN_tg9G`CFFt%ZW!wN@@Akc?9c>!D5Imc=vQ1vQ z7P9lSwpjF;rT$QUKIRJM_WQzOt>8hm@4d2+#z-DArW?c8cvd_0cw9OwqOUb`WPlCb z*$701J8zm(C@XXS9R9k6CD&%Z?YGYGhtt#zBGe1A5GxMzHi{Q&;|=j4&Ew33u>X9u zS+r9jS>96g)K1GI7KoIO;paHcLN2=YEu4r|&pzHyHqhsiuu?pwwSp}D^83Uf!6~>y z2nbs&gBnn2rjiMn^SiF&uQ)`H<#zJE|M;#fcE7V{dB3~y{d>J}JqA*au6nUF+?&*S zI`_q;8r@QQ;t%A7h)o+5bNHXpJDpWkkj+ncQ{O)8B6W3;N4*s1?d4dWE|nylZIw(D ziY$)U6|wl*PpYvTvXdV8g%Zb0R@kF4b8wxlE-#DAQ17?R}D4P;HBp`l^M@uF(@YYRONX5A&hf0eol|5qU`>^SZ zwG5s@362hvgHe>_T^ZF)1yWnjZAQQj_agkVE~ZHe9D(?VF&~@#&j*6A!o1dRvQR(U z`O`ILocQ^~Q_v6%ZiNYDDEuRKBfa!4CWaT?cH~uWOzWhPttM(03Qp(5A>$WB2vZ>A z%MSiH;VHpTqCi&2o8@X#=WmO1JVl}@y(KE6TePmdKH+(qCDH|f&l+tYVMhg7G-_)C z;vO(=daQbJQ!eiS@^c%$@LQIkpf>~da*{*^;?sPR&ptnSBI`#|-!8N(gW}P+!;W*1 zm9?qE{ATM_bDipjQQ-sqp4M|&x|oR5@xtJQF{r%W5I%n@P@zsA26!%1=x{3j7>P0i z3cQ0N<|D3XJW-8t(pKQp(2?M+H<*;LwSTt0Y}IYx?!Z{xJnyWr>fh=69C^Yz2u8&B z7zZXBH25?_C8^nhT>=I0M7=;f!sPf4 zN)y4UsU?2z#}lf|00bOVJXjw()9u%hy)NkSzx5rhj~L|e^qizAEU2(WF@`A28tX++ zN@p9b9q{bw10y4_&jC4y6Z?84R+xi^M_NO$DdVXpDXa^vbtl$ZV)5HJ-3|_KLMH$wQ zC>Mr{8R<@#+ys}{uhB*klV><`N#4(fU~+QC1)6j{ObYT&69{Q#xx5h!_(@f#R8^Dl zy3aZAo>PHIj3Q%cy<>7gdA8SnldRuPA0h85cV`dGDtHjyl3x! z1x)(q&fC;&ZI4;7v7I`8d7d&i4NXd?lx1mee=Pr3j0A}l=0P^K_;T-EFM}x~AuKUM z#*(RzeEIpCc%pLt6%2NI={Q(CnRM~2oaMcT&Fd00|) zK~XKkJV}jOn0N7V20J9trjI>3!BU?qp5+KVF2O&PtH!tlEFsPj63&6(8mIy4t$i{g z0Z_{6I}|=0YN9@PK->`&PIM;b_U(r-04M>pl(;KvL@Yw;-eZnP^F@gZx;?)n4iWg? zKdM?cruV5~jSSW;@w7KG*9*-D|AXP>y;wa-x_U%t^9s9)q1VeYAae0F+<6lSXAU;~ z_+e!cozP6Y&20+kRw@ae^PRw=ayk;zl*SoQg;%2g-R*iUpt1N zzs^^oHng*wY;Qt6Ow*8oG9(f7Bw#j6g(r(MMuc!5R#S zf=_qKIQGOIq?X9P5_x9vWa_bC6RFi?8i@^kT6Xm~m?niH>5}uEwhsaQwH7GMw)yVD z(3z7oX2OYJm(SflOsnPjrl+;;IT=AOQvI1T3XqSEVmgJLV1$)cXJ&F#SM$ z+{o6dHxeIqy82k?wuMDm=bsAmP!;}2NfT4YWu+f@p{Vj?enTXgU`sMKwCh>C!#{!D z;Ol*Jw;2xYnYN-2r_ugzzc}*Dv=^@gX&x?h#ZtA=EJcPF5tS7&U!vXc=P^`-(#6w{ z308|ue&i|ChKW(tSEOkRVF{XHD*yPg&nWG{(F*J2VsZLGy1dUYU^fy#I}+xb@+g{Gc1GHrq|!?f+#&Ec|kw0&|7Re!SE8x#DtIiX>3!<4%4pd(qEuZkTK-%P6cNi* zIiA+2tX9Xn&S>-oBAs6P{Uep8wew_E0{%i{$p==#ZoVlDQ_NNJT#0ZhR&?9|2T}%; zRHckIZ8O0ne;Qfa3qSvAshJ?Y$nq#i$z*tnTg7GE!}9E6)ryflS$r2WKTPi0DREZL z!Q6wxSKugpH10KmuJ#96r2QICP|~ERx+8}$Dl~NkE>Bn>1PJNa9jk34um~e}U(L%2 zZ9t%N(-(A-`v_{Dhc%U^sTT@z=EX;sB`>i;l;QY+s$t~gScP@M5%`pGVzO$%_1l6g z0Fh{QGS6)RFa@N+)R}%o2|YRH{zn03?>wlW$@_y61(s|`asn*0z0%;)oxbt2xbo3C zzNhxk#4PCf8-&!{~CP8Qr#*DQKRR z^Lr6qVCryQp{)p}v;A|y%S==a$ob7)Oz$SSR29?%D#K0!{`p!u_E_twdpTqhYS__A zs+X2crRqVFRH^^h0xVu-|9i>?r5lkl6v|_pyp(Ds^(J$Tkm~QJY(Dr7$*M5OgA8`K<0X*tyh6y|CZjIZVJ^89bJ^^<1+C_$V) zRAH_FM2UY@LYk(^K3g~dAyfr+0IX4Nq@zE6hjC)aES6io$K5qfp0VQ+0wD1K212kL zmq!D~JHLdVh^Y}@|0pL6kWA<+p-X-#Qj?;-&g-aFV3Lg$FIn9Kfq3oz3dinWa85-ij_@GTbZqTH63Old*;bIjXq}*5OZd@u&hC5&kijt~h zlB`oopzDJCQVch^o=w;*3b&@Sr{Gx}wQa%mEq(Yxw~P^dgaU=@?FxeS3Kgrv8im*| z4+4IBus!;9MZH}8Cr`%18`u`Pcb^K@m7fz`>I+3wf~3*;OUdhpP7?sUPTMvoZ(uRj zoDG;MeIZxx#eif9sbQ*iahX~nNz?bdQwQ4+gP@nXcwgheH1E+5zz+2XyY`1+?(?IX zv!H_`MtRBC$N_ga94nvnehl{R0ru1X(F`A#C%q_a__{&gGzs_~ST0$1!!yLh?pP(n zoc0~7-tXD5qa6!o;L&80o*6Em(Oxr5Lg+B!fn1JNo3#!%G{(+b)UF2hUP^&q1U`h3 z3N}zaZ^p;yN-W%_=HOK1o(dvnEX&K>qNXh7L?rPh2=@bTe}?U=Gs{=!9^R*I0D1~$ zh@Vwsh;bK;+(;P3Az#FxXvE;b>Pt$G;1?`#;7Gv@1tsJD7XymCRm5qp$ zpO>tP!4E2XOy4;gt118K>kVYZ8ztoF?C z_1;MEn2)64q1;{{dpnE8@cCBvvrhVRpY}sb0ta6~Vu%b4LV`>ocU`E{8dP3Vd<*=T z;0CjQjP_s0J{j?%(u@PmzN`%q zc)xmVvC$myz^$PTfhlDkBX^1;&)SJ%_u z?Yy0lbp-~mg(wPM@0B6N7<|3?$YI#$E}NqJ(^@p0W(uB?{;NfhC8-%w;1nabjn$rC zKBQ{@>lFULr@R7U(*{RBuRN(%WgeBi$iZS~t1^W{?8*fc?Ml*!p+jM6+B=QYmO$HT z=yk40wPPXi9&NtLg-|bZ2_ZqvHMqf?A4HdzdXW7+^gsWmrLazBRU8?|%=_2T!SN4IW+~`96w7@vL~)3;3!gx1cr>x|)0QayO)N1tcqm@D+;w#{DMx zf>z9`)xGcOFH4YfPW0yCTm;Nz-5Q#3w{5pS_4tTN`AnOlQKfGNN+))ps%-%3Ni1!? z6i1yGg|XezOZ2?{_jZw7A3y-;x`H*tzRONAj1n2MmA9#BR>j7(KF%gm8sJbqtnwL^?rE`*xbt6tLZ4?^>?}TxA%}>3#5d8nUL`|MCmXqAfv}B zX*FR%E%11*PmFc`qAUkp8s$$5KS+d4&k7*B{ixDjC-U*5>x&})bj95V{iI3k6Gh?= z;C1mtBsV__j{ef%D``~=&GNkWLi_5{jbTSzzYD>h_=ZKEz+$;Hm}*R zsn7Nc7bpJBTVx$l66AN!h*oD4*;bW~OBcqRDgZqIDDznX#;idPXV=x2SAd|&zt}3` z_>AY1?4Q}zCy9qroWPn^>F9)pgj$50CnBad*iOKAt|~OB!XizY>emCxuAk9!o2L!M zi+C_h4KPop5oUWlJ#XQc4rw-`~YV39n=2@hk}NMaIpPsWF(QoZf$i5mP~y zC$iw6%w1^q)O94*L$FE-1{BRw59Two!0BWT*C2nER-r=&9Zuj=dp@CvE7Uyp$$FX1 zI4n?x?1(lXecd8<@ms<>On*{X<>26$I{p~|Q&qD_d8G5ecPLg%Abdz|N#>z@Kjmlj zG1Xna@ETe#mNSTx=yM~sSf@PH9XLOIQ)v$iq;lwIyvumO3%788Id2X;`{~EdHF=ut zsMoJ42y|L^tXjt_e$O(bU;O9%!k*g>q@`i#zSC3T&=Fad^=wm3p3MtjrQ${xk=7sG0&&us#V)16?!*IeB^=^cK}#qZP)+VsE(Kyw8n>s`4v^DC}1`k+XUUQoE_;@rtf(_p0Xp9W6Kh(kIPTsE5JRGx7&qX$lBha{! zo(-$~YBW%1ddoUo-P)P4pnzL91>myjlR& zVOT1KakDY8tWI!Yo`&ArMR=K(;as-L+}et=bbOnkXdg#kjg#S6TKwbARf<^oeyWq6 zyRrG22oLk=$oZMQMQqj{>%lj z5gNHt8P}*_*o6iK4|5Cqa3Ae9*07YdR0sN@b zcRb{$Ds(NZuLUWKF8Cu93zL0*XXvgh+3R^=p)m1Arytj7t=$FbLjeRRw69fz$lVma zNpXqoaHH=0dR|>L%*c2woEyL&JwwMby2p7F_{)qYnQwR=@_aL>TW%KzMl6bek0v7{CAwvnyEaOYZr@Sot^`)|T zmRm1q0EZF)lBv7jwPo zC#5Mic(t$H3=P=idjzkD&4Oy?+!T~fIhb?Y zE|C3wqn-=pfvZtswLq4Z(bRgNH9}{rDt{wYOqmLaeZ)hv4{_}#FGF7mHFfr7OLlib zz?tD9t9b6FY?m~Q8e;i-(OCMXV5H7V(Mi==wnXfh0HsA!*oLFWM6*YgZOmzF=si+O zfU3@{5;Z13Pr~3!%-hm!SfMPjYdhf>fe5yl>_qU;SQc_g;Zre&0%c@ntu&@Ds2nPm z{#CP!XYC8Tu-JL^JrY>FfUbAc1(Pbq3{AXx#L(*J)TGz+=KrJ?Ecip#4IuW|8 z?mXmY4Pb2unD$&idn5>^`J)m^)3(sFBL4*B!M87OQ#Oa>)~^1V!qK55Cx-3w-|(Cm z`+O?cw179y^=6zC{5Kj~MEPGdyG|S}&nuDpCD2n}U9;<{z*SL}$-u0lV5CO58JfJ; z8?WbXY2lvjq=OtqhX-+CJA7Idy-Y|!52>fb_3}D}^>EtvYDZIDMn2?B(HZ@pI|En- zzq4OQvbO+>Hkc0(eBs}EQBVM_OAHw^(=go?CpL2yN)k|e*Id0lL&y(xepQ^)ji$Ox z#OZoUC$4*HWvdHGn4WDN=Sdj1Yyfj7=?aV;F@24XL>rb7(p5+C84Yn4M@%r^l?bD`b zq>$PbML6OTkNlYb;gIJxDR-(#oepWb+yAC%4G-Tmnb)OsU!I6luM$?|jD^Db?>g;3 zkz*bDw9Stw3*LEU&)Uzny8RN91m1{EQbC$5or3ye1;$INPz8|Gxc+;4NL`T(&9Tca zQnjq0{=vn|dvnGK%g*fgj3ut5y=Svk;&BA&QR*{qj^aRPeOVN`Lq6W;S8=uDCCW4W z`1jX@KaxNQFv}TZp;j9vqs@b?jEag7vYYEQh96UV7zsy!z+5~$F3y$!Ub|lxorm1b zM)7)NQyxUir0K3kP#4_#0eG}1gECQpP_f*J>h&@lulF_9xMnXWWEoX@?U*h9$SMZl zWZ?k%P9BcZ;0P>m!&nqKo=|ii!jWT=OLoZnsHB4a&cZV<5MBia+i0w?_haWxF9}kn zas1ipHbRikqee)KfLF*Xt?j;8k5LVyEdLxC-$OhPst9sL=bSwF`i>d zUJJ%M)H+VeYL=@c!{66IdwR-s8ouAi89~gXwI(?JE7&6YHs_%3zze2yFqToI6f(7ud%{e^f$38QR)~@~7$4PgiKGg}pZxDNe@D#odyvYO6IMIm= zK6lhHlX}{oGa}2US|jeNCfAKja^MsRRh|%~;h^V9gXub@(*XnAO~7mkyjhq}26qrlboU;=j-KmvR2yt?>pqr0UBAt3*oP|8Cz2I!gL zS9id1usB;Mz+8YgxsKCoFfr06Enx1KGsDGr!ro&=l`1PKss5sMb7uBS^OtPFW=qx0 z2dNQ|DfNHA8V*3~Ce>>4v}B0jq4aO(KbRC0a`?M6C+Qk$lM5FTVLT4VR_w5+eT@CW zozHbSLMddI)z+y*$C9lf$~@OZcQx2bdk@g%g+nO1=N$gFv1W8Fu@{)Lm(yV&f&rhB z^pLuk5m&6Qi*tCMOtEfRdVG~h(p7sm#xgXht*9KE_FMZ^4ZN+f)`Lo*hd)#O4 z;byAdngNqh{fzvqIq&S7%yr31!H2y(ULm2zu)?OfAGaxM=1M0#Bu4Vvo}ZYiNA-2a z$VAB^bW9|c>7g>)@3G{ib?fkqIwjW&)^1u)e_iZR9?`}cnJekCw4IM4ZRRb04||O1 zFiRlC&OgG0$+OjJ53*`N<4SKBO8E2VGcY{5K9(cwAAiXRl0Bj5?@=*)tbgLa5?w2w zQTc`?XP6IPr#uW#m4;?)F*@|G5%>qbHT@tLEDTASBkyDQobpte@}}OgDoR!?ZNqH| zVmJrLumg!eB5_-zWtE8J$`e;z3O!-XZc*yUG_x=_iV|yO>|O~A?v&J>^$e$ zyy-PwGOG^=Nuh#qmCNI5LK50QbYgpkN2IdP*#DaFm_O7=zowjT2t7_qQ7NE^1baw< zb*-n#KJLLZQ)SZJaV{X-^LXVB82?Cm0p8-?x0UgESEJ^}Q>tpqI2f$|ha#1% zKnvE!C0dc^*cdd+1TdQt2@yHsn6k3GBd8j4df=+H8Mz( zSZyT!`Jy({rJPHW4^_SOx!>sh(pHmKEqw{nhEElsOqd%{RqOAh(!aU6IokTc4m!Lu zsS!$e^h{Gu4nS+RvP{hR04j?CrDyGN(Tx|dyeaXOA;i(u zU&mKCe-l4-bGZC6AS=Ev!8?>?o_dS?RlmO^RZm`u>n`>sa&1AZ@$sNXU}nA4Dybp`L06NO}O|@~Zn*6#TcY z7_@JVcn3nF*i2|}4uN8#eje5}UC_Sp{7*UuMfTa1X8ORSkI!pY|b z6WZFwFGXN$3pT=2r3-FVpKP@q#sy>+FsGWRz*yyh;Atn|GK%0nMUta=hk^@4Xwq~B zw^4Wn@G!!yv{tFopnxszg5+y$EoGHuyO37(0fHv|WgBpnWk`Yn-h=Vu8#WTG0JXYj zZW7NYDKx_|rdVrevhOc2gjE9R4h(pT9lZ*?^uZioo`u%#NCvb9Xt&eEf^Ocb@68G( ze@-m_^=DhQaV2{E?fK0gA+}L(cPsFVWLQUj+nzA%0C0vDozLGshgz->IWgTx-2D}fepM!GgP#by2zTyTi`Z642 z{d2wAx9Nz*4|ZsGu>eUSk?*Vdk42Y)@%krD z8EX+~Wgh}Ay(TqAomK{(`(1rWwU5=*uCIs7s(=Ix9R2&hU(d{aZ_Mu?z5vBtUuq0~ zv=JCZ&1+lKipdfZy|4xni+?57yN*!sOy2|Ev( z0np;YlNncl8<3rkKwt!6XpI-QD4Bwhzfk%;!5nf1AZSoowhex)y5y1r#L_yvbHk0i zgEaBX%(PkYzvNZQW zva&zHreyRcMb@Y&5onG9!FN!Dx9`mbA}|e)$5uuU1=Z9($JF_JsRbO*@CToYSt(2s zkPNq7?2V{B+`VrP4gpq2cXG#*=~K+>x$xN==kw(0S9*{^rvon>+R4z%1)mAafWER56@6zVX`+VlL3ZY?=yS zFZ@}i%Qm$+Vf8g`+=j#mSh8!YL8UuvLIUDt9*=GQPL=MrBAuTpqeReh5aNS@vmKC) zUCTs&m%^I6stF~~=bd#I-RL!PQl9=<*H}A=aUpW*GCs?x8V-N@AV>ZzG-jQ~yU^p#|+e(~7?|uoj#U^U02P=1}bBBq1 z!4#?#5h5$J2p4Fe3bQaFCw+d{xR*t6pON)}z*sETGcu%ll^EOH6b- zQj2h`Me|W1jUi0dbgArwEao1HFB*?1V2TcdN*yKO#n3W%Yn4=Vka`@)U!coLtf%s{`+0mGS$AK6!%n~`a^S@P?Y_$l- z{S5YIln6}pjKH5XUkct>QMZw z6*$M$@k_1nqcEPWzq3>3dd8>aP1|0;RM}QGTmRPu9&!HOVmGUHVL^<<@_1#3*tDng zn?9gPie0-mPMu~HHnO%G+t07{SMSgl|sef1~FPZobZZfM9UH0Fd z3!PZ1QfsDipdebMG+D$#OikQ=q{lcR5cb=fRxnHuEvLeNSMTByPg(BN!(W-s^vmB| z*8(ma9-pGmrr1x;C1+!{L!{d^p6atfi+jYR|U3 z$1Y8B!b@Q1#VG$BvoOtvzmQ)Nz~v*@o(?=A*+XtFYce@nNC>&Hq(ET`INhhmt30 z6IpD=oME;h8Y~v;PmUsG76ZsdCC_iVk^D;5O`<$_`}+SCtV{Q=>niS>$aS@K~C_EIa^n z!jlY}3j&(C|17sw#HsmTGp-ZdAqwi=#dKJ=cS>861u}QQb$aX2?Zf`_6B3BA^GH4E z&VLt`5fIPXn2>+bfJ`4m%ps@`qGcfLN4VLa#|y~k_J{$47#syb|F`wn599=P+9Vqi z`m6EEUmManjkV}WgYRj@Clc#{AhkIqlnBL|-SA}G4QQDIW*!#ZmY{v-aIK0jf+rH+ z2K~OS30hvv|{TtJ^jAkS*#Piu*;>)~j1P+Uq;1P3sLKP8H116fb!fSzf6 z#cgfpBs=NJpeEr~BQf7z@j^5oUo{bvJhXglB|FXw1GQc?uH1=;AWlri|2=}n)6>3! zZ#b*>zRVqL*)jwX&% z_Rkc&R>`QKEn0Dw1Gc=UrzdZdH&yW9W|!Cs4Z1$s=gqXwXpIXcD4Ex>I@X1%uI%{C z#e0j7J|;UbI_;b>=>B0P4yF2wy7ey$+nmE{~AK0Hc~v;5mT{ zDE`knz-md;!Yi%$;c;0K770 zeOl3doKHu?5xra`M}P$iigcg{kh?OwC+f8Nyj3Io8M&7YOHmXD4!BXwmw4jHw<8&( z)14b7#Ncl@hluf>iJ+yJ_iuhPg_U_HjKk5G28Ql#&}8psg^b5%*ob(tb3R zzQ%LL7?#JAR8Bm*f>4QY%GHgntZ-$E^6(I32e(P#@pzEOr;V;et7Al(XXIF(SQu+S z(`dS$E$$++QW*1Q__AE0*pJCFYRz3j4p7azTsAR6sl{6*H9#pFf1K6oDyCy zTzQ`b*En-C0IVoB%3+{)CgE zx#yg`41_8Tw@<*K!m`f!J2|63d5hdzSHDLwlm@Evs%=%#CC_HoG3|%qKp0dje)889 z8t{QQMLB1*78X>_;WwBV(TS!8-%5vX|4NkUj6s9HnPEi_xcMLpG#OwRAUcnP=KjTO zMt%~7`qQ=kU@v~jpE{o@IidwBq)I@uwd)}c%wz~pUFrh_tKsxLR{$wGMa`d2762eI zI~Cxt$!+7!>&e_B)@ME!DAPxN$!l&r5dwVGXe%PWmvpOx37Zs{AB+sYHM&E`c@^Eq z%V(A`w2fZ#uX$9?5#>+P=Vn4xx3|j+CYxYbewcJDyW_JaWy*&N>pjmf{}K-zg_hye zN=7{gWy&S<2N>o8*7DMSF|oLk9zXT4rBr(Nu;GU(KywTqOoio`B;eqCh#f{0TGftH zmViwthw?j+T;1FN=@;cK>wyTh^$M*z?`^qFfP^!%J8VrGWC$uEhO;2X=}4D z!hPKz(aZWMuAeGO6xCvCvgABIPN|y_o&;5th`I|8LA3Y4Q^O$BJPy}csqh|0LMKQE zI6>c7pMsA^b?y)QMc(>@8VG%}D9FJ`@38~K=;~F!3j)CQm}RVTNlvbG5LwRA_yx5= zfKxp3rR9axGhbL?KQma43_%;QB^sQn{M)kDJ(>W}5BxGC2%`}OM$>PGAo8Mspaz7I zbwRwepR5bL7!6tRRC|HwM1knQSB^NcQ<9hnsWd%Ueaz1Bk*;i!o(dl~vww*O;@ot& zqy(|z#T=p?V1j!S&LR!RAfR$#>lFyDJb64Fhe&xk?!;wvrhJuZ=jaK`(lwC?xdowk zad@8H)HlJ?s#wfwgj{(A1@>dvFvvI(5mxPxvUNFMRxOS7B@es#cnoOVMt8Xzkh)Kn za4K8VZ+~mPtU(4-vnqE?3;!Os`)wQ0yD;!J?0HKG<`v#|USxq`70ZJ50<+?0 zn__-xbFGfH?~0&`EjdV#t`CwH3ktU5c_2_~+s)uo9B6q_DhCc*&RI?yM+%f{oWt*- z|H1@#kJ117?taSd3L*6gZFM{S#u%;<9SjZ3dZhFzJmYpgq?W9;CF(h1gQ$9cC2lsv zxSWR0i}Ul)-wN_9Ti*cbhz9(boBz%20B{^L_ma94ub5N=J_@1g*Q}B&q0N$06EUHM z-p6v{?z$TDG(nkyZT8*KQI=_)S=rZFTv}$60^OyBRQfb6^xUwmR+%YI-&$#r1;Y~W zaxG;S05vCUOMC?Y(a# zW3iz*+T!IovVwzd+YAxz&mme$4R*JHs)ff5{}Xu{xf$wylh-l7Zv zxg^l?9|<N@$YN?jjCx*objR zep2Wah{g#3_T#0uG=>1u*Si5H2<^%M9(HI`7&8J>{$#}IbF)(rpS~cN4w)+_S0RtK znftE}GYwR~LFjBvpuxrdR4F^$9VRujbsk|$UVn^CbKH<_ult@HgGOT*rW`&ebI7?n zF8I0d>B!dky(@MX@2yjVXCu#qo%PENTnefg%!Gg2VU#zsunH%Z*HnF*G&i*fwFQ>^ zOhmGS>m!CmJ*+FJW`y_SC=P3Y53kArJC;25B$gFCV$FsZd14}h^Ko02wyhItpufD0 z{ptJP-YPM#v<)r|sb$%mkISWHsvS+pd7H{Q96M7?NHNSsLHbl)4K+Z=V z?q5%FUC%l^Uy0MPRSOIaE$-+fy`qQt2QVH)zQx^8=1ir&k|Y+41AZLE2B(Xx#6~+i zrXNJo<#6w0{4x?p?Rh_JuCGJ&mxwkDj1dsI2YMPJq^j)WD&w5C$hAWTigV5b(YnFC z!l_OP;DXQ~-2&y*R-Yc4ZWBKj;Y)03ikE6S8I5D4a8vRG6N+fu?-Zdjmay)pO00be z1kJHQBIRo?II8!(PAnK2L;O|ie_G{L6dU4zjJ{C#4t|akZVr{{nk<}p-z+UfM}`8E zqRt5IV?sE=%gmr;?Cw?Kwbz&1b0F+&?msvf&@Et?u2By~0OTWWPdc3m)R^dTZsVt|rh5s&7HUPOk&hUH5OXkp(3^=qpcRa;b8K$Brd z#>>;J@eB9FHnjE%h@66;lW%O+1@zhXMia3A1pktb23qfFr1DU<-t94MrOX-DJu$pc zic8B{76QME1Va(Dba}Xv`&N@a6F%IpW>ZRP*x-b{SCh7bZRr6SahNbWO5&g z5|!@ZbBi4Bn1SfDmPm7q`g4C3YQI{9^hzCyp-SHJs(2`mPbBC*T9=TqB}vl|1>|Zl zZK`k0c0;6PF8fgQmg0|4-!b_=(0Su1A=Qwv7>R) z+Hb+jpnOh!6pZxCr(3`(n*2gz5+}()rt(Y`f%b4WAZ#~hi2{RP8&Pzk@?kp=NfW!? zcfmk9Vu0g!xrzF`6{oP+fW7>)SAJ$X6{z3=r_Z|T&yO*$-A|0Qmhiq!q|Bf}dOhqf zFj)A!NqU3yFZrU}H4=v*)g%*)=^qpmKZMu$HN>Z4R4(Pmmo7k?mmws;i@Qx5!Zg90 zsDGq-(_5s_lZxF%*8<1b)koC{lLVO`=(0N7*tT{s3<4RhrOiy~i?r*(e3H@b@HZa^ z7LQ3(xvX&vT_5-*ANjrojSq;us-Jo7n!5mr;1eO9zVW+lTFjJNPf8~f?HXDG?k1H* zMF$~)(`U8{ozu`g@v zhsdC4L$rlTync`3L{v8U5l=!HPb1=PorRJ!UWo1KR^i3o`We#q(>4L$v30JgeM;}Fe{jOQdU_0d>jHw6fjkq;NoguXr?UbYsiUnl+uBajfq zI18A~Aq0w=2tgTHcjAObYCUgfi9?>6y=myFHLz$6L1L5B3Zpd{&%VG^tRE=od|n^d zSnG@6oBxDDO%f_$GwEdyf#+y&D8Njt0$cLB{b@c9se>dU|5m9Of4dJF3Ts@aw_j$S zuAjb~oaWE}2Bd0!Vix=BWQIqo-%oXot;XI>H0$6SML-GFN?)}fG|eS}i2-gwAp@d_ zw>dC*vWTlr$v})*I?l@c1}1fW3e1GFxQ~BNm5oy9oflcOBjeP_m&7J-lK7#v^oR6I zn^0K6JVzusLW_`_yb$Eqhg7IkSrlt}Cq)VJVl%pYGj`?G$iO7Alk;Jl7o(;E6$t{tBp4a{ zPq=+vSr?_hw|7Fmf<-9kMWks{sHcBX-n&}G4i%azIy7P7H`5C+XAz4g3I~fpkC-`a zT=LGz_5QAgtYC18QP7p(QRh;PgA|$Y3ucLAI7}F9m&xG2PVGC>1!W>xQYHv)+RDIK zFY>1S4g12cF(3p)Ja70Tl61a>Jt8d}A}*5TeZ-;G%MAjgph~5hz|Jev{XI68suhH* z?Gu{d@bq@L3cp?o>ld$qf|7ENcg9DwHhjcWdhv}rTp2zCcSab!TyP^%7-IauC{(A4 z!bE}b%n`2E%UY_kA>ZqtoDZp5a1sX@dnp;D|MJIR@qUJPI!ynn4yc3ji{eP=Hbqak zuh%I}YrvE5b%I;1r)_X!6y-?Mv@pq7(jk;l`}j8w>fi_bAWBNB6z62~D3@`=h>)Za z+ZqK8a9<$IoxxR%lQk^cV^TiejY?m2VzRS_zvK71@B;^^uYl7(-{_FePzo4 zdux(*_kw*e>w_3k1Yxg&=Wkjpxe`^B2aym%LXfseH!Iy(E2{<;o*|ZMA6{>}Rz*Kv zb#mqji=9y@ch;QHC517t{tZQGEI}&2dxL?<*Qce9XX10hm{Y@&oaNZm6Bckm6mc!= zky2SxTR$~9@?To>Od5y=6-O70oOeGMN&*WFB27*}rK^qG8~pekQ+i{d^a^E|^ruf? z;a!4l2pUz`d@ebf(c#1OVbk|(hBp{<+rvRwH+Q82X#hx`>Uu@g+7stUWq79#Lt-G@ zn#6qoePZ^X{!^d+9rxl#SH-Hecv-7)`=HXaOxh5yfP2m*Cet`w-(HD$_c)qqRbAL@ zT$f5G=Gq>QRGcguq}uQ2cLl%5veV^cjn~J^1vErMtWA!OQ!Sf_ ze%~zgQ#2rpx)_a!0-A?E?O}m|n%*qXOK3gihJYZ#65-EUCh=6+j|9N=cv!jaA(rJ* zP9z_Nar;c{*;R5y-iF7D3P|tFwEAjO)h8;qB+`dNcloL;pGS)TWdqW zHGck;2~+#X+vU+Nuw(J@YVLgG3Wtsx(W&kHE|12>*C{gaFr5BMCz(MrF$8@ z=_hd@)joJ&7lb@Dkp<$01!|mA1^`<#e`Yl21#>CSAJd}8I?Rw3y1f)fhS*JILru>z zCU$pB;IEZ1fj$Bg^Ry-M%(lgPos~&b!C+ksoeJT*DW(>()vU{By8&eS4VYN2tUa*XPeE*|9qT&L`k`N)>T z$FxE+;dJpOp)^~j0}f$*IK>q<$i@221k8|8!uRsfGl4a5vIf0&5YBFBE&Sa)H&C4Y zh2Or^BC8z=NRXQR77>(CSQ=r1!wTB<5aabVibn*LGX*-GqdO}e0qjs(75|B3Di9U# z*>Y<-VlszYUBREz9m0_THH(cc%j`q=d&CgQVtcz>t<-|4t%fLv7$P)h)mc;<2(1N+ zdMKi3;3bgmLKyYMm7j0csmCXsi-{_X=_1fcE}{Skwx?N;0zYtIo6P!w3zXyT7_?`4 zb4?;B*u*HQ1&0oyUP2eUBdAV&d6=|i3b0RB|D;RxB_Tb{ih=Iof^euHE5dEoxJBVI zL2bG4$(qyT*$>l2iY&?J>1$6v`lf?lJPvq0u#$ZK(pDKOiN2Z9)~J~t`NDDC9TQ?i z2cm1$<0Ge2hef)pNB3iVpNzdA0&87gJ08@Y_9TVFyX)~z%+Ij3+m4^tClnr6ZWTR_ z;yh~U|Ka)$qsSXEUQWuedXUsl0Th?O(hsmWEO!<-VP0fO5) zTq2e4;qJ<^r9{C+7)ncr!8r#-`G8E}@^S0rgayDz*!i0IC((s-genjxfIx6^bNKMT zx*wl=6K-Oz>*%oH9jT{;v6kXRVrwZ%4{w3((j7>*K7Yd+H_Yjwx|HKlz+lA1M`kNN zt*brB0y)|O3;9Ive5_f|A)PuSg~!LX(^gziA_dAd#I~-&ex*K0#s;PD0cDYY<=9NM zBO)svH6nAeBp|@yp-J%1-DV?-i;%p``A_qYM)zAA2813F9}4|;SCQNKa@>v2qPN=L zr}OTdY@wLTKqwaAHx3!Rlg7VmG-`QU&p2NnDEqKUnY-1|*_^sGk;nBT^>q{%;O zkYPVXEh!M4Cyki>DrNW)c^i~JEwX7lHmR@CJ_L3%_g1IF9k*&IKJG^PR~;+PG1ON* z8#vdWAEzZs=EM?sQgMCl@^s?XK}ix3s1w1E!`cemRz$z13TcGOJoj?2MA2P~J+i1q#??+;o-4!D{CGQzh^5F3}!YFrg=Xe1=|+`mb=?8kKd1VYQG6k0YCQW022!axB<2xqXfWomY(FQH*QgMy`xFiyma!w~fvM7ke)3^|hMj>G^*XwtUArcZp zqEiO4;944ki?^1SSK5Kx(mQITbSz^#_U9S{*}6<2N-{t!%wp>NY& zLiL3gn(dG~SoQ^|K^JL>0H4j9X3Kpbf%6o=$ygOc{wUW{iywU4T>)I2<slXd() z*NNPiMH81t9wdr#?q^;OE(oyueds}gF@$@gJt=5;t^pwfD>D}7(o55y#eb_}z>kon zvdkc>&{m#S$Tw($XN~Xn)|-!2YyBHAxB4zYWT(Q(_r4L_W#+5%eWCbj!JeKG19MtAf<-CjrA z|kic@Hy5K@5QM~@%4dE(iu@JvHuu_!x| zKRPWtK>aekR8ROS1+C6lT1s4U2)%2NOlwybf1}Q_LUxK`JN9k)_T_-FQ zkKUboj1xZ4wHSHf+cwAr6#K-*Qedsu%AGp{xyMHm zQ}Z*8^b?m0T^y1X*=>q^dW93

X{64KNA7;V`|7|6ccE%pe50&B$G-NH;^qJlY?Z zfvgqZN^6qIk}Dn0wHoEiXU~Gw^S~ojHzwP7>_H4hX43tPYUPHB8~Ec-9X_B3lmN2c zm}F+X<1N|bWZZ5kxL~m^pEzu!G1`SLa9VfJkNg>LnC_(>=`zC|w`k(>5=h%wn1UC~ zpB z@ogo|6?lH3&$vwigSq#D5W5#J?!J27}1T*Y)cbK-|gH zh}pVuap`c5-E!4XmsGTDCzkt@H)jN6q`~nJMLi{e)!%ozY{fGF)m4+jRj=NX!*RUS~z4g7D4*FCwT{) zdJ*Q?-uM7z6HI4ZUL7Qb9Vb@jpNk1}%m4t|l^afu9k#SLK@s*}e}f(c%$5T`cmNn+ zyED>tOqpP@*&vr&+w)Fhh%c1JKrjnRLtLn;W(mJX5Wrv^EERTduXF29C`A~=gF7AQ z4g+!l`{1!FMrm3ffV#TDDT1Qe&0znXtl1$;Lp9!wjKi6)DrNy=X+!lIJMYQil2hEsoKsIX3k7NE`3q%s@u=chEHJz=H`gcKKk*=L*lU>;G(H^-`ai@V$mlgV!^rWuL6so z|2{m<4+xnhyc$-8tv&y^()@6{LI#IkCP%@lI4CyGM_r-+VJ%QTHnf6Dkd^wK;|TKM zcO4*i5y0?nTRor94r=rlli*NYk^p(jVJ=;*_1j41F8ryIb|b7mO^tt1v&h`_#L)8+vhvJy*!SH&N4&Dw@;*KDE<@ zQ#?^}9g#LG!D(!vzl;MZP$dJF+_eZTZ4VpN7AF2CJoKS*l#)Qj?7F`CF~jw>hQdZn zs{gLO!>5C^6~peXLN3-?@27rS$-c&oJ9em~@F0oy?qbXN+vaoZO6+^rLmGOMaCBB1 zXVyWiR1RN-!SN9OD8L_7kxJ;6~qO^LsrAM5#CL+4qTe@&HQ{|KNxQvG#Uc42F zOl=70Ah=BiRC+31lGs4Lw79CS(^lHWb3AffQ(bY(^&Z$fDi!J>r6o|Zxt4-uzH9)3 zQ%#L8a2#_y8KA)$pa7THF6Hnps&pvy28ERMHb?IC!fs?XX&!ab(itd_X#9d*ye+3T z@^Sj@9iIHns%CPN8(~%OY>jjfa2K@*wz#e2lt?CZKS7Re{Qf)8b*_!Ym1JG@g)e7J zc~NyZ=rH)w=lTOV?bZ2SN>u`0cb^mQ*hVJX*~|J4wS@&;@~{PWy8jq$!I;dXHbfro zodcri2d8z2e*7H58Aj+Em;?yNM1@d=eL&^lj#;Dw7X*=(?ELsAa`PMnP%!Ln^D@=H z0&|o_b6n5ZTM{Cm4MhDkNH$sX#(v!$Nzd}`|J8&={-wJ#J{(iyQIwu^c_$kMkNf~Uk10AWL zkjFC$V@Nq?rQN6%8Da5FmoU&j6`!e!Js(weU9NILuzm`07Jwj>c`)i;`BPpK4<+X> zv%!qk0XC!*+L3hBe?e3KxETvRxSR%E(FCuauCI^UtgzZ5P-ei{s5qIe(471RQv@W* zWB8>ajA4*8BG1_7l2vUx8oN^_wto#ppb-AIEbKFocmCuE%%N&G8b_1`Jq?)~erlK| z%1$yTfu%7X&Y#xJ$iv+iL*RcpJ}*|^U~z$9JZq&{v;K(7F!$x5<-m95DPs>RJ5$j& zjj2@8TY}Sz6BVRsx}-y`2kR%2=S2i^NbI11U_ z+ok8TTIi^4%|ZgrpWYueHm)xFqln!vhG>oJ&4LxlFUz?6+4Zr38$_2ywut9diNQyv zuxyZkcvEm+`8k}5L4*1dhf1rQf8Y-jE*uO(tGpu}AEeT>KtsYkY@fZoI)m>uof^PV zN6776(P)b8(FVeS{xxk|OZNAUL+|M!#~4RG3G5H%h5nRFW<~u~mWP7|FS>`DBsd|d zG0yW;isBkD&L88bbg8VQ{FxyG+py1@6_m(u(iA?(jF<(hyezn+!vy48X&D9=lTkL! zSa4Eleu|+>0_i;ubw6W*9K{jnsjNpdU~Kw~uxRV9iUj>Di`S})$oGVdsQoq-32GP) z;z69%#d0Q3$0sM7dwX=M@r+2KN%hwb527%(Cr^Xw3qhKMQrLV4@Q@7Mb}s;0KOlq9 z{CN2&ivSu_`q|zl6oDgnNgNClhOpYK#r=&RDPGowx?y%E#^;I>suPGzFm5z~S4Zko z{3+pqL%l)y{eAd+GhFY_<<>+K(}9e%l96Jw&6+5L(TJgPN|!#Gw5u+^`B7!Ql2Qb& zWC+_J^bqkd1z@0~liwb(xvW?MiHjw^(OJ`Z?7G>0sCEz4+2Ne7#ypsH8E3B(pe8wd zySL3izdzuXewj=!<7pU<VE6B7q3EnW4k8?+t(15xi zpp6%cAa#JBdxW*h7+BS!c@v?kwp;a*v#9V&UXt-AF|~;rdY72HFDO>D!-63A)f$PL zu%plTX3uj?v*P`il{i3PseVbidMrjqlX__K7$Dsw`Wfs8+shl|=VJzgPQY&i10vmA zzrjj10V5>V|16e2F$|}A+pg&G(lIq+qFA0&)gVcu*iZ~S14DWn{93#`;TR^X?K0Il7w?+fb z2(MMI1*(Lh@iA(6zeyJT*}--bj@00nWr%0y@Fwa6_g}#TW!UHe<14f4^{39qEsgCb zx=y1QI!jy{5KOF6Ifi|Xmf5QkVjQSn+x4O^DuRG@^Z9nIsL}D!%heUXP+HbNQ+$@6 zlVc-;5hB=p90jaJjhouVp>MjN8v9C}=76^i9Dq`3^6s`FHV1BU`T`eD_E5WP0yDo% zQ(4v}Y1cX*d}=A78lV1Jg{_+y_+0KUJK2L-kUvGeVQjbm7^~U>XtUg5zE+gYACH6pxu036d;X(K1)Tq)_D1dEI;`Cz}A`Euq@N3jN-=5J@l>Y5kG_63~YH zj0vb{^3*dcxOS0gf##p+mX6f8({S-x_N!m=f@{GvtRJ|}3VKa;yT0a9emT4BdUmnRDB**Gi&4=8`47J>e@0>$O zkB!zzx$a8*q1J7@encH0)O?Pzp+NZe8HwnpPzJ=#-d=pprMUF3YbDge_6Z|Ww~sMT z`Us#V1e|G0+~C18PtD0u_YvC$Es3hRyv7>LqACg#{GpTTAp+&s`gs_c)@qYH z+~fg=lkQXk*upL-^m0+QBQQZw3$t|6YGmah&roDY6@_r zR;%M}I#x*!%RdTbV)aSJ3>$;W)o_OEFIBlC6!1n?LA2gnHyR&`h|S&N5TxEJz%s8t4feKZ@} z!B!3b?9)N|S9*wuZvU)%R9R5E2e`}Z64cja6pHBh62Zjd7ZT80cjIlINXERN0u4X) zZP_9oXg0j6rTXp*if~m1CDG|*HVC;Dj320*8veG&=Tb&utAQZ!L60SQ;uwMUT>7Tk zr(b3HGfH(K^aWUAH>q2WssZcNgJW`NNY)b{x4z~rDarHpq|Z!yK2$(0BinWu{r#M3 ztkze(CLpOBn5Eb)H+8vWISF<+`;_0BXuTSWsiO#z%-E*fhLd?C>gJg?LnJ(W@u^uQ zvTu_u<=g?^rFuiU&}L}s56r3q2D;6g1UzJ^^W;#0te>ogfTcs1XAdZ-3d6}tB6#6l z4_YB0l_GN-IiTKIIT7sI*4uNUpvmIdKbrRF$3%?E8^|4H!*f))^LdfIz3hdyU0aN%8)p_LEyBx3A;DD6{{$TwOgM-Nw@hr z6<%y-ldC~To-ish#2Zu!ZL5;V1ekl3OVA{K>9^wZ^;@y-F9R5KoR&&sL6VRx`C)IL zVym3`PK*`j@WZF#fRJEi|HllfXAARp4|jl=bsb~)<(*Yov9IWuIdz@JP)@Nl9(Eh9 z=BJqGW+e`ADf}8>LIz zh;b=~vF^O@3|C)}j0g1UEaeTS&WcBHxq0ywf!(Jf#q#C*=Z|?CgYt1aM4247JQ>?L zyYkP(2vQPK;uVd--~}Lp{`XB!g{X0g6)Di>I;t^hY32f4k2pF1A#*Vhe~%>@0*7v{ zL5f6pNASWbbQz0sL0d|iVz_c7CnEHb?W)tXJ)pZCco$#`%!2Z^MVEPxW&s6WDT6I3 z{Q^^cMoH~I2RI(UTlJ*?O$`|9CH~Wr&Cr;!)#?({5DrbafSnU-R(&(e7`$pz$^GMC z43iQiQl|?K0Eh=_YH>p*|FlwDNCxHc;gHp7u)=f6vd6@y1XZtDa3drvCHDV3oS}TH ztC!KriKnF|wO?#2zEQ=7{UbQPyxa=}Cwz_xIo4mcjC#5W)Bi|FCP->>y3y3Wq}g6) z$<<}iP?=#}{rh*wTaGyJM&{CZMngahcx@!u%yKyb@VbPL!`4i<=H;&67l?j7Q@I!H zz_wK>O`Zc7TRqI?wdJaY_)Q(gIKGD2i_g z34-{%V%>BlsgUVQmZr?|ci=Fm@nV!!9Nf7#NHh0mSbCALA2Z53j4P08n}AAmIQgFz zhf2=M$uFnLehWd$NR1BC50`B3ujMFcD5yh{ZpOyVK?%h1VL$vU^ORZ0vLWS5RIuc} z`r7m)j7cyDOX*HQ3C^K^1>tkb0X?e&*(@?VFpiZ|%ZqTR4g2ddaE-O~$rKkYotfbcyB$bbU6+WvV@n{1Y$;rBg){6BBxd)-r)sZ@)?o?Az{y zBZ0xNckZfL9uAUOSDiSpBpGqO;8)l&9q|}Dk}J^>bVZ0Nm&5vr5D-K*C}~1R6)cvo zmyhUWk+4X0ySwT|r&6Xk7%O$cL;8R}_khg;0WCTIL6@8RRYt@)@+fLEbt~6n!r!yE zNg+#AGjB7ho6CUOF7$_4?fvvM|7`m8#*ZqD4ltlz?(BPpiTXl$c}@YQAmU#^U;X17 zqE&(4W;m1vEAFc89&5hBI8&YW5^}3y=q?W`OtLZ9|S>U62!wY;P*^Ya(aj-bY(TnauM0*!ccmu0F0|6F59PQ&)DPv_c^A zd#yuA0u1JM!lDfZ^MwX`b}P3sb3c#lC;ybZGRCD8;-{*K2JI+tulbu1soSV-KM`+QKSE2u#;nCUi2`u>Y^$zgDg)Ysw7 zpAd%>HOax-!KlgApTZmiH)4y+ekbC2HMD6k`Wut19eOz$Rl6^2g72zCX}7HjHKz-0 z&8uq;#LA1O#YO6{S@t2Vx<9%WhwQmQMPqi}G=vta=;;#718n8g9!iqRoO5%Uz-!O$ zOZu`YbrymAiz(na{wbO-nKc}TE4lENJLOE=TA8Cfk|fm`ZL~Zp1HML=xztu+xwrqqBb_3i`2fW ztFG$I6Fwm@PW_yF)gMtpAE(6%l`PVZ)YiY4Y- zdEB!JWj`V^TpQ8n(k9FQk1S;e&62E&g$re~yntAqvwf z2jN-HZpV>0mo^=Q5|Gso>{y)Uu$50U3Z_CP%j*M)%Kd~x6k#;FWBjSZN?zC>3z%%K z?nhSMC^iw2E9xaFWgv+^YEP2`+p&Or2!CyF4r)AU(#pz8z&GK>^ARCEf&a;1#YicZ1~Gqy@j0Y|>RvG-SM`}7hGS`}hg z&1J;zQ)kvsec7xJC$2wDFuyEfE4(ycFf@KrtsQyf%#I`6f0?F+(}gx4(=>8q46Yu5 zjkPkT8=6iLLGO1%oj>`^biR2g)sI&}5@h!J7ZeZUH%ObF@)tUq9G@8Wz%lCd8v+7t zVY@69=qYah(Qg;8!a|=tu`FQrmKV9N+k*?qQ|RrOvoh=7m)rb3n>bjzC|f&iLov%Y z8t8-GF@MnUy-S_n3R})Gfl4!K$Z00Arcj#h=3!KLy@1c>lyG>wzP}5GiVywM^DJ40 zFRq=pY=1HPGxrXkTALQ2utXC)n2JxGkJ5nZsWkLuL2B|lw%_Aeu!-U9*-1Cy~5CeFlcV)D;46ae~`7BsQ(N%$rtw^BH)8{d=Io2mCDb zFiawZ7*nbJi42#Sk=pM(%8jxU*bh=192|VRfNE~B6&xmu>G0hzj0gd ztWk8uE2dNJef06RuCB?S8N+ycHI3?nDnU=hCoM_2F%?^eVhfL36V3&6pMWVf)7a$8 zD{<{^KIv{f=@SF)BlyzH|<`f_8)_aC-akAAN?_~tg6FN+K+@7-_wM*R8$fRS4eET(MSqVK6SM9r%v@- zI1HFE7Py8oPTYy_?~ynrgWX;pFtmg=krfAB>U>M3hnwm>d~|1_DWtJFTj}#vr2IQ* z7mD?X+JGn*uPQzKxIOhPOc}Ar^oVYcN{EEY9W8wq@#-0un^k*OeG(F!yxtXe7X0cu z4&Sffc}v(|W_hy?=h+jcb@jq-8WL74(%xL@pMgh}QElH6Ph7ta7k-8N8t$J3L}2Fb zx6LGFbAMcsB+W56A6rL>(4?NSiYFFg3)JJ3Li+WrC|I_`)^Q&b49S>!IMB0RpdetG zdnfSg4mnc}{v8O9bF7XWqF}MminIK}5<(ZS^OTIU#o|X6)>y_wtqKmQW>ci9p=P7W zHG(i*U!Hh-1RlN*Ikmq$<=Z|{k(=u!N%EjOFKdrwJS~ucfTYp89&5I>G>g?={ttuu%Lt{0|XtY8^ zxH2@5=MbAmUp+%9^r`j7U4x{%o&MQ=lwCZX;vjBK62Ln@q-B%_Cw*GpJ^1_OilZVa zm7kOJpxG;2IQ1L95g7wgBLxSplMJEmTVb8xpro<#r=K1F7@FH1W-VLqJ3498Db94N zn9QHHc?wDh)VyV8K}~%*{KoWFf(#ExCqG;_f5wrCz8#Ie61V8gDFBOgmtUIi_YaP zW!XdH|0(WF_p-k+)~*sjMn9*Jg#64P!rsH6z^I0TQNk8wew#bX`McP@G+@m zed968N*?x9Sv>tpP}vYo+TBU}u^OYQ!^?}Nn=%cAn3K|I5jnI}xxR(<4Lu%;?c2h{ z1WdIJ@?_96v6MSxT(eT=S4FvtFT@WIGn>vg(v4GY)ID9s6i-K2pI0ZxVh)uFCQ_B9 z+%J}gHttZ3lwWo;SjCh2b$HjBP?DRI(0NfRI&o^`SLQFPZZ#_ucjCJjS@aO4b(h!3c}GX9M>uKYYqZeI%i|sde54ThF660pTJeu^Qo8isObUN zw^0!ihmzk2;|J{D%oKh_uDiG@ahY_x*P%!h!C!x{$@`p>)*mm?J==J;r(Xr4j%lcc zf;y2BtNT|fNiYHD-a+E^a{1%8d#z7!F?9c+sEfji+VO*V)B0^{{!A<^J_BX!u7+QA zy9raWbfHVrs!hAs#2Znz2~+J|Rmc`e^h9RJfDXwX8Y)E98G~NF|F+|=2ZM#a4htlM zcIZmAL*`=7Q)kKG~;;MB> zOrbQ>Xy7_fBHW3mLZw6YuID^1tPu&FBeJx&o<7$yes*$?>ga$3n|5?I&F-3KTL^Xs zNb~lH(0R|ev>{cE;Ef-;9yw3u%o{TABRgRzeGC2byH1TUQ>e55tj!quPsXIdE#?&$ z`bE5k_$AUlZnM^!0hg=5zcQI5qK_ow!Bbt@yCZ4l3Brm!f6hz^_iPM5u!vy7Tb*IZ zpH2|`mn;knX(*Oamu1Z;w7iyJ+qA0vd?U=p?cwD)AYBf(AV6_S0!SylAnpp((X3D zcPwLMd~xEQeG2-)`-Svts?6G@c7>l$DbDA7rGtKsFm*qEq=d|Bbou&M{2+RhxPdnz%8FSSz{OLplo=9IySrwzkWK9lF5tT`>{F8OyZ8h-7J5G4~W-y=)DX-;b*u92b@N8bhO^BuT#<094!D z)`nRbU9P4=FV5(Hmzhf!h(_9=c}8Y0TbAAs=>@5GH1T&8cs`ST>S6+TDwnp%0Yk-O zmr*~7_ZP_IwWjz2`IQjrsIIre?X|jDlz5(Y;-tgws8r<;@tC7*5^T~bomKkIibkLn z2s`VWx}vd`$>PBGQ6SOv;04>_bH;*vwz2!NJCJB5$BmOe@OP{WnY8bvXWnuE1!Bi-0ZKlkDoROm=Pm(|CSYd^xEF+ zL3_Vi{ZWnJUnCv^YsntMWoMEg8ZwRV`)hS+es5asacKh9f@mo%Y3J>_X9_S~LuJaS`R z`ntqNSFipE6er^u)6xt97e@Q&rS?(XwH#TdtlTtcZGr z8~B9rxf5-uOv=5QzJjHcpfZ~&o}it4@Q!Q?lgFh)clY3RLIht-_yF~$J<-afIN11i zgud>Awk&w$xgWFMRDii6!l(up5SEMwIAJRWDTTl}>danoW4Dmh-e@E}l|;15|7X7D z;OR+Rnq5vgauvQPScR;`j}xN4h20_u8RU2(wrdgdHG7NR?<5PWJ@ha7$De4;HY!k( z9)-XkUE6+=TuUZWV=`gbPi{iNdxzb?CPSU>wd$Z9XK@rO;{q2)@26X(S1d;InaY7H zllkbwj^Dqc5|B(jap&s-i}xigN5ug{T3kpW0vjU)X6t_XE6g?5NTcQTNZkI%2-5(! zoj_NiEa0s5bU|OK=a5By%IucAxa(_s!84wqb<|oOp&^`V^R&jpV18b*UZ|8Bd?w<{ z;xBE6PmX}~Ikxr{>GCftE5dWyi$kM8L)0)Aj`l$SO&Y)<>U2w2|LVMhI z3<)pDcO)3~-;*`O`71?~i~39tW;sDcS3xdlO(NA8toVDk0s?gffoKjJg z4}Zga^S2s@)9-Vw+Ul+z_~OlaMEP5NdnVl*b`y2LHYxm0?STFXOuLQ5~ zP|?P%nbh&H$cv?q9*t@ub9gFfL?(6J=C@x7bfCEGUk}71UM_lmZRY>At6vID0Y1r8 zeVTNFryIOZ+4tF>N3C$Ob5}vi%RPSm?Xr*!d7dXjcVFdqy}a#MYJ4zSp8@GE0=ZSi z0vCs(v-_wd zw~0^XVu!Yr!R@}w_xDSImUM%k5Z~>bXjb?~Lb6)b3g;!SX*Ge=v5v3^kjgel=NZwc zW4XL${jB$-u-x8fBtdrF_|IW?9#V;_I}MZspI`~$j&zUYX2)(0hqe#zBlSiadAK=QbqR|BT;%_qD9OkVkDFr$s*eturJ zURWwe#161C6Ngyo;Ye^QGdLt2c2FqY?fp|g#0<_sjdU00_z+OqACRmTu8q`Uo+NL~xNALfU1ocrIsb&g*)sU^syHDGrBQ2w5$cjh3(2!&JjBhkGcy{bE_ z^HAv}-E**t{KnIo{gNGknDNeZa}Wq`*fHcR!iG%wtUnHaR|TqjCO+N``^vGHzJ?XY zEpLR}B$yZdqAFX_dVw(|3ASUS+cfd(IqNIMyln24;x~;`=WXLz!~u#)ABR}bcYL84 zH-$itj}BX@MQjLZr3pH4rGgt4Xo?((sZIV1gG>R6id4#2ki#THk+S*T=lk<9Texpw z9(_WgbfcyAVaiunu*-M;5cu%;VKSk6w2FVg$epY?wnaE@lb8D0zfslCH5h6pm<}cs z73YvB#7WHum4jmIaG^@~F1U+{5vg++xdd5jY}n>K3=cDsgG-)4)%~^gm=CPKp6*bJ zA+<{5${vyRcSJqAAOD7rTc}HhAGKDv-}LJ4fH-Y}7tV81E}9jU@U!%6f6kcvONw;k zw;2ndxPG;u0uOSsr%rrz|G6D!cOC)>!}vFgFCN{|E_kV9TiIh*WtshJnQ^ zLp)R&8_*8H2^ZTDWP3^o=9NmCp|L$1Mi8&PX&XK@+vvwR&&Wr2w7?1K49xoLCFb9& zVY9Cun#^W>SxchK)k9tOCpuPzhlV21?A<7nQRDj3^6}GT@TB}np*$k?1UX1dvow^n zb0B`RE645yp#t!0`FKP%d%x)&ZP)dR^S(&RO;Rc5l;?&3{j3WK+TLf_CX$?pdm|(k>d~(IiS8eyEBa4Wp6iWY1HR; z@eM@-TO*RmCSp#k?lHD`1Yq%IBWd6@_Q3%XvDM%@#v4Fwz_r6W(Ck^Q8LqS7@91`6^Kbw04vd|PHX)F>Yd@S5sq-2trmaP|SdggtM zub9S}tUixv27jrb+Ed$E`SXDQ-O0-fe~+)#%L!9e+J4~-6B0-^(^y~ux7R&QzDtA} z%o^bTeUI#9Oqm-$mMl|zY?BIFNO7Yyhcn=TNU`bLIaE4X28_+A-xCunBahSe^06}_ zpTNc~CGQ` zQ2F;1(1&YX+`e4I{cQ&Iu)DA=iY@5t70vbpqmt$~p)g7t9ffv7hT`E5= z4|0@bS0z;rC1nUA7rDJ{|?cAGiNs#3%h3%d>n+%$nL~U zvX}>+ch`-}7gt<}39(^BV7~(o6swp@Ti$&eUc+h{+*<_`lOMW`&cG;`(A$F%v&oQ1 zKFeE;mgoq6<~ITZ(7(K5siS8Fg#hN&EQbk-Bx^WDen~@-@2tZX>PD{L)ljw`F>; zrG?!66O0uv+}J4L1jWc&?Hm{Np`1c0^NRJ3j3^o^-}s+N8IAARCofA+p0d+s;}dlg z$))m%!V9!Dh3Gfsy&u@&^xjYoP+_mAheW#{bH=;w08_xwNaInyY&p39S~7iJbi(*C zY^Xf2rqpY=_3j^08Qs}dx9#QoGlU$mWfvSHFH=NrMG0r~?~*QLV$zyMek5kA;Vo9m z$Kag-gaD*mYQJ0Qyl7baI)gF6Gt!hX%Q`obeR63`6>*TPTHl&9j=72S4ifh=nJQc_ ztFjJUMX&Z@#glO#ti*HahSd@euMIy;=8`+lYCXMVTybS~f65|r{;4<1VW6RUkxB*1 zeJ+Zn7v>&rS++GC`}zeFbu75r5G0GDxj1KU&!Vz;P+e&b*}G)=;CS_5zCQPgP3@v} z!?$6?snh5Fqst5js2kLvQt_PO;d>QqV+*S_%@X$w+KqN+6U`^F5sKT``*Zx?Oh<>; zIn#Drmj>4)vJ@A#lf7qk=O{yicl`=cyWL*i$g#1;QwQ0Ff1!3Z4WmhRN!5&@cmScO zRPVs=aWbapKm#Bx8B2O9RDEk-1BbD;xH3wNhcYahQ!Q@XD7>E)-HqSKy>^C=94hi+ z8^SR;yCY8%HSmP8MTvwzq$^FCCZ0^Ky{A;lp(%h24~n8BoL6{5AWLhaSKz3@kToIu zh`19kJ9EV~;&;SOWilat&Gq5Zk_+f>RfSpE$wu)xA_>a_pP?&aD_ zTSwqCrW|x~rSLiyE}kKtnG@@O?CcS`i@PA+>Vc+d*rE51C`$56Oe=km_0=>RGIMQ7 zLDNO@tsW@dO;nQZ`*Mvslb^c@2FDv0+rw_W?CKc~z`ExzN%AeI?)v+I#S;-DYO&~; zhWYL>$KC)oywJiiaSR&AN+@-Iq@1xtF1B4>ER(kUgo(g|LeeuqhD7XHNyTSeLCbAv zJ-Cz4JpDfPrST57WymXBUWErnq@m5B30FjFL`4vMJ8{QEHdGL?rl>L8O2r1)zXMi& z>PQ{sTjcg2rVHbWFG*}b)d7=*xj|p%!hFvHg^fFwePt&7GMDJL6-Gi1=Gqxwktsse99y)&(eO?tYKwx73|(qbp&o<>$8wbz*^uuKptxP z2a&E}zP{nu5hx@fWI(S&H~9CWkKDPB3i&i!gfT`?!8^kpvn`^t;#mG1Hn-Arl)NRO z&3kie?sF;I2o1?sZGV3cnF;smuisT6;Fc;!2J`wsBkRSi-hd64a#w4$Z32|ndS zuOB_r%m?kVwF)~akC1ezZni$23@C*~REv^t?vB2v-|=nsM#CO_R% z6BH$F;yb-R(fo(WDNblc@02$Rqv0WNV|5hLWTjy}su=Yz@-6d;yZo`Q5~HhF!4zjp zSK`OsbotOw^=WW~ zB^Y(6oPtEkxHg2G13!A-N<72sXO}8jUtW>M&o?ik6$e>mt(CPQ5&f!LSyaB(wdKxH z#_|29Y8<5T4Ors?DzCr9a@K0gIk);V%zf1L7#{f107(NeR8>rEADd1=5U^Xmz$gQF zrUOMhTMVHH;irHOB+tU5s8!G{?94xvH|a}XPCO4!hHHEqzPLR9%)TIGUAwEpVIE|L zj?{!r~Jz?WZ-oPno#goacFsfR&tlg@_S%t>89Z5?2)Qf5Os^1l@U z`^!uD{c}>f+gK6is90hmF#sF~zf<5Mv$?9E)5VqVh$Q-NLk`tPF{c|Jvb8F3Y;A4X z5@T^^PDU)V)nIaMFcmoz@2@4OUmYguy6Q?S3v&P1fuSMNje_(k7R6suxZYp8A{x30 zj+BR6PWgJyUEqDL!Y|YV21Ch8EL|B~?p)6MuME0mKWu?WM0Twa$}W<;R8&6aTygoLfR2l`X06p5HnY++`dJ8Fgimuq@ zH}2vrp0wh4U%nqbvYi*#}acTcVjusH{ ziT~x5^C^<1@EW#B)Le2bIQ{0D+Si&lq+>J#RacbR>vfn;dSefm z)(yI}?J9p$w152vmnU5%AT&@PEIzf?cIQ;^ea1uHls$r(`Rm_%)~uk(k4}Q{%*=AC z?zB+D-{_jxtpkT?vbN3u$WDTTntB?yoWvhBi3EId;|1DU0r`uC%!Y~}1N|CxV_sD_ zP@)nWdirJvrMFVj)h-&EG!_znq9Y1z=Ay>J4}w_ZLo|>q0i~Ft{tD{&u6iI@6)ODS z58_?(rKK=Jufy3sC{X*z)i&~vbFMj}wd2hW{FUrJH0#vj^{$C9C{|PT=db#|`8IEdypO-$EZ+~k&EI{iTJ^R|t~qKt z6o<)-1!2p-bmHcrx~PrVVBJc`Sq4A+vPeB1DvZH~uM~tZ1jOB`eOP56p(s_0DT;EaBV007OeZz5iWBgR3~A+aI! zC!KVUJmkZx9Dj|NcqhSL#{+jPF}T0a*Y0<=c{bbXFhUQ70G4v&;2+RRAK&=r%=6TlFEYBH-SujLJL*l znqIO3OF|DBanTGbBv(T;=QZJv&x|=N%42?8?)d(0ywFen5fMfq*+3DN|D#Qzy6rsR{_Mxf zl~}!Ym}L}MITp*eMDKP-Y3niHVndBdu(FUdP=f)pC#~`cQw;preF7>B3A2)L@b(Ss z@=l^`{)KSA<-~cBybS2xfLwg|TzxpKxpn7mQd5mR&WkLHDU`8n8li18=Fm}-FYmdZ zn9!APy7DEIZkt*W6rId%7V4^#{AKWN4kaTk=mKyI?-AQAAni&)!J7rbB10Q>L z%=qA8D?N!0V^Uk8hb-uh)u99OZP^$8MQzb#W0Z1`+biW6!X&BA;Gw9rh^e!3K1=*D za^4scGCY=ad%!NO>putIKz(pbZ2SGZ?4dlf!!s8@t>E$;yL*9J`Q_q&`92i2kQiEuW3Euxr zf}!Oww9=R1{%f@UuDyWBV?m+oPo#XA%T$R$c3t@!Tp zo*NJ!B0Bso_@onif~MJKK8lva8cB&gGaPc{DoN%0{!N31k+oMdS>7w3I9=r%5^G$e zH_k1R^y2v!x&PQNa(apo~|xI^4_9WSUbWYOI}NF8#yVk`aJjeYW1*tb4_0u zPyf~$Va>hWyv>5S@Pm2d)x=korEe0&ip&3UA1Ou1V@yvEKYE#Z^2cv3clgH?k1~F} zb)|h=5LH8kw~McCSJc2+MCle=vXi>1o;GW5NzS%kzuAaNoAAg~`?r>ly(K<}hGRbw zG4dvkk)-P*sbq^m`4L|Bl}M&L@Mu<~1v=vCp6f9#0Z{hOf}-54jT0ObQ-o?7`hN~n zxR8@yTATO&Z2r_I#|sQ`jK6Os`&!i5YB6=Zg|p474z&J>8`n(Dp78%I-Y*k6`r&oT zZBnCv5vceYF^hlAAf!=EMNvC&@%LGC8QH37LiqL1zH1CK(k4p?fGhKc-9aneY--@F zc>Xy>!J7Qn!Ph1i@h?0LHj*IajM7lKLQpP+Ss2Mya3GM3Zdd^>_UI{Pvhy zxeOJ}wV*`+y0;%@lp9%OL(T~|Wjo728-kzTOL*;kUTC_DeNH@kZG$7MvE zz?4UmMx=2APrRU5opmhOKHmSN75*rivi{LIp<8!-eBE%sua#Led#@vYet+Pn+ZAOV zJLx=IUN2B4OxLM1i2CFC5l?OEG^9160kkz`J@+3&#YyY01W=;}nGSJN*tF-g0J%+~ z*L`%mrY%eI(k}aIKze-{tM@J!0~fpHvQ~3{fA70;q^rlfg8YOzE&N(}z5g=hUNUDwI@UW7+X|C&%}&8AstX>>$gOZ(-@ry~pzWeE{0 zw&|vhtmqe3$x+(mKYQ2YmyZ^X-};W&2is-Y6!tonwPJn)KPAc{drsFAM5q#)a<~or z@-|u1Gxf?7-sT9|BOhJjLRVkVtw}6qbJUI-F>i!|N(Z~tjtpHyc&|rzdqtK_W*bi3 zOOX7@kc2{!9F5rJPi+N_*-s6n^x?2118lR%hN+yJ2vEV1>YkH=*@30$4hZsj2dPQH{poA@nXmc$|{aW+sc3h{(%ZoZW z0dbS)n#_22RL-8|tq;ZN(tH;d9qFX&El&(ux=~4uVpom^{_&l2*;s=z}?ph}9C`>EV zbW@W=72L>(5zP%lhZNMvWbTmF=-?X+^6#Jo0*ZbFGLmMN^eq#StP{cI;dqIXQSD0% zE%2}a7iUqyyk{?oSJq!U7$WHu@>0JYUvmN0e${LKLtHQfTRpd5H3~-8v^G?V`Gc?H zNbN$(T5BWghZdFnU+8wLc=tj=UH$r7rSyffuuSvaE(1wZE^Z4$+~KwKlfQ!cc_JoO zsgMwNfh&8kv2xS}Ks1h0Ga~ydH;CT^*3U^(WrX?p_dEYS{rr=!W9qQ{geIA6hs==j zjNtu+VAAUqIgb_>P%Fv=#3QGK^OTE_PPng6^z~0gjRXv@f>wo&*UFC?TwB%kr;eLX z3YRsQ<~K-IXAqV3-3!&2y?&1Q}r8W;j_>~ zzhXeF7v{8i#Y#nzGM#Gwt$jq=bhs2*I=r&%FVTI?LX6<%@+|(yV2LzT(HH$dWPh`ZNye!PgcA}2*n8t=|k<~ zUio8{NK%83POgjay5z_**w9Mc%OdwzPy5%C3i0UVyoIsqhEitQZ(l-%% z(a!FxyW=*7++s{JdxTR4tt&Hxga6cMT*SQrnbMdq840w&KE!Fz!oh0p{PpiGE6p&C zlSMAO#N_H+h3n;PpS*@9L^Mzs=>jKl%&cx120&VL89A{jRgzp+Dx9GVf`DgTF068##_|lQGpWZu+gH$8Qak4DBfb93b4tR6xleghW!M=a06vmPJ$DnDyLJNBidm2a5~oic1(Q5e~mn#Qw;sPGU2q5c+M5rorz?bC_MuH~B0|5+Jnz zMR!J&i|+WAasHP$qqA<3@OGe6E-t{)HX{b(lYLbYe-1jxAzvja$87^9xw!WjFLnVp z%@Bz$Ywa~X*8^aM*wIR!C_f={}AP>NmN1kPCD`bo4WeeGEsDl zuGq93-PFl~&wtr7va^**Lzt{0M~JC6F(5km+RFa=b?+LWX$2~nf9!|R{G9P;D+lWv zontC;)*FR>*c^}~6T$Hh&lKr8Ir+b8r#X&{2srF833TcF^xNU8P zq_Y{a0SXic^a$T`!oR?}yg2@CZW4U9RNVxE3J?u>$VcQed7NQp0j{rp<{Ge%R6~md#fKRJA1L`;vGEu==D?8_|Vgh&iwB+8x~#ukK40 zPlE$ub8`z9QC4KnkOHksPoJ;5R{s@Za41s6qFU_1oz^hzn*i`VT9%Qq5}7~+{5k4= zkwIE-;naD@B@LXJos+p>o5VZ9mS+-cQktA>A~MduD>I?n1QKHJ}~0!{uJIS(lh9fd2LfuOdY5?3L#;lIWlnp-qw+J7Cn zh38jX`bBr$@Gm8FTO=vKup=p}mH4dX)UA7MtK^`&(;Xze7!B|AqjU$=PCyMwg^519 zERDVg^p`N*bEXTLX#Z*JUhNH1TYbD!pJq($Z~wKPSBaahece3syq(DN=MVrKD${5=j+CK=NG7IxduYh3ec{ zyJzS>(g{Rrf9tD6b&647Wf|Z-@7?ATYqM_$qL3z;!0u}#0mI7%X*9s5shiss^mrh1 z{#>2ZBh59R_pd}~F?*7>cLwz58 z^`*;`Eo4nq)#p}SxbnFEF)FJH$ao5k3D=UB+w`4vg6gBraiO$(dpn3#Z2FYo>amD` zlk3|^^OCGMbH}J0w2i{=x> z+vo;0YS!ULu;_KaY)=uWAy||$lJW6?<1nNsM+%CQFJ_$xAM_qR%{6q`kR&GjE=j*K zWpVl=gi)Ld<^Hb}*&fV7-)PnTTDs6d4U-4x+!FfiXl40ceAmx@er-t~E(6qkNIWnZr3#z7@y1U%>QX|4jc98@*m za7`U)MDZy71kKklHYfGiV!tQ)N@Ov`i_}Z}&P;&28?EXPeC0JXc*whd{ftun5EtXR zmHuO*Ur7~wC7381p^`|&Y^7Z)W9?ZA!*o7|tnp_b=x1OCjL<7G|E9w@P?zAIcERXR zx*HODi|y#eI@0{OZYy)~hmlhCQeo~^*-+p=$+3nIg1dYX(xpBp>q6(rkhx+=3ilpQ z6b~Jr;TiO`ILBntbkO5Pj8)?Q2!5*jM7%>8o(!t;WV+*B#-upw8>nbE-SB10pertu zzhh^?z`*M1BZeHk&Gq8oP@u9qt4x9;~gxnR11~v`{6?uQ^Z6f12+lm}vMijMSD-wbDAN)iCs`>*K-Ugd1D2q31Wq zg2B-Wj-m|IHp2guKPp|(5hpPEB7`T2=v|NaJ~h9Mnd=e6tt4@=h^^dF_t^a?TL?mA zpJPtK;mtYR`>lq?J+{dq0Q`y&_m@{+)1A?MHR=_f3=+yG z-~l+rpKqh8$hEoU&hDeDKLcXS8&v72(6koLU?yng_20hb&v+^g|-E zg#~R@|^GqOq7R0e!N z1Lp8KsAFaJDjGu;zyqWMma>UgYjH)Net_qNQ#puGK9Cvv|0s>~@SCNL_lWT>syO5) z*Cf4tX`_NpJM?k+SIORRE(}JcRZ9rj9tl*T-pjlnS;t}T^3dKGLR@%5ic@+cn)-5m z)dlw)K+KM)CNiubNDZqlHdI`7>(KRkDTuv$@?*gbcJk6wuhp!Kuj64XO%p=-gZaI! z#@?qf_765hkZUB962KLxyd}CLOuPz_xG6ze=#a=~>?f{dUbMz&)EpChq@4nHgiD)+t-c}NeCQ5>3%F1w%lgoJ)i zJf}yrVPvvX#vsaBJ?-IG>@joHLdfX3Q=QGR<@5e2$-*N0DiVkH-+!F%Uo+d?087(? zJIt%KPfwlMc)xGiQY$x^wrI{x*{bb;of(;k2d9$Ks$p07zjK>O87{FqR1M_9%ygG# z+wk!-QA)-J-tt?5q=9N(Zcq=m5imufdU2e!sGCCfn= zpwKTqo`3P~C*`=7D@EytClh`~hB5%Q7~pSWPT#;p;$^r?IT{Oqz6_63naJ8cR?7mC z9-;dGXnL!tI@+ddcj4|X!QCNv2u|>z3wL)7?v`M|Ex5b8Cb+x9!rfg$u-(u5{djK7*!#SrqC^8b_1Pl> z;IKidB&447JL7Rg?63H!_P@6j+izDcU08nq%}sLuxla7dk(Js8>qq`kebBkXk8}6b zHIJGN+Uvo`qZ{bO(a#vWtN6MGW&y6-*+XAS2pGOsZ*H6|=ycj-MW19>lmNDq`E}c| zV1t&KW1udt+bqd#R(Xt=jF(%&7y|DEne%E;VLa%KTMe)^1T^2m`^-Xxh@I zB*5-==FoFKt-fV~8l3%lpl$M0WTnc%%! zspr)TorKEdV8qt15gy^rV$}m94YmHlz;dB1vj3l5(Srl{qkPwqkm|`Ig6P-`$McgL z(~ME$XXr(!!5YJ%%hLt(#`bN!ujocPDH(?mu9;QI8SFpP8zMaXyg3M5^)B^_7OyH} zuO;eI%>6Hl0pIN|T#*Ar4OO4!OpVSn+m+Gv>f+%8@aX^R6F%4#I5;3BXhjsxQTE$2 z?xIDJHHUO?tf+sx`c$(<;5_a2nb#60s+=)GRJK9xu0X^Zj;y~c>UWRGYH{}BshZJxVJVRjDCz?-I z8Vc$aJm~dx$SFQU`M$)9KU&w<$b6?hvO5bDX#FFk%KZ&;I!yiqu3fj!TVskqX3)XR zxbI+yq18-~*?LP0eggzAkJ02LH1LSqK*)ct64HE0xrjgP`5Xa%@s<4FgMV{Y<=`Dl zsK91E{1ABwYB%N}+zLp04Y!>7om|nJd#*-PMp>?U9ap?qMsxTkb0LR{`O!`)%Qb10cwI zrw3~#}X_5He;YaBN zOs~}3!{xK&SpA1j>U20zxN~F|rUivaVIbuFiAd}(^MU+bz8j`h2iaQ@kQ}`7^89rN z7^etYicG_i%^!_DFgvbH$r0bULTa*L7J3M}KDZO>naFy)uiJDlQYYgoId8wCwZ4C0 ze@3=kH$Tu$;Eb^j@|h7*X9*`^XTl<#+bFNJR{`jEuM7zuPF#WqzgPO`BlB9%&X6}^HK0HhnixZ|0 z_nenVYQ9e%O8aT}xTf%XzhxZ{Tnc5cqW0**MB ze(`zskaIRfGJ6;FogbB0_QOa=B}V`GG5y}=^~aj!MQOz@AL_J)I9eujsxZ#4RgKs# z>((n_NWSXtwk+rYL#S7Do$v7qyyk?aA{Y?hJUkW1|L(L4KI}8&>KlV?LjC`}07qQf zZD!iGfQ>mduKkc=mFXp8&sIrQBxBr(6S?A-%+1KqFaPh)Zfy@{^fU#dJ)>3-mbu^u znW*(iiHo?QB^#dkMq+Nof^r`dh%}|=&Z>BG2m#d)S8~pDEDNv{8yKIe6ZCo8Ht7(e z|LECN`D?zpz8-eN3}v!MciE;K<|=)iEcfQu_uNuk?u2V}dMlIWj7; z$pw8aw1>gWsTp?vO<~xyQ}XOz~K)k(*r=a>mjz~4zQ zU5=BcLKmUpY%-QUVdVP+eSiUY`uibD22{}qvbR~z!i^$t*RgdZ`%l&k*>joxe`LpC&yXD5~|vjO5g&VWcYk5dllvR z4=H6vnVJbsR3c*xpN>6UIe)l)Da~Loo1NuecLzUd3z|ZJ_qJa}Y`e7Z^WGd1J&o9R zD&vL~VAZ3xBJ>uM#lh{9bmF6ox~w`45JmxXvEd>hNoNBi%L3Ki*ViZg%P_+H-Jykq zY7x}BhxK5Vpu{2&e+gB$S+ExQ<%>@nQ{b2|y9MSg@(nGPDV3Qgu^qjSA!-rYm_VbC zko&YhT}3%|CyOn8X{J?Z{GaNxv=?Fj&qFtKzhk+%_%QBqYI;Yc6|3?p+&FoM^6Jqm zZ)o6#v}2T1&7?;74mD$R4+u6q4BqG=&A$*!O?7mKW*3zPY|cv~k}@fDeuSHxrXhCX zFnzDb73pNqrBt6+BHZwoBTTgu$S}(bevG@lmFJ_lENh@kBqDk0ae7@ykFC=mf}O{S zc?666iXaSf=0y#OwHx&$Pgk%A3TCbW{R2Evd+rHJ+oWm#B{9DsW#2wzxCZ>$=*bN! zvX*PeZm4XMkB)P9C$;}beo=RS+j6~_B?cY{fsmw{9Z+S;mqvdaAB0U_5JqS{Jc?fY8o@wb|zk#wp*yRxU?d zF2s%uE|2lTuh(gBGVF~N#9zRx$SQL$8hQ%e2_@b5wImxYh_Yl7WD_%k`b`OlBBYtf~;EY@t>fP zORm)hXH$%9#P!SgE|h{^3s+ZG<`<4)Mc5l}H1D|i?-9@c`rPHAv>&i#qyO@Q^6Y;h z^`pM>{>K}Ei5BkY2CCvEM~1d0u6cq|JJ{|D8|0qvcK{E{!EqxGa6r*#a+wGko>kp2 zgw6ui;6_`~Ux&zt4RvkYGeqB@gO8J1%Dfq7LVDun2(Nb8>q)~xKhw})BW7vcvJ&T*=SUGz2jJ;>pYcNvSt;YLwLN|TOJz^^_ znAcZC#)QSv?5jOl*7>Z-8^j9JC>+jE83`H_NG|-EUzQPgvgc*oWpT5S>NT$Gd z=6e3fQ{uVe9icg6!u>6%yY923#pdm)Kx zoING_3<7Qgy)Q9?+{*Uh#V(X1Me}H(;!*)HcQsi7~St^J}~-WzwgJ`YuG&DSkX>Vg6M?Aiuk(y`%`TVWVBC)j0LL zC`R1g!?AZBrDscefpiDdQi>her)~s%&3*utf4IacO$zJGiu3k*xQ@D^KX_ zGUTi*lDP9K6=8NU8ucDio+y8~e0g-0*C0Ovp?=A6cJ=x>XDH)ruZgYYUjFGT-H4QJ zOS)+3-#7p;WgvFYct23(n-4o+8^31Vk=44xh_1dvkATuy&afQ#8ET&&{c7y>aa1Ab z`^*Z&y!bN7uu1`*#8Hhl3lqg6K%fNR~5irP&D2;w;WmY z;5t1};|1>;$RSulqBYouGjK|Oxzuk1-6`U}y_`+S*}!p=)PF+^LEeg&d1(XyXd_|v z8D-;<6`0kVB@dzeR}PPN=Wg}@FNlEGisjXo8yy11-5nf#sczr2-G8jWoEa-ao)L@a zfS;oEpI`Lh_P_CGfh#QzM>QfNQUor|xzp?ay2Mz-w!;jpZuf?Ls*GmHd5?!#Ab^)K zZh^o(f7ml9E30kU&cGtNqj}tPXqm60w*R{mLo1eoCAbI)=vW~;lV-lnWoJZgJaU%; z1H=pQ&4qbl;-B#C>ul*iEv{a@y9R;FrYX3o-iU3YUzn~*g11}}zlgHBs!9WekB@Jg zU6zVbjzwTwT9LN?^B6T6dwhcVnt5rgnbxzE%6F#7uNGj)Y(p7gYlHs1Ny>vdEyFnS zpICok`kPK{75;rJ^%TFKtjyiSwCThC*KuO{RZ(?3@S>U&$sagMC}oeOLafL$f5UW~ zet4FjDqc_%-=36*_e9xZ^|Q~aTpSGxKZ$I~F`wA1n?O)j*k~}NG*V&!1taH)tKe>{ zHxH0wZcYWe>eD7D7K~xD;|gf_-9OEB`!lIb;QqjNDNwkufD%ZF%)~YMGKZL`nD9)r zXMb}J9rcnG@1Y-mlPZrB;(#y#AA+Xy6RuRWDH<#m97V9ZGqvIP0{$k zZ8_D4_O;5~6XF}&a#F3|+J-!6=1MbZqJ=*>{dG_ew7p$gu= zOYVe|%yS5&z0I`)$UDpplJg`74a7K8{Ds?e&pi(2;&~o%6e(fNS{9@7tC~31zy4ZH zQU5*uqG*o8Hom*$vG#6HGRhvYysQx9C(Td!+ha>z84XMuykpihxH-jzCzXGAq%vOQ zIQ7Mu$Ls&>P$>43NSVXGGG$=dBh+Y7+ROLa6ZF{=PA9V)7)#a|yn2CVgY*H&AQ`iM z=24p|glDI+AG0H%gG$#3nX$2)+U)0;{LhB^ILS1ni*1)G*Quw zfq1c>I(;1s7mr0N>naN>aI3$ru{DdZHT)24rdA9`b5?`)nL+%YNG276K7(^bgZxgh zTRI5M)v;q}kKP$|sz$z#^NwgB?nl&*9P%qnFaqqu?8>{ZPL$-=G?Xq0!3)0u>SfU)IMilm z`M-q5rRx$RtTG;0tYve+Qz&JjahAgMYsODH?^gq@fjuk*e>S?ntiAZIjZu~wmatr7 zLM;}2<9qFX;VI`eLDFC==zT+}-p_#piE<{`2Yg_s?yy0cST=y*$Ms^j~WyaY2bKz&?ter=l)RxIXrL6h!qeQUWi0p-3UXE2sS0wYh zPwW2I9!fW;c({I46ym{Af+SSezzNIz^U6qzpW}b@_8UL^SSN0>I%rOiM&Nm#ESd*eani6Go*wXOsgol;viYa6*JdXvGi2xS3eizyB1z(^ zXsV$^-V~Y$v(2^uNK602ofb8|+sIdQjom zUmHaW?XXjMT9n9)+LWfD3#Ay4+I0vXJA9Y~GI#>iRQ(xL3X>_ZTP@MJm@g&~_EgV) zBSCg{!kRX+?Pk5diV{9)_=!z2v}zK*JGx{9?5mK{H?p>iguAHkXa!`*k(NLQ?!pFC zIDvI~Hig9+B}Ca)NMe;&+dsHBv;Bf4S+278*hJg1v-2Q-$C6jkgA?J*;=S&PSnG@p zlX=n-8^b}s6=Ca?OqTidF7*DfI-1#N#P0|xM=-MSFHTi~f=LuYu$i&HncB$I70n2& zrw!f4nu1iIX(k;`YB;A(msu~1rIij^yTOnJt3W^^4&Vh$3@pp7@5@nQgN`roWx~FA zY9ZHin;h7$f%1Ix9BlXP{ehD2Dt~minOor>LKF8ayF=C#4c-XepY`JB zyiLRY*Q897KPY)+2t%n;KF&>Uh!qHt;Sr5bbg*He2xm7x(WrHiO%61AYIW;qi=V65 zme-yeCyx{~l4^NT#fYkA%COOs^i&+=y;48^RM=I}Qcg}LU_{<9@*@rcoBcU@@J+g8 zcouMd>{!pD$`VZov(i0#+$+J&pP??72}TCZe?(~BEyPyqjFsIZOnf=Z%Ob8bl-vip zA$J5h%ze>;{UyA0P59Azmx-vo{CGYy@`C$WnKXVWBbCvQ8ewxo@Nj{uYTKAouvi3r zeWthrxBiMh>>&}FSlRJlFb_p;VZLChDQGB>Ibv}#_DRoJ>R0F{^{&dcTXr1CpqElf zx3ygF@MTkEC=h$W+-0~pvg@0ZzkftecT-Ef0z6Nm0&eZmcT2zMRHES3;K;0V_a74$ zQRfyR6LbI)!)}8Pd&tFwzMForwel|iHO2P=@Gwa{Mt$(^;?*EXZ3W;U(`3ugqrE<6Ekv7 zDKd^a$exxSOAVCUzx>>`=rIx{sAO_v3WYHvS*=UVD2b9kS{s=Jr2*97jZ4yG8n)1b z84(mC3>)>hQr8zgq;j#iy-YX>ggkJ{>Uhea5}TfO!f=M8KtK?qIvuT8s}m58SETKm zD)~@9$9%#W_n6NjUWk~$v1kXsJ4OIVTiv*pvJOq5{qG6>W0Q0r^`hCJ>&q=R&f4(_bY9&7OOF@uB zNfZEz{6`t^2l3FPT+N`CB7)B)W_NJn9jdDyFcfKDbHCaHMd?TZHh|w4o~mP*z@UFpn?kY2SK8mD?)%d|aIh6)R=KLw2LK>4N_F~M@0!ysx5G+-k&e!Lk<01#* z6oy#6TiaJqyzkFL*L-fjY1ei-Ef(F|1(+ zz9;sp7Z#%Yc%v>pB1tTe{0#;`St;RSv%X;iaiqRrHhikRSj9MnE16;lbg}|h562n+ za^>23^WRR8-_s)S+}xUksMiM5X{s06J33xC9aQS~BEfDafo$8pG_YISTlkVCI{cA= zDY6&t;Xd-(y}!`kdDC`|>xd8?pEHx$ssSaN{B@uKs%N z$px~!wEHHQ#c{0yag0^tjW-84ecoL$DKq)HT3-9s>F&x0L8GDgS3j+l^e9wRlKk|W z{=UvtHVuP1%FCy1y_MOv-lo^=_hj?8`yK=8vg9| z45iBMog~M|1<`~NF`Dt>od+By;ajsBSU{CinqwxTLXj*ZNQaG}mMU6*iEHQhC^^z2 zP*Wa`uh!qz_t61puqqbhMzsj=P(RTWcTOeweHaSbiB}u-qOp?ROIQ78JS+Ral3bS( zl@?1=gjw}r&o5GwXMS-tO<19UJJF8YTHLTb6`>pE^2IAt)?lLn-jwfc&<4a zK3P56q<^<)7?I+gLCgns4>YU@p`}Hj-V4)lt-rPgp`*W#CgB(x;MDW(rIM$ zu*gx}NPlZs>G#(E%EqVD{kwdNzFECA5_t&yCiar`R!A!Gq_r@i9mei*3AQYB^weEl z!+_7aoNBM2x!$sRJ*!3|k~&3Fd7o!8q#pW*wNs~ntB}iR9n9#XlVt$JbZ8qFd>&=w1>C=OOU%rU9UDxms54i>^56Ts@za! zocZrGW9xK)?51umVIIG2{gcr#5mo&@RTF~j9~k}-Ajf+Z0p8dbS_Dd)6Xt@a#dA|Gw`6G`%%=zQBQ!D8lEZL)o+~=n*S72H zB%~iX`vLDo=vem{%1O2)vHti-h1OgeS6#ObcKV--msi99mA03wg7Sa*Pk{ym;YKDH z$w{_`CSUeTTo&o6LroL}qh)QVZp&0v>YA!{Qf(~&Oj0Wg5u&hbIK0FV4MPSS|B)(W zjEZcID=fzph@c~~DdS)M7^`q|!&FvIj497z%WHprwR#YSn8Irs zSAgb_{Gp7A#-ux6j?Q?jlPc#It$rWI4et}b%K$za&;sA6R_~*Y@@I?*RDw5YWy|4* zXyd9k0rON!@o|D2r!5_YFX3nk+L+5J-7OIwbUr)qNwNhML;<18C(K^43%cO>s0m2_ z$4Rbg7}EPXouj9;4A;9V|6B*v45q7Y%|RrWYfk1*>fl#ku}h+sc731R*;*R)A>UrW zr4mmqJoNaV-=P zTc4zSt{IrbWuz3p%mhz1{!j6g;pO}L_skz@m-kfPqobq8qld$XqkWTq{H=U6_|pHu zbl7Jn69&>u8EGQMBNubD{yx1M(vs4ui>pT-{;F=D{;`S4lCcyb7}btzg{-KM zxzcC7=A0j@MjWO_7#8P5+fm3iX1_GffR&z(G`oiOeZB()>~&^nvWbr z(Bn#KC;g+lZ7O`;*+@{0U;T$Qkur1CE!apJ^NF||4A=K{(s7*CRvl`$jh!jaEp$e> zkrL^_T*x70U=vDL{H{G&%1ey`slcOMd2%Z6mAeGyB5J@e@|q#1o)NjZ)NIxbXFXe* zYv#$GZ;-dzMNW`W=;pDvFRe zV!AjEwNGQSgA`+Cf{As`d9GYt=-NX?klHcjnQ)jwIR%&0yW9`eWarm2qGAQnNAJ*v zPj2D)AX(g=G}sJI1s=4%ZNlAa5H7C`8XSA)Ur>@@oFr7Sac>$t4n}Zyhz>gG7(BytDWa1ds2S!9R5lj_fb`y# zlcXvZP{NQLb%>{ts773~;%lwh5NSr1TYe&z=0(E1lXs zHU`xqpY-Tz9Dbi0Y->5Qj@WVjg86lFsM|!$li4`6c%WYtR%0e8Y_ns+KV~oJz~fwJ zp5T~)sC)dusiRije25FcvD!4XgK1TC3Tew1o1}0hWp<*wuaW5Ftk0-?s=YW!5*+HO z`lf$=Gf(z}G9^HH`d+sjK%>Cn1&b|>C^VD}ho>gW?k)4$mG9%$V^M=Ge||(T5T0G;EP%OZ)~&Row8NSWKV@G1ZLs=dpB^<*QB#_+1zn z*z>}+xn|QO+{6EWF9733nz_VU=IWxJ4iB4`1vM5Z)Z_fL6enk_(QdOwBLGH+fFqp_ zRyLFhDUKE`^w;zcCeo;#Mn70ttZrx6P*YGrE-of4dL&iQt}TZG+R!=O#l|O?Z6erk zkSRrU;Gwy)P2g@|hsPf%j#%Y;mP^mxAQfb2Xn6RcVoXnTCl-Em1Ze0X_m7+(AVH>| za#P?8;y8$-LCA!wu;~`t7SjV}g<=V~;R(T`Drkz}AeK=~0kRa~Fy1V2XpS>?N@gzp zp`htMI!6VS+OioJ9rkDC)z%HM^^2~WzpN3?1mtYy@S~{k#J!qDa0_FhWb#AKEOFn z-OYQ3VlNcBVbgv>Hznvu*}~|3rt73gY9rD3nM6f9G63g2(8MVN|3l*M<0@P49vVLm>`NKO2S!%VLlgBt)>H@k{loWZ31pLW{%h?#zvoKxH*aCehAwq^_xLW&RNX6lP z2K+;euItFESa=Z(5qKIbb=8lqR(V-bjhr=g830N+vmhRO}9 zn-yy^5K~lEA>h|r(+lanj*-q?#N{~Yc41lOg)v7ZrF0Udlz}ZqTW*FKt2aIlq;Nip zaTNUk4-Fl2HC;kX3haT9W5=n}aQ!p2Oa}vnAxlL;anY58sg8>WywQ*7%w%DUP!kx$ z;??<6K+w=deyIGYutOl~I4P*R>_`WXzzB!naO~pf?#2(8y+$hCdy>&Zrl>qH!4`of z=#q3|&I(ubmRsx{TV7ii9R1?xh+r>W@qeU`MEqaGVUpsC39quSY8 zK&utjVR@G7se5^{s`0&S!!#9ssba^^%hL6EWx8=0h{~&9JDr2AD50!7D&JHUj=XCa`h(?&-UhFprlUVG9~3Q?Ol*|Y!@>P>&hG#HaEcL;vi6CQ=67Vnr^9KU578=GDRB0J zz$#Q%$Pi&Sp&(y_V3^_j)|RlyhQQ|#8l=|03k137_w&jd?(^#nDk@@Spt1Z~MVQ@f zSl)dj2x@s{ppB^lD@nUWuG_c03#AY9ctnK;L$ymGG!gs`JSy9WG6i8D!;joMKzd^) zQYzDzj|Bf*G&O9s>zJv`A;THVOwX-kapW8R2%aVVDgW9i(c=IK+;#%5*62SQa@bV_A9 zqK>L#{b*KI%z*9jX!WWoC^!9 z==pB-rxLQcsTq&Qo&K|%%Tb8P^hiG^Wr2QV=eE4LpLLPlcC4OLTQkRgyE(3`g2N0J z%)uASctH-z-t7*5^u&`8KEKgO)WA!I|E)9f*00-tog`OwySg|Y#(&zW7?Gb}TLmat zVl_(;Ic+JbRl{cm)MTh_S2hQ%q+R~4!BflF=$i-zq>I-n;kux?72!rH0+xRX`GZSW z^S;D}7=`rJvn*DQQJ_yl0tQ2;PFuMMkC`t>{`J?_FTZ6aI9Oq{Z(P5Tybg*@2==b0 zPEFTIQzUImRs|iI9<8I7i#)-d4DqC~uS-|ygyl0}dXkY2wVi+mDQ>XUWrK_rdz^U% z3*-sEMQ032$Rr?c_^cegOcHr!OGts8?~>^*8kLM8ympZOZ(L#3iZiEZ6j4HirW6}O z4~AQDl4J=C`KnbwBC4(0CpyTx5Qkx!B)W&xV?aIUq}A6yg22!duera^nGkg@lqS4% zp_~J)uj$Hkd}6B*-Lt0&0m#ahE}d=(pzGHKFI|d=mdrtER&BM<^&B5F3cvl`9p6nN zc#r}HkPS5ug3}H^;#e5D@1N_!qNLIVOTc19VBGz%Oc@@iG)>N~r-O`EpGUSBCQ@8& z7yI0F9+3UrvuU77G507G)W{wd{p$t)+h6U75H7YdckVy>Tq-5s)w``4ho+nL6;1a&Qkfb4a{iXPm<&hq3t3O>Q z-QPv8p!BjVR|hq+;ipxS=GjkMf&6>+hi2Lz<=eQ;)U+t~sO7k;B+}t-Y0fpw;F`SA z5*UJZ`O{J&W~^|{9+ITclJH5VCM>y=B*hXC>Ko1139CNz)v_9lPrZ5MnnU)yo;DwR z3t*s~U>gyp(UAZJC54wVax_x$K#Q1XyP9BR)ZzM&+S*@j&A-Lm*%9LIAG6C+n(uja z``|ltvAOG#AM9tsa>c7sydTkcLem>B8M@$l8Gwts+0O?Ba&&gg3&R)AtCpBVbGX8d zDum3|*ZC{5)^rFCIhU3qUu?Ev>fg$P_J~B2X1s z1yd9eXziYYc_kOc&Wl9H0vcAateQ7$s6EF7;5pN9yUk=c^x`AOhVarY0i{VBFjTwcY~ zhAniogmMoQzr*l%NOTgvUTtB`%*=)Y=~NNxuzDD;OsR}wdy`L^L2JY*n0LppjA0g_+93j;ij=QNc z_bmgKrIY)#xFchZ>1-p8IzQ5WqgLLfSKG*K&TD>BG)&rBnVVM>h4VBIz`u1Mafqrn zJ@3_sPS#C-^@!k5DH=vTX%fVhf&u}@X~YaWPC>K{Dc$XrC6Wr2-VZpEZY$Dw5!I(X zdWh6Q2;QN&gK0je*B2trUW#v*q}$zL;IFor6TGW%zG2v)<(%&q^n6i|Dd58)woO3; zkB#E2k5Viz`)>A>p@o7PSf&a4qd)i>`wlo8 zInCB_Sa7Y9xF;l&GS}X|2 ziNB*c;;ns3IU`vYMvfomFR95di^;*`kH%E}7q3a<3mvwv_Q=F0?B<{9_nI$w&PlO1PLdam~ZKbWN26zV7NTh~>! z50=F@^YF?iDWjOF;l4q;93EiX6a_`*w?}^0K&!Gqd)-)m6{1vWwVJBu{sJ@}es7KJN-vqfzb9Pd&5Zu}!mC%}lVS-eE!MY@b;9n|!o( zWltF!dvi))&mHPNk2{*vP@m~x;hVU?Qf4O)(Vv=zm?B3#i=RXjTgRau%Z&UMV;6Xx&`fi|geSmR&sB8AZl#FcS0+Sqx)|Z~EQzc$i z3NkI#V21j2a5)qfBf*GvgZ5#lN2LO8j#y<&o#wjzbxI>QJ2|K@nkMl)7Z6ZY=DD zJPd7C6m0Am{EUZp_m{AqA$S*-w1tT2-jqYG8)qj$A=-$GGz3V$aPl05q?(5(Ao^A2 z@%`$pwbv@Z0zvn>I*|s?ScQ&_$pb!4K+c+SZgqA4jv?~mwCnuIjMjL6v*jljw$tU; z%>muV%~dxZbOvl|`_*PyJE_ygLc8;VN2j+8M~6IdS}ADSd7XMjRC~cpT?JtQL5b60 zFh^sI4fBGm3T>h=kF)bNjpFrl1auALmup6|wN$II$hQudwc8u*o5{HqLO2=JAkv1I z`pGt2zcR(|p8rT&0a>BzmN#4Y5fRfgf{Jy5-<))=7b!LAer{0W?niaj#_JCZ;8$}_ z4O{rSyWC0ez;1Z4_n~cy!p;1KH{xk}s>~-rcB@oU6vSaCzpZM@D(kd$F&%k z@@u%&07PXIZn6n&=xTAI;U;sLgb&Gg4f@oV?fc$Byzd|L^6s0Jh1ITH_sDDC&~CN6 z8WLlF%Q4n=?IIrSyNq=d`hsazILVyt5p=5pAD)(@h$;7_9 zFQlIr|CdOpyqxmo*r33q^NCyk<<_PI44QAuREWL*cTen)*t^$NANeCP+^_`%gZ4+N z$*)r!(;c}^qKH9#c8}>jAb8$@*Kp%z&#(RS-~I$de|HG1l-KiGB6lQD^>ncv@3eo( zV5F?}mf13Q3hj1Q7zU;WIu}u-{eH6H9Dyo@dk$Q*$M@Qv4)LYKeC z^^?5uZq ziaeeC(K9dsJO?moDOZP;BHfWW0}NOt@0ggSpx=+sdhFU6hrs$K0NI-jQwpiPQXJFsTgUqSr^3K$ z))7IuxfJ`&juooyy9ntkmN9#5DQjMYs+Ysu8VaT)g>@(YCojdSFKF~7mLpX%)Q5HD zT4tyH!o_*X<#1V1`7?aR!aib|Y^k5N*~95mX1kY? zG0NxEKo>)nSBV!t5b(Xd+xDM&gU}+EDi(fVEf0Q%|WmR>4ryl{uZ18)Y*HtbY|9*$w^_R!k4-!U{vuUg)(|C@EYhjN zPsjfh%JNR>+Ov9Wm>UtdX}lfv06!k(-C_YnF0+#MkiMVTqZ>5zq2g2uIM)&8;fB)5LO*W;aCsafotai)z_FR$yx%mss>Poab?RS=bKgDv-PI7+h1}*cwU5nd zcRr3=s(ky?StRzUu6%7AXh| zA&7t?0vph{r*2(Qh`r`@RdDA|8>Yjr%}C?QwCzqu3;#Q3<@tkbgY+ZzOt-;j&Ec#n zxRi+E`L91HO1TcO6`eJ_(q75pzK&OsNOK$tB{ly3wpE^xNd|?6CAa-rAStiPGsC8A zp*tvqSi#lE&g$G`)A2LB0@0@F8}etZ)dT&Xk{Yf{ihqu*W+uS*{>Ox|i_OHC)+Co|M_M zIC7NG8_=lIKzqC3r}K1p=%Uj@7~<92S4GCeymaqc#{XkT2r~GV3X7*5EZ~-`725i! z4{7H7r2qnTQsf%clw`wL*MK`zanIA2S2fzKr}p*lGt&o#EER@<;aW2COdilRkplwG=|Wm0e;5 zEg>poT|gT-R4C&V6Pb?+t^zp`%q3o=((kxr6i$yJBe+<9lu3ZqPN78X)u_sg6i<ERJ@)Jq{#uNUHH;^?R?qj-^M-8KKbB6xP?V2UhI8$Uq-5V)CI+EkY#1 z|FG9lz+x$IC$<;ZORccCH$M^eGP*wT4{?5Vj#lG#3a#04Ye7{;-O3*Oyp|hc*;ChR z$qh9vEHcnfEYVWz%G4mRBs8e8@dK9a8-_lYNbjftG`887whqs!k3twKnF~P}%o$W$ za9%-;Iw(7?CN$r)@YiASWJ4)rF>TOtH!;HL$eV!xq#G$YxhX$s$_ZSo`BD%UL+D~M z%GnPSW|ZG7=bcqo4b7XfTiywuBGnPkncc0gTdL2FHjkOi)e_)C!*QEtyRYj=)G<8e ziZ?)bfDrKYf5pB@b)sV|y`-aF#YG8{-Qz)AOX^THrgcLOWDkcX3|rxoc+2TZK3;gB z5j6hcHhx_kB*~2hg^suv_WIC8xZ_z|3rIxY?$JoIE8U5nvQlnp!V`OFkJIr}r5SsnUHUcXEN(@($lqXiXVlh~Nh;@qI$TKKbe_m_YG=efivIkrSx*!l3 zYlb!%r_aHE(4W094^`2qw@zeXekbf9=|vhw$my1oP+z0V=wu*bLKGLpcNM~rRp~DB z{Y|;e?m!7vTV`VatD9y7y@iUzfU!&seJ38(of>5-_jlqCj}$@IXl|qS_rGVQ_xJ0A zo${(*ejNtj0?obW?oYm}i;l~k{Zzxj{e40_j+z z1FNYwV05xQ!FP-C)1au4@gr~5Zu`K9KAVXJqfeq=AFuDrlqbjF0a7VJ-S+{blK{)CC?b!&F}1Hic1HRP#{+CVCu{r+RpDxWu~D}-^q{`EH(MTlSUsAc$=VA z<1yK4>*ZaZukhs2-9B;vo7T)PAOsiBc-7hAQXVF^BLA9wWEbT6TlT39{;AFD#7ZK| zLA^gE|A53?-B!K}Ox-Hu!i8eWB&ZWtH0fhM{`ZR0nKnN!;eNjOXC4XjfZNgh8|Gnd zr-nsalXKXvz{AA_UdkP;(C#p~&jVGh(>LV?4W}c`(-@;SD~rjm_2r0l-fa)Nmc(3I z$AtO(!ML*F@9kDa>RKiOlC-pREe?FZVQ}dEI8MbG^kH1>S17U6?|b7U@&~ediz*hl z)7AV5YX2WkXBAXe6J_CxYk=Uv-Q6uX!QCB#1b25QNN@=*!QI`R;O_2j!R5~Rr)q|x zc%V+*hueL+w|r~u3K+ek*ew~2RNxUd&{FPnn;M= zV~n_b3XwPp2LT~XzgfS_&q0VL&b;!_Osyl1AYkU;XC8svdtM9G0LK8%-$H_^2@dNx zNe3?tc6N+tJ^1t9ngwAb@E#Y9OGay4F+lVJ4B;HV8Z`|9=)1c+=eMU}p`ojf%d1^L zPfrTk{&;__>9~?$?)--iTH3tqM->{lzjt-;>1W9;v)VC9GmUptTj-S6|vTNr7 zoXIRW@B%lqvb8jba{}^{g1|rF_)Uzc$KUNv4uqbu+oTc5!3S}n=Q#wm=W=6p!oGW- zm6kmCR7F`ev0Q`NK><_>q|S8Xd7U19w>1a^CK@j% z#+9Xp+MM9xn$+J5aVZLX7VYV9Yjf3CK%1zNCDosewEk)GW!uy9YX^tj@v31(W96SdeW3zUAM)^$M>>zV1B`{OX$pgSNF#x}o~$9wWkB zS(%x63r=54T_*v@2bG*WN9 zuyF`v=Bt~tRUNH8WOc508W*7`_uT{#%OeDlq$nUPUbH<}y@J$B+vqZJMJ+jS^9}5U z(L745%+8LQ6|}$(^&+eqIjHnJ zvE<|hd^Su!yD#KW7KCbY+S|Gflo$PM-4gny8yxbwFKPC*i9eplumyQzf=8Ik(h|_b454!w#nC(${hi=O>q>oDW)=!Ev(0A+oVulNjbWIk<1S{Lr^ewbxSFe5?6Ont&ANy&bHLF54-u)P#)ZBrVK@ zGnQvqyiId-D9jmE-cLn`8nkdn8(S`iGu4ADfrI0r{zMgm7e2YqOJl>rLZf8d3qpPL z)C#f|(tBk4Ls1f_FdB5Y5ET@D8ZW_z>4pf4m?0mWNf9<$VH-Vxp}Lu~@OM0B%2Cdt zg9C%c7G#jrdDZ$6rO2Kig$8MeW`++7EuCHeOdcW}M}ZcT5g)TzU%AKA($y8ym^KdO zi9y~RYV@q4^@jD2>=XjXo?>I#o09mo-X_S+1yT~_{q1iQfy&pO2Kz|TP33I@^!n>` zk(k9^+G^=Sg^02lO&PLpI{8V1ETx)`O>W3+5rzebF|N4q|5$*qeu&crJZNQ5N_FT# zFaw1i%3dDL^8uH33c?s$o+U;AL>V5LLS%!UoX7g!A1bC>4Xy)Z`3z`P1@&?}p|JBi z4t=psjo|!|8XKf0VfE;;) zBdUHHX+bO_di^fc&=09rPP36t2E78Xxpg+}Q3N5wC~t3cT&I?6kiIsQ zPSVrmqW1iz8c*ZI>YNxVF;@4zKK+f^#JDd)(K0j*I-dmgNN=8v8L19U-ZM@uy4Fa9 zYCSxoK^Bc0=RDQyvwvb8r+lz6E*d4mFAbzjnxdxhsD4WLkB}P@E{Jm_-^__*@3R-r zg`+hR9y@&PdKAZtjTTgeIB)YrGi?!Hapi%lx5=w*MesjG5%}J->h7+Z_kV3+hHqQs z9d0k~z?QoP>X{bl*m^(2m7%BZp6(67_W_x!SX}zkvh41WBs`JX?PsSQQG-kRtA>RV z4OQz?ye#1`1=O8lJ2y1B%vfuw8PQk>@9u>sza+OQf5n188?(Z~M!H;Y%alm4$Z|V9 z0DPN|JLJr9BUeh1hxmn#!GZ)7Hpj#u*USC|vQ*fpO!I@)g9Zd)W0BX|Z`AMmpb?^a z%>&bqDWC|MKUxh_Q<8)+tcu&{3=avzIZW?G1Jj3$GwfL~f8L7xyO}QKVDL)YG9sQC zDqh8$zqJLK-w19=QwZr;nD2tQjwa+GG-Rbnlt$;9jtZk}&f)r`_}1TG0jeC+bT5jz zHVH82zId^7#N>ooZUUkdwc&|ckOWwKxfcEJlb^T_v`W_j_EQnglj$Guv+ z8UIg?D!619^HgHT-<$>QEl_iTE!VamQH`f6ma}Bd8GQ`PtSX&PG!(u%QACvkClWB!QTSt2r^{@X~^$` z-~{s(Y@6XQv8?eZ)gT(-{U0fwVP;7(@$HB+9YqxH=Z~a?97?AS1gRz9Ldd(*Tk*}K zAR6hCc`G#W&q=JyDKKlg1&_dptQ76TI}XOWhC&8YB@G*Ifl+n8_lGCLuAi|VO)>rt zR|asyj!zlg&-nkHfm0uY%{MPX^EdwQCSST=g%q#H2BfbKW5e1 z(Eel9e&;Yg6#U~&(18E_lh40u8@1=|sHKnWkerWQD809BTv6R1 zrTUpCH$P@?iC2>~;EGBcHm=aY+;Hi2Ny{?$OczsdKU#O(uEOXd4Pw3t0DnOhMOgl_ z_A}sbop6?m`OBJPrYuY?mRTh~RUu}uGT@_)LGD{~-Fn8-yzD;EoC9TK40*U*V;lft zS;57oVqt|grWo%WaQRHWOgf?HJbCQl78ji@qMwy zj#pvaWLo;t5x#SzK=+y_ej^mik@$)MY>g!Kl;J``-L1mD^tLLBjCmQTVM(IV0Rc)? z_c%sbs>Afz6TLQ>;y>&SF^AH{cExa~GLK7^ZUVAf21|j!|nfqWu(@FHNq;k$@_3RA;x;qClU8@q3^v z3og(*iwp)+bzUsz=5F&6K~s>J`HFXsymr5~$_eg#=XWzo(@eV9&|n->iE~dYQb#LCH(4=83)=MFP^|zV zlLR6EjmX6goh<_ipbCH?XU?N~T@b&)OYIvB;0BYxJJWsi8pW5;<4K^`lsk;bL=JOR zh@iHF{v`MLD|#y)KUid+Q&&D4=S#a*FU<8{6CMdlvG6wvhP6>{#TFU1JbyZWZVCd zYh7f`r6jItT&_43!4m!=AtUxun~Y)w{_UMubX5(18}w;c$Z*Iu948`|Pki|YX?&EH3f*x0GQ8icVBTu_1mA%y32h`0J^-O10i8K2uwp6? z8h+g{&P5TXAyEa*k^U~OxgBNn$gfN<1Nb(Fm`|_}SbZ#c+4<3EK%L}|N~sYK0qj(9 zGnS!7==2Vei!j+aMtp(W9)tDDt4x|HH2p0D6uYZVRf>mNO6NzCqWTom0K<|2^|5xL%6pQs!+yd zrrSbXI=qtnqLo0*<~c;MnOj&wdB$o{sdRDu?zf^NQ8gd;Qd~a&)o{o((6};NQn)Jc zZA#iko!mR2aIDjin0mkN^Gn6R}f`GnkfZ$hZ?l@Kjf9Vw>B zvX4U^2$hyoF1!Mr)So?>*c6NBU}WoB_M8de#_EiIhn3gu;7DT&MNz!D!BqT32>%c2C=%dccN`FZgB9 zk-#chCg1ngLNb0SjE(-!Z8nrN+hE<~JB3N(U8_89MT{)Aa#XOBW;nas5kx&g0S38; zpIMS{h4!}im2m`w=mIQ%dSf6O?DM6~%}%i>^2bKW$_x~o4sF_@bI_)rizu&)uN_b%y$0l6LJF+ zw6seEPMx-p0yRLfV;K!xAlaoniSJ^g{MlEv3D&v>&&0xr#Jq3fWFs{lpsTP`(N{&c za4YLm3f>q*I!UvqLf=(CH(kJT-wJfktgpFg%r^b~yVuo@%Il*2`fsdY@+*ntdHS-9 z>ZL7dlheB9)8=Cr4w@VY0N8G3B#Cz@Z?<+P9fOcW12wE?fNfG9rZGpJ#g|&BvRNU~ zi!s$aI~L7QRvt9`XAK`Xn=+H=Bn|`3LabF!8l5vdjU0UwR9lB72 zy-L(nX4Q>q*{_QDPPBJ#XYB-lrc-TX*cE;8rKV)2!dESX@v$YFeuY6vQ5VbNu$?nL zZM>Q$>L_Ex%fs!%&8e!G_6lmJ3?|5vic-G0>n|CnVHd5s(2nlfSJNP#-t$q+bjHR~ zn;?f($xG`5QRxx?Wn^lg9IQeZP}fp#)?ea}9eiR|#n!>)r)JYIB9^M>aFt6^ZSHR! z#O-~uw>FC2rreS5xc!CrQM~0H!~M}N8CQuR=f~QI1Ac+=x$k~Q%lymoRuVYo?;NHH zj*4}B;pfKnnHIl#C+~PtBr^F|0&#T2EJBdE6YBqRl`Ev~a9`~1u-Fw<{mv}}XM%|X zKJy(pf;D)HZ4yJNBuCPSr#w>{2->VV6isQ`k6&vjA1|U<#@7qH~Y0NmE ztcxG%R5XPE2@P@6fFdzDQ-_B0D*pXSRUefG=Rbb&=;D42LaQSrMaz>tTpvT%QmLq| z3Rg34!3qX?4gjZde6C~tnGbrAI?O|p6(SiX=(G4}&)@49FpF(}Y`!PdOzx}~&6@Pz z{2sGiUGS(71%T(IN__J;*9P@{pWay@%pV&6xZaJT2J{ie0y}D;@2{*E9u*nIyi=ui z_5nb!wC?|ehNGBm;}TtyY#^bY7%z{HUXx-b%I%^yZ)*P+2g0^2Z?UYhVV2*hy@fGq zXvS?hi;F=uHl+5!<%dB+58EhkBFovCLm)IM1LP;WV z?_YJx*8&}AVU>fZY`c@Su^Ov##uP9QAVhIb4T*OiKT>6Zih0mYy~$gB_Z#QiO3v3l zcfhA4Taa*D=#5+bZNU%%Jj(xgeVJppHwgZK-FlwX^+@%`>Au154*X#+)W0{3y!9c8 zEOvzOv5ndlBN=P(?e%fhURZ^JttzKq0iRgur2^Fj}abo<8CqxL-H0CUCZ&Qp=f(LlBwR$&q{0)|6G z_94AKibD?q((4oML&Bdyfl%Cr)>B0&|n#jA%YKM`KIkB3+7DsZ?-OB;b8 zW+jBo^PZ@%`Y|(k6I*I*)B{;U1Jb+ZIQU@g3RBlFVZ8{dDSWNsT9z0`~M_<+lKQv zt8Bhr0v88zgZFT*H(z6cYQQkDe{^{{eS;38oQyfWpYBLFnbOdDVSZgg0@;M4M>g{> znK4a~R-rqls9pLz1&D^j%BSzKwbHE)-F$vCV1nUER*!7SPGu-~2*s2RAGEg1&@q=1 z1c{P9r}ZOve+FC=qg+zafN`7qpTm5$E5_6&P>{`=k(uPsF8!Wj@WSMV>4bA2;=k96 za!Apv*O9x85Jo64g-kaCj(SEp6L$huFs6c#&D8Xz70~WF1eelqHX&>nf}UknfBg}s zYRIFyzeno*XiTY9Gd!6GVuh>Nyb^Q+&wDI@Rxkq`UCjhUQhKO=bJfktvJ-WEal~EY zn}G+}^>bZfz_Z*39n+VkTf7d8I9Kc*iXyjtT|$(pl&@CG7cIXF#G*^T9qST=!#RjjM|^DA zJ7J>tTpGmHV%toD9AR|IXlfGxU=v$PEKN&U2z8)HPXFnlL2D*HU&cazTB#w-0TDnF z*-F?hwZDPtNoKpzC3nX-{gNHS9UDq#guh6GHcC+_*bgi$Vn7dm3)feoki0i-a*}WRhXlW`ehR&()apL_7 zdj8Grk*!!bw0>~!_NTUsqK6XVl@{Vv7UdtDz%i-^kI=R;H~{WF6X}CDmUlW3sFtHS zm@<8}y8IzjO^dA2*h2w_u`%Sp6DrTR?DBDtMDrQ#LVC?jG-u)^eSj%}C4ihgj5aBF zz#<7Y@*Gds%gaIbC`eaGY^evgfB%KB%w?qjn0>a0#7P?^jwvrJ)5~@ z)_EimU#RH*m8iUiMZ?}3jIyj)!G9l_8TKmrB3>bnwBerWi%zGzd<@FiFUOqT7Cv!t zIXuiHSO9UodTXl_ft+e}qR1TW=D3^#@_&vM$kqBbp8*q20kgBX$8~Mj%-?ly9eI5b zjq>ND+~g>{$I^I%6oifOlTy6OR%hYm5?(C1Xn+QGLuuC2AT;MFW#(4jn1!U!pz$6@}R@wR^ zSaYS9ENy7I$OXh~JMTpH`Q;!v3otPgLIEo&aV95bMI(cdi3ZW1#qKa%-f|{xE}ijjZd0KZf+qM` zT=65zLb}jvdoJzF(~ee;U_z3r9c~4=T?os{7z!j-Vj$w(yH#sxGMa2GI;P-9e2P>( z{KI(FRSmg!cu26iHu@fUj@-?(O zNddSw$qJ9e0^(;aVT(72)}3`)m00kNb>w3;JecA(69-(CbbwNb@{160=swp)fW<$A z9AVFXbN?$;wT5&~?wn)Ic%S^t)3*Az@&YZkD}cCqQN{qkBUQ%E4WnkEp3WxOE{aK8 zolxk3eG8rd7pL^f%xDWDZq^Q((fg|aP_tPc@-joSG@voS`vf%f=QvpLVsp>DEMF+E zyb30)bwV3l@0zPQ@!~Kk-S9;)No8h(k_~23NY@Ci*qD1#c$qD?>T~RLHxn(>kMF%a zp00QFnpi+Sx1-d(M=55;9C#2Q!KZB~wN;b<3U2~af3D0L-uJ16AV9cb5Mw&yKWHIi ziG>szebcZh?a5~!s{Q@!`-ALKm(F}in*s)3IeZni1u}dU#GaLsCaaG6zCf9Q0#S;P zl@8KNq~tA9Rt&`N*6Z=Cm5qr0`dmFn_|D8cUv48kLKFc%5lr zvlMb8X}Z^4+?pC1O<|!*-3PAu0I^L)pn+E9w^6zFkl=DcNt<@be08Od}8)`5Fl|ub9!C56>4;~ zt@4(Ko+-{`v3Il)zN=hH57uIfel&HymLp{i_brTcWdM0

u8E2cR2AQ#pGttLm)! z25nO@AC1quyO5xuDc>jmW?OvF_3apQF;%b~#_jJV2}aCsXV^^CS3b#P(%Br^(%Lxv zk7hIeno;8qln_0^Dv|ieJ@U*q$xFHcypiQFLCBXtkAq{XQ-T&Q{Q_kBk z5Cl89_+D|OFg3!;Q+EPD^@xQ41?d0&(kO?KPT1x_0RVzdgJA$508({_`|~gRGB7#5 z4=Zl4$WcdqU1*qQD)3kl>vzS7lOBS(;v@NOE7S#+M@$iwu4eXH#Rq?j5kMt!nQsWPo zeQ|0H!v;s5)GUC&L9(Pplfu6#5R>2mME6Cm-Kr+b5IS?hrB!^pLAh9x9(|J;^z_Wk zXRF5aW+h?c6>N{d;hP)B^M@HOXCLG|3{v&J-{q3)UDkl#U_yet_Jh7oGqP!72@MGW zP~DKb%{nuq4w)sfbsOb!)P*M^HnWbkOb-;LrEhArXhU?gAIEX+ zI_wP47XSKa9Pj#tDiHy2k__|I)x-(lkoiSpobpQMETYwT?CUYn%eU3~w1-#ZiFDJzo^JhRyJvT|TQjJ6wU9LZXCK8Ykp+Q5Gm5I)A{IBb6 zq*Wv0u%l9`8nA{G(oW9tR2b3U{%m*mR1i~2BmN|jP*y5m0Df7r6lP9ZNL^y~0$9Vc z^8@yHScZVugQgI`E)=r`ME=YKkkQ9st*Dzi>eU=d!$a)wj3k5rx2{!VWUo;G@E7oS z(E>XXz^SV{9!(Mga{!gbV6X0_7g<-roqY^{GLq=#n5$zGT~iKqp?!m)4Vky^MDRuP z4CJ_~n^*5a=2y)v}vI;@-5Mqqg~XT7?zrvB{CBo7*2O?y-%&BKA0L`duKbh9t{yjo zII@M=bay^XNPinfI?7O9MV~+`*dkoC5c3*kPgZ_`+dqsFxH2JO1!(j4_(IqchC8CDcr6(>c> zmmNWTKfi2+Vv$$LKgvdMr}p*H(*!8t02Bup>8RS`#mVQ>Os<6A3ZUvQ=|jq^1At4} z0v)sns1P%OV(0i6KE*6hDN><399VH`#q9G>J4&Ws?*#19s(2;HEcv&}Izqb^x4tE# zNI?jBuTAZ4(mjMOuTuT32)V7{UBUFNS}A&=G;VdKEB+H*7V$M$$GSzPxMPTX!f}?) zk4r5TX7T%Lz^5tH4K2lQ3`YH|_8c*Q1ty~M>+`@0oy6+g(bE4T_ruW+e@o9{Ox24D zLuh0GQ4@#+UchEdTAVA;<5||2zmr9ylu%M^dopDtb(&y_DlscgUJzK(l^y@jG_QU0 zRi~u@_}%3y4G*-K?R{UYsJdg4JY6?TW=ku8_ge5rJd( z?4NT?ct7+_1^3IxO)^&0E#nugE~te*ST{ZP@Z$*Z^ZQL)oPR}__v8zA&J5%(g%(-H znSCJ`7D+G#fcLc~BW-Mgq4iV^_&_^ch_rpXv$8b65E1Cj0LO9OSykbN15Zdkjq?;u z*X`((Oqm*8jV(TR+d=aGvjE1>N0z@$|E&>S1_K`P=c?rzq+@j%?*oq8Jdh%28zwAa zI*pM#4)8;`WeZlhLyyksK+Zwe5n#|9HR=)s9Ex5(b#eKQuPOI>E2++&8TSm{h6Hi! z8ejX0)Za{%;mv$0-s;eFwE^F%bKU4VpoOJ`<-(WxTY-asn0tev*!+`Xj=pz_Gd{@# zQby%DQ4fy`XZeqW*BAF&G%JYysZZzEihL-;5!#W$fTL#Gez?XGN>?> zos#v>9>#9;h<**1ELrI`mhb`5EQ+>NP6xstG8`LU%A~3jB(oRsL`Ak0j%VI%?)B>< z5B|hXe6F6lT|v%=cxF>i2#NrU~qvhw{e%HS#$ zqCF;v6O7!hCvBZwD-;+EO=)%cjBKz3npk@a_C><>OC6vekjKU1HD9}&%lY{C0|Wv9 zDH=pv6X2XquL@qR^3|(f2%_wG#>doe zE3bU|M*P1-sK9!>Tcw*{_W`*sVv|{PZH?-L}n^9NUsx+# zScOGQ{NL5a=DK~zq#347Kjbu}6g&b?jv-}e}p)TQyP(Wxh+JB;nslNC2ddtr?ML_sbggO_L0W=p6JD3V|fKV78qHHs#U14->7 z>p~n2_LZhjW0T} z?hiBUVTHOMH@%TsNiA_`$G+2Yr^x}qx28E);e-@I@X@nMSycXVvBV*ZCCQkR@G+oq z4?Gg-Y~>_C0i?y45`h%bHD6)oW^PzbC3;=>1}!-HEI34g5?&z(?h%fG2Sl zUewDWe=QK3n1}&bx!Dy%0f7M!IYdB0ivU~;5JoJyYGuDzau5NNp#Y=hj0}9h@dOT) zXuEz&u>bj)w`h(Q7$0>F5Ts7ldl2Va>kzXGo`!V^50(NbPv|Cuy=wd9PCAtHsUo}w zza+a%Rkf={Hun*2?qjR~m4UNAecifRSq8@%b1!g-v$#DoWQ*}TkJ;*kGwN0{_UnxG zxDG6qaXHk#!-#-9P@1y*{}iW(Y5Zw&YoGj;pU}w<)hBBzB`WC zuAwbW3w>WNwO3UQVf9F3#gJrF^fSobx@K zBCDy6+Q~3d*Bx6#Jv%gCIn{-}RnmKw5+#9I%QE6+b=|df2WHo0yBbMueywcwVyfjw z-j6gTGhQT}3Y}FSSOnIwlZd=~?Q`8fOKtcL*X5#xRbYiZ1Pq?MlPYep7CyH4vryF3 z2f4dm=ssSm!FWS0IGbPIW6D#y^D%S$ZV_k-frA}DtH(n z@V=X-QVgYrN=dIxW|`@GG7D^i$6i}z>=0?e0gQWGf-+vJTD(HxniF$y@S)Qudiis$13;x%hcVUV^l|7pUO^lC{f>rT?NWxUh+;1uD^2=$ zetgk7ZjeX@avuJKfHh_mi)a1_+t34If{|FAQU)@_?9k1PS5!w7bN2Q}aQOcUHgyi) zsDzp=4}7%a#i)Vvpb;`qc4$gBrTp}Bi_e05mh~fFAr1PxSO0{mj^tBx*mTAOkYhk1 zsE@6aI5Uukt)kgBpaO~~az@@-SvHeoK1)>~90uw%jl31+tCX#AMOp3Ru{xS=M83z& z|IlKDHB52a;-7y@{Q2qGhMW#0A6B-76|N)o6L3ybgQ})C~v4ny&TSIt2 zfFKlp)_eE1-nivR089;M8FFxTuCMWJ__UL1?UB6|RSS9;9&*Y!a?;C5;tanW6MZ6# z1FfmOB}wZi{a94bUZ(g#UuVl_Hpf)CSht!gaY|5Jh#V0^tmf z&A-J9VtrGTD`HJ-$(Eil$`{Y4NA>&YwJ?V$#cP3KI5UYyLv;?^5DUNH>GxD{}cmD!{;!`r0)r;nu zYMCz>a98!4Hb?gAS2& zgE)$xbfQK)pihe^xfI;e^#C{nD5iOhsnfxn7I7Z`XDKsWpF+PwFoiF;;xc0U7iUe4 z`eIdusp=O%)c*PgB`{?I%rtv>!K)(+-fMwz3f<$GKXbK651Vmtv2uw9=(`^bbxM$;S+0zw6}a3x4@Ct62Rh}hcP_^ixuN@myz(VqrfkWEP#$>7u{ z_myardt7fr05K7Af6v{~6j0yD(p|BGTrbqtYx-+tBW3nfLs4o z(Au4RF95ioUa)KYLLfD@|9QeZ76oOwI_kLI_psKW^U4-2y~6{i?~U9|t^ zg`Q&{5%G_PIr=k#$8GumOm#X_0ccVKh~l#3Pe{5b-Hi0o2~zm{+^K;uo1-V%hkOLh z2~#+>eChQ)>0*6%V(hn5h%^65j`xH&lAvFTo~6%L)9xC1P@k-d%onZuA&{0AaPsu? zHthD^-U#X#OrF5?k9I(YapbwIx!^i>+U9!i@+kNC@4I_D4o-r#6Xoh{B)&K_!gq*> zb@dl~$v!zLJ#8~L->7?2N?y>`re>cSbskmydN1K}uCUPhc9c-e24?OCU%6ag z@AMb$Pgjtx7R_0Hze5j~YNdr=Yd&irGCt@ZDsf`;B$PUVdS5I~A)`?N@W zX-_nfgHsn_l6)jL`(sc(U~(Utc0QeM*f-&>Z`EGKH0+ocvHgdf*H^94AqrvZBmP5v z#EO*wEc=d$G<1UZsvWV#=OZmZcOD z?M&&8KA4&L)dysReapraD1*Ev>B#8Lr`a2VA>VCIymxadc4#pm{DD>#J2c3EOjFrb zx{{uSpk|tJ2+i;*%uUY8HW+46`hc|UiiI<=nK=PUnmT-BKzgW`)3xX~pN)O#u)Yu; zq@uYWp~iulicx3EUV_6}0h11n?$RLOVS=solWY-(wu9OBXM;K%P?1qn`}X;ITbqyG zG+bxR=!sNJkw0-@+7!N&c4-N z1`F!K`eWz03+bWre-PIsf{cp&GacJneJu!QMB}D?zc|~`&E#G6p}>ip_DGBfW9LhN zXz9c@pvRr5J%>e&i}~T`z0-~TE+9xdC}0@Ikl&c3zBH+AH5JfE=)2Bc3U=?FQT0u% zH9$aZW`ij~2H$1pgOQ~t=C2;bY)N;{-;fWS(#BFE*rlUczK2etFkNkKI}TMQlE*GS zuUK3*!~{$Qod9HA{$5o*w-|1VebyzdoR*`l*S@y4_Mhe@Zo)k6#SG>odf{SSzt~!vitCO9mM!c0tWEH&2yHf0D&A9} z3~#Sk=-slRA|;`VODVvW)Cbf$kfLzKOw*A?mW{`pJi=~flWLrl0;X%sTIeR6%DHM! z-oy&kF%kLW7`V6)?XbF$#qa3JB_%3D^L?|3rKBOzz4GuZUTTvn*=WTbeI#0r3hIy4 z4uctd<4`*PXz0Qf!!7qs*c`iz&8rzu>sz}(tB$py!q8(qSR_VYkngY%Xbt#Ekgq{o z`EaI-TJD_HEX~JpjnI(cbZcfyf+9_y_ePT}6KGZB>TC2!ekw1ne%AZSMOB`4!uXW{ zqGDSgRo%Yx^bi>Z(w?W>l^0Gct4F%RP;Vicq3{>o>s}Kf3|RN_#Kr5z{>mLtUp)H| z0pHhug6vRDLtob!Kf2^T7d{D~HXKgu_tW10bf`rXF|BUOl!NayXKDZ7yg7D_(W-as)&%)~dREV5Cjrr10La#Wz@yprqwPArx2_BJQ*{FKij zJ5U$?&+@LOyE_(;ZmH2>0pTz3@0?zf$v5cBG~9p1mKxblo5mZesU$?lYk*&oGDw4At)ioM) z`q9^dA)=d8%nX_^#}5zp<`G!$fALe%W0RZ39{?Z)SL-v78FOcXeBS%_Nco~HMANtj@yk*;FnKvq zTx@mbd)DE+Bf;UDF~yH*zGzqd+Wi6Sr;44X=Zz~r91w6Nigi4!TFY9oq?Q1UPSSvt zFLx)3{&-tYL);(`038v5w(+-~U;+CIzw2P)+!dSM|Gen_dliAcRki>7*?({2&1*OK zb)Czdk1$E5@Hi-vw2yT4!p-sZ!4_h%A}G{hmr~9YgNZI{ijTideXZzDuL5fQwceG4 zV(#RhPDQi#RxL`CoiGGkM0bfI%p3|o7Rm%jOI#EN#- zzGosVLwoRIa^R{0f~0$_O&bt9vckjAE?9s=Gb{sOx$tFMdwM98gutyw}{nekK{-fMHs3s*fv*R=W! z)^0H{bX|R?>AtwF9`;M&d7cYHJH46Wh@=@63UJFgiS-DdYwWvOU$5{ZZy{SfGxQ4Q zU@<+&pXie(HCIS`9v&ZYq&t9wJ6o_5Wvz#A^2DVrVT>$G!Nl4cN%y2O**PWI1`(<{ zcv;b46mn|QaY2V-HUgVBp4mFYh%c*3!pV`j)=V3_skzx$`!k{*>SE~cZPIJCAQ#_b zyL$KYdhAY)v)S2ZdN+f?7Ime&G}^1Qi|+@-Uf_s6Z_A40DySPM$vZ3NKvozOd9 z*UOI3&_9fx-tJf0^NS0Bc-zIud4dk>CnXZ}X=xdHeHV0dcTasu_*K(tHgQ!#FTPw9 z)t}+c&=yS&UvbJwcpj$=)(%v-YhVhAr$N75tkiv~7kXv?Ol4cc^qWj@XU_nyO(=$j zq$y=KB<|(LFNMnA;NRi(Cz|@%hmQ3GAwPq#bF&ZRn>j44&L;&;I*V(-YRwS>RC1A2 z)9zjK)T|^$_Kl$)YOU(qk?r>r?x1BE$f_V&Tm-RJqOjUeW2f|M#YJY7hlih+A3X$M zi+WnN204;NnmuWMRXC4+HfcwfP2(8bGR@UsG=5x!z)S5qWBZZ?T@nQ?mrg(z>LytDZ~Qa3FWSB;j;3v z-@$ze$KMUnJgN^|DXtf>^2P8YhFtjM2X0aZIKQz^MkQ|bg6DmZz@tA{~r=7Pbf-OaC59~0dxy*V8pQ9NE?@Zh`Q8{E@mI~dddh5G~B z;Ca>F`Pa#R3fs%|R`yq$U6KQFL-zbd{lkwmg<=5lKA)aPy-iYTx~teVg# zOoJzirXh^;Oa05$A<`pt#XA}46$_P8Q{YI!vVvt^5Z|}QduXa_G&|9&6Ko7(Y%d#lgB=>s$8>A^qT{hCltXsf5&<3sbt#1PEM zF)S~~M)h&c+!Yjg@9t=(-+Szb{3!S$Xvh5l!L*jza=&x-+bASSj2Myq{NfF#$*?Cp zm3RnGsN5vUm2eN80}$N;cJ5g*9o~v*3dWmF+)IM~`WtAC)CmM<^65u3$7~t~{6T&g zKtin9eij)?%96tc`ePxElP?}aqQ}EWg^5hgqIWOLBq<4sAQSVD`W@F*UucUPN>JoS zDx6e#ceNpKYOoxP1}?8A{Js*<^#O7pgVCD$vPKW2 z_u9Yv#$;yF`p)3K{eb1BmFASc;j0oBIsZ1u>{V5!COQi6J|T!@G)qH9i)Lrp>?)DN z5HT?LzP{+A$x}!nHgfUjKIE&rf3^U&gGUBiW;Uus|L=Htf-~b4s=t&E8Bk-HS6>1> zrz-5=+&FbMOm(oW4rZ-3sWgrqtMMb`H>v#Ap?|b+b7O$?^z?c-JAMj~FGeiyjtU*{)mffZ zk7>VEhz!5;O)`a75o2e6=gSJ6la0N@#bm~D`vI#y&m{Eg;}Y0%w&=_CSxDL($=To^Hl%m)S0VCM+XPcd1QUOc*^neAzvVm5AzrF zxFC}V(>%4YxSwC}R0hG|BK)AVP#Z)#`}03dTLXVyAA`pvR{rLqk@-!b(=ng&8>~Ub zJ>RBwNB@@zobIE)DSQRC;KI7oVc+}*>=yuo z-z50VK%0c%YGIxtM)GlLBH`}7F zj0zb(2gUbaRt6VNrN9e7ILjc;Y0_%WoHQZ)8ts+YEUNjMZA$a^XV*oq!?Rb6h#XVj ziTa`E0#Vq$`rSOlLyOo61bcqf+8IgWXlSCFffR*NM&$!TDwgyHhhc1ChrIE$-o!ki zTW#V7Y2@|W^1iJK5>a>wa&ea7#6FeO(MhoB5m2m0C|t5@uC1>RF8)<4g*a(yceXgb zSSbgq`WMdgb8CWHU|3HE&nW-6i;G-FQN;IJ8V($V%#I(@alYKNs9D4Xyr1}UED3zr z4kH$8Ez+rOp9KJL!aav>h%`U8q!r<`|JcXo2CTbBcH4PWPqq( zhITpf59AFnzKy7@ck)U+CK!CtMnlRf8wPE^-LbmnCdC3Pgz- zw^Yfms1(+DjZSaG;u~TyNnBlC{pa_0b~Owa?J(JILo`ODzmL^&^-)f&e)2C{86oYI z*S%OZf0pE5&rBWoh5F$D(r9L)veGWcM4+(mv9R(ir-10O;LWkrXXve#5*Pe225uRh z6=*lw_Eb1Atevhoq=Mic?sToMI0m{Q*Kdz@6zrnOL8CHkEks%kw3%O{&5otqzK~ zJk_Fu<|U-LZS`<#4z{&sOX^_qqsE!Y0c{D$}l zA9ul-%Jkv?v;ch?uNbU%r~(guZ^k=bVeaSGet02gPVSd+Z-mb)#jmKZO`{41=Rdn5 zx6fbjXq{s(UzuO|v#ei;T;I0#<1={UTMVM^N=jFnN~L8F5=ABgyu=(##Plw9Hj$URzH5GRw4M4fah{Zf3$D^OcTIBfD_VaKh;h z`NdVa4O6Kjf=^|MYwz!=`*Uj-!XNJ_%j>UvDz%Luyx7-X?p|ofm~qDZx=)r1vy3YS zKagw%z5?CSi0ShVHk~!~dnsboHRpBd&2*J-dK#_1KI>YvNwHv+e{>*6uSk)gFM=T|AIC2*hu2c-p*Av|L%9MD|j9; zoR^+g0zQWWD~1?GM@bv*?q_H_1BfVZc%yqV5QIy;y#PN+<;CX$c*G`sW_3dWZ!7-_ zTnvB7C%Y{7Y;Vr8YNo;xOJ0xO#Y_Jb7HQ8H$vbKr6<3#nfiYx zzxFb}%rbAf`Q5u++BNz5=Y0KZvys%j-Bo?jdd+NqzQ(`O>Vn(^rhInX3p2lcDtQf4 z^L~3;AKEWU`>V13paH!3l9vX(=bOd1kNV!1Vk;h(s7zyN-ER*H7lVX$8>i<}Yl08= zue)D6NW!3KUfRw(qvATQY7PROh7~3HZN6AOgXQ6w+b`a^eWe$yOC2zBxO}6?dRUwK z&}ZP-ICry4C7dsbm3mh^cZf8C$)TPAlEkL#6$z~Vy-RKm7bJ9$eeI_p!?ASjrM>2H zmqa00T^ljTfhjb1ejl+ev4m^NJdtfke%L#Do#S)d#yH8Uw#UtkzKI~!@)U!+Pe$hKP$MCESGUJ|4SAocD1}7^<;>RG zU^ZqwVbBd#gTDpOb?NK)Zk)P$n)4Bd-Vx5@B5%4m-{b$-;xQp&sM&=YY^0fruk!v4 zgY-0XAkYeG!V}!WUKI_lH^KTfQm)=6!Pr&UnfHT|pdmIb92s=_?7D-9BpB-OD>?nm zuTt6QTUYh%MaoxhZp2T1&0S3d%5f~IVimdppxYj%oaB|sWv&VERza_eZx5MN3xiHv zlDE@!kt&vmf!kdTu0u}vt# zH_PZ(m&gZ>Vk5y;rV#VFSd3nC?Q2E6XYLU)*7=k5uFgvm!$f7;H;N#tD=Q5>kB+p7 zd3Ika(V2A!vk}jN?3fW38jN_0@*CYsu+ToJFc>Mw+$icNF^zuL5Gl{Eo`pl1z&${qMS;udUirp<(Z@H`?Pqcx3)y*gix;c zxL)n?C>l$!KKEgM%we2s;?}B-^em2W(o4sR=~UnF<-TqO&q0FzqI**qbBtMI!7tj~ z&Tzf-VN;)VwXGiDDfVWCDotLzy!fb=*P$2S;o-5!eW~r@at&VE|2?;xS8afuFovft zFtv+}A2;+PT3q)Os3dGB3t496aITd8Ks)Id0+@@^$-#Zp-+QhPp_ zDCx&LRN}fYrM%Y0Q=AacR=^!b_cG&_$yt;*IPXI zJhs7aURTKGF9y+`KCWLisumNZf8x@!YO|;3c;|@$aNx`gUyiDOAFHg~7W^k@DxD=m zeBdrvmeyoZ_mV6WMYo3F=AT^LlWQ++hP(;LHP#yQfSJOvSCfeucT_c>_*{ZU$KF|e zYhBSv%1yFqw<_~w{Q6Y)HA=nwXZ;ik2NZhLANrHuGoEi#DK}IwK-PuT1C%6k0bV4n zMElz{=-Lk^-ZFJbsN595Pc{$EE*ttX;1hclwZ6kQ>g`e*wWD{CFrEg-XZ;EsqgDTv zBE#o2Dv58(s>2cqsUG)rHbiBsTIS-ri2ic;%*EL6)a?mCuKAjAbzx}sj*fxa4WiVU zdp~ZeVnwSxVIUR}Y5tdtAx+2(q{7w7_G=!6FbtALn8P>Ip#HAPC*$EnLxX0(WJAhe z0sZ`=3~q~b%c?jgu176=$#KrkXby&9sq4^XVqV^`kO}7Z{fmf!S+R8ji&_BswZ3T| zUQj@}0toH^hln^w=D_AAIe@JKO8mReOy<-|V>80QbyysDHpQ4|s5L5*3Q^b?kj2<@##Wl69)0@kb>j%r`e%4+3Gbk`)tHt#ZI zJM0e+AD`}Md0P*hwh?$c$^AXmRqmOLON+`+QgiXk_+nknqNuL&TQ^^9HXkn15Ti5sB=( zjL|}SkZKBXk{Ms%;(dxt^VFI0^vk!Rfl09>AC!i74FHwtGSVH!c9wWZ6(r}RPaZOF zc&58BCnoadqz$(fj2;{|bj{0%(w9qZ_`KdimcaMmEigSpF#r1d_wPUx0@N@D!+ggU z-IAlo!V3F!%=>#Bb8Xm$T2a%c`GUN~1c_ zrLA6-NPOC#RtrgG;v#wtYxWr;P`!Y}>ngLiivE_xYXrmgHW`6(jgxWm|XA}j&U zgouQM+EOIG79{IXOIydzkW_1CwL$e|YfAyhD}#cX*kjZ^9um0w{4X;4**n#6_2s-T z3{B(67jK=a@$k3D!)_Yh+mtc$$miCsuCBjXCWMIjIC6%&`Mn2X4G%jbSinxBVXM$0 zS^?42$yQ|62Ep<`iZFSm`o4FSTG<5=!p(jv`yQteVu|zH>zvvqQ~*Iyn5w`!5hWd< zV(#6{&`39SZcI|UMzZ$p@;l&nlnPna%vwE)Fas!dCuAr3KZ_@R;TwE;R_5YI{E-mi zb(wx!n4(D1j8xE#9``xCa&Rt6%e~XvR{R%cIPOM#t;6kb99|xMms;8E--$9X@Eya9l&!}Va#eK<(@CX`L{gpcODY%De}dok}!QN2KaF7O0q{$*l@D*S-40c!>zB66%XC!*FO>jwz~sH$s(K@x7h{Y59AdTjGK~R%vF_IH>eYA`6k_#m|LsM0&M9M z*X$}py;d3%dw~fqYaaW={*?W%a7Pz+gdaj&G~Qn>7b9a7ZSrA_6ut0lLK(TRUUAh+ z`5d}YPsYPdl78E|aCLqyy4*l)bc-9fA(W^|*&2rQZ`~+dH2ncSK^9POl93>FU5GUY zo*b7$e12XTk$ki^TD-^W&SOwX2QCL(q*FHu0>vKRT?;wRF|Ual8VijMJry>Ju{g&F zs8lR)bJ?zOnQH~2qs}=oWZ}Zo{rb#{Ynnto<$51_e=)L5lYS(L$bKK~uSS(C46Q_; zVsCHnUs+iRJF|253BtWQ_(XH7LaWc)^VRbL!xxyS<((kWCsjqlx@PYVGU^w@SK4i& zvcn%Pn#GUvj?9M|x-sDkSUAV%qI`k8Y5h@hE z{Lm15@*WiOT`FHq1Vq2T%<2>aQGnNEdwch34u~PwObcl@eQ1K^-Y|JFeF&zpP z&>AUOX{UGK|E7oz_< zx98id&k94!qJ0(pv5Mo*4LJO8&7=8qtt1+q)WuVb4WTXLewWU)HTXdB4?bmO%SfI0bzv8k*Qm7+$dygXGp)Ty-o?0PWnj@E z<0Q%iJ0{MncLk|?rK;Gt#Sv}Is;P}ooC@bjpDvzu|AH&eJlV7+g$=y7UNB#8$h0{j zKFc#w-759Y7HdcG-<_Zm$|WzmySq~?9T$GDud55l2k2`i&{Fc|s3%WQj4=;)#MW5i z3lx9J4jO-eqkOWu4>_Esz<6U5KJk)-@U-w4AU>QuU4g%yX*dlC8s8!Hf&Z zm*mpkif;T>4q9GY(~lQ}@_5k|9%{7t(-_0+cD6B7Ad%<#_lZL;N#_zvd>SBg5x)&- zr-fNxHA#te4}K`7!D3xs!xd@;8b<&k<74}XtQs#N)g{LK-q3I&(eq1A5je9Rm(N(r zlSGtf!^L%vhJT78;l_8)6zoz%iO}veq4O5??U~|iwQXo&5bmhE(2_z3j|v?TyAkI< ztVuad;RC^+A_aVYu}KYEn37+(d2PV0ct(@K&>gdGqvZfmk3v4^d6eB*2UYGIuk5G?M}=)R0B61E8y?>Xv_c>pP_{k zHyl7snH@<3+RC^boNjD%Urs2l?Fp3$oH+|nA$ z#d625ZR!A1#{5SK*7W1hVIEzUB}MFytTI#mrzjMnRZxt5e(^RxZ0F z`TltjpP}Ele@zRi7%wqR3ee4@Z*al)I&uz-La^atoOo=mI1WRaV<&)o)E!6e4`CvF z7p37AkPnW_k%3AqxFG-XRxPBIMlp$Km?iw=Haf68<@O;>inJk*Uy0M8u`DtCq&h+A zJUcgz3H(SlOK&**KhdCM78LM@&a808pWxr z*Xb32ntZ-8KFM+w(`^0g4-dNyPLLDOxi{4f;lccV`dqk!I=z}R&u3#D*51aj9#C}P zEq)vge#{Vl9RB)`@2Ywsdp27{`+w@=SGfldq?IKl(Ew`Ki!2PL+Ow_^`C%nm@v77< zL&JuML@_ZbU+SpZ6(+~7e?{)czD=vx@FBKo4mFDewY*btGiPDinjP>*1j)j?l&bau z)vsd<5l{p$F*7%~gx){-U^hh#f3E{%DZ$*JCMn7 z#6uAeI_#U}L?frjltr}4X*}ne{4%qhSJUH=HIPF)tcj=86~?%o%#Qle-j7h`CuR+4 z`aWxAeuO#-PRM`WMQMN^jB;@@7^}ahrsH*{Hdoz^lrHz&OA+Js@3 z!vZ1!ah8i@g$LpW9(D^c$&XELlCVbx%FLB9IG7QD|Iw*yrbUeE5-vOs7Fk)|my!Dl zOdZaTN>6g^r9&!H4q0-YMP|h9NEtASCF+J9_e@>`)ip=5vkrfX(rW2WytjNH`gxdT zGr8mIqJb2clYem0Iie}*H8`9)20rvPQ)gmVNEob9|@z!%T#hvw%VYh;rj@n%IJROMdRWQ)fRKldv zow3$@$MLT6JTl!Ql7ansdTN7>6!LRAvb%xj@aPDsn-S1by!~LxI~T=d<1^g&O&3fw z@*C8*m5?QP?ECVI*EaH+?TkxTEood}i)=WZkkdN@ATRszHN#QVYa_$hS}aCU^){Ns zXdusj#;+&(zLRh$BF)-V4?|S58#V1_Tsk|{%`>%YrOeoq@Y-FA{OjuAxp;UwC)fKk zqNowFoEF=!(6J*IgJf3wH*)nyARvn@VO4GY_>&J0F>XV2!K%g~h1{PALYu7yf(Cb^ zp?;~!usn?|8k=wlr+%guD^x_+SzD3QZwAfR`OB>pne-f~uCA|3wCKV?{liaIZ8;l7 zQU@>;91-fcOo8c7iZ|y$RzsC z@kUQsGmVJ1-L;lBPc-x$c0yOg_Y-=Nw3)!c768uq&?oqnjI;uE8)1NnWp%e*%eueZ zbq*ZX4m`?`$!lTNHEJ*pTgAr5C?r!r{_tgUD{S&9#%0ZRR`d7A!WyP4cDhK%+8#LM zgXgu3Q6d?NBY1-l>qm$e27ET0-A@%EQ{NP*=Kje|F#k#yr<1J$95w3$CV-;4y^o^^ zSvdU4O!}iq3U}`%b&QHFQ|@pTI3pw9O_7+bx@A4FCDY~|^5(89b;Vh?l!45!>?>I) zere5<6ld{j@b9iaoe>dG#Vs>OJPE+|r}E?H$B!A_Z$QOFrT2~`5^y`3 z0wQE|s?l2>>?UFK5tm`XjuHbFerQdil?4|Old23L&m5uq6-AkKuPx8Bm=aZZ#s45g z5$?ZX@5W|$DH-q4NVR*Ty=d>~I~`4V3xciwd9DNGjmqA$H$PwotnT_c!pD41x&SH~H3vlx>H3t9?GhXOL^k*!swGDF|)0yfL=8dvapoQtejBEvY4-Rlp& zyeh9=U3W;;(MWg7%P=>ht60EYyy_1v#O zMPZ-I-Xh))ImHL>Srb&16{KS8mTsKm+IS*R-alQskLxdLtUax&d!`6pH0`I7#trUt zdK>Rgxa}m$0GvUDuJli3X9y?q#2eJ%jU}kKIDm^e&Sa|u`NKcrlc9Kp? zOOyg^vLBhR#O09((XQs{W*if)(fpvwK?REw+diLkd$|@oIb^&McOen6j4oC(9Xe4! z^&J%rEp3>Z#5$Sy81XlsajQYy`VGvvrb(4bvJW7D&GeSDg5z9oOf_iXkMv+rYjz@Z z73s7OL?&3>GV8qg$-D`K@I(2pKY-V@KJ`4|wvF?#Qjj0o_;7wxsnqTTc+hk=4|m}`+%q?LB4pVJ!3U1F+7>YD7X;rs20Q4#uaYJ1eWOx9FuQOY+IO8KV<pAiV}G4%L}0e|Dv-;&dOQO%&5ig`J)9UvZl=ok zmR|U=~2QjSN{ZZ3T7tu)@muE@s5F#gmbk3ZTVgL7x&VK#)Ldtac=c+%xJxpfmc+hpUY&q>^fV8I972l zdwW8mm>|kqj zq2n_64ej(kYciXX22f8XLxdrtt!5LX37F!iN-|O#7=Npn*hFXG`z8I8Nga1|yVN{v zT_bQGCyw&=E!)BL7~GoWZHgMt+Z4DzDH11Tw^AdR0t4#ikmt*&=F5J5T-xDQO}pZN z720n?rZsTk6|9WZE`_NxnsDTps2PS7D#qNvNeEAu&){T3d{GUe3%}Hd5!Om!=4XwA zB$R$C3stJ?pv$GDr77FM{7oTXo3uCE0uEE)%E)SW$1ErP_Za(;7hr-i70R{CjUa!3 z95B&5MNRUwz+@SE;q_8g?1U>M=tnFxp_W9=qp$_4$^gdMI1a{~MO6QGah~!lcd$$B z_CJwneL=>`cj!u++Pl=rNqyX4ZpolQeDU`9| z-X5L42K`pJSA?X~eLxaNZDiM_g$kD(eJE4Pf23`G$UJ&dJ2_t;L}Okrt|F4~z*2U_ zW#!+^2mgODm_+o`~~=1 zl<{K~gKo|L!<{k{WWcC^TGv&K&qC_GM&g7BPmK|9oRb33>&f}~`yac}EzQjaj-$|9 zMA59Iqgiw>LS6Y8npnN&#KM)Pby|QuS(e%fd~LxOY6CHEg0RS8`7eK#Ty^^}845(F zr0IJ~WqdN+po&fuB$7alP^1DI3l%1nJN>mV!1kea+p^gipJL4kr z8ga_hG|xNA)$|J$FUG%EL`R=ivR(GLb%lsuzq>zQl{hX76DAJ>1kp4!G=En4!!0Zj zloe?lqJ&jT*e5#)W032$IglPIFIrSLPVVe5$$}&moAh3MdZ`*3YfHc+dCU~}-rhk0IBj4QvN%5W+40Kh7W_z zep6vb?ng6@OtBhGQDDb+=mX`SICWBwJD+$JLj3vhHV!ctGiHkdfUVe{aORRqa8L6^$M>(*dS@YPds%%Am{Yf zZ=k>5Wm1PYtM4E9$_@AOOw^s3;UPPd$joz>m9K&THv`~S_uggrCbgUl_&_Rriwj>= z4SmN7ZLkn~HPu7!ln)=#t=N7^(Lj|f06z=xHvucl2z1%eYf_4&;U|TF@;#Lgq3`D{ ze{Kk4KHe61>_*^$vFoznqK!zF7=H$3I_Ot;pcec=b@p2?Lw9;Pc0ojAHoX6Yc~@$o zwZklF216s|^XiUUc6@N=;C{ddyI8=&@~p|Ot(a zqJPTr$RZ#cC3h}Q<;Nx8%JDP$A?%2}o~m47|Ej~j^Oh{`L%F%23=^<}lNoklTU2SW zp~kUgf&Lh9>I0&Mf*Ay03D)O-C%!}J?ivEL-vHIPwQdMfNL-w2MF)W#X@^}?(dC2+ z=XfZXxDEfw(7E+Bv0zq*aWH?U&~B0M_5R{dy&R@L4*bs8dP>8r=?Cvj44-??pDztD zIp@r->0h#I#bleh@_pLE>uN^KYwBT_^d;9rz>l*T9INV$9c>wwAsO*r(U7zLxo3Fu zO!_!uuA6&#W0W^ox*%P$AZ^|dJ#fD)T!-$r-Gg;gk){X-$i(gW-IVgKKrsQ_Us2CH z!e|)(xHG;9c_cJNu^5{$**>^Jr?%jO*p3BI+z)&q!X z{GXA{=)Qc7)Ya!Jik>oWXUbWKh+(=g{$71ve@#x4YL5OjYe9ew7~m0sjSK)h01|NX z6fM<+9YC|za!)>i5>(7!GUS36L8eo;#E2vg%^j!h#7EMX(bc_?C@r)tTRbNdE0rDZ z-|o~Rf1HQJvlEAe6wrium&kgaSW%tiaE*V-gJ&9?{h`i+2Mox8fkAC~K1aB4$!2=a zgvhzf4pRl@Mk7xx6MhLKQTp`I_`NMuf=M$bTCYxXU)gMX*9qpa+yn56%@Hp{M(N+o6DpOSO(%5I8q%l`QE zeY6HP^a_S{#HAm3)M5GkD4+hjJGpDi#;->WM@FbI%BDrm`Fe4nmtmrvg0upZ@XJ=At8-WOcH9inqV@MuO&BFMx<_h?fjTQq)0Gzk;m(*)L~zwu^E z$qQAj`kE#+F_p$R^K{Iw&${W9UvK6VIMd5L#}-yg7talw{Ia77I)ZE1{Ip$3sJi|# zp6NF7t#R?xkgo{M@W-0;d&;A&JcAB_M3C~ck6W9bDt*du76p(0Kmv&iYW#36=rUlv2)09RElh?N0z+ zmakn&Po5Dp z33ZdEt&_=ek>|?i#{!y6Z@U_=1^HjI7DcW{pRV!{0!BGsaPAh`Ew?WWer<${1R_)~ zWH!;UMQf^dk$2G$oM&9= z|G4Yvz92UbN;3!j?Cj5qUWMqCWU60rdGxdmVG)_(N9Wg&XTnepFYRE;0p|fwWvJR5 z=9=e<#f$L9ut`Ixl4W*xr=$uM&_}kNaBJpo7x&3CaZh36`6^sqOaXF>wwhjIR>y)X z>2IE1;&MTSPZ&2Tz*3#9buf(9Q?X5kIcju-ZUj#xQc|6l}z zuIv9zIsht;DFRKqFD7fLj(h~zuE*7x8FZQL(-*G33x!kF?9=AD{|1JcH>h9pe7fz; z=synaW8IHk6=w2%Wtd#Q{-?hU|G4hJMvy;e@r~h!Nf7#Z5}n;#>j`f!*F=kUg(llP z1S=FDzO{`x#!+k}qxq!;Mx$f!#}oYspR>{hWV3GJhzUzJicg*%I3S_{;kLMaFgE}@ zHrcLfqssvqW)X}zFsg$JG#CPm;WClUE?P%4A2kGQyKMjP;r0d;;u;J6sHBL9D|Di& zA(IM|Nv^CXua&%(8-1T=sTX(>n>j=$FF^D$d~|C2?bx-A78^;`R1LyZ?(@+g{n|z3 zj|+jT-q@tpcIYf6`4PdM7BYA-!9*vy))+jPkF064O&m4uG3}A9CUVOMl2W(HC1EI| z24APwEe~$&GpUw0KL+`c^p*Tj1RF=dDqZuv$^UqWDaLE|vyf*L<^&YZP!ODw+cN)$XEk@#vs?#WN2uvP@Z*u2??#VQq#sIef|`6_=BZ@iZF z`LzCVvHx6K@WQh>lBvK^js*t=y6|T{A%>I57MmME`Pn}!K0@@2&T=s^vdS&86I0vX3d30?A9wiXz!j06QF&f(@H41P2tl49uA zJ?K2w1n;)SiuLO+np(FTC-9@L-MNsPyWb<*y#R3!|L*@yOXDCj1kQ**`5<%5fI<&c zSDis;bEX9O3tF%%C{bSO(}#Vyy75UD+BRC3B$%+Sg*0p)>ALrMOIhXY&raiBN*04` z@Ow715Ak=DyP=ILgtL?7SAbqOBrptH&XeE!KD>xsWnjTdO>>po;_!?z-AniVt%es6 zN*0}2wWEx99`pc+Egf63F!QC@HA$n@fOhXz4%v^k%?0|Lu&v$l3+}VAY=)uhrpV&Ok4l{AtYXz;B+v6b#9%M3+KQb{2GM7#JlH!Dq4 zWc)Hz+gQ_UuR5CIoEe6G?jPCGBlA2;p)cmY?_F48<>AQwaY5RBjXJ{pDP|{8fuJ=c zr=46;jO|hYR1?e<^#b?GH*bO8D@meWtel9}OP?a8Vis9SIk_|_%vHnFl<0_5wu0Qs zZ4l^K2Fk;}q8J__`7RM}xkb&BWq}w83~~n?ZdB%nk4CHE6b9_$#D{Ug)lO2ox7!Us z#;uW;S7yX`B#(}1)rg#u>xJc<+cf=SQ*GS$;d0x#PdgEJM@KDPzq@LJO9-(oryhwWl((e^ld>l7I zWc#Zq->^G-Uo$GDDZ(@>_|_|kl39@mPgjA_8Tgi+wjtf)?9uZ`K{_5LKXwWJbI_#Ie#90neUqoMNseHH(e^RQE{xTa!`@49S6>nRZtyw8n9aUVVI;eI{A zIb+#yG0A%_Y2gg1wH*<4cUgCKEuPInGFs4{jbOS_PtnICLa+zV4<%pTtw(6(wQ z$<4w}g!~d!!gqe`Kx?D!y~~NVIsnou0AMW72S)E&3hT6@xpWj&{Xo|8KwyeuVMmFa z-E^|Au7bnw@#gUME07~#QyqY37-xuxL}ba_3H3B%96JdsV%AkS)cCZqk-vTL}d6`0(Ukpco4{{q<1 z1PP+<>wvTUdAaH(Lpq5=5e1Bhu8uxv1kghKOH@uw?vU@5Q!}KbOW0VcOFijJJ+?1U z4cdsns#HgdDJCz(iktgJWrX=*qMQTu{3NeaXCS@w_ht*ic9UMfLcxj7dz$NahEAuv z=#gR~`o1I>dB3;ToZL~N=@ZGIDXdHFB7IML;`wl;ye5y_0L(c`AZGO0Q&C9Ss+wd% zoiOalt7Ne(V%J9cU8+SMo8P73dk%NvF2GRd<>mEfd0Ds#GB7X@q9{R&EJfD(EtMl^ zloR-?v$71>2tN7j7gjNQs@IO_aF(EaT>>Fh6r$M6u>uso&eWy*hkvzVjBwwg7&)MA zX6;Mo!jBQJ83bYSy+l!yj_%gRyGj~-q(NSyc~|%f$eWQY#AG}V#gW9gpVcOB;f|rf zDX0|)1Ty$Dy;$@~a2@(+z!x#U|;ZFTAAI_+Lh}yo1eVoH#Gkh}_hRP_4 z02sTF)TwT(CV7q{ldfofVq8{*qWmzEs;;TJy1I~A03OKw(F9;@^GF#*Z8hl3dWS9Cv|r5nWpSa7#G67^lw<_ItCgxV0xt@EjBRz0+_BiW6c31KH`jk-ZS-> zq~pTfK~0LA;Gn*6c`!MHXagS|uQ?)W z`7LUxEZdI_coEq^iA-kN(?qp93P?!c{jhTLvIR?r3B8(-v|I(xH&K8}U!su`X|h_0 za#^-hn)c`_t^ah!^S_a3>yMS|m^QO;i8c9_vnxZB!Gz=NEJ9bBJBe~126MptK<KCmRZYd0mjkvxN(uazQZJ-3FnYXsL>yl?AdJA6P6XRIM>U=DNlEdA&(6sErWrl+OA{KWCNJKmOYg6CPgkFK?0Yee^Sx~>)2BnyWE#8AlsBl&l#jc4qAorD;Qto0qiZ z{fEK-t7rP*v_w^A(b5JSKZ+sUDy_iR0}0A)5^fp-Y3X03f|KIlmaK7kZ^2^2?fOk& zw#DTjT@nj^6S{PFL~by#o<0z@^s8FFHEcSMD##q61w>?=PkbRouj;P)izyjW2wb+jfR3U(svJFBbvveMD!=_e?YJJcWr`>`sjR)jq}1W!wHgUVc0 z*bJgsWkEc21*D8_t#x>5FE>KdI8QQwraAtp4x1n|ur9&j9vh%r)&P{jmM};7K9AHa zFn>3Y2mr8CtZ-&%TeyW$b?D_5Z1=`?lZdtH<(;M!nKUpn1!=NkloXX;EL>dXL}CDq2( zhl0Rx&gIKE31h(DW8tN^OR^6eSIHB6ogqv8XIXmkz z;GiwpN65?cl9EXVH4qk&GAgye_52bp@WojlO+B2;%2^3&Pzw);(6{Eeyo~cBYS2ch zRF?^#Rq7`p$AD*)d~^eS;L#IlZ@lQ#bXLi|))YPGOgOD+6w`UVxxwywJ?`p!-h{~N z+1O+CJR;<5P-^@K_kFjAPP943;u2;=*w&}YRHf(_@_9YL1WeBM?#*FO_wR`IET(zc z=!kP~U-&hPP|6`ct$)1hbclslfPx7_%qq<+Lv~5RuANvn>v~^!ug;90-nGPdOfwuC zVrktboKr5%me3oBANzO7cgdJ$!Tb2LCBNVvEaJo5GeY|M62a+&Y62zV8LttB;--1d z%LX_@esB206T*0aiIoXH<4F-ejBBe@Mz}^*``NFD1+Y^YBDJE~la2zVDG*aKbLyf* zi;cTp+%$_^3kNk@y1;!qS?4!?Sb2P&fAo0lb(}c*1ktIb>^Ks=$5JR`A&Dsk+aHVL z&n(k9@&ULPP-WSSHa!4=L8{r#a!Hc7GmF0XfsYgzhC)_2-)!ru$fqIib4=0demCUKLo?wHvN z_I|BF8Z{}PL=f;{!9#S_=HR9f-0kR0!%~x!I1mqPbI?BPyWPC#D5DaLo#^h{wT}Jh ziYWg^C|=|L_(~F;NRt(71os;y1ouZ99RkrYIiFpU{Ew<3Ae2DKV6CXc7j~%gL-77` za`tgJ-iK{xCtAeQ%-X5I1QnU?TEQKkLOcG9N|W8*7HbkM_)a*uEA9UPzqr>apvqD$%byH^bOgUXWpsh{Dv;|OEmfNXZ_G5vT}eMfPa ztkU;pWpAEP-Venqw?uJ+)v_{D&7EYy39!eGK2YUe?Xnok%6QY0U!>@8IPsEcVQz77 z1sF~Mp)w8$%SaYKC$z(!M%n{z!+GCe-c|+b@tefgM-1Ro`5a7VbI_i9Edw9^%8$K@ zE91pyoX|l+zpn-4j(ETQbnF^|8{rso;AqMCO(e@*uZBg2^u+KlQqNQNo6vW8SHC4L z0po#w!nTOSVJb}ZD^9ut$dO*xh&47ci}bGPtQ72QbW0}8M1;*0(aC&EKK2gV1D#iUV1SlY(cD5PGT)sUG{0X18giH5@tE5Lkw?`nAOszkMF z|K z9oT=LtKsK?S=T$#TLF@0!6kgw`tjBUK2HLu5fok%l9TJr9{Rn%<$rUDqNDMkeL3Q>SR_|EI6~19ptZGrDf&Nv1Exh?I&2Wk4cn@k3v20Ik zfUkr{$0ROfKMUJ1^Q5NcPmk4@_(DB27Tcv?f?|o9;Y*ua5(gzdqtnoKPVC`2Ze2a& zKC5w@**@C;0?lS(orJnvQZ1ON=V@_q3zH{jBH>uHGY7^!K3c(Ttj$9Qa<#KHQDkUJWpl{waUJe9t;ey{1 zG`pfbaI+!qd8tj_au_>N*k_+#ZHy^93?;V+fJT$FBpZd;{JRHLLb34PWg}=vQ5t09 zm|RjjPa-Uk?^fu$?SAqs&=mBsLmO=5NlDUJ1z|%w34{B>i@&Ab#yj`WDZNzl;YlNj zAdX+1!UP)m4i$x1pZ;iVmkmzLrAW~3#1-CWk&@I$v!mrd;|AXBr?DN&HKKIDChOP$ zJw8kgRf5kcf>}-Zen3#L;!tDeva}ACoTx{t3Xqs~R zaKJnaEL|pKV~Ah_McQA;j*WI`nz^U_9ho{IPZyOIV@h~g5to4vK7hW@gn$I$&2-Tl zXUh>c^b#!$(0(AaxI~8e%@I@A=XhX2na)WcL~hU-5}lFAl=<5(%sz+(%sEScZ;MT_+Fp?dRg;< zFR&Jed+yn1|8_LTt0hVp88HMup`)bJfEcq;h}=}O+=C-nGh7r)IZzE-C0CwF1MC<< z!{jPL-3m&-8*uZka*}-&oxR5Y{yKWcgGlt;f!)ef` zFD^+(PoNybbB>r96oa(*N+PStIWt!IO4k+qlrba&FSt_T8-!^7JH_c;jfiSJsFs!}`XpD;%69Z*uxUTqeux_6qUs zAxMfzW-%IxIw|EKIkRO%jDBsnaeZ0w3q84wUoy;9&V40(a7yszt7&l9_nwXpvC;+Y zc1=S*2eTM6J@K#Q8t%t(v&Z(C^v?xPyUoECGu1bK&;0~F0p1UnOk&3;_YHu&9mXhL zG{|?qnZV%t(#Jn8Y_TV#p!gx~uzEO}Q7O@E)r^KKiM_Y*6yZA6fcFBw=#8cb*#rFK zqWpn%TfykmiD^1_6=^U>RG-1D^_^1Xl(U9Yd^+5WL%=_cl}y={niF+lEi1SxT*{H5 z4R@Ugn6`faVAx}FpH;x2`iF1?Z&n#REusFNlrGX?cSu%0J(^d+lnCk2bIpJ8ffz7` zDGYV%DK6WuFl;{zh$P;ea3+j_!?}`?cv3bSW1^J%Hg{|{SY}vK?=OT?Mkl#oC)MPQ z>X=Z>TR&Kb@A1}OaLVHV*9NK)eJ`&K4gTi!n%>&t4&naM&$*_BX-$r2=In%~?2XWV zfFpu7j2-x1c>cY3`O8awMLg1H$r%Mcx~kQ=)H*jj={GPVV1wd zm)7w2Y0*A2V43&=$;iTY<%&B47$W=j(f9=^<-pay^G$cwjb9xQ$qQJZ1^_AJ4Q4CG z-17y1c!3-tf5M5cXv=VdBJEy34pqq64U(th)j_s6O&ZP(^^Lr$Z>Wtc|EaU@bFkS5 z)p^Vs-j<9VQRbk^nf{`RK~Mx$a_8vhY3z{&yeIC}_=j$9+XEg_pYz0Y4~G61@$&}m8r&|1j#t>A#4lvy7+IoU zNnnGnmHo;Xr=c8I++~EBt)o_h;Pg1&Gp&|L3+RymLI31c>BQ# zu8i8c;q#y0NW0;!EaS2gp|R!2v63QGk_U-p>c`e7O-CYGt=orn4gEsheze4IDPB3< zDR4@xXdYv zxHm&y7`%kkfMYYfE>zhF-wmzzJ^ovklkSf|*<9#d(bV6=p?{H?0|Vmc=jT5OiD5-= zh$T;ojHg_YdcRTvX1{_FPzRIVkv7$z8%IDoQ0sSBi3Irmbb`3 zDH7fiO+~~11~K_B5X-h_BBGxv6-16WT~$J}1U{uX^GNptIaRdB8Cp{qGg<6Mb|Aj_ zWPkij^1+jttTQR9_qFkq!wsWQQ^zn}T+i6iA74W5v?c?Sy5#YREs~Dq|1@T`o&b=n zT`Vr$Qia4Kn_yE{KACT9vAd(+k`=KWPe>t&2o%{ZcgDy_1WA!KGi4_P9C`Mo9|Ugo zh<_fMsiZSR!r>=L9tcYrZ-w${L42uEC{<|b)38yLDLF9WXv2Nx!C+mn!M`gfu7>X= z3PPerTio7Rs(e)zhy3|b#|lfZ40x#)h(PCeI)1v?2)k& zZngTKmP1phMen-vC%JUejuanZWT5P4st$$4;(=MjUxx z+Dh7_PkGg`q8PO^gU96q-N<{yFjcCwUGp|%q0V5u7l6<`;T z;})f;NF&3O+vY});hA2DD(@$tek+l#9!<9DWj4*GEdzz^HcfSENXLYl;+*{Xy@TN& z0mzyF6t}9NqVSj3nrY*EW12(%RToP3NI|Dv)q(VbYQvKW zEN25QjQduB17inzG%^qy5;<{ZGyY58D;SY8@+25P>UL>o*?+1gay>;QL>@Bcl z9IQUpSG>^97*}qE?^T5@xQG#-06t-*$@%05PRAQ=ArvKfPO7_YEylFOG4paMYHi@H zDVj%-@|7_PcICtXV4|647Ueed39{`G?!TL#X0GsYyhk;rD^sJ8MnG_ABUGkT?A@|J z-T^-k3tm_#C&*($=*ap{fA6fzG-!t2=od#(N&|@r+uNV)7g6-fsP~dqKZ71Jk&}{4 z3m-BL)J5hOQThP`zSF~{-svyK`*Fcsh@oBz38&r9%Plw1b-{N5{59)>%(t5_5~^G3 zTy~DIebSt)4^-I1)_GdLGl1t7sUY+%mfes)kvd@-tD%cl361~4#@^D~w>#=Q@YwQ2 zLpYD#2kJa*0}hgd63G=$MuA{sSx;d6A*F)I7LHQ%=E`f3xKuWXUik;sdCD@&Rb%j5 zF;^@ZMdkMc_O%4E8?G4wc=LY&efStvM%aBqtfjHsZAEZl|GE2|6?bu>oKp%(#V=ey z83;5v0J|3$Bm=WF)IH1-ww)xouU2fa+GZZflsGXoCx0xQKF!l-?S@%lzxn!VwFKWl zvcX(%D80bNFQ&_YTe6TrUL8A&VBplJ;@7UYeO!Eo1UaWZuGjzX6-lK&-X7}>-Ir!VBpjT_9A{|JF)$U0cPk@i{*>R!w^7_GBM(71;ThEj&i&e0`4a6 zqn_keetOcUkkFF_<;~qOwn?{KpA)J-Fcj1)bJ=|wB>LU@hxVVa2Uf9%I`G6A|Du}0 z_@^i#U0B2?|MJ-UHQUwh;K2an?RD0gFePCNn1 z58gZ68zx}lW+J3oJM5V?Ww4_Y!@J2d&%@4*8a+w^D}D0Zow2+5hXTLbi-Z5ibUE`O z1qWXTJp#Z12n?A41#3Cy%f_WEzu9;!{N$mzAQ6MFxZqef1junONC7|VV7Tv2->9*)6o9H_}v^#ZQ>Lo6#TmWLHoca;SFZto< zK0qD@-i|o^yggC<(d|v}FO~sl`wdnC2`D^Ei<)m$JkZW)+0VBFru_n2*>!gfXCY>A z%ngdc<69swD0J)3)K<#;>$?o{laY!#AU&pqZf0d4;fl#?{%n7sfluV>S%Wj01_>BB z|K@|dmXJ~Y{J}*kC`z4XQORk5p}8?w#BZ#Np&dekhs(aBi_DxFBQ)~TFqZh}yXX}# z*^;lYO!Q_U>OG1>@0*)*AS=EF@8Bm=r)1`g1GlWFAEGee2vcyr6(B-q%c(lFM;80C zI;8MbxD^r2-g%Q+vw6wp4qv9m0*?^`0wNy!ANq`LMQxq`41~-i`U8%-e_8xjZSUg` z!Y@C>55HdxUX81zBvq4s39D|McG!CoZAd=6xCJywxY0v{*@;aKbB+8_dnqQ6Z(_ms zPgGQ<(1GdDmt(T^VA&vj-z2u)F-bk8EK`Z#1}4KoupsfB+bUg6>4a-O%lL6UR0 zO{CJbi8arZ=pMrj%zQhR3AgRIVVON!K=j4+?a9LNxI-}C?bACRRC*T?ClGK8D4E-Y zse=wxb`;Q7&Zs$IfBw25dL|?KO1-(o@kYUe=S%Y94=%dzq|Rl29$&r|Jil9LSrx0M zg3r;FEa}&k?234QB(q5k3CWe^#)~E`fKW*b(WEu33DT#MsL>11rqQ!TnVr0J>=lhe zDLsUMpzS@mGW+FP2~FCg!Ko4XX{f7@Ym6>=xPIlx*V4#01s@ywvtIc{Y@c?frJKEc zNh>{`bKHb>YjXD{ojK5WZ;Z=T!YNNsBXCHgN(C9x4-2-gMx5<`Q5Tlh8*uBEvZ6%d znOi8)GNo>l6D5&>OxG(vhVsb=b3d!YHOBxNsh zT-rWLr`u{g=|~L=anws}0oF^(SfT-hmUddv;k87m7#V}29Ek(kWi1(>>~e!L1-%7| zTxxoq^j0?hYA#MDh)*XBM1!@lsiKX4Q6^EW)oHuXv*6m!Dp&1Py5^<^O_OZ;yK&x!dZ9VMZoEujeg@$7GJ zb|7j$S+E!*kn>n>Aswm$_(Aq~N90N(OMuEIyvpKcEw$Cv4uI4l`-RotrYD@=&e z+$1kh^Q6K{c0E#j&$6-CUZQy;g$lBU=3OicA{og%hgzggoMh}Eeb!@MCdx< zER-Q)CxPQQ^!AE~e1C6xU%i3B$H#y7+^AeTZ8H)-J^`!j4t2jBInWoUVa^rrU)Fx_ zbQaB^+wKex)Txr7$Ros5rlIoC?*8SVZIhdt%6}d9KehQ(%)%_G9?DvOW#Dx3DIx)= zIf^BXrbQ8A=v}A{UQONX$+f>-KG*FgO)j24cOf|W? zL%v_CMzvNrC25s%)}Ea&GBlK8)Z8Lb>UOAjAUrW6>-?oyMM}Pe)#;HHdkoNp2XX57 zzVZ5MN#dmI;(pfIw#D{**g7Iw32o|Xi;-h4dGBkfl!bR>$EIR3&vSm2(? z!bQabFxhurdVCpUxb)NTnj|;@I!<5kfe8#?VW6y6UZhUn(=Dal4?h^RKoU|u5>UUk zlB=~>{So24sE#QpRyOLy%s{G)Y0hF3r`0kxeX_iaKb?7ii&U+FEE#EGiD| zL0KgYrzKs!YiVf-ySuydeSUv~>Gb^+*>lo=hn?skN#MRbt})6#XS7v>J!K>fEti(F zNasdn5+d;ufyuR+G_Y*NmH17NzLhP&xLyXTxaH$PH&LW|auTGq%8uVh6;<{)@jk6f zOr}nuI?gmMF=Kwko?nP*10O?wik%rz(JIy*fGn{uOt zfE(vV0LqnPuYne!*DCFgcO>x%dw_*B3|vWWs<^vdy(%j!pKW)VHx_@4N^rLO=o3lK z63c;eQFQGUSG+!y&Ui~XQYI511+}o9aVhWpYKz34CuqKmWCn{TvINe_J4JS2X}Jpc zhVPJdNSh0T{8(`B2KxP{TxhW?G)#CKLyZ_{!DG#Z!y|kcQieg*sl4rMnPs*hkT>eNQkAVU_KH| zi@n3#1+N6eK+pf%{VBKG)tAtPSx-1S0Vm79k%9CLW3rhv;=07d)E7k+s#GQ{6K}Kt zEeZz*&Xd4GNTjx3|Gc^~uMzr3VaD6%GDMp6(NtbZk#PY8vTP-6cW~+4CtXeUC*QMUeVr z|H%MVtVQ9^gZZ01m6H`|5%jn>iQ;&sv%0oJ(aGXt*0DoBjKNFb#PYYz@{y@A;qLg#K&ryD=63f63gsqOR^ z*YmMG)poS^TC$7*KI&U;F2*0`b0!D+x#*4=qmeHu?>SK?-b_0Wo@R-tA9cwF!G$WR z(5C`}Ss>mf3s0jzqEKou2*}^3n^Ob(7{^*HdW!NqTy2eHI`l-UmMS3Gjd;hQ;dIj) zWz%>HC$F`ld=r*%YoTel;)T>k?yB5o)Hn${?GEL%q|nkzIJa1QMd^M~EL{k0 z^3uT6`vU6SqKMgUXv6pTmLW$j#8K(Xj1vhrf5Lcrw+VgXpZ=g5BsuF-cL|RX`nN=% z33dYLdZZ}O-hvdS_br-w6lqCP%LLBN&=OVSm#EMcSy(8u$W|4K8(-*m!|8UcN87W@ zx9bnGGJqsSZ@8SC0 zV*IpA-k22GiW8sl1SR*=uUH2kSeT!Re{U5hw@8YdNEb%TwnTP{jb2gGlz+5|whoX% zIU%N2l15n@9bPykIyf~Orbao%h1Q5Hrxw=qklH*6z85sfh&L~Y z%#sV@m*T8$8A{cK|zzG zgx6u{*XDRr_DF!~Q=<^P<6pmAE7&cF!F7wpSA@9V_$&79{lyI!H(nGaf}>0p=eQIb)ADMB8`UPBLX`NDTn<>bB-E@&pw6>#?67@0dQt=P) zF2QYhkT80VI^%u3erjlG!KdSl<@^3k1vSV=q9%g1W<_&;JGkhRKLHyifVNF zD&ZyHCV_{FP~`Lod4JhQO+L6qqB*(_*XAi*6yow_FqS;*N=-__`HBr@Xu3i?yv4`T zXNTXJ{Wv=F9KMMY0WeT|9%Vca0Uq2`7pG4m@+)?``LoPqnd3>995rs4UkTC@Gi0<0 zGIoD`$Gda1+?`ri=)`&aeS6E8&@V%Aatqey&ZD&TXFpOtC7_lgw~l9Ek%PlB%RK*r z+r|j=oz4^BoE-rLMZ>(lo8J)HK(9)yi)lYj32|Rv!tZUbDcGlRnUUoK@#m~=!3#{l z21W*(iuADd>MzdxAUl<$bNe>1!eK6gbVMN}BoN`cE5=!zHN-ll-y1g1e46DT`%<+s z@jc`d5pNKVCMfX}fRo%aTUsQ$*E4I&%Tu0or6))F{}9`MkYmthz9dVPAy1Xl!7!`Q z9Jd4`$p@AHy0=3Kz2IVNWexvj*9x3nj4XiKbV7?DgO<0fd>QEWak@X(KDQ`tdimKI$7A_qHh=Wxc;C)HMs$Kb*ixhCEEUSW+{b#TGg<%JW1Dv~p){kBo zWAd&6NoY@ttAQxpbC}(mAl2<_{wTTXnP3nrOm~l3rTXOLq!ypQic`WNTpodgZ4_Do z$o+j4TV%#xphg-4z?nm9jTYAcIA!x^Fisxj?#dmKCu5}=UE54U2Sa#pF524umbKW{ zr0?8%_PguiJ^%g&8*xg}J}vo_?^`NzO~@&OO_;ZvfE0}o+Y&3-POR7DGnXW7fPeig zx)^WBi2#98Ul+8Ml%7xsb+PS7f$F)a3vRG5g-1#H4raR~cN@9b(XtS$7KUaYogqBZ zAui}o#y_>rBXyB!S9QwI9Xg>GdDVqqm1lh(b1(qlijeKx9iu@(T0S7i-i`{Rg_WVU z*$};u8O6UzO&muoqX-;H<_S`i@2qb6-`A|{OPa}@L4F&}Bs12=wH!C#{k640WEac8`oJG_Ux5pSR8 zqcPKuFBe_F$^ns6-*P|7Q&kg@n-;J%9K8gSnWOFLq%5;K@wp2Xgy^OAwDC)_*F8BO zjHfz1b%h61ros8i?Kmv_-b^X-RgEVWr^x*xAfJPXeuCR4Zta}Mb%biV%!zHqV>ypo z+n#NX7fypje7%A2GI_ur^U)b|c3EnJI*m*?LgJKLxux3qy9@6Ne}1+q+*X8EVu=t%ggCp`AO6m)B!&?k?-i0d#5GW z=YFwdE6GTy&ne2}i{+NCg}b94HfwaML1`0oD+3W?t~CYo2JQQd8f(3_$aQUbvPHA$ zGAy)tNudAN0@x2K)6Uml+TF_T6Cd>POTs(d9LfvcubKqjWtwgi5~LE4+ZGL}uK8!_ zTStOy&-J#+bY}$RgiDpKyn#qxcHd3W^inoo*J#{0Yt;574%$BkeYjrqd$?wq{#(o| z(NT3%>W$KbgN*L68zI4#uf1yu=TyuGTG0U?oq99;PIfT$APBxn&Z21&bj#l|%Ps zvZ?V!Pdayh)fGGkI+>fllSPr0qQnMPs4RtHm?Ao3iu$yfe=YOQNk)D|?1AV&z8#!u zOm*D0mtNV<*TeWGB~go;IH}9sBZ4UA_(-qQcgo7>$b}BTm-?(;b#x?H97t;E+?RKUFRvnLIR%x91%-EnP?bIFyTfK3QF{J z^rvwqL(zHJj|qi@2C`@_Ciy&S*iP~v(RwW4nJ}9?p@=Fwy85=6A{ymSn?-* z`%H|%8lf0Xdc3NtTkxOaVk%+*chuzMNN4? zFv5n$RmE&DQ$^^q9X1KYX^Qh;0>rVL_l1i?rFCo@i9v{~_^SfT_i2enE~(Oy5XTML z6+7c8o)MoESpnmdTh2Ml*8MZ?wH_s8?C=hG$+(Yiev%=d?TtKBKnLY~{d8kNVpdAQa%F8#6!6O>N)}W-Pec#a^Y@-SFyruK zbiL9g@2H40pRht?&*J*yW_&MQv_5|xFnB#MK(;%Y_xdmpuhd;aYkUa39<9z1-3t~d z{HXF=X~N44Bjs~-DN6@NNn_}cz9VMh&B#8~qg3%d5>OVQSSXTaS80`AQcztnjnmQe zldvWlIv6DL#6?-MTi<}NPw1;gnubVyL6lNlSXmgGqFbgz0U2LP!U>2J(3nU5zL`I9 zQzMnbo8jAc%M82Drl`^1?Io{hqW`8iE%{gJt>zgw(}QZMMzng$*`-8wXrHqL)F)u> z1#=CsuC1EH8#y~;16LuyvI}Gv)nvgcs5k=NNK5X_<4ppb7_|hqr|9W$8;ssAW26~B zk1U^*T^YcJGd(>`)_{~CA`H&1Q>)9GcalmRvcW+~1Mb?5ot@Fz>1igUVg<`cGr4Dv zHm&e4@O}I}Zju7;u-x@L_hNZ|9v8;P`3yJAlq~2%CL0K`sv2YSgxjMgM!I6^+?1X` z14GdS6la{Vo>Go{$3delw=}}AFlD{hx$98m(6)VveFwCe^7KPWfMbk^v5!gyeK2N7 zE2D0oZCbR8>i_A(dd6L^gnA)YG8t=QnWBUFV$!HbN6yEw_k(Tsj_RTosd#N#wDWBc z2~OW${n{#|a4qkubkOB6&t4TbjM+Za{mq&h_fvRKn@+2hr_-ALQ`h@#pgK5_LNa0E z00stFFyOHxX(GWjDx#nV9FzrXm^c}7CTID%{h~%7>xj^}TgZ|%-p!5I;GevE^^uf2 zl2j9QPG{NWF_I7lEYhx3TqZS@6VE|W*T_btA_n-JaW;uSOE6C5OqWYD@Iq55524BR zQCYW7ys?|LpoVX!^;m8hZ(kU!H?cmq%|*~sGT5ShrsKD-(W|TlUTJ{E=3f)T7caCJ zz5uPLcNt#$@1s8O-11NcS&39y3eoiWVwBvCI}aiakt1;6ge4dk1IRg%4Uc#0=mwh( zR{N27UCiXDf&TI+0YDU1y*~@TS;s=U?aP+20{&gg3Ik=DV|;c<$5Y?_9e(@Lq;6p| zTXXtbdDpK-g_)k4KEgp*7hqYEZ#l!IY!c*Z2&}f9pSpNOnj#_u1$`$?*|oH_`+oc& z{wJmYj70#Tt^7tS2l(GA*Tfpn<&_n{cJn_73BG6f z#fR6m!j)(fdtm}O@M!j}g5p}rIVadgKfM6fQ39RPu>+^~CYZ{~{bm<=4xbH?yLt0Z zO?X%(pG;x!_RzqTju1B(TbjB;1eLrp3B%H#t7`#yxe}l@ACNA{>HSz4r)vo7!gn+Z zGJN-SrhmAA-VFHc-#jSQ-~&RMS$i8tYj>nm8czV3-|0n*$@<5(LYWpJ6xR`|f4Fpj zmEMQT`plwN>>vThB9tv#eygjHYjM^$*kY0m0n%UUO-2CFrtkOLj52xb<@q3jGs!b} zzHs3(PhRU`DwQ*$7dwTt4#Hv^%|eIiUXns2{q zzy!F7I$&!8$81`1*}1<~2q?K9%gi+|e9TWNdR=tOGq?NKIK#K>>>)|vUs!Gf;_LSV z-tyZolkXPYSI?8jb>f0CC!;5Pkp%GNege__(o0sz2iAWbVippXZ3-knK@zvEx^%aQ zP;V`y2h2f6P$+?7#Ms@|yVi{vh04gm{kh|h$m@jZ>`Fn29r6Q@wV{iUB~*?wC@x+f z#P!!taEYyi_yu_Y-^VVi?e!rh%C3mGgy$yr&PeC>0QXKh7Ur>{FSj8ab8e-){y&2B zlsdsSr5pD3{&~N1I_AzlGKjiif}f>b&ujkyxuROMcQDlw6NL3+vbmZ}8W_4yg6XZ- zdPk#)6uj=|?*nocZU93^@Rf#!#{ElCW%8wo>cJ>R(O3Q9cuac)*Y?~V`2hVOGERHTD#{BwE_@&5E=@9 zc~d?4d*Sdm<2k>S(^NfHdvPPv#&auSz1cJA)IjJn1V6_v_vPH89-w9k^ga3-ASPK7 zOAZGC{wp(Np*dxCC8rEyhU}Qs6)fS8e&+86P#l#UAk?Wjr*8|-Y4-f=c{`+|Fa@d? z?Tqt9SCeX>gF!c&0@*o8uR)KGKjYpgC$+yQ%waKtpMm3dehhB*7)2;Bh@=>%GU(8~ z+a$EpUUkx`+&(!?_=*fs9&kYZc^ey(0P3HdME&;{tgUGS;aWgcz6IE_LXAEU3cqBh zQoLmAgd*QUnp7Ujw6y4jt0d58D-n%{3=iC=LXhc2p*KF}Z}k!Cb7>Lk(d3qV=hsBm zA_$kHGSkx&o^AVu+j<-}TWFz;bVSO?_T1A3RW^t-eC|L<>Pn5?Kqv}9T~ib1V-_9+ z5-J16k?rD%9sO2DD$wz4!5$=GVW4&u3T}1N7EBTf7rL3`&@wO>0n*H5^Y3*@quJg$ zDhU#Ox5{kB^$O>LCaj{qb#Zx9pIYFzY;sx z%-Uq190)5c#AU^qt-sBNIX|NyABPq5}Bclw+Q`}>sR2kiEnU6Bn} z-{?|hv~+b*f4urV2w#3VAa;JW`#kkk`6y@92kK>6>{#+EN|d`G>`z35DC2YG68+)P z5ndHuI2G=g1n*i-ypb&=S81&T^!n`_@G*g#b%xH*t2Cb7?iYsNpLMt&D+F3NSJ$s2 z%Z?G67oPu~eir_hkqT6O>`bO}O!}2|5%&dOq@jiFbo+&0%)rZ`Ff$iEXVi3bPZK~* z9~VSkRI6%h_Yg!L17`u;Hx(24Mp;-5Nu)sqS;!yCHYWm7J^>WMk-j2}@CTle-_vy% zH6(3_PWpG>qT>p+#mNv1H*eP^ zjWj1Rx3I8K5;xV#+bM?*inl_6glgMTVYX14mR}ODqr7r+VTu zuKO-k@x- z;uIs^7tP-61=!`Uw#YZwag9ls*-XH4OZ~;A8nleVZriFNXIraXD)h?1s9V61F9SEv zcF0q+y+6q3v{$x!xPry*d3zl>Xk;=c4-%91{z5QjD@B=tNEAm?^CV3aXO`a~U$Z$v zmlK`tmWc@M_KNKNW>&1;=c6){`M~`jwT+?nB&cZ!*%=iK@f1^4S{K9ue{6W@c>Z{v z8C&8KX9lG+S1YV3%QmDYF#$O^hx@vpEi+{ada7i`4iNL>`Xm~5`?CDfOM%rcg$?6> zqN{16){odNkRK?E0=GOv+AqyQC`rJP3%FZo{@i~yfXXivn8#yD5qjG%TAx8HB5N<1 zpZ58W>1&Ye=*uK*0W#F^4s!eGaoK(Z>}N{iIov@}qN8x65|IO#qR|hSyEYj*x~$1! zEcBoWb)#rUG*tJSMD3A}YHEdof0U8Lxnk#4?@t|EGt`N5&IuY<>W;glD92L*Vz8jAe?P%!h& z!{^VRN6o!$mj2F`sI-;?_-@G(@;3pe_Y)2QLaW><_6l49E11|s4NHo>EQU_8g6;#j zcnG`i>rJLuNFANV=z7x3QGIJ`xE%GKoI%<1ag@>^s0K?P=DBN-=%I{OiUjWBVTiy0 z%$$aTmj$lzq+Y<4SflXLGcr1R+MRb}MuxJCmwob7qao)czqHQZ0DSCH)T zj_ltliHh7L56n^IGzwV>>v3lO#9)48Q&rduUVr7tR%T*JM(99~$(`Hk>jxftLo+i7 ze?Q&0{pJji7dU_YE8KPwZwQ5{X1l?T+R2kxZ5e7Id_!1OUA+@Zpg(K2`7JoYYU}It zJ^Gs)gErzUu^H}y7Y%hM&iKX=@ND=b+Fnv}qRHEDVlmQMCgAPck625HhbEYJ6hW0T zEU*{AyDela|F?po{Hbgy&zr@wx6N_78fT(ft_BAl1B+!1IJ;OB8hx97$A^~^XDx&9^o_N5t_nUNh>lK5v9W#9RM^+OWYT2I_81cJgEdTWSVTiD!ud=5Es`#5F< zg8{hlruWYQOR=4aGv2WELtJ8bD`g;VhRrm?U(&duS=FJY*`is3FB>CaAxw(AYiVy~ zcI5rB_@_Fhil`61eDA9(qn7{v$X+NV#~;b3T0Lg08iA`&Is!7316!jvM}L+Y1-nE{ zOQ!t9cD6-cQUrlJ^fJY|O6sH+4o_oip;T4dqtsqU4_hx6rD_2Z}Cu zu06+qdxD-G38FmvT{<^6cU?yZ(PQ@LBLqpF-h_xV&FIe67N_~r7K{eJM)pi-=8H-Q z_$z?r?_sXI~oCt{vdGA6MM*qB~^~HVD_LWk<;B980JGw zgD04~=9lv2v-A*KczWXZyN)(k<+hj{2$5x}eE6u1KzD2WTJV5~4!t*w`1@s_r66+0 zvrC_$aL$&zHDPBf!b41;ni@M<^0yzO=d4%3`tC0KUkUOH)Io;qI9~*GzZyj5DTFT| zr$*f?=rmQzm69aqI{OMjGYVQvKq@UqR^I9NSkOI}9h6BSbK(}IgWHBRQ8 zk(K0utjchk6DypUvg7HENWBXydj|)0L@LpV2Bk}}_I`}C2MJ49-+BEcAg4+Cr$JzD zYl-0UX(6g^gg4lrUT#dR*xp-S^9u25_pjPN%<}9k_-`;=(u}qNkew;QEU9YovrE4* z3p1?kz5#}FAYLSJ))ffHy^JWyLzn}`RRHN|MuG03ze_psRQ zw>azpd2-{CZtn+2fa29{b2I`w?&1Z>-7#FU_$!GS)lR<-U;E&Nokpv2k9cZXI(v4< zL?SUqlM(N0%;f#N5>ea2YOam;GC)riD$rw&<0XVO%8EuP=ntZ%X`XT-v`&+?-EC5> zu*Z3GLZ=W;ow$(OWuH8VM3%@~C22YkoFQHUpW$0Z`cbdHL!R;NVSJT64pjvYEcQ*G zUh4_WkIIY+C~oGhCk%VLHshZotjRzAg#}2(qvDa{u-m}CV1+6YdIBq?R(W~@$b0G< z8Vp9`fghpbjJ%yY)KwNq$aE*ZjuP$ID*7tAM0ivH3!)eMWcuOjYB4NH0c>jH-@JO@ z8mh}|0Y#nDFm0)UHHA68JM`Z;KYl(dRT_wpi~g> zsMTaH9{c^KP-yeXo_%?nAWa)uedYJiX^JIpf=){>Y`yV%QTBq;G8JR(tlkUrV_B2e z7J8-4s%8)hC)O)fuQjx&HZJ3v^E^d_o&477j~45pN$FqnKan`DiF6d8&|@D&Qr<`~ zHVkVf7fXy(ElLm%41f0Xu`A`KPCWnD=LZU4@rXzK{=u}o>o0@3ljdCXA}?{ zGA5P+;DW^Y^$VL@&KY>E4Ak|LzZa0CcNr^vYn0oMy#tu-*hM>Rav4-?yr}*-wv9Lk zECiDj)n}tfKWFLvUn(b&mVdS#3yFFuBgALx&12}m` zQux@$g6iN65)t#AkR7FOX*7c&5;o@YM9Qf+f^XPJ$DHJrRI*3WLXf0>}MPto$?bD+}&v_=byLaosY#wh|L+~#Wi)wZKN$>$55J7gAs{OF^<1q|ly6Y7H@wRpywf3! z4GW0qYr8~@#tost&vuJ}iCF1S$!wQAY@)sY zSjVR++FUsfXpq8I>L7s9%4M+mHEiL?)2>a9eypaDCtZPpLqH(HIcjephK4hB!puHj zdXdf(cypVEgZjcCIXfNli((6+{@*#T%{hS~1Kv^g1wR3<3H@FO9>lapYubCW#ZJQQ zXOl5_3FB4~vp zH4Rdh--iCN=$SL^8T-id_hP9q7l^Zb{ZOWNcn}WRphd#KoKW6SV5ge&)e? zKh4*Gm9_cz2Ai69tmnHCNK6VZy#=B#!#c;3>PEu-(WuSY4z)jY zPXKj}z*1}PPr0Hm@{HgOs`jbi&hM`EzaREEyV8x`wGlf}7-lM|;lT5cFqP#bP2a1% z#Nc#YN+A4tamx1+N+*l6$Ie@@2C2riaWf)Xvk3*C1mZ>#pb>TSqk_P~_H_K%I7VE1p2BKpA(OlJv z^7v8lgTsxeGT3td<@<&$CxTe=6oMroO$LG3DD>a*#pF4=;y8_v(XoBoPvN z7r+-zR)K9Jo$ya&P5RtxP(ya)SxV&~SJG%a6I3wY%GWoWj+!(*0nbE8ywN{02hV!r!TwZ;YZs_coY58D68Z`0n7^fa);KHn;! zgRx<1HaU626e+IOZj>&44qNegR>B@^+y=g%v&*1^84ke&6QO)Oaj80;VaXeoy`?j(#+Y+DB=P?|BBu+=)x{By8Un!}O7g(7;YXd6~DB}OP0T4g@sweF}f#6zuoPeCzxEd#!vQzFMHeXVh$w^c3UK?&A z36&!>oZEzHY|nnuQ%wzxrqXE?Yi|n+1eZ9V9gFosEy?Ztn+He6TlFK7T3!h>#ioEV zCEP=}1wzQDgQ~d3Pkq5C1zLczD-wq$rqu>{1yVrfTIHR5#Ikv%brfFKb9$_(i(gQH2kNk>zwg|^g$zuv1s1!?;OCtfhKY36$VRel4@^%qzwNQcAe#RzZ2 zK#!CRbX4_N8DVY}Kim{buKc>6{yM~V)37wzTibe%2N`k9gP%R&lkQ1$atdOoQs#{F+J&} z3_T0Xc`uJbEIH1>kw?$T%Zw z+|r)dslzbgztA?%jP;b2Mz~ z2qimHUP(*wKj^CSFsb(07tnKnp>99n(8+E#mqiz@A)^0we*>z zYQ7WgX}!4~Fofbbp#S8;h~w87q+TXPEI+`xJqDOK?1`nJ>k^x6)Wy+czP+lmQ_l5_ z$f=aOy8)VK9@l34!T=RcmcW;|32J5A>D2LP#+FM}FhnKQT??wJYaut)d2#aw<*Qv9 zi^1^xJhmn{8C{pOl`W}lzwnkq^||~?G2?H)8K(^T()YN`+UU_`gav}qH%j%%Jo5wK zY|`cS_3u6&=)d8IaFt;DB&km&^Kv8MI)7fDSM{`4tc-srAG$L6t-giOW1 zqs2pUL**{X1cXb6bax}5q)4Z9NnGjf2I*(>{XPFN?i zg)uy#3tgH1@@cR-;6jk2NpWNY>9Ak_4iD)NJh?xz`tIL)N~RR?56k=#cjKkj{t3&D z^1*yAhuoS20BdpsK3ksT5pJR=%I6h&)i&Z(9imm;N_y6hCll9oN7cxWMP@lV&XMdh z4#I+13JM6-3TO7sPy&kboaOtJj{lSM{K7dD!BjEX1ggb6)YA+OuqylNlF4fcxGdHy zOVzKN&1#@2#cXp9)PUR~G3t@Nn6OzEKfXKPrgyVVgKYy$VF$UJqr@WVW4XUtRqL%6 zLL!tZVI=R0$ebK41^f4er?ASTM5U^|_66CTVWuiX5IAuEAVk+Y(!Q4Q{mF%LCX4n( zas>t4W=;9zWT|ZG_N;H56)d=r=wGl zTM`jYUJ(wtdVZrK#!0pgyZn#m>4Q!VT6-nFa}4-4Ra$oC#)5K58Qdtz;198NvP?9I zf)qEdj^rsZzF(1irN9XlfPJyz24|3FaXGb2bmv0lQ|f z=aZ7btIG4$L#*>YVY>k2#{?tY_PxNGF3UL0XBbyQykC`Ui6d!nbqJW-(L!w<-&@C2 zjq)H|$jKPGa*KH1FC2v|Fc_w5-)26fPSyi8G{b!v9elD%vL-P>gc142$(v{6JlVbH z90TpET3eKl4I$~~t7xx-cujA3p_-dl?)mNq;idY^W-VA}q(x_O=rjnCGx^eK-__dW7 zy>Yp2#|KMAD>6=(RAC2}NC|b8nbH_d)`SQ&MOEyPYE}NP68Jdm8{b0J+iL^pH@Rl` zLOMjp{X?8&yDUE9eNz?(B_9N}D)LE2jnW!*VophcE z8!aSRR0&pFW9pZrYnb^Rg*D;Ruv5h8$vMJqrDjU611w;0xV!PNxHd&#BkGE+yi^dr z(25h7aTZ3Y;?#kgVg~lR9vbWGhkOM0^<=ZdlgxXa59WAPgJ%L1#%S-d+a9^l)On(U z9l;Z>%W4LSDvhF=)|f_+Lq7ptwfDk;PXmveHh0WK7rt4UKpKnbwRS!)8c-62=8Zpj zE?yOd>wPl1^;afeM=Jk=RD+rX`2Cy%KV=6HtQ1zZvUcUqj-<|%j3fwHL4l#VB-RMI z^7l^}2FQQX?y>wi9F6pMs!EJ?FdWk4>WBTvG=u^k2_U~b@u4nPO_o)!-evX?wg)mG zuz}MZ zR{;;oJMeQ*p(!;@IUhLTAL>PU>_yJDl&|PIv(|g-Rr}}{ilF6eG#QX({t04l|5H zQ->!JvP)NvAmDVn^rl>^R@TX3$jPL2Nwv;+0aY(|z~hhNRrbxX!M@FCvQ>xuY<3Qu zg;r!Wxb4n60a+CJ&y#8S($AN9^H-QTE~%Ui^V;JM;g-msG=4I_;_l;@GlhG;rXWhW z;YlengbN$GYOoM)eKl!}#tl`-J?7;YZuY2E$2}_wtgUp2cF8Etl6;1-6UGE_%3mIF zZF_$Zs)9poyUQ7~$yH?0Z6~Z}7P`pB>C^R9-9a0ZO zb?pT<>&nGNDi0mQq#9pfySW=q6|L&xJa%%x+{A2*R^b5C>liPQQBhLijPt?VgTR@2 zz{-`1E6|AAy&gx#AW!vw?OQ5Bku68JAqg5;bc{XZYUXBHT*41nqK~|R+>B&IG1(ck zrZaCCxk{bgw;qtstW%>d^&*DQxJbpvDs?L6BOc+#pY`^tOqSju81_b_Gx45Uw&my5*joWp1YH#%4O8mtF*=`i^6*-y~3@??#+a!$knZ2YbitD?NV>E{*_xmZNlE_XLxQGi~AH% z-EPY0AgZs{9b0;|AWC;0a*m~DD*rA*e#F)G_)qd0dJyc8hmQR!3$Z#}jY#pCMG5AyK?WE5ZgA7j`IGmKtu35zqsF zFo#V}PWoi33(=0cb*zCTTS# zDj1@?>34!%RO3E5m3H8c0Uc}|FICB{J(jL(D&^yub9YOIpqj$Re|VHvQ*h3&`4+tK z#csEhK{6xi=eWq`!?Ycb4My_?hHvzod)rL~sqOhrAaz|`)wt!tt0fqdm~C-G>|P*o zgf2i{UneD(gQLwJ1#9GOwk9y7aes#T?ZCb-sY6RQPPURYSzW3SH!0$ety{*wjrDO{Q zCt=ITEvZ%auRX7Yd^V`z<0&V}Jjp5Cyi{i&*mF!-SToP%1-E-lvq!}=gIg&sbHnrF zJeyS<1-mk35rC!F>M3aTHva~C-p728_2w8p3W|4yK~5MfL;lzMdrOi-Cv7~<$2Ke^ zq_PA&Pd7tGR<9)g0D7%@MsHgtaqpSL+Ma=4a0DAP?VX{L=v0>T=c=@dj_cIa++X`3 zExid*b(M9}l(pRy8HcZfk{E=61mXy=?T=UcMhLc-ujNIWJB|FhJ1bsKEKxg^wFpH zN_lD`ZGAWcvoK_Pf$7|Csg1L*Z@TL6+VbN*T^bA;|Ev${=srAu}>Mt2wQ2qTvvLlWRx^|gZa;-Ig ze-RW-eaI{Qy!z_s?)u=Z6ko%bnWjUZ?@X=9@YBXC2K7|tZQ+;4x&(I3mkhqgahXV; zU_gF}*~yByCXDgINUm8rKC(sdY9MlIRnOND3wOK;2?>WcC&MdiiTWDznR^bDCpbAQ zn>d&fe{xdD-P?o++C5LJq1f!BsdrTc3&Y|i4NM$C_Bz!9;^LCobDrhTcCqru;%4Th zLZ*sUP!g5SK8%Y55y$6ZVKTq=_r0Y{7Icm!&hBkg%&CX8%139=lRoaNQGXb4n_5_h zP#1wcI3<10Ge%&=FnbU~vvms<=`0QvhSlFy7LQl8Biz)PpNZ(WeXcTyu$XoOD{7OH zlQ}Xpg4Y%a_c{*U7@`;n&3?X&^wQJT5z~BxedTa{Zu8($8}r3*=sn|j^fyhPqP8fc zSGYGs_!U@q`I-m2iCymDRRa3Mzu%h8pOw9r@v~cU6(ku$f2W|&5)YeA99HB8GspHa z%-4%tuEza45xaMK@Nga6?H@=4F-$uA5tPxq_A^fV!gt+|)SnY5@1^v|a?HPf_HD>8 z?60KJPK4J}wVO$+HF4*0w7{tvrJwN5iP8D{I?ti)8S<3~!R1Sw(0Pm`?BY#!O7hTC zg96#_9(dHSZ?w6N44;&8BTbZc2ffH9QbJu)=?YI(|IBi~v&3BRibj7wP!Bd4Bk zpX`y@HF4Nidws?yWVvAcI;E-Vyr2m`ZHu>x*qIW+MPzs%%XwcT7Pa!0ysXZhY=|`n^py(ezma@?Tl*=x4~qe;}&6g1?M) zije@T703{#^f^_XeU52#^`hz*rL#mb-gsx)KlJbF=fY-2wzoFkhiy;Y0V!Vzu!XmY zY)kDym;nb+NT79DUnTeo_e?6}U@A@aM%QwZ1NldBhY#ivqrnVqm)di}1jXgfSmM&&T&%)8)DtKZnnW zuMAu#TYSFixlZ1A@j?keAiPN0)szxFymKbIJ1m=#=iCzpm4 zQwEUhP237HAwQ;GNCdLJH#ppTy1Ty|)(ZZaaaU@uTKgKmC6n|C?@L5;5L_41Vs^WK zb+%LQdn?GMQ~${E<3e8L+%LXEMEQEJ+tyaGUSQn1==ur$7R>#jYbaUH+0i(>pvBd3 zIKst%et)=UpB#CZ(W!+UCsP|K08UT`V?5$>t44LBB1dcK!yWQjMb8eSP=^;0h77Kb zA{dJPP&D+E6_&wQSXWz%>XS{k8=+G&izY~=CZ)F6H%oc?rAmpZXXa1p!d=~#o2#oz zxkgoe{fqZ+AIP>eVYWyM8i`)iKhXMe5U+O6UD) zTpbl2hPUG+xZbx{F5thViTZfb{f3+74ww~0TWFgMNS&8M-fWSJO+{uK!f46;F5LWx zhefYnRp|cw(sF;@k{J3iwrkZv=;MIsv#YwMB8Ghe&srb538Sd|GSwVKDPu=97=qJ& zaCYVrhactDs}yCd_>2q*PM*FN|4yT0l-!^of#S=>3ItR@^Gi^9+l#(DS@n0nuqdKb zN8dci&&kP)>`&Cnle09;CTzy)T`g+_=Z0V#^RY~%TEO5|z|-9D6RyrxxaqdrQHog2 zA0w0DNnQcq8jiPp4%0oZ}Bg zkx|7h1)c?v6KcP=EzvFTdnFKn;(v56`rd71>?G-p^E#*!tjPH=dU_}AKP|=5_?ff8 zLDu6rarrfPXX+a`1Lw))^)G*G_U;HA zdj&(~RMigfHAU!&1<=l zn?qlsuN8ybbGG)4LM@8oEh~G4Z0_T8@M)3><@CUEf5SrbgMYt$3nh}$a}Zw)9ob-4 z$CZG(e4yc09R+}fk5~_cEC)I>cV$}H&G(;5(tqwG;C${j`op7SDgiuPV>>%L6~;XP zFZ~;|^X*_Q2s!OY7|(DlpZ3gVk~Pnr)%@$e3}-}TJ^`;}H$CUf8|TRG91YHX$kMhiUs-jS@(Kle3!s5l=G7;Xm zIO1Oq;7@=HORbt#^lz5;$| zJg2}m{~w?5qFw!SPpa;^<}=oZqWgia7Q5*Xi+;e?%#FLvyB;mX$`~_>UHKQ;lr+nv z8!uIhLPqRTY&Xfx|6Hn1B$q6YoY%bj7QdG3hhkm_un)#q^nvyD06vI4r`PQY(YQCl zaY?I$hvAX2An@4PYnzdzV1ooB=LkeoUCfJd@wtM5veC=KKXL|h1xz}4EA%@f9t!zt z+%BmE>lOb)#cU-}R*D$7fMp5T9G+Q{+1T20`q^>WH4JoQ0TD9QVofXah(BJT!#FM^ zj>%GJTlA?EDx9Ap*OxfHS`KCOhjCeR<)5Tpoh_XJ;K+>2K@SqC4Wc3gqbje+h@x3V z!7EG8a2HC(#xcnhJ*#S)>e?{8ZWo*%`Xv4tJkP67IA00+oR#Wh5v1Sj{ZqvaE}Dw# zZ8kxnn73*ibmHUzXY62N%Z=&HOy(^Ku+JY6`yCPg>r?ivKH#g~KxJ&e$QEoe?nZ$u z_n=?y-5lsh+n$AgfW=v4_nGQfN+TFhu{x)>?85v{1evO(+J+viIuoP43-qz*d1lqK zX?GEVGJE;azK&BiobUn{Ny;`t`qxZ?w^F`Tgz@9WlQ9Ew>y>=oRM#qFm zp|s)Kdf=ps)Oq|_OHYUL=H7ZX`()u!+r5g%srkW&;-Av$Baf+H(vwd^-xWH=cf4D;aj49_A7Df+!tQiRY;Y5k7Dh8R3JU*QB@*36m z?=+2Y!g~?F;^;4a&%77?rjvq0FEHu+N9?B)yZ5i$ncG69+UbY*%1HrjQ9%4UZas`B zh9<86+1TcwMH6o)VJInXM(+yzH6X0lDm@J_roC};&8NPMx3>6YTxt;NS$7BxmGN~d z;;coV(!NCXSlHX$MS5evBJzHD8@5&>XCm}2xPI`;f*0i(%kiZ!D2rZ;i5;ZbP_nG- z$m=_!iSeR{&hzF%}RQJx9TQ|AOn?k01}1HkdH@b?$s?VQZp_X>PD*qr_+by3I3lUQ@k^ zNN7Gx)`N|=NI`kJve*X>Y{Yf&n6u3zeT7$ohx;KLy77<;+|$l44dN(K8?XeUqRjth ze_Wf~|K=w^=w0@>ZT6h`?>eeh`}^~m-yZ2Yy@N}xF6KH-X4+HV(#3b!0^4r1@wlMY zg!KAMOaG2zMh+1F1*nX$onuT}rEB`T5Pylel6!PwSZ*7qgtDHi$M#sJV=9JCtxxav zr*orbsfAnhm+`Ife=bY9SxO5T#FG;k_}M+rD63&og<$hKBwjvStr#dksqNgQff4=P z-Kc;!tE#EVud(s_30gt_t=Su1=|Qj%=KCRn#n|k{*K3T97AivRfb*`CWF^N2a?m*> z-5!&(h@Wg`J3WVnI1=<#aK!uc8nnanB}b~)yvg>%i0A%9sHp!R3$U6$nY&6YM6Byf z9VRgsoMpxO1dU(6HiZ zvnzULF~CsrgDMsY$^G_hDj$VmzSerV+Q#@fb!_4<;N*TH!=tJvtvKa7246!$<1$j$ zK|y_^mG*n%Ex+$gZ-5O=tq%^!UWoe+B12GHuuFCb;w@RX`FxHq@gk{&Ag>BeecvwX zXy9T>ZAj*nduIo(L}~3aW{FJBJ_LarB-CJNUyo1|@R5p)GKz48dB#^|z!B%21*ZeA zwh1Lv$4yoop-ZfVb4tbiE1}`AgYvNVQgk zjmWIn41UcKruhoJnh?jyR(&YGHwk&vsq?#^rE`e*LCd|UQl{wOoYD(Oiz!90VLJ;Z z8Sa}7v5Z? zoXsJC>G|EB#SAx}*L+**jv#B#!N(R1qMjOC?tYJ^Zev%U`GA-|7~Vi{2kMXmZMzDm z=x;K{{P0Gf2t$SfP_O;{S9$=qS#=bn7?!7-@NIRwF^cO(qft{3)IWLyd#{z$vG*Za zc)Mf{BT{4g??IMcX^aflCCRB>^McqT(g>o0G3Goj+(;j7lyclYm*z_TU_=DxeIr+s zk_^tKu}@vNG?y@;)=#ze)6o@f*C#Yy^XTx9vdNv^K~v8i4|he&jHnOgk$rwZie~grDlnsQKOL0;O$WbhX%9qU@fq3FYwh>9;}P&)#^l@Z?0g+It1#Of=?U@e z(ANZvJ+?1$p6jRLvIx8OVtf#!Soqd_wcXnyGHUV9X~qEy|GjgjpHz1yr(!m`P8IDl zWfSC2;JI^ky-kGF>QGH_B#ip>o4-Lx2G!iJB8Eg4c$PyYD~?A<#UtdObF#S`Vtn0Q zm$R9b(z#M`@=*awKiN5hLR19Je|$(vAyOtJCOunmFX6#$f(1z9iipAjzxt8|6p@df z*|>}5Y|eb6N!RX_8n$x7p+TJ{Ni3={Xe|h85cvB?MZd?mPOr_x)AH~D4o9cM3x0aP zAUx3twM6cN#wu8YC`L-SCFw_7!{=)V<0?6ngpRw-QN0Pf=#jkdbJQj|7AEg?bXJw} z86gQsjxqSWX%~%Zi(MkD8AE8?Vr4v3>z@z^M3{4Qv2-z<+AB@QP!L&Onjp_!T9xX$ zmfWP|c6xfc6->)7eLzCWbchBQ2P5y8jM{mai{9&GBKBRO_e(wTXhlT}AO#El7CclI z(aS#NIAaK)0(QN~K^DrkYM?D6yM?a{RF{gqDG zKB~RMzME5y(_ARep8HCWOt9Xuv*0Yq`YzF2p8!3q9xb9Zr1dopSuv1w1zew>(W*&o z^FH`bggsqXFOYTzsLT*_XK{4%MFzE{-=C+K*NJ(zYy8qdg+fwM4nqy~whOHgJM%rO z6R@n6oWI2ecOy+iLSKRkK$woexWwrrGt+!G-Li+4nT75;+)+3+ob-5QW_{9z^iF}n zQkD@CBW7qZ0JF*8EtQ{$-o0bSB_!?$glL>5%D|`|te@kB%DE~`ha|()CD><B@qP z3VAP0mK;yV#T`DVo~{5zsJ&RdFmM}{lAucI>C>)c7W^*S?V`F-{ZVs9+-#$NLZQa1 zlbZSzAxir9S5sA0Rk$QuP(mLwOIz#wpWi*oRO@_}+Mj@FB{J1zuMF5bdDxE0E*qxs zl-VZz?Z!CAjSjuM=C|-o=CqZIlNKiuH{YYoHvL9C0jPiPwCZ1_(D3w5{-3xrc`5Dk z6Ui))Ci|PAFtDGpWSC}Vn6vG1<7-Ld&N;CtN$lDckW&<|#zr@p!ej!b{7D23AYGG= zMaB#P*?A*CT17A}K{eK?E7-rNLs7J%s3U=6v@+cvf@Zq|KPWe4`K{hcwI?7k63* zr`;W>C^26H1)~zPc)?i09_Zo&!^6gAX2IG_M(7{D7T_Sf zpjGKgXTanCrzEU<%hixjoZelKTMzBZth90OWYa|1dmXa|2G`yF>@C7L=^*n-1gZ7q zx2Bwl44{%qO!}!8g}krbz3XHY^$#Ov2Z27>Dol%)8<{=8cqOx2Y`q`gln8&hW)Rsl8`zXKSCLeR;Pfi%-Ag`qAZL2>#~< z8nuuwz<^{#c{c~H^hBZ*ju{IilF_Uz%Sf4rSBh_4AVa0?8`AW@wlz;UH8*TeY|E}| zjIbT&yOXv_&`kiq)SNEI=m!H3@m}JfR~mAsh*U9)2!XFY)H3yn@gB%Dr&DLnQ;UmD z2whRmdA7~D)6-cLKnn2Yt9&!#<~t@kTw96dESh`V$I|tANkwn`h7&Hs;)1z zJDG1S8=cHF_luT9Vx3|Q>8tLYH{9}JHJPui3$JrRy<=yll2m#5_#6NXW?R)~YAvMc zp;9v%zxjBkh<@h4`Ai%31}7piCzSjclKudMAhm+*h2V&Y2;5PN7w>U<>0_i!c40Yr z)-;w2mnRz!Lp1Pb1s~4hY>m}W-ft%hogQJjBwwgnNLKQ_QHuutlL9-BcijR*?HYb* z_}8N09SuWmFsm9*iiS%CW&3DZ9^#P1D9*CXy9Q32N4V2s-QMm-rC8hCGer1MEAlE|cDxt}=rRcj4WZJ}6Gj&E3a4}Tbp5t@^;`=C5b0+ZGujQ9v}1{)Q`qDh6`TxbqfpzeyZ>ib?$IP`3>dU zdNcXn!bypVqMX5M+Cyd54x}^E>cBBRu&^s{zR**NEKs|s8*jsL@-}wg# z&QTn=0<*k!@72T03fh}+D95j(ZnE}k+^S*Iqh3=)cW*9FP{ua>JHzWscD;Qmo?Ed6 zb#4esTpgxrq6C&pMg3^>6;5Tc^ssmv6V4FdZLs>Fl=Km_X6niQf6;}jw5d>dQj|~e zDSuG;hhLF86;x6Z^zHDFoRXclS*&Xf7j>9-wJw+uml9&tHXn)3ew*K0y7>ict@NnI z!maV>OES|=%5{Y?tHzVe86nF>X<<*Mbis)niG$(uEY)r2XOe=lk)@^Qy<0j9Wmm2{ zrX4fSL4Gf0s3mf@ORDtY9LfnlKd^%XE$mTiQtxt4JU0x?jN4zwAV+C##*wh&a=hiW z?4=V_Til{9!A62eR(`{7q{dIqL z&F`{3(M<4-K-F2iKDII3C{yrCf`n(e`X4P>9~~J5eOP#JHXcnU;wgLAyt=Z;6Qp_& zV@5qV4-O9U29bA-Lh|Br1o0d-7H$MlBInZ~tzb`i!ozU~_zhHe ze2_BNR{a^uuVVE8ta3FHM{k7@US`P$cX zl1bkY(9n09=eeOEvezmH#|0W^PW6R0MR;ioq(GvA2aIHpdD!`xb1pq(1PYgjs%wEc zgs9)0@Pn{%dFcUW^AB1k(jnM!%W0!h(-*%Y5>g*_Z2atvhukF7`Gf7yT{2rEuE^#o zG|#Enhoh=5PjbS9;A;!TsPA()lU@X*+SyWdZ&@5MD?m5Z5@S<>npO@4p__p4#1p`I zw=ry=NB#1NPN9YjXWeI46&8{4orwk4H$StNlS8S0JIo)>>Lz7&*!=Egz_lKFdL^-- zfI66e}iXS@UpkHE3VhOdloA(Cc!fgv~!&hgiuY3u1pv&56)ra)C4 zY8&v-*XnX%EI`G2#Ai1@k%AnBu}$Ev>Qv%24^zYYy`M>{F@f{ah?(UI&R8=Kc*BR( zY%}*(Uy;x29RUx4rfv+lBFabnG1diZ`-pTQYJtnck`cu<(>OL}s05)i_OIP`Uc_pZ7$|Lt@S|@ZhV9{?{5CL`n?GvIkBc4$0SbYn~)BH^tDN!0P`Els|rl3%TuU5qrBw7h}=I zRoIxBF;?5gJ#X)%{!~Hql?^&}{BVAt42rah72FL!x}0zl1SK@+np?pmN2-0Xs)mwC z^}C2h8&{T>9Oj_F$k^_6@GJO%7L%^h3RfT|`C{dh^JXgbyzC@nsMdLZ*aVsq-b<^E z8Hy1@s`yo61e_w=)8}=*J9S7%3peY0VD&9(&s8OVSHP}&SN49KJaW>l^z9*Ip`CL2}EAdfv zZyHOLR-Q<<7*LNCO=nNe#zqC)m`25oF?E<_)EWb}B@ZopcC#UpSjq$ICF%j4w%!@pnCw48jwdYQ; zZ#N!`u_1W7DK!PuC*B$^C5(nyhC(NJ6YbWdtaCSmhdd~%*&Wt!m*W!3LkN;5+}_kn zYUeY^{W|E>2)Ez*ks_-=DOJdvD2?_h;c`(vY$FxhE>*=EGa_)06L{Y9d6lC__|uSw z7>9nmq*tI4vhC*0fmwm?U>tRa*I%`c8AFk0IJQ_W3o~zgylBeGye`#Jh#)EIbobSE zes&eMAT|#9%W_xDvpG@*1_qFkI=VNnIje8ULjP65PNxnYrN9sX_8Yy;A9A8UqrfC= zYrED3)IR9iKq#n1(=f}{zDXeN95Sxy1mU+$)6bQzxoX2fpk%pLLXClWmT_QJGrw9M zkOo$#U={Lh(XCEtA4>W5$ilNT7jJ;qbdHUUy@Az8=>+CbGo_dC4s{WnBkW&=LGLz+ zVokCme;CeO15gJWnh%Z`87d!w{{H@l=Pi0YGaLyOxZBojS>8j|L_iRMdp(^35X&^N zyQ8R;7#Yg8<>lo!I>??DM@_SDpAyc<3elo8H3_UEEgrKbh?T(c#z#dsUYOzUMp=i( zjW4Jg_B$D2s|^-Q6Y?jhv2n9f=4M7ni={|vh6==Rs1bTg%#uz39uBMck5=&p-nhl3 zkG9szgVhZuuNg!-!Z{N9OxPP4MP|aNLE(|a@B9L3#JcX2t9okXS`2%<{SBJ-rOmsD?ot1cH+hgq)i&BU#bu0f61c;69%Gm9SmJ#mfveMA3R*xA zWi7eYJLWKeu>YZY@!%ydR7zLFOEu|fbEz6yPrZcMAR^g7mPRb0uQhqt#E{##6VEGA zV47P3*51>_pJM+4#9HU)=R=TOHipt$N$q&0&`Lt+TYgbpPxpYTg%7U=1qo0Aph$Tj zH4Xu?9XB&@lD^%%(k;H-pY(#-L8zT#GB32hPM#r%)iN{lKvmX`^cT}I-r6HHfn-y) z!6yza?iwFSdr^_eUvA5wAaa-jd`>D-)P~wbuhd&>`n6lL zzZ0?I8JLUq?(jMcacTYxECx}@a^T%=rHtlJYwhe@n!jhn6M6dn-VOc{In+T>XQJP9 zu^0E%z~E9XPY`Q}e$)d+LE%RPJUalo{{1iD+AfD%22u)LM5IhBkJ8;EFsUdU8noQ&k^KZUUFuJI{Cp~Rh zqPQD!OqI5ALoS7q*=y5g%_{9j#<3?#{-OL`G`8-ym^td-Xp^-)RO;knPMwL)KA7GU z2NwT9#dTu=9|*K8-T6yQXlzn(F*n0=MPYjkl&`7&(qvpEA895Io2Nx84n|Ff>ec2mog`m zwdP_69;|}C+s#UlJ_eVMUX-E>$}FQO*w_M7>w1S3RFJLmka2>9^dNLJH3@GXfd2gG zVa)>)s>Rxu+-%|0TUFJ@>*LWVUuT0A+9+XUq=)+!d^ECoc%N`px6<9_(SIn@t!3{K z=b6|qk>h*;OpF6T{9Cq-B`dlTIl@G{4GJN}5*c18f#uuG(x&nQd+xAIPamdt33;0% z78)D^ULZhPEcRpxE`xc}4D$@X1z7GFe2GbL3ym$#RsKiSH{0=%s_Fl(-X2C?hf}U( z*{rxU*f*L^1C=`F!6HPSIDskLb?o&})SfGTy3$kiIQ2Hf`9|)z?f7h`xTk9^@m6P; z(GPu4XbR4~z0~?Irx#x-|6*wq-QA1QQo3r#|P=@>9VSb>-jJV(z^lt=%!&|8uZQd6(I511Lg(^8-@N} zwCM0)IPj39@T5x|&P|#7sZT~=xpuw9odikcpP1OLPZpjFPsKNr0-xuI)y{%?s08kW zrs`H9V+B;Yp(rvxAKayP4$?u~DXa?lgusAmFgFQScBDA%1`NlG%2pgne<%Fs@jo5G zlK1jqU(WEtID^{LKQ=j{887zs@vV3&j^rCcifMbyU8SR!qkh`rS0N!RpMKM)Q@RCkvvaNFgjtbs79-@Y@l zM=~Ppyy;yKTxiLHYAysBWH(OSh7$i;y-l24_--bnKI?@{hz+RM_2%2#hoqY3;m@;Y z2=c&zl#%3puAr49A-#9qLdNk_1G3J zu9ldbhCN6ywsqR(++^4}spN11-3N*$_We;8e%gO{@Cj1z-D>_woT*No zMTjqK-2STRwSo-RqpLvNl4ihGhgx#|e!lIHr4ZKhlj7SOlzOVkE?QKNq6+qyDueP| zrff7MKw1w9j|#pmfeMhX;9Z*h+~c@D8twt!{VGr#PENin`xYjp(nFF+UhN=P&hWXY zS2CG13R#sVq`KwnKZGi-bdfcsQt8y5>k)|1i}Yr2*e-WHsIa@X?oauBuilOJtmMqy7O}DO$$2yqw@L^I|}5j<)W$I=G?0bIoMK@ zN-^)vbiA7Gjxb)fk1BMYWXID8odn?_QHzN5*V&A47-9aYn#sie=I8s65?V06%8*}J z5UrpTYC~6P+hoiw(jlPV$yD>w(VHBZC4PAmE5F#Q{}YcMd*Z0M1-}@E%75r^gKuiz zSr9Iqz?1Uf1$-SZ8r21okj|W0A=rl*<)D9r@}^4FA+Vg$roGLdk&eGkHCb?+y!i|}uV^A=_k zhUUrpEt6#rQR}1d%%QJkv&T#uz#C)|aacO(v~T`mQ;j5|SEP4NY#m_evHZf#Q9`=i zkt>{p8mTz}ngG{TT5#Lv#IOdqF0mL_gPt_=4L=GIxP2ESo#V?kaB!gi(2&dEMDY2? z_!f+hZ(l#l*7)`qsbD-!BH6EkZaB&?hXTK=!KzNXXjfhuZh?UhSoi3ReEh2lz3p37 z&eZ*x!W4;bU)dve4-8FRU5SzvP|G#KUixI9)lzmBQSIkazIqvt0q&e~^RuFIUw5iM z#T2qRMUlm&pK0IXU?8GG9;@)F8jXN{A`1A+_pX(oyJJCRlKg0?kzR=?0m1Pg$MSEZ zOW3J5#h1Q@KM&@lLIN9UbUB8KU;qrfN`*e5)rIOxy8E&_Qi1SML+EN3#r%Qk(hTF- zZAG7#YyyRYR582eQC9Q*i^A-4w{Ys^3)MsRA-^L>_bXu*1q{IoD9;l^@$pfvQx=M< z^7c>=F4gM9^i*IyBHO{xBhqvJ4y&`cvWP0a=;f%dC23r5NG(6SP8^q+oEiU7@1RWY z0a%|Ci{7@$ptSwdbTPVZBDiBuV)<{DyYJufuOpUq7e37g1rx0e{Q4NUf1!wY;f()q zEosc;E#FSPUmA&4OeTKVFSnX25!E;|1=oXebMDv+;NTC)8CA{r2&MTy7C=SpZ>ka| z0|aNrnP3x#*yUUU6v`!^lLS7x^4MYF0!6z>!0F?ndZpg z8SanayyT}M1yuJ6>?K?GXwp1z48uDcZ25HhM4#V2Vn+2npO_|7T*--Rq3VN|4gWF2 z4ptmkx|kPd?CnGT{PcKdD-iM%4$ckU4dt4-Pb)%|L%5%2(-#b`rX9La1LTxBppT>s zUzUk|7@1+)XsCz%MZam9tBw0(OT%Zj_pj(bHkiXNuFrJD@`p;r{r&DQ?Ktu&7q)-z z{*+_RVP(nTG@(vELeO$MJkS{9? zC@4(h*3zZcmPx`3nBV7+VSVC53Ut`QEGcE-vZ5@h7Id0wF85*2Y7R*VDJ%JFwf74Q z5zf{=WTw}`&b(69JVh+!`Z^D9z7HD%=aP(!%-=EwD*uIO?5@T~8Cw2NS#)MeI?Sfd zcgRm3$!7(UriGJy65;2^`N%he0+IX&DEdA|1zC!5u?5+g^He^&*qO3(bMysayh!bolDUd^W#11s^xq9OHt_QMAKlw+RvK}v z+$)Y7`uCiadKYPvCSgz(d8y#v#BF9IcN4)p&^(EpA_IOyB2v-Xl-JpM?$oIJ%y%&^ zsV1`jkelxhpmPi)MZTz;#DJu2_ zIFzIrZ4sO=u9y5f&RUU$<|vlThQ)-&iAaUU7QRo~Y@d6&uQzPi@83M<<*U<-^!{M3 zKN(UmjV)fmrRLtF(<1eLi}&4LRTlYp6_4v;$XFrs03%VYINPXM^IPt|p#uogL!^#E z;W!=gI$J<%aTCuk`OeNbWL3Wf5S&2ebBe3yb2b_O0$Vr7JbokTIsB_pt^e-4_?%xL z`OC@MK>6cdYiu4{2CwLebKQ!IT8?jiakZMJze)n+1FP=!c>Jd9pS`mVjiB%dVcowe zwBoX( z@ef<`Enbh3WH0x_k=u{zlEIN(eeNLh(6PR%-o+aeA;JUq*jSh|$9$I;Uv8`Z6Cr*- zfLc40*~K+1Qis>6F7=m!V#Y$h;nP0iYZZ-G{Wl=q!NUY~;=9K8)X5+N#1dOrf!?hb zxJ@f(F<1b9dHP02Pl1pwo+ilPUtBEK5?-m2#`N^{QZUsr*v9(VWlL85S|j^Fca|vN zjpN)mj-D@$nb9*Z!ge_aIoBxO2AO349k;2rHm2?j({HTY3z**7BvmHCqbEf|v%yao z{tiF-w;vqcnQ(CQY-0GX@vV#BcSX5eZ$2W#d$N#F1BckHSkmegKhk6xM%p0TICd1B zka)nMFMawHzs0*26}*|zk|&B@Gk00z?W&y?WEA>4lg>F68MiX7??rG=@L&M04OIC6bXPL<9ZBds-ihYL!cX_N~vFn>0_JbQ`x3W$%q7$?KBt~sY>Ndt) z6R|G}Y_{)|Hng67mYw3AG^;}P%t6X68@xIK9~zsi`uTT^ViS`3=X8Y`w*;wa_BOf7 z`p$CK7Ylw=niV=n>vkowgT7R2Y{sW8Wx9!tvK-!dvowv$Au0EHim7M zlFf#e@GakqY&V5XvXguwO7Rqa=~?~?H^fOS{PfHE3P+NeORwxpq)q3a{XMg~)K-SE z8!sq_d^2mlf3cbLbNfj)NX2FRx;Q?z^yWRvv+D7K#GqT057WKV4)*Th-?dW*hufw_ z@9)}c@p^l5^PN~#kkj=t?=No_F5Lr<{&7U7OMT(}%_-wHzYw-CG~9K~I!s)j zO_BSfW#ztgEt|nyWiMDLRLlv?r?hZ6+n^xXm`C18#^kCk>hu)c{y~DOH|Fd;b@>Jp6+w{F)KZaU* zqMO2bmi~Q3@14rXp87loMXJZf1=iFpxpDY(E4+ezd#EHu83wWJ{IDeXThlRy?}nT2)0W#kJK`SW@?pWO zbD71TDKC z?QhpD0;Yc4?l=z5U%XdjK6e-H=kZ(-k$2KmbFSEA*2&*y-ITvbDs-=O+wHutw$5lK z9JaV#bq|r#yB0C-Ie*XK+3zh%sT^%up6q8m(lY+TN0^ef{}U!LJ2KL-L*&w-mbrF^ z>$%W)!$BMe-(mF#bM zhVJg}7>884K~nU6INx{95B|--#XZm5d#|Vt?5N9)H^RR8N%8b$ zM^A5W;SdkPTR)#~(SEqZoQBfx#%FB!y0e>;_fT;>Rw=KpUZ7=?I6XAS zs2>Tz$>|R7ofQ|&ICND2l#TyBYQq^LdutSDi^+%vC2u)$IW47w|Jd&KCbs2 zRqeBzo!z}&WuriOI7JKuZioxBn%ewE(^@)$ou!l^JtOZKxFK})u7#&Hz^yr&55|{Z zQz&jFwf2$Xov=s(0q2PWxh_+GI%oGEn+Sr!MEtev8-iX8gib%)6P)4Ou_gH_1|kz$F*gjw65CZmu^Q1n7m)uQCQ5^O6lHdFa&vkMjv!# z|J>23R5~M@Qd5a~1p`C`>S_^PJHmxXqVL}%u=;0|^*Z)(JYk!02PD=J zZNLCa1|bLX8YGn4L@pD`4tyJjjcZpiGR&}ES*%;Px3y{wuYG?}7~j&NsY|qfYb&A3 zIPwGdH55PlK9l2wmG(N5(qA>q+c=9KxvcHGd4uN)LwkqN#-OT+SqQi9JjD=utm_uK z#7SNRLy&vS6SxQs*y)>od45*#T8JeU@>>12P?iY3pM7I5^6#<((yktu=)?QQn&eUM z`-|_|CD+-3{rzu59w(+Iauav;0b4zi*9qTq5ZT?uk65LqqCD;;oqa*1ENL0h&1&+PIr#v8|Lyc%X?R-ZMk8{S zB_GM4+~TG0-}}A0yPeq2K!P0V>VQtlIv)TyUI-vEy7jrPbR z{ornr91&LCF5mb(QT3ycB`5=9;l>QsK17I6F@TDwb>FeYWoMq~7+tIx4~1yT`OLZ} z>ZNj*sOsi5jR$IXyS~L8!37OC#*7CpR^$l_*6K?cjv)IYgX|)EotT%&NGF536(x4> zJ$`!9{(;D>AZ#Amx6-|mj*G$c$BZ4&z{4(_#oM{4nr`iy_SK9gAG~#I4{~dl_usYm zPdzYNY*C5K@)nKQ{rhvabbn#0T=bMeE=cBk4D?LXx#{%LS|q84JSDiD*}H&FclAit z`tgsKdUPh%Z$EKApSN$M_sT|C@im{i{EazIdFh`#cry#1?p@zf;1nNuloqNeUCfy6 z{`kJdp--is15>wXOFu!<{5fmP9hbmaAq3mC@X>8eE@2$z>Iol_6&o*$y#!4XUHe*<6`iz_r66r_y0C9|` z)O^CqoVNcAF#Jgt5y0$`6Rha2G>F8xYQ6e67R$)%rEt^Q-w;U*qp~h7hU*;fQ=uBa zqVR`CwueF*OYs(KzQNB)@OjVN!MPVnjZDyupC6SBC=&k?KFQvu9k*b*JZid&Xup!24yZ)-h{*M=w|)nt3(;ES#1I32i4 zUToIkQwD@af`_VL9;QtI>Z#JtuJR=+c)UByUQ<#pc2cuqq%T!uSYLaGk(&A9CEWT%mS z**0*k0TOrFTbaxh{CqH1OcTJB6AcQ0zX}}W47{;x37X1!9@bq4bS!fWv`_nSa^=(V z%gfNS&qWC$yhdeqP1vd@ag&9wPNO+*S$HCdbvN2;nFfS6+j4zRxO}_6H4KsU(nJX6 zbhkx?E#LO9_Jt~HvjDtt62y!qHm3sVf^&H&En7C4cDYMs${{0lPdy&n_2-UM!yd!W zP^QcG1(*7)&ow3x;NZq0Ao#|dhJ9;5;ODiM4vyaaQ8!wPpFkApR{2-8 zQ=sNoduVL7GWm%c`IBM&aSriDfDDm@SqC3YO|tY)fYmPZ$yHWNvWO`lc{8n|nq>Cs z*T?kUI%}g{@8$#Vz3CTusJi0C$sJdu3m*dZs!R`?zMC&}s8UU1-}+DzbL?UQXt`4)-#bmGnOC?fmBKjyF92)x z)JLI@RY#tKytj?Qwf1+tBU2Uq|ber(+wwtrn3jCw;rs9j&#=}yxX=VZV)gVor zexi83{8rqu%Qx3?fmI8ndC$E0uE`t*6n)D(^;=HHJnP8O8>R{~)+##u`bbdC7Ew_Z zt)=jK7G270F?|Stjb$zR?;uiU%Uvs{Js!~K+6a`7 zHF3P}2u~^+98hzMN6?~4EM2CX6BPQ&CZE0~_~4fA1UMp!XDSMkY;P z^MOtK-Nm1F1-lX7vjK4jsHP*=9Ti7(jo#={nvl{TVdc4lAH_Af?81%fjj$2Naz@?0 zZqI!%Xm_m+N_&(A5XEC#joIs)ZM%nz2Ee6 zgJ~)x(x2CBaANH`GrreSP!Vh|CxJ_~3%+5KD?Wd_L(9OS*R%P}fabFZS$4|YPLEFL zOPdZ<;-YwmM5LGSl7cwvnGrsLkzg?P{&L_&7j#TIGv&`dzHnygfV|m{^jw!V27n-jgXmB_iK`M$$hRvWV#%mKJ331?R?K7}%P z;#~EIILxPi=hM#olG_I6z?m(|T-2l`g_rm@_O4!JePen+(J65KRoQgd2F~B;5m;=y zG>~PK#WN5*H&#cJ`<>2F)+?*~evzLUV}kd$q35sHfxo=Y@xxlN)#rDHmxCBl56vrYN6&BQwm$u#98+Bu6%PZH^`TOdF zjkA&QG+|VgbEg$?V{gtlll@e;pRV~!UVGEup#w`p_0z!|xuro#d=WYHFunI~7lDJ5 z0n5f^PfBv8iiKuOi4ix^OFt*iOnm~~zA|R9PjZf7w1Fv{qw6UFuubx!sQ8+wC}b<7 zDA|DCUp^FE2uYl%c=4VM@I~gv#?n~@CyuUEEMx#-F2+D zSvdJ9s8NQPWwIFy`Y4#pp1&UEBLQNvKMwbGG_S*Yl!c4tPIvD0*$Lu ziG|O{^r%0;@(PG#U8$wQpY(t?VN_eFxe?YFY!sgp;VDg$w1Ho54J|?{ewXuY>>0ae zQi*x&U;km(-v>ooFz7R!m%|!_Ry6&>^n_=A_b;1Qb?Jop$u;!?)ezA*9^aI#0ZMCV zDz#ABW}Y&Q?z8Hlv9WgZT5dkz_y^ROWU(87F&?81fIEw^Q`P&oH799JBH!~8u>ak~ z{tE}pIdqffoiQoD4F96|^!tdO-^ScKH!fa@R-)BCyvv9Z7woornl5=JWA5Y$ANnD< zcI|w4lrrwNrE;}JpT7l+q{3ufQ z+M#{;MBLa_`5k8dmI|np?ARtOqL9AOlc9UMgkXn6gzTvfimY0t+)#%^6E}SBt4_EB zS~cwChE8L^#!U^PRv{-O}E_Izd5Ktr33q!5g_m*T2z^zMC@kE^MiqhGPFubsPb;3bBR5dH~~4Y z!J-d;#T;1;hP~>zAe3j4`M}nZ_m7oEeQeE~ceZVXjWWG==>5^-{hcO42Y$=mAMMxg zQxb?Y1SK>bSUR;AyO`jN=&I3S1P2KRd0IP_L7OS2j z48RoZzM8kCl!rgziuLtkB9orv@^U9zcni3bcnFkG2@A$9XC@pf0$ZYtzi%@Q?o+LG&QFk7u!zJv zXke%P3=Qy}yeLB_@GQReIlN_;!|v^HE`ZUKvZ-x$k6r6sW*=yLf|tZFdu$x7J{mH+ zWO~8TT0Oq(5k8~kV`>g#b$a0C{XQZUFEalQ8M7RXl>)}u^KM!*9RV2iQM=Dfyu3bR zqLx6d-Q?En>}4vw7-ziJ#78y0Z7K_(*TluOVz|}}R%C~lKu5kCVL5$&zB8o1&J0_> z?JErWV8~agq^dkF!B@Q$)&AQ&d3>@`)!zQ{% z2-2e{IE(r-|9r{F7hl^4F0-KaLSV{+sjuvvPz_+4kML_D>VlVS;UI8wU?~&>y*HjWXnR1vVBm z-T`iy`0}AwI_{spJT|oxuH7XdY?;0Q{Y`;#A?3WM6ac56Z&?_mO7yKZDvLpiP$ z53=*%-3Sc?bCB)4c^fkTeb`)sQjjx%yS3vYZ6h%#P74V*wO3cwW7n6}F#7lHaM^a4 z?ov;AFHrvv0)CyvDbRSelw%BcqPnz!H!3eKLuA|t&6sN7#%*9E_9e33g%g+dOWyFv zBQyEta#uZtxJsC&BdqSs9p)Y%twPyoV5L>&lIekGL7XfTW237_2?d{UbQg zgE!Yapk&5Tx&FonUJI(xC}P{)&$fYkrXL_07CqJJ zLd!lfeDZX%@MeZqL>YlQgl!`;(P=S>ZzK#$ubkFsj*1!69Z zxkhF$iRcSh_-*TQDty+@iO&Y=20=Nw7`b?qF+M!+LZ)3swVGl=%n_t5phRgZ+pHcn z$-3_c=$yE?Eeak(n~gl+QPfl@2tU58J!~M}bxQbPO z%qT8x&?v9B|I(u8=edT9t(nQYQ|&fz=;i^FfJ_Qjt^I(SLN&w?h0`39)`n|3*F zN1x=r%J&>0R>iOZdpt%nAzdw?5pv8$N1z}IYnkgTSZrd8ew)o+j%5+;bfbo)LhQOx zdFffWWn&|5RuFR)njIBZnIA2mJK2_r<3DfbyFnA5*uyZK8E*U?)P$ zO;48e>q?)7K7Xg3gWNRg;nQ-Lba6-hb#?d4difWCBXSuiTR zD)W1TvsrP3cgvqZ?q~AcP6E+Y6l1W1M&%-bC29Fcw|qKweYLdpK1kQxw#+BBb8y|E zIo{$@zB|caz$d!`mV^r^Ro(~J8(r6Jynzmh##LDdAe;BHa#tfMTTaXdpIVpMOgP+h zv0{HT0lJ-vveMIi?9UUO;7Oo0M)2QQf8^lARWQ8hP;nD~@V(hQ)fp^s>?mrytB^lm9>puM^C;YVJ(YKXh z?Sx0Taepe1)!nAZl%XB*t~SK>g*vz`e@**QY~xo__ID|DTMkgl*l&yn7iLV``jO!< z>sw`Hm!URr9LlL(a4bG6Wm>PXwt{1|R>Ojyj2_7ppWR%6MRlhXE4ogQYI8(y!if^~ zsLwR?g|0UFJInR*5ynN25g)E`3wQ}yNdm8bhMh7VyhMno4O}HokhJ% zTOk{2Ct`XmS50QlR+uqvCeI;HG?us^lkvEOYSv<^Y7R?D5E=6?s&7y7=>*Pca}(l<(Klb!oim460Im2a;WKCpCz zifRc7O*KwDP$@N+f95W5NHmA5S`y=rtzXQXa80+ezDWS?XmWAlu3PV?!LJ)>KYA?P zoiEN_0j`t-OAxXbX#2PiBriV{Rh3}16(hU$&O=zozZ@85t&zvmr6u(MwXh#ZieUX? zXnp6y9V>ySHbOIdTe-uSyDIt0UjvoSVlT1LEDC6*tyAZ&@Q-6;$nKYX6-*#yZ|DQ+ z6k5D*ImI6K3z;9l<-hCC2t4xtxU^E0+sE?wK_A0y7`YeyG`_k5QS6k%e~*~aQklAMGIv0OC5L4*+4mShwH(Xc4H!vV@(&Eqf7P|-IWPlO_Bu$imTv2 zZ_?%@s^MW%7u=JauHD##2B-XuH>9y`;`S_}Ty0>1vW+`&L~gcs!yKZ+>yM=3$?006 zu>j;Ks77`1o<#Vf_R2$qV*A1=yuV-S#fLY&v97Sx#3a|w{6G6@JA77c;6P6%3irh} z+EpuH_E!_Hfo%aIObfW%+ker=ik$-i{i1HvQ5(20k#;EZ$h+Kk^mmEWip$<=DlRTH z5<(2qu>28d5nrRZ{NYKuma&!ouz@-YAlO|1g53gNe1#4hr94J05K)UoRAYaQ-b*gV z04Wwdvj@-On~$W7x8%pbOapF%uJe6zE55Vm6h>`^%v`C01-9!lot0d4f zet+AqVk5BYweP<&r#lnIB$Zd3x~TR|W#-ff;r$GRz*s^LgRv}%rlKl|O7Kp!o7$Pr z-gd`CQLn+yVg|Ydy$a$(J`iEBA`X~^B%uCnha7Z#y39^51sH-@YTS#vi*Nc~f9`l9 zMLzH}ucnmQ-5J`Y3NACnipf~@ST-*DSozUSR*fC+byV0h0ET!uN|smtq_{S28M|#J zMKJnaWA55Dedf^$9;SBd^&DJi#q!DF5lDWlxATeUyii=HVdKb@SFDrM;icnu*UUV| zN`KvZk$JJp?9sBo%4Q+6jymRd|F*XBxyc7gI^;*tHJ2r#4qH^p0^Jvku>`Dlv7kby z!f(rifMlnwv1B&A4Xs`)|F0SGp*-^ou^ZRaV2>OLNUB522KktocyKf7c$ zP}A*^D&N0N^^0})Gs=sj0pZ^MR`;sjI;7QKw%U*&hC3gj#c1wnCC@enuzKwA*6v|< zZ2k;F$1Pg*szdJQ^;Y_t8p&l>6a-*Q+-GC=&Zc;}&-X?8gw+w;Mxe;G!XG+i3|BtA zuClfJg0$86soor<_j`nG-gpY)r9MwbH}!UbQ7B;#Eq3%sxpj`a_`83OjB*b6)!zTY zQ{s_kF*32@!?LNt>EX;inW|x{(9Sd*uZE>MSrV<1|`S40_6%AJxxo6+bndt zYA(=xqvph$RIWLKPvygvdKhp9h6-EwOG{hU%uijwq-W`?9L?tPbLniep3 zReZhF2L7AJPI(6kE=t5|WvJt@Q%og^xWLopDz>@;S-I-(rK!|%1>O05jFow-?i)@z zQ`k{%=sOe?^VR)qeXzF|5!e+qwrW7rM{hDi8#c2@t=d9=4h8}il7ht_3dOhmPMwup z>yz!FAyS4+)uWXp<|K`xz>MDhAAklC91~LvIZo)cbR-%>hc`j0pGay?_C7wEX8SR& z)-h&iBRO^pJYJ#ox7+Q12JKrgMvBFfPx%S)v{S76Du=zd5({Bk4xLKPnbw9Dx`>K+44@$y5y zUBkL@^rUgPu`{c}?rTkKa7IL;Uq2~0#}wd<{jO5QFzFE9_A=(+CsS$d#U)bbfozwnSD5vBWW%fxdSu}M_mWbtq8gjjkA)Z=cSjXW^8kXD_Ge;EY6pM zW#3^%mz~BwOkx^wBdk*^Q6sGDBGa){`SqigjW&0jEufGcF(V4!eNf$lyuXZ4ksdKA z0Jk$5C$XG?CfTdrbhKjZD+D;^i3-;7IEKH#1IahQSV@Fu{x(9@Lg3zqBoUQHKWlu~ zM7=pFrxN`m+%Npe|9D$sy&1Ozkqe8KnDuVZF7c2W;eXf;$6qAxl)M^wwGL^Ub2N8` zURDk!HNg_e@yr?nx2V&__TbM5I_d$H7uzGrxcQjevwyfdyGKuRY4`FbWLLX_yi~AI z$DT63Of=(mjW)&Ix@4N!eX))>ig&#=$7{+g@gczX8?oVY{Y8l2M)=<4 zax@EW9NRgXijzu~65|-EWOI@skC;UJS3PCvbc2NhOr{Js77?l1Hn2TQ=YAVlDYtA4 zCa{*HRD@C$UPTtmv=4FNiBHZl>rH>xrLcA24|p*zbXorpAXX{7jJ>i;JZc}BY~Pyx z^JwUjxm%`icX3^yB(VgcbFl3=1dYZa8Z=Q*)DuNLch45Otn#sq4v8c@qpbMmx?s?N z+%dW=JZ$CZ$=BY&f%8c$B+MYC%zbsb4H3yG4{gUB;NN?unaU)D2%(C13vaMV@R}6H#ctyZl+}b2d=LF^l7NNTz5rH0e_#E!e z{sQ~kip9RU86FIjx_L+ECTgB71#|t18qPs^QWC+s!hD`cE=SMKDI4%8)DrNh2h&1m zRa2+|t*^Ug0w#}EZgpmJwv9x^GFgP6D>2=D5DTwa*8P7T!F42I1F4OAi|nM)AeC7Y zA54G|k^sahKa*j2s{^4kWDJ^#VElNz)TjIgh>v?H`xxbGL5zr?_rBRNA7=huPjlH= z$bc%S(P5sY;0S~XFdSsDLwXz7lrD8bC08>OetY}-Woio3ud1m}H9QcAP*tRx)JJF* ztvHPdQ1~z(2K|{gy@708gwjO;8LORSX zr^_TqL}w%dPSiVHrU|_a!pg1P4}k|cY>mEYr#VXtRG+9_{Lb2P4Ia9O$kv?R+p@c4 z{B=~m7lF+=9Xnd=DWvD=!j|4M-s`-rO7KsWfeEjHfu2y8v~G6R;JTU9wz(bS2llB6 z!0ZObM)hovM_2}40?3wNG}jj09py3y#GftE;a^xUZBg>dZgRf+fiE< z8Vi$hneKF1a}ziXb<}4M+z9mC3#w8Fo<15~!AR(4jJsA}ELP=lfdlMNtQLUH{#7t( zNcV^F+H%4!kv>b{!U)T215=?wz)-%5X?FTgCo`!g5{fU9$C=rkzC5-@tZ)!+hH%6oBqK!o+tszG7MmL zIOUBF!$qk$*Az^|(((3qA2oAB0wbc!&7IUv?K;frc!ND^J3&e@fM+XbrXQ$|$FfPY zs>^8SpnvMNdJE`@#AXNRe)GEIUnfiUH0Am}q+Cp33-FjKOWL-_ph+b6B4nZc5)OvS zHWi;=`p{A0>I6uuv2=FeC2HySh0eBpiM;pA$2z{Jv1f&s7}gvywaXDUt;%3;q|3Cd z&0Kq33LV$KpmCpCKGu(;3Vfo~X)ZrgZ7xS!Y*St4K;l=}$|n8zT~`?Z2*zzHMKBZu zX3`BI!LRcZ6}HGz1fW;X!I`3QOudMnIjCGCxM=-oTB_%*^b4DntuC?4B3e zz3N>@CpBNA?s|{8e{e@k@LWm&N5T-RT;C<(O>(|R%=6Sid^&_`MXF$&A&srMza&r3 zej7DkpN^t$4BiZ0=nu9I1yu?#7j5Jlrk$fEN3)k%n3_$B!hJ(WR3f=J&tjY0GPB0f z?Tyy9v$+N<5bWqt43C%Ie0K74C&sNgd$j98%NIheup~fDIt#mj<#oCUeMr3xN&7}W z-(QhAP?U!1Y(a|jAHFwwhzAf8)iMKIGAq=*jy;qvf7o`&7omRYtNQs51dP&=PjSfA z5HOg$nTH&@7TRhH3}r(JCQ56^+&B57PJT`?t$6(XW%<%xl37a8#q|N z%EkbYsyl+IU$|tNFEd&}l5ZZkw z1>hx69&EVh> zM#@KvC;XsS3BQXcR3dS^f`}^o>Ce&}W`Ln2@gaazbk2lq2_u|tTcnIt3(N(w1s2UY zKJ1A9HT&+S-%s316eRZrUJ@yHSgi$Y6I^KdtDeDoZ9ICnLKk1?}HnaM_u4U<1!eO9VgqWl z2nT}>*VgbPXGL_Unj5|e{Ja7dY{}9wYmH*Oen!eY3O@u{=rZ~u0K<%k2))3G^U%Kj z)I2Jv1njyloYgf+6bS2!pSNSsA9X-JCC|+>giG2HtRzTOoV6k-9+o4y(v3U-+ZI!T zWq(JHuX$3R`9cQFr3cxGRw~)go7R}tmuN-%4#VLkp=H__DXk(S{wy^tj4`o_dzy2 zE4TMQF0u_YJPeZ_8S-_!QmB|bOU!(h4Xs1q3u+pZzV1idM z=Hi-hQqQqSAdogSrTpGy=JxepWT5tmK@V9VT+R0?e5aWg2uXb)9Sl3G_F?9O9 zxry+s1r?%eDnc` zfmNa!21Rks)7Mmt?J7ea_d%juH5_oW_acjrB|p4Q{We+eVJ%*zs41KH{$IU z4+-qMwbyo=MVoTTOnXvmBt8D!7B$F5jWa8Ht6uL*xq)hC1J-7d!(DR6Kd8sB)MK9$ z_HuX$XDm2TRMn?efZ84dj3p#<5i*wfRGqC`{1IJRVqX(bF9y_ne54Po-U#h;&b0Yhypc#L!V)3|UvF-2FG9F{ zddK{9df`d+xl0(xSUg3KAAmJPDo()EmDtduHz>^Z?s7atv@JY)awO2zTJ!&OPc{Y1_!w7 z1HfTF&(9X56}`-HNM`YT^{#G+f#71W29qcII(=<8aKBL5SZErXWi~DrclH#3`)}U- zZ0pRKSyKNz?@|oY4B#kkPSTa3z-2XY_V5S?qMOY4$+o1^ZD=n~5tW@eN@Gh)JqwYwex3Vp)x=Zx>$LXm-kp3<(!QyzSwo9As7z!TBcGb+|lQsRv{CWm;dfX+a zsE3b!4+o{s-T>8xore$~gQ>!mtN9z@ZxHcmoUvQayp&JBQ4f7*f@dyU|7Il62>Vtk zLht-1#kfo0B6sV@%bO(Wgg`^RG|EOSjRGs}r3~zfXaR z4s^f#QhG#1r9KA}UK?S484t)Nl#vaO>|vI@y(X(bZO{sMB+A5pf2~2 z7>V}91~RJFIRGtK@5e#Y_fwp)V>&g^7C?QqftkkJzzSbJN;R{L^PUFv=rtd_dg}eQ z`HqUpu8~rv*#_q(=kOumE#UP-<$BWLdPIb<2{3$f&iBFLnmmggTiI-{d^%7mg%QlQ zgO2M-%$I=$YeWRV{x``_g^4DsPoO49>pEcWU&+_wIvVws@{-`(B1X+c+Y}Qhh1ufB>ssV`}a!|H3b#Cw;V%E z*0)^je>v#wcPGo%@3_X0Ao6kAq;evp2}4C{3S5ckaoNd1eA4~yna2fWEp6Z|7L()l zU5Z;7ZLQ3l$gFgchgXzStyO%L>_pN!ZD2js{h84*JMEwLz`>cbh@i~@qf-0V7}A(l zIh+R|@CzVe7_6-e*6_=HT!5(4zJ`~uR@(4WaEM)Y|Ei&nfwlJSylH)(goJCmlwtD+XV+dy2)OHrt%90seY?O+-K zYui`a+Oa0sLvKGiwa@?azLv`9_K*DwzIbr@9HV*#UWmaNee*7Nzh0HQPD;l5;)aiw zX02WoM*K9igqyt)^`OFkrsPNd&}Dl0F567v#^C5%2@@`r*~+_(_Rwgn9G+)w?1L(; ztLZq=s||La2-r&&6}ePh9VBtBRdAoWm-DL~TH(%jQny7%20st<{L| zAOBn+me7zzl)$8)6gTsj&c=qb%vXm1#0xLU0lw!`C3f=1DF=94P9L7%tMw?7mo zZ_1@9ogtyuz9Q)et564x6bmmP6E+;wsKwIy@Vg+`be(yW6&y{EU-Tr#n1on$GMMU; ziE^c!r2G5kQ+>A$%f{x_(vQj0-R*8jLzL`}Rh-H|ZYhA0$7~f0n&nYp#$0i+?zZOKH9Tk>8Z(Hwi&YHJxb!7oH}GQ4j4F`d`$yx_BF6y?AR>YYpfV^=rIOtn z2Qu}BX??)@*{AaLLF4%NI1ZD^0H)&`^Bs!IIYe`sUhq65nA+{jF!yTPq$#xA^Im?&7r9T%)F5#=0d3si=1HqvfZXhcQ#PPDx(bf44*4i-`tj>c z1!4gy^#R;>qPaUmMIq)QDZs%DnB#4rLbx!$Fp8`@pDD5 z*~Uy*<|}I#(P4NwY+&5BBCfzeV`uPXP*^1%?m)=^2Cn^5@>I|T04@-+Qs(MIDtm%# zF!71wL>DqqlFd)dP$ zJ3M#}x^A_QxRSnBKl0y@q_2}3tP4VDV0L%xUysN+<>NjEV_Cd#i5+Z1kKAp?D(@g^ z93n)r^~ofzzYh}p44iTEzrU1BjHGW~^M-{D0Lm7(IAPE7Bm1Nz_vBo0U9AIDA z7(JO)5dg*heFdzj?yDXi=ve`~y}$Lv zcU|-e$@kd5y?Iw}v%K?-aI7V-6(S#npt8_uFzU=M*?%({lhf|`sAsWolG74?2 z4W)GjU#AZODca8t7TbVVqAW`61g3dzUX1JEl`OijZ?)dERNr-1pVWwuEQh?cbCvD1 zpgn|N=qtv`jdK-XM!8WF&sf3APW$=qZ?2uKzha^PqG>bj`K$@1T6AHcFgrhn#J}^$ z^z=m{wLqTwdcUXvAU)##2MWJb-}GbgpZNAcZ7MMC`!^%yX;9op^qQocq}l^~g#u3! zHppBc_i!sPf{MZt!i2bdyCy*QrgH2{H7p4c*b$OcMBMrBEPx9rwLY-QH#NH1R3z{a z#6mLo#8W0(xMJ}U#xf@ktv^U2rdIWH!EfW?{FRzqLpCtVsk?PCNN_;S0r+<%N%t-DP?RWLl^Fv zsSN0g))X2*R~4A5rL8KuGRaoDe9-vIw*uo~xju@upg2bUiNiIh&RKQ^V{CNPxFVo% z0g{m4gy+pv>9NC;3rtF2eOwZvllaWRb#Hh?ya$N3={5TB5(mr9iV9E+01(Cm`h>oJ z)=t|+dtaPrDXGnI0E$?v22h6B;k0kYw*!>Qa)IA>cSQNj)R8zG}9z#4p`(z(jLkm2= zPQdAkGFFMLk=gVN{~kvBz47&*uZYJvLQVJIHXXXYlw-M&ym}k9rW4owZ$abUxhmA< zx5lsY8P<>o=ovj`7@ADu*^@+bE5Cfr-xQYOAYtiVvi0(k_$F}zPzwmbv>75+GaqxK zD$xGW3pG+o_GvG|-hovh4a zg`~tY1J5<8$<^2DMk#Fg!+Y&{2mwuo{4lBMWPmd+>N_{oP-MU0u|zro=-$K4J8Om7!vfe5$3t^IESOYxaL|W? zC_zh9bdsK^qzw%F^~wsdfydbb%NXgmH_3c7%VpqK@Z%ChJzidnuQIY@2CyMYnkf{) z3u9DN3hLpcc9KGmk%qM4$Oe0~5dUtjRF~liN@8@(tNe5RdZyA&u+?Wr-12PN5A*$CD+R8YA+CCNNYbF=E#G5R~=C~)73&%sCqIvW)c1fKJSbi17 zFpV~?bd~KU_JKsb=$jH>sbb_xpR)Z__YyF*b8#Vl`W|(OMnb0q6qBS&TS8PAd9Py$ z1mt9d8dr%>s{=17hw=KqRE0*N3>0ZL%OmR*pVKdY;f6CRQ+or;@nACsU73#?Np0X) z=e&OAJ86iWemd{ktt=Bu)je=(nUP1T2d_NWw)SsZ<{*HMUZ>M%$xUKxCp<`G`Rl5p z9*mF$?DPu7=Weq58;Zag$yJwD>9|yXqQ>CFI=OfRe?X5-Dt>6_^*qPAzbWM){kcQy z>F9_HgauUG-0HUY&GRvugW9kN?r}C@9i5YsAkZu7GK&kBJVNd+=RF)?_NmYcpnHYy zPRJ_d5JIkHT>rlMgSW*bevkRQ9?)^O9c6f|*-LzpNPu4zwNU-KN95{*%usM()tR}O z6m5e~0<@%?5B@bI!>Z|L99G>;GU$mS(MjJd#F#KB^^e=$6^sAD)184DrTbDS+;`34XM z_P>d&M-UQDKV?Jxb0^kcA-`rpzdp=+pn2%5GzLO^zIKc_B=lP330n4iDt&T2XJuDs z+5vn~4SaUUH)iOvTy~cd`ET{_34++6l-Q(O+t^U=cfY#mjvSNEIG^}BzaE`_mYiTC z?;8#^|NQc>t1c$Zjoc)AwgC+>$gwNps=dAC>Gq6Y{QNzCT%5umaaT^d*K~@6rp^$G zd>r*EWyRJ3YG?8BD5UJuFFl>lD=p1+*Up(=oPIUvlXX}5R&1D)zc@7J$GYX@TVGB0IKknPl>XFm-O#=%2KH`mw&G- zW6pUkO}@rjS&Wvy0I+$946L&zADKr>Z!$ah{vwG+jRg=pJ;Seop4Y({0fm{!ZHkVz>_E|YL302it%?@@)!PBk#FoUZ!I30;haiY!_F)k|a7%nEtDwkr?6dT+tfk4o z5t2^)@|`81BXb&>1>$~_)pX4@k_03hY#kwHxKHqtY+|>8BB;V|Z*S{5JEPfjs`ehB~%nlKeXbJ6ScL3R&|@z1b~7SzCFpKWT zvc;U%r;jc@?eJ=^mIM%H-ei0%GSpK>12rW>x$*^4^d)DeNxl7D`qF-#@Vb(;S%4@Yc1|()9vre{}oKmoHkOYTe?hgkJ_O;vjl}2TjK@U2gHY z5?>|%9t-fszyjF9+3&@dytT8C43~Fl#8*E#F+d7>mX>{ znECM$$TEF_j*foUx$)SU*Q>R$s!|u2XeZKIhEZDM^NY=JFO6%P{#u|elHr^=ZngOT zXgcelD7>$YgEUH)fCwTj9SZ`|C@I}tlDjn0NGaXYNJw{gcStu&qjXC5d;QM)o7oxv zVQ{!y&OPxwpVK(o%|tL%OZ&PszYXue-t&u?U(n$Sf1jAhCI5Jm2_rxUzu?k(qpbaO z20gNFCHelkedMytXd}t|ESQeuMmCp5YLJsxHCqC;BIBZJt-hOdFsfK@VSXP=&Y@vb zo=DRasqOj-_h8w9Jt-UBT`fQ=uNcCdo0|`bwbEdg?SR!h#m)PusJL9|EYcH|0u~KWa?@}1&z5F<(EAba7oo&({=Y=+=<(qQseEWXi@Mj-N$&~UZ|C#uFyD}| ztmPtkDLV2*TnANh6Dz@m{ZPhRo`j5uZ=sIY$vTBDh{asVGh^>1xxFsh?vBq^0sZln zi*UV-KrP#oE3V*{+3wvhL^2;#zE2dDt3I&>GScPViOcLi1$^GbZoYjVKJa;7Aw))E zvy%=5`+tQInACFHjqVuK#_9VPbM{Y_&#(eUzYUx&KwiFSun88st|cQqced}80x}_X zw=+fr<~>MK%uB)N#czR#$&Cc)MMeGXED>XM#pdLYb|Dz-bI&!GkQ!T-jRl#E8<}29 zfh6z7#xw~}VjN0FZpy8;Eho@^a@Tf>txd^0dS1N?(R#Ov!I`T2E_+ubk7Y$$5x7p~ z97Hv{N}GdW!hK_%cBFhEM8E4mYv+mYD?>&HCR~4MyzwE#QEsMoD5hNK{^#P5Zo(5MjQM3TXXZ~| zadGGl8kaR1zgP;B!|UmiW>!UUP1f+`GuM)lqSA&wzgX!_AX=x1qneASdi;Y>q`Dr- z9$e_47P`tfsovz{JH<_2@8jt-HU@KeKWEqLPf}l&FyWXBr>TD)kll0F^j=g|&1KwE zArpAx(9IZ|fmpQpRB~#^rZB!Yt$vK3wumqvT^T{v#idElhz^G&)ma?$%6|}a0C5eU zX7Sq}Fi)UAtPufYiGrCtBGH9C7ZP`QB02OFKx+s!|IwGkWp2Out9Hr-zMnNy51_7N zN&Uf;ct5z8=zik6Gd~+5+!lPX5HE;vz3Ky|#o2Jv8!83H%XQ4$4$7qa#_lB9D=L46 zhlVe^i>&_VjcpD8)?(?m6ng1f!CCz`I1FVK12DhdmUG3kwca`UQa)bwjiBdE-OQn8 z&ax!1Qy|T6W%9)4v&r?}g>oF_LzHF4PDaR|RJwI|E0{kM3lHsw#hz}5rSP`R1Wd-_ zpq<43>#AQbEs>7@=5&eW#K6aAy!3x+JcO4ZCLrIBeLf#QbRWGDO!t(1wgWXH^aNu| zS8nx(_*MTH6$_s?6PHbpsAz564<+g9hBT~|cl+OwD=55Vw7ug#>V11nlvuL~@5zt=o zF_wy*J5JhsaS;^SGqB{$@?$ZueV-u58Q)=PGqTmiE>%T4%rR99 zErnMzP;PsXJ&T$TP>;vC|WhjH?o;_cNYpS9vvMaiM(!-o@y<< z=iuUTRYU>$8MoL4G&#>GulFoogqWpI^3GSlaJbFx$5J-D_Njp}UX)N2b%U7bzF{kN zem3rCWZONwt>^n24Znmb*-YdgSjyDi`C}E+abYKjyZ2GM8etV&EN(^o^hdg_nN0@S zQ6ibW9YmrQ;sGTU?~%IsoWGAd-KKqJzoW;h93YN+&d>Jn9W$xgsykkR@3-Wg67v+I zY|!xu=J)iFmNR9>mbZWZ^?d(iWHG@-gBsFgDhoFtL)rQ=kuvHmHD%&+QoXN(U<6fd z`GY_0LAo`oA~(!LYZMz9IO|=LiN6ckF(tv1=}QvX_87QY?leA>n1%Y$G+DF~gKERF zbR!qJh;>)nNX=f=N~ct2 zv;mb?ac!^-S7;vj#27WgcBM6Z$0=l1-(#4`HBpS}t?5Oq!ipRQ9$c8x&h3!!E`Q|l zH2rarbdAsi%WmmgMPGOAQsQ31_K$vRc$^(Z19r+nW}|}g$RDz17YPrn!Ni`gr7exE zU&#ny0)8RStc#WUR)w1_6}Xj(xC4=E-jUymZ3|ytvEtwbbJwZR(7m?MNr-YdI^O?j z$=E_`5%z&IyJv9(yuz=Hx+1=}E9g`XLV{#QSUWAL7QyRfwK%kBj-{n=ZnELh*btE?$c^&nD|O}< zk$k7(5_58SwAv+FNzGv@OtyI~uc1|bp*6YvPd6%^sFkJZRhU43XbZ1bq+fhH6OhnJ_r78DemG6v_^zSf5z5xOt+zMqjL|&CZpp<%DUtE%p?@D| zC!v^4e(2oxGbFnqq(N)hmZjT~P z^(c@*`>Ks;t0ZIl^6sxP{_v)8sh$X{e?AeIoHMPk-2I{_*f}p5RF000GaJ~3v>gA9 zDH(T4p~AQu-Qu%dtO1_Djq!=0-*d|g+PW!)a=j7Qh;&*y|Gb>XpoVZm&c{g6uNyiq zV#?|3a^jcN|1~3`p0G2sO;;;mj+k$NE2UOfAeGnVvFl*qWcSQjg zv1LL$R(tdAg1a3hi3o{k?F{T$CtzziiVqOMXG?{8|wUih~o81q?4+#I#cJl|0}jvKP*@C8t{LWJ#9yP1g$T`#PoFy;hc)6|?5Fd<_c^`}NQXWG9fGefTZdMe$ z{}TLLuj#rLND?+efK>XVzaT~-_qU{#cQz*cA?;(HY=FwMD=Kegs%kkO5)Wu)1N~Iy zX{D6ZqvS|M-!nNjsQ&rx*Y=)*Y% z-sp8xK|NQcUsW@>9<^NB0hI6E;n4%@rQ;U1{7psy z(im94SiV!3mJUu>D%A9{jiSeM7gYvOkU>37ojwI!WAYYP{NdzIT<<43OOmTh5% zKXJ7yM?Hr{3n>bY*d!0?e|3k{5G&rOUe56s?J%Og8hKcMJVr`gZ1a)fKJjkCaEcPEILwAvLOB zZ|b4gkOUzGtvc!NJLLGaIMEz_lKg%DwpoCxiXq3GpxI81SfLK8B;53jyWz_q8o{H) z!L}d2dLhEkqKv|_FMq-FgD8@}^!s%^#T)k4UEdp?spEI?`<~Z5Y~H^A-x`dFtrZ`U zU9nbW5Y{zg&8dbYE|a?jMK3YGR?bh_uDGD*cgf#OIMfUrtaOy`oS$oHT`3j)N~2yS z!JX6&8TshusmaqBh?yQX7;;(lWUc?8LdQE* zY4xOSh%`GHmhVh)+z$+`X^R!m3q)ShSKu4<--A>f6nSdwClyzQI@BD26O7u1yw$d- z=`WO&uA7{Q>}bEzGE>6<{EC(HfAzscJ%@Ef$ujYg``&0xhN@%fWbLUJXHo`3^6b>I z9ZmvTm9l##&?U~k%OTWn3HSkE5)c$GDM!tZ3M7@QE$D>QlCu{rE$>X^$(c+=S*Fc7 zGBD|sWJeoBiX@xHm5|(X|3rAULvXbz^T1c>wz%`ixG};rU^0lt6x+zZ8GVWjJ(vS3 zFB97CXkQ9>20dO;KK}He-vj`$zxCUOYJ+bIrDCQIqp1a)BSUTC&c*vHvZ{07qovZs zdWtvmrrzDUXw{cjsaugeGlmsZ$=<)~o%FZ)_-ghkP=b5T$X#P>Ca=8R4;S!tilS!T zGt|&Eai~jtefsX%+S|=qGCWAl!!-8dY_Cc5l1YluPjPkWO+C9Mx_`3)$C*MxeN;Ia zVTm+{t^~wbKla1a6UX?>p9=<~eg7(fzERNiNBmt}y3jmHUBo=2ZbsU!{S|BUvU!Z^ z+Z#LZT4mwJPgs9m;1d)S(HgQ#j#sg9N#F`3mN%VWKl+s<@5HYMK4)m=#6Cn~JCGWI z16pIN61ar_p}&1G+GiqH>tmqYL|_Ic6D}P|oO2Js=UvZ$-<9}L!Lv0f*g61n>ck1N)ax+}z zkMB9geg2}5+`nijTl%aZm8V<0m3!MP(j8yuIR=WT6I?J}l!em&giDCD#OVXGOvSF# z!o-6b%IJXMJ{6i0PiZ3{dSEj2=|$&c0g=oRj-A6LflYJ!Hsrf6;Noriu^$W58@7OS z02hcdMxX8oo&%-L>kVs@ZqNX~(&yZOJnE@26*9{@xtd*~_g6mKI4PJJH@`OL`|(R= zXSya-TkGpbAEX1A?a8bFSG%FdQ~v{&Gsw+0^h_GsGzKk{+5UrS?Ette4DRx&bx%!% zHFt%O_k=`3{ZMRN2zdOzVrq?ba`O=&#W827df}qfI3bUipmi}q4Zs>YjWT`c3t8Ht zc4tK)6o++7KkF=78Yd{*5dIO+mmaRPMb<65KLt6dvR#|a4QI{?hn9|Vg&y)`vF5aS zvy0~!t8c%4j9t2=IW9yob6hfm8RN*cmuJHL(uD0Ssl2ttm(=k%&P)P)3|v;RVwtQk zY~SAem}BpLxFvrG-Pidu$$|L zHS#nA$+U(U8bA%Hj3n03k}w4z1LA!BEGo^qz()fw{#+u^B7bz%8h3 zA&XOr<}ecg9fg<2;%_8BY)MAM_C=a+rH)1y#_4;F087CFITqy}4<>J;{Jp4wG-fa^ zkWTLUCkJ{H2t0ZTJ1q#}&Q<{94&XVJD7(Mvdp{HZOW~p_k?eUPRl@eI>Z5084f;E0 z?195Ksve~VZ4m%VX88!Al_#1MdM5uqpq!CN*rt52H3&UV^I~??68?#4wpl(shx^-H zt*J}DkgTMFBK=+h+PwX;dFByYT!ODtWZ-efXF7Ez>q9aH98{kxI(^qu`Ny178X~i> zkv{?#L?HrFZ!2ic;8v&f)-SjNF;q66R^HAr;prsj`wgD2+W%*X6n&&Q^*$*n=)hW> zbux6-qEoAtipP-oW4U|^PrE;arhPM9INZ9w0ufve4 z!C)AH(Gq$Vyjzq%vJGE6Vb|Zs*Ekz#NhiiKPf}N_nmdC~DY!5bI@*t!kUqv-)oB8hL|das_ceSe=k?h?E%wemZ(vtx6FE{Ke4t6KdMg zuPQ~H(!N8V?&+sf2U|OzHNbi4>P&HmMI@qcrkstPP}_HiM7foFvqs%DkO1ZE9{cEI z<`cFjI}J6`5%K%+ALr z$wDT{BBQf6K`r!P=uU2)|MRTT>0nf zJzfuGb2!MP4rC6(3YC#Z1EX7xkGNQ!g7`jp!Te0K$<%e);PU5idSp34*zpH^ zP}Ld7Qn7AaDG*f9ii;ThYP^-+wIS6Fbs;?*sOElCsr~QuOk0LrT7$eTALWoSr-2MQ zSrxjQbJh=vH&;GTncTG^ZVqzNvQ&e@bzbrX@+5Sf`MAR=g_Fwq^OzM67B0a5mVlC) zC1b?^ILZ;{>1L#wq~i5xlB&#-UJvcVo>cBR11ZBCp;Ket285r~STN~$mex18l)LEt zPdr|NeD5#~8Ma)Q%Jf(CTCG%8=aiUn>-A>0=b>Tj*Wnm=E}$Fplmwl00@Xz|qm`EV z>BtrKZW6wBE+VHv)b%U=Qfmd9tU$8;`|Y2R0ZE>jNWFzFP@AB&ZxL9m55{vxdv~oP zTC>aKN>Wd?X+M~#=nCD;dgv8Cm< zYiX^7T?R~R^-?_21~@2JYb!=9w8g)K{MR<$l!#>pGwc__X7K#-^FVxlr*ZQiF^*>n zp@;8y~RW${dSQSy2Qsg%*?rJc%C?|%zK!S?cn4)mACc#NDL zuH~^uEt$-f^6wr`hoMkT6`_h&gI+gFCf^%c(eeZ8=*h1Z z+I4D@mC&ImhD|;>UE%I$+Po_Ud&#uk)(`m)$@Xb>G6LTl$l$?HLR#eb%k$e;NuTve z{+m@Id|6srGDM__ov>x~mtmz6sFRj{p+(huS-*XjzGrBUer)pymScu*y8p^}ER4cY z;B@LUBG&m%*s4o(@kGLL$Di;IHf7 zVM#Ni5$x)+fISpgs7QoAJuEJt8-H46`|V)&ENrl2x>sBcGm_UE_`v}00HU~WE+wie z{{&dgvop1F<>!sGk`^mH9pc zOoi2P5ga)TY|0LI)h8SZkRQJ2JueiXw_X7PSB{O|g$9YM1DrsVc?uC;^}oZ{^4q`?ZNtW=fJr$ zt~;#Z5dM5N2(~h`Fa4)A3p95oZ*y?+`}yZ>RnaBwPBH{uLVhbURKmPQwYyONohtdL z;A=YI^kQwrO$M)<;9pCfLGLO>J2qnt;}}Sxh+y8-!eIQ>WH)s`GlGsx+4J;_rL8>{ zK46Lf#6sD=E{QsfKe|uRb{!llm0hYXNLQ>kKCq(o>Auzv;0WSENV53T7j zD1Z4FG-jkpWksi?Sd_1Uj`71!(qKh;A%std+QsCBSkN-KUfhI=Xn`I#napgOe%`l} ztKVlL&}V-KKMu4=@N78^`~jo@n zDgp$f0%^*wkbsyYWmjs7B5F1}r~1@DIB;Q>l9CPrkZc$$ppi5Gid{bU|F{k+#kC(z8s5np`Wf`8U4tkDW7G02vT?hpYC%M@tkC}956c@Zxvo4Hzn$m zOS8WOG9EM?ezqZg3$r|$fZb#*z)Koi+kt>6NHO`3T#4$(A=zfY`e z%)VnJB+iSx3T9c+4cNV_9Cc;$Dr!BJ=*)|(^h*09F*W@UtM;5?S<+{ZIy|j29oo&eQE1Dwi zye>P}N~hu2gW+^<}3gA?U1xv*G_g|u2AH9j#7 z1A1ROLBSci1kGZ1gptiP-auaQqS}95y2HhW9u7U7y{!!IPe`+fuT&mwUR4fsqp3XV zc6}II;#tem;h)g>aw|3ws#WI<<>#=mID0JAtb%>G+jj%Wdzhb@Z>wm>@dn^5t)>k{#2PT zhHU}k>QE*u7Ewxz$@$mikHue1n>WWGToPX6bIe(p$&xBiKl>)W(~MC7&+g<)=MEC6 zgb{4yg}p%iWI7GjX`Q%g`3EUuDxf2hB2Nt>)P9Tvm-lbK(WWQUFcXn$fV`T_5iNJs zDM$?msp&0AP85gV;@K0b)a_VGhM}3ItR{>AF~mCr&A5pwuQl;LR;J89Tw`K^(jpAB z&>;7e#)Dq$+`op&*JlIt>4yAi>!8w5=!|THHcB-}%#c}%)m0}Sq`F@&0dt|xO`gy0 zB*iOb-6E&8jm8Mkg=r&4+u669PgDg=+my_RzNLPf+TT>%$`bp`+TZJcufJ>EK~@w= z;&Y6IkZ8u8le``6fIo<-MyFHFCN_A#kKnS@%0yuz(1Cwa#Z1WCo}8}b_Ql2a=e65` z_bzaa`3a^=^@&T)IW;<@kvd3M-!!mbq`8vyG`%`pGrXaB|pc*k$yPa+hs$z9}S!yA(AOJ|c;o>t1R9|EIA zU|O?~%8fo~JTLg%vaCMdj{X(;ROLUIHBS$jmlOftzE;ufZz-m!EkaSmJaUw-U!GZ4 zXD&DSITuMrYf>8ZyxHH2s<7jj8ayW4P5$RL_=!sZSNLZr0lJ8=x}2c)EDDL6`ZZ6n z-$7;&wT3G=$`jzj)NOLXVr#prtg@y-jn1~3q?O($fYhc$akP3WFWu_K=w;66r@SM4 zI`4@o`D|z3%ehZx>+>rro6rAL(P(TBt7v=;K9o2Qf7!YqshkBJRV?3sWz}575>=X_ zDhI})m14t--^fz#ffoD;#)4Ptj9)xx4!bEyL4olpTSvy0G018%FZJY1dJ1ro2GPAV z%t+J@z5#4+jovluD`ihG>lsV_^t5w;R{AYjFjpqPVMNUEmcn9xUFhq0iO<$65V}R2 z)T@`;35^K#mUutFj;dGsdXQTlENdrB1>esM1bBfS+qxIb-nN;ixn~xdEF4x&doCB% z2%A(v{OI;<32kfFm0>Q9cOIMowF65&MfZ zb|u?&c(46WBl(2JJYdtcDSK^_ReGyMYge8s2|Hqt+JAVbz-$~OrkjLsWL=!;&x>Ze z-nRch@^;*mJVAk0{fGOakQrRe$_8c32UC_O2iUE;Ki0$=a(-IA_;jO6qzMyQH@92L zU3ljcT)jGHsWSLMrusXX?cI-`FR2Gw@f19mWLuJG3k{LmrNj z%1mXVbH|k_?)Xb|7ExXAf{#G9JL#Rb)C;#Au1wwix8`g3kgj#?x^v>~-k&pFQ<9uQ zxT$}orf`4o>dmm?lE=>4+FDlJ56nt5H?3noF~V!?>cW1ie>0COxEFZir-QcIZ|Ag@D69PUj9=>E!lvGrVoYr`F7KT;?TQKtiV^L?^##{vfz0&&c z-{ZDzeU1+Z!l|<=4y-OrrP&U;Ils+^;%SG78I`k4wOqQTXjrMKG~*bszaX-6C6fNS zd->_YaP-IFve(f|J0G?3f_ab6Wz$QywXOFhW*fR3CQ7uT#48jJUV)3q!?3!?De zO892ONOA&SK3%gapt)`*UGyaaW1Nd0m4xw%BvqI?v(zy0#H>k8T;e>^bN z!U*2DmKq7k;W{5Q%6o`Ar=ataQtW22-%xK97b>qQsbgVpD#A741#rSj6?LuY72$SI zcKN)yohbzDm2VCdr+CF`J3xD7ZTM?ZGPslvzF|dz*Y{4jj`6BQb$NfTq*0!#9mT4< z$2Shs*3Pc{{)lg)=s+MGJv73(`jc8{aR~m$lxg`X>!sLwipB>T=al|(QoFGyl7T8t z=?pfpOf&+Uo11o5$40v+wFjSkc`oeXQqY|*+i09wqHkY5N*({v<-+@=-m|`LEZ{|h z9JoCZvZ3IUDn3or~^t0eI7QdVv+PglVJG9=uzLRz&9L3Ey;R=iN^+C5FK z+?jZW%$|kb(+cz9-Vmz;p94!~7y_|F3&Qj2&bDvU=$}O6t?k6g$^-`=T{ICrdf|6T0%M=;4PThyv! zG|oG1lz%3HbctB6ypuC$75M29uSP7tjCF$gZ|cuoj}HimtEd3E6%RJjK3PXkVMq11 zw@HgE+@&sUlxNJ)HUt)Ngo8!toC*0JybZy4d0z&-x?tZM7Yb)oa-wX#XF#elzbrW? zF%qm?&|MP1{2iiX$#~+*!5)3Y30Zk5*N&;hPN%!oZ4aU(B4FUJ>TW;yGaEL^ z>eoXex18Xt$98;rdWz6q0y7rnmg>gz9LUZaM@eD}lpLVa=^$2L;S^O#_#Iu^3R)iq zNC?<3_*QA6Z2b6+oj*D~&R4IP-qNiaFRmYh$<7mmmmd2ZP_Ny;<0$soj^Rz3Iz~Z- zR-JH*+mu%Qo_V}FmXG($f1hPw5`@rc#Ym&6?r%bcMW5)o{+*%ch)!!)IeHg3@fIUX zx>`MoB{9MaPE#vLW3g~NP|Lsv4NaFxPvtIX#6KDT;}z63YG*iau|)U%OjXeLHqqQ& zeQa5qOl0s{ly+BHq~=pTKw>?mA}Tb%V)LtOYJ3d% zf40F0O5m;4qPxXCSembQao3I@Qc=__mKM$18I)}Wzh%9wuVvp}%bUawBRIgZ`z9Nv~ z!WgG|4tCsleCa{yK;WLeL&6cvsFBxb-7c5CD4X?K+Zn2%6!P!80OB{SYtNSkHxmi$ zJUq115#jdiX-`IHbPJI;-1ciqc4JyT?70)OqbQMk$!ai6k{q38u^80f(wV-MvNJKJ zsh103lEL1$Xshw%AFu^QsKigJahGzpcuX^*(Ht&0R~YjL&-e|R&Rbc zf)hb`m}9^nkCtU{%{_*o6mYX?$%74ykjD2vBf#gtT~g3>Bx$5HO{T1-ExJ+um5t;q zeF3X7GLnCQ8#emjaXo?OA?5bol~BaC%jpMgf$@$PmuV|a1 z+j8=pxx~ZR!QZEH-5-Cf?}&b>taQWj_b}OoDBa-8pnVY0#jO!Hdd*HLSa22x{=j{^ zK0*!dzV!xb)&(OFIV)+bSQMt9atZL**#ItL=FsI>5BJEWdrPZ0D^$bfVV8)T?8TN^ zLwD-qc5|7nO?T}8R>z)N4lxMlv>91Dug!KLfnz*}nHNQB52~&b!lZ=^8C*pA8M~Ne z^L*XcA0_(RK*Dg0^vBo|kCOBXy^3@a$RJ|QPh5=(VUyvgAZE-WmY<(H8z0auw>nL~ z;ta2+QY7RwAZSA0uBbhi!A(U~LA*D3yqQf*PVR)(EfKd>(VbDhedV_#(tGucL?W8C ziA}fu%jwqWMufm&JJ8kSo5sGO)|{Pd{PB8R$V`o=b#cY)aJosfgVsIlWB)~0Q$+DE z`78^WvCf^7$;5eKe@BhcHMBRvW3%P3tPZng{Xpa$9_6q6gto~5sk@Um7iQ53?bl>5z4(Hd{V z<~l$y|M^MnxhPXhHjF^nRVeqEEFj_I@@n7#Rr+?qk8^hlM@PrRA3qMShIy$axogrC zM9b~ks2_T+4To^jI`lMr)s+nZJ(Ucbf}aNJUp7cj;M3HDGrI-kc@$`PO(Y~FC;!YK ziHV8rCmVef+AaS2FK-d}59&lK%WbHk8`5xDtI;!O*=}qla%ilcQTbi$^>92J6NFAm zr0d^N_kaACbnt2L)8|?^P)4u#GK{ZsxtUJZE=jz!47i!Na5Hqy(ztt;rV4(DDVIR~ zI%$rm{O`s1?KhjKQ4!e_p&74(tPCIOz35ZTDqG*oLNRYh^5KM3sUH<2^;ApL^GP08 zGd}{}FESiHePOT|{sFie9WaPw8k?Nb)96DZ8s)RK`ASZ+{4KadqExm@oMF8`$~f9; zz$m3jP0!vir!y2~tr6e59Py{X zWhBpVE@l1leOUbrn-4DC?RcIM8N??fAZENydpY~z_1D$Y<|~^N23HK!G@lmK*w(w> z^umY;o`;U^I(UUX)6)B&XRQ zmmI42ErtJ!#~^zUJYQCUW)(awUGHzf@4`0xJHD`Gk9)2&O%l728u2i>br)cCwlF~b z6kE86$YqH_WRzs5!dIf_8dsSlaK<7^MgfIlL);ax0X`<-SS`_wILn;1n4#4Gc%9^P z9vJ_~|+%m`(}pmqtG^5evUHN~E}@d|!&;QE(5M1zPs<)IMF z+uqM0j&iV}LuvQ3d)IB1%aYD2#gFZRF}GfFd-67}kMY43R_p7YYwH0*E(7q{6Mb6g z-Giu2O?2c;TJFx~$S{s`N%${+*%jG2|HE|tK|2bQ>agkaz3ej>E{nR z_hL}4v(y7@38n1ho!@?{?gz;#gn>~Ya$4~7QxqI$xkP)vzI*vGa8~Wj8?3lm^i$%G zw~Q)vjEg>B_iqKJKSv?mdX53X*JrpO_{TCOyLC@Z(;M%P7suAU)pz3RE6~@k_(HvFVlQYeMG4ABuaYQW+4MF>WG3qJ;lN>Gusq*z(3UP}gU%#Kd?x8L4L zUjmXApMfHS%3vgP);#7_l2ZruxZw-x+MVY*27R3-F}CLY5~V+D&GajeU00nmyiQH7 zw2Gjw)mHY4;c>gm-%y}6q3ABXOg7K6Q50|u%w?(>s;8k@xH`~EroVDU0MPwMH+Oz{ zcI8_~hiDFA5Q4|Df1|v=zyHlH#QD4<@lvi%hW6P{fVwTyI7eOU;G24%;v~)MvjsvX ztl2|=WT5{RL2}NPDmF917hS7nT3J-GFEz0Ch;Ujhp_0kihc)G=ekgBI${d;l(!|V~3&+mYLdHtV!K2!V~ zKRUg^UEINBUBiTPIPF0fzdEm`OH^&JQ2OzUJaT)=(emCz)ETZ&to$gg?3LpA9}LMb zi`19G;Ys&ge4o!#`NnCU{D@qUpA}U0mAj|c@e1yw8~@GagU35!x#{DMt`rz79jSTA zst{a4C6!pn1sa@;q^;FzE7w+1!tza5Uc_`RqZ_plw%iio)@mqE0z7Ut})2v z;E#OhhbwtCjQRIx+Kbw=Yu55P>d-tBusTi7;(S&WqVS@IG>D%P}>kAVg~(32U#VNYt=7hVX{NV?Z3R5O*jSDe@>i0ZPp5-K>QF*WbIelJ5QeaywhK1O#N*S{u%!t*|a zH~C0G81b$x-3QI%c5c={%~`2N{eU{|$&*5Dlk~mTDQKbXEvbkj3dq<<17od@EnqNg zgha+3i-W2gQOYD7*lS3(DxCaJapRAXJ_E@)ADr>4Gs@A^8m(0PFZ z<85ZFs$GHSE)iz{8dL2GgGBT&&wH{q4ShG1@b^gns+D69t=`m`TYEd5{qgTq>i$;m zL0bgXiE1&}b7vjHdP(k!5- zH%ry~i$ylpm1`|lmVNblf5pDaRM23?3Z8HKXFTB*8dpt@KT?qBBUr^}6d1nh*?8Bl!Pokmy{QNvq*@&{N2u6TK(fVPZTdj)e3xo8$l6Zf# zwj(O4q^eCb`hk5+gG-hfZ6RI#(dj<$PVlJEmMoB4dpkE;}g|}evrff|_ zSZ~P`G`|gnh<<=4wCMsR>X?@1=qb1D7wYd5m+W0Bg|x*m%-V6o+rV@po9KI)M55;e zzWurb$Tdzk=19$m?n>)DG+@y%7Q)ibnfrGOb}Y)tyWsZAxIm$3acaf424K~|m%u=j z7yM3AiFOkxOIwYhZ^zw+Io;A!8pWtg>;%~WK6BTVnIL61mPRS-r!^2 zq*cdosT+Y`Gv_SiGz;CO+_t48M@!#@&>D(g z1nS0HWT5D|PRVmZPGa-~p@DTt$e}?K(k}DI;u@<{JSWE5*G|`e&Eymm$S)=75w~K3 z#xhe+0u{&SYjM1{VJkCkK5LyQcks4*a)ebt0hwK>E80sKabEpP#w_zU2%mLr!^U?y z0ahtn=T&^bPpF&aSV%w}LYKb(ag6+bJ&A^*t*MF4f?S!&6Zuzfh$m!8Th~_?AZZ)L zPbTl}uEZ!Yl{VZZUroL7Dxh|XLFxG8tD5#-7CeWI5c}~EHRZSf2KL|-cEgvjv&e3w z3P82ZpO))gA_$r^`e(&cP~&|unj$e+_N3E9PFZBRd~73wYyVT_9qDPPG0Ny$m>3Ap z-({zqTy}(ln_eBwG8d#Rd{PFw#eH0f0$pRF0Ow!iM_tXL51*yfn`}0q zvOm0hyjw{+{H83QF%88;XL?yFgCe~|hmG4B^4sfG1QMfWhX1eJSLOCDF14~tGz4-E zCk~^Ss~}m3vn|eeg;PLF;OUI9)E$cX50!$@4unW-PN|2hWknfv)}4L1l$=obnK->o z6dsdx+S%pbA+`-bBE0&Cd`{)F@BGr^zIy70k4CgUc+nyrKNiwt5CT&{3`NMA7e(5; zZog>UI1k+{+B1(r=EVky+|^8`?JI+kje^S`yVS`68Oh`C6aEg6JRfBEgDeC`ovR5i zcbTMktn5K}e`KBIbt{<3-?2tt1ykAf)&+^kbbddWk)Yu7q?$7AW@W%sYz)JV>3JEzXy|u4;yaF5tzhGgHZ3m z*i-iSc$>hC;fF%zo(0dRmjXeoF@y9I^lEy@*nZrT=4WI;kz3vv4BDO|x1K+v-Xmpe zn<3h>Y1LsM6dpDETiFwM)s3s{?0_ADG0CIf0J15pVu@!}t|wFSyx&!8mMADGEv@JH zm>ru^sMv-Li`rDNJREsmB$joo)$r4G-z4@Z2Y+S?!#GG5RFT@)nvb94=H?zpM}nxw zR@%oQ%IoeMw1J2-V7Sgt74k0@Z;ht+b$26^tYyQ|QckUnU+U_KOC418Mwulrll~;< z9Hq}PO#P}yn1syEQnp<9eU!f@mK1L>KmU%KuxrR{3 zS!hVc&}C4XSS!Iynli|&g9N|emTG+0jtwKT8U9e9YOFsi6(Ik-6WLP2a-i^bDm^&0 z%JKlNV7`Iy@<< z#C7K|-9r}+U%R`3-*v?SNJCsVlg!5~xQ_w;+{DUiupynZTczw5-c!L#sR;;W97N>q z!`nsEK+*oW=aYDjWfXy)S~;7|z;zpAwh1F-^G`g6F&29fUfM8T4>j^w<7MgQopS4Lajtyv8>eC;)ubSk~C1h-iw$YozgE& z#yLg1J5+TkH^V39sN_26wM}i^XTOH*vT=DlX9^$=V->2of!Hsh{GJE2q>voty|N(V zilBo7vf4W9K?w@$W&dv-pm6cEZ)B1v^Z~>W<`s;s4fO_rG>S28u4;bqR2+itM)|c? z9hv%!qk6Ze1d!|pff?qG5tkB~y+L;`I@f_Po=ghn7vXw9ZlETrGl zN(~EeI{uHSw+zbi``U&tx};OOOIo^9y1S9?2I-PU8l>x@ySt^OyQD?ByWf-F|9I~X0y+|);iV^7u*Ao4!i=3e*2{4rmq-6#}B&%a?3>D{){qr|L_rvO{7uW-XVEw ziA1v7S1EaDYjSO{z^D)uZyqU&RPV7~4E0)tw&XnIugx|4LS6}QZh`eO^|B4?P~Q-a$hcTT=ezlMzG(E=crR~I$Q035gr4`<>~VnPr3&Wv2lVBVhIW@OW0;TP@j$B;RnDo*Zm z09e%b9G2J>hS{SQ;06PSgGe%j$kc*}F@4B9(}S<7{U-j%imcjej5~E8>rrKHVX=B} zZJV1i47YJS4YSU(U)YM6kLzQ6^Ys3XKW)4TQd0vCl{AY7C~kU+zFN9YzI9Cze*0U$ zg;vh$CRv-3^w_K(x3ldm?Jh*!Pt}eD2gs$fzV(qQeZD9d&!ZE@(?Zp>)pXp6d|^Yb%*4 z)2Gti6XiiRYHV^*DV+V)OaBpU@7tM1{zI#o4u$N>@({c!GT{nJ+w~@LGll&K436^> z%9enEqenCz;cqv+{KpwzS8pC{QBk)H?jB01W`tn*;a3#5_`qsM(}~62-rn18ZE*rL znGne`ZEVeEy4fMZjG0Te&&k=R0ACt{e8X&wdOeof9T}dvzJqzRVM8u}i<_N`D{R%i zJ^G{3G*f>*LHBri`YB$yp%+VqjR{%TU zxE+Fb0PI6}xU4yx9|ua>!l6&qJbt`FIQnulbgf_WkunAXZWiCUmVwrgY)*#`Ima*P z*)0k9i5=MbxihOleX0{jpHg!lF3Z^N0c-^C+@#&7a{=gnRj3Meb_p3`!EyuK^qEUQZg(|@TTkt|&w?)ax#TO0nkGNjsC8wK%mMEs+xI!&0@W=J=p)YfN0g+G zNe`QVN1+PmfkFgquAN2ax~Hwu8Lbch#ggzzZoYjYWNH`c^}qs@>S0E{{p@`INp-CAi5BMA#ExDRqEWqh(*j7{)oJs z{He6)mkIp}*ewIH9XzB;OkS?JE>bxyykR%)Cg7# z@77{OO`DZ#Lp>AaIIaeoG<#10QUwUz%1|SBq*=J;_`X$55W*d@f|r$#FA6Y?t~vUq zzq2P6rxl9kggtC7GLLHbeCOt4Mrzz$!uwgO9IhwwR|FjIVpLRXN~7Tyo{FHBx%Ref z2|a_bJ~Vmh;T7|vW!Zmev5V_#j&^dnsDbHLJ`>VN-miO#|JO8TNMeQR8Bf&Rt%<;X5iLgQ<(fx5X-uAO9~D9;9@x~ASZ z{eU-62*>0Kal>>PzfdLoa?6mS<8+&|TdA_kZ&Rmwy(xTB+NeT$TbpuBB{ASU7e=(# z>+<;sa{N1tek$lHY*7i9wi%6b4*k#4y$;f>!Os@XKn{9KA0|#qkb#M58)zin@s8G& zI{jvfK<_0=ux&5&vU%jD-@|SSMBMCQTHBZ9bepW(j2829;iSK{${WhiZGt-Jz8ae$ zw6zp6?iY{7Hum8!l#S``0zelHY)57lGK#UuWvITG<5lhGi+*cOHwXdv0+__npPy#k zl%W--PhBdW3|V+MPhZM>3wmw`Aj*>IVcDQe+eKgP?QM-cDt=6le5b8qc8ih7_qGv7)+HxRn81#7L z2GoLrS>Jux6FsY@<|EpajKC9>Rw*J}kd`4cIajLPiSFr2wMM1ea#LMhsIL8T*l!K& zWM^@*xfQOGUDfi1a2Hrmp~}ZbL^6;*>dMmT2R%vKPsz>ULmK7kb4PA!&A-K0A$?K} z4{SeQpZO+ok@3a#E-c_2MxBv<8?{?{G|F3>0DhkFCA*|P)~sDpTWg$QNSKJVSrqK) z5pMDp8;-GdD<7=_m9K`Jl8C*C1G1=3!^aCQ@_zs3SaymNg8W9k@1 zF5+hQ{2XrSczry&?-P0!^SR#&^SIN0MdGtz@ElTVW=3!q@{0aDgDxlZ?UWF(dWwt% zDjm1eHZ)+HRXxg2=Ph@9Mxo^*Nug)^9q^q$MGAki#s}Yy+JA=8rec|NK{${ z&;3%dc(g?CFaXQjjIWEgu_FF9<#_k%W`v}>w4_BtylMvb^||R+0aQo>nLW~DG0~*; zr~USZkdYCDf>|q{`(C(~6AHNaaq}8ivr-pHnT>gC?80qWO~WnU$0xRuJFahK4vWfB zKa@*bmP^<3eptEL!Gxq zsWZ|vyy5Dqt)B73;piW^bL2~@LkYIKjX68%`f0$p*-K{{LnuOpk+c{h(;6hlS(-Cf zZWNEj`F#K^{u|%~vI+=91A`A5LNSOEV%cWiwz%VN6|M_kNI{Fk)vwkM`eNE|RJ3`?bV} zjCtbmgi#NEdAP#YRjNi&ly7{Ke|DCEuz8@4=Sd)lSpF=+EXLj_7tk_i+tB1;a0%s> z2pC39pkGX~i|^4g2}F;kOM@Nt?+{3z$hMJAJaqVEWyfRvi9I$U>;yr_wSOftnR);H zNg^uqFM5s>nBX#0Bh!%_!4e-l0_LatMgJE~P!Dd``8#A7z7l$Jk#aKGd_$3e_!Ii) z3FmD5?f=>;#>jh8JYVz$kB6dapH}aE#=|Ih8($pHFva=3Q z>?E$qiYzc0PS&$dPVr6ZqdeR{&dR@4t^`%?L2fAE;C#T;eMsh*D>pm-_!8dE%F0e6 z^1JQN6#QkS(NUc7NecIe>(6z{MS-s$+Rc^Wum%gG)G#4R4HehT_~t%?$}%$WR{VPu z_KFthB1qL3{|-Oon*7KtxS2HRK1R-Rv2UCCd(kxh)Tm4d|7yn+-|ev&{U>hu$PhA` zwBz~`mQ)XxEZ;ZOhARSE-}Jj8FDd396*^vfNPZD=qCiPan{jc_d;xQPef>N6p!fS4 z$x!O~fGMeeGa7l3?Kf7Gw$+wAkIWwgnU zXwKFW5i#8qNx_%o)HRrPSVRlG$45FJyw|te%Dm)|N?KZVC)}Bu3Kzgh*A^y>rlW%Q z@AgMYya;(g{J7hfk5A5x+RddVLdkHv63_=%Y?3hz{@#xWzKF%5rJgUcDhD@s@XXz1 z2MSt&&})X9u>QRB^3#6ew%9k58dDM$j!{kB(LM1B3H@#Xx&yc~wVG9Wy?~7wi-3R~ zN8FwlA*O2|JA|3dgnVXsm6WWC5Fi%Ec-=L8g#oAu?`-Se61=T70#*L#_s%acW3*{j zcFT}92ByPIDUn77e5N@Ta=)n3e)bSUa?Fami|UM1LeJmBD?TYNk$0H-oTq7?FLP#0 z5n24OlI{4E9C27EeTvOTg)8S|g1p=-$jb5KZ|VnA*m#2VPv0C{9AaK&2Sh(78!*j& zV8NU@{3tm(p<_pIbVQ(KxFOt2Dl(%G%}ExAFOSV8E{~6W^Z&R2`M*LKyJrZy|C~#G zP9_crbed4}YKtI14i*=VbS^&?$5LP&uEtmZGr`0vl*EYyZ>-o@_6zIqtcUdu`z1%; znA3L-ceP0s7uc)Dl8bWJLSj=6L)*GiC~*-9c&Q!Xw)CEX3lix~zYBpOm@`CVbh^t# zR9Aa7G&ahbN{HV^4PP-p=Rmj({at0^Ts^}2oHd(&)yd*=7s5T~&!W5|UU%Rgj!jPP zoNx8%s4MVKc{0Xi=qAz=8myW%rwIdFT83?zq`Aw$W5m^8Hhg#W&S2{mH~2X@0PB}2 zO$#O!Wm^uAaVIqVT|!H5*&&)~C-|coxxn|Ex*PgU!tXxk4U(=mlo=@P3n(hp%H7a9 zyx|XJHv^Dctu%542#MBUPnKDE=Tf!xUyp;Zmk<1iAslMu*ucNQLFnna`VO<2SSiB= z^z>Nw$~;~cS0stFz0vV7CoyKbCbe(NKT@%Dpn|$W0JDv$(&yTJm-cS8a(mTGqD(tC z;q9-LZFS_+JVNx0F#13|7Tg7Ui!=?<6cJ15V*9*&6J!Q;caNI{7}__nXD0`xP85e% z8e=ig`J-XB|LX(5zR3zS#ZILRu$_>vUacO*CF!kSkXURVzxwz7`mNt}!GZ392)sxD z?Z79ivCDjGTZnd8Wd0f5vFb6*go)-^WjvntA>I^`cbF-s+6v*hA0TLL@Ln^5dYW;& zD#h6js&YOESBgU_u2vl~4BULx7NPj_lQFyJ+GmLpiOOf%A>F#H(IBKGwra4TQ7XOk z`uEbeQKE&m31npL0~#fk54+BMZW-H$KWWDRe9}5W_Q-}dnR8&6Dw@I1ou!X@-b-45 zxYZsSS~_6+sheYwtNM4C=D29uXNtx|ZW7+#*g@NhdwsDAQ-cQQTa^t=%FWW)tOaV4 z^a4;jdi0#wuB~~5H3;lg>{BgEpeiWZ!!zbU-~Cr>?A&5=%mJWW*IG;x6AE}GwdO>k z0vR(ww&Zjlb|6JN-0PZJ$$v=sj;?HDUYL!h0K`JZTYj_$Q;v*k-cgM z1FcSe@mar?Zgklt_++ZFTfRjurGx;dZaDtiG?6JzD^2)qd8)NM zKBpq2m~UkTv|;CG$O$$!G1!8cgNs`Nl%g2;Y>#}yV&AFfCK{t{qCfTt}tU!TsnEIq$g{=LR#p_zC z^g_wuae>`zJ{`v<)R`>qNVPEcb_8&b`UF$N!nh>b za5QLV0(^`$4yZ=$mx41;LoBR8XHG@9DDhR5K{-kyKsqa5cP1Mx8Q zyi$b{L9`H~wcToK)N9Zcr<@3>cq9XtUJwI!{!w|lC`Ofq&KRPIrUTlpnbLwI_tHzv zY50x_zJylMS1bM8Kg%6dNuvd-U+PXISy(wEcR3<#0*AfA`5eSv)w!bZ@JJ*j`gqv6 zS9_+2NwZ+fNH~>RRmA^QefUBxsiehtykwR)rVEJ--%S`cJhT~-Rj?kvRs@Wao#iK@ zc>xg-2-{6x@&nb%o}^a_Q7MC=D5w3jZ>OG-V(PcV*yF_NX%MpmelokD!DSoaoVAo} z0&EJ8{k*VqAUDt$puPsQFbj@Hp+Z;_IqrsyUkyR)=|$!H9@&QtrPNzYZe!-$Lz|nM z*Z9BrWeRv}lqh2Mx_uOKy)gqb<3cZ)m&M4EFxxkXS%j;KUg*-SOF@LX!v|gzk)< z-6?jmJVu+)7bvbUMHGH6NxY@q?+a_H5cDAVDs76R_|!(0Za1R2#860amA>tfxt1u; zDT4TSxs7B123Z{rN7CPNL)eS;R?nhs=SHOvk_kN?CIuCofVD%RabLkNJnDF3TzQ{+Bk7}xVao%Bir z3KiCbtXo%g6pzk2qz`1zhH#O=&_o?Ar(6kXh z<31X)@WlA|R@c+132{DB!6r>q0sM15x-tz|YnV99A+>FT)hn3BvaON?6pnjL4O)^elw4v?SM=I%<#j&eVtE#U`rd6#+KFg{XW1~3@dc`6 zF|hIE#(Wj?W5KCBnVSV->8ff^oM1DC79<(6lpg-aG_22UhR4i6G-z}*^4QoI+LMNK zq6wcm3KF}n=d($p1yr5YosaBj!Ay5$n_~C#E;9rONS`2e5lVKtwll!E4{PE0b+w2z zbs~1H<9K_loyoWO{QLFD@QqjSB0|x!mhVHB%a-x0_{l9O%djm1bO3l;z z`}=8sa&afim)ZPrwjLoBFb0{^3rNyqQ`7#=iOBd;+o2u4hALcqf^VCR7kkZ!xPJZJ zX)oB8mscdIIo(v%{!B{s0IN}21L70-kbF!x*B&vP1_RPf)vK}8!1`0_V_vc6vl9j`(|P<{g^En7a?=msC56beQ&k-Zaupl& zo8EXI{$rTWS|T4)a_`VI*!1-}OBl@zuvFaQ^+k94j8d#Fwwaj0DI_@~A9L(xJ7Kw3 zU9McaGjNibxQ#ivG?*y_;s&~OPdA065-UY`1ytda1c3+SWaAe{rZL%e{^$>cyoWeI zafX@xHxqMboTsviA%;gfMIbV0gXMrI(3U-E#AZ7)A!kB ze1vJTcMFaQ=(2rt`b{%^MP9N&iG&>jIoYwF%1m&3|1S#J&{w>Al|*=#(Ep$?<-GIE z7ZvobnBu=2rr?yb&(|C>kXV!ZE^laNYg$ROaP{N(CL2Z{kx9d!2}>^mTzdC^k}`np z`Odds`@$|Q)(noo5vncpNr>1B?>F*^+KL)1cYVtJtYOY~OC1zv=Wflptmav=AgH2j ztF7TlOZL~o$pmv*q_;5lK%0y!Ny4sNRFiw4Q~_^CpZ;v_o@~MH5&=Is=r<63?O1X9 z$qq+p{g4u2rSw{=X=KGl83J1YS!;zMTwlzRb6QOw8b*Z^^H7(@V=&^|1p9>KJH>G7 zl%l{12hTg#Wy88Od~BMcM6akk0|eUXS%9J|*s!EeErU}TPnRcS7wwqW@k368gZ5R} zU0Be0JrmBcpxe0&sU3pb0??9B=FNwuq9D(4M~9=`wdPd zDrPtmXGBclryESgT=~#`H9IlbvyLki`?dpWpWFJJf%jy`Z9&0>noABNMyRZ=>&uqm z75hj2X@R1qD&6dSlC}w@^cn{R_FR#s>t0?1mW?yi2aKU173oItI$wqP>(|4 z-iS|0u6{G!2bIm$JtQ4aXco{{Tjk!102@xs5}&OZQ6)YEP+A;IOBL@UO777S)(R{2 zBJtkJDZtrEkJZMB2jmA%=zXfHdSM!<#Y)^+gM${cv^k~(%CsC2{nH3x)>Y8!-*45K z4v;j`c*Rqg^daBZboSx*XwBp5jtr;e|61&rx{bM%??ytH>s}(u$PK(tI6z7&+_jtS zV6s47y=2pbp6G7% z``oEP!=I(_z=&1nP0;NmBKk!DqZ8;m!bmEfd$bIvSB3_26IK+&^rQ()pUy|%vd)(c zlvgcXOhJC3nch@*DAx*Q95JlODv2Y6}pqB72+1?WgCOKX^NzSxZ+NMn&!uRH<2vcs<^?Ykgs;n9b9WB4CMfdEo1U z$Jxta+(+R)l;NO(TI)(h`DFm?kD539`0Tr1+)umAY#p)X{!xj!J_BOAyC%=4nYEnp zM(mI(_LR1v@Gw`l+Ah27v$mn^+xAK~vqM3}NA4kLt=l6RP0J^K+*-!K4S1>lfIg=i zaC?#`eSi2Vs*;^B$HMNX-olw2M7c|B!D=dq?&a25FFHm-Bqx!#7GIyhK{cDNwiO0n zDxIJY#<&BhZeXcqbOG?7L|ymbn!T!>`hjg3STxE;@(j`KTJ8fE#=3aqDB#zU{Et}U z*5t=Z4Ti5q&!lCaWUWh=UB7dgJFs|^wd`@+<=wuEneS1lQdSm zl;WkM(_%>vc0?oP{s(xS1KW?mcnV1tg8D)EfL$mnU3OB;+xU4LixR z&Y1xTvJBBFE<>p!K9qvoBR+tv1vJ(9lCkg0xRv9b0ei%SR(K!kQpAI)gRmoZ+p;cT zcl4gdX337-l~BWPIXVUdP%-4}B}t>AaHz4^>Csa^`f|!|hiY7l#Ru zKev7)B;bPuwX}Fm>&sJbsEqKuZffJ#kw9F%c4Z6`=7g|QOHd8!;81;03&&FY{;E&9 zd@#~k*Q74Nx!Nt(uSL0KJ&!Ll0RGcU=nflMwDAf^eU4-27+J+Pt-=8M>w+B{Pc^*> z{+>mdH0c+FgzcwsH7}b_vMp+MM%X=Sydf`OT*bBia1hxv04>mP@8#z^py$YEi}CL; zuv!4GK`$=*w29dy>a-K-l0jO=z|z{c#Jgy~{eYXwEyErJZ4($rO&()9tsEAP`#&ub zb%MN8Fiwx*5Zwfvju3lz97O{w#tk#RQr?54jVi7OBwyR1AcVP%P}+IO0<{C*JEYj< z`*c1fhT5olRC@i%L=2MWxF~ne{xSpx)0!#ZOb=+h!P+W!n3L#!{99AIWFVY^pm$Yin8M9PP1D0SPp-z&KHu;8zgmELa^4}t2nZG6Dyv$5jcInMiY&q#Cu6I{gZO_iFo4kSeNgK1x7a3dVkml=XL2e{sSF( z-W?|JX0+Hn-XfwHmBOxfG|hY}%P4Nn^AD(jlv;0vuYWgt!|O^lu|$Q>3hq@uszx1x zol8GDW&`uFb8aa50hhVpufsyXGNi&z{)jbWoE>URti9b{S~ZO`BEmOc%iyotNQ;Wc zMac{NUhhEpVnD`VO`CqNd1K(}EZvWvvRcIHAnV0d+%ENu{u-$=!5NQYUR9{3ST3Je zu6em}wZzeZpvk5sazxGiINguG!|ij2 zsOG8lSbDOTuDX8DH^9~W6W1hRcq?7Hr)4M!cUTnQfgzIlOS-?ihNMYdj9u648Ogz- zxA9TBKeUCkSoS87X;-zOax{f`CohZ`5@bhrV+(`)O_i4?h3?}wB(F5QXwk*zxT+0{ ziOlyrmvg{FZkzdao7oZIBfq~CI*(9eV`6`Nr8G&%SGAt%;c->{!VBUtZ;~xC?1z6i z{BdgVl$&d5hbkUY+?iS;W2j)-Tt(VwTJOf{rG&zzjEio`8kYQ3_Il`%8Qb)={Wfvr zp{8_c=I`im?{``TMg(_7nVbUWglj~b#ZT_^H7AX~;b=9RSlNxgtf^_~i!_3zJ1JY- zWdlT3?31OsUUpnS>v1Q}U~ z0Wva{Q#qixoR8iV(=w|{Ghq1a+ds@r^uym8_0e0P6i>$N(=0F!ayX|*l_7)dau zl409+PuV{F`2lvF8yZc!ckr`|3dSh(le62`F(0{c0|u7OCAt zHH)z0Jwgyl`XyY;Le+M@v>7||-lYUq-ly3ZYWX(X614AOAXv z@K`P=3v9pa?KmPxnaIB+Ghn5mst93BaxL2yMY(PtX6zO-lboU-1G@c>N0V5hdq?Fq z$Q>;jLjx*MZ*OqpiRD^wG6NXEn-5$6B2^p+48~PVTQRk)x#83!YLKTN=WJ=u9vD4M zCe1$&pG2g6)<=~lgBI7cPn~J5s&?`q@p8@4gnp7eVl5L&pDZF-(OJ^d>p!1M(xE`F zC@or&t2rXW{9$BgQkd-x*t`I{UPcFozMn0**hkzeO|)`w*W2)n%b?7op5}>HUu2JR z=+1YcE>Il-O3;)p8+l;&c_3bb-6EH<0*&Xd)d?UtB>a631WEdZ_aMl@MYxXnaRWR_ zQsDl}ZuwgI+OwalPL`S~Z>(M$vYQnECK8(kmqplGrP6Q%N~{k<8a&u8a8l^@ECtW~ zGRFy2YmwK2(hatB!EtzD?{AKy?T2y)K`7y{Bl5{aYB-&}t2%k(Q8VO{@SG6TYOoMj zM4sM6yvPSy4BctoFJo=;*<)ddNk^Oq(37pw=e}J_J@YzHP`*9FBypqc{sb~mt*}a^ zkgIN_SrcC!46iozDkByD@P=TPVkwvct2H9Ud3z_DDHZ*j9mZEg!lNFT~$67Dd z5=CjNd;tdNTAar)5gtCc89Pu);SjJPvkn2@vF&yHtdrE&d z`P?RXyC8u$j#J11gr|jjzXuxSC3C=cDv8zv7~9zb;>X`S{id2EdUd=P&h8@0MtC3- z=t@SePeL5{sL~pQY3K$B@@phK4km_;k*exXQ-kSoH>a0O?}P&4zr$U;E}u2~A6Xo4 zME9f_c-Ws&>8g{aYsM=>Q3Et-4&~Xt3!kLO@iz9rwvq7IfQ1Joky0(tVID7kf#266 z2mKZ+mJrw0KsC#g0v+7Ht8gms%eSI8>Oa#tBKg%HK(q!gjG?zAJvx4+^{g`;aSN1{ zU*bdDR;#ku0rWLmY7OWgNS6jml>3jp^FeY7rv)>KFr~}}PwIza(qMo(8!I1(oIaQx z`uh(8g{H^%3ETuf5-o3H0 z-ANITGJ@PwfvZw&h=rj4MU>&@`)lHN_st&{_zkD``ZVG%=T<0?&^vT8!Nd0To`S$y zy$s7(V5da*Xo&_o5jS;Yd~<1u6(ro1IRtoE>@JbRstKwUo>*+p?I~ZEgp+x!&OGcJ zZ})x8YOMCyL{FQAQC?M(?oah~=z8Nul+9w*VyzqDRD-%`%7)ku$`QDW+k@#MpN?i65bK4V&6cEa2U~gF# z8Y~L(i5}IR#%L<>2$(;0@KPnuSMMz@fGzeL1K3787=&TjuFp4e-703;oo|ncfHF*4 zNm|it+!|avEs%;wFyJiAd4ch@2<=cvst|Y1aa-E~P@3_hU$OlhF=t625XqbCTkMA3 z4zG%e!-&B)4PPz7NPQQqI<49@ZvmO|gMeRcOH3ZR1iR=bpAXgkWqt!9p~sNC-({#H z61c;E#3GQ7VcR}B124Rsg2Hy~5OH7qq+ogBIP`5zMmQOcTpUVKb$5fHo9JC5uMDre zoE&M+3901?|8*k?Th||JR|q5qVAsjI+Kt52AKxc5JxHlhZ;GXwwgKHX9}K2L zD5_Z;+fX<$REgOrE5urVX0;NLVq({dPvh+V(9)3mA$w!|_JOFx3RQaKh}mJ00guRs zSY-fq$e??b5)b}TguNuqNTb&r0kdkO;V1}nb|YO+krQwZh|PF}B(huC0(5_}&^8l=`t4SXZJ!68>wvfkeE9H z&V2UxT7cX={Ak$!YNKk-W0J_xh3zMsyQDv-TZ5D zd`UVXxm3zK+zD`Gk6+Y0zm^OJd66+15V{tjV1-EeNKrKnS+7!hg_tPyEDiA?4g(%?iJ{j7+kef9&SvsomX%%TRIg&&Y`3$`m%Y{bgq~XlEuhpqgD_?yd`kdZOX; z-%}2@>IcX=Ke@!{NtPQti0Oj0UQ#|KHKendRI_mL za#|Salba!-9$l{ZAOjQH;-}v^zAGyqMuo_&_O+D~Mr@3l$s zJBFQ6wK&(m<$rjX^k2W&@PA10j{rcSsts-5L(pWW%r}y+;eMNBVlAn`;n7_s&04;{ zW0+@OgH4@bHro`q2i@v99K&+-|xTvS=}J%LiocB95hnIx*Q{DG?JC?tO5Vj+-4+6Z0)`PE!Ix z%%(Z=r25r0HCTK`8IJ{_0V5WfslZLD>~pX=uNI+#cXLO_kAnlNj+fijlM~9iD09^4 zC8NTHS%?Jr=>W9Sm_!CE$<-<-{$Bblw;a=z+4*Xz4W=VOh#tUl<@RJX3>d%xT3BF9 z>?9qsemqiB&^p^o_>YK_&CU@{{p>Sx$9PEPg|GmW2OzuqPeCF=$pp;V z1?S$d1|p9tNn`j5ZTXZ!jrTjgi4slpOUHBECSe3$4NIQBASJ@pp{=fNYGo051KXTD zoWMKn`bX7Not^6=6V}h4N`7Z<+aBM5CCsN_56GyZO_gX$d@VJ2@r5QqVJDMBgJ!xa z!{NI%7!AJ2Bc_aTkejSqh8}v2Rj%HADjN%8#-5;+U16XKop^~Ir@HlgBh_3a91Dv( z+WdTB){d_?N)Z~xu62QXf&%#ufEy|orXpA3tN#})A)!;N_G@XF_yh8;(hBYHGPA6g zQ!blO)ZrW!+pMI!HJ6pJIj)~lTo1pNA?r{nSgIRpyl3$J&W14iKmd1E6K=~C@qH1J zsP5PrWK$;&rw3c-CN`LYgv+$)lJi7J?05fFuf?%9$qMAII5qW?q$rt)^SP#QJ3+pC zVYJ5VZPlSW8o-5gTy%K=a|C%h9Pbf=+H<@X$r=mlFUo(e|4Y#3|IG_KDCmx; zTVAf!dHN&R6>T7#t)r*@sZ_j)8VgC1UpdN}?{ve^pd?E4$w>sZ7_?4uSL=H)( zJ6X&)PeJs?Y4dT)@2&z=I3{_rLwd?7$DSNpgz8F%L(;*a0Sy`)AF|HwIC&CHQ1E^@!}x^jt4 z$nS#}&{e%3fu@gypM)%8-3kH_A25r2kF}2C!!th0pI?CgM3{4__%{yDhlo zR{9@uWTVLiphg(yqMW|?@>^JI3&4VZLD%7{msgwYnz+p; zH2;Mb0!E6S8J077?#6kG3uGe(S#(!&A`2)uc~rC6^ld8&Sn>;K>Z~V+YMz3nfpS8e zB^cU*g#(F=138kPn-~R`KT3?X#g@-vh5FV>!xRK$_o~^*>~CTDi>y&wk%z))9>C{w z=;+YH01EiKRWU(4QIuZGiD6D_tk8m<5Zp54 zs>|mT){2@`80>ukGMQijr|t3-kYil@@8_Q3%Xn zUWMu0fYNK{z_ti3G@Qk6*LRLeR5H0!QX~YXntB`Hmv(Xk4@gzs7c@IX=(ZsxxKdm+ zIU0q`{rfZS7I?@zV_u%srDyk(&bCaSX1 zAZ3nWUmz6UZ*&T`4Dp2+`q~gF!#w|#NSLH%cGzSIEINK`Qe;Z;M5A;{j4-h$R3k=U zrySoTVH-(IaBQ=g$?V`(3`-gGEt4v|=1+D!^@SOR@)OUnL|#+xqF=kcD$}Au`65iV z=TE9a?uoqd0f`^J*Y+qB_whhk+Qgv5*sE+_|FzW@b^$P&HVab>$WKWGsF(h!JoM<^ zNrxU^LU75f(eyA6AR@ePd8lb4YzJRovjuZsbz*&9v&`L39A3`KzCH#41er}qNS5bhp}!-#KGDs@ShCDx zY^4y?p*a@y{%cbul0}`D`wGlHD+TF@5!NOK(34@88ZgU*z}Grzbx zFeLyK^ouS)&WmTE>D&RpcUypDAj;^|ro=fKVFkOP{7v#ki|@2ErI$`=&I;c)+9d{H z&J(?Gne=-4P=$U>`kuPnk0|b|$-tCn~WPyn`f zajH#|aq!b1I7kLA99op4k}$Ph2)-Ib{4*a{*!~5}h0Qw21tzRKAcGQrC?Np4}s4kL0`yQ$1eRG)}n49iPF{7_L zD;}>8dk~?RQIGnh973C&^%$eil8l7s4Gri14~b_@3+g}=*YDS<8A6R z4>D(@8-3&g%r;d}dVm%9_nRqlR!z;|;Hf}J?=)+N|G%eWA_|jcG0uaI;v1PmzOujVF1Iud-GY;JPhaA(TH>&)X|0 zjjF2j!qntLuJd*(R)!KU1H!;1H6iIFNb5s)ON0h6a|AUq-SUVq+Q%(a|8O8EaJ1#9 zsvRf~;$1&*5c)ask*!zB-7!OYf}_@y@#BG>9%v*T zuVpoMu4aix_~IQc$|{xG)J*{R8cC2LWibfBFmSp7v5E-y&POZ*QVVK*_OZd}!li_& z%_DGz+~2P=X za0NC@nE~<^SJgY8NZGqGAln3SK$10t z*Dd=!xn(fW&ZhS#Y|S};-A_dwa9aeHlMRXpA%q~-ZK}Z`u4aPqat$I{wE(`)e z>=Pxf5GeL0)yaqiody%Fe!_8~wVFad=gMu2+PoASEg0xoV2G@(smYC=ldbXIBCpJ% zH-%4L6FzUfB_sX$tAEz;?Z(grQ<3*XlS<7sfnP8|f7;J2QKxFrIEWz3C?UvNfGACp zVk3#O4R{^Z#Trb!;yX-wYfqZ_AF+X{CfzL^yjf!xW~-vkbuE)cMWRO7;TUJl_#+13 z*m6tx7DMei7ZPdxlfm7`Tpq?}4$1h6NZ%#c$O~^T9uF)Zlv=de7am< zW3y=_RM$#arb`9t(eI<{=vcF@UkA~1xGvb&CE-*@7+9Jm+c-d!>a zv~|(WAz*4uX-2E1+uzR&p~XdUX@WEQ?GaamC|wv&kM-kkiU0(H21|9;RRX4E^0)?q z>if$wwBqD%BxNdx$RqXWLgfm=U3Q};+7zquGT?W}GJ&f7-^V^A^vbH)UNkjonj%HI zluXhog%$F(?q>ojbaPCT+(TZQJGfspe|leuU*PVK3(?cjH3c3sCS@#bnkgbVWh|Yj z?1IC#Q$&I^5=Kx2RGaEVS^yw_C|&ZI!&x)cU>+N?m*{`{uVDKo%dtBJRob#4BSg99C&9!+&QejD(uMR@;Wf3i9Q8I592pq76*UjQw-FQ-{s=4s zNq{=^ZO$HY8@PJ3k* z!I4OH{S735F(R*We-LUJoH~KeIYeB2-|dPQ@HHz}FJAm{ncTYbJG%pc{I9tDzt7LB z12P(Z;AmH7w$u1EEDXWWam-d1rp?NCic-{6V}H#-q-3e2siKNBt_dg|1)&JyPs-|0 zt&bW~O@`_>DaVx|jT*KInuu2%?q_r$CGvC-cHIa~vLvC}aH+w?Y(N&k4ZX3}t^#75 zDcJ(A+r>=lE3sTM;z9NDDs#E?U^S*(y=cInRz8YGw8JuU=jEeOExb|t!-k0^1`x5~ zNE&jaYi3&Jd%wRfpoKKPbMlhWao=>YcCFdeQO>WAY zbj|^hRJJY-lHq@xqwt0{I+TW76h%fVgEzf}k1~gX(_1sRYvNkGS??7pXo$q0|EJ^j zfIXR{+>?mSh6T1JUX`kGf>GJe1Y|?GIFgFCprW25$y`e?y5gkZ6T^)bEj+&Nu@VJY|`d$b5@?R^Cv3&^5*;f5VKp?{^1q-->84pGy7asbOykUD0~8}WO- ziO1X6-N1rSZ;D^Fnkf5qi)c7O+soXPf~O6En73rR&5PFmN7GjYMA>~`4;@OEbax0y zclVH^gmfq^9n#$$(%lWx-JwX!5RSmmEiLKy@c#ba9T#wOIL|(NueJ7CN+hKyu^{(K zJ*f_{X!{Q&$ObmjzHU#BMwNp~G0;Ywe)r!w<7G}Qm`BG*;UTRCW3UCZU+Jp!q8S4# zKc_ZrN0KYHEkhqjU%irR=`2k*;0pJesIS@R=gbLBpj89pA>Ln2-~MDo0SYN0Z&|ft zO5GvFw77KQWR)Xv$92qC$-Y)pn#$EwDTIxBJ@;OU*8dwK$pF%jnaikip)oG?1Ur#A z1Th05xvw;^E3%zaN2u97zy+vjg5?krD_?_u# zGxpZs@!h6}gLf9$Wq32&k^fZW`_k_yC4%{1g`p=|WwU4>Cs_D5wMqO(u?!s6vw19r zW;7|k-A4GUVUN%itQ3Xvk;bLmF-0~bCqc98xS*3m%w+S{H>N!jKf)}sWQ0KLYhXh? zi^1^;b-}4NmtdMy$3~(GCl;aP-~aI`1@_unNG%PX)9B~y&``rf8BACuhw#LR9(Ns5 z=?}zj?~7sNkO9@IKRFkugqqtbVPL86%^IQ#(po@C()jPiSCcB6!i##Dm7P6wdCB+t z^I>hB0|!bncEg-iV#`te!4?tz<# zqGdZ`zf+{@o5-rli~Pc`#Hq&@!^o^Q^T4`w1Q8f00yqFTwQ}68ud!M=m zYo-I)%wV-FiKMm7R>pN%%>dTeP}7xxc@2<8I~~W{aSq)BW<35x>(!>?ajCFL{ACUP zc~YFu536UuFWV$&f72Jhk_2`p17e6E5m@3Ibk@g=<-%%a#{{RC8~komg=;Xx_}K>Fw{z zqbC*ZOlbKt_YYCc)Ywla&An`^fYr1d%FyFd83YYUo+zDvWz)Zq1-Th?4o7G;1;y|7 ziiKQvUOH3b?=#4HG`40kwFdVp&(!)Kgmr3&IZQM&W0LdNxZO20Gz4aU>V1Zyb>G8= zEoAHaTc|rD%l`a3MO{*7M$HhualhYSqb${6s}o%FB>>KtDbMGmL*UG9TKs1HdGY`@ zQ$S8B8hm>y^dHZ22={f;XPQ2Pl~dK!LVv27F(4CA8dWh7l!RdIK?Wl$;(Rq?+Q=6) zdTaQ9Sa^RgHjy^7i83r_b#&13Jq8>CedK9N5VNHrKP4Erq*e|DmP7kH+0!tkKI2zJ z04p~T$xb|ySBug!p_**AnpJYpMEg4~40srtgG+dzK@{LzD_@FO(AU@ZCO5A{B`oax zoxH?jAz<$dc{8#Sluen`NXI7nyKy%o;X!47x6m+NUEu6*z0kGMJ)Zx3sUw>%+qk8t zw8$*7INBn~q?U^arnA|YW z3)K3-xTU%75>bH*_sv0V_WJ*(do@0k#D;`g`vamhG}H8@^N|3>1E4EP!8K$jMb_j} zocj<}MoVxuD}bOX6!A5Llt(^#quFaP5@V`uB6Hk-q&f-mc}bY5)eqHWxsYjj_ywLh zGUvI)KT92>W~ySPH*P;Zlx1vDzRq)JP&KxdvndAsq5y2ZkMjklx_1+qAUhviR2nsYtMhKdLlbtK|#kXPae|BEdDOcYBY?p+L{co)bE!+nqZj-`dQjLrD-r^6w z<77#3Ez@b)BEL1Q?qR7UOw?Edju;^@#y5H@B&t(MVnJJ&vTV2bp0j znLmRj*gjB@)A*M}FN=fTW5r~IV+PZzFHI91x5*h8ut5DxS%bKLO0(@Z`aJ%YSFT*sMB6Qf~9%-^QHwuZb1Nt2W2HG_Ipu9cYga}rN1>;_1ds4 zl{n#+eB0os^pu>=K8%O+gJ*j{pmjh%fTT-D4@=tO&jk*K(D=;feVisUW9 zFTWeu@f{e!>kyDb$Ej84EA2n%B{H&quARcIrCeLkX!^$7A9uGOA^AY7o+}a-LG7k`Gfq0h)e3*O7E$e z&^c4=cvfD!QhaiHt0Tj;uc&(<7MPE_u64c?SQR{4cBec_O!Zgp7ebHpU1|uP+B*j8)FYFn?j9YFXUVHg_~$b2;XTMEkY<3M!2=aTQ>S zG|s|#&#lz2t`=+Fp|?lnsm}}k_{W4mY1pjRaIk+^8gfDFPVj>%sM)K-zExR(R7%lS zD(x~P`T~#f)EtkJonWiTEX@e`x4%dX@;BaS2nG-c1dK{!K}p)Ii|1>MkQ%0%RcjO$||MkfXC=@o6i0=|01}Ef6xP&Y*6{; zsWAy8$Z!|94?uA*5ict{z03k%{rInwN_j9L&D3^rPSj5e(|@S}rhVgwoYtX#-54v( zrc1XkN5Jrh@Hu6@_wUGSkIHPNDu#F5NoD3Pg}&y}A2E5M2h6#l3G5?@6P+4?q$Y^L z`+v_iDgWj6W7$`~M%*)gFY@RFHm#~sFkGeXCkm<}Z@!IO^uZi2&vxv@c>bbA$IF4E z!~tTjQCo0U{bQ1innKeXcT>sNWt**kl!h9*Ag3VsWJ~)~{Y*OrN<7}lcvNz`b9;yZ#aRz zXAd8B`T~Ir>!8{~&1{-NY_JDl=nwcb>`C&~D#Sk9iw@Ma-rwKzaC5V~>thWCP7sj5 zkAL8WwSJGUe2F1*E{vu2i!jAp8>QPW2aRm}`~PNlPIog3zOr=t>g*kc1u*9p6!6w? z!S6`IW2n5ue-&g($@~uF@8}p`;n-A2R)pfBRC#YXzZ^$Pe=Z0mdv0d zT;K_EnLupU*^C}N`eZQvT&8YO1!Haj1?E&WP_oZe0 zJUnVC)x?2KMQ_`*!A9WPFsI#-g?{TL|)~$)PnX40`${>$nmLsZ-WRR6Gr=Wuc zl@F{eqvrEIUbhkaAl{ND!B)x0nY#vD)MtpEv#Pq#5L-iX*3d#(qz75y4_`Y5GZ~k0 zcO<|a1Bnu3@Nt^JoT=A$J~_2<3PYF!_^piCY?fi45EhL!oil6hk;m^{fQ9*I*M?`Z z?W~ykF>=NKwME;4{|eX@aY?n0xPO@6tBs`ta(`VKPc)Gb=o{_m^KdqX01|xP38(u1 zS^$_E!PCj<6E;W$qB$*g@v;R>@)QkN%PUwPCwm4;)e_>W7BBB~-57Xd-MUE7rhmpO zOJnM(XvPyZ7IaJ2mbjI=hk10$zx_w=5etk~0J{k;in0hGS^^jEzG>W^WBRf=Ncso( zUd^`Bd9PywkW1n6n;%FOhj*ER7FCGSgL|YJZTpQ|{X!1}_QR(ZZ206AoBc4A0Ia|A z@*QjCCENDN6=>&Q?2CS_C<+*^^~ zBxzU$bBq;lf8rohE2~nl)N}ja2ROZy*e_P*@RruB#ziw3 zkcojX8W-#uC}$EvG;C?+H5o5_wTo}ngp&K;cwladK2QGz1mLR3*leL?1~R_*)wM4W zJ3&kaq#*zSXqn?b$`lH;`<`r>vgfOp*XPnPr{6XK`Npl=;$Xm%hRLE!2arv{7s+x< z{ZgnuYoh~85hIsORyaVcGCy+pG&!5K_oG^;g>igtP7vl;TWwh}r<|ugFaj>Gb)2IQ z+yArH@rz(lONk*)EeFU_hKiD|m+??(rU;r;m4vx~jzu8uM#(vmB?sSH(G47ys@@%4 z6hrbF{){7g9O-2{X@{XNk6`{yfk0|n)no;|x3&2#t4>n(8rf!m$Ny?mQSuH?;@|D` zW{k-L-P48Szm)0(Se%+D0D}l?#=W+WdsJ0F-VKSN{3jy=*Zok(ak2jin7c8HaUxp*}_|#e>v4i z^waf-Z{#EL1?>)!JzHAUgn?)!#DS}9Ybh<6a(cW3f0fTFCf!_BKwb*56N7uJ7esdC zm~$d=<4PvdR|VlHxHs$~U%wdp=N+iWCT{%skt7<0@C6DXrlKYb1p-J7{1!E#jg^r$ ziqEWMY;u;(@%JYs&t+w4mxD1tiTGPMX7EqPTyJks6u=+m`oBCrBsVl~U2`mkypr|) z+Y9}PgKV)l3%UJVX7dS*sG?|7JwEHUeU0wmEr z9U(W19KtKyVu`=&A(Kyfc2cw5Up(P9r-+05r-5}k7*2z8n*I0u(`5zzRKKKn8;vZr za&2c)FQQWB2KCim=M5kK^D;SHx+Mm+vrG@p!I zo33bJeWs)2(oSZ)NQ&osvq@HANzV_dAsta~@R=f_IoC>hcpC#w=dtXw*_&d08y zhI9`j3=N}?fG4XLI@3lXZeo>zHg-++>glkIm}ZsP2<4C?_M;GcvwRtYqZ7Ot{yu=tm=U^6WYI zEQQ5Er*`9%zMT}QMxJC>@Ms+8-!_R!2|eOsW%HECE@_2CjW2-~+4PLZdfXKCk;h%` zkg`)#->UF?(H;`3y4;CJDZ#e|r@CG7`5aBx8aH{fBB|zMR{*)VzyeZCkUpG`5#+vj|VMNyz{$>oMK?IL_mqBQA~+%8l=| zoY{LrFt$Lh8!$yS59gUZtUh%Vxmqe*A6|DlC&M!Jk3ahCCd6Uo>Pqna`}fSTQVjVL zG9vx`hveTWQMTn+8rj`{rsT`k>5zWL^X1;3?U(1n*VjSp?Ce59Lj9wtYdAz|7OIH` zgaj9wTKS6UKBM7&M5G~Dn>eO0g6z>Lq-u5+8$WCRetZw^q$wQaN2yp5*B!OK>5qBd zOfJ4X#tE^ExD|+lGDM(IoE-~-x|&N#KRZ>1 z3geg1V@DeNZWCpzau6iQw(y(f=RVxA`~ajl^7k+i@CHxgRGJ0lmT0zHdGB{sDK!u7 zv{K4{P!=d^3)e*vCDngRPA^BO`vpM|8LkCx&|3-*(6AXbU!$(?+;9CU6(D>g=Gve#%E za|CaVT7?i5l6Z%f-`3n`4?nj<=eBW6h`fIX{CgbtDe-$54_NFOZe2+gV0s-?mec+7 z2MnpT>thz|b^@6C(&Y3w5V3WZQ9?)P`!STTQ56Yjb{3N2)bNJOghA(FG%2nd!qX)g z`L(Zzn*i@J-5It@JF9yqwhCiIT5(KvqK{ z?C~|mA#Q$G;9i>WqF$GO7uK3x@y~NqZ3;)E2=@`WPz;1f^~UC279)>G3-G9;`Q|Cq zL4-K_P5pX>*%VNjE5vVeWjzUsXNV)g+xs?NSJrIe{iXA+)-=9xT8ploKnmz{wu0Ez zf=;`~vB5RQD>WYyWGkhC+nP)7vl};5x`@&#+=8jclKETY3U|rMrG%T`hp5Q9@7|R} zgS!WuVfXTM4o3p9IOBavB_b$!T$Y!ghK#XeV%R0pn;Xv-)U<_lwGG7coHa{-bOBB* z5koH4b8)jdLv%9@m-4beX%?%%C2^nBZCOfR=q;&7@+-6fC(Xz;qD7ded;{I!mKs>d zSb{n8c8w3Qt6US{tF@~K^PUr-bbG(udEG;9-zfU9?tmWe2QrCYpSAqGj|5!%cP74i z^4Z~+_#bL<#SL9#UG9#p7Uj5VwpGrlW(w+vx^Yrw=8XJ3;%Po%adFlZa(#d~iVPed zi#P>d-s!X1MJGkpRzmIjKM~}Z^HM5_&0yMd$QW9m_?0K9)2hiWQ6glu_3d~F0+s0P zH@wD)jRpj5qmuP2Ao>>{FvvkNC#cpOHu$KFyaJ;CE~F+L?zZ3uw+V?bt1^@KiR-yP z>3XgbIR1Z-9^fQ>1&$^o;^u6B>U89qqzyHLz(pbG-gyzxjn#D#84LOQ0+yE(^wv?` zyG~o!MlBJR^r~LtLll-VQfv|`UW;lFbRFq#>N&k8?cLk}q%QX`83M-h`Mudh66RF( zAZa&FK8*LPo`)=PaU0`Hvdd`IQnLNfn^iZ!f@wwsT@G;qvu*--k%WpYzO^%zmseT; zs%EC9k?P=$Qz`wmHfG?C-*T|Efq>R;auN{YcWOqFnKc6ZNIzDZ9MrcOe%dx`i`|*d zyGo|46fo|3`oi$NU%B2pvOb}1DA#xKl0VCuc{wMGeCE;&u+sir%Zm{9jK2fbvnycz z%f)(=Hk(+(wh7@J3Ip1bMODldlTJ5`XM4nyuBbGIM)qUzlzq68#rW3?jP>joOf3yU z<1=L-1M7K^ex5)4{|-@Wzfd1y$eNk5%GjY$;0vrh&@W(rGzg6Lu22suPj(6@@>``# zZori49!!|}h?15)u`z?LgDFmqi}%%DHHKN0V>ZoMxwXAwi9dB2=ZBq`LwV2d;?@Vu z{9@%TGW87Vz9mZ$7#=64b}cLIYed6@2^YLoAZAc)I;Ch0*ej^a(Q2C*Z1#%6J<*+3 z#pMEVUPWSt(X$Yb&FpvhWZdCU>gHvj&bZ%$XrS53xPu~VPoyIjIG!U+q{EBLYYrCo zj=^?OWjk*NSD4ErQ^EFXK{^~~vZ?b{| zIs+cj%zVQ3Ru&dWz?IW`|DJx))|@C>sq#uq2x5)+u308(N`$1@?;_qT<51$PnHGs^ zV8V=Qk*2qZ{1h<=@7u7E9V|hy_7lb?`LL|Hg5?U)aWGAw?=L~E-v>IyF{EsgA&7|oJpgRyr1DN}B8;G*N=$}Gxz>9tFT zFGNX6`Ib&76PHLW(p@aWX=QH(2L|t+^v9wCuQq}dI5sGYE5&taxeivC$r|Gokz;b9Bw35dVN7H!H#x@kyvIsr(sHvcHhDI# z+${FD{^V))vTvY6KexJsxMwNc7nS%x7wLr0N3mb z^E&?o?U_sIu0fV?O^Y1Gmwu5`A5Mx)hLXAO1^M{X7wc!3ue;%J>l()tCdDl1%Z?4N zRg#_vH<)A(|J8}$IyE@+Yk0GlShM7s)JJDLf&f?SA2@Xs@iEQUjm|B;I4zYElbaOS z{G*+nv1P8V2T@ zN0>bBN1oSO>&m6f1Y~U>PO~p6nr$}7AwD&tVGIscTnIOEK<0%O3kB=;oRC=k@;#9L zqUtwBWM?a&pslliwJ1E_Qle$J*O@7l>&d~@o_g5LC!yf+ZX)kZWq`pKQ{vbgO`F)S z@7@xNLEmg&E&eKU6CAm_0eVG8>^J-ff?tMcv%UU=YL3~sxe-F^jD`Sc3$X7^Q2oMH ziYd{l{q#o&VqcwxT;VFYU3j7s$f2b{Oy@cQhk34ztN~J`O`zreQM+D}-Hp1XugR|n zV_mW=@Bi-NT&X8W$yL<707slGS+V7%>pI7eqRAox-tKlW1*csMxzsuzz$^6=c4^YVGRO8#U*J(M|u3 zL9bzbv=Yg(RuQ$&iH={k0GDYel5d0^w0R!hit|mHl`FUoX+EN z;@T**SZk4r;?SRM?iW>*wdKc37{fvw!$OD|ag_}}u2%n%F7E{;0-+RXO~Pf=6dp9$-n*9G!jhX3n-M`0dg$<>~_* zmFdYA?|52pX-=+nm4(Q{J(~jiI|iERvr{xsxO$gT8R)Ep^MTO>%g&_rrwZn}GxL%V z$?u-F+7kjAf694GbvC1SBHWoCNvN~yE&JX}91@m=-=s_IG$7F6rj0Rt{iS5$*OeM4 zS?cPRE-&fnWNTn8>g6ZWP2oRzt@|7K4WlvSPQTc`2-5Hdp!*x zP8sh=n^RcLx0IK(Gg7{0f4~M|!XTeHWdX~Y`y_#ns5jEUhi8x+no=U=dkPd2LLHc_0iqKknVV;?eBGRp8ohfLP>|Zi_KH) zY2~*)(eQxDAvkG@P&?KSS!Qy{8Vy~0fBz1UIV9Oo?cjd&fg(#XHi&4Xl4gu=8m;YbC;;O;r~qsi+vR^v2Y8T zk$l|Oc=pD`#>V~wJOt`P6-%>}GjF&37x-}~v56KtfcrPY{jw-{QaI5+qYyv6@oRf7 zWGdvl`?mkqHup;{OT_b}@VIh6$_628NN1m3QU`U}PU1p>)jsi%OiI9otnfao{FHKG z!MW~D#5=;2Mhtq3RJble^1r~)eHb{( zJsbV8>kf=v99rKsL)~|HcnH|W$Cb>#C@!YyIU;msk|)Wei?TUW`tVNx+K{~buRPx$ z6ZCv;AU$@WOw(7$s8Ww&$$7MFVd!sJ|0pfdEbcqLj{D>P9Ul+8X2(kjp2FDnGF|uP zBYU|=kaUb%^tkkf*0&K|zU+FK7f*?d6|S{Eylh`MQKCm8%MnLaeW6gU!~D{&s-=67 zteY6!1C2i}n%)6qbq)EV#E?n|nv>B(~+K^4WObqmsdp z9*95^8;k+HY0<+fF2Gs5mOrI6g2I%h5nhoj1s;i~0Q~Y7|KqauCAr43=YPxe>xd!Z zX9Lj{yLznl?749liIFvWlzg>z9gqORk5L0<1RNJEcJf>e1havCfIE5&7)v5z;rDw? z;x@WxG0g~`rIQH-ANB)N@aUB6Z$s;DxcZz}%W3|-^p_$03V{7dhpR1mg-_U6tQt0H z@}p(ev7=NHt1?fSKOKE5oMDKLt#2Z=8)Xuh_$yJ!ewE8=#=a-Iwno`iQhQ~6s(V_> zQ-Bn!@i7w2bQ6+ZA|hTKx#%#5JB-$OQs&}~mn1LF`7*Rrr8IW#uU@BJ z6v@&9lAxsg)3S9d_7-{$&yLB95BiiX5~-xsKxODAco zcO^dM++23mk*Za;cV+~}?ECT;oW40+iezmm6H#jMW)U~U5Zr}bCLBkaOly4oP)%Wl zxW0SL&@uqib5=}=)Eg7}DA1_vIm7*$^~tjSg~5@=yof2cf@5Hxl|M%kA&vA(tx{_V{>*l7UX1)s0K*nBZUI26LcVgl_qWb zRAI$20-VOg$-_tf$4uI6J%9fy&g5?XqWDnt_Luz(Miy6Y-jG7D+kbl*0KZe(oJmxm zP1`*# z)9iZn1u?`T)V&9NET(k!E5__8;LD;^7RHHySU$dFO)fD5F5P`oGN($<-p*!M&x?2_ z-Py0rSm=mhN0YfJlATvo7+o@YnZ7}YN$}jx9DElSe6cPd%QAI^*l7%eOYX0 z0~!<(uSe(u*x~W>TTW_W zvszF9-v=fp;To9S*~4?hj_JV1q#77Z^n)-TX)EniXeI^!HRh({P> z0lNdgJc)8)h1g*z;k;s|rS&7(=MQMZT6^)+pa_qaL5oad?fW9MZ5(J@?515`>-^T` zyF|%%f-$Z51cf*I6pu}6$pFz~e_~DeV3wGJu4T??Q4)RlbrU;K6XvdLZ2&Ya+NXv| zD&%xcn4uINI$Z=fnA_N30EK^NlwfdiMNG^l%$`WqvNPYF&^I}ei0?-yD$>Ay6muR; zG`MPX_qWJ2B zIMlIF6~j&=Y&j7^xL#2SA)N&Yz4=psox583snF@b4GMz*ilR?c$YDvD7NMQs==><4 z4Wk=GSL~edzh^rQkhwR0GeG$zoD~fcTmgGn$7J&VYYT-nXL1TT2p;HVB$V3m^Id0vbNy zZXmRKZVvKILE#S!)mf=D(zI%k97`Y?r@6v~ai5sV>WAzXdZAhk{2JB^>s5E5aD<}b z34xoqgH*d#QHP@^PE1lF8<5o?yc6DWturO;|AcjPa#W$3TfSjH9|OiTLaA&(U3V)r zcoSDi81Rx%(T`ANlLfNV2u%j)O|&G45eC$+db{vlw%Q5K)#%u2#lb#Dj;Qi1VYu<4+Mp4HaXYnxZpqjJ$?XM*D1uynkCI_ zMPdP{TG7b0a0Q#2#?Z4p+isqZx~);Onbemdxhq#SD@|DFIR8s*7E)+BmU&cFs#lY# zLw1*A%6;9DS7H*U$c(>Rq<>gCWAGo5GE17(SxXnL?t7b*0znzvEV+3cvb%XX@DDM~ zQ}q9@1z>vXNSxV#x(qJs)rm4ay94MO4zXWY9;YpyrC2eMqcr{*{=nC>B7``oRH(^7 zrOQIhBPoevy5&T%VPRdbnzi}r8UI2;qlIe6B!2jg`q}P)pZt$!brMtwz&%iDYC{e_ z%8v3&(EJUh#UMF@qKs;&Z89Sf)2hiBh!F$0Nb(&%-q++j6TXYW9M_NcTukxQmtsbjCU1AFgpMS7ao#WkFuC3@22+~0=`-JpJmlgFyY6gE;#>m_u!_FddI z_~gjQ`Y(0J1PttzgT`W_KO2@EpeOGP(lc$}es&XE(iF`C-Or_skfQGDXiKt4um zfV*mEW?>6aFCrfZa-r_VQoZ}O$(zShJj3=Xd{e~ zXx8M(F&jU33W}6N;z#$#L$~AjzIxXd&AWsa`|ss6H{{a~ZIL5fd-JuKRRzQjQ=Iyq z;hf!Bd9{Zh!hDkLGVVBOqoYN@=onA&_38DY-W}9hL_9EuZd&deHL-o|{qPX?f?AUw zc2!8;^RCh}-KcBgNA#(u^n?VpEV#|v6>B-L3gFt=PFbJZ(F(73)wup@G}UW0)2j3r zu9CwpTNpYftn!q6s77o^Gyaw%32!n*G+Mt;mOZYECs;kDQggO!>+WgqW;!9d)Z|ip zOi>?D=A)@pT^f%eP~lcOxQ(#szJ6HE$PkZ`VSU%792&a*;C97ACh9q#P;5g!PRupq ze!{^qY4)KkI-4`dl)dore2WicTDGVfrAt;!!T`5O^Mc*_190kD!;~a7_cTcM*x2WRlulXHS-*p$s!bEC8a?RmQ8M zI;!l|cRPZ$koSO{MQG%3dI^Nj1v)063+bi|2>|mDumJW;qntTdEoh)wkLRVUvwQxe z3t(g>_PoJ$+yYI-RA+kSVHSzdDj?{qLP|kDqui(n3EgW3BO1gOT9@Y{R5MQ8 z`f3%U%b!%cj8^cHy(Pozm5ZfGee&n|9^ zyybww!{cNV@GU6Q=qkUL*igO^#JE)P3IPi_xo}`mtT<+&*1wh0u!D6pTTji*68^DI7 zT?Ocm9bIyykES;~{Sd)bA(C+s3S0Zi*`6QnDzO}P4Qf^LFWH+6RIK5+#fE~dR$$HtueVeB3@r{4gP*$JCX$Ac%ErQUC!Al1# zS&2;+H{`vwO2{ZFvkr)fqPXmX4p~i*AfB1($3X4NE-T|u&O!gsLxE#~&y|;!!r9s^ zx++VD&9ln*?RvvBH2kiTt%jpUcRXR2Yhtd&YMO3ZI?MgE&5<~7FOsrt8(os;fZWGH@;nY{^%!Lvfn)l zaOb%V8)&IK9UhydX;XH3ILP z&8`urV)F;?-fImgGw~vIm5pHLy7Ig&M;cGKm~dOOK@Ogme4Llu04z8E0t=gQu@+0X zSnKl=vX+=QWia;6xrWLQ&j_pqPtUdT@NTk*ARsY1qbVB1vb;Dgft0^V338-Wg8J_} zEzgeLu|RDK6m(W@tHQV^_VBVHsFXIr*Uf7m<@|&4nA^S-nXF7d1M5FH)h2T+MU$A_ z4L)ISt88o9&!wuc13UPO{?8myWvsRh2dpKP0d*uHty#Bs&7HF)%UDj2u2yv&qIzUf zv{#xF`t*pMOJ452OU&l_Vt=eMc;oY*RiIJGT9i=Q6x6AOe=zjg0LP4VO;rV$;@b6@ zv_)OrTCE`bEPlL2WrClS5dy_tNX{o>NI~G#!TffKckvTe*_`U#Ra0CY$QV+R^CoQ4 z4?rZiMNYeoEzX?l>+0Y@+KHaNJ`h-n04$$NI=9tY^s1cuQ7W6qUl%p0;oI?Rt>?&eFSu-{Ypf(Ib zVM+Z1L_pwdSNeylehE~Vl*l|h%=oY?J=j3?MJ=D(vaLt3(PM@7Zg}*;nM{S zh^|`B;Zo(jD3hF#<#WaE^0Sz)8(rT6YLUukwaCJ)QxXsG`f?}mP)HKpK z`C? zPI3?^czzRpXW3b28STxBtN(G?BDMJoa6mi(9w>ldW9c?>Xx5UOlj^W1pF?1KnRb}> zLoREN9CxC5RG5_gL8qCcg?TJ}8kN**!%%?IC=la8srOE(ohH;aQf)F~i@nr=d;czo zk(c3Qss9O5*crd7R4X5`z*7hurtu$+OW}D^_j?hhsKHDv6;r{T%%i>^jI(bLolq!P z4sgK@I%?tV6?ZH6PDb(v0mAE^C>yC)1`7h#7A8dctSiv?l$A5mRH@C5^ zWEVh@E+UN3!S}BEVPVTPq8)ly*ACW2B zvX`d&#b~dkccz($APZuq=Ojj$t%f>mkM%7Hw?oSz>*ETAP-t!XF3^r2iO3to0eXj@ zv54Cf_}3!GK*JN>!=_uN#R`lvN!Ln0kwoM<&U!Rex{)xU$qYO!+JIvdv5<(~aAr?B z3Aj{|{c|I_Sum7D>yOrk5`9PCgCmTI@jsv;hfpj8z(=i3@kp%7(kC-s&%#or0AbjS zgjC-(Lg8la(1aNh@U7`(861?&+tuKQF%gXuzEbPRH-s^ZCQ&k^@ti*I-Gc&Mcc*}9 z$GHFCpvoz`CgXRX8J6*?z-wc?;a2a4*s<2ei$pXM-Gf&!PkqIy0(FNe7xoF2pCfdH z`+u`4Wsv9OyX$MN%=JI&(3R|o*gecM;AS}n{FQikPkqjBe&0fTC~HjCW2Wp^PG(fc zzUYlvr`jDpA;l&hdJK8>q?J*hY&c8RWx3TuO7AALUwRaVucJ3 zxr1y+8N-+sd#zBW^-T#^TH9n@yQx)6Blf&&McXv>m6S_KXm}-!oeMqHtA7&sGNA`2 zm~SvTMKfZivJK1U<_m`&MgkzL+_=u|vYbi`$zlGUV{~qpQN4wk z=Z)KrB0X*9`kPa&Nv_}+Lz{+4)m<@2 zsmY5O9+G7^2F85Lp*8o_1H2YC{E$bGNg*7rSI_!lHr2JYd}Pz+Ju2UEH2O<#C#+dh zm36oi-_LZDflIjZuP2<~8Ov<1Z$4D4NXz{g0_~3QM8vBSsKe0tg6G`ck2go*%XVv{ za;)hp2?BfHI_krKz?DX4HxEzx`Y+7pb&PZVGm+Amh{L^WC!Ohm_KK0wQXX0B5qdBt zqR5)BCAB{FNw7~hAA3JHzJU8oWVtzQlkXuNV2+E++Blxt(Dp$Eh{Y8VMk8Q>`(ufI2v)o1q3Fu<+p zl8^>?V9Tl3kFtC-hdG+(ct$$Pu1AXw_)4W;ns*3;wu-;LY4>dN-ZQ{NJf#?Lb;Mu6 z=}HI5!T3P$XY`yMvin=43ArrGKg|0jTrD=6w6VUD4X=RRRqZ-W4@=wusluUs1&MWCAh4^m zkk@mG9y~(HA(fOR&Pg`KEmDK-ByIaQE!)tqj*QGRy=bzXUfR=CCY!&z6Ip~p&+ZQE zH-RR>>;AZ{ClvA(L_(TwDM$91q(oe!pZcZ2X~sLt~Jb zR;eAh?uC3%&!Hm$M~iNOgr3#5+kYyfA30h}GPT>Wbtqr*cH+}z&xm3R)$*YzPx z)}IAywX4LHs|*KCIw&!+=;IXsCL0}VMJzVIFmMU{b3!4I^ldqGT=^B5M_?NO?A4)T zY&yH=P%vT4?boguOiKv$CthGAn%qQPQIL+;-CNF$FurfcTvYIASR%%Q113_!#sQE2 zIlKP~PKoLeGGn29ZU_ox`sbv5ALXxy$_|q~Ia<5QD6n(Ug|m|5=bgX*@jZ$bl7i5z z+E{$OP=**b8#$>d=aZm=O-!CJ{w>Mj8hyloW_4$Q^~Z^|?TIY)c5PISEQmZ=hF?8D zU%m5nU^Zi2Y@R=dy58agb4*eWb}Fl=q|8F?hAOWg|K9}xYBi)B~~*| zr%0y&7)W*@#lh0A5cre_XUuyp^+s}Zz|Ew-p&c)SC*$}-#eP_ z-mwT>hn1;HCgrb82@LR9{ZLR;WG>;88(t_;e0g1)QsbQ*{1gpkgoh(^R$j7Q7z#Ri zo0Dxv*#IU5_<-%z@ZgZEo?eD*rI-f*iz?jQFXo@F1B&aRAMf9{-)<9kzuVNznD~xF zk4`pre;QY)&4tsg;8RDex5(#jf7+6nX?y1^ZeRkF*)BxM(@MrOnqRUDGEHau%kpsl zeeD?bkFB2ICzN=T1g8(CU=!Q$n-#h$waVu+crPdnzAwDV4rmXC%Q0Sj&IT@8T(Cbj zwqm@VLk%Jbn0S()6@{RmPfz|k|GZY_egG}|&wtiD{5YBSc-$}P`lkb)TtWSSZL+lo zjV$KzBmHNSvw{Os#?9Yz;{Jh-^=?zL??gK#B<1c^#hy5Y3MY7cBZukjBT**yvKjx@ z(-TXRzvkYbNk%yq$?jf!WeCPAjB0hzDJq8h^l7rF7xqBasAHr0O!(SCB~k|TX@{lr z7-`opE@MsR(Ht{iqYkke%nJ@=q+;dTY{d|=7}W3HJM3@#ph~)Ot54T6EpG6n6qdBn zJxWQjVM^@o8{`-tIyXbW{ER44L>pe86xl;PnUoGRTwd0NhmM_HM1CoYSaLol&L^H9 zY^CO2Sws0OBvB6pZ0d%Hq#Lt&`fs|-b-cB;4LVAAoJ&S5Y$fH&mj{PU@?`<>9MWm& zq66Jk%9bNyg^|`71ZQf0Yi4Ap2h0KH#9DO3mzIGs&tHYjjV84jDBD5W;6XzS2`TXCVi+M;HaaMFMdbV^U*@W- zV1%+D4S@7n;qc=O^gSz-5gVkljgGy%h@;Dpsso9U)h`2|0`A{G$2)pGUO~@3{k#4Y zH8znK!zQh`cr_l(Rh}K?BbW9Umr0By^RaS?B(qXR{{GE!`gt!5Czk?;*BgkZtRSXT z6NZ2q9~($lbvUo@B>smfQ(%HckQINTM;nJd_FyY0GB@<)uRDHwQ6qhb_I7D*;q)1X zzr#AZZEJ+)jV;WkydpowBpL4Stpu@m!jso*ffqrmTwBEnK=9+k!h``3E98VpU;0zl zCZn)+a{P-OQamom5M3;2*>&3V`FA4rc9%MI6}>&uADE6;E;=E}I}~>}0MxAYYIp>2 z{>DVEQ?nEfz&|Mr5}wB#>)f4Of3gi|44Q(QLt&Q@(w_4kJ@H}7!l~sbFvD2va**!W zL}5zIn&EKvi%;;$6VeXsaz4KHe0%hl7npk8$C2C|{59vvj<0cZo;IkTXtkWaeK%}+ zmF_)`i*4_`@h5($wa1N%3*mQg61Be&1sjb>mKV~s07~z(Pv~||1v$&1-ztTnH}0U< zA`h(tl@kl!vEgH>pX&@Qhp^>I${ELQQYX{^=mv?=C?PE+u?N^_ejj{(-_M`$dEM9h-gE9b=RPEO zBf67^Yj$c$_Dwaf&C_;0%TLmz%Bbv57ud3R@24`N*d}1w!_xMs$Cvz_$EM6I4Nk%e zsc>-Tk541Y_u$UTb9^C1^thu;aNG-LsZxoE{EsA1GkQn(~N3`mEVg~DW_if z?6X8J$ih0TUQL^ca?h$bUQDdVI9L?=7($s2|5Sh?2jV5?sEu zEi@{8;-P#~Hn~H_D&!+PimIy6Lty<;ec^Pc00-w1ovtJuv0YGYa5zCmr)JIa-%V;< zj^a8bSp`g8No;>bgZ;y&V!-&hEHszk>5oJjueO~Bf^%}DLa&X|YOU~BHho$%Z-L8Z zRg#vlufD(45iV=UwjQN9H*t;gk@Tct!^P0?aiCZy#HD4r!?TmEP@8$&o~XytV2%7M z19_-iYKJgNoG`4-F4{-6@j?k#xs6X+=PNl1rPh5X7OfORBiCbq>H-3T?+!26Wh-V5+&6#2m%bS4farYqgb?cm zsd=Z=lGo`j%cd&~Ut_v$Z)(`SQI+K^wB?z+<~o%$6T@~%JOrFZ6b{**z>P|!C?{=6 za$4?L7wvmoZ8i=Cgc#iE=Ndfz4 zv&oTr zvt;Gb^;4#DUg!90$jIY0(bPS5DT2ZdVh5y4{e zj;*K1lg(Y1i31-$GD9E`%K)?Ovu95fOB*Ca_u{rt({pn$=#M^!QQOb@P_m$R3$8R* zREqX&+ZkPJkra{b_2wyQGN=IlgB+7E=>u4UZKBzFhjIVK0Tug`C+iqN78Ld4Y!&de ztDx8v4KZp1)*Ct-^;Jt>A-8>~-r^@>ta5deAJm&GIdMR?y3gmCyFH+ zM772n-P#DmNE&d!@iRq)kYd5naQbiGrRoO5 zt%SL>X^%`j1?rFDHi-;Q&5jCg){_#t9S})`NgveB5E1B5T5yO9XL!C8n0dfEPFUmT za+SI-vX;I}`R|_^pkjwvtALTs*?X{$EHMTk=qd3+g4U8Q1}+&Q)(q*62|^t54W*7P z#c(2oenfE9><$GkAMOU>a2m(2TaO+6KWr3z8S^qe3(gYLyM>@H8!x#54s^!Vhqie? z+*N4jTs*m?@=FrBSCe8z-_hhIN#TqAG91yWrl=cb^PXlAvigij!NuQ5Q%YEue z@=#idP<}Sumv;CUdQP(569_6-YRuR9+l~({TDE3fr&4$& zrO-02`l$@1v3k!hI!3(v)z4^$Ba8$`#VmKku;4D;)Q|3L4 z(Jlzp$b0?i{ENWQ3`6PHz|%Q>vQh)Q3gd7P6hfEI;rR4CsY~p&Odc_dGA)t}Dopw- z#2{BG_Z25wfleN5-XyXh-&%bjKa&Ne{4`Qd&x$_~O4&(UsEpdAmf(AiuN=}_6%0ha z17%DWPj@I6RJ>7Ciq{ac=Lp@p5?d=2KM9mCcq@rtVFRG1z2gGthPSURr2(R^*Ahed z^`ob!*;!|DS+BrDNSwDnW-Ae9Ec~z2;i-qLWZmI_YQwkP{Im6adj=0Bl2;1Ow&MYk z$>-XtvjwsMD;%*~Y;i_)dF&StAozJ;Y~!cWmi(PahVi3Asja8rkIQqbmwcR3UfvTpaIP2?tme*WGDZk82i131bZtSU6$5cDVBM^M@QF!jb-``xoKwrZy z@^Bz=XcLeE$mDiL)!w-UJ+9wst+K~2q4+BE<2TbxYAKgx07$W@nWtvrm#i}0v+zxy zj9dRic#+SOT?vd6NpK76twaCCXtuDDrv~`FDCYZa6_+iR%M5W66k5 zWc?S2ylWGpO*?LSMsR2X>e9OBESC@D@;zMz3|cJ#Oz@vHGt$^E{gh9hv;+02`&tFzTnhO?zT&e^-fuw1bb>Nhrsx824)BoWn+Z8Up zBY*=FZ}OlY$QNM*qeuy$Wej=+9w)cyI`sq40+J`()xA>~Uh3Y(4hdSg4r-Z93~ZAW zkw+=u><5{7ZPHJy4T{Ix#>SXLK1MQljfQsUTzm?Q+w2z0tE=PUr7+Ff$)HwWryzzL zi5xZZ9I(@CL=ac6qcEKJ&j^Ztd}?!q%E?xd=ZdVbnEA+6hYoS`kR458?cZ9iNA*C-MtUr-d}saU|wm*iRiNGgMbDr z>UKns2`E@BSCxWpaOM>D zY47_d-)bP<92ERev=4DOT6a01HoZ8-DYX!}Zgf`1oP(z=8mU2rTsxUQwc(Akd|Vdc zXI2ZU7vEexK0&JBpx*^IGQvbj9B7FMAd=;~vSf6oih>R%c=s=m2t7>h#?w2(l58BV zLrHc*ck{$emJb_OgT3k=Qyx{rnSZ>kYw*Q-|Yafp2yKcKj}PeVSs8VHOw1lWhT{zh_>xharV`jr7(vzOPiT^i`B<|T75suH6eSyRi$ns#Htl`$o3@j-%wY%DJPPd9D_VaEtW0NKEo)K4& z?1N>#Z`H4TO$~Z2X8M>hAgL&}Tz&5>OCaELNGVn^FoCB@1WnbM6z)!gK^mR>M-QZG zxS&U8JFc{+(1vqYsU)?`6(xJ7q9UUr4WNuSu3ip~Nr*ht?NV6uA@57NUVi5QU%#RM zfnR%gpwK_H!gm5P?o0HHyS*&54DjOoN_>W{4+M+7CH?RjFoLDwqWZBqSaE?2|NUXL zL*NG6E|3O7F?VrJ%meg|P_hWi#i{s4Zb719m5XC3l9>K|L7Y_2R+6FPw_>;Ll$?1% zbbq`%7I4qKC$u9>;K@ZSQiPoUT1&)q(AxMj{VnYKMm3RnpysSUXy&czwt6+6m^A>N zJy5WM*Y^B!?+4(YwF6mW@drnvbDQoj75Dm|UuI#-j(D@CPD0h@Xvj*@wAp2yS4)`+ zCQkX6xS8PhJ*gJ>TwT>Yonz;Z=)rEeVS_6rNaniK4P$F?R5%ZBwQW8?fVQU)W?j{a z>yr5!)>ya^6Y*`l%d;*ZcN##=?!78Doz5KO)HP)v)D)uKKU>vk(A_oz`92Cffeq#I z32ioco~l_V-O1oIh@?;EC@|YJ5npcjlXi3prT&(5I{ouZsh!w-5%3%kFQ_m^qQVnI zO9dS}z$CVl`XlEM*STm2W?@ v`8D3;It+U5NW9CwYPRNod)Tc+VE2NA8HV~5Bu@Pk1bphM+K5sW%h&%0-QaFO diff --git a/planning/obstacle_avoidance_planner/media/object_clearance_map_updates.png b/planning/obstacle_avoidance_planner/media/object_clearance_map_updates.png deleted file mode 100644 index 188ce0ef206a7d28360541ccaf94ebbaa3325bd5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 166998 zcmXtf1yGya_jJ%w++9j=cL-h}K?+5RyIXOBQ{3H(6%R#PT#8d1ife)5Qlt&;&X>Ob z@5f|d@=PWq_qpfnp547M>Z%Gjn3R|R002ix5&RASKuZSzkQp)15m#&;1}+ePP@%F) zS{R6*4;WU_i02d@5Iqk~7aI?6b9ZZit+R`hH5b&<-P+n2YUko{jM62Ac#(j;mY#>4 zyS2H8y^HfJEqfF+r?rufcQ-ehPjol4+f~8rJ@HExSpIi!<%-Bu_8(z4=u&1ZNr2E zdh0M14)Rww1_$L2X78-&KHTyMU&Y{2wbN^)4iK=V)_+KJT8;YbNv}Z2^@cG@zzSNu zYHYl!U2dp*h{CP`U`Mh-eo3sJUVt%J8v+KpeL?;k$Md~wtm64`1|xj<8HvFRdd`R$ zLA@6A{5X73)QNNX%;hwhD;g%hjV~@PGA>+ELDh{>zA$Pti?~9LB<}4zbKh9K;FRZV ziK5t?SEcQR5p8)2FzR)FNndi_B=UPGm76{8%ACFb0r>)jM`SWj>$i6VL0oK2lA_QM`bk zb!_9!uKmjJb_6yt!JHOie|`}jsJC%2nR1^yB|Z~<|BPu3(zF|3zwk;c`I7MS66fzl z9*tb^YAcke!a+XAuM->FJhl-~3%zId^aUJ+W@Ejt3%^QGD?h)`AvvbRVyYaz zIS7+a|MLb#M0d`xmFwY>ka<8HZLwVsIlj0&8|@?y=THWQmPsgow-@a>=49aZHi?IC zlde`l$79N)-Ky?{r{29)wgOeyLWc_TwqIraFHUHXiDlfDznaB{S3Dyj%kSpTZ;hDg z0^kZCb5(x<4iyde6!L}N_V%wyoA#dteIOlrK5Ml%_cbB!eg1GB+T6L^DlX5VT~8JS#Cr8zu)JAJ3 z1-Jl4<)dcl;bU{0-jiHZtwfw( zoWy9_c@f`VOGAHw=B^?Ngc!UHr|B8;NLTJUg{x(T3&aIF$XHv-_Y`fk;oqs zMg{#UuCRI4yQW{O%R@1i@ToUHl{isRWCrEr*mPS~7t9ea9c-c<`=ZGkrgv>SS4Y{Z zd0iB=s2YF6Z9J07`{6Xsw4bG5YMokN5R5s}5x}I>xSMc=Axn(>O1VI{#)M>vj^`{S zxIaM<~an7yO-NMt(tDcf-H{X|#hp!d5ChOf`` zCu;Yds=LQPCHPwZibY9SP3o2rAg7)|4(76&&8>24jj%t@U3YV?qn6+{X!g};jqu$? zBRPk(7c-@{6v>;TGO4n-Onbu4yO>Q z5QSo0{J<~>(sZgM!0#t;%$xs{eOR{AO)-^Fsh|10M-mg(%`hWAL1m-yE2Cn}^^hKN zbKxbB{NsIu6{*7jdn^R!(%=_yHr0KUjTBT*Y?W3MRlctLwrO)fKuw=FANj5_TYI{r z){Rug{6Jc_y3q6R(=!Ns%+cILsPuXwUos9+JKk%)EHjtUoVa9VcH{8H1cAS@T9pb@ zm-i`Pq_m+DP9+h0{EoB@2^-I?ddv~v(2w)gKKA}`c78BnSMidX&n`juss%f2q}Ho? z$f1>YRs|*0gHxH&F?>8Gk$%SVxPS+FgDB(MnTI^@Yl6@!(VlJ3r31rMJUej)!Nw&-0bLFa1tnzO~; z#9O;1u-V`b{JP=0T;v7=_M(8*XKe>V)JO$RaHmB}Np`qnq`zv3A9k4P&`sENFuDX% zDe46)s(uXb+&h9!j^lAZazZ7$`Gp0y$2-qu!R&Jmq|mrMnV5Isfj65`b>F^4kePnq zoAXOO0IT-#rFlM=KhdcfDcjRod9-z=yAXol7NEGB4oy%r={y1IjCPlHGMex31y`SiTao_Svs z3({ewt+68&@WHlRH9jNrA6MEVB-l$m7P2iA1-bbYGX#4m{!KW&*s;4W^8j{sh$b%{zQ-7yxeyBv3JDhfswSALvD$clC}EvdZm&TYNS;!{#NeBJC%&F ztOnc3t&8WD5mmjgE)gM{+Dxh28&o@}$xz2-bniN?r2Kuk2$?{?D;mOEB2#P1mpq@szV zm4E3Jss+C`(bJdT)^(X#jv6cWl5-K7{xctcB?BJSZ}o?)xeTUDQ_oBri#3H9)^u*w z%i`5@!&4N&J^SyNXLWRS>$thu{SXu3IgrPOoT|`gqgleXsuTM z7d1aw^?NAV@v%Ymp~HgBOD2`F95GS*m!)N%lHq1prQD>lALqNywK<=A8uXsRZ0oLT z$PNYeR#)2#d1FRUGmNaykYYIRLgfHI4c}T(4*E#n-UKvE(M8tAjTL(`l()~yl{rO^ zH0oj0k9D+sMA{yWqYO#$%DonrS^e%7y+wQIUUn?k^^>$AKUgud9!#8*ljE})L1rU~ z?Hn52qLfsKPr*QFMHfD1~ehNggAw65~Q9i(8r#T*^6^ zYhKo0?N+^Zsj(#s+e{@o&|AAg5A62TT#ksrMykE$A#;1+Dd;;p)(qca?726i|9jQ= zC^dQ&zimsH?(3e8bxUm;@;y4P!`{JR(HHIyU=|&lzrl1clBX{a7=muyh*9EfV_EOb zzim_22SgAR$o^wbb!H3ykuXQSL=H9D`t+8wsJ^yn&FHp{__dy%$|(Aj#Z3=Zly0)` zCur2Pv=ehh)E<(l7eE86Q*kx^Z0u%b(J#opS^0f7S$g&da@g zo5~=F5$Hx_zS28!S_>-l#ky=A$4V3bw;wFCy>oucA;ywo9WSArTY#Ev9*ogV!AVSoW8Y(#(rnJ@oRZX*c-qY?T{^J^m>5ooC-~3R2*!* zN6b#VOJ$044TIKz?!P1Gm$m_1SBisv>@9O9pbfl&s)1{@|z3B4_Q@G?(~bZsAtZmDvE5{lm^ z6@v<2tn|9i4V=N8C&iycLqwk}yuImIRDIgh;g@a%;tm%OaCSE{?ZWr1RlL_-(5Nq5 zA;k9_zo9o)_f5BVVM5%+CTu9=3O4Z##oo^A*o{>P3Jrym?uBmcd-xySO2VQwSPMk{ z59VSHwMh5U#)8Mk-+p+6n-*O1G9oL67LM~vW0<3Q&uL2@trlQ%oLxu+6EZt`lSdR* z9T$VRW@j#CQD5vZasZA!q%UMJ{-S&3FmJ+6;ohzX!z@#+r>GY}U4rmUMy!y5v+zbd z);6d$JIc0^b!>$;2c_w2qiM32B~@_5Xv<0}bg)tiHpOOfqxgM^Sqyk}fCivg>3UNX zEOQ?Di-!z(DGeBJ@a26F3CaoCaIsfAbCsRR*s@{U39Eq!D;`Jh5lRdrYkVEq#2?d} zUb5QG&co$^+<}{wc@g--@4|q=Kj9fFY3P~t(U$DR90#8tq5PxR8~-}JZnaTQ6kXsC zA#^2oSE6uRjefQ8w8bi(u1f`y&K~yeG`^OAC!eNaCvp47_8sPi3nk;EFyN31igF8?^yZQrJrDQ#24-g68tGJ4&Uq@|Xh%cb18ebM zRc4${{cZ8VEb_qWRmg-*_24!&N_)s3ZxiI^&pVHD2drK!M!LvrHp$`xYCVUcA}g^s)e2LIXLSq z_A;m|e6Y@v$o$qgt~OV&*_n_5L>S01d8mbsty{0r;etF&*90-`PuQkanijmcmbP$q ziRhPIG#dGMRXQbcq{gBBHl)*prak+d)Xh)OO@K~2v1r!$)qB_^@pmfI`=x~s%hOrkEJgMu*nW?*G;aHC_M$mD zIc;u1o-11z72Y!PsrJV_7?l(Z(fVVzx3{Z=o^{BICv6kgBiLIM+ZI`4xp8XTP0UIu z@4X=*uC$CEX3w-tyqfS30^ZFuLXEXlE%wgLo4f~oyW~sH8p_v$=DFG9BAa-aj!uqv z-uPR84SCVtF0Uo4F^jF?yOQ7H8BojvOZ2WSoL9BjsB9TdIYj*1BqA#KEVnh?h0bhz z=c`drgw0G@{W}!(KJ%t9)v_qBI4*t$_D1*gd^twKX$@Q;n(6ewvuyPIzsYX>eFGOA zYG&YPWqly!{5}?K>ffxlp$>~q#u}io?bsEwM?MKOV>@`4=^RvN1WGsB&{0yhDHEy~EcAo%Ik{sK`JLcG?E^eHy1O zeFYrW=6?UFy?kt@%am%K&prD2JhrX=f1nla&T8ABKL__bI6n4oLRpMZzeNf79xdBQ zTIZ}&$-Tqao?N^yFajbNemGsUOft8&Mq9s~@U}4ZrnF$+BCPk#s{)=SRKeqxxHxC( z9P?N#sceQS&qGVdb0zY9vr}t0XCmOcj9yoC!uLKhd=Wd(57gB`X>xk197^%C8}^gD zfk!u3gjnVgU{eqS-wf`rdEp&df{eUn5jPKAlmzc};WGX6Y^PsiV7qzIa2wndeHWpS zX-2tEFT4CXGW=^mvAawIt7EfXsK41s8mmpP8adB>7zvSXT9rq4_)P*XwHKOz{lE3w zy|&$1Sq5Hmxd%<6%#@7DQ-+^Gf;|gjJhr6n_KQIQcY-E9n`os{5K`2SpI@ZNHtBZA zCj$c!v*_x)9Gu6_3L`0tj@ZET(l6lsC*eS7rpl=Pd!e^)@1^kGKPk7=Og#I9Cbwc6THE_F=}r~{+y54mcAS(H-CrW3Npq>ezDYttke&Z=E;B> zagk29pPAhB2GxTKtRg==ofnYN2GG}~{kBVLu@us~-x#Q>!6M_{$oD_$Y5so6b#%#P zL0ivg9PPg4jHui-|KkA!FdZ$~YM~+dD%PK8eN)SL@);O<1+<-7F&}pPqQwp zQa?{}_qs2wc4DD7Yx@3!; zk9^&f{sh`!)X9!l&gT3)6D#I>?v-`a&PR6nz(CGrEl$$1UD4I<2-%)o1)|U}jP7}_ zPLoMyRFvSO=>7u_F-^F=aL$~kW>6A@qWK){4lwt^tg~yiY z6W6j;!URHoVvTnpR?!s*PL%QzLa}T9V{ty>jAk1Ljj97_q;cAvS93To)c*L9@JiK=HuS>MlPzvvE!BC(b(=N34;36+3B9>8vbRKO zHu1Nf?@Q)nCywIpJ_ec?8VVHiY~cqZo$_I)UJz-Iftk~K6zBpNKR*kCb^9+VRAqw* z`5uM~9$tERd3`|JVcgViNsM4rusdmU*3a$lfE=#uLUu^Ka)!hs-;~HEgujZHXAmIl zje)g1&s~Xit%RGg40?#YH%rPpYx8~K{>47dof9{pBUOa(g|d4m&7P?yX&_wMCm z-v*4oXmx(t84hy$Kx3d}#2NlhlKC^8v`W!0cWJXh+xVoi*ep#A_1(HUnA z;wK&Q%k`3Y&qJME=003C6bwjSuY_fq_}SZ7>M?${qs9ZGjUg6}7y+_3f7F6TsE4~l zfAEcro!pjcv1dQKkf>K#@V@qbp5YIBX|k7@qquVDRhHYY6XGLCsWGr&GyCYBxd76W zLNU4h6)4-Gn;R2d>G<_V4OQ;;9>UMj+i%vdPo3QKP`QD>ce!pPyS>OacPu^1&3L>Kbo4EqL&}i?e&B z`uCEb(mx7eyV#Ym^P=kf-Ljzn=#G}RDoG!3YB6XFx(d+|?BDgPidXgCGH4Rb5h=|Z zKNK!rUuLmVDHsrxZ4f|4b4ttpan% z8E6R}^>#n%t$?!My=C!_qHnyf%-C?t4f=Pd8yB%%TXMqi2W2?j^CT!nu$`dkn1177 zf23d&?=uw1%}6fh=jY3Dsip^Rx7^1jmcCJC%IRZ2yD!2Y&V9)!T#9- zs(E4&H9?PX^GGHoR_CqypCl^a*JTVX>Z~eU3e-I^#?2GHs?%gy{c_1}v(!Do%^X=Q zrM+(juZd=hx#NFqb6>^sZiaYL0~gp*ZU_gJRF>++V#2DUev*tU_ltH_FJ}rNOwN70 zwkzLYr{(MK-ULI>TcT~X)EcGGck0>-9gx^2f!d3=?&&CLGK{b+gD*0OLC=MLR4AU9 zcBR#6l9l^6R325ng2JF&tI-T{x7F=y6tgHX;K~UiOJK#(bZqLkTZ~2ZV%DG}hj4=8 z%t!|=<%7SHAk>rR-Y!ms_~`iW$>8zbUFPqn2`*!P|i_<>NLzceV$bRhGb>NmqYQ+>Nvxv z!5a7W4|g=w{(oP3R7)d0Hq)P_+tS0JO}g5}8?@SryCl=a&c`ws(%)n_eMk66LItoc zL{}Et{qI3;j*@z1#Khz8KC20KEFZPVA0HiV_Z!2BkXG5A43{*E1tWuXnp$!cwpVs@ zA+EIgTY{06QP2fBSDRKc!aS%1${RfC*!l6CCmbfiY2HDT+LPPKpuoSEYSXyZ`BIO& z1L+Q&N_36et%&(Q(=<@@q|T&qACs+(2RG#p*My4k39U49Q0 z5pT#D)h5Qu0O1JPjygBJoB)VPDtwk#E{LDSk%62`l$~wltwX7d; zAgrPBr8=sCj+R)u!Ol)|P|%YEG^5_CPH`E9i54jqf*tTXMPaP>Lm=ZX-?1e+mx6g8 z3}iP{B0E`LUV<=RS1KxH32+W^oY%#|`)RDgbJ7N74o+B2bQb2`-AX@VTqJ<44miU} zjWN`L+5WKDp6I1cF-iqPD_*x1Kdw4 z8|urtou!{}R;vE)C8JYKweyXL1=Ht-`52h}{&7(M%G#Sw6Jb=95&mj7y4-EuHwY!1 z`sj$__ikjO@ab!5M_K8@_T+EwB;-9FqB*#>KMB8R2yZDl!k}fgVdf$e|H}d#l{Hn% zUH^b6^Oq#xtoR+K>*LAQE2>kEyath-u6nO?oeMI3?`Jab?`dE84{}UPrSpgm3*Ux0 zfMWUHu(;p(AQq_>(Nu%(%7S7YX-rhdUyaTdUMdlV5Nzd`U6q31_Kq<6;?6;!IJTLD8L-(qZAN*l&Nm2%{pu3W5Ee zI#wH^X*D0!eF}Vob?w$RbKhCrnsm`b4|1^H#$nRd7-J`*EyP#U;Dy)VIbiAh>Nqmc z4s4&rZB@2`oyEN;+XH%m^;OQJIwRy#NlU40xq(Jgz=N&mEFY?hhUNiz0bdyw$8l6PR+E%^l~;BMysGvn970-K za{DarZ0tn4LC8NDb3Uz;e z_hWC$jv7|=kJPL-2N;#7Q{G95SUKYtt>_m{4*#n|dhkx~2tQ?)-|P)T5nlIl8v^M$ z8IRt!_6n2Hf-kWOOYTim&N-DeW8}vnT#q!G3Fnxx47@b9;1+TP2v!Q=4}zhkspxa z^)MKCwi{pgd1=OIVwAr89tf*%F);fCU;2z+fpAAX?cFYSeIh92Lt4OlB-%;mb_ zOgCCsptdo>zRGjTai(D7n*ZWl@!o#9e{Ax}8LKvKU!&REKX{|*Log^IaNSiPM`sBY zw9_gr+PEM0Zvr6N(6Z@;TrkVF8v1ws1eY0Ntw^VH60%{ZV*h!4;;8wWMF{7yR*5V^ z0k?<3vPb_L#zdc6<=~x|*ft%BP8|h#+%JOIPK3_XDR;faM5wfK(qc4xfsiQ$?qogO zq}F;r$SiDslj^eGnjp#O@4G$U)2Pxp?K}?P@i29Rc=oT-y_$&0y@E=8*(Q5re`ZLM z2<_{Wd${jMpgyk;{+X za7NSCz~^7~8v6W(gL^fEg1u(8L$2ChZ9>Nnt64xQz-vRpz6rzi?E^EyfF5K`&hX`W z7O98{=Wbm#i@|tdHto*1EhdVy*WCu7DatPz6mjF*UYBovc?hK`Ciq$BZhpudSY0{H z4*2G|D#WlPid$p9w99<;)b*U{q~ARG57@`>Z7(3H1Y9Q*h=y%LTjP^&#UeN=LCI;s zs&)Z+2Z6+p&-i^9ZplO2`XN|h_L~LudF}X-_V1q0bhugB37iEr zDj^u-Z#6LqMel4G@#$_3uSMGrpbv~@XyQAJ6;+X>wcsC^OVqs_mTC_C`e|?EIgbq~ z7LJ5*Fn@U6zE76`4Z1{`9l(x<*kqoT$0EO1=jyw;{vJdyswN$`9dwEiP~g6UA(Qlc zbPhT#c_Wv8*?;%nzNzLX+YYmkH(fbR{JyyQt03{-Y`=h_hho5d=|7A|FEbRizW#pK z(_;6^SKWOS^kgug!OQD1?9w!7k39rCH%^3wY{bp}$or1x_og2-Ox>MTGA2u|;6@(h zz9_}?XV6zA40EXxgmqEUBgFZ2k`;5W#Qd2F=M%n4&IA$OX1{VJlV}g1_WSol%b~>0 zl1!8OZ$&XZFJ24>pv3KUn3F7nnDt1b^m($ zxTYL;BZ}hwp7y!#I#%x;@w21#yuC!CWiu?u#Pk>mNMNJXwGIi|z|T&nPPX>o7pT8} zjEl>z8S|F{ujV6XmaD`ezB|qz2_&J18N`A2Wdj9J+EW}s&vwR>Y$dG2jvaYpGTC~~D zq5)y`&>lwVMsEep6miB-5e96s$ex0XAy{+3)kZgY<7khA!9z+?5(a*bP1k9x3#Jgk zxIyP?GY<1`GoFVndVpUYXi2cw71VE;BpKPf=7;4?e$-m*dVRKwsZ9Dpgio@Z0ffoI z=al_wnhF@VF>U5a)?Sq+{MLiM8$x;j-L|k-jtwpDc^x}~`{M~In5iq*s(BxA6Bz%3 z;y(79)xL)DCx>uxTk`JT@*MnA6o>vi-_}gu{(iaNWf|YAXmE5!P2&*ys5y9(rvl^Q z&E@R-SV5iQTK?6SlTFkr66MH~n62i`;!PVmpE3hBV58Vc7kE#R!R_T zTQT}8eyW?XogxctPs~o@vFzkp_MpV4--{9@m#sVJ|MyFotIz(knQE%a45vZ+IM&}< z&#Ptx7jy}_UoHwCXB3A*#8YND0Yo#bsQz!sh7nPb|45;&^gRXO?lj*M6?If}oI@gx z(sGV~vSW+EskP8~69Gf??4r(ha;0umBlUek zlE~;`J-?4nFTYCjqVD^x;y>uQ40?MfU|_FRnwPl$M+cK%x37**b7%7VhG4lj0F>go(yq>uMwi;&>zZ-Dc}8~sCS3&5L7uqaYk_|nM zlX6dpl-38Fi%|0bfIx)MH#yLUGK^|c2P%i_XlaON_?p8+R+?g1_!(niF)|Qc9=A0Y zNd!0itadApM8zpvPn`Yd;?7vkh}P5(`kwY{YG06_hIw2sp#Nop21wKQ9-A&HA_%KMIl*u z=AkS9+u8W0Jk`nFHk+RK2s1F7F0Y+t@i39H;etj@MuOAZ_HxcpUYGzNpz9?~;v)$4 z=nk)-r>AO}$Xj68nLDXiaKzede9QSr6ccU4k|CQ9;VHL#xIL?k;?wj2!$CCdCflxt zs*M7m>O&mLPD1pQ0B)Firo3*gr@>MZMFsS#Hv;RQg!}z=+$Hiz;3e7_SivrungK4# zG{eQ2&Etb=lD{8YIDiyJ_@+a(&Qf12wYZ0kpN^VxU`GqWhj}fkK1Y4mi55$uq|ey5 zcFkjPdtH!c{M|hjd|kdRLQbpb8f2I~O-35+-&}4#9XrBZ{woi9Tv?B^ zCY(0Pa@$6a1#7TQ5tP-{iTUmqH+u?tvVoKjqP4SAYzG3?7F;2iF|J0PI5st62(%s;J#2S27 zN!X(4qSt~k9!c6H90>Vw{(2)0J=^5HBdc-(o%=$z@VoC=v3e_qRr&V z4Y|jjJk8e|6)38p;&eI@dvXwi7bBYzpUSogS0VPv!l+f zB2~8IM*-(W-7_hRS_7%d(TVS-v4gNiwbS~05i!?@!$T+ffI8A$Xb!j7wJ^7B?Ycxt z;wmGk2%?JD7ATF-Hr~+$m`5<9&VtRBzGHHr+VWF;Wgy4U5#;_7>bwNA_CYO|zAKjQ z{aK-VI&bLWd-VMIH)h;EPppxR(j5lT=%&{M8rxRpJkY1rh&DoYSkMnAN)8)6p!ziR zPvvZBhFS<>o28}6blKV|>ZJH?p1N- zsnSD}e_gz35^evrd^tX^v@H-2&l}U{dQn5dGEL@J7WSpXBI(K7``WGd&xUnNvx;Vl zRIhVbeHEek?-7zlWK1$)Z-L+>&NdV63Rw&3~ZqDSGD93IX=Uw#heC!493jQVE=H>T%t^V4&db8yD#8XZV{1M z5*~sq+jv3x#XnD;vAyBEXxq7#AJ>T*b`W*9xV+pq8T53nx4^+5xbKs|7o7%DIjUXm z0L9*%B2=8Vh(6vV^p_c&R-T;6HVw*r3GY8O9{LMpAf>ICLbO}JySbl4?vra}Vwc;k zIdZ1SB)F~g54gM(zn`7j7W7@lO-}lOPE&Zx#AlmH+~k_rYKX+9V}I5`MWqlL=^<5t z%G-tI7gLBwEQy_Hn}fa!lz5V1v=Q6(>fb1VePsM^qR*r=4T+v^RR;1(Gz&>C9B!cU zedYyy{D}y!U9T7OOzztRMxI@Cei8Yy<*HqQ99*`c0u@0yeL3+MNO#L5M?TDL{WgRG zK%6=~7Frdy~fbwwbU9BT9P(N496O-rr z4N$WH7Gb93w@DHZVnuSgP2rvV1Ah$|D4}X0!qQkiNmup!!9-5Vv^$l7KUf%7dmJUJ zgN7PH-z~VUV}uJh`*cmUm}(|*UN5JIz8`9k9F4`I1Z|g>d@67Dj*sujl2n1Y%LsfQ z>*(KFT@AhedB`kSt)$sL?tBtlQEU3Kr8NiX7=-isL*V&|ogGnJ z-)o`*q&C3Yd8enYIQ+LcndGu9AHzU_*Vos^%V>}bpAc77yBc4&T^1IKe4vkc(aW9z zi)k;;T-;3+<~~N$bp(jm2~w8-WJdF?T82PTXJh+CC*x`%Ti_vC#$OTGpO<5D=O=5^ z|M`Xg_?YCCY;RI#SQ@@Hfpm(h#XMr$Mcj25waKhZ-+n-fkc~OZ%iWYB1yYa7yjH0>ZDAQ(IXI16r<` zF_qiYzp@+MHlnx!(*fSat*7#l#gqa&CqjuqJZWz{L>By_9hq zH~2gkpr?OB5DP{qe*OxdNH4FKjN8a8u~X5Y+BI3qR^Lqh;>nO0JSbZGIxtK$ZUQaj zXUXVn0aQYRv#KHEZ*T6C(D&a&o5ub`^x26x33l!8aW~Q*top$FJ|Q`P0K+yjl=ps?vQpLDJIB zBb*3p$?xM=L&h)C`s4*BSh-rANqy`o)^5Q8;*w#aIcsFLg!;Ny=AGM};;ZWNR_Pg4 z{KWi?y1uf~UuQY=0qY`$G$HMPQZ)|Cmsa||VG9uiyg>v4Z6)IuqXjbLKJJfc&P_Pb zx-gTos>^$c*Xw(4?w;YJ)qkg;7VnV7)%{QlEvH>jY1o0cO* zk%rgb%!I)Bawxx&%kW=Tg{9{P3E*+t+h?lzo7H4AKFs!L(^aFD6fLf(V_lT zRv-?l1i6EwHQdf8St;9o*%rr|ch!Xr?PM*_J%xBx$w?FABhxjv-N8du)O8y)ze9r6 z_3kV^SrxKMB(Qw81b=j?Mm3}d)*Rn@H}A2k|0JOjC3?~L1Mi3&Us^*nC+}|enkXIV zRZiXWBO)xZIXF)BV+Tr(8&z6PEw93SIAVQ&>K*$za1@1zK7D>-sbD$Dt1N83M$##F zz9oWp>ub3$EO)#EzVFq(?;+N-ldF#aiTR%-)N@SZqksRhdxuEHNSi~f*vN;5{*@^r zRJK*syaqeE{=AE6n4KvSViWUqx6q!6HFm^`{SyhWSOf#XO>RF-doYT-5!J6&r%S+X zx$5_r%3ru~o`cP&=2xBRmY%psM-d+~A1IJiEIKBo$2e5aC^1JK58vT{ z!NG~LMkK3c@lT381&;@|Zhz<4j5>U#zrCddzM7#e>X|7symBLNuKl{3Jn5iLeBYUF zdc>0?zBI0MAf#sH5lW>)kS8omif|g7MfCFWeT!G6`Vq!n%vkWIm5%oPEt3H@%dCE> z5@V{U6*#8n#2(L#`DpEPQTkWSWo^!1Lb0;+w(A-3<`UL^EIE5@Lc`iN+5Fybp9SqI6`KpC~O6gF&OXu9%c}P6pb+}Q@px&kX$peCeUBeZ#h0^ zHJS?yFxb7u<)qLHjeRbmambYy&Vl4_n#XD;kMEUc7QLJ`huGIVSw={_tx;p14s4m} zmw(j)^55!z`Qf^KJ@3;x{H^=n$8i0MkHV^Y^b-3WuT-~R z!Bdaa#P=rha>O&;DG?!y545Ge2da^Mo4o@job2=GUI=JK>_pbTAG5|j-BU#vE-KqG zo)Dj&6Metmz7tD3_zkOdJI8#~!1(HnYu9|ZF;Ej!mZlF>60455Ck<&7Zx~v%;9Voa z4@*&3#0*P^F$EI;s>4^QJy2*MMWnZyWR{OJuJTOq@|-6PwW=3J_dRYge;pnjZ1=n2 zDmcuYqRoG>P`-#Le=?3EO4MjXMjxm8koRuNlO}z{gYk9ljZ;N`$WUuuh1OJ?m(vlD z2h2~6%O^p3Hz*CF8IYkKlnJ-zFbRcbH3{Y>z85TAzKMyR-$%;W$LgjHa@!rFFzRxn zX?9kl&APmQ{8DK{+sspO!Ui-6vyKn!Cov`fE0WSAZGJN|rDeT*alAypsn$Z_@AMh8djT;6$ zqDg(ogxX|dkB0XiZqGrUe~G_eR=JG(v8Kp|YxVXZ?Zj|0$e5In(Odb8x3IZ+6g zh){k8NE}J+v`7BfoT)DDPdaMqL+USm5z}MVt&QE(78ExNbD=NTCJeB5iUv3eJuG=F zRWhwD)K_LtY#8B9`jAg(>S|4smD5iek1hafj4Unz0ii8vRCL+SQHVPB23P!8x$f{+at{BadYT)q!Wov23&&Q0%N}BqhW@(rSw%tBr{MT{-z`S5ytR*0f8STx+~ha! zu(w;`wDoqTh%vkz;Gq#QDg*rr3-7 zvdwZ9)`Kzf4wqvTJ|#}GUxm`_%*b6nI%>D7;w*H?NFVpUmIxt9Hdbk|-)w~8mEMhU zTaRO4|G6=i=m786R-e_LcT99vRdID(Ejbj0e-;Ggq~%6Q@BmGg{yDW$4<~XRm-B`V zw6Qqz=RJqCJ^DTg^Ie&6oqlqNSa#ShE)ieW!HWvboNwf`w@+SiYbWjs=ZKgGC?*UX zGg`{8}{H!iDi(TN>*uq1;R)rI~c=kddPb`l3!IlsE;~6z3LVAgkToy!-Jq9%HlevrQqo{<7z5jMYTN%6C^MbBl zfv&FWv{8{!UoZpc0YaRNnkbM?`nTX0Gs<(1+2Ka!v=8CGAp`6m{`!q_j)_p?Isu{T zy_oH=xSLjz_~OeUjt_U zr(@X6vzQmu=C-DD!W4M6Cr^{=oHcTiP^5*Rht)4n7dmOu$e~QV79r|uLB|1_u2l;- zFC07B2Vb_=zv~kYJ1Mt^IBR6b4tq{&7lq4Pf-z8`)rbbQ6Y%gWeDSx4;GOAzIt+h}*VE1M{= z6y|L_f7M@d03qJ{wlB3~2#8abGUa8!#l^ce&P!88vO(k$5vN5x4@EFj^cvem3V5=B zUvjd>mde&`6&uqiHj=Oj=!3-|Hh?KX2N^NX_Y`nHpFu7qGNqW$7z~kVe`FXWKU?ba zi}1=TW&vxp0bVU3A$9ke!U-EJ{fJ#P*I_o)sggs;=0KWw{)Z0WWpW$j`tWNnnCM#W zd6mfpNlJE_=Jf?0j?Ia>EE2OU9D(Y3#>>2r9mL@{S^B8NwY~}5d-xqAVXqggwUC5k z?9pJ8YX+g&O)Zj91<1S-o#7Z2a!kq_`M;wwJgJwL_mca0+>IR&JFISDant{00bV7; zt56VyYG;6E(4$~Pdo4{)DeCclLgBZv|C3vI`2f)Gco-Ov3Q+I=T`pjq7qA*|z1nh9 z6{pERh4=i#}WQkgcV zDZIAi%!~+Tj}~Ea%JDl1ugA|@d6eJ}wz}c`EMDLk^>wVPgfqu?k;wwBx(pgG^o z;phI@))wg1X**zoY=k&5we6=)9z&&(0iW*6t+FI5v*l>r0r_;{!Z?Va^O-g?6yPx2 z-36_+OyNh@9zH_AzK~#39USR$QLxIXe)!d8`t!2)?)aMBOQ6`(z3ccK2db z!zN>5NjdNC4a|AvCatlMgrwCakc{H7u`)3PpTI_}Z-TGdS~G%UnaV3IxQA<2+CI|l zeHej{hAA%pEMYkQrnuT80q@r4CyEgW;b8PsjT&&I`G2&2X%gDv)B(_N6{EuBh+k6|Sk4?tS{taru&$P>o;95DM{lV4V+ zsYpzK`pVgS!=+{wqqA)Yaibe1)N&HG4dEv^CI?&jPW9ZT9i)=?s?ZoMZsX4~T_AN! z`O7sCc;6PZghCSy76Ag|VxfqqOR7OI4w$k&xiq15>`MHpKo1aFfGyvn z35D|95n(S#(uM?&<%A0sL&V~2F~(S*D+`A}g#uD5pM_6?SYvx)a_@R^rJd>fG!Mc} zEtzG9I5o$MRz0E~n&2&ZwSH%0^M+qm+jC|1FvX()A3^?qCo73|UwF02B?(ViFL=t5 zoA55tZ3&MMTN1o8#zF?50@U9U)j3a`(ywj$mbe7O6c93tScyQpw1q5o1Y7>?&>g3o zcP;QgbMyh@+9KluJ7`5uj=5G<{tC;h)0o`Sev>w*N2Mt)eh5y(6gku|nd3f3vq^w}Y2^&Jl&gNvI4s?C zS5nk{KwyJzC#zRuTG63M&!)5x z;h0sO`)2i8hiy|#Zc(|z47nEdN!vkF|0qK2XB8hM9Ut1vU@EL*=@@vT47U<+wXk6bR2eH!CTfaX9Nh zA&Z8>T{BTpb8s&|JQlJbH?Gdo;Cn56uYFKW8v2BM4TrCTQO-P%%YayPch_HPac0&{ z7EBru)6X9JReQ?xAn*@k92$N1S&&(HJL7?aa84aJzjf%Gc}f&R?6F z`b-(@IZP5~6h3j%BvjctrXab+^F!S_G#)5SSab0j69kB`p?uWPqQmpa`Aq@FT|{4Y ze*ytYwYHJdstl|fd0w#kesmA$OOpSo-0z(z9W+c31C|FCDquZ#-XxQ6$kxk)VHl zorKw-OCg7a9tz)3I8IBljI*^!^6rT0cJ}cmlSY=?9`Zr}yBBHiBkYC{e4D|3@6T*# z@^os*xsoXKAgXAILs(c=Z}%E$)Y>Y`4K$Wtgp*hpq&6_=*tI~7v*~Rl&}m%WP0W}@ z1}xk&!U05md7Sr=QPKDg@B6yD$}I0#di}b?MBgkiy+xOQ48^#Y&gGncJK!7fV6kiY zx$v_NOr+ue5_|b7xMH!@^%*j!z0J?is@`6Jb<>reg*Gx#+4^{u-vbH|ro=)a zhe%&NWoG)^by9h5XEur+5WElN9Z?AA?A-rVj@+iKv{i!F&Eurd$$w$SKH3q*Jn|4g zT6bBm82I@{;ND3U&Fb>d&c*(1nYaF=(>t1fpcVgDr``!Jxa&v(Wv-OA(2XmMiLZGi zuP9=~_IZ+lJrD4OgkO%7plUW4=#6r(9u)?tOmA>IoU?|vE2+XG*U^7|7G3M3AReFh z?3l9BH)WJ@`97(V^UWhX-`-FJu~$q6Y!4=AdHr?6^CJB6iI3Zuc^NO6>>#+u*hf{9 zz1@?Q1wn=t|eQ>yuHV7 zar+-}#Z-ozkbIrgfRAH=*^Dvpd7NMHzw9-z{oM%9cNIF)>ikfzc$kgz8~CjbU7jia z<0}HrS-cy4idX&_%`oRtkkcyjjeWD=>%zl|cJdT&s`J6r)^ejw3wTG0mb*fRn}ckA zjUVaY=SM-n(M4di*Qn{T1cF<)uWNTv&i`8O0xivt5UGP|R3B384FjP^yY^bYUp5`! zK;nIfe44MfH29UhiZJw*UtNRCmcz}>J~MU)7+A2bWpde(a$?B^NI20TO!Ld>5knxc zB}I*NX({Ww(W2RBR#I6w(k{Fk-4Zi3Rxj@J-P>jmlNM-YZwJW~RXm@I?Isgqv&$sa z@noPw)vLt}YJK=r1=O9D>rJjaMkz?N@2?&nXp1pnfx7J+Je9g7WUcBmj2L_mg%RV# z0hgeHP%R+py_2x?%NXTeZnJmt# z{BDRSBWlEQAF5`3u9Kp}45vVCwQeZEUfbY_VRA(TdH$ z0Z_cXDhsko`(0XStyWxc{VHc>DH%&j>$k8GT@)kz1QCkwwoD6O?U*TX+YeNV2@qTV zZK#6|@1x56zneiX|9geP0cr^48|bR%*}7*IpuR);Mos_zr~;2w^+ zF7?|dg0RI_JG`_{RghK6J%+4$5)S1XVAz}gowGrqp_Y0h2g)_6qPi3Rv~gm5?`eEq z{2V%j#90^AH$Ki8}jSfD`7^4plWoNI$)deT)mrIUek^o>E)*T9mxsPV+h+jifw zf2OS<3)z`MAN{#X-}kdzH5fvF4mLQ@v!A4KXMvZgJvpq6}@-hKXfu(#4jmC~LqaAZ8XwVu`m?%_IIcQfiJ$GAa%HAxd@?v)XBHO3g+|;D2 zHL563)zZkUdP$*_#-A!fjvU*|9RP4dj3EOp!%l{;-~JZo*q*RHq9*t`weQTOxo%FL$z4mm%wYeM>|tPlnQ3GgVcXt(3pQ z1b20-0-O8iB33etbZOQnmQ`20F?ngr7{$W55AEqIZfvR-hngDm#&KO_oOfB8qeIyh z0+ep|ci`=6SIYBXDo7KlLifWakSn9t3Fz?4oF^2RByO zq&Q;@3t%ogBhY=fe!-AM%yDZYUfBS}Pnwo4Q;8~k*n*eN5Muv8#?R@udnut`W{nym zh5!fWoqLx34W~--FY#W7F0=67*rfRyj4-=>t}nXURj>DXE8Kg>TC65)#-0#uJK{kW zEB!@TEd%E?R724bKk8-mZNK4TyB7i@8m)QC_{6e7JP_3lqA4*} zm%NlKK5A}2gn7D1_7M{P>p6CCvwCiz-L78~#$hp~(D;)86*jqwO!|F|rG>sp!sdKKJ)l>1b-Pe9-E5W~M)Z14=i4L&Bdf#T-aQ97yrcebO|edxuF) z$OeOFXqQ}CC|V7pI~^4XiBN3&mWZ4b@g1H>~Q7n8ybRT_8WhtN7p*Q zpcWQb^|P!f=lcsqB{zJ5(I!$5qe~uDBs6nzTM*l^lM@ZzFR+rF`#_gr7=9{A8!0EK z7~I=)Z}*X*KK#yOGZ1cKL8Cu%bc#z_8j48k`nn2L$3m1(+d$TxE6Q!XwAVMsP3Cm4 zW7}1+*$G#5kh}iLb=1OTCe3oljW zR4_O-2Nvv``CX^y&)lwlDEW>(d;9tl2dE5WC|9YMKCY~+6vYmna6JB2Rr=g$!%48; zu+r?1_0|m>Vw#>tmHf7sOGztHT_Of>^vP8dWy&O<5*5WLK4JHSXB-}G4O9cF$!802 zr!|=Q0@&;MV5I>F85AW~z9w7bF&JLLt0Ka@J|ZVBWKg>C<2t3d3aay?=)70hxg9Ghih0LIM4)R3UC66arP z#5FN`O4eA|x$`(te~_jk68A9B6fZ)m!6sk)^x8)uQvb}_c7NO1v;ddm>+x5zgs$B9 zRRn>Ox?ai)nZp-5O3M_-P!`6kNGS9XBb9w_fq>#;d#k*sv4jMk-0gdOBlqWA2^KkT zn)5U(8sE7VKv^OMUWBMCZcp*@rnztuQOs62(H5W1;Yd6{fNO;GF|sz6w_4YTK=#=_ z0h%Vf_M}l4pM1?OH*4g*Y#Fj`$=d_!4A51^tIk5VwOb$=7S%2#CLvj#2Lmc%^0=7* zu#uXt?3wkKH8wX}FuNa25rcYwxSO-{^0eO_N41^f)9M`b!89O{@4q?N+h?AQ@IY+J z8$4o46=4v>gz|O)LB!{WVd18~RAYk73E%prV~!d1n=KOvRPeBX64w-e*#=A0-BlsF z5m#lI!eXllm|4e|jTI8{A5lYLLT5!YT8~bbY*o%cPhy7Yq|wj}1-k}Hpr>amY;=HP zDblC3uyuRMyek_kgZCI^G!$C1({C_3TWx#uI}YQ#bqpySBMQQD5Rtu;1X2GW;G3M{ zrvXN_QBf6~LodS4u7WORvn9O*BS)M-rdzm|A6%dr6L7IJPqHVpndB&W9)lrWMgAJ^ zz$L9_;7DU*5#B8y!uexyrflp_zFM%B3;otw?H}WAj_I(XNF|ES%P&o0-Hz6SxGuPmsqIHSCRO z$3s|jxa06BY>L}tkd+G^Wk3_@X8Rj1ifH6;!cSh}-T*y#a}4jbWr%!zw6K110RBi` zE=i|&;j=i+pL=rvfEK56_~Afh3nu^_@G6Jj9XR#J%vydkc;3d#_2r!&R8GLm$Aj~^ zndH{HFLHjwQW6NnqEQ5~S_cWd+|Gdvv9f@Ps_U+?M&;>7Z0H@w7^K?Jod0%?d3>KY zczpnbcH)>Hn-0$MD||@{;V&^jQgS9o$kHYlpIyzno}aP zepWDdRG|A?nHFC-di*{IB2>i0pC|>qLUm3__D-4E$qIb;N_m=?8{TFl7!7NFTQBZo zC>6P>(1_Fm@kUx~C!XK!mh!zhk*Wf)0aRwoYI4wKphbsMRp%6~|FA(E5j};Dbay?c zyT#$7t-8I~iB)HH8PR7&{mZ0=&odrxFZV~mW*@UA#Q+BsHx6!7U$P2 zWA5JG-j8h`r*1|P6(FLBQwMOX{vj+Cf3dO_RJQmX^-Ey?V4X;;p zM(hRRARd_AyUq5vSIKJMCr#N)92H*m^!2$+=m3=fx#yh6O{Y|&p!XyA=oi(okk9of z&F8cmU`To0cX)*bT>|6^2$0b0gURz{m~ga1e&TIE!>J^lLJ4OW_YYnFBhTzt(l>&f zEV{_vbT+wnqC`5q+W}(fWs`H(wr;hi2^-NjY=ZYnS!47WSYl`jT~kXdFmv356+d&9 zsE3EXXhpnqOr3;i;Iy%e)%Rypg3R`IARI{#Ag%cQtuO$yWF_lvk-c2rN?ty#$MUBwP0MDRF0e2t zy4P~REz+UREo&akI%X{Zt^9oq@^m7bQgi`eF4OI+q;O0(*>=-ibMnub13oulKxM45 zs!9cB7tmn6%l&g*e`OCCt&Z9o^N8Tp2A}I#Aj2BsWljTD9*gghJP`inAf9CDxP-j% zON%v=E!Q02L7BQUpB18`_vR3C1J+->2zs%=LO1>Rs}QQlLqwIGXk+i<@Qca$`P7OXkxM*9=ez-rsG~^$<`e=FrdikX77N8=Yo}WXq4wz7U z3_J4A{Rik5oS)8ql;*OB?03JcbW0Y^_MELW{{*%$(&tUM*Bl`zIsgXh+_R3xvi*=p z^WD+_QR2~%t2f@q>4hs&(hhjUy?D}?%Kj4u!8tW4$g`0HI_S4eFS7OP)&z>%34-h< z<(s6XQChQ{F7|8eZ|iGo!x1|tQq@i}crFx|EgQ@4iedY_%I~2oYP#t1a7b6r4^>&l zChEUrYBmPX&+U>M5U-bSDH#S`%5MKTbJ&YDlsxY<9A<=N| z>ZNLDcLs@Q+R)`ChjykyXsr}7|ED(jQ}*fZr_|T?mU01W-SD&j955Jz8-v?^GDPl-JtDe-E}8LPOGb zi(t(*o?Y#6mf6X1UtAqiA#KOb2lY%%Y2I$*9P@NbM~ooyu%}fd1^LAYx`Tm5zRfxp zMvcmRvzg+ogn8qfbY#Or46SI(SJa)ziA|V0rDkW)h6vt|`EkU+02rx~w#rgMX z2&;{`r|`(56IMrXmPc^3RyZK|kE~czf(<_3a@4lH@GQ6EYc&_ zR8?&O$v}x#iEo-_<-~T&zrBXIuV3^@i95yZC==~VkOWJiVDkNcOLzYnzD`K!K8tpu zO_50!ueBNOpk#OIXQH4)1eh`S7#Q3B=!vIdxN92NFH8jYtIlZp-e-+kXix$7KeN@o z!P@u>_(nQ%Bwfu&7zN(tX8I{#ZZj%@dHVC7GS{9^!Y zZ75QR*wiTpZAp~p#PRXKpza8vSUnxPJ7B~Py%xo&{m1i!jH9x1X(IuXsvxZ+Fg>RI zmj|0{{>OoISN>IAnDxyJ%rX~w266Kt(C7u@6aFn5{_T5&QPsJ`MC$|6n>c_5Qm%uCBO?X^&*gQDm7+4juFooh3SYIC3*FHZ(*G$sh2z>p)?? zF0-$wxbsL?e@R4i{KIw~6|Q(y4rk=1XJt|R^it6$E+^Oj%L1@K!^f!OaY(Tiu_K0L zCt&1oG@0!UtSP5z{N&7az-dDImyHp~cA(YY9s?xEH1l@pX`Z^saDN+PbZ&HVpBQ~4 zsPN8MXwCi&ADu1d*>Y{MV+lW=^+U0g)ewGA(a7U*_zgWn0aspL%anb{fB!o6)I?GX zvgWm}we=`d79V@LNlME9`Ql-_6PhcnSJGBC9d`^tIp3c62^GduUnn5s)1p zzPod?HQ5pUPTMA9yk6MjrEt;x=J(FNYh2LBIzNtK&{&j9o-)y9{KkQnzK`#wh(_;) zaR3~9IPM8Q-xdq{P)hE4L;?34)P8G#_r4i>x!*wRp>2ZeiEf1d;)9hQgFm%HfJ>~0 z(Ts0DsR_WF9xA#Y8Qup`kH=Ceg&~bD#~GXsI@-w%+n*xX$0pzuFC#s2MsB|vdkNe%Dpb8MYj)SVGemwYQP{$#phr$fyl z73z%#ij0RK3cwTlhz+ zLFw9$U_7%YQw-+$EywLmb?iD~+(1t{BvWi1e%t~>S67^;r>Cy7^kIItB)o>84}lo! z%C0)@RH~xQYm)pMuwEio%80w>r8tK>F%Fv8=364>1^P8bOW5vA#)9**c+qp{dI@ec zPT3ppX_y#0J+Qbl^bKOK(Kkv8=p_HZh@O+X<_#AHQ3{Ie8%^R?MzI`MUhY7)@Nph% znx6|^&qHTiN?*T0N9B9nooaDVW=QBfKQ45;5hKMpGDM(Z243CHDZLkU{NH|bON%>f z#`?h-EG0nRh{bazq%;d&Jm5jkRb`v1EX9TA>_)D~YCKc6jtv&>Yjwo(1Vf1DSEDh$?HvgB`YuY~kfa;Ct>HsK3U;2(p1dDzz6-qX**xUo(eLejb<4 zz|r^u^u~R;Q1klfocKto+C0EB5XTMNDXAU~CQxm@My1lx>UjY5#i1c+rCL;OAx}UD zauXZZe7=b*b$SpY`-#88ppowuTN;0N`Qrl#mPKt5#iOsqm?_DT)_B&+%A6%?;-mo7 zl#SaAxArqw#v|nq3S%q{Y^sx9#4C3g??%m^6?(5Mn zx%|kf)x0CtWF~C3$e9dd$8(WpA_m zTed3IhPI+ScT#{3WC=BCx0WLdGl}p?wBZv%zx1%={p*)3Z zz`4}a*NOEeh`?pZuU4<{Xm}f`C!KRcp2ezTEc)`}!RZ^=jw67Omr;YQrZ6Z^g*UQj z9(a}b0p#3a!I+R_TFdP3H=}WV*>8jn9f1HX=!5(Ds%Y_-pG?hto5r)RSy@0L^82i% z1Wa#3x7FstB6Z=2Mu|(rJ`c=uzjgO4VPQ|foKS)vuw&%3B^q>i1OkM=MO+7?HN{2A z%RV0FLL`VswJ${?CFuW@;U=J&FKnJ#=B6T_%rNt7*Q$;17UVPA7iNT0ZTFx}Pqj(t>NONu z8!}`SQOxwc`TOM6*wJA+m1k*llf@xK5MvBsB+#>FmqRwgSN?#U%6R@?={r}z6H`tC zj)C(Xi*vTgRaIyPbJG&UqT3PxXt^;lC?#hfgtMYycEUBCg0$F!s#Z)fPM#ugs()tB z6(T`iM<3vlf)?-RMiU5e0$g>bCz(#0Y*lU_Pil66DVRMqE$!;4G;ez+PI%~@UDi^% zr!()&J<6KRWl+jRgKtl)`VqO?)x!oc&B1oPCu=!N>&~e}0U^zz$>~?V_qTW%ArWu=8=O+*{FE_tz8<xpIQwRsajrOdz!Uuq#5@>K(D_Cs;rsnaVPJYiOksfWv?GKyTMZMBTHB@Jq)NH9mX3!_N;RE#nRMIR-EU9b z;?A3qpmI>V32&0-hb{JaNt5rQ+zuyi-Je_Mi>ygjd+5O9p;elzV|25~^wRhkB2Fn< zR2nCTsw8RDp5y%d{2+75t3u{^jWWHS{2e_XIXavI=0EAZ&7+gH9=^Ye3C4;MY}FZS zGX^a1ML48pabX1bgnC0so9jr6I}S;iHo6b?Eg3ccF$<31546=F;32 z_bK&r0iL0vqTrv>ic%)dfc z|8wFB@XWUXU`*hFbh3*(OOKnlcybnRC9;`~zkai0iRnq)>tUQDP;reO-l0=)`=UAH zz8_n*4G8&n=RGG3CYQ+ISd14;j5f^hFq2yg5xN2{y&Cc|^DLps=HVqY zA>KfM`dKBy*>6zzFs?>D1gCqOAgvP^F)J{lzV#$=fyl)#2|hYSiukF+#G<=^qgbLp zaBVQEdj_KR2kGD$(&7_@%Ww@IG}m4IU2)7ov2|l4>D$Aw!i}RdZPuffp@>l4up`d| zQFn&VIMS<-YZ(}wYsO7AF{iaK>HsE(5CvMNKDfvc2Jpfp2E-pQM!&qS-*@3XHsNXs z9Ms^sn7FQKr$sPt<25GnL{j+K*Cujtm)b!GW(A-o8TkJFW2NtuNy*Iq4~wJcK43gx zsT0`36(VM`gOr7To%@Cl{jt&Xd-C5Jg!3nTh4qZ}jRq6Alo9o+IzrR8@6$VvK*vjq z6sd?7^&+H+C!b^LbL`Pak!)nnB7>~W_N`%Qr}pJwG_!j4?Hy8;*4%)Gq1c8M+Yn61 zz@RmbMV>#&JtwZznLS~O{op6aV8lQ+=NHVsaK6^v`rXoY+(!fJyTcf~N`<}U#-l`m z5aD5?qIx}kR9;iEF0}l1(^cJtv|@qPNdN;U=Bt#!cRh7@1$_;5X~&s+GWl5^nnMOi z*g5;-kOE!iu+C0F@|DOHPohx%CVR5V93eB)pl@;MIzCldRfid{7jifx>L$tF;zpJ zKnZge?s3*gat=}PdIUFa$Z6WIoJRd-av;SVRZ zA9@(2`qP&LUIbBEat0KgZ?yN5 z4;V4AVN*VF{7X_2k{#&yRp}Y9^*skcjDsgNg1sf14l9fz;BfguSR(9C6%m&UTDx$O zaqyTx>lpACzYUxVd`WX*<%7wEP3YMB<9x!WTdn5k^D7glAFC{=&~V0Qd+FjZB=^%q zQUy^e{NbO>RL^+Y81_yPGAXRh4k4&1kOG+CV}Gkk#o^Rx>YC_e=cP*%VlO+*Y5<{v<6agi< zvU*-;hO9x@6mdugRql#01T7i|#zgYf`Rto$v^>&$-x4FU;#jFpNJ+ZFxuYxIG#G|T zcw`l)m|x1LDg+>NFhOG^!gu;X3iXBgQvc@Z0Sg|aB(hDt)z%=Pvu$4QWA?9uuRF7GK7VLmJq?5YU2F&Sgqsv zdi>$_zMJ$xv(8VWq}Mb179M35$Sq`>om_!+Ql%tu#0|fVzR!hzZ%-S;Z&`C>>OJEG zX>4e$*|(p^*wB9MWmbybl{l}JKV54^3`ILU^8$TAFaG@cpr1}X3ZIreL- z>6{1EQ4OiZBKbx>jqD8A;TRLGlZ{&79H~F(6{76f(p%Wb(el?o&>FTjfsQXGlv3tj zI7>3VkrTScPlGEd%dh1)0zMCp%l6;CN$}FaX>nO-;6>dPR(w$uD=>VGWSf#!!4?qo z$iyFJK~u;Mi@Ngsb9Kdb&)2Y!8?fo)x8KDbWVpN$knUqxXE|J%5)Is{| zkp#(kokDLcV_|{Q-7+&y zISopE4JXC#iW>aX%@M10!kRBp*L!*Y60K|b(m;)8m`ARxwUdRsl-Te2$9PkdY>z&` zJ{WYf(R@wa!+i9;I0)!#^F3pl8FXY z?};^zb;f?7r>1}u|K6ZJhg)2rZoSCU9lB$VWcPWl;ARp12l>exM5s&*+f0V8ggaj+ zorHr;Cb6YAoii*;_T!6?+`oS@J&vm2YkhVSiB96+Hp*505m zhf0CGwz^!VJ?Us^{t&#Q;qpyt=B!rkyEt$7iiedIf<@|ubHdUf;50w%CMhZZ_^NOQ z1pXR`8IY&;oMNjDg`eb|ftMTS*rXEy{GDp0BgUs`!@!@ehQGe!$clf$9_Z+^y_reVHDs3?jQV9sxmsCd(42V^8e==JJFinpm9}8> z`P!)HK!HLJ`w)C`qktvN8d(vP7sYcHs zQ8QsW0O({=64tPgsA1h4*SNfy3+JQBzl?ox0pI}Gu?D@349D|&cM)_W;0Hx zj%EXJWf6C?nO~7Gpw-oMJ<@jpf+%oZ9DsV-x$k}xbnRxR(h%KZkE%Ry&3BG3vdl}W zlZifbz2S1qa$-uiLLJz;&23BBusE6K_tPHO{YovO_2#ZsrsJ7eak{yhl9oF2y8UzK z(cW{+o*n0!qb*gOcGn`gE6yfjS`D{Yv4%Tjfb%mFY*QxJVU@ad&j@lh1Th!GV8-|d zR-PPbtWAKPH)LazNs?mBq;U8h)T7UwHoMY!u>4{kK#H1?{fQt(ETSjB%{$7inQ79O zVUG&?`Yuj;_I#0b*ciu|t#`Cbqv8+USJdqXlw-&{%2MzzWrcW)bNv&LNbwgVzUuMu zaZP>w+}F=hagHmwKVw7;uipSh_0D>y_Z%T*fV)twOxkS+Eu*wg;!w04g*_&ayvBKd zXnWE8&@Bbl8Rs|yRuqmBWa1|=JGbCY0b|ObFRlC8EPB}F`L4Npur$w)?~I`@g}?%% zBY$QsuFwhd$zI0d%?oe3@!*5*)JG{JzN)0u*$MJ(b@dwEu%@Si z2bAv;w#rMFnwAC1B2`V%<~Jeh=rc^-F1zQeOtkcmG~P{;F>S9N3|09=^-?oMEJLsh z?9_w1mOW|gexho#o{zu5ubde1UGRKf;Gmelp8#vv-JBiFrL<5lc0d(1t~Hx83C&0N z#9iJ-nbVR}ib1$M5i_65GnLWnTq0o&Ftka{(vaLXb>h!R1OJJw&r7KduA6o`;-Wxn z4c`<2r8=Jr?+q+=^^#3QENw#K-XU-fdvJ`2C(e%ZauZnK%lBE$%Gn188_sVZWt$d} zPnwQhJN0`3vt00Ci_=}0EW@2pG{tnmvBa^V+2Rdlf+1n>Ai$CACv80O@M`wZtrKRH z8iTTaigoJo-E?&hQ|@{&#`gZ&Jk3Jre+XL!vwEn>^kP=@#aFjP=heQL;QgU00#3` z5AmZJqCwrqqA$hh1_{Q|U6)^!-K}h^HS-i5Pc-WoRVi76aDjWdu1=)=hH1zac`PvD zM39K47<;DWD^BMSy`dl6(6^wSOm6MFW4!z_Z1?aL3`i%edj<82Xq&1zP^Is z1J{znUA)I@DHZ(TsPgcaPD7)h>RN01&gSQHeqpfjqVd zoAvDcH8KsMfBp)ei#>;l2t zH(<2C6pqKodP>`ES-rpw0%{DVHLZbz_l=TGQvxB*dTTtpPJ? zgLxorJmZiYkR`I6vNYzl_VvE9X6(J>n3g&u9!PO2F`MF=G4E|6BHFzK+18{-*5(W_ z+8ZrD7r9{0HC;3*VC$|eEwQyGxx2gD-M|b4^(*+uC5|s6ghHJ%KYyfkW|ID1D{5Xc zAlH6RPO$K0R~;9*inwO~j}wmdY_7cZ3HK;-PLLTX-+vS1t?r)C;Gf@R8VU)}M&Tm6 zQj?(6yv$ywf-i&lXEn-X`NOOaqXg!-Xb&iCkY|U32wYSAyXG{a4Hs`j3d7%8Vj9hp z*8P#o8VORTstUd`7tLi#*5gxh!G~9Kn%kueF_s&l)bIS}5V73p4n&sl{_)4w$dk#L zp}t(dX6NPI|>Z=om&V_->yd`3F;OLl3` zdNesD{9pbqTpi99DLY(V_QiRQm`x@7!GPntUhY-^Vlbl6%dKk1+v`(FmllS=-FARz z(~flEj_9@v%5W9%@Hzbhw}-0fPAk1(Jb?Hd{MY}%s~;SWoT}@S@rs*;Eg}tffg0Ru zX`@qcE>_oo6B>vbX1?!RiHZ0;JD6#Ko=3>)vkAMx_A{yzld_EJ;=f^XIh#*`H#P-; z5hkl$k5H^TR6i{&eG#!mRM3Ij-Y)X_k6wcH(y1dOz2w|m)f?=C=xw2>Y=j5M zbV&Ic3h=ziAYveutZ`&WEpEI?PME4r;w~KRT=p;h7tc-ZlRE9H&|s*i`?@k?AN%oV zzJj%6*agR5(+3SU-rj_yzPBo?bDO^kB`s%$OkLMPQ}|CCCMv>79SVe&>&RBzwUs`m zKSy;xAc1_AMl%K?aUK)90Prc*htL%ltiY(ht)s`BB-5B5sOkqipPXr{ozGc895OkV^p82A%=dwY8v-`rDGNI-#)aA`d#?KNxS^g725$-95<~ zl8`c=v-Trl&C&TLLCX%%p?}sYxU~anK4z?TeMe!HCao1SR0mDatEt$bmwsi;7-Cc` z)O2IMFytZHeqQzjxuH+&%zQ*oC(82cc3>u2ILRF1Yzu+&eR=TW)%VoxQ3)!gHFUx^ zxo#^DW-QuMY_A$#A#r6B5?;x&z|S1jtE>?`!kcfUXiF!aPQO7f*y75Sq51hf@uWhC z=s9%1Z~=U8)5yPK>!&5)x{_uwar`MT4c!X_Ji=+ft+_ftAt0`;Tu!K=@Bk`;7 zs1t;|X?&h8Z#=v%S7H_+LtP8ST|3d-a0wj+a%ZiuiTTw%I?X0*f@??zXuec6HMk*@ zM?Se9;X6sGzJZ1oOjX@(^8>G1z{TiEJke)S_=0Q0f4-{26jJ)F;ul_*dvVJg~2N>r~7tVaD4^Cb& zIjd~~0kX+S>3^7zzmaxsLEjyXuTcG87GPDkt-v`8&hbODZF{oSXw zK&vx}HT?xQ@?S?TC3b)XK;U+9v3*ouI-xaY?|jc7o5)IpN(p|34VkC7*J~)^i8k4s zKj-XP@ha5qKRG#>JH!YVLlq z15VWr1n#|*v&`DRa&daGypf;fTp)&K_6eP;**|L$Ny$X^5EELz)%NZZ9Y37wH3j(^ zb-Q6$!=^y_DcUU4vChA-j8ly`MerLe;lq&wW`j;0YeeCMYKb*+hld~h=eDq4vg7UH zdHoj#Se9mo7iG0M?T`gEU+9^WIlT1;kqRLETW12CNjNw4(`Wct8YTR1*WvvjM3@P( zyAP=Cu;5SkA3lvCY-@=+GN;wI7JKW}^QQ;sS8+V8Iy*mWH_O^^G-*_*`P?m81V-LO zfcU@YL!O#nD**jG0f2Qzn<5u`AkLh215=fg3QU3dOSZ7Fh(=obaN6}9EE3|gtYkKe z+$!vo4YbT=%bsMI0#K)yTG*!UPP=WQT+0t&>?;#jq$j=oM&E$W@I0Lr?(Tn|->+N* zk{Uv8z`V0#mdT>E;Vde`YA4XlHP5!TZ%<5#(B|ra#N9yX;k-8qJY93f*3d#^ibpkP ze&MiShK;wG`tAy7JS=4SuADLZ>y#h1@ois=ny@rjKPmAVtY$bAS(B zw|ABFLUT6E68i(@zGD}bP3tkz?fJS-LH{b6)GgL2yL{oq-=Z9 z`}zCBNh0WlJtj1~Ctyy@qRKajR9AH%icV|s=kEznfUOGxjv=J?7aImG06(&Kt~M^p zz$}k$>qt>2uKV3x?r8tZyzYIgzp5&iXAJ2rhW&T7$kBZGQd?ndOubB?v{2k^`Mwp} zLX&z#OFn;R%!#<_`q#t{+e4*ERdb>Z6^NXcuxT{Mhg(qA%1WC}tA6iQ6fSC>cfT3+ z3?I!eZLfjR)j{BDTtInWYqzk^PO?N}`Jgu<)rx~?YIRR(<0GXwRO`0{{LF3ptY zqi&3`4x4>rwL45LU~AKHbX9Tt&4iCWU;O>;GT3Fq-zm zgl!-$Q0MdLWX_lfgq1sCtkdHE!B>h0lyW5BZ+AGr!1jwhZiw}XWNJhp!3$-+rEWk8 zWrzQYOPEE!BG~eJRJYB|nceA?MIMWl199C=4{`2fP-{xMrm4@w6cPQJ5~f6muyQt_Cqm8`(lqc;X>_?;&>*RrhuP31gB1m42xVwU#~BhK0S|Yo-H2V zzj6poALOYbsFVZolilqR4SbqS6-_eBWXf z%UFUwl4B~XIVo06z!D~+?2-51w&J}F@IQ|Fj+u;C80r&~$MOxSoRoU(W4&5B#N|aW z*(a*q#{aIrqlT}Y=z2U5(vbh=qw#M25NgPrr-V5|cd%pts)iLrN6O(fyREI=AFz#R zt90p(Wg1UYm3Ys5ufU_IEbrS*@>&U zQx~5BNcRHwZvP$3FD#_?8Pck%{;-t4%OmJSd%5~YyT#7d&dm+I_tx^~R2$qO&9H8? zx=C{Yfi6|wC+93-iH$QlQ8|i+gr)wb++>^WM}eF&Vx7bu)FclvH#mM9p-l2*EnXGo zREmVxTTBeXYHKG8w3wzgB%mSy^HpKrvk^}2rl~!NxHm(ZO7ADzv7Ie=(KM98z%7=D zi(owp8_=K3N9O-eQ}7TE#UF<3(h~;ij~TE5+o2k|y^k<*(+*K785bpwBFLhB4B-3e zkJJ)2cI*;pk=J3W@})*K{CiHm3zyp`)Iuv_1v)=Idv}ww*;#zw>uw5EghgL}N5Yc~ z>AX+G1)Z-!QTp_(ZP}F-3-==arj3hDtdz5WLf9n1vDgy7NsF)96XRxQ#BmCqm5!ld zFMw~wM`vEZYH;snqhLANeO?h$h|Ab=Yy3Uh!6nVdaPrj9uU?^k8aSf3_iOXtjH{Sb z|2L?y9AE`5&lPIU84EwIQH4Aze3L^O>*FjRc0zGxZhVbV3eiBlHW^Zn7JuGO2$GHa z-o;#2dD@YIr7;P?ti5-h+6KpBT8K>jI(YymIBMQGCm%e5_O@lldK7)7UtE{7{SQaT zg0$#fC2mB~X~co2@bE8>x1tTXFK)WNsccKabrh_W6g2ryBkCo^k@C|eT0l@JuU4y(Y~|AVAwkb6%TUu0%cN8EIpH--QImnvz)da4#h99! z>e%@3vNWgCR!__#$X6y7*2hFDxr$M)qDocXp4>vAv5ey@VqiNkwli^YnMuqhb4G+$~Hzkfk2I>TJX1Me_jV$D(a zb>kMK*HScNWT~fQIj53t0=fDxM=mz~W{v;9I-vB77OgFL|dkpJLpILu^9Gw8Ch^Uo*}6 zdM0Th2yeZ~@y7O~wBGSsJuK@x*^@ z1zB_2)~jd4CN^mbeqfF0l0R$=%_jNmoF0_^csTxu4mnYNx=_yYnW8-A|BTB70G7Ji z4`voM5x6H_ZU=_m&KGgyF>y>&!h>|RdWLDjNyqp|0VwceFuS5%jt?(XZ?~VM9&d`L z9yN6P3LZ)DAs=_S5jqka7G;dA2=#?*1V2Ua62#m%BuB$t{n%>+M*A z-Y9Fubde!r!9JD>@f&={ zbFRNNE9XwvI)i=`#}O975Jr$XWsSM4t3|7yI}39ItLt0hahxn_7rV8@nbx%7t&?I9 zxb>WQ$nJZJwy#qbUW!cqVi^}9J+p!7mXKDUfl8g98v5KzLMe!J%;PBBK7Q@}=YH4h zuSNCnCh@06?Py_H+Db>bwY>bA1Dp_9zr5GMZ@>Jr{R8*vr>E3Kp=5?%OJqXuvtwyl z8{FdzJ#+b3f|eJ#u7022KYhGyWKtF=1k}*{itT$R8!x?%zq`F*$7+2A{wue7{7pk_ zH3I$&PYpl)i<7;EZ}J8(A@koxtJ)-)lxFt`Ayp<1O2rn49h-=*}KRIVTSZp_@?cK8|y-8)`7x~X_h zreo^S9Z~wA(9mJC)UAKAd{J6@U^&eoFia<6p(}PXYv7bLLq`Dl7;6gu`Aq@nQ-z97U$srBf;Dy0=lpL%@U5WoinK#IMmXZY&V;}z8yV}jhNjH-J%4i9x8-fslp zum!W=yZ(CF`E*^{`#^uS>-d-r;P;QCPQM*sXUedkMbgvd-TFUrS306bN!*ciVZ;*D zAh6P*i2g7NY#jVf0T@0d!>qOqa-kV3C?DZEWsq4ZVY^0AmIXv7(JqfY2%8YJ(^As%u)3K6; zvHZ)RL$7r3?}bZ1k1T|DtkPkNnL)ERlVw+b%>c0_q4)<4N6Uxcj(A!V4xUB~By*^c zEyd!}O2?6!8OnIJ2w$hExV`F6$k+$@Jd5+9(NhxVHV1!uY(D;bfBoMs_kuyvKp{NZ zn}BAexft^>I4HllgxD-8 za7!5-tV@^s6gAO)ZUj-Kb9n(noQw{sLykTqaPOwLL*Dl8k@RV2ae*Z*F}y1?yta{0 zOkw%a9v402kSlxdHsn-rg&c1vt>a|g(E$CS_!F;Daplten~9;bk*F-K!QtWE%&b0< zD8)SIgmMy?wz@JXtOAmcmuppG!o)%PrxX4F&8gMMSl&Z9l;o!HSp5peq7Td|!vbA& zs@S;yJjq^Ah;Hij|82-f4#sw&+84pS#7N3fXvWbkc)n5+vhQh+t)!^qfXSWF4#Nwc zb+TaqNXlZ1G4z+Y+}WMG>Thq271{P%iOe=UZzDk+^TX|L778QMAnaJ8ku*xT$A+ML z|Bfi%;Ojx#hGPdNxZ(AJS?lePL0L~-Fru2qhmlxrmrg-OE)GSAc`PE<3^8ME>gedn zA%sY(-$iH)92*_|{$gp++IOtAJ-UY3+}{64kI9TfMwSWPD6D6)f4z;aT*?MJ1;^Do z{65kv=fmau5tslb+xTDNCOp&qlpgJULaZUD9|bxRCG82{_OBxt*k*!Uoelr@D1q@- zFT3B(+of9*Y3?WX3LnQQ_Me`X+PSKjUQCqY zMs#*CBfM1p!~Tk4e!?8KBjmBDc)&-}()x)pY2q5&>;bmU@UO2`f{+G2swzAP91cO1S){`|Sj_ZY;otv4+Gg9yZvSS# zu6`~c(~M##E-gDr-!kD(5d@fcL`BSeFIB%W@A}Ke9uGjMiJ#=kB03u>{Oq?Lw?Y!D zRT6K&)7SxA-9B%88Lbq40hQz%=Zh~(4LY;>#>TRx(v_7R%_3rU8?^k18={}M3)S4(^{=v|QBTzVC#*e}@URk%Gs7)u(2yQxD-sUc3zI zlaPvA8HNj%U0Xu>{n&C|y$eP~JQarLV&aMG!o2h)WywUSol&nQrb@9$89pR!3HyWU zgzpb7ERKbJKRE_xR6rGfOfjZK@wfx16CjCcZ~B~oz2Bd6IH>TT4jbO{Bm1KK;y&iD z`q}1d4NW`*rkH#J*<9O$=LOL0oQjs_sfs{OLYnpi0ec`uEYr(>cRq<{g+Gcr=@@n@ zzrDyu<7eMGdLRtYpRWc{HjT8olms8K358ElRUtD4j3_z6p>V0vEG#V5A0|A*7#6$P zzv6Qi=e#_U!ZeL`Xh+fk;`Cs@n-sq=FXB|{*mSgHfo(a2E){y9TzFVSUvUvH8RI<#HoA;2n{#pw(y* z-!9%BBBszwDx8$Ml^2sg`mh7A8~HmNO)M<>m)G%f*IqV>v%r6;rn51VVuwfC)w*+( zeTuadTbx0g9h4?*<)8e+0e68Rg!4m13-ACM_Z<_Rj`~wo4kj1?a3y>PbsC7@qMnZT zT}DHIb4EQ6*>^v)?7byU=N9VZbK7zxYF+ViP^Q5N!tbP8D||-fi?Pl9hilL~ygT16 zM#g@Z3uCda*W0xun>*e3JP7tt+VbHOYe&OE(b=xzAAPxoxyb2Y9xcLwtJN*@^DyX& zM-jE#gLRQC^Rt1u7z7`Sq>>}X5pGCc18bMWb@RDY+ISQ5yP zun<)>5}FJ2X;Ip(%3LO8{+dS#abDb(w1<$ve$hl$GSZX08#Gnd*VTNNI^^*Ezx}?u z+r^&2?3KEod7kRr21f~00Lp^`GpHVVh)>f+o!yQm*h(&PCrHP9Y!K#!n#%v0IGS?n z!6(mA?ECQ_F7lW@dZenkYu2SJM@G<7>_4y)?1F`Ue~Q_{Y@-UJN{mU|S)Bq_tZuoM zNUmeiHQg{5uC&R%&0#;91Ms+c?lvLZHG@g4YNVCJlMy%{%gQBQ zIc+k3G3<${^=qHWT5@tAPwGQPFAbea3B9LGGFw1QLJJPudtcq6(Pz)oGc<(if}US; zk^-Axbs~(cNWWBV$1)hb3S2;aae1-=X0@1;iu|9GyzeI8D{_ry;|u)kV*c$hXZ`wF zL8vhDc(xsiNcP1=Sj^O1Aw^DARO?F(4kJM-LJJ^zw>wSVZ3~Yp!_hJ!1|kMzl6E`= z`gK~};I0Zhk+nG9qxw2tD&riZ4v{SARDEibUt)0l3!JYyeu=Mp$(C5l}kw zeedt7yKpO!@@11oTB-p^Pq@^DR@lHuB5JkBrRS%z7TeI6pmsQ?sGY^1CWFM~PO|H1cD{CH9Z zHAlE3c2!1rABDF%#DGy{rRm1|xAUK^i%j@Zm<&B;#fMOLT)LFGyl0V1287jbeI93V(g z3aGKPcr{My(RV>JskB}d-I>>(!kiRd{!Y_E3F_!Q;1Y1Evvcm6ko>QngWP!0<25Pf zfax%@Vz zg{C=_Vo9pTB5Fta`S9!2zHynB!{x$GMv!^9zN3+hPobS%i@;6$7KkD9oZ7z!{pU46 zh}N?ZYd7-_SC|H_Ya)S@0feJ-!hj7)K3-8}p)xOY0@+kiH<@Y}C}v>^81eUD>5rmh z;6Ra^(I9IW88cUS=vJnf%OADe9hIJ2>NXXCt;xR-+Tgwd7Zh;g+;5McBBJfQGay|7UhZ= z#2CHCp<(v;5v19IGD?9TZnjTwa*rF0Tkj%khs!&tsLf;9kN@rSr(eicqAjQQih8*Br`f@H{M4j zz>UOV+l@iPND@>pkF7#nXiku@uPgnkwyLGBC>Q*!uandg}1jGPyE+^OhGe;e~@*31$_X zmT^4RkFR>qBRnc6xw>ehU2MXAHQ)-t8?+ULX5)SjFWFI3WL2WI;lyH7PG8j~!#+UR zAUQVMmbxx9bY2FAA_|SLO}G_kyletygl)j9pI-!n9nL`NV>d7#)m{wjfHZ{`98NFI^7MN*Id8E%4!*dA?vnwj$eEtoV z#{Wfb7st8pa1Of*n-=Ynrn(UYIA%D)j`DP*<8@9+a2)X!a*~f-uh zM&}KL{`yiE$7!hq6?cOp+1f@gs&5i#BRC52XT+|$AKMrD;o{D6yvG{SKc^$MG||kQM?U&5s5;-KSyU-Nngs!A_zNzAyBO(KMMn+%V-cjo1yFh9KcW+Q5K) zBTJ?zHn9Os)iIY^{-t9Rsf_6z(!&1G{sj^*fr^U*b~kF#b~NEo z64PdcXBS*NxxXjg{``epBP|fNl3e{WxcnSPwPf5j)%Z(;{*wNu*5K!6^%HQ*@s5&R z0}Pd7cEkI+1?AIAh&V)zUzE#p6Bb z?jT>|XPB!s=FKTci2m^bDJWnsut98By`L2GaO@>>PI3lJ&P?VyVq#|BRXl;BdB8r{ z0qqx{bR)1TNUY3B6j%`pW=0QICo(lDym6LZq~h`TyX7d*PeP*_%4e*}Q#G2XBp~t+ zp1)sXVzHsI(c#%LVV$7;YcyKu;Dbxhd0vfwK5HPuOZbF;x{Hw=Da(hS^dq^CT+?sU zChfj9ZNoL!ndy-}!wbC#!!1yDtEP_B&!JM#ks#qW*g%Q`Ry#0SCG~tN@`zY|vCyFeCfP6VXYivZgx!U#T-@V3y_NhFQ~0 zpbI2i!_c6i7U&yiKNfg;f)|^CpZH1NPf&cF-FtBh(gDEujhn#9sLSdAcho!q1zsJ- zl8t~9%qB?#!8;)x!ohtimmmYNQ0B}<& zV3^^R*S#cG6i1Wl>A#+MLuP1dY znq{E{yY<6~nE#p|bSutmA%Si8QE^yOvlL-LR3f~A{8D8n4LYn!hK*X{;&81&j~#Uw zdEGl-M#kP(+VXdC5~S3q8ey7k`~>IXiqhP4pCE-zr+{vc>+6#g=*A6<7(y*0gDIUF@cpKEq6Fz9NWQv>f_}DK z=t!tT^kjP|-3cj)+w8q6Ey5kO|HX20dA9|UW#eMW%=Z$FX{Hh9Na%?}?Wj&cOejKC zNV#NB%*D$u4cdoas{JYa#TVw%c*8mw?fam}D#iIb%%w?bv9O;_N_D=ifBYnBNZ?Sy zNKjl6ovvul;RNQpVZ}|nx-K&*opqTp~qNj36r=<^N%Qi^vl7`LdmTc(< zticG2r)`ew_oZSgzPvC;)||^u0e{5RWFLCBe9P`_kk~aGDH++HXNJfpMwKl^B%%k# z8G>H50|$38_X{}?W(E6WRB%oJl!1?f<-*M2A7a$s6Pn3MYSxWrE9{ll^CIxf<~8_E z!J+5=cM`PQ48n9hWCvcNzPIPgJIWHAKdTCO7~>l46rcw3oiRe{nz)v>fFOt|9y4>K zMsgS$di$2J-5oR0T>7@`C3#Fo(^Jp}SnLlwVn2xbWT_*Jz|&*e%D&qkM^7fY)IP8* z(PH*A&f35^xodeoHkljNKg%bzXvqBi-3rz;)_7(Q%UYUvH~e-VE`)$qD^D=dN<3j; zc;M(l&6fF@{^*rLyHAcYrA~^gl)qz)MOz6 zg$2Ke$UlT&u-tx#+_4}rIyk-fqe`4HD(_5H%XkdzWz?`vMgZY}t!`ql&6`qycWN5! zlN9btc9vA>jgZ1-*yYxKXUO{M)j|%t1Dbw6P1QWRH=QjlW}tUtj10}Vq{GH3p@oG- z)<*3Zjrv*7%O-62fiGm=I9rXHMrTD{4WV9{DYUv%-4?Vr+))W?S4ylj*|E)A;Jt8u zaTfwFy`0RdS)TTo)%U)vtaj^_SCnx)%!Tcd{GetshMfZBHy9liAsmuACPk$MZs{R_ zh4_Q4*Kv@Lw;za`@yv1@P^AGk4FC8k@%e8ol;&OIOJ}0mP!<8q*pJheJYAOjfr%aZ z`A4o^o(@UlJHZg*#f=13|BTnSfdmcBb_rZ<2JxK7{KksPJJ?m0zd?{+Q$kmC8khPerEh2`+(PVG5WVk_&SVsPBZL0gIk!?J^n3!f7Q$`Un82QaM?XCN**)m%2BB9HUV)(kls6_@4dh;g3|J*KHE_>7p3kD~43XqbZC?pT zRW_yC@NO-T=Z5kap)P}BgBS#Z7}R;;pah#*n1O3$5X3rM^gy3uz%~K_ir9v~C`^@= zrZyHXk~@xIrkCzC_#?xNwD^+Wup{+QPe0;mk2Y>Sss$>d9ZzbA9fBtC?r$z|?z=y< z5Cgj9)R(krEc2*-QGPf&(k!$VN8O9Rk6djjCs4nXPozYeeJl=GtMoat0V-zfXZygW zF*?f;|0NxXb5r4Wwfu6%m*UyRS zi1PAm_uoZ--L&ItjmER-+|jQLA_&7tP^f^l)pIw}mt9KQ{g+%Iq0HZuUik@F)BunoRD^2al(w}m*JwD@> z3k$mIV_~$o12}lOFjeh4%iFt2pFTQ6aN>At$Vc%GU2ErTMe82^f^=3FWMujyEm;l> z%-WBum2a*|R<99>qY!;B@+mwnM|+BL)|Qxlb}^+09ZUM3vl&6#L;atgwJEi?WA_Bd z=PcwZBn>3)adg-7uF-X8(UG$?k|OQvsZYbNBBhm` zoz8}Z8s4eDCyzAMVab>x?dV}L7$8twYiQBPimrFH!)U*qsRS;?h5=Os*Jc9bW#Xy* zxr!R)T9bRuKg1<}`G|eUH>Buq`~#{*5v5$0!>;~eG|#UJTbrO>-MGM6qzREd9kUS|xA7J$Z4HL8 z4AXffbLAt88;LYl1Z{ctPTM7_jle}Jx7310_xsco{`a?d>Lf5j{tw+oue5VB!;ppx z3|snulqq!o^UhPYojW>54EK!9mXs@ubTozGLl%aUR6kHvo7HwB!q3| zjVx;yZ1BkkUj#<)X|rx*XJ&Gacb6KMYjs;>`|!HuI85R-9EdV4f>7m^X19&3kas5h zF|B=@MC0EqGgNtY-#Vds4Gw}tCFgOK8E+0iY^ z83~Vhcd8=Rf*sJMSUxt|Av)~5p*6k<;S~$M+g5UrvhG<}9e?Dy1mIOqaAPGmW`;1Q z02mdch*xh94bfd-XnNXmdGmsPMQhF?_&(aA;<@b$pnCIfcNd<7y?mk1;w6LS;gu(0 zVhE!m*tvR>=La6n8^2;cR7rJWE0D{j@GxTqwUD*EUnF}psaffNR94;_=e{2?9JB-& zlmd5|*mCLv=xd5XZ)rbNDCa4bj+#@MO{4hwQacrw`t%bB6L zL1)1ze^vs?SF@!uk6xu{Xh%~hMWy~%vs4n54Ts0Gi>E%mwg99T{(=xUa>84mGahbne}`6_6L(TEFU(zUem zV50S8-_)xGsOk6pSo-%N;=5jOQRdkjxtK@rF!a9dHFamG+@9PT;CTEkADoQx! z=DeBeg!1bL% z;PTFQ6k$*WPB#@}?TVeo<2+K@1$!B<_rZkWc^LVU&yU7AHvkGLx`#4cv5zN+@DKrA zX%o?t>kzD~bt5>Zwi1jPul`l~kv&(3s}C!y3w?0$>hM6+gZVNDdzKR_z~)Q${{FB} zoL($#m=N8ls{fDczZo$JX#5h2u!VvXdCLW;@3N3;!X z*;XBsR(5tv4zLH*hMC|Ag!5cd;~275T4522ep>f=@%boY+gJHFynTABS6Wgp^n;_u z;s(!qwh9Kd3YCRYe&bvf=a}}B32@lgEfEiy;n~=v1aR6fX8yn-5^a3fG(=^7Y`sYI zbA?StkEBV$FYVi5fu0M|D2^Ndu^xO3@0VoEDPS<7kBjPY(QN2^=E10dGRy+Xd|Q)= zzi=Hq+ucR6rZScf#l0xfk>dhSzLj5mEBRc;hkL0}Jsw_b!~JvuvhwmN{ABIqH!FxQ z61StjpDCbjzc-B1d_mP#rE)V^E?!n0^YwRF}nc=4;2BJz^Uu2 zxDz9&j3#=Yb}cjJzCLJ50sfR#pL%+}0Z*!Dc^qVy@+$&tbNzYfHfl61{5W?kS2zN4 zL|~iJhCqPD!Hz!#LHU$7t$bJdr?xQg#jUkJ9<-BQF@@^$eOw~~tmEPaBm57>b%dtW zZFQ@d&L7W$CEX~+mK;v?n%>mXM97D1ikOQ!rDhNC)^vdZ49(n!vU zzn2r)J-U`h+=-Pf;kEfRmMaw)T&pb@bxJU_2lnRgRhm~Y$(Z{Kfm{yh#X_c(`n-)l zKz-gVh21{1p*+T;<$=VRmJjXny|9+W8$|A>a%XO!n<|hZ_1AMg{IY5~vF8i|=5mmu zpNqVUVzI5?4XVD-PeqCnD;?~u7cYmlxLjRby~hKP;PvUc@X&z|tviLA8%||{^0d3J z(-)6M?(y5jxweo90`|rC?7x^TYMg}(OB7HD;ew0^f;zDtIzv%cHS2|gh5`+yX|)%=wX+_0bU>C(N&5U>8d)PO&;3Q1#(j38h z_#ah)X6u~}zw*I8WGH+cMSn{Y#yK0l9aRCP+hY9mdXPI&6E7+)s~&v>^@?bvF{pDw zpn{6l>WEu?%+8O)e|C0dQmcw}x?I?UtWFEZzuBu%j1Xe_qC|Ldy4rv>SA}IQu|8Hi zRFwu&boZ8;W7--cZE3kHdZ$Xx$VjHrZ0vS=?BaZFm$6HDO|c748tCYb-ug0PhHSed zGe8yKx*;FOpc~R^Als&Sh1YPNc<%LBkml^aZmiKG^xZr2R%Be1Dk*{|9FeT4uf9Dv zJ6Js)Bl#dv<<*C{wn@vxuOymAsDjEg@VwD<%p_l>^OieiuZFjVQyi|24ME$(IZ9)f z(|hOMG-t!U=##d$=Z~| zAc=?1zG%MSe+@=ILBJpNXqB7Y6C!`ziW*FHL+Y<^fqn0*Lt!o?y@3bKQA0@5mLTyz zROYwLbq&0ukFSsXS=E=MzpFI+cWz3)nc~r4!JBd{_dx|e&2MRIHG}1>av(ImTF#_> z^-X&vL0Wp(am{g#W`r|R`K%or%}RAy@^GyFE1yVsDZ8(=@MYgfK@n%^Y8^f-MuyBu~x+daFvH)u}Ehn@Dt{g4ifROzlNM z@q5a(-{tLdTydCYKxNkMv_=-8$%Dn(g)t(?M+{%|kO>baQYuP;En{?(6GUrYG^oWJ z67&f+6-(WR09jt?gUXC1V28=EGwp+N#E8hZ5 z8P5?esAlxk%fjwRu}t zmg%T2OewRL-vpO!zs$VH-~gD)P4{2HxVcs0A?v5~7tT19TJolQSCc3DI2?^PWwZ7t z)3e+&4j|0+CqLBPXktNFJ=s#@X~ZfU<#OId1Xnc>1+Wtt7m(a9&Vpy}5Dm^LO5KY=kAY#|)BltsWPBc}ipQ4$!(pw;MXv(2H zM0xmrH$Okd-t=4sKM1?1E2IoKo1{rYX}i9S>^fe39@6@EXSm{XaG5%KeJ0%0@10Pvt1D`~ z!OXK_id7u&vxnT`W_QbDiZ@f%9w>w`L7ix39|r7jBX-M2Xc>I!EcE#<3*}&S!^?MT+ee`ciDAZknFJWJZ*W;DqFQb`m&Xj1EI7u!_x}kdlrmbWDY#lD4{uQp zbNMfD0-qi*Nm17?axMiMU-0TpwPzY>t1gU7WOlxN`?kT%&JMb9S!O>!9tE5H5n9}k zQ;k(r{2IRHX?=_U^E;?$yn$ywV6YM-SSRL`vBk0^ee9MTVaKT>t`QLCKV*aN^0VLd z7e9`A4_hJT9A?xugjYOYB|2_2f35Qr&2gc*uXr4s;6FRf@C`A!uvo;tPEbue&vkNK z&nO-7nxcfo19$kzb%aF%wf(7_rn5gcVRTOYI6cB?I3w=n;91z41r;47RRu!y3)ay< z)`PJvWa;;GEq9qAuvpm5Onv+tHlPPBy~1*AY&zb=$@*ga1K z1=jF+z`y^M&CPAueMpXh~*n zxz*I;RG!lW4aufAHiB-*?4IPSek1eAvaS3Fz@leRy8CY3{&txxUJ#SOIZn0iIu7V2^; z!#Y@DeXS#+3Vc;WsSFc?$iaFxKjxGxI=LR^f{a?;n#TgFuo(d_5FC_|DX?1iFR(M7 zc44`_$sn2~y8Bz^NJ{bx#b}yW_<;@CMoWCrgUwkbSK9IZw!|8hbHxbsJMwkslo;5= z{`H4K6Re!E`+YAr*kQlP=N$ZHhA@mh446$eKQp*we^kBf$5cCpo_4<>Tcfk9u|?%X%@Iw7-rX z{gQ3czpgySM6~xkHV~Q39W|9nXcLNS)@|?|IY5*Ewq2rOUXOx&@oby`fq(>ttY~Pm z=`J1ymHbOQcpLx zerk86e!2nId%3#wG&g;d3t%sUKI$^rR<%-XAK!o zqY7G1U^bM48=;~g4O%JCGTfkz6khb10`o{o2a@oYgX(q~%=62OAU*&ZGafOakRSa( zsUi?jIT(9SGhe|?f=qj^}k+42y??FVATOJo^LEZq8OpSSccUQ`C)?PxD z!%`HRHw!uLL5rncS2%c0aSf~)JCMOnOULjW=I}u(N~Iu^chYM5=u;$Nn{tG9MUEeS zS(R$hhhb!QdBxAz5IF7~2P$J1p8bsfV*#MBo_4C(O17-SB@Y4-kJbD^QR@gsE$4qU z*;3xLYV`x`+G#K4wg!!q>OcsZ1mWtqMjD^sbT(=KrL`q~}UfAA@) znh5ad(MzZ4+DFq23SSTF6fa1-_*WA$zK~ws-GL|dJoI>hBWK9RDZVCXe@x5(|z@8@`TKhRS-O>o4`{4q9_Npqi+ zTtc@UV#{}&>OOqYa`8OOMd#VaJ3KsGJ58|oZOqL#9PA znKGvf>l||jVKupWp^h^^AB2)=@7^`q6Jv&`SPK%?3IuW6uj!kJJ2qLm1$xd!TybUrn~EZy1)F7N*mH}2+*3P z_5!MrU+&~*lIp+b5*z(~Z70aL{L-ppf4v?sYZWsk2bFQ!SwkV7s|ap{38)DUiQkQo zY0V=z*$Aku8=oT0fFb|8!(J#hNPsw^((=rJj4{T*Z_=f2I(paDg4j^O9skE?%P)m* zB|&CAaLMvO&!OmGDNJ5`7I*Pq=X~?M-bpAE2i5~u+Tm3wy#lzlr+v&}I(e=tviT$I z8o|#-kfD4MOKa@_F~FnYsQ+jdJwDAX5VsYv;F+86hkQoX`4P&#o{+d{O2>~=TFh7GhlTTEcO)IP7-630W~#@^_m-1wOcUC*OItX%nv%mnt7h@b+af9 z6vFqmeORA<*LJ*2)YWo|$pnv0kNgq7CBZd*N_h80$s`p#CQe+WHDute2gG0PmtiZ7 z)n%ui)^L$6{#)ry^!5*Z8=SQATmjGnQr$mHgGkR%nT%9W2gKghb$j^qfRE*CQO*Vu z%(Rw{l71ub63EzkPA}j4)}HQ4O*&-4AN0WAEG?L;`|L-?1`Y(RQapenz2%`*Qu~ak ztlFG2+!B6WEtoUNMb76E8>z)W=?)^yysw&9U5-+i)NvK`sJaS9Ej$h1_?19S5}T6L zbEJcIov=DPnPp4RA$rYW53cI$YYZL#4hrlVk!G6H4U@;ulFVu&URP}h{%KE_yO5o4 z8k#z)Pjg3yf-(>2n@_G$%%K8-yRrEMp70^26*a1`d74~i)|m}eH9uc2T>c2)F^v;} z^(u#2aS(p(10WE+1xIQOHY^EDmCM-M@5eya`H#=tXlRL=0@vk|FEyqbD~}}dA}|eX zVQ8zj;Ph8IB*@y0#FJ$6<7(l&e%FB)(44!CLDjt%%`-pp=LuTeb96_~RnTfWRVo+E zv63#e7;q{{nUj8NFr*6nN;H44qBB(QUSq~#9w?@Ar6wsff)ATb5SZdb+03mwFgx+r zqp@<>qFR*V9U3flZm?%b*l-(MbKZ-_9xM?y_yi7y$+cCf)imq;hfUoCkgu$DI~bN| za9U1Lh$#hv$D#pr-OpvpOgQE#jVlXW=xf;gXGrC*llsyqLOZwcxOL-FoTM2wA43)P zesqX)qelB`|L_v~Mg)WL*E6efaUE4$DF2-h`xe!fxsow#Mif|-N-Vk?cJ#I1!I5cQ z-HJ>(=F{j5$?snNY;Y0EjJEajT*=z=>X~1yMB|UVMxHbccjlJG%azd2u78EBfxD+N zmWVQ88UnNy@RVdbZ__gS%QjBUDW+!8)^)aBWErI4zyCC2vOty1>kw20*s=6MHWOLe zTj1p0$P!cO&$k}%+<0{zXG=1Pm1u?T_oXGE=4qKOE zmgar`-fU?W9J|B~SJbThb{PM?H-_mMn9(U9!XOUUIRf1-tlJ3oN%wRXwtZ-ZgOa79ExywtwT7+igcwBu#Zw`l@}&%jp`XHyBvvI?>#t;#b>6cFMTiIX3Y0k;cU0hJ#cFjxVTyP?IO*69t^(Z zxvOHo_945Xlz({<9SzQPt=eGOR@q14Ol%6AKf4%-!#P&Zr z@LGq`Iv4Ki$#iP3@gf$exeQAdssGvlZsTC?_q%2;N-u124-!>^^s(XQHsM7i3#SEZ z-t-^M%}f6{J~M6ww0#ix{S|e##TM_BWlPyUv77J!!SU z8Uf;Pz@!0JjN;qRDL31I`Y$e|V)H(_P!bHb%G{IrCOkxc{BrZ=&A}bUTT+@{_||Ju zE6$D>%mroRzgm_ok)>QD}&J1L$a%7TZ9GIJw`kWgMqpE3uHGRMhTbvNGH@7B2l;pm%- z)Z=J;E6u(TIM{nYPmT(^8aC){8W$RT8}b3_kD7hs=)2Nu4$lPZbrt5lo+SSCkU4@|tt`EYhe)1iqKi_Rn&T}+SH7?t|I>@O# zk)qCCZ#YsJ^a?J~DarP8YbLhUY|&o$ibre<1|=Ua+7er-==HlABEsj1iT9uRKTxr+ z>sReF?$ABXl4guOGRUdb=&{dIY;EomX}#4%IM+M8@y_v~TxNc!{R2bDjv6O)N~DQ9 zXB6k~N-ccp1Qs%>&dyz2cszokNn`za%Z~WMRLIY3Sa~l6N#pe#=M}dbnAF_ib>z5a zB1*XF1kSkHVz#^$m-|Ji>BPaSm8=ax*frV)<}N9}?e?9S33QU_3_8j8Cf~Dv(zyzA zsM5N?YS_*c=qpgVW!V?XrU}9$cvdT3^ScYZ8WzjWyE(U^7=%9)i}YXlmAz;#k~kQ5 z)v3B{%TqGzga^u(h#?LuGNtp(?uF}tI3j#XB6Q*-h~Qie58P1TMaKC4R`!GKRbea% z|3%YO8(U^Eoc0-pybEU=jh$$2g(G+MSYXLx1&~&Og0&COZ~57~ccspRLtQlMU?ekm zqvOx*(H}Q-&VZiioFw3ar1lwvQ;$mhDNEMwdy@{VSKNAin8Q_Y$*0*lqm0~a6&{$w z4O{cMXLgqb#I^tXA33)LSnFp#yG^Y5eif?9yB4iE)XD}DFKYF}j!k5wqrmy6lS(fZ(Dr|LFm)9C2sMV77!&d2&1dL)IHoJnGZ<{1~?u)3$ z`2ny8?vKPP<<$j4=O%)d0d6)0d<1X3Wl%tW074*NEjaX_>;aZR zZO`q0tCOF04PVTUgl}t6*WQI83plZ+VL64tKK+vM_;Pn5vX&^ObdsXmY9&wunMs>A z7@@`t9(-Uf_ADL0@Nstmt_FRMlDk!( zb=vM-k@}|>gqEFz=8)jeBoUF-qOd&;ecY?kgoq0naL0ptDi)M*ZNWv~i|Z@8cqC^V zK>t+1MA3z^&UOg-Y4EMAmX2RmPzZ*?@}09i;goVq#pk(j~P_Fz(zsU@RH`5J@#ExvJ;#rhhtQJGovs zg~zw~0qML=IXkZseZxF5Srz*3or46NTl`&k=$ZXHy@_-EvxM&1fx$tZl{M_Tkc+}8 z1hW@$gw`?L5q^uq%L$4O-&W=o%M`7aDROLM50PKjISeNUsP$~-{-+GY!C#04I92U% z^%|ntkBEWzTVN-mn11Slz2VYtB^4Z2l_0%-&S@)NBhn9||J462_hUJcJquRV*IOl6 zw2$s;5Sx6PUD^M++mFPye8Rt`dZ7r8A|B6%hLoTZ<)*16+mAkmm)q8V?>5@Fe} zT)vN)pV^iO_|rf9$WCk?5*3`?4%8z1cCxq^rsY-&@~QT66~Tap=q)BPdy2MGIU~$6 zIIdehVtCIM+7<=2J&eB--bUm(7ZCW)okB=LL}b)LWY&l7&(YCFzvpZ=0YmZc6PTK{ zy|CDiR)Yo}VGP9gOBcF?fh(!D%i-3Uhge#GHMga!i`_|9S~g31Jpx}}?ML6B{;e`( zH>uojrgdDp9juvl$-Z%3EO#Cqe^wei=Dwba<%Dz{m-bI!_h6~5>Zk7g@>$?nm$Jit zxsr$N;^2+!2bYTR4@J82MH1;AClYddkqxCLnRHtW6cF^l#IQR<@)xS^!w+JRrIQLKeSo{uvO zna+V9n$|jhYHcwE6DBsv8^rpc2ZZ_!!4e6H)W$qR@d2b#uXv0pvl+`ON2`ui9^<_| z=UU65+*wEkbXR|&`0BFd$Kb8vz4zq~8lYi%F+MABUb>43pOoanBbRFlOWyk>6tz8+ zh#0=LmqIjw+pK);?GLNZ+XQmnKk9297#~fqL(8OGb72uLYvyx#t50Mv(ARTA4>8OF z?#4JltTHhIL;>liNIX0^RnBz2c?MioxIbp0^Dz40Z2!8ZSHgt%2lZ8OZdD{5jk5ZdhsmeP;;Kf{ zs~&1B2Z&b3c$K%2`F}O<$7YOdxfTy%jeMe3A-3azmjQK5xO#iH32?#7 zA*?Y=LPbwJH5v$7nQ^sJcgJGotO5ooI%}lVCLZA zdYsErRC$-h6S>Li@2VPpU?Vg8K*irH6A1pn?H^V{&jTu>uc81Yg$6VVf6;=4@rS8#DD&oc_<`JY#;( zd-&2Q4Dcx)Y?g-%!T%Ula*wfoZqJz1f^g&Dby$ged{^0j*U)qDF8|v0)jeIY6ZB91 zd*bdC5YU}i-iDdh)S^R6SOSEW%5R0i*oNM)xQ@Y3dTd&J4z9PZ+M&-LP=tOY*PR3K zZVxfUg6Q`rJn%nITFa4FA=C-e?$_nZhMQS24uM(v2|s01sJLp)1vu4uR9iAhK)v{b ziKVq*JmWSM%Wv@uZ$F46^V7FvmW?jB)vwhytDctr>etEM*i;&UMU|J+0xDycg z`+{e+$9RMyyhq#IwmB>DCA~U`7Bx3a(y`R9c~17#e@A9hf$&2Ti&taSKiHPSvyV$cTxp)(RU|h zsB3_jF}(YsynE{?fPj%JBiG|=BKwM9gq!C$JU)8L?>f5X?)R}!2#=RjO{6%n z{Q56&jRH3)?TzStgkxA~a``j3>FN70;|QeFQa_ypCMc(5^iEhA3Tq&j!h2FxgVx$_ zQHhgT6yHMnhkR00RilX{Y{B_BmdKlhWex z^o<%3B0K^#Su>T#^H7$`+Srl85x*XkL-{o4Y~~)nTl~fBmt(13=&Tn-#*kMD(e7O% zE5@q5z^r@YSGJD#?*j}=J?$>Z*zifu{*bNMG@hTXws*QP&N6d9dS=;MTxbVyJpjj+ zZ1l@oYBZv$T)*QVerwx^y<(yb^#i&Ct>*4Bv)-;i&)!^wF3;F>n1v5gkPgyz-|0H8 zHs8V4fpu#K8Ld;`+eGUE6XzF#J&nA1s}{V_wTQyN`EsBQl?dpB8gmkbjlC86=2x>~ zv-MOF(Pd2U?T}AO1in+L%&Msther)E-$8^F_{m9fR)P@SNrh(7GJ0JNfzpv^y$NIJ ze~XJ@940=(e$)F)f2N2Omva01t&xy3k8#Kq7BJnlFQfTqprO?csObw}1yAg|{IzKu zKk<6RiE%UT)Mlq`hx%J_vO>7`Fs60^6-ys(T33tZE)Anlh|acUYgjq0P9j1rDUPxn zd?k1Eo_S6&)5qdIe{ekUqN_pT=L6B%t61pwIa_`ldVboI=Y6;i9S5eLz58`5eVblR z?3Uh`6;2FnBq%H%a5@r?$2?CrhOc}s_w*QW=siq7ip!+z*D&o2%vwmZK!WA zRPUq9FgDh3UVfOEU_lA;(&0Q$%R7)0zAvpvvm1YD>E}E-r3tzJ5TF( z0D+H9LHyOx&h%Pj79Q>Tu^);C_`%N|=ry;TgV6bBfF%JsG;!iymNr2nVg((3D?)ty zrFi!fP5UgU73!sB;M-B#+v)aij;LFIEMx-Vg5Ms!zhd3q44aqs z`R!Vojneh@KVX0W(s#d29q*mMNt3_@baj)n0+q|{aFbKsYg82By3Gax&)q>psMz~A z{x3j8A?CHghoR{cRiWO3u6|P(ix{_FpJLe76OL_Z_rDu8)y2|7gBKUMDjNGUWT34Z z^I_+F*l9Yu(G^e@FCBmXd^N?Dr}PnOSSsvH$%u!lO@QIvZ(xZWk=<3_db=3!a$A?( zo5=rny#rU1se8;lXFqJvd`QE#tmUPDcDsr0Q~S@|`uGwiqC;}xB^3aGpkY2+_Q~Qm zFc8!>3q@A@6Nk1mNNFH|5e;vPI+po)??O20iueLjS6$zyUhu57csj?uoJQ5H=I&F_ zj~CT5!a|Npka1)5x0Kp@O!O&pUI^OzfXK+sLr%{dmqLJv_U&`h;9(YG@Zmy7Yma%m z4~`^kf-SawxW*vNf>48$%i*z7I3=p$0{2WD)O|}SXhY`sc?$kYk(x6QL>RY&kc{)* zt&50>aKB1_25zv`L2DLmBUjn7*9uico2hEqzAtyu(MRC?FiT&)4ewQ_&?^OWJW~B*!sq1#e?XYB zwHgS#vK-T5{ni8PaCMD6iTw>B%v;S-F{#6R$e1 zYnxKLri-aliERn1SGWN0%aXg{Q3>QgPK=j#aGMpGi)y$^#m|SY+np}~uQ(q*I8q`O zFLCZ;2%Nt#Bgi&ai|0S?rY$Z-@U(pjy$+N5@4WBhcBSOWN|H)Vx2kHe$}hkjJpQ*J z8JFT#|FBBRvFGC0yO!WN$fI{`3_1K$(1z;kDvaQIJvs%oq$B)nxy3`goVqU|G+k!S4CAG=pbR?)w#Vr)dVJY9PKs za&>z1hTcF`!=1Rk*g7!0GkDB8zYH_NnJj)?aV(iCE4FoP232}j0km?$1o3BIni$W5 zP^Ps~k_dc9B*#%R^uOPoM8CHCBq!Na7SvPc5`m-RB*47|YYc2zRwuUP>_G_)0Q~29 zzA(l+>z)_tpLC8Z>w&jBHrg^QG#+TI#4n>eZa=8&JPWKBPuCEfzm{8w-5JNV1l^?j zZcOtUa)oWDUrDvvXq`Mh=bKt{7mL@FziiPudghRjOm&E}LUiAKD!%w=^TC(v=XSqOX^{(?LP0Ib2y$)Hw();WGJ#)Q#28MdibnVHZ8PJ1OzD_yTJHs1_`XS3K7^k=GKbTkKE%<$;Y&T~Hwx@{qzjflj%3UTT1slgj z)Rg3G3`A#t(KW@*-^iNXnH9EEih`y#NmlAVKHp6p5aR$ZQ72GA%7=G}b%_L_g0zX*SRG-@S+hlr%A%?iZy z5cuS({GS$pNl_rL%IL2vX z5)kqf5qu4+%kGiHJq|B8r;{fk#QJr0+FY2^vU!Ne0F6B}q;8=Ss&e)(ZrW7cJLIWa z7k&OYL4ZG2#2tO|i>k!y4X^e#t$^HC^xdHOW8F|9Y{Umo?uj3%%!!LehY;|Ew)RD^ zt=;C`{u9~RE@wShv#&O;vCa&7p&Hi7i_x!0dk+tqH4zGIh6|1%eE&~Nu~d(b2ye3o zBf6Zyz)GKA)&u0jIkJ{(`9!f|r0P&r{g21vr++}GeREV=UiU!zZC+v6nV>9XyH|9} z?+IWhdXcw9ti8BCT>QSaxDZ=D?rQjS)_@Y>p8zzZS9ZhhUdWW;9z@F`b~Sg>$VylQ zz9`W2t3x9&A9-KJhc=Zv+-F{avIc$O`g#9Q{CVcdZc#MZzwmqV%rpS!};PF zES<>&{Gwmh{_V#7{#+6=YUa!-FdQ0I)+~M-%{>?m;Hdx`c1L)o^rzAdYECO zLa1HrzABx43IMKx5Z8xyozZ47+k(F}e$B`7;yBELZJGvkWe|Iw$&_d*4sJ!3VF$3keD}GVt>*dBlWfdXOE=}T|r0(}_gsN3EcG0gG>mjhgx3-_Wi%$?~LE?vp z$XXOlps>4)(D;;~wLllzzc){L5AHBSnBL-VtICgIP)B?`$vmdXOO z_Dr2<0P48f5THDp4;9t`E3a~xEde@Zw-$u8i`7Hd^UOBm;cXb3vkwvj;aH)2dz??1 z6-On#%kSobmS7K7A{|?t5!m7c`Gh2))L5iF6c0CUZ2-zo-ZL!R6p`Pk5u_RF&djs$T0OI7Oi|Z=aDdF zhVPT99}toy=#A$jM!{8C7Tg-_s7dR3hP|AwIIJPSAr&0PB$TSiuXqG^IoG#3VTSWj z!Y7PDrsj{_#{Hja8(zX->Xn)-`0w!?ku5!cc3WwC`TE9gI%@mBa~u*iE!3B3*K7~V zf@b}@H~y~27uoS`V*jc~e6!WMR`IXwjNH{2;+bS)%mv(F`wz%n_VGizbSZgs%x_d0 znhJVL<=gEjGSKWenWD2-M{KnRZwJu+2_Qp6xI^%%JT-tr!bDopL-sO?4g?Y zc%;%k1!YpV>9CZ>x>et{;6r98SmNNc(7S4=+zB^z=kyf_FQ{4(S;s zS8a=18k&6(g61cNS%BLLxVxhU$wKgw#B^8Ft(uLosQ0#orRV+}_=gs47wO~3FfnLW zpg`25O(+j24+X6=!|#1hZwzZN(x-W5GD)Mn+u0 zl`hS4q@^%J1Sw8R@l=2unmr`!A%{;kw-#_DMNHn6FH(DlN`>J^P>g0L&j4S9{@{-E z+6^IJ_O!A$DhLEnij9i}!!vJEI506Y0yVDxE%mpWSl__ZR@Vun&7XKQiqBi}C*IkHyW6oCBjHbH#9+64$3&TTU zDdw6CVhsZukWbsDl}|J7j^D&o7>r2Fe{!%p<}M#D~=CmcGFsqGjw~G=C|&8DRa0gnYOLs1_&A!}D}!QiA=3*|$+qCH zVemO2ovYqi$O)@7BNVbRD(p1)(bBBih%_xorVGpxNn-~4k&^EJb&SYlBOF9 zAk?XbUA|HFmPBVYyEh1dYO|fFvC0@Q^AyZeg}AH)trkz%IG|(RN$91;BW-;E-`xFZSD+dq=#M~_b~PQA$AA(@Z#@Oy&x=`1lqOFVKGyNaZIxq-u-X1A zIHs9t8HuJDGa;FO@`A$tQ?t+YLE;(pSdnt}yt!Zjg#8^;gRWb}XQ*WMefBS4rAbv8Gmis6+$}auu>Pq3bg}c%fk!&T!+=bU#4CH+ z3k*zbc~aH5dHg}bJ9{SDS%eoXB5m~52VJ=m0rB1US>1~x`btCN>Xe-JqOJj;*9puu z)BIxvRL%8<*#)=N9tUGV{NM((sRSRY+z){c)B>FEant?=eEsaSLK=p+Q`Od$=bKPn zQ4Mgp&oUfU_1l33-Hx3K7&`p3CB6F78@x~*?Gwb_lhL7q5hfgSgoY0_o}k(wq`m2-vipBY;E^c z-RkuR$vZ7L^5(CVaoIPI`5hUO>}QqiBSBu$|uMsR<}iK5Y=#$8A9?Eekw(J1y4DJ;Cm6zWW9|J0r=3+vWkx% zj5OFt?!JRzJ{O=Jsok=mp&zg`hqaBL9^v*SQ8AWNj`zY;tjkR(DHB7)rnF39y_e-$ zNO5%iKFv-H1H^7u7wF+tK3t@!NG#v@FF(#ZqF%%LGuQ@Fs}4Dp38Kr4TD9$wm>tkz z08f!R$$g$_FSEgh^)}gAv!C4&IRfd3F?P*f>pLgN9vjX>(DF@`Jo3n=W33v6@Qf0gdB7I8FPrqwe#C}Np zY?2DCKA`tEm)EjAVn}5`1428s^4i_C2|$#m%?8yd#bMjDBkQaloN7rt>3nhFJ*;U! zRhzZb7AW$hb@lAP(J_}ft>dXK=cg|CFJZ7iOnnizb1RYj{}9of6!YmdgZIe?F~Ac7 z;vlwGBUGYJ*GC7Wn`f_`Q-J6@3Xn4mYu=6H#WflGI=7K0+CFBphXG>vqV4`9^IEj# zGIeCHLhu;Z8B)-JMLSjKABvXJurVU6Bz#M##m}s^a~MD*_SmfJ`T_A zxLl(_E7qJl+wHoX_Odb)_7ahJ#TlVL0eFL?VTC3_1EF_>C{A95;(t;{>$*D1f-!_* z0Jv_gJAfvm>r7zPb911p!%#Z+zmo^-YzQ!!gplhef)U|o3pY9Opw{`0y)C>onSAv0 zn0|0Li1pEEs;N8yoOvN@o_aukNyXHw%%Dt&~v)~W|L)dYz#PHZmBU`T*}rU z{Gp=coPfpST9`Q9jgzW7ao4e>`ieLBH1xX|?QwSaE@l4*A9bMw=gbMOle2et7W5bi z1&&q)Pqc9R%}a%ea(OQ=loUG#vNrEZb*0ns_&1@~iqFZ}Jv@u0%g@kwyzu2lK&uOy*?|?`@-1zGbPSVN3$+6mq0P z%d}^@8(?7fC;KCKcKXM3EjbGojPzz*K5{HfW=*?xRCBR4FBhrgA3IwtON!Y$l;gSs z92~T!aa>SuekXiGL&M=y8e&vz%guUPM@mv`mQNb8o|$&blnD))E;?>CnB2 z_iKzPC+@4wFmRl~V${gZw1)_l-0ocS!(kk@nmO?T0t`EwxC}nOU5vEH_nuEgtJRj# zqx5+Vz~%mLY71DA>2??j{+d*7%fB>eM!t`DWajJNE2Zh~nEPVtF9FDwVQP#nK1N8% zacyVc|2B~C)gQdsjw&3gt_0CjN`i@2*4Ey!djkjaLtJ$4#z@E;JksGD!V;I!KYX2+ zUOmg2ziEY}%tM41ZqT>Q_3a5fIK7^no7%XF%9weTuQ=l0DlUzX>4RrJ8`nu_D90Ut z0)yWys~A3gtP5SV4TmNyfW{>Fv2~J15m)Vf!6zSzg4SPP&AOCos)~5LinD=RE_ojM zu|SZWa?Yq+|GB;&vZApD(9AXIBXVG1zT8g*#9w&E#>8L*$rY|$y? zu^s@61K&V>6(%?8-r$8&H(g44I31ry$r>Fm{eC(@e+fvNqkOy4BP}c9?@*-bh0`5k zrLcTbLCb(ZzP^U-`0|t7t6gA0ixYDd0dl(JreBPye@oB#WlLhIvdAsm>d(DOpQ!Qz z913tXF}KpX^}5|2!Q!KPN8nR_Uzm+0?uEkEEm|P$F`^q~F~ktob0zXwff z-4C=0#`kz$Tiy&}d(goL^FiqcesBd9lTEHE#M$E}fH-Ur_ zwwsyqTNLB#n4TCLelMN4?>ODnz$O$Yvt}}PdHSMQu!stMkrDwr z4hDt>{ObCQX1}@YMW3CW&mPPqgbsMA^T$Tw)Fhe%34!KC#nnZeLoybR+eO&yI-hsh z@*pc~SdK3(&B&W?iE$ZP#}v7tZ0X+D14JOD`rOgqw(}Iz8boDfw!R^K|5JfLea*0& zxubeE^w|@zkuvvYslU(KR$pv+{6HImOyCq?WiADj|o{M1h zg38gZ)-Wd+>3lgQ#+7iE`W6>6QGl_EfQ#Fjp5f-s4l8QvZ_LeqK+-IlE)v9bvkTDG zbv$q(`P-{nO_E~;)u%uO5UUmK>zEz<1zCw*(myzbrTza<%hr<`PPKE-=Jw|gX*?y7 z2-m8C)&^nv^_gW-a~f5CO&nbG9b}zZ(eWX)B=QWFt@c$M!Tq?TsKV*}w2WApVFl;! z)F?V2b%CxXkBAC$hwerJsM6*JlA29CE$EZOqGaRJkL4ZH!ZFd}noaljw9v9X%Q`0W z#Z*98w2WwLU1b!g&%`@92jRhrls4*F&fCn&sK_D$!ZT8*lF>x-rZTpfWOTMgJRc*I z9epmN7SIfuT-uH=P|+@IIGj_wTpY?Z^{S7v4e`!udBEt*2)VO@^`zZ$u7pDX5%Un< z8lUP2x4bnD-V@53OboIG67K~%`us?yayKt;C?-GGL2@V3AGPLOr>xV@b*bFxhpff3 zdh1HUf_FV=BsPJkLo$`Od0ArnIQ-umMk@4&;^=#Jvm69vyj+;Yi|(qJnc!F`p5Rf( zSjvdjTdlmzW`IpeBv+d@^;(`i-FktLBT|fzEvIz5a*UZm!SYa|a!NGp`sk(&M{LaT zX-{n~8V$cT&>{C}Cj#+9Snx-e^!n^BMP_o*VX9Et)aZkaU>}w{aWrdi&pwvbgMljzPGvP;4pl_ANQ&TYFbK zeJy$|9jllnmq`2W*T7Q}LyKd|U-k~W`ObLgmaGWSaT9zYwYQ12ZX(Lr*|~$nXb@G-BaBj*WbPz#t@kw#3NTyg`FcS9_6PDilq+s`QETa^nY&g!h za&or9xe7i8mgflUCM8f|%>Hu>j1%d{hVDzIQMv`2#-_dez~Xi zA&;14{A~6uDkem+2*FiGnxcqeV%XsfQbfSCOPikiLH086&}~3Yv1S1N!d&8A9^bH# z_1CWfKke|-_w+qdz^tTM5cQ|KW0*O~jpuB41JWyQlXyWd%t zrOVe?EqXxqj|MYcSMp*VZI+hi@~Jwz%q}!qg2qkTNu@b_0n)lv|UuAL*F2?xz1!xbH{HCPjyQtYO(7q#0Yv~ zTzf!^)z-G;qpg&XhZLebiz)fH<`Zco%79a0?+4O5;5`BL$s!^W)Nav6Cao+uf!Hzi zJY(*NGJ3xfk3;{THd5UxPg+_Q9I_GtG?QDv3P+sJ^k3fiiQ+W07$h#`stfgdl-a3Y zU?LHscC>c&nb~eWMQLH;#0yO1dRJ+&Piyn5dUQT*#FR|YpB@#O#dY*~1fnEudXius zjS(FQVz3h9Yk)(>135Cw`l6N0zlmoVtLaL!9l(#b(G)sl{x`6AxrS%q96k<_V+XA< z%L~g_T{?1tKvpb_+s?HW6(KOX=tI>1b)CpcW}-jahdc?M7?(tcs_gw}IbgZNn4Dhu8-l!n`$%lKInB z1AfPe--^!0$fjh}){kOL{IWh0!nS9TrC^HaL-KF)--+$0yqMvzhZqR;tAt#X3gHa2Bjh- z;Y1)%(wN7_jyT$`{7*(dW5>spp?#Q0ti7wi!|Zr9Vjxx0I~_8PRSySBiMPgOmN#a6 z_o?U+FFrn@iMKGK5>UScs?@PO&Ia8m@=?vnG~kkqASZ(tg4zf-?lkMz$bu3l<`8gv z;+l=|(?jE{w{2Xf1h*L+G&6U~jzuG~4EfJT59I2XQoMYBU{&H&cH*A@r@kuRu675seGFouf>^m1KO34K5z;xj z!*7lve4j~vc5?icm*fsA1{p2Rf;5mdjqVYE_Gn)UOd=@0Myu62Ku+aKeLXm9+2Z>c z-i|}gfN(ziDSM>Ycq?~P<6Y)NaXJTOdIiSYTza2mE?yn|gf}tx{;w5}bkiq@80Wv@ z7DuwK#m{kv-IQRb>X&Sp)+ z8&qbEimd`?I6#K9ya2V}h0$Ff&vYEY)nPTw*6gkbW)!WE5r|W;rIvQMB`awFsSl_r0 zTfYdb`njF%M!=DfoGyU><~OOKW(23oOjkwK8n@Bu)&A5)bHHPBP**5*E=^8{eE7a zH*dmdQJuz~gE*@dzVeaoVW`Y%U8kwg56-fFTFNHN$iY=Yx_mX56@q8U3D>!KF}{C= z`tR3jr;g-;No^01=^K~y&$2dqQgN*9xsFvvjY#kl+<4eOX5mYE7A5vRp$JxVk=S6&xI9MBa{dKvREB-T%Nh7Pp~b-Of{5!AG9%>q(NnCpAlrDRX-j?I+J2 z;lqgKTNi!1>bv6s?;z8~a%&Y*itR}@>(3Bbm_KLL$E)PqLDTy;nJ1xgRBQv@Vj{3C z6gwlfTX)_JQyE+^hQ3astF)X|&f==8?5aCKt6|Z=*gB>ZwXR=)Z>B@M0%jLF!7dIO zkqPPQSQ=iLD{MIXykECG%to+)!{O^Uf*xWdr)Cn>E7{Nw3(RbZWz`P$hS{8IBW6^iF)mCUpQ8zL54|k9k~I+gBVf0oHlJF3u@oXmr4&gv+Szxs6=}(L7L-d3~&&*(Ggz)V_=l{ zQat_F1Y6|4*7ziU*~Wy|A}{&>v;Zc$$5t_O|Be?i!>i=?Bi{PohN1s4=?XM}IF6qL zc@{B#MA<<*Q4Er8!-D!v%dDg1Rf+FXPjv|qhVhfIkQdHa-337E#$8`6+z=VzT;P4| zma$oBkh@$j1ix;&XAwU`(0{~)4=z8fB;Fh!xtxldWT%G~*dH`5|4d!nu#A*6Y0iD! zVZx(K2!R^M(;<&A1ZOh5f}q)azTUc~%`S}_!urEVONZOel}rus*A5Z$WO2`H6kxpL zi+Fj-BiphiAALErnhwLZ26iW#+*5DTWvz_wZWJeBJU%5`#Xc6DVS~Oy`x+C8Lbh?k zFBAUCvjxnVBzZl-<3c$zO(#;jFGf3Z?{RA=C$-r}e=BnrZUS~clUlP(O7{O$g|q*u zuG3?ME>lchmuc==|A^MTyPf{K(-OP0J1p6mxW-uoG}#SG+nudAZFDfn0O5 zok){{?wYuO6Vn3pX5_jh+o+9-g*(`Cl^6A09V-jSj13Zf4Pa<3`g2|`Kf?YDB6i5e zep9_=dPe+ra^4^QcS>PAMcaUrV1ed4W~lWH9`PqjB6&5#+dN)=;_r%~b0rt1Zy@)k zk%tmnxVZ|6FYudkK*uKe zD>5J->5HwfgI`Soo9nj1vMJ978-URBBH@#QLZo_x2Il572@G3Stk_IvQZ_M*1 zJ@!pOY%`s`({7tdqpt&Kl;P@)OAi*w42p0Y7@#`(Vd)LlX(i3Ei6Z+(U8PcA1uj}J zm=qCk^1;nH$?a-yMU9~L8!0BytKqTkI|!0^CU5!b5TYc_MqdoR=V)NRyql`yz^CKD zV?4%^F(@+Lu<;IiE1zgwN0Vg4s+P(x-JYiFVLH{SKYRn%DiOD+ZsqNG($oh4j<^!OaW(J z0yk1oMdzY9t+daqyG_SF3>Y)~!ndzV(huCO1^!{DDw!fByNJV?#zp*RCDc{sKz?&v zx<^R$s)ly)vQ`P(J~0B1*AU>uqWSLO-E+UHPa3107{DJ_?hZ?Z(z0hz+sil8;ie6F7gWx21w^z?`-Ql^<9S64ts<5ULBUl+#-Qn& z8(!OpuqOI?)Mpg9t-JvkHuxhd8ayWlYReC4$E!-^YQz8 z9#|tMS-TxK!Kwe+*zW4IQ?bWJIhE6RZQwK8(G=c(n#VN0(9VYT{Ae>^eeB~?;CrO& z=d1quVTaj)-T+mo%JHNMv~<vDN%eEE}6hNOA@ zA}kvs_w7@+2S7Hp%e1Btm~hrLpp{q6U2Go@(}y#=8jU5FS6F`?_|2;L1@Ym}1@2Dp zKVBtD8mbcMjq^dDdHDw&KXW`B)wQ|p`?jhxRzSf(k1P1pH7nFBN%-(FiEspM5@GG& znR*fpJH%-IF?r57cP}!*r!48EQ^?6eESP*^D8N8-WQU3N8b{TXZ>AwJyss^ z{gmB9^t7u`D4nEX!BgS-tAcA7Wn5JxLa(HF%Q*b5lUKbQ+$YV~B!;&n&!#J9F3{69 z92glFN3=Xv$K8i#@q?Wy~Z_THZ%g2ky)U#^=_O2IR>E=FNZ+NvK4vz0X95G z)V$EWO3L1-Ge%Q^cJ4=%9DyW8<#yi$=trtsj1L7{m}MWs`Ob=9iepf-$s=v-gpfl? z;;`!UBQi0}lJ*2omx+|}B`oO~$*d*{F9(Eb37MY>3XiWd#*@k6wy0DG-$nzs?4LZ- zo!&wCN>lWX96(9icZr!hx;?*!w~=#tZA{T3yxF`k?gHB53DWng^0}U^fAw;%sQL{5 z%D+ILtseRgQ%o}VLP`@V@EL;XLCHz>q0ye1I}^959|tA}J+sCA6ns=M3tPWArBx?z1BY zFZZrA&2`m_Oo&Nn7(dUaqt5(MDUKl%({x0bVr{ zmApzS2!#ddBea3F!DQv%)nKrY*dO^+-(AdZF_`V1oHXw}JsoIgQj)#=d18*4{O4S( zTUzo7Qca^Lc0vCaQry+`b@_bfFOR$@?F4BaqRWKebo*$*YCja<1QnB>tX*jU>yP@5 z^a|+~`ru6Up^1~uWl;bBN7GwyMfv^T-$QqIcO%_hLkS4d-CaYMbazQND1y=`-8FOw z3P=r&(%taCKKJ+jtu+sT#kI~k@7VjbpEHm7)#p=N4tzV)Z#Lu5w>Yuo@5)Ulaa06o znKdk150Nbjymy|}p~`n8A5jN*(B9)>^RM=+l+1L2pE4{wsbf9Ug_p-g_866eLOJc( z16d1u<$^ff8ood}97X$!<=kK%NwGtkL-9SuIb-(u2m<&}uk06sU3(jzm(Tn2RKSfv z#9)TY%J?1Wv;6KacbqZp=|57r;pf=Rhm$@n3;PcEB^0>*d$Q@U{opj%6oSOP-< zKMv^VjQ)uLZzHF{?bFH1e~t~BG~+x4Ko1ujGqE^VKy1^q>^AsM`|)kz87kUw7V$R< zh^6wehz6~DV55Odwrwc6hfT(=L+NKS@{pIy5|oFDZA@l2Krcxi*5@4rZ#x)l@VjGN zi+IshFYYbu{O{jt={J~AxS27R6(PV{YipQhOSXM3a_Qexwd{ht#bq%5(|ujYkU`*Q zC7$xpxErm;fTZUlD1u9XJ3;ma$wHTv?q-yNlQ&6^;~Q#r#%x~?2ubz8%6#L6&xIm|c$ z$g9ZZL~{2;{sXmw*CLojJ?>5mbrFWG`%- z5q|sbz*0fZ=FK0!)xWT&-q#flM3`~Uo~^jYU=uSj08;rhyDqPT|ItF$!c&eqrtecp zzF8#Vn0alyWIeaOc_n+?_r;G zExekZ1Wz`gYZrd`PZV5wS4NX6_e)C;7qj#X7(w)j&PwlRaS1DH?@Ugc!Or^DTQH-* zwa}Tsl!E$E2np|_@R1t!ySGl+<|j^i6`!dnw-doHMEk4~sncY{_Ux7rpN@izU;y|gK$k=~k;!dBdG<7(@oo63xgKG(V51c@2eI~TDt5f1dHteg zeq~9h8qgO}JcrQqk&{E)KLw0v@3iDs=KV9_a*{a7>+AtZotuoD%#C}jmK8!pA4%91 zA5l|pd9CxIc?H6970OV)HG4`KQ5z+T&fn|TxYQrp=vo;Er}BA=7<%Agar0?<9wZC? zPVX^%J|}kWzMH%G#OirhDT|4j@}cf;Jqof75NHc&vWEaCJK%o;PN(v(MjqYrddsK7 zsyD~~vkslV(f_ni)1aZN%e*xI-RMJq57zYGBqOyaFj~`y{L;MltpDX-bVvfiM7Cf| zWnIFJE65Ot{Oae?<0U2Fz~97kqseyFZXXB8e7Y+C6>LREdKzAQ7{~R#NH-aOHgHZo zK4ct^A-)btRWOcuT@;s;RBW6El`dxGOxe>(D+4xp5#cx^m9 zN1bHdyTNc#vx!9EgTFL8T1ePn-YnRiJgQ?XHVz$*{Hct?xIZ{xJtH?z(gy?)@Ns)o z2+OG(0%5?L341nC#y8h+{oTTtA(w3nBZPD;JhmkyV7J9pTS8sse{aVb7P=$od!$?V ztlW|eux~(@<^Z$c(gRtoi-=-fi$); zke@!a4z_slTYdsBUl;PH3fT05RKtzj)Bmbu z9j>;64cE}HOQny-c~0*Q(H{u#{I&3|z(yltQF#d+_!z+c%1RQ6|R4H$M*c~IRqxs2PWDGgjf;GkB`r@RHnzDkf?K_vyF{c#6{6)MmTf< z(hfAVuu8UB8?=}|GT(j;*a*aMavW@|$<7m=28CXq3r!(=*S4@f?QhLb1uYy3_95Bb zz|(L^%j)VLd_~utvs`eR^+6CcjXms0vmx7_BW+$LyuD=*nLtyUA9{u%P!~x;LtkHC zuzuu+-+$mLtxlWm`Q{`#CHI*XHOotZ6au!ec{0s4$SyIT{EXGdSoEz%$k-r?Yx-{s zT*Hyuo^e?1oUhx*#6@sYX(i7+o+{TYNl6t_kCmU2_;lJ{P?bp)W#g zxIB53MufWDSOz0oS~Mo2=_m-EY?PD4(@faO)~4oFmz-;ryfl|t#0D+8v0&+LtX-varpV|KK_Z#w>pY=(t77TfX3eNWNWko zgA=jMS-AX;Yq_|1(cJ3BBYax}XV!Gdnxw9&@9YM7Vwm!w3mcF$7ObbjmWnKd3M{2c zwzr|FkY7wDO8whP?>sy_u%|TX-Y}h_c(KX*5*<`Vyxwm~-}8_{wC0`76k-nH>k#dI zl8TFez&g0Nq{IyuX}nGPOqqP!);BURuBd;2^dk=8e=kMUIXdKjX?yX;TFI}_bC%O$ zT$n`On`fgP<2h94q$0T-hQD0KuQ-3BR*|yl5XJH?H2m?e5^zrD1^*3kvFYlUP1ll(3|f7-RS;|@2~@8Vd$!SE~mkaNzVAb0AECT*D> ze<_Ecnkz+qjdgpWEFiXii#GUzx*de^-bR9pvBoXGZQ7~FPvd9R;-*;N@p0{KaXW~T zq;7k_C%nTlF#Y|vL0eugkLyi>x-4qwRTj^ zdFY0|9-be7G;9VSC*dlk7>J+UKHgi1Q|F3!I_e`M= zczH-n>K8E{wty(auC51wT0WZWQV~5Twq>a-M9aI@kLs?!{h|Jq6zlqnV?Nv{UJ3>X zH!cN~fl&{4J`DpPWo-CLBw+|$A`uWe@d<1xBs^ps0p&6HNW`{Lu0LbyH?ATa`4YkW z2RQVnr3_HR3uDz1{@H37^3t~dp;+KGL|8R?An7O@3uCin>x2+msJx-CeaQxG z5HanJQoYk&e{wB*)+#<#^*oaJc)DD((!cFs*B`3K+_>SV7?;0ifZZ7az?j@K>N&j) z*vXHczhu55VN6B+akXN512J(P_yKJ*Rik_R6~*5cEoIxHC)e_%!+?u;)>-UdAVEjD zyuQ-`&Izrv;P-qi0b_N}7%!0tCPKr=PJ@A#O8?s%1WLcZsnA!OjyjzDwO<>+hAW#< zqT3(6t#57Z4J9=CP-K1I#&)EGsU+{0a}eL~FDQpZ@DpXelUxQNr~bKP9i#PMkakdt z#+UfO?vw(6mlT7o@_x>#m3D%Qaxr}FZ(lm&l}6Cr^5x9g%^(U89oklx2!y0Vdffwt zf+M3_8!Ezj) zerJ~WH<#VCr%BtgpG2U3j=XEyt6x|xK@x6api+_#Wc!%RVLX`V@o!1bG-wCgzbBMi zC{r<1ga65uuW%N9e$6L&4~dkiR)FMINOIrl*f4=UjEU*G26KOOsrdRe{k-Zc`7$*8 zHl;E2;J(%uLwHfx#2TA}jUYg*$V#ke>*j_ybIe9M@ndb$FSnKGZ*7P0$w}%eQyjjF ziRmbjA4`?t{HMu@055p-x4|7+ld{#7KfQym?D6v4~@12gJB3pkGij6)@j32AMQ4FsEd+}IkF?ioJwjl1mA@gO(tTD^P=ASje}RZ{<*>uL)p0Hxl?cW$h^fB^@f0!h zHg9$sXv`FBVeu@FCF99dSm+CDlWATHtNc1ENX5taS~%fj^4*x(2Hfu=B-^YD^%sa@ zYzKf${S`{7unwWRx{-tHKnLl6n|pi6f)z2Ay{XdonbQ3wulFT67uj(lSae2!+NnqE z#c6R67hg5&|3gsqtWJ+x(RTbf7O*5012!)z$B~2?3Et>HAW`ijW@3ES(nvA!A?^e{ zp!oe~WLJgBLpdSZ@43{Ut1nDbZ*ic5si?T$D5)ObwW zF9*9B_}7?MWY8f&r^qryWO7GJ4Pg-6K~%Im_y&=A>^&kpN7I(P1^L#9oJB`m3I40p z{d|>_un#0QXHk30W2@A#V$Nd3aMF$+6B$8`nV{F-^k<`H^>$RBbtF7guR0#{ubQ4oJ4q5Q8fC}iz=E`-J*N<$Jf+P+8x=2)vT`vO=jIs(x=A)qZ62vC3P)awFg7o1Ok1z>|A)GiPWI!F{)CE2 zjELNV6EO%AhL0c<&Wh1XxrMD9e4>}7diTf~R;^0nCL{0w2NKB2udFEo3|d<;WgG;f z+7=>gEA3yuk_oCE?-YDSq(_(&Net=5nP{R97`1h-*e-O5XiTW90w=;eI$=bj!DQpr zHKTmlsHCM&O3vL-FRg#pCWbfWy6At82g*3Vzgkh@titj<3T@f^mAH)+@OrzzX9j;5 zkr|w8kpE`dcXh#9Cy#V5I*Wg;bz(H=3u-dIINGgNF>-FaUlA8Sx- zzupmL-x3(qZ^#s@(TSQ-5;LOlF$$3T%+ww^G(h>2_7Il%F(y7EDD(Zh&hM=+$~yFi zJ7u{H^i3`(aJINM%C=o_5`20WdPP%KEjU?8ObAAk5ELlkhJ!{|vV~zRNSkc?HV)aU z_n&K_>~G^SzbmPyoHmn;%dCLT3Y@apfwSQNDVBFA&Y}lz!E$aAR8tMhOCR0_EpTn< z_!x!rqiA*_(@88kkW1zu5V0*{_F>f}rJ&OoSozpQjO%JsFG^~bd*z$R2j|qbr=`uR z>P8*}EIWkHnljZH(Ey`wPLevrmGor?`)OUSa*I;QqOyQ|lUyE+9QO?v5R>$uhE1*J zC}5UJ=0XN@M5Tokb8DfFf|*8#OFTd7wu@(B9Z=1-vbB0{tO&su99Fh#SD6@bDkwIt z0=&ZLa2NvKVR>-7$;b%E#^Vx+FP!b5qMF>>RH;@^zT51!u#YYd>bZ_w*l&p<%+Q)m z!hF(cbgYNSo~fLenMojBVw}AzQwSzkSXVTWXU0RhnEUrOFNI=*S=)Q@HNzhxUNG71 zG3+~9=`_dsOF#mMxi-?iC_v}RK03*r#w~*BKe*>dPQ&ax4+@pz@PBIub>(gS)S~Ya z*i7!a?%`)rqzC{0MUq+%9%!sA^LY=o;H6gkwYF<$pFh>qybQgsh79smXf4TgV z6d_&tKP`ZdZ>SCeC5h4-tgqNzK7x43U~2L7KcAbK^+9->K7wz4gJrL$m;Zwk^nKV z%0?aR)elpiNZU42jgC&0y&=UJSg-rvUofqAzY->^Em>9aHgJjL=vFRA81e&e73U|1 zQZ09z+C`GtPMi`zXcl|PBH0y`T1!N3^LKBaC@G&LG98IM=rn+JB5>n}7`8hKLgB5R z+wO}PJi-@AQbLzUq3yLl-Eq-z@ws@kOY?Po#dUvYodZFYL&LI+BjQmO)AyNP2HCsP z(*U5eO*vXtzuOG@w>rm^6nQM$))J@yB&gkk3s=$QcYZCVf7+3bv|0P0oWZD)ZmsW& zRS%+Zln0xSW*{nm3yRh$Xwy#OlUj6i_1)AY#%DJ&OqmgA$lkePO5oVix7qXfT^{_& zH9cTdBE`1&977V5%#G^J=j6?6tm5LUQU`QG@Q6)+T$Efx5B_t&93fR^p5Hoe$89ld zwhdWRNx;#=#8^hu=R>lXvG2R+G8DDUHoy8X%@T-$heW@Hw=K-%sUd&)mWz;<&%DQx zs}_=LiZ)BxXQ~DVlwP;8a{$d2fX)!Te2sZ zh!c^3h(vGQ;ka{~AJRP;Yu%2=gBvWJ)TwEjj(-$CA; zw&~WpV^OkcZqH5z-TE(FHzKPIO%DLVVpz>*j(6eE!Y2FmmLdtM!6=YE+4}cpeo$X? zBCMr^{fqxA(%6YbvlN0#7zD}tds|tNog_AbORMmWS0=jrsyttt+DCcO8s@UIl z*{^``=L({xJsa`(x31y4aZjVuhh}D-Vt)pTgav@p+({{})%tt*+sn824|U|E9No|V zC1{sP+!ktfnWiLNSL)L`(L#Oi?>W|SBkT*+Vdv% zl2d?-SWj#5+D2T!^_fCzUa-muD?{L>)iA?mvoEOmR zjr%JyofI1C8^$Xc9j1d5O--^=$_YeHsHkfzWL@DRdETV?_&1)8Z8zE1uYtUz%^%!s zo4RANdmEAjsR832uEDyNVxyoDSbD*mn?sbz{Qf`Gpi;NbN>c?pzDnA`d14k<6XNNWZ);2j$Q#HcHH#24U0CU#G;<(=(iO=jj?Qo6c7iMnDrie{`~Zakaoq+I&KA zviIMNK91IpK@qYLuo$Fp54;(9!pM|a37f0R^X$~b7<5?B@$=c=sW@CO@HkDTcqe&J zm`bu!hRyb#o=K~m{tk|>K0-`P;uEV>&(p;t5P{y--i|h9Bh$|RorAq)M4O{dUyJ=o zvZ*1Hq=IK!`e1WY7UxSA8n{|^@#$#xPF8jCkRx#%Wbu|<=a%_?DhWEPX&`mH`Sd+j z81pTXDJWXRj{*G1m#`9xa*y!@7lF&Exo9QVa1dpOHotW!V>0sTnxV`6kMEAT|G=Sz zRDSuErNDrVRjJwHT&=L>A0fc)Ga}5Jsia<8wqCV;{fyl-!l7sPWxy=vCS{w^jxzT6 z+d)F|R)^b;yQ+hTIxs@ar*4;Nq@oyvdAy%!$|gQsAtSd#x<;Jx%@qBy^7LkyKeIh- zGU63)ueD@vHX`B0)qV^srP(d!LNVbo{xCqD#rx9+;@9%f)DnT)g1a^QH+A|7cwGvX zV%s0|nB2|5#EZtCgHO(JI~JBZr~MP6-ivWa7t^E7H_fmx}EYf~zC)euyVbj)vSYm@0V!>Jh6E7OVQ z)?a!DT6Ry+o!`$USBt{R=vkX}?L@il5;bSJPDEhZc;0Z)pBTLC9j>)!4VDLY zJIqOSFBcOy4d%wJ|5dyCwO7t=bcnoROYN9HkGhyzg+!~sW@kFQX|lVzSNR`6{q%($Sd2DPjaqmOO9rizOI+V?w5%t z8MK_-;b&FxlmpaoeG)h$OJQ~Yc#vaGS@(Kn&s#}{-rEpi8|KRPzur8;N=U4Ew_1+! zo4Q0K*`C7QK1n#J(y6?Nox5w^9S(U={?}hEH`|k@LIJdd<=jp}LW0s{Icm)KvI+Yh zco&9&-W=ZEFqw8_V8*~L>J_vpQ^_j$-RM%z;e$j|jU7Q20d_{VW4VUD-(do21swH* zSVs{vSFtp7H)0FkaIPStlsc)GdLk?(?tGx*UrWJ3OT`?H*I{455A{IzX)Ma`yz1gV zLoxt_BqoZNoclkKi|=D`yrg|czNOXdSH3H+;<$6yz7#S<##&kuQPU(GEBbBQ`X3Au=BrkB@grvYjh<*t} zj;|tBRTYcQ3?V8-UWtzub>b-^8?BBfTe`FJpn%1hXn*4D#~x7-$4#p1+K_5uNnEqT zqbhzEar>6uo2}La>wt6uF>b@hnM2yu9a0(!_jBT$wj{Mj5RHO@4M=1_>+XRxgm(>r z5=QVL0$c1X0wYf90Td>_8huPg>V_N4{wp$8*uS|QDgIn#AE)$yZzKl8Fx|3qzKS5A z|MbmE3V%^i^O<@I_?4swZ-en!o?W^sW9X&gSVdvMe55d5RBSuy2C<1VGOV<&bvCpO zE{oJ<^ShQ7AxNfmWq5PbvTkb>+!@3n3>mK2tp+xOozl-$Pi_ueY+9nMX}}ED ztq4cfifC3!h5uOoZse@aQ*bl|@M(it3hwi{AS@=YN8431bJ=+v2SFl$=;q;fTC%DT zWq~LMsp(ZfIi?qe{5=18S=4KVCpF)q4Tg2>b>`C`hbSlv)pj$6(9iq(POe3kPy{cX zz?!7{hInROg*=x2mf~m8utX=Sh(=S*^K6P}_-Ayz$w0KQcu`pLC>kA>axd9|$6n!t z+$LOZmlSC!k9)oE5gxB4_ep;`IOZxp?-tUBUB+$oiawU4JbD(R$CAq$JTv$bkR~)&PC=$Z$ ztF_fXh;m2Emz+2Ug5hyr_{I7REUMov_9JYHg{SV*K{OICtp^UpS0g|o*&4L6F>*FC zUk7~`rRy8iC@f^ZBjHlB?j!C&EJBQ9KAqABQ?^*krEAl(2>tlR{1U)!%}F?r`FqM+ zEcpGk3OY%|=B}9}Ht6XB&=-t9T}ASFnQTqaKPz zig=QbDGu0nkaWPub+ifH)c9#MrLNT?Nk5URAsOv^J`Ef%*$lP`#$|YB<#5WPk^1nx zA-5PW_~WizL!2YnntpG!kCU#`&>{5vNK`;~crAFtJqOao8-w7zqVABNuyRY$6`!V$ zWiX6X0ykGX`Knmox}#0>dFygl{f3Gc#emRyYXFEED*b3BK^FNwVH1-34|8uQx@2hU zt#?nuTu<3A0br)~k#N+AjgVNavoq1}&OL_r zi-czck{4F@DTm?0?=kn)o2qSVmG|GQ!{?$6l=F)gqfy~~wl2R$n%-A%<6@-Q6p=6s zoE*G8M*#KlijPcn8VlrOY0eC@wS(ZoF-WirdB(>h$aW}|@HAs$MVUhzi3(okdRcru&esB*$r!ni}ng6I@7h z3-Jz2So!u160j0Tfl%SeaVlQC{~6sSdLPB!B{b;J+~6!RNDI-7@HB0Y=cjI(131Z!rjHOabFg z#VOrCO=irHMmh!4$xRQI&AUu{V{T*K8Hkj#NSttVb4^KEiW=3Wv#fadMiQWnzCvS`hCgih8^1#6%BxZ)>5^#~&Hp_n^mw5P8J}r$o zBC+`__7Nt@#in#K-Y;wTh0lgnraK1bfr~mWX+1f7rNUZG5`i{M!8?q%O`D-Ghw(72 z3K1SfHL~xLbR<&$lH((8HiVC+TZ1Q!#K%ujk{IF}ks-ARVkR^~ zKs|f-j$wa>?YjtCg^3B>rSfvu#12V-^v(kRf&bvi;Tn8-z6XgMweV6tEEaynG?;eT zt?{&O#kU2Th(2TnLj1Aqo;QC)P146bzcisDFk2%SsbfXkQe)xmA$ZN{YZFw^z~IKK zOYCOVt2I=8T{LAr3t^7SmRE}Z zNSnJ@`iAcS%|^xc{Euyg3(uh7{}ddT^VB^mcv+$ata=7|ClA4ew}G=OJ>u=L)MBwz zm|Qgb7gBoT-gCtyGnY4J0){AijX%J;wUuS_e+BF_>334~W&Zt53~XZdBhfW@L3lIJUdxbIM1z*xO->QYf7NU`(7!Vd8zmkYk^ae41nyLe0ZVGZ51B@?QB2kqSfM z!AL#v!|x_eo`zBfK9x5PQ>24HCl3tJU-sNz>^3DzG8#-o%Q#fkiK^3+8PkL2I#v{) z6i03@=FZvraFcU!Z!SzeCBH-Ap~1p)C+JEUlJf`gtLNSj>V*7zzt~_!Sbq`l zwr(Em2=EFolRmT$<}E9{coa8hV)ZqD3<#H6`CjJqmR_2@SfYUN#snHouatOQ`;Z$9 zK#W^ALJAI>AJx7bV~l)O0nMxM3|70c9d+sqTM|Hob9qt7i5k7xwjJ zM}5s?<-5$Zm*ihIDAxJGEC=lvRPpxjQf z$x=3tp%&=_R66>8)_lD|#)ivD(PHeruadVH;k3o-z7Lb%-u-9D1j4_w;qkF+-O5Re zlZ5FAOH4~r`GW^Fli$}5s^u4J!J$1>>&TnfyP5_)e~PV_NwF-by=Ps8dGkoC@ksK& zX0yP{+sMQB=6;?8@3QL$^e(gb?P=3{KcjD?mb0c`&kURK>V>~2*T`WaOQ@NYe1F`g zky}xVCQP)wBDXH*lP`(ia*gy3s3wvy4== zjWJrhlQ_C*-IPmoUeL5$(VmEnF!4J`!mr!&P*1|A=?PguR;~*#jW|Ai&tUpJBKJ3I z(QgR(x9xQeT~)Id_yJVmx{W>1L@W+}x#WoUm;NL?nRFes!t+&+#LkrMl}P>{vzo?` zFI)F<+&Hnlc&Ycj$!E=tt_h!lGMeLdIbYZvg&Yfb@nVJx0z)iiU!P{A@A&s#l~83{ zSCC*7tN<&8H&2begnJDuJ0tl^xs^MsSZkZYi5X~^`!w6LXjj<1-crp9-pB}$IO!mA zOXx59Yy@{YY_!A>+@6(2PMqVHy_*!@+wz2&=zS!oTv2u9ravTKeGzB9_Pq(HA3eSX zit3+k@YF5j(H?#q(0ditIjKp{EI7i$aJT)4#is1k*%g1oew5|1R$m0AHC7Em2!LV3tkzh-iz) zMUM8?j{ZC*>-KZt8`iQ}C%Nw#*bR|a4v7Or{VPe+s6u3V`}Wu% zlQ1o0E97lbrVm`U>CBmE0;VeVb z!I%uU1If~i7$FkWHt855TU?4wOHk~kLJWf#iPNZ&t~TYas9lYYI>*o0jazsP$Iz$k z-csB19P{pbe5zW6cNes8Us|T{g>-rxzpQ0?xe9++a}u^Rqkx^5y}}ML#vC6&)*vkM zGv1XtG~M6$E8oVCo}d$~{O91A%Stenn*L_jTU z_CV$b$!rfTb}huPe05ig$$jUn;qJcH6T2!J`FO@vSSf6UhfCpmVis~sPO=}-P?+Y` zrSa;x+H;$DLq!cx{0d1@0wjj4_v$uKX1~$%+=S0u3U0&>*rjZjE?pI2h%V*qA!y*jHV!h>p&dtDk4C$w;f{q4!Q6bbs$INvJv#L#90pGE z{@(B~HB>m>h+V8zr~-brxqti5(-Z+%(~71VHa~41Oc{H~4jo;wg?g};zsZixz3CNj zQGl)4-d;_JsVyP;7(qwh_Q3Hu$1PwG^QF|rF3A(y5O#4tP+L)>^3i(X@fBDQ3D+Wq zt|;Rh?ZBF>#MD{0a%d5ukN7mBBrA=M7b4B5zs`M~AS{|LBsA{1+ky0x`X9(pH;zVM za{@2TdlredL=gK6eD)Yb!-gZel=Ek=EhJ&3zG2RnVtm~$C+lChj=HJ4hIV>lNoJ&@ z#C<@xtO9>MB@6{Ooz?YhS$(luoE2|=ym)BGeTu8y*9<~Ozs8D{|K6#-K=_96V+9Ru z77G<3m5FGOt(>)Z@LR6OnSa4-+8AkTBOUf5Z&6E|u^A=_&$46|>mc31PO6jO$9aa|-NRfPT| zMxvAP|g$?(NMLhUcGSw4NJRuW0Ol}ic(Cd_lUnF{XXQLbXX#rfaOmU-WX zygIyGT9q7yh5I8aFm3j9(Tf9D1L9V4+JU9RNj14#WE>_AV&CU;suUwh6UnaVum5Jf zk*E;}Rl*P38)xh&LIDcG_4VVd&(S{aJnc;ccm#}w=JvCR7JV?1eer$j=P3NX%f7y} z;sMO1l)p0@)(#8eX%ZG9Eu~+{VL*>UA~<@M8{6YJXb19mw#1Ajb~|PE_p`MWpeMyN zamYtg$pG?JoqmuT)e-{`m$Gl{FKfMzeiQm?NMYB}7YUvh0kkin>AzgE^c`xdMpZhh zx*{O{6ol)CzVMd!zu+zN%rWg~CvVm^+us|VoK-G^2}h29!1Oc>M_k{$a{bo<2f#G< zblS&>WX?70Q?^CCmWSRU#jB>-iY9f!>UNsS)9xc8gAh_1XURxy`AM4IemFM}u&!(L z_X3}xMk8U6ar$BgDRJ z$zfz$Y+_C>FqumH4GQDfn3HT(3m;XN0pZY=;Ns#co2$ehGhA-3qZKQ#Vir*~IK1K@ znn6!FPMSi#)-)5Z-)?N}wk6_7Kj7-)$Yb_&_RChJL`EWLs`g7D%b{`3!)LKp)`_!V zB7{kLmR6J3JqiQd{kHCIgiBIJ)j7!ncnhz9nW!_l5X30ZM|`yr>(LB!-Ji0KJSBe# zv%#g~U#0cY(l(6?zSMJ_6Z5UI$u9cJ9Qw3%U`PLeL(av9+^_eBWH6F#d(ec17GtE* z%9Hb8A|&yW#=xz#c=-5410i5$^|8L4ScciMsIs+sgZ=$*Kq$6N>SkxF`#DPJ8OndT zkC~3a`$W2z-?=+TH>|z>>L20RCe4rX7niT(d^cFGi)4E!SaL^9 zWD=(5ZTV5O)@|3wo}{9&c@nIyo&HY?Kp!`Xe4ewI{9~iBWy~uB4D~e8BsR4yGj1Ou zq*La0Zm#?0Z+I@jbr*AqH)JWM!P+9KLUUSfn-|1g#yKMA;jhHC*+gy6&Ms0GMpbx{ zNbh~1NL1HMU+2u2xSF29*!avRnNRXhVi@6HzdtFQGYU;U>hjw4?!^1H29iP)e;59N z;!i66q-*j)Up9A+L^18;ooNP1DRP_eSXon;$W9f5fu%bDh_C)ZOPw6`c$}{zuP+^@ zV8g05xDmt+a36RmlV^W+ruFxshVz%bOd)Tbu23bGFS}GM|0gMsp_h66jMNt)N(Vv0 zqc{Wq1wQ0N6AyK28Fp+NPWdwCU|0>Ng%EiICq~l!@O97q9tB{Hm9MQXjS72@7L{>k zhfaqW^$;!ygm<;LR+!ZT6FwlqJVZEy5y0Ug0-pbzoSa!EG=Ku}Uu0Z+`sr4qR{U=w zqIbCxi}FZuCln-E;W7p{VQ#{P2EH-D3-4z5Z(H3Od(_K>|MVLq43pxV?NLEOeh=Oo z;<%Hdr#{2ncHKJj4pM&W2=Y=R$eeo+8CzIj&hkD-1Xsjr<$n8cy1EVC9$sZ=BqAyp z5>S0fxlbaYuv{-N~E2ihLP z3;#4`glpDZa<3RDl(kE}5>0sTsEywo0>ZGyXzu=Eb|qFgUtdyMS1 zj_t83Iuiaf`fAZ!?*5-3vL}}Bw`f4RT>4oyTcypEK#oTjbetyRVMNEb-<3 zM}p0{qrM%yOV8VT`33g;%VK@$0dAH_Rhnm#Z;O7?_dm4K6yl^v-y;u-PL4;wt zSTqs)TTqg-&wfP+b3V*=W`S{zE{{=RC|-ecsA$TtD37nt2~%OLN0L<=DMcqE4x4FI zftW-%I~KFFfgn>iL5iI@*0r7$$@BAJ`~{ zo)Ptg2e@vtgx=9?t#pc;+|s}f)C;LXP}}$W5M~_(&R(8_u4t%d|9Y2Jp-ZHe>1k_e zJM&<@TGan?I-sJF|Mm+K7?=P&L05s2tO@XoK0seu%8LH*Eam3rwl}odzDrUGL;$LN z(FR1)!2EK=z{wZ{yh#8B23W=S|NYC>M`{8M|N6DT6~jm!A?~$E`J-GpAt!Fr%=9z_ z0tp+lf!EcwBu5^(#c^O|FC7<=mWFP;9B)jAio%0CeOk3l>eaTZtEx~9z}_=nMg^@R zrL$(@l92&^IopHFa})z>#+Cv9up~d!Iy&)c*iIKVJbC(9E(-)}1sJgG z=@5ZbD3E_!@2xxi``6XU7T2Zh=={q5rZ=Pn2o>k33FR>!|9Q16lEUAk5ApyGl#`2gssXI4CXrnBSQU)o& z*A?5X$HO)GfQ_UvaF#O35(uyRPN%IL0mozT_ZF> zo%J(mvf=^GLwv~wc|JEYe@AhyELpTt%gz_NR7se-WcJvpaNM zQ^9w@Oit+Ux-zo7Y{+_Wu@Qe4_%C3yjE>qBkj^uNCceH`9jvkG>m>uYJUo<`K$YMD zfq+ypN?8+5$ypF%EJ3tw?cLF?hNLNq{s*^nhu3HBJrC$joYr>*8!(_85Ed5BRT~Q#h9L^B8o7IZ%&XBQ7=FM{X!FO>7p=XNl7FPg6r-XP4CZtD122S}i zOYq{jPB;?_V!xIAi3Jzq1PG&vqCKsPUsj62L>U>B^;=Whd!f`$YCYjCi60Yz0@$95 zizN6x8Tzn}za(~#GesE0Or90Zbnx87f*uc-Ur2qmXRAQ&r>8Ap_$A@K@o#2l^8yHK zeP`&OotNbOuf1A+@G9ZNG1p)Jowq)~uAOeUL=2Xu>rGm*UO6Ohp zYHyLM0Wyg45PEmLR_`a7^udMKv&<@H-DO7o+hL%MsbfBQXJ3DprO%vTAAb6hXLlYc z<#%E0ck9q-i|g%Y#gyR&i6W89S7zy$J0W`v(+^;2Ynx|42HSxB+M`Q z;z6tN?U)lyGHh>tEnSxX68OGyOe;Mz0uhLE%y*elG%9nb_7DDU>rX`Xw>zY=FE z#DTXIjNp1cZ3Xx3U8GH@n&An*iR{|)NCPiXBrB38+od)QwNlMo%7y3RMkrRm8D`UQ zpi7Lvcw<6(Q|BBA_h`JPr>D>UA5m`^5Y-!Ydk;u=4@x85^{1tWknZl5ZjkQomL3Te zq`SLAMCl$<8l+?1?eo0nobP_X&1T>CwXWY<>v)NmyzvhZgZ<*QXxa&H^y74(3N9eh zq`Aqx(Ju~A+3tiodWDx+7zR+rz)g2LWr2Zk(DGpFCjW;B7{6pB!c-m0gkg|_H;zjj zn|fW0C_MazaLb0$#WKN0>b!4B90{}k{wD|)^*o?eGw$%j@!To`JE=!=8` z`t|!ENlvp4GcL$V?0eTys~Vw&_oc9AJcn2oA0@E$TKXWRz4w`;nS*HpRN3%jR!Fy) zQB_waioqczX5%$IACVu$UKLen3CNE6Q!;rCg5FPmEDUwEiWjl8_|ptECJk(!DXMH4 zy;r@01|gi@Sol|2^d^HYp}gULBab(`cjQ#{8g7}&Qhj4%I>g6*cWhQ@c-H-(m8np^ z&K)VqZ(h}(-w@kytz3NPHejRM_7*avxtS$&d$!> zo?TqfIfc8dcZRY}#6sLBMyn&|M6Wo78#*imJg+%|xbKImqt#O-249osYs?>g+&L>X zurp9Lp1_`j<52WTJ;o@K0xV)9Hv{^EH6^~VlL7kTM>Do$Ey3UyZjQotBi3oq!v3{D zs(sszcm}TTYdb9Qt82GzK|imMO$V5ijP{*(eci;AwV%-vtdSqRB~=g}uQKHP2g3qG zIJ3019K-7cTP|aa2{L~;x6C>sse_XeS5{X3c6(s#v_%LAxjtY#WJzVTiG3&~>E4?* zzz38cb#x5%ySV6r-Q%$oSnRo=~~@0@~ljI6F*=})GW9msQ ztWtPmpT3h(Bx*@hA>yFKUNkj>KZS+ zo!iUrBf9eH(!sM(p16tJXa$}dZlsy{az0)sH6rcBvo-YktvRFisIyD;56Z;i-&#gS zJ8WVjAp_1yXi?hvP0U5y%4DAi1j_)yaCUla@nVJ)`#cH(NPx&Mx;c+3!3)h6Nr&L) zVlJy9P=;POKj0LR2Ots!zkTnf$kc1ZEPo_qV3!d46n;8wqnlZuJ8qmS<{4zQwywt6D)8_RIC6!JV6 zJ2u`QF8E3Vsz1kpm4Ou!WnkysCz5;ecd8^SG-p2R2Q8rp{us zKK*gx4NARse~A=sT@4=8FUgDP1?iE5z6|`e+KI@u}~L8$J%EV z8SCC)8O&$=cBdX+QxbE(&-g@`u5!|LUH2p53{j!Z4wBWES(hQefsPBbp>-T$PRQeD zEf95{ojwYlO|6a(+kx`YPIn1*sKAlj+&_-_eFQ?{7^RJh-6#ZTbB4#>G64Q}DYOqC zoIWQ{JN$Rs|gS+Wq}6Jfv8_ zD3l`fLR*v5sPt>Y%StkrDG#sp@a*H-3oFa`r0w<0xtZwkM^aXNj6TF`SvE$!geW}Y ze*K6|dX+UHnw&u>jXc|1y@NSY?0JF`%@tjuX?Jx$W!n>4;H?JjfzKvb*v@#ufTB}x zlK%ea@8xH!9HZY8OgJw`L+w|tlBqK?|C@FgM8kq;|CnDPC8bYz`T|N(H5xscW^1bj zM|XH>Ye&*4ctES5Odcw`2FfwvXv^{a{H6^0StXpi75_>rSDTtgfMJDD=syladH^Phu-x&FovBF) z>zQvH$@=Au>9Esxs0AU>vmtBV!HXVm-)$u3vqj~V!_k#gtw}OQ--mu7zM`9pk^aF( z%@w{|_AzRtxePnBLh=;di0QXT{)+3SEze=?Y=$mH3uEMs3pltJ=Pf-`++U_NJ2m~r zURa3aM3lubEER??*Nmz5ss28p#nI7Za^&ozKv`P9Pyi-O{Fa4KrVZ!4>5A#`fnJ|< zIa)3i|Cf!6@ovBQvn)$#9Z9xD-8%o)$0oMqQ{o{{;mD)u)$us!r1it)VF>3YffO)T z0xP@rHRr`B4Pl?uuhO?eVhFR$`3z{9?@LA->@X&7Fo!1F5;UPCKVyP}>>oR6gZq5} zj|UpfOMA)v2pd6c@0S5^ngY;!Vy@mZ5(Qgw%`Lt|89JkrLu51cET7x7iGWI^S~oUc zl8CVzrgn8cyL=SYpC93;81LxT&yIe-=)anwpU~FRGa^S7*mz_fA&O$odFIPvUIX2B zbG0lLzeuG+e03kO=~b&Na_MrO%!z?np_m@KiMCgV7cSY}JLv~)>rF01gbC~zZ5v9u zp+b*t4(@*WaB*&(*OL02@^~AwajCSPE-RB?tGM|$1+49!^sG2f6CaC+9&GY(u!!@Z z41>CQbJvBA&0OzWvs)6r!~qvsnlXYOe;f3Q5DQcow<(hbdC_RuXprjp;$2ecH_AHg z5oA*{)pmdvu~{>rw#aaC;_!+1(Kg{89%>$EuSS;?#>L~o&3U+SCECMeMi$gLlo3(A zv!v9J$cWjN?SowxKm)AiqMrQzb1Q!l$2oSrCtpGN$_dUmx)x?gA45SkxFBLO7{qpw zct@L-#mEu0%l<2yE`>hUF|$@zz3z>*M@^Q!C}bn$%VO{)THnb>vg+gQwj0s>W)3$R zL9qf$C5u_S-k%j^oaq6P`fI(c?UuLv;5&S%mk3w)%WsvD+6JXv!IlNxkbRM?|CE)z z)|~mmEU;5W|I^hkwG(ju@pAKkVW13YSwrf~{UJIMH!<;+^RErr@DI+-7Jej=DW&N+ zr)3EbUexqBN0|sK(4FYU{)F23hk_U8GScK>e03qQU=uax%!?fgMdk02j5kR~y;q%b zjJ2Sb$e|47zAy?x8YF_!vaqyqExRa`IsF<5bNf1w1z|6ij1%{vwBD-qik}hNv<9BK z)rN)LO{{kOU2N(1vx+^9Y9>^_p-S2@k*re0sCc}{7GO#VcsQ&eqfkwivZO!OKE~{D zUE_RUCpJk)HuVoo{qCn;^#-%f?jwnc0ps2E&cfCP^gIuOgp!5XM=Y}aHTJ-7W#4!` zq#$Dt?8V}tjIAQM8W;;+TdgY2BkSF@n7Qo5a_3PjEUzDN&a8k2~KHN2zxE##k6Qmz#auU{T;B z!y$-idEh1ww|Q!BHl4gxfli%q)Bp{js`7%5Ru~H{@?~>}HPuri>mkyErmtSF_7;KQ ze=38UZuFXm_CxRB5S6z&fLa<8H$IW14@jVh`K{1etSA|Cp|nc2_Q)1rB`l9jAH2TQ z2<|tV*dbRYF0jbQgnz>@VSA=u^`)kSXm1rkC{0`$Aob)?uA4Nl(&TbCbDKluZ%bi< z=1GlcVBz~0EgWx{el~MFEX9^F{&a_Do5#objWr)n0Ujdb=;vZ??O*0NU%(R)B+C&; z?=fCJ_dSyI!xBeC0bNwHEk{Z-(h^~iwjo#u*}*)@ycj5lO67-$q)uo}dJx`^0F3B# zi;|QL#80o$n2oi*1*eiEZ(_L{&;+c>ROykj@_5>I1e9l?*P0Hd3_v^5cI)-$cLZUq z{Br9So^Im@C>-^q8#uG#_so;gFQ+JY0X}81J$SKb6Y?Zkq4fAf4ruGnaEcu;r$$~B z^h0Xop^oe6n{Wim4-ZwY8%I;br?80t-yau`yESw97=~mSZt{l$o~qlaVTBA_9mw5%F8fD*dXOx=jp+6IEX8HbmoH0< zG1|RImSnu>BRm;8XtScCfiQ5_osK5H{v#4=i|c*5DnTQU8L#HuK*{m>Ku`QB{R@&EsFEB0xGilf;`=KQLqhW4Jqp4m${g&0 zH}Pejo*^{#zChPd2n52axK~jVVBlL04LMGcm+Ue|OC%zu;q|NzPBp3+U1zZ1 ziu1k|qyOizw+Q7fx9G@FCfblil1m+Wp?o!E!+Y7X@8==KRZ~e@P4@B^dS@K-IN5k6 ze>{LuoeSjciaV^R)A))~&b;{Y`s;gh`)V2;fLpmKO#|>mcX*SvXdS&Tt5>jtz{`iP zC-3IYMea_2LUy4AO|M%42p5>KiXi4_h|DwEh4HUUhaede!GY*Lc!hr%I&EHpym zmX_oghS*&Qpf87G$cJfaMD*^L4Y)~N5VkkT=74&~xXm@Xja8^pQF5S&7W;&K2R>_t z)kw#_7Zeu77zu>C;?5;FpKbFDLAF|J-S@!F3w zvbscHoSE1&-N74$9=9Nq>6&0t%M!uKM*@esm_V%P0eQH6&D?PKUjj~IVq*Ozjk-=_ zjqy9o)R@|Y+}Z#i-6W$8h zeEEn0JHdV{(LS?HI751VUnef0_lo?9d^XxJ+9!;#+#&dB6*6zn!7ZfFyFTjctK-h@ zs*sm6WVEA4$Bigm!t&-lD^Ui5ME0AZ*l`jNYEXWpuWE5|dMXsMYTPikdR;O6?dW@g zg}cePXft0{Tm0PMiU$f~7w+8#Jvao$VK&FNAF+AoBMzvR4~mZ>_8ngfH}#S&pYPm+GviAS z1QU5|`1bALNTVDqH7OT)@yL%o{{y7aGO(eZ@XDz<`ocf{qy2KJKV%;pQM0X%G$ey# z#_?(V(En}CiX7!87s%KT{`*dJG~X%^VkwR&&7(t@0i=XcK#8wnXdAwLQL{p>r)S;kwRY_V9r2ubZyzAra$fY_SOvemzzi zRx_XwT>rH+{C`-0+oiZM*c;EM15mX! zB_+*CWp}@@Q1kTjMbXPokcy?M(Sh@G1B)$wKRvG$&ooIg*z_6YS+8*@MSJXtf26AP>w=OrZ-`67)zp9%N z66o{l?9;okjQJ#-i}RHYppalUxd#tFa(B$v+jSG4$Vi^VxFyPdDt??y*k`Y8+B&ME zy~D|L%1w!|o(-}fnWCE?MIQgrmox!@fiJj7iFK=RLo5xs*a+L}qiQ?*U;*&z&HGM_|AC%<@v&Q{yI6DZ5ADl2Bbj2lZTYOL5W};c2VI_AZyZpFD6E4duJYUTyRGn8s8;f zlGwq=pzyMT3(^0Ay#MlwlHOxD=w?I&f@gJ|iZZq5Rg>lxPh!T&Jh#`^uH69F>%Q$f z(Z6y(KClq6NZNZtw{3q!(@wBjPj*D1w|Stnz@6<4yVMgjeKeJ1-|`&^x1TUXVYyP+ z-bV|fkL1Ui7q2)=%>{)1sbvN7*jsx)b5ly$kA2l2&(JuyMj_IVVpC}C*nnQ~6py1+ zkM@7t&N*rYD#JUU9sXly8@3hUuXcHgpA-$d9G^DBHf!1yiR?U*CGsD#$2ZSOsii3U zCC;USuylP(FO$TfDQaNloKR=Ky#YK{lt(5+#AY+OFN)X+<za7Q}heIu-Nc#%QyN%|Qie?*xLc_Y{!k5tMq64{7A!{f*uBTt2Q@y~x<8 zf;z0*vwY2ksNQza8ij3W3>OBN?n)IPAxVghdX1O3LOIh=E(P^ZC(rc zZ*MThL4XZkZjO_|>KlkVF_hpB=2)Pl{5q!-7h$=*)Ldf|QePmUGAsWCLy^uH5Hdm? zar}JKB0tHJr`DoM>->7F4oTn7QEIU|TaG9I0q&E=mndHH);U^#wO60^E!Kd%*Q+bw znQdP9cIwbUp3b1R?A8vZbv^%Y6_a`Y&t*1~-GVtrc9GH&sM6wadIL!gR;A?{?+qF> zMS48vLe?liMMc zuB;7p|9^+hVU=0YI?MF;lSPuwDAeyduhyi?BI75BkJQWM?sV;YSk`|{5QiclEsaIX zQAb3a?o<`+Yu60jTtJz$peeftTj6O-jdz^{yc#g5%ecRFq#6dx1a+PD_qsO;^fMz7 z$d8U8dPswD!-g5LBbOo{u`;H-jAb6bac#nAYe?TJXxOOVeQmH?TVG$d5G3EeyCVfQ zl!`0+C&5(9S2I@s!gmQ**vFAcAUb02Dn~#4ir)82)r+B<)lGJ(@|RKa}htr>HRJtE^w!A(7tN1`!BQ}`sIhiL%!>=u!@$RPDVf-4jB|c zR|O$_^DLDXqbEz+tv@N&bcLb%C674J66j)!Qu2$pL^UM_sm z*cG1E>-!@1Spd|H)F^AAz~o}oY%DARD#IIO4Usjj0kWJ)L0sGn0IzkT<9~Vu<;o|$ zr4|mil)}x-8j%*&VJf4}kb3VY6&})iZ8Jif-Rk;|ET3O87Eu29?YZ}9{iqB%Fx}+Y9Wx}j)h~TPolqSVbb1@Bpx0W(moot?Moz~?^ zR)2B$49E_*nf}iHQPl4$A)Zoo=ycJ*Q%z-Y?2=IF2A6bnBTYu#ZiDKG!{A{2D4zrP zXAkhTv!Lj+z%zefr~`6m%1mlz67w*7x1Ry|}rs2cr0# zO)f0w+J%OQ#U2a&y3Sx<&jDiU{CaHxpdKL*j>(ra;de(VZ<9*@s#uTIZRv$B3cZ$2 z4Xo2lwH~b}YEQS;2TH>VXLN2-RDVsi!3&h0pkC3a6h;iO<8JR=#ri(8;^1nm4xK}c zMw$Z|ujqujB@=poX#Gy^U9@WUI_@CFMg20?WHrL$(ld13!KB*;wMfqywvd$8{`I5j zxD|(O1!IHtDfK2FXIIpMzc%t>=Xk@z*teQ2mjoQ^RX#x1=fe;)rb;mYz#HDc+BcKA zebi+AWrDBJc&%0OlgS`9*Bl>!9t5g$hNr}TUYaQFF91;IRTs1Tma%mB$?u*aDt@@@ z^NWuJai}^@E14cq{WhXY8caZeltiCsAZ2f!*yYdp40sF0B-v`h5+4({6SXw*D=g;{!py7N*)ALTK`4vQ)c8;kmgN46Dt^zpA>s*|YVLmhl3dO6xRQuif5aqkOjo~6r1!HNZqAb{lf`o_RuF!?-d z=S|U6Oocfae8Dknwj1yaicP|<`zu@g?|@;HrM~tI^1zdN>-kZfs%n)2(4JAcF;9-M z_D+oVZXg;TD=vA+M~44b#O@D(=~N~@K0Y=fS^HQ>RJUxd_ZTkoPin7gg!WFd2{IPO z_mN`jw9~lyER5X8a(<)o7HM5A)f7S)Y39yP_+jrXjuOrba1|xG5Hli$!to|1QzHm| z|GKN-;MS};(?wfgx4$k(_pl$&)2 zA4wkjiKrP6u9?0_Z)I-HW)Mg+vupjWjzc1mGs(Wgsd*u8mN-UOKCcm+73IcZCN!4HUvb(^UFyN{MG^MI({fqef z(ImTd)%j0htU~RYjpAOX+W)hAv~YL#NCg7|V_edpBJPyweDoEg?NGo=Lt0$U7Sp#$ zR*U$m$1VvYCJqd7KyfoBO!dVCH*xec59|hm-+ezm9Us^x)2a%!vV=}0AbRZk!`V}W!e0qhZfzE%U$eSH?uENl*t0CdYc7J9?>7b4}V>L_QAb^ z!)RgZ~Q8!cmK6tBB#uX7komETAFh;SqeY+ccKAR>R7PZkvk!eFzw3Q!jV zQJMA0%`qz;-M`$Fx707}!kKdso7OPDi*3labYJ7R)hw2qJldYKPGs&0m8F}!-!4rS zoJ#_IA|^;K#C>_7z2BEwk(m!OZJodk@^;*~1MPdcluM(VKMZpWFrJ#B!3!;=!+bte zU!uTR_~-dqb)Nh~4&F2xQ6MFy%q$)+$#$vr?pME@LMse{jJ zI`MaYFTQ32obB10?@3l{U$1DA#LfYWM-SQw%?d|EzolgtMQQfcB?Z~a=#pI?aOuxl!>-ze?pueA~ ztexQ*L#6fTUe*rq9GTU)I6-m2Cxn;3mB7i)#lqrV;w8-0{qVaw8Ud8jL=kH-{p>Kh z@#yRJnS7+9qeE<3)xX3SA3v*3LT?=p(9t$%xk9K>V6f!R_v1obQLm`+GMkpOni)|< zSJx!psb{rB7I8MRn68+@qSvUVmG^){{ zL5c}i@xZQVa{;5*l6M#3f2K*h3~R&dWa1T6_+?Bd1%B3hVOi-jKyB&|YhCXi{g=}`Fe*ZV^-}j(MkeMCeQ|=_K`HKt1l91yM8`xZ0(gDs^lVXT)G37mq1@%yx9%KTs-b-~pFC6M0Yhw1

gn`q}$3x4x5bgQC*4Sy-z(aQ_ucxZ`6 zhBwaf=CtfG{X|8AUdl%NfEIjxy_{E$CrQ)lByHZ-LA`E1^#oJPQ1%Eq>*KcLKzS?2 zU(cN%`!gEo6I{U0^spdBF__w$-y3;N`pR=s1-M|2bRq|V8|I^~CK z3c|cuY~(pcWJfxC25fkbh}wplfiXXY={=u&v<8NL>c9fI_QfscbM%Xmd3hjpO>N8j z$I|!)spbs{5C9aS?@6kzoQw6Ie>&r$)QliM{fe`<=4gvA~X z-Ud8hFWg-u2PYK4pZ004A(V_R;`uCtJ&jDQOMS9T_60pru z)BcYZNF%FLt)-AZA+q z>vJXUU%-k@-67TMLq&nNw!n3INK7*fIG9_ql_#c`6#a5ZQQ8Y^EFuQ}2dDz5pKHLS z;=YfvU!v3oZ11IXh)B~NIY#~`ECAbrONXr$ENkY7KGJNiM?$2({wDzP4J{!~+11@W zOr_!#2*?Mq2pOrGkcb?YfQsyNZ1%OT9 z34Sg}+OMmvSsD07$IfZWFuW-1qW1g9E5ERCJG>0qxalV^vDwRg}bRI1} z2)wwvyYzg@1KFlQuQ3Kbl}GyBop_VY6ux^!gS5ZD|1YzYsZ3BvsBa>h6QD;8zU#6xUU8&4=_90?C=bDXzlO!UT!_rd^LDgs@*|1ExDW&X{2o=@-nS8BEzCIC^7JTitN zoeCPy4alP{6wo?+cemsV@vAk!8eSV<(=~8uF~`y|>OpGbL`%FNwd2#t+js+v+<gy#ux!^>JCWd)BK5d z2@}Th3BTCg=Bs~7)xYONYN@78{0*o~2f&9nF5F*x`bm3duT{-HF#xuzyz}R?VEE%d zG8XVk{tv!EiWBX7bF9yR;5$c$&XI}MkOLiR6jj-`wggZNT#Bp8gfb|UO|;1_EfDX7 zwGd<-_YE|@zq*ECQ1J>@X?pUJbjyeFOask}5hWvh-}Tg#(`B+}mHu&@OIN5Qkcq8` zUeJyAhN@rSB_c4;B7ZdO<_OBf^7m743Ef0L@^umF(9 zuG!if!|{A#;Ir^o!`VvfI4aOTqhrZ&8z|68=osCmbEg3R5r*g>NJumIxW8FFAp?(n z;4|1#mDFM@$3Pa9xUmYMs~Ms5;b!FNF}ur+e8-7*!y_BuxZR=RE&}-9$^0OvojnDm zY-Rv1bok^`^eai@4Sv{}u#e!=9oJj{WP4~EBo1E?yJLSjJvQAG{{|Najvu=w1K_vW ztNb{_ef&(mA&)Eg(gDZT9d_A#Muii&PetCsU$PIr?zi4Y!wH>}U$ADXU;Oz_yQ4Rr zUxKmw>7IVOz`+T!Z?Rr3f>9TRU+^D`)F1zl!hK*x<`1e`KV0BwJHLC1{9nreWb-FU zK2i~L>a*KTmai7{Swh?{&d%ps(NxZCh?X0Xje%6ELvy7p&TW1{u6M7V4t0aukIWs5 z{&;R4s{O?d1?6`5r_;XGc_T6ZtS(8$3m%)JWdauRxPkv7Nx(COu*(jtFmKreAVZ*u zTGtOkREDCjW3CkCan`g#VJg3V?zZ{wfLFbA0slMOwe3FraUt|;iLTl=7g`CvXoH{a zv+C3p2ogR?JR@{B?^C7L{r>|8a-D;ZO)7A{0UZW_{mSQT-JI{u_pW?kog5t8nb0D(B&@WHCr3o^2--u0ES`q)=dvf0#c5gmkJzcMyi*=K87vA9`I%R+ zvr5UWfg#?JpRnNGnk;xI;bWJWk94etFylju(=1ww@c$m^hHGoQ`j9 zysMS-tB`NGjzRE{ZE(*W^1p9haBwo<{yC$9n-;_OgOTlCbuyavJto7E<>8EG@CR{( z>7K#gjBtXVMQ{&1P|eFB9Ha3=%F9zxID+r>%!^^lusGtg_=_B<7k*pxB2YXWjB{B7 z$CQUjE5RG!2tNtb{c=I)x54n+yUlQ15Qypn)wa+284tU&MvuNseLXtmKXM1jdS&|d z+2?OYu#c+W(nRn7%2SDbUP*CSqKM$8moZiIn@1sWJvN@&#kG!lLUnm?$ScSiw&C5gvTA zzN71Y+PsuL)sl99Xj{4Imv}e2Ch@B60P=a^fzafY ziNLy)1gHP(tH#FFCA(H9n7(oIpRuT48rllgKQ+thGcABZi20Bp1=C z>InCL=9(rp$&alqq*@eviOC=Yyr5_P;_T2h4z)w0YZ_9Cp)I`sAUO-c2u~Jn^k4o9 zSw?mZn)ndp#@cq_@nwi?9&%HUcO&-vS98P2n#0)*s!`gx-HCpa@7PwdzE~(~t-{5C zvAeE=lguU76T{E_Hg%OCb7Zd4XqO0M@@wX&iX(n>#}-%8eOty51U|C)&!Nud`e&5V zAD{WJpPVW@A=+=_$Ll*^X*Ug884hN4#{G!xbrg%_FO<;so)`C#_M6)rYOrl}J0j7> zisD6-{{FkfOJJkTLC);l$QlRz_XlD*IXO_(NIKwkqecIg`QCcB)$Dfm(9?B)y1)u0 zPt$I7yzzc6%H9{_$ZdE#p|_X<_xlgPK$7qQ42&*EVKpKuviJ`NWsY?Jt!5g2K`@$yPWUqnSl{h(muavDdg4DsuZ@qdb0K3sXq z^ZPXwof z{LU$CS zB6s(9;>CY2Z)qs=p{2*gFVS#L6*x=)6gc8exABpx|7xahH4rD`KeGzlt#BW+?iYvE z=a0x8KM};9c2@8TgRli3h+pm|;ICfv;pDPK&p58PBfY^dExkA$Z}3YWUw_TXmq`_$ zpWbvDZsT}(c9q5j-w2YsG_!o5voNw!_pQAJWiMOL4=k!&()qr+C+yM>HkFkRQAATl z*EX&hFCYpXLNylZ;VgVNkVw{29kJVhXPz5kosULS--(y*v|t|Lv1^Sbn}!xonvg{t zUZQiS}cV}6U;AJ@5_i$o7RRo!GiK=H-x=wZg~980=4D#4lu8{UUR7$ zLuy7Z6#qWjKf_1mkqe%Z;E{53DK3KgYBYxPWjVFr`;9H7AaK#kK*imj$VUH6B=`E= zUGOmD6r8N50)8u45R7$r7@T;2_7sd~(v9QRi3{6@W4oS{{;BwFQ5mN`EbG3!5`@;Qv1?K+M~1;kR6I zER!zjwb>PQu7Y{Ptn5Lv8aRxY8D0Dw;tx#EuTk?26r0aw*&=>ocqQG`2N2H!Sr`#% zBcpbYw|H;t<8ha1JsZ@A>`LkP<{1(RbEg>8GF?-R)5Z%`tSgh5Jp*wRtd4bX2r|Ko z_@wXKu$m}oWn9pf<)xeSf$S1y^-^+^6#%Q+<~a=;z9t8%Hw~HlQT1>RID_veV*eHq zmAStzH#ZZb_mzqSt^K0O!HF(omJ;wX!#P4Wt2Pzd$X^))>N*oDnS_!G=$sXQI&uDi z(6E{(H+2ZaZU@o{u5~%nERv{nZPRo{Y;p=uE+01d`teByfC;moRd6&cxrD1=&-%pPK0ChJp8T+ z2_Jfj^4Ha$!hyz#H^0);{;dbp3IDiJSSf6p%PkKqG+y{OYy*F&JjuPAGM`5gh18xd zT=}CDle%5gn><>~{Dzbi?2MTbQ5sc)lvWFy;Y@5EB#!3)d4~#NyuT9KF?iK5-7xrA z?uO|wKq)4IQcZONdzcjy6B*7VRe~iMSCRVbqYz_yHb~m(<&niybVr{?u zXxx~WG_v)1`DBguxj0%;8`5AhwBAQEt*Sadd^Vias~6ggXBArOktuXf$4WCrl2I|o z+`e|ob4vU5;tpb#Q?3BklsG&slgyy23`W2kC$LGs7#DTg8~z>H>aof@=Z==Gls)j% zErf8NHlhx6kTfG*Z!srJG?W#FfpOEgmT_Ob=pG;MMxPr#-6>4f+-J{{6yo7V}V z8=bRRONRgxLI1lMYFk$|Dw7|wu0)4XWSj3ydSGu43Bgi~_myBtyeybICO#0|0Ia=+ z|5>i3K2dG$It1fhDfWcXJ&TY&R`}9C5rNLj=6eP_p2R^_$NnHY{=C@a%ydpY%$-K5 zWnfx7U2T(QWAQNO6v-cKS&{k)`=gK=wNe}6ReJa{?mMe!Y+xaTUT46!=6X=C%Cz zJ)H7J?uW?83*mi$scD60?gfY*x#%>{IJ%79BG_jh5h4;y*j| z;&rNH16hxF*K^ZkfDH^7cu3~2efltz=c)uzC2Nt^k=wsoIwo=R*9`Jk5R$gK)2{$2 z+yscmJsA!hHm`x2D=q}HD$L$ACQCU3pRz1^qFD7EkHT~ zMLT!t;`fCAv=O6%^Sd{$6T-p%@aJ1i$|kS5VPiHPbouzJRFcQf1-f|p@v3DSvCB^R z3_yZhtH(ah&FyWjoSCb6G7QypVW)OIS#+f*Jdu6AMSB*Uugx#<_kXXYW^>|Gw_Z)g zn#`F6Jip#kEHn94l+pQNCVVrX0cWCL5RXagVN6`JM0~^^!7m7c)zP!e4aZK}5dM99 z_v-_u`4YXlYpJIQE#d$3qdj6GWWFF@qg2** zzVBphMM6T-TLdwDpT&g}_&-my#!pO4Sg%5e33-x|X}T(W1rjy&VG19f6voFF|Rfz9Gf8 z_Wqs{RNeC2(#it5dkqAFq^gQwOO>iU+s+|9DMt$?M35Q&>7e7VBy(uh+;7F7l&$U} zEh{IxJ|31GaZU(Jih=;<>TtE6f)61=8C_dwe4cAot)D4-6d02V#0k1-C_<=h_OJNz zgbP2%1%>p$AA3+i0Z$hrpb)C3O;k`w(bEni2o!knYtjF#t0n)Y>vsJ!$(p^4rU*u? zw{S?jSYCp0?b%L5wV+V41vMif4OidIlW*UW3_ttB_Lhi#a>ziPUK?%8+qcwV)n=66 z^On4-ITh0AvmS^_;-!hqZ=ZgnXA}ShQ^E}X{(_k9ERS42`S{3w%e&DwEFmrXVr5eM z|MY)gZX84UGp*ul`CcdPW>&^5C2l;S4!8S^tNrl<@Oltz(o~7;BKPGMJ^ekL`>!M< z)6%7UQcXv8Y zK5{IQNsGk#xHuuV?&Bn98%Cn=kbydpdSMnjYSSO~9TfBdNoai{`$I(RczZSKO~uUL zCcot{JwP4|5HoG}3LH`0q%3FV0u#C6|B6mzr*1J|kAb!_P_H1~0vBW(0#u>o0zl7e zH27Y2p3mR-$e?T@Hw=^>0aa2p!OutXa~(sU?gNr=#qOwMOCV8Ncoth~ zHiv)8h}-qROB3<6KHlC@H37S|E?S@ud=v42CNm;f?)A>I>cD3 zZIei0kMFB_5+!g!w8e=JpjrktMGe2TuWS}wt?PDZZFKaM;dN}wx*o(QS06fJdKVdv z(XarmQLGBa5jIF^sCIh&ae~~kXH{)~!z7vBA3fANBgC*Y|74m=)0W90>x-jE^29EW zQVwf>k;o?mG_YI20llI;@jmpoicvw(;REqRO2nl>@J&uO41Xdg&*Q)YUhLjy)JSDG zbXQ)j=3xteP`V{@D`-W2wg30jdh54biahH?{eH6*r;p*6LM4Va@7?9?3!tyZ{n4$X zvH-FE+4#vl@d_g`r8BnQ_0t`NL)U!hmBq?)Zgy|hFwf1WnsR$U^!;$?eQh`%)P^hrj zUakpWX)FS1j74-mrlIxNWIJ(T<2a$?7ndY`H=)*l4rJN3uOL`RH^eiF~0xN4|OcAnEUD%S^M2hldC*l%z z32)PqoABG`@IQ!HueSPOau$kz{#3ZgOwp^M$1x{oz6g1oFZNRLZ#0eVJ12-g@s0;n zrEebr+*VfgsD!(G=5pQh&o`e71;!6U6}1Z`*U9YLZ5}=agT!uYPIhn6IwNFz#}lys z%-QhdBE^lvE=bitTA}tEe>CxsW6II&ErygQ_dV?Xn{pq-Suplwm8wwmG%*yrgic}g zVsSmnJQ2!)kuxT>ZCuS z{iAutFhCX$IFWsUeUc{gVm7kT;tHi6=8eJt#qLrs=3h6A@R`GQm(*@@w4I|FY0fWS zKG69%;nnYmbkJXa#OyM02WPP&U(vQEa&n;NWGnHJX&)Pl7?E6lruoH8K?`;GEM}$$ z?VwZ8g8J8NL>eqzCybs)_F`9EgCUQOVD}!dU}59x8QbeA*;d`|Xt}xbj(qE~e0wBW zHv9zy1u?!WEc@&wF?lU-3(Pj)8*Mn~)sm~!`PNTM8`9;>4l}7~>7>S-Xu>8-e!Ob3 z_krXP&n*jpg`3zDzIk|^$SiSzp$V$8wRyxe@=;!FIUxs&b#G0bR26kkw@v4`)TGco z0#QgkGQgQHEYS9wKzj2F5%s$6n!I8}zru;4^Nu+w_D-RBh(3p3gps=Qqz#HxjG zDXH33IOQa`>%pA)+^fTQwcU&LB1q`?d|dk`uHk&VD2atb1br1}2H~nV!u8X!NAa}V zztz(Gcf&{ml;e#mE_sR{`P=EGhC(hXt4<6q9JbxnLi!E%$PY10?H<{hO!HbMPKyJ+ zKSR$p4QHPWhxCL18u{bY zlA>Z0`mhyd#lCM0wA#ncH7b8`pT%N-mh&yQW}9l>F!3l8)>9t=#uX4?hd6xKdfv6pN4}il-1px5s(sz5TiHZGmzS5vDq?y_#-&Gd^Am$${cm@;k+#$cOb4%j zP__SIxuj_#g4d~#7=Fc_Wz0DR9EX{5MiZ4RogBx&>{c%*Vwy2Cu;7>t9X1eFCy@-b zTtq-=CL;|do9D~ziY}s)nmR+;chu#0r`q=k!}2_AcA*G1X#M#NfgmYYOO068xEJe~ z?OF!3vDUuM0K72XV03HMu6!sH>h&(l0?R&CXlH#rr|)gK;jJs9i?IXV84EL_6lmm{ zJ6AENJr$HWlF*{(I+Nul7=e@&bMrm0+Km_8^3c{E#uWY8-=XtfUmrgSUEWx$#XG^% zTjnt)9&g+6*@`re*mQ01lv175C9QnMIW5OZm$Z&bEZyTN=0i#3f+6l{IcqdD$FseK zm8HF=gpbxgTDNVIA2OK=v~2rkZ>qV=%ea^E zN94o@5ClW@F*z6o57y@iP^raC6o81x&4RRHCxH9xHR^E{glhjvN2&kNv34peu*B}3 z9#CEw9d0F6yR?-?B^z`J8o!GheC+!<-A)tyK9Jsop6*RL<1$Y2sD6wXL5UbO*Jo6p z@Wb~(N$UUnPg7PcvMK7?^Kwb^Ow( z`dturu-a+E>C%vQ$ZyexVUTCSoh8bRtL|=-F8VET`ao(m*ej4)DZm{~U!;)nDMPZV zE(I(C`6bubhUE+z_bawm!7aBURX9G6{#jK4dPJ0JU+&S?sJ7SUZKh7REt6%bUAzIJ z!F?cH&m!gALM505Jm&=(Up5af=v5!<)Q0}dwv&OPB2mrgcJ?xhLxprPFfh`kUTnqq z&}D(F{!HWW63<3sn>Xk@@%BLEQs}3V@88u~`nk}4?Q_b@VqgbZhwUm#CR5Qx*CjWi zCpwe^7wxG#)qyd3-j*AinnG4}>aLJ|1R`MP_t-(M-3@bhe1QPV8GrrQ~sy?9LoA7KY%C2V? zEM_+AUdsTxnw=K93ydLXC3O`Kr}TVJE-kZd_ksAJcMzyX>XNs1x`#@vNaDHQijj`J z^j(3@lZz6Zf4q$=xKt7k$E+@RwYB!0x;W7G^4Z6M^vf3-ROPT|pcd z3z`E=Q$AoJc*Qx>rnIA1_mWWRZNMJbs6dZ^~yll>hrT-_PwAJfw>@&lB)4x-9AtK?5_W=a6;D~Tlg-ihh&;U(KEsT z_S{5+lOf{;FT}&itY7=45=U&B9?aNUYGX^PjG3%2O<{6UwO46EPH$T=U^SNMw}&R& zXnUd)3HJsJVtec379HZ-F{7c|hg|A6#5P)x$imbDS@YP^&o&TtEvZ%adRQrz?K+Vb z?|_-^g>!1*mqzZYsh0#1*mbXi85x)y9i(Othc~#`^KtHPIzjsCEF4N=e}Ut6*ka2V zsKWz0hFe(6C;ipEFf%h8Hb^BEBSd$pp45dlwkGnk{?z1?hf?|RgRWuyvMuwr4|f*x zzour=em1z_&p*@wmWV8RD>_l|LtJ{Fjdn2t=vHf!um2DmH^g{bFg@9}+!(Y7ZRq;} zbB$`jM83$!I(Hsw3+f>;5>`~Qz0Ltq7QV%oYf0VaO>L&m;A1`s_7f{~{$CNj?S^AXeq0=qlteLMdRxCXn0K?rlmWq^f8$#e=Cp zj>zSku9|XK?QolCp%NEcwG;o+JWX&`?S}|6VUebPkBe`=8F=aQ_HPwbiG0!KsiF{P?I@AkjXuf|y0(t&17wLg1#*+@ICP6FZx`ex)vG$g$Ip7|Ss|5A%eC9^za-SF$~4V}EQc+RzfPuZmyY3K=xU-^YTG=M z48@h&?KPE}<qE2M-3X0QrMbR|-)+d=t3=6*OXS8!` zY|a%1AbkOM`JxyZ6q^`iCO0{nXohh#!;)yJ2~JK;)iyWpAFH!Olf9#6%~&WP0^wI# zidaGRnG^WN++UG|c8_zM_E&^m8KRjx1m~GRJ3?)ky3I38nEPEpY<;yI5<6V?#qU_4 z#rKKc$!Fyy#fo*=-k@3=L8|s`xq&;9mbiVOk2ayV*>*T`bKIC)tdbJ@u^{T{M!g7* z2WwR{W)*Ka%4$^`cldAK;B_IeO~A_${8)Tiwcu>SpdbPQ-np! z*tH(r?g*#3{>qLX{G563X9hUakV9*s6VtqXhEh@BByV*25ef(h$crtX<^8Bx`QmEOC&S+fUq+9!-ycOJU(6Z^hg=UEDq z{uKWjyUnEydW>12{b9OX?^rrT@SN^5%|X_huWTBC@*%>Q0KlLb2a!m05{ViLxfqSl zFSmz(FONxiY&r9Kkvlx9B`terT)BfkIdVvP*N&hV^d6oGtqxli8|*Tq;K~*O+0o)v zAFCwI!?94>Q}tcjfDg~1HF2%54(Ur{7fDbpJ#vp!bIkGMi@iCF7I3M?9N0@Hq8^0C zT2QVsZuA$?FJsQT3Q8>#WA~3TH#=-dx9WqjQ@_sD5slg3IjGa@!S4_8;Yz?Vh%O$$ z)loB`zB6uBj=TUxr4YohVF%XUS(X^%fEM2ztTuSjL-+BMPh}It0*qQ4K^rnmQG_|H z%Kb)cqV>!AqZ$|?0tL-k6|Bh-{p9v*x~zTKh^niDa!Hc$&MJm-{H4u84mw!yTf1Js zhxSSa|M^4K>5`wF#AED`)imFNEA%Zig=qDAHbuvQVcn^a3UsCA>7eMIn0;UtPrS>v z{nRt`TYjevhAZ1D77M?Ds3R_d0?ccN;{jt{8rx|T(R)2qxbz3H=+ ztJ-3?h!Q-Yj%CF%jRX2_t46)Dg`e_TSNS5M`-LI?)!mx#D(SmS;bUm{j~3ZbNbF)A zhvJ;ezmh0?vO^c(I=Z!1Cj1?-aeozCV!gDsHsMVWMmgD(y5qhz-@T}9O}D~*GBByB zgt}tN53tkOZuhOf@$}Bs_KG85_)j@Ze7?^FLPrx)&PAfDj^~7H2eIGr|zTKh34 zTvTj1ld!zcQTty>Ez`)pWF|5eBAou^7@^zrBWe`XikzE%-| z{i&sxUVC}$OW3rvT)AgyBy%z?aS*INUlIg%i@e-xKaQ-qj+qyj&>IrcSAnZ`&O5UW zRoU5D;=g?T-f#K89wc={rr9$_1_@VEj&!UMM??dbhT|5{e_9ve;CiS^n(07&f8gPL zk&^nZCe{fy#7=?D-#CwWJ8FY`^Zsj=XTkibyK1FcXw19B<`}TUVe`JW zV}>(^Y;UW)0*=yZY`{xuKV|F`>+Dw@wCkU^3k#EIljseDd%n(|^J@>@#zG0uhkQ(P zkw5m&g`I!~p>Vm(#Ni*-zU8s~@Z}Ot+7IV6>uv|7nwYEB`ZS%SEB3zU(+n}f*za;?R%K&$r;h7?q5mA#Qk|Dxb9KEa!p zsKZ=;@ak=q9SQvL4a*faJhyLf!t4^ROqqXGr;mCDC)*aApk^V58BPFUZP%yD?HD(_ zU(&dnJ4+TfDYwM0n2?F&+2el&n$Q^d?a+RX7y$=3KG5&O5e@EpfhA<)ukESLiGqV8($>msFMDeO z_csBLm;?U%+vvOD8`V(vn}Fm%R>XWFOs?*`8~FT(EJ+-D%20?KKCJjSJh z>O=i*uL{M90gjRpt_X5!Qr+mG(ZDMGkGj5LR&yF5b&#W`Oo$;}FuRAv<6`WFq%d!7 z_{yR5T6;-M4Y1!F2o40I$BqlAq-QCbnZv0!)1htTf9AWj+Vf3iRl2z+ zU*uRaTQ8{r{u zKvSCC?^5*5VO>o^A)Q&Sj|l$uyGbPlI^}gyJtOpUm$>HU*Vhf#lfZV4FCWV<_JA06 zK*w6|wcMAu%pGKAYO=`2NRtmEZdkKLhwmz2uG#ni+nsP3wB6WMa(v*Rqn;pgG|RK~hZ&l&V=qH|P&=5&-+e;cBr$ zBGp??nnM+uFjU^di~CE{r}gt^l9#jd7nYR2F2+-&dQS;&kIl213F)3tLMI~HQ&k1` zs}8^PvodO0{jXKCUg#$awwjOQLWfcLQKo=YPjxo8NnWt(t}5i#tn?cYa$MJ^eD~~V z4rsw)=*sr^n18W}sIl6Bdfk|%g@6`wqU6uz7aFZ#m{{s#%pB47N&6!CT~vOGLUaD= z`Q38f4L7=p*fN(wCZbd?t7&{Ido#SbH94KYm;U#`LBvi-Kg$YP7F6+mF7;yIis^XC z1vfyio`v;Xd(*kkcoP+aOaA-G6F+XbN3L%)Pnl4eRLT4q9RL7f{1z?qAl+_84TO?JleL7!iQB9q?}bo}0yK_+@2Cq(lI$u=^JaX?9>W?XNR|gmyC7D>?H@ z?SLOiz*fiX0YpPJ_&R)6>zyH!3I2(`+(FZ-jqwi3Z&GxeKT&J)y4>>YFYaoz;V zrMR5=GK4pd%Z((J8xWBW?>w=1mvugo#%N#OFjq*gzNBClK0jXWZ8AIFs$>-;?(}z_~(JTzD&hH(*1f zRGr~rCg&ZAQeaS*YW)ENFXK4CJel#Eor0dWTL7_yZtG>PRQYurtB9y=+)+$qdGKud zs;H;w?$qTWb8aD&`qaD9+J4H$E%meentO=r8-mT8xvbCD84G^Gd3oA|m#^V6y`hv5 z)##Q|EO7|X@@Q?b*arFkC9(1G#UMe_=1;M46K#<6FzP3Ukff#oIwsj9z?A+y-xugP zNz89P6~Egr5o4l*VB;4vDK{L$xWbSdT3VqUD*bxj9(NsEbv*4xynT6p^j)V~EFchg z{JXn-4fORZI)NZ?3r_Fx7GnZn?Vb9#|7Tzj$mJ2=0>kf~Qt&D$L?2UO;6VHKBt9iy zB7t`Xt>qb@xj8w;0eMdB78owcIQmyK#e?sss{L;nVUS%JuL(nTY_B~wr0>z)-B)ck zAU~I4BF@c(;FNUfB4h~i49$el90VK03&s6lm}XR9R!$MYRQeST3+IK-jzTlS{r?kp zp6nPda>>qrxEbHJy5?JvX`k7flwqJRveX<6pl>0}ToEP?4aNH_si&uJ zZUit<9us8m3S*v+A5|C`yjP%n3v)D8`9x7+5;{hn<%<nb%$@2CcmNc7vVosy2Y>lxEp6bI!bA>#krV9=fICSk zSm>No)BQ(tGXp#4EQD~C#-{P(n1aVs@O0LvDe>5Yhel=#6ga9CTgkuSCywjLcagHB)7-zD8zeq>3?|Skp3T`T}Oh*KJY&^ zPJv_E3S;<9i%q+M^~&7MInIYlg6OcNV?4Q}#Ka%y6}uMgg&CKi;IzXhlN#c!!i96= zRojZlk?m29s=5W{N#_IQN2^ihK#qyR(%YH@zf>NkEI~KhOQ6%L{O>#fZbPy&VFhH@ zdR(Zs40t3^hck#BCeF96zV|%_CMJN&_t{#3J)?S{kCVIQQ`M5jrIE+3Py7&pL7MK{ z9sD$N9qCH2gboYqaK815Gl}*7dx!~#Vz>*w`tKHL*WdXK*0?3IrX_8SAO9* zE^v$%g?+`9UT2Re$Q-m=9PWk6x%3LoycDfbEh4=}j}LXhxzKMK$&c=F235VHB`rdT zBM98{Q7tg^$yG4guuT`bUa>CQW|wo93RBSceOY0q%@q%i!Mg@JR3 zp6>3^58&6K;@A>m%WPO-qq?=VVtMQbTIr6Y<$dg3NpCF&4 z)c4%FzuYDTe1%ZUfbi>U7l4Pe5X$~-1OyT(TJ69ExI13v#o8QwJX2fmK*Adx{r6pg zNq6G~gM~EU+bvreGJcvtpPrTNn@W{tE0K0z#KW_!fzy;ed><{M0koQE=nt!fpG)oT zk=I)3rqh!e3r&NSg4!)l`}556kXz z1OsOrS4v0PEVj|fh+HWBfOBmQZ(>DJ9+K-WSOG{xUoo{3Q{<3^_b1J^&jZU9i?FmG z+^d{(bH?OQ@r(a1sg{(!FV~Be>n|W`o+7(qfEV_Az;yt8SDH~{5QQ0ptB$yccX@zD z@#2$DqlV7d*OWK=ES6$Q28-(D)A(S>X)vx9<&!&}#`iDE5Rn?X6&^j@Q%L1@p@hl= z`}USMQwtzOz&i;k58S|?p&JucCp)@*sFTHs%O@)3jbG+AK0{QNHy|2jt2V)A*bH{o zuI;{_A4;-jChe ziC|)!O~GHkW-yY`y_s_85K~1I6W7zm7TJ%%FQw$I1fc*eY1*f-hetI(_r|*+_^~QJp39ducHHgsU*(&~YeMao+e-ly>AtrUdx4-g7 zmXgwHM&`rLUgf|edS7%wrZ`Fz<#hXSqB=G7$(FoztqlhkGJ%c{62j12DU{87?qp>F zZM7Y&3D=y%MIP9D>n6wm#zA^IkM`G<5YD?U__P{S!Olz!fj=ZY=mgk91J6YwcH3AZ z^NC#541TBsvpgV;1|nww`94jGoU3XcOmzy>4m(B1;2sz@)XV2rQLuGB7uVWz0&a$R zhQVz{cu$l|Rl|k>Y>2gkAbi|Mt6aIWaW1~GVjc_bxQ(Yhp8J)>u5h4qRzxK8gO7zO z$Q*Lvuk4nkQv&lsb`pR)Ll7E_$8=tQSs2jEJ5&UW=3`OUK`l_N5%HFm8cEScwNlWL z_J&l{Qf`>+S(rw{`KMG%>S<2$v9@dDL!~Oi)|42kDv@u(;!^SFl0VBKyOS1Dz-s#S zbrQ7x9wRncX29#6&-4|GWeasoSt&PPx11%+yr0V`GbUw;Uffh)yWPiHN}ttCM;bU8 zPP8_Z(O<$*YMD(qMY8vQ5x@L0Y~Kn$(#U7S)5?>yBC8-V2vk6-WLt9w#er4$%2fM#s=coef~w zyEX~5u6@xKe-t-c$8Q@a*4c3l|a;1 zl^4U_!?}7<-r)Cl;2&vtQ8JSoUT8Sr*nxuM6|A4*^mh3>J^!#1+?}^j+0So3+A~9` zOhp23vrvs8K`Hs?I$XVOdiMuK2{15*Pg|fLrMumzJ2fv86MB1WfIhf6$8Cu15KyO7-H5eRBbw){G>upmxo^Xx?5d-F$ERBifskQ7RRMJ!EDlfPWX61LkXX+-ru zfFC+z&+RzV`tUEtz6ZKfdj?lv>#zaqyH9TXkNr>U*rgn#AeP$~!TfQ6B^}iysVuoz zVz~rzTDWGveN+D#S)zALIo@k-hx$p%(I|9V{wyddrpi>>nJ_*e&`6t;#Jv7ZyO$V6nS6iGy4h63Qt-mosgpKSB zzpGhS5(hRmsb1&?C}EEZVeW^OyR_xAFNqK~i6%z1qc6OlEN=(yu6)W5`B9OxFlDkj_)`lxx?f7+MT-QvDI*oDot5BR$!eGbs>2ECcYA{60rSwjPf?EM`zIX$tCCZD^-KPsKMZ zf@f#VFCRx--iN4W$o<>TaanEm!kqOazZgqL?f}@NajE2rJcQDkWBl;W^ddbNXC+c9 z7!bN&i79s$HN_bE}N2Yg3DeqK1bN6Rdh7tQ*X5>AY zFGy_S;^}H}m3P5H;R3=Duqh4Jm?$YboYQplR^GGC&axhuu}Tnb>F>hX=^LM(+U|Dt zOZ?N{%?1bDmHIX8+)EXIAWT-wrHSx~pkp*gWBKe%cMi7)t^;u~nn)0?`kcFfub}ZffIoD=j*Iegsy^NvW!^WT>)a02XR0IbEMY;;BzgqRCK~kR^m{ z{0?NpHdp=}{UIcnmta+JOo&$;GgE&$jeB58BxziY^tZp`YL3zTtdN52MY~MX*MnUD zkJ`)D=s8jd<-GHb1RU_}MnpVVEtEogRb$KdH|(gRLzL(JHGD$n1sT%H@=)?6%Swk2 z?eakku9P#!=%gv)_Nc2VQBy(d7+gN)L*j2U)N(#k9tM;1sEsaJ{lE#{!|zWorE=WqHXn32r3l`h}Nx4 z*U#e%(RD55ZRJ6G^R2{~{1Z(lI075sr<9H&->8cL1F0A)4s@XmP6OqBf*#lh$gN!{_;4)D^}~Dm@@C>Hj0nu2?9AE zHx^Fs3Y!kr@2Sq5TPzc7ug2Knbh4kC$=I-#8B=5$$e|k2#%uCPf`g9dF_ZH}XI*f9 zusIuC`cNblASk44-5$Tc74p?hg^`wWc77f=>;}#hb!_f3RaQl53;uTnk|EJBA366i zP5zrP*XI_k6v9N6l1W5&${Pga;RV8f3k1NNZtKdYA4Zj2K z<`%FPK~2U)-75No+Q5}5-gG&kW*4V9&`9;wFtZ8KnRc}g9=IrWKu+Y3);Z}1Uz77S znY&dqaHa*^c?5WvGcgVKZ`M$ZHOaq`?-l;^&uhDP{f++TYA3O;DNKAU52ZxJVf*y^ z+WRp~3<=VjW|Co&$Sg2TJ>_Q>loxnIw>geszpg*a6REq8X~KuAO=?N0guAj<*u~2j zg#xb$b8#|QufAv9WdY~x*)Hq1sEFJaxc1{;T-3MKd}pSqI6lCqgHXYS6{yrhV5OY- zUPhaZ6mt-zNqCN(B(60x8%ved9^Bzsiw7(!>rsv+_v_fm6_(A1zFV}SWS5m)(aC~u zINJcU_8J=R+;B^4(W1}(>?NkS4m|=|^$5-KMhd1G@Enr)*FH5EjP24mms-o>0&icsylMuw&(_)rY)tEFS@qjY=$Gq}^e%3lWtXL3-3%hQ7gU^?P}@88 zF5LVBEb|&LnEXnvDSY{g<_?)$(gbo~Aby{gK*fxYH(L}-t;8$AfQ{>|t>s;-JKEJ! zwcO*)hawR8Iq7EePDr-&I%Kcqt!Iq8*AB2r5Af0eD>VVRc8bdrJZrZV8c%WU2QjKm zUm;*@p7MusuC{w%vKn?NxCs(Xa`&vjCsGT_c%?<0t0?vG|I4h8j*?6_25MmM@>IZw z?jp2SoHXk&2^bK_KtI5a^vm}yR~8U4Fg3e1cQH}yOD_Ir{%IfX%~4?*k5K|N0eAg` z_G~Np5l;2Bt_%_DW%+BG^biqWB+q?vsekN1CPr<5U;APJ)_)~n_xIcDuXgYHSh5V4 zzDsx&9EP_78QDCpH~Tv#-+(h?@7ccWirA`PG3egzFD0hmb&i{G)7mVs^qzc^7Dnq8 zqPe9S@e~}ACDfUVKBny}HmS|%*`@yTK0IjI)}6ZW9h8)+Dk+|J6beBzY|0h{Btj;4 zNntHR;*pWbGsLcMf;45R<3bADgj_WFfL{n`(z|Xe9X4e|9#j|ljm2|w&*&)%>D1O_ zQA{8!4h)!35*QdzYCV;*)W0juiv-k*Aj$4RXQm}?IU1(kY>R&K9o>-ECV|n@mSD2a ziwdAD?!*bfQHx_reBIatu^z=S@-j1h&i_th3HB!l4^sO9tk%VlQU$Ve9-d#+ zRFvKT%>zg7#fcdr)h%7QVHHP=jEx*|kerNGA{3OC-x8Fcz237;ZSM4Oh28#ByhHcK zlsUZgy5q*5DBW0AE1x(@y3*Py8ET~p>ExEje~SUnS};8sT{qN)(1vHrwcLJV1Q%6) z>TO(f;J5n&fV`kozCrR&PobC-?H&t7tXDM25e*4=0R?e%6qIiRsV~lo*1r6aif%0e z(A9=Z0|yb==A&x=pnp5r5V^~o0QDv`u3 z44HyRn4*po4u*T#&=iK=9m$+sqj@N~Xm55H-A2FETt;t_1wrpOWs)CVk}06T7z=dV z-krWeGZ_tm_-&DGv^9)D3X zIHLcobv)kZyM`Lf6p=|qPuHHqVqs^X;@*~u-XChLeN8g;(bWacc;2FMdq+Ir8I?}#{KhsPFvW z%lUPmAECkrDX7)3#2cHWjxyzy;z17w|BQV)2g+E~VW}C4dQt1N|@ccJhaorgN|fUQZe8TWbJOB4loWJeJKL0UM^(qLgIMUO~^w zrR{0y4=^M_#-^-D_+fun?@`9&1Ual16hw!k^U+|;jV-@-+Uu%v6wDM|f6XE@_;TC^NAOEVhot&gdtE|3r`8#oEM(;f~*r zKl#O9mbPt3Rfn$>10U1p+Xbvu3$7zA`GPVQ+|;JZZ!iYfF7x$TM?a6Xpc;|WeYWod zqMWR_Doh)NuURUF-!>K&>Xrj>BeBEV>ZAzG^(jFnhIA#0;8kG&V2YEbOu9^L^VVsH z=Nk-^9zX|9$6p*k1yTEGjDT8@0~Mg!Rf+#bPLh_tx?fXkKkl^m8ZY%~sXTQE5I8Q_ z!CBzR*V(|@u(-0|rkics4*Sb1e?{Y2x>HCK-!&4Y^g;4sk=E^QB?+5dtLNnEeQ|Wc zJA%k2QTkeg{!e4?n}ej_=Ex3nhM(VWw&_V5MXvYxCj<7!0~ZHlMO>-K!boCsq*GiH zd7yP{=7S347c3DybcU|0~b7kl3_rbaT=IAX$q#YC5qtFQv<6H~HcwHidIr7F~{ zX5MB&d=@iWl}g@b|8Iz|BW$Ci-OEyHhEPZMkl|S+yB5vfknUgJx5V$()P|!tQe}Fq zH2r|A?T&Fwde@&aDs(R&<`>Wj36Ph#8R!AghkmewZ6RFP#7&XG78@!6%lK)2wo( zm8hymIt9mJ)N|1xrTUIpwv0Rc5I0~aGRR~-fuHq_`<1jK(7A!KFRl{KI1gO-vWW#* zpDEb+WCw0>QmuzKj&B{0)7@g{E%^aZ$4}$;*wuGU^)fuXMsM_6@3rfBVAZ9)K_~9+ z5luFgoaR&5uO{RY_Jn<`*O_%>;nr*q|dT4J@Rkt0V?xLq=BRo!C;8rkY!M69Xl5p1VF>;0#|0=6P0+Esr z#`i37&ocdr5Q5FviUD%8l8sGg%zDta#wz^ z%WXH5&8cRJTJ3i5zRwxFy*#7}nBWY*={0^rR zC?z@ECM!kA3I3?1 za_-IpLk#Qn&U$Qw2ipanJc8FT8%f5frfJfr5%WP_#7xaG+#4b5$so6uv;+!U3OfV_yft0@ud2{@Vld>Qi=D9;D}(RAI14bS^O zp1CFbV#!)HO(L1;u8GW*sz&k;3}1Wj``P`&lhkNB0rmsqYB=9crT^+ zVvm|``0(G;6H(mIJU90(u%Lv7D|{kr*uWO40zh#D)h3;ZRC5Nzo{=VoZNLqE#>wI( zKDO4K$@vG^1lev+13P8I3A{W#CwD1iXA=! z3FZ05pYvkJz6fTG0WSxtZqU+KQHl=Eg!dcGqUU%6n8D#>?@7W9&EV1N#X!z(8NP7R zgmv7mkvs9wSC|k{A8lauBFChuRK5*H;1iCO(9m)l%N1^js^%CWanL5yue*~$&b@2S zyNY*h17SRRDkRuVr6+l5`A<8eDR^S072g>djyZ*D{aXb10%}@hW42d|oItdPxwNMu zbVz&^$~d&OAhC@(2ZO|xqV33dx#$8fOI{-9<~mHV<8KQEq*@K}&VrFXXcR*B#k=0| zaHn;TK-}5IVQC%?>bU;W_D)a-%B5 zn4(qqKtfH!0uT*l!{#Rs_*(H)5NS*iDVGMyek~{3e*E&S2|vX6o|npwM3JXjoH&+I}h7`s-bOK7aomntk%P`tpHI zAv)!-wRVpNqYn_@g#Ys_NjZ$p@1UpM@S+0j<_LdHQe;T$&%3j_8)u$$_hPpFsV_P9$2SK z_FPe$T{Iwl8Bgd`Y2ZXPc4(53+-1IIWY79MFtRwbaZPr z$t)N8$R%m2D?4ya*SapYZM+$(6wDjH#XC&W&V1+tzLtAiTGOHUe%veE{du-&O7A!5 zpP~W=3!MYI*X*tH$fp~rnIdVTQ|jnZ@mlA!y8^lysh;IsPFar)1$&ji#tUnIT77`8 zLh&wryF2Z*lw5q1Qx5!lIFqCf^C$Cmxk?9JJL6mi~TLjffPEeW4dsCS_gs= z5+l?og~Af89THp&|<;Y6$!}w+q#^$ zl-w>j*^p~r8*&JE)B{?wTJG?wV=Q>sHh(;2@@NVR)O~+BCb48{0PclJmpzG|bez<~ zTFj7_W5SM`h#55#65wOju13XppQD6ic;5#Ck^soUjVmfWs!w~nJl#k{Y-fI|zg<@j zZep$WmwUMTHt8jHma8>A$aBa(Bg7)ommZ;*MC1-wQg{UgB@;M~Z079CoVLVVu9=S- zoc1;s7ZNZb=rpEbY9E&6+XE$XpEPqG(;Yes-SGCNKYcuLD+oSsV|+`0u_(-9$x?iE^}#dG$sYYP-cAt(nR;+dnEKP5UAV{h5wNRw;Ko zKDXr${6r1R<`L&G+oMDQH{D1ckYqhk@sH3pkim)JhKxZaYtFb7 z?R=jvs@QV8vaG^V{bwZtyvcXq?{|!^!nxH>ACKKmU~zP6vBu?4>xuhMz&7ADO=`rQ zr5YonI%COy^OeNLpbkGgWI%9|0X&|5)A>I$no?=MS+3aD&kXHf4n(%x6_Tq;r6GWZ zeMg$gg1lq^`(yCXyYB>s)1Fo_FEfH-q6{O>RrkQ5f(_Kxp5&~^>GIX10FvHJJ}-U* zrScFhz_|yR>QOdskad9U&={MDgRlwSW1Cbiyt2m3TL2_bjeX^pmUH!GrUO^J=2YMO zr{Jcbcsq+e5M^a;GHj$!YKHJD7bCAwv!r}Ssjo!Rs8~1i{2b<5B-xPYoyeIctiq@n zBOT{aR%$++_pL6md28&US@fh-1YI8m6KFYZ!*sMMUtuM;e)-0`Gfg~&n@g#qEFpT> z>t@wK&^QsF@S0G>+DUZZ6+C_7AU8}^6X`tiMo!wuaUrTcU;r;QCH{vj|19m{wsy8j zFqpT9%_>@VmW6iVlrLNV!tv4s4ZtsmkVrl(eY!yq1AHQHjENe1f0@kL+l7-^0L~3z z!*r7`liYpz(3PzjmG8DvMlg}g>M8l?5z_`zkF$XKhK-ok%x4nz2mYRb(Zzu-0vp~t z@r0S2Vpug$YM!9i7X7bQ`m|4Fi?2iM_9ZWu58t6+=b_mLI(N`lI#4~=4t+V6>?F$a zse4qDffAd}+ghf#ZBi3>lWG*j!e|C9F1 z9#8k7UPra8a`aB+$a+)beoYwaSnP;i_!;-RIrTBY2MW`Hw13oOT)M4eSs~mFT?wD5 z76Bz8;@_NWI*M{3!$P{GR1D-g0CngL^X?qrE2dX=;nfa|W*)q6We z$t<)BVXFxC)iI}YnI(_zubw;1*R33Kzn|f~&~8Iaas0$Tyvw7QDsD-2X63I+ngggL zf#?POwltl$LtMe`i9MuEaforWR^Z~fL8qsOIQBSNmcrzPcf?9S;%92+HZ%v z-kn@?lccX!ukHtPL=byLmq-5n{NX^21&;hUI11N#p8-kQ2%e1)gM9I7+m%GQbfO-q_?!gp*losG6W{>`7a;wJlIhnu0+eO zR`6ev?+S7D5lI}WnF6*6H+q2K+I;Kp-YHK`y$EFf5VniU4m}1TL3Q#XV??2Y1V)=4J0Z&1D8o$GT;CTxLdJm{Y1KF{VJV8ElrAed-FuoSQk3=|I9v<)fB#O<9@65;BFwi8 zrz&oRU<&sr`(M3VZFNC1d_K~uCsCrAuKK)Um)i7PVrR-^+-Y0i(h5L^=Utvahnnqb zL_Dl}p!zX2(aOV zu8}O!vzc69=jgB2Me7`JrtfO5fJJVbKs}RSp zvikts*jv!EQ_05$Ap9`Byh5|WuV^IfFU*dTiiKRG?%>P}w!6DKu+8UlTsusi3thec zYFe{pO1~V#g)?_Z3mn(+<$#|bblDO>PCrc;D7-~25K=N8sL7)BAAVnb=sDB9b=6P$ zf(26+wkt>^P)FgQN(KQE4z~V3nFouxQ41ch&2nkZr<0NS8`~vIu=mB7i9OX(BE>wI zZ9Y=~TqZkdCDZ7Vrb=N$>LnNt?cXF*k)7O%P(QZQgq8gejT@BY9nS%)P8)#NgN6Qc zB&H^1X1Bu^;D4a z!7w*V8YV41>tT}edyHzQIsT~A!;T9=)6758lsC1m91i?zgL5iz(oX)z*5u3S9mp%` zPfh5$!vWK-Vi1Z^OXG9%&3kIUDgO<{S!Fv(>`M_KD;!uSA@WcpQur;t-fw3&TcG;X zx&~nv;Q3zh^ejc3;Aaz_8&`UV{QOA;^(L3J(-Gtk7O(8>NKVgBT@(l0l$iKizu#Yo z0e?X9PqsYTKauOQGX(I~`m8QJko(=m%nde!a~;H3`PjH^ z6miH|s^~IPAs^`@fHAulxWB49p&wGZo@M94el4SI2^xzt z(4<5|&b$8!1DVekIp@Aez+dQAg|>AxvVQRL6i=^z9lSi~>0EdvYbp|kR-|&UTA8PZ z1OE&XN|en>!%xn_^F(^D_16ycgm+UUmpW$j0s#;-oo8NWO4`8fZC6y0ii#cN)Z+2~ zX!^>4sM@aULFw+09uS63X~_XZ8tHCOLOP^-Xp!y~lx`4^?gr_S7`mjJ?{Gig`xAc6 zIp?}|tiASHs5BvS82A!5v=-UitP)K)L#i2^o&*ViHGt#UmZAa!fqIFCh~K04&Ahj$ z)$e2S&^0CimS&Z=8-)_E@$Ve`ylx zw~=q(Un{vt|2bZlo*RkFaYTvkuo102Qm0~~AI@(zEJ6hdHyo>-M)#2;B)N0Qw?B2dU^TUrhc4KOPjcToa z&iCO-UBn?bc}6w@XpA`*Dc(eA$$I&JgsmN+aPXwCN(pVJX(ze)b~Qo8Q!u}=ovHvU z(X1OHmc#$%PkCJcBzmTlRz<>!enu975Ct&Fr!vOTwHu=+i(I0`4WaPX1r%xjYqWWZV6;fq?jAc60Sayw@qqyx zX&5~G#fV6}KJxSTeS{l5BDo(e&6Ap>!bdEz!w9V;ejjK1iS4i1QrGH2SAqxF`rMdo zvhM}Ev4X`$z^bHt6N79Om|G#zeaS3lD}DUf=jJv;_(u z?1K?6$m&Rq=AyH6xF%~?d8?yXfe8~5U{3Lf4mtr80{c>MV~F*+K}$TjxZcEkFXq{&+>HWp&pB5bt>W#rS$;4uk%j zv-7lI`Zo>{7$S>@J@Px1MdD^_Bwb$O=H_f0un-tB^|6ogJY_8N4RoS{eo(rlU#s_e zyuX>8AJ82)f!AZ)MVV*u$)Q=Nk<6%?KVE$1oX8eUbr{|E82#NhdJ>u@weHhb_b_z)vN`fcyb}-=^S;`0 zNAM@v+}KQhK@pgYbbHEh!h`>(aI?8ZlKg@*ix(W8o4+xpBKRxj2+s3!S6w@XOGq$u-#owVr z$QTy&sqPmmXd1wQ-Q4O=J=<3M_AAOxJ7%g0o|1?F?v9>g0M)IeGay{N9^QgpVv`Eo&YPE|AqT^@TE46oFtYO5m5e8!gQW(}np$fioO3^t=F z^p%N2DY`>#KLm)9bFtkCIU>rum?i_LodP`uavCWkebJNwaheIRc#$4s>sIgZpGwbI z%;{6jmA!HdMOf1|N)EbsZh-x{4{z7e8gCeWSe`&qcL_93DCrP()(Hzg8LT$H!LO(G zF}!>b*}*vpqP}~zQNma#C zJSpA8)s<*}e}CuV3y@;da1)ksi2^1*x{t^7Uzq9QJ>c&4b!@4Nm3hVV5NRmxGDcUy!nSi^B_qbZW;K+RP?9Noe%xOd0@3I|G?njAm`EgT31+1;OXTh zUwwUj%HH?a?19w>D9JjvAMHpR(HtCwlE6L8f$!o*(2|ynb)mA>us{Z{x#QJVuPcYG z;naSrm(nNwQLGO5@fK~~W_V|w6&u}k_s^lHTvaXtq53$4a3ZK1P$*`(9vI0kZjAie zc+0SXjK5({m+VKuLu{1&HkljOzu1-!*>p;~oEyn*VJ;FeXE&aS3aMz|91&}?um{Oy zn4va==aD79y;S3Xj`PL(Txq^$Mc8CL(fUHY^p-U73dw^^b3o*7WK?F3)e0>1tLW!p z6dpk%Reg=F^i>MvKyK+6ZkBMAiR&bNJ-x2`d*f0HO3GYKv$1A?IrN)~cpVIx;>5sF zl0Ze~*7pQ9smQkiYhZ*D0w?CwFMC|n0KIX3e%V7!OT3F9H*ihof-KpncZI7Ge7Sp` z#&-gbKXCB!0RSedT3e&F3_V|8mRrm#E$PVCBZymiX4$YiG9IVjU59x+wbz!JM*Q=N zeAOfOqc=i+5%pFZk z1kkp={h**!=rs=Zpw(uU;lP$8rZ?>T>v9|!3Uz#!nKAY`=5#u~O*Kj)raC!iSZbZ- zm6i_}LJ$W0rNFSiIG55g^Gk7V_E1n5et-!4Kx24$s^a@X{L`CzZA2NBBSGDz+l{)I z@9cr4;X{FhSRc_kxhTF1Uv~td2)G~V8y_-Vixs(5qAy6awyfU_-@?h?C~TD+rV%ws@gCiEq9Wh`mL2$7_StT2)|D`w@mm8@r3lJ)#$f8%n+ zm;MruZ%4#9my49RI+gd_kbHjn4b#P<1jR2wIuVm9-HPBx0+bqEG8toN^rw=DktW5p zi*Fv`5WuaRqk=9|G2cx+eou`!E8jL_6Ec*NQjr7#8*fq*C0t!z7E=yRf0}j^9P1k8 z6-@99m$IjcgwW`k7ygKphB>@yi@2ukQY4q5et6ViCfamrQi+vKFk%KB5fI%Hxe)#9 z-4)&kdO7hQ>YXeVErFkX&(hB(`OmS6K^kIK=)VLP{Wj0G?lpNb_1f|&n6Taj2eNNH% zl(`*FBXEiHD}*6O$Bo&x$2Y#f9O(tH9dVjng;!*dkyaM^&u4&Uv*Qr<>$HH z_V;ws0FI2Iag_%ggd}`gI+5&(Jj&Mn^@rYkDO6~$6pS#)3Sps&08_hz3B)o z%eiw6+47fn`+sDdcFF56%11^KkRYG9u@^=9#UW(K7zd}8hzJR0^G1LWpW2NDxU!k* z4gW~Ih74J{y1EYMvf?kK8uiL;goo|Q`>4p!xZLp4f8E7at*(6{qyhFb}9T*-2xCSG4d!~ z^MQ3PhL8KFHA;9!zy}2x50@#>O-?;lfrWlaLPOt_@T9nBqI~<_{C`}4MMr00Wc$U5 zEa0HE)iC?|o^+sGC;Q!yfL_j?VsNzJI>iRked1WKBGc(hGG}CQuQs(bCQ8vsR7pOq zXNUVwVipg*_ok&8`(eAw8y=OzfL6=0PT`)$KC>(jb!wdrsCSUDUbg>=8dU{})A1T| zQOnw7CP%^vc>A|O8_?V$nIZ|9)#GBx1u!mruPPc^S)F}n;e=)T1$-kIwR$Q48Vd^x zgb@8tV71=z^e5MKs~lj1*|l2KSYO4`2V&v#R|N-x&IoX0PPz${Q7dLE8Zl3v=vNeB zR(L;_7OXP;l|tjSYOe(q``uVr0{i60iRZCLxcRv$6_1^h6Xxsj- zwqflpTw)n59H^#bUb$Y|kh68T3igY275h3}1#Gxs#r8E#O-oDE^0L96-IrFw0?I+a z{wN&rp~*>@Pa>HSCye!Cs{W(9{=vdoO_T^`Z2d;9vYU_j+xh~C8qu6;*9mlT1~XcVJFAycQ( zllL37wtLoqJ+bPG8dT#`qkVZ7~>cLE%4dd z*|5ME;M&)G8eirb~jaAU@E0-3vY2E^}bOnt6y9&bx)Vvy2MT-rE{ z@-Q7)h6oe$F{7`$=t$4X&4}VX7p=na@R95uSo?aFGiygb86NC?0Z9HQD_+NIJtRim z+4lq4#=!47{(V2f}4(S;zJbR{! zDXBvQte1*v*Lk8L^im!%EP$QR^=WcjlxdX!18Z1f0Lwx+MFZ<96pYs_DjQN9K4XuY zd^$5jeET2@ypy-N7qSE4Lm%3}LjT$O^+b|5?$5B@Up@JLOTTXmU1SXDjBji%Rwn(G zU_~*)xn-P|u$QcyTc!R=z}7jG3oyiiV%L^fY>v)t4n!wVqYv7@gYiNrlj8JrrDpnR z`B7sM4bGE9fZx=NvaWvm3>N+_U+y|<@Alk>Gp12+*X(k=ak=>6X@d7Bwt?K0o$ zQiuQ4hPy)`Vf}l1%#*vk%!%k!V!j7DSr@dqx@GHtBqM>TYsDftdZea=4jwBjpf|0r z5b~~LE|yg3*47;ph)Z`e0bmYAhlQrd|`MG3q_BImbX zLhUZ22-!jBux^`$3MF{vvqOb)H@2=bk>gIE0U97L#gZ6$Ac$Re;8eD@zGYx%L53=- zWQSJCc0D(R&-W9cU0)9 z)J#D|>1d{e+QiXL`qA8z4_=eX8zmSfw+9w#%Cdeh8-zxa45qJM{j@BpG$vQlrf-^Y zK8fNO-Z~yH1fnS+*M47NQohFJNr$2o=u|;6jJZHBH7~D{w4803FUZ4x;Hye-h$#O< zT~ag~rtLubi(g<#_zFPn5=*KUbOTIy?Tfx z5dJKuy!x=bx^@a5x&|!N-0z5A4)7%kKJIB*YNd+XC1rdvSmmV9q?$S2284wS!s2pLO9>2OruxU3uT~w zTL>TJnV=W<5hXuFX8+EyuDMTa@$!I`l`Y4~DC>hDY~TjkV_1OCC?_i9kNs6KQ)ZI4 zTodI~R;n`Y1bESA2)o;NmQj3<7hxsg9=ik^ zbmc9o#Xt7E{MK;aiNWz#`RQEQ@$S-&cGSW(W;gsS*iYmlHtA{9{dW*B$jArC$N;P4 z8gTI7Y6_6z&6nf~NIM_Xxg68D=(}i~;>;!C zS8`5#Z2{-Th#r{YtG+?{Q<_)3dTYRGLuBl#VPEc)!kN)*SrTF^gq6>U!y`#>Ign?n zSvju%HLXN}VLS560TO6uV0hrk_+(xvHRZE{_K~K+z5_w#0mGIV(W?heX2_H|WGHVI z-t16?{;8Cp`5&qqSXx867TE6S+S=MmDYiwiGl!*Z6Psyfez}Ccx7yFKdxukndn8 z?-HZ;qyDG%9}_GR?Aa zZK9o=vV!yvj_NAE-H)@*FZ<1X($muc=`;9GI#gAUg?}3}aOv9kx!sm(bIB>#Z%sgV z_XO||5h~Y$lE)Fe7z8U=od9bEfI(PTP|(X=y8+x@^T^2R#Z6l4Tz!*RYl+s`{k2T@ zl@8(KmY`=hRk8auoadv{ayBZgzF2cP9sSX1gIUS*ux|F`{%q_esNAS6#^~`hc~5%; zA3>3qKmOW9mE-qXT%kzNwj}vOA187Uyg5i!fOkZ~91-KcT($P+2LEu z{_;XnH8#~4gLaMtXaAt!3_)j02;}(a=$AbQcV4b;ri&|!)$uv43cNf^r-oGec64rXNaRMiuz$kHfFuLGhK(E z|M2!~!KNZwFdp!@GUA^8p)yQ?u=)wzl?f%fK>Hh)s?LxKIFXhuc^Gi&$~c-BusPp2*{&5tTGspq(G|?Q_>h6qc?< z{h)Bk5`5M^X|=BJ3s2NK$)|omZLnYNth1RdxM0IHk8G?Nel8mITRZ?K#js~x`;{;I zWplA4A#b&qwr|Mr>l%ZK;nXOwB6&}liBgQHQd$Fb25dcM4`epk;K1zDJ1=+6C-akd zw6wZ_l%E1UDcNBMDgTJY2DJSJJZ6vF{$n0@bd)|%r9)4+RmiU-%!gwfefq-iR+{nYxtkz6=Z$w1(uH;Vpad!f#z z(e3b+q0fZ|D;wMVujJMR_0BbcaHuJ>;WzJnz13GT`Ul6yfUw6u>ggs;2v~_#e~?!3 zwrC#BwM*`9fiK2FLXvKu-Z?WAt+f$vL?5n;G~$Lce;zEuk@;Vmg?H1aY;0X(LnJ#( zHT~-}{0K;TG4TUvnY9G%t4KIOWo3&IgVWe|1>Ws|G{Xz13No_TD$Z1hcA2K* zq4e<=awI6!0p>RG%?-LmdnUPPiHmL1@CYfY=!`6mAOY7Tb~#|7=rG34?bl}F`&gpH zv7Z2zk-0$do7OTy0^MKtiPcB|VUPlI-ha@*TO@pjT798#z zCGnZla<)G0iIlA-TBBI1_FIrmZsnI#JDN#{QPG3u-XgBmzihgk?u8!k1GkrMcRBu6 zjB(R|xg9y4fHxomfL*{|kuM>0sj>MoY#nniA~eXSo1}Jct>{yRBwn6 z^=FrhpEsUO<{Exquz}jMpKh`@0HcU5SEb?8?bk}PHvqJYG$!^W64A4+@=mkdT$(lY z4N0BU&H4<|(#`6ls9NYCWG!u$6EBEX#e=SCaNaiUr+2fi%+avU-mT6Z53-H96u$M$ zASO91M8O;KT1zmLm59V4TT?wo(6S5qJLQTf01t@o{ivm5Ap8-;bNg5Cu!vpnC=(W6 zA2AbLAbvsVz%UDuG*M8o=Y3TU54s%?9njDWjx0VKS$~DyDMyh&YFIKI3Y-Vi>m4cK zl6Y;I%PN@Mea2EygopF-%3G0t-2|Obc(Jq=tTeXo4eMksYZn^Zg6c5%@}~zb7jD=o zAf#2o6_BcMbOliVxhsEbQ^KnmAJXgpot_SHY}{;TQ$OD2$BN?f32xLty`l7J^t7IkeyH)%r{zwb9;~GSdtAeJEFI&g!iN+Ew?!EpQTW z&XS+jIUYMFIz;xt_JkgQU2qsfRAM5Li0?h=bAt|)O!+Ylfw9Gc?nFiG79n(IdE9t$ zBi{ub7;6N)5WcLP6o^E2)%(<<*zGe7B6qHxOo$S1M}VkM7Rq%h0C)t~I$gEzIrUYM zeGn;k^;d*a=T6xFHN6D`>F=M0cmNC)v&IDdXc`U7xIKkZMH1fCA*b+~_qj)1{#o&< zE25Pq&7+I<2@Edy~Wy?zDk$LcR%w&*zDJ!icG zX*g4XKC{^cYqOr`pTYyi*!j3TxY`y{S@0D~i2j`jfVyDnqkV1of=(Rqy1F(D$Dy+4xqF09~?omX!6)S_6e6!=JAMFFT#kXX`TGK z(yotz_&_yt1C)CRpvO~=C;SIrKL|GpSv;3b%k_FB$bUQA&-c0naE`0k07^y5q^d0E zd2rM1(Fe$8&2?|0vB4k$Y_octIWeB~FRo#VVtQA-S=tU^lnVIm`{!1nkdRmkf0=U4 z<=0{&e+iMXo$EctyQ8ORev~JlDa)DV|DQOne}_ViE4P^Cvon;{fVOJYlpBF*7T( zloII6V3A4ITjyPKwgF|Ld@?&4Nuu;|iEV%~*Fz=L4;HicSGpkQaYpa+bJl#eM$huS z{Roud$N*k@UD9@2lG}a{fLnioG5@d+zK-Z<3jn4+hgwZd&EC8a(c2xmma7#n+AAeI zcbGk{{1;TseoW8Fwu8yZMtL3SXaT2Jet3D~DI*yIwl;KuDbWsd<+HgY#0Qy!qGssO z@gEu!qBWtIxQ%9WKt`R`_&j?Ba3t!$@g?4KqTO3d3@XWs*x~ItufGo5AWn{5#ubOR zax*e_812r^%=98!w0VU4YR1J$)2qi{DB`FB!re}~Tp10S6Ba;9n46nxpPa-8+Na`m z;g-GE!9dWM+MbisjtM%`?vS0cx0ncw$LvVyLmJ-0-g13~0{@of3e<@JUuPuO15oSy zce`Kl5|rh2Bgfz;5(A%C}97Fz)U_ z6eujPK^}lrN5Jux_F(UJ1vyylJ2D0VNqj~0mGPt|$Fr|coMnYi*rE;5D-jyjbrj=94 zlw)E2r@|kC$q-)_8ygz{VJ8UWE~!!Zt~bl<3v@~uVt!O!UQ}^X2;c>ug9dxN^&jsT zt0Iu97)#Oa%-7w@%kr>nk{SsdVdE(pFuf*y_792+MKK$;8(Io6%^S%UI;8)=B3xiV z#)YGI&1uLGA9p&nR0i7i<8=d-s1^%T&IA&b#xKaE#LSXYUPikiYZxsEMa1 z87LHd`uHdcFcQN6Up|mH?`=s6f_Wchw?ax3eoq;O$H{12WiuYRBuOHQ{R%;t9h*3U zN?=XX2VeioErztdHS-U#ir%D~RZ$T69;BrrqQut`JHT78;#1g+^!$m6InNG!#nT<2 ze|mRMjrP~|_7n`&2SWf4L0W8h4kUSKZebxJp_l?Gj}MKi;_E????hkwN9qiydy>y< zJW|#N;;PXBA3Hn0TK48!^WX1OyD|84H~#(wT^+CX5h#n$o+CwII!f0Pq&CEs=H>L? zo3Geq+;-?CoBkqwI}2ca?EqtIeE;I4Ci?*sbh3QxO9HB_t`2N_SZqV$ye{n8xu@dR zACZvswE$=sf~BRUpmy!3p2x?>@sN9f%#wC1&HX#4i|Rz+oHaWOJczy;{A zLXfr{d%l!v57qSY_3y+wJ@!)L2UNARh!8F=bz8I>&bjLKF$>kmn4ZXd)?Rd$Oo*TV z@sP8hp#eDXKEqFoN=iSz2K8%WOa$`9E>4%|t5m(>rff5zBAK568{)d3TBjS`3~D{o z3)b2Ii`I%Y0OONwTcvj9Blvy2jsfT;d!G(423(|zBW?h87&TTXZH9(AI%HI{Jv}{Z zb)VHm9)VGO-<~RmE+KjdLD#^|y7&G7I2#qWe;#TfXFqCLW075AD^+A7$zeaY%`6+N zRv1&)LiK*J9FG)?C(x9|R_aK@XFj$24r+Wb<6b4$z%>0s;RIN;Wru5ih)Fkme-Oe{ zKA7X25T1iclVrcDGpu15UV}?%K+AonUE7?(8oLkm?=BOu!y~PMWs=hH;4|7+Dk(92 zp$;0ABGw?O$SFxtf<_K-?-9OX_q%FdU7J!Ct1G)owaOxkXb7(GIkYh&8-;pPg_sL2 zPJf*JTpcA4Sq2B3d=QN1lz>-J{|^WxmLA?fP|epiY#>4h*{-h;$|?t=IWo!4%TY=% zNn2=|#PX=+nWRD3H#gQQFLKP%#F<~_@Xt{*7FE;7CBg<}9?kQ_by7$1!Zw*@Lo%}B zS7e&hd-rsm3-?}NgOXUE5O(0tUrMm;XUdyZwhy19t?Uyp zw|PdkV#*rOCu(u6sxI!o!QBoQAG`=t9f?#UM^zwTY3eu&%*12OYt$(N zm6VJ&4I;F1A|S_K*wynFZZm5Qqia^}rIxS)5*5v_nkB`WB^`Y1 zDR4MEx0scDBClD)7=s5V6{Stdl+nGaZp@@HGU&TzNwl;vWDb`oR|1#Ji^~RQ#qh4V zrX~n@KwXMTnnZ?KJ!t%uQ_M<+ZPuX%bNz#{pO+zecL|Y;aXhL^fpJ;n$1$HUi*v9&%JjY_$)ONq#%Ra~v3J6?+ta_Ir?O4I0LvxU0FGGI)HG1Lyd&UpYbJdzK*&|U zJlK3#(LdIrbag>iCeU?i0c7K;&QV||3c|Zg{SBe7sdV`@X6_`a!w&bA=>#$!n!sh?CWM+2=}D4K<^Q+< zOO^D%=K|VA$AIY{uk(D#aCY*jb3E}LIFGanPMq}tZmrdm&QfQ@E)Dbg8ytJ^ zwn3s0agE#L<=SgSCLOH8zS&=Sz0BeSRQDL0CU^q|QO(bF{rG7}u9<)p;&CZ<&uhw# z2K|vs8ZA%KfHhUat@Pagan>-gPU1(ubA28ja%aMbX~o@B6P1BfkpL|%pjCoiZi1%$ zIir<66cCI=ACa#BoH(-uqZzjmuVlqWM072!*>xCc*%`4Y{Xk zdHDl&i=@Y~{?`mlZ+B89JXk1`0uaBR!5XY*_s20XhA*5Gw>_GHQaqOod3a%|-l zXh25V7!yK?Hn>MD{@<`3(n|TQ1QYSE8ZlCMt94`vw<`7#5hq>(Lbstxy_uC23docw zAeZ#-cEI$Q)SDk45CPo~!=qNfBuS|;F|(UVM=acGzE@7%oM<|sl0UstX@OCS*HXGy zyO3yWc>(Vs)t!L4wcL!=XQS2dl=Y0InE5;Tj5GTb83l59aCH$gp{mKhX0377#QUa% ze9NDhrb;}wJ!|5olsyvcuS`%mlf*xeg#l@7?;?+1Q|;X$FVGtBf_3^Ta)z z6OnwcsOxc5-;s1{?1=YJ9GvaVYk>YaGGWBFT1S+OVNgk=Ugc&c6+b8_*LQu@6v6tS zLUdEvb?Q%b5mw4+oaxQ|?mj}w7g699m$HjbDRh~PLi&K=kib=x@V=io1qvG|J^WX{ zvE7`?T4ccRDWk^wN_Lm@qP$`lPA_TP!dq#Sk(f1+{uPw||vBe6BG;8ccH;c-axO2?2Df z)WHcGY-xvwhpGMWTJT0kdXcYKCqHm>qAmkcNW|8~B3VX%h;YK%fjp+IU;6}yO*xvl z5(!PiXZS-pv2-U^k75Buk`R)YCN0)Ehw(61`#Y(PZ*HIZ%8ny;gL?i^23xbeTCu@n zQ{~mFyp+wwRr-S&Kr84tu<5;ZT&|j^HOJ}1zDdDN9aQHD4sGh;t7Y*T-y(I2kRn~8 ztU5~f zH^`2_vcyh5_KOO$*YYaSB?PK#QJIZ3Ksr6!9&-+V=bOjxF(Y^p5RxO^Q7J9oLr<^l zO>BgHx_+72c?*`)Oo&OhX3JYu+K2kEXWkOLkHl6RIHdPEEPTY0sX z!W^^dpe#r)FUUqWrdJ@ZL$I%=q>dk;ILa?3#_>j0FoHjJ`cop4*8CB|Xj$p3Xk^R} zT+ev+jetbW>zKhuWLHe>5JF*~6$MiQ*MyOEB30%D`*e&0FfssWm`iie#JoiyQ039d zS>F=&92+AEON7rNS2%$66k{?}g5=mb_;>p#tD}@vZfM`)kNzm}#r#j{`tW$B&&-R^( zbKG+Lyq+)8Yp@4U5EDm7)j`h>{auQ@@mNFdAyZecN4Vow#cD6^ZbY&7NaT30e~1;E z{he`leNY)jq5dunC3oj65M`)hfc$9vnFUUP?hmR z--7(TEIy-xIVn!_!&~!hClBA%^fZb@Q_iD32BB^ z&$`N?dDjGGdm*;3%3pJu9Ab>sy|?sCvLXQhVXpM^&)`eR@dCfx#8}+8Bfh#C5>&gb zcZ@=Cl<}w!dW_L`y2yXo16Uve16aT>Y4XD%rO9k(TeIpXxicU&ZQ|@T%5$1!YXf9$d)k}Bw zp({=t)(hEPEk*PY$y^7^pQap88toIMN#gTmJY?GOQY~ahB=-2I=iVBQ8H$al+-EDP zC-72yy}*-@H&!pV?(iMzXVZ6xp|{o{1Pzn6V37e}Vmb9YKrj;&hdIERdAOOuvELLJ;@&ZQomA^5(O=gSs7%j^g&L!dXk5xIF>KTE z|JdIT+Sn)Z!mG>f4?h|MOgPa)I!}tGB$m3Br@8_oz$Z_j!@5zs7VSj$pw5!Y^Ac zXDjs~Xo|V483QwfzApZ06Ziu6j769~LA+cgcnEqB(kVuq$yv=!<9K-+VTYO;^HFjr zTj`U9@W-q`?5u`2#P7$IB}l~P$sC!)L_7ql zMn5BlIwV&E&^l8^MFoyCFnY@n`CSuAUF4SF%f5Fh&JmbHm6Pv;sl6AA@8#t+HwW9n z*n<&-o=_lpbld9q`OX2z`@`K8Am8F`W-B=2iM1HQn#Rf4@gZYnwBC~}81 zE++2M#j*-o?}CaGk@?USO$3j0=^o*A#J3`n2WC02{SYv zHn8llx=|`a9}$S&NlD@5pqXuW9wsbB)QNMvsKH+f4nG{_;$;i5+UGDZS|xaQLQIP$UhaQpa%|QOw(Y5u`ynWbo5vy z53lE};Ng(<;wH~gUFM=wk@I?@*Wl!5JX3uNL{Vu@0EYp#f(bw;e?BM!OBnu9Tzf@I z4g1MaV-1uN0=WPwXZrUq`(gId4euF~x9ocY%!J;UW*okcpCvIPa+8v8B>jt8=0@P_ zZ<-96bwfoN`6Ovj8+#10gSw_)Q%*F<=M4elY%>$XU&X8Yu9UMHLK>{Q@|_EVBxfMw zeKm#?8ROw!@}9un&a%Chb`1A^v>V|Nu$bbm5NuXvBtu+D-4P#JiKG!C@;^_Hs_JTd zUFsG@sx-SG!oS+6bU=e`lu;#o3D{hEtcNp7K43zwabN2;N84y}rNX`R67tp0eI!(_ z*hMO9$-22zAcU9y08VN@H%t#Fo5DuuqhMuzbJQbvf9l> zflL78pAe`qXVF4tS=O*1tr z$6ea@M}b5wNCEDZ+!G=>I!T)slI)^;iy4Py0Eposvi3tNr^}@-G9Y7!la{W+FmNao zyzcM*-!e`SJl?_8sAfi4FRME|s;R(AK)9DrONaCO$GoYJiz~L?D^0P2icv!=LxuWW zDBD?#FQiiB$xICfJDa|o@^{|e3Z34xl;sS6i67Gy#g6~dC~b^LTP!qPq;dlL4g7kL zKOAnccxrF<)vbl#9#w4$vK~Hqta0+p3k9_U1W~CYIf3ygqZw4xG#jXPUfrUQp~PaW zLqFIanXURo$1qAROsqN^=O9aqkV~Sz|0iknb#{41ub~1RMP7w1_^o<)%`97e?sFi_ z7w%B%xwXE!HSy4am3`Icr>1~Y+U9E#a@njj+^K3cbry~Wrv?ms-`$wT! zW4S?!jY<^26~o2xB=BcMXrU~rHa#z-utUIUNDWzuj#JwyF+Z)40(#H`@LT;Q4tjVy zH|T4to0~B}?}O9T0*SlO3`Yfu!al6H<^%MOd=*ScSX z@qu&(<3s+RFLV{*1hl+XbA9@?`>s17f01-`g{J@MTeNp^4S$glKsJbZt;hd~=L5R` zCNm0N00O2dr*7F+_bH__O1kqSVv`Hs;jS802y8qHI$y||DzFJTgLUR@@B$J>fWEA@ zzJGtZ>qHDmQW)NXMP8=3n_Z|Yre)%%x(HL%zet?)>ooX7#Gw2=Ok#wQs{DtVb)q2J zQ*Wkqgjj1uJ&t4d4AzN-_X%y=58hYta9#ki5$r|p8K(Vk7Owl~DE=JFh-oD}Wk@l@ zAQn#A$dG{-qeAyCZ3b*o*#z;5@<@GQ)~s4&Yl5L4*P)gOHENEAOlyG)pPKuOPb3+3 z@^ei!Q^1^-(}f3#`3jMkc>J~pmsS8?gn=>P^MeH0(SwFqa0U9rI#XttcDQsIDMLEH zyxarO8hdZso$ftmJq2rtYC^25GV7MFR{fr-D&&zJ#&+pie=a{Tvb1oJc$7;hEqWMO z0W8|mS&bE&a`5j)pJPupj1740>K)1q*RV5Ip2e$dBto9x1Ns-lkRcp14)b)1{DMrG zVAS7c?a&I5%vRO08`quH$#qGH#Nr0L|(pobj4&05t-bA~vZsNYfAzT&DFAV9fJ#n)!J!m~@Bd zQ`#8)h67K&;2lZr-@Y@lcvVIm);^qqs%#*j0n;Uq+ufq3g@h`cQdo?@zhAyRCZ&+;oYvK^v?^yb zx+;toACqrBhM~;24XQy3@T&wn)RTXa015+h(j;?CwYWNm$qs9j#B>6PN#;c9($i;7Om9Rw}C2LOu>_2e@y4; z`tH#}eTv3}pg~p3*7;~j&*t$za<`^_rM4lQ1m9S zx0pm>)V>@j`8`dBzhWkAw_Pb67fG5$ z1v+Y!TW0ODELw`aa6?E`8^<&iP_$Ml?wJB}8(k4_d|lZN?4hxsH%r$Tm(YT1i z;lTk-_Sgq8%t`hS@f#;nEZ}Rrr=kZFZ!0U=rbMP3yznmKY76n^Rf&gzrM72_()(Gp2^-!_5=->XUEXja&QPr$+PO65`VJDn8^^qxO7ovC|nf-snl3vBG+Ve;v8 zR$$@x%d-!!nZx8*p%$H-7<1eyuW&@&vrCoh?J_pHEcuogX%ghL36Q?z7V(Tv1=?0) zM!}g;+O08r%VyX%&ncWKOD9O4TY=zWwA~#7Oq%tuIHW(=ZQT1-56a` zB`!%o`Ty1oOx(>FU|lcSZQ4HG9oJLa`?%w>N=ZIW!uGzS@nGM|C0Quj-2&Qt z`~jB{Nk!H@6X6tgm)X<$F|ewc)18#hD%{KeKF!R(TSnb&=!HGNmLKY2(IOLY#Z-nh zBV;C;Aj;t8HNX6o)p36h-r6Qn?H@C7S8K-6RVQd=AvUlv@39MgWtJNzSy_0F~ z;MJj4J`W*U)VEM2ILAw_F21%NV7H)KpT#DI!j?ovQ~pQiLTie<+WVZ4!Nq!bl0!Av zRjBskou|$^LvKIsYG=%N&X3q_6OrLIfp~@LRr8fb$CscJIESB(i#uUdWyF9XM>`aK zp_Jo35SL(i!E#rO#pFS#|MYl`{;puo7xgU@B<(a>sZe8WJYX|5*f#m}_Vo6LeCmb=^Lp5-w=C7Y2=BM& zSg{y$fM(a}*5z3z(ft2t`o^%z{;2KT$*z+**>+PCCrvfku78-!$+peOuF1CD)MQMy z?RWP)@6(5_zMQMt`-ipeb>j@+OaKG<>=kzeZp0u^FXq4qH&BfOXb(|xN{Uy+iIO)) zug41jq&%ty7~O^TdHD^WH;|o2SuCRxX5)Dy4!{W7<1h}-gXmbZy>NiB0q@fT)@4$N zOn<&)d-xz+sb+V)$hWK`=%JA(>mY}bOG4@H^-oNB-XV|{JBYM9`vAKyRL2(eP!8@; zjsS>YtY`W2KRo`-pO&*k<3_HF!s6t*x$Dt9PraiWRkao=wYdmSCT)qpm{x_qJhDUW z@A)tm$KM0TfJOT;(1ZiHbw3w%FM}+4)=))Q<~78vn!F<-5w4DS&Tmu9@hxMDHbg;X zM^6PcU+!MJD1a2<9Z?PJuBQ_+sYk4&d?Fl$5GQ0f>pDKWg=K_aQSdo{^wxS>*Ql3Y zlhhtLWD_tR|CA;7DUK`hSEwL%JoIpl3%w!*>!3rDY1b{^ufHUb=E*vy7&CZO>Py^E zeKcN7dO*u02J@szT_K~Z5%?pH=cxWRB#H1~j+Er3)6UK_cMF5L*X`f((ozp_F+=@u zO^^G;A3;LOc?$bTgOuzd(|IM!(y^nV4`w#`G&s(j*QG84oGt)bmj`Qyf3MCsw2U+} zlzOjIavW(y4N^+@#UwJW^!9FT#6rOvqcwM{s?+0;P3SV>4Tsjz~)T7rU@aYZ~E zm`v(g(2B6j&USoePr+`%H8Jc>&cX!aN_3J7bmmxIq9v(GVWwhvEXWW9M!U+kT-w<~ z>}Ndj^*lS?03ZeoFZu)UC#JeINv~GtFPpDdNpeYrJOTmcI6!eL^Nw($Z6((-KvD(~ z=~jo5c0I41Lm*!zy+&ir__rcorZq4(;f32m5mg%Sv_`2sv+Mj(IGql!{_n_9z8|NRXU z#{Biu(vtkbZ|^8R`9jpPNt;$3_3MwE>q=^Ie7V&Ht-$oo<5X9p2F|FPFn&R}2j zGt;Ixl;hhqHlyrF@}zyGNV_7buNAlL>fHn|l#s`|eACnAO&jeSDt=LfGPM^XJiWO9 zK@p(kQ>H#i2t&4K8s%%Qzy19pk;Zyo2MA*T&X&Y)jehmcD;xyRVi01nJv!{nvivZv zs74pH(UN}L0=d@Z+>}sy&Nc;Ml6nQmzx)U4TS-_tE54z0^c9}SYjI5*CJBc3Mp9&A zTM85pdA+d~_3?FBT>ex`;V+f!aaC$DcQ7E2CDZ+5mLDydf2PZNkb_7CY3#Sj%NlJ{ z&62wI#LT_VtvePP+DR4*LiXJ#%#_FfkY0)Ei!rPEX3G!t7LE(>kz#lylu{{|&Rwvi zeHD|n>gy^<7FU*~$dX5UXI~n>m>R}!^!eD%=y`VH%9U!yG@Xxz1pRi(#W*u8Fso0B zDk8`HEUxt`&o0M6i#&6D3k)j7JF-$DV$5>3sGaB+!_xmvTy1?Q6@f1eUESSv9yR}} zm?DLAedFeaiMq*3QU&KF-C~^CkYOwF*n3$<7OKCs4!t(`O z7msq{4iLy61Q*h4qCLfKT+GBt z_AWL!e0{!}$*x3Ioe1sjNj{$QGP|n)?onZc^B5&KD(~~STpAesUF}PwDTHP25;5&q zlxdLT=G_4q4M0vtp*b@?MMJB<9pij;0k7^1? zB?0vzk&7!u(2CnHFGH!iXqu*MS7ODA*pj=~_J^DQVqlYvzpRKXn^v$@WKpc5*-*cQr;+L0YERd;|Nx=3!D~oD6QF| zZC;EOdJN*UXz4xTen>s?*lvKV031261>BNHtv%nocVGiFOChYv&xZVNgJ39|w3;sD zF7b8b^!qF4E5mND2fHPh9F$ws>Vizz5IAAK7eVqqhMK4hUUW@V@li9=JWpExof97Q)Xmk$Qn+IoZn{>fns(;FrJ}3gDXLR&TgX$3>*W(=UGm03)DE=#?)h_hGPfx(Og!>)Nb5_+03ak&8Ra!@f?=3Ni=)v@dWu2NwuQl0WB3VQLz`top zM5ru(4JZ<$#F!Pz#L^J*-d$oBNYRk{^vk@q@3+YgT-8dF1hT}s);8xTMVg%0EId|6 zT;@i@ZNsL#GJk?(@k&n%jRGu6b&dg6arK&YriY|d{>o=K?zCRt;(z6zI01)(svH>1 ztjlt{@&(E2wczBMu6|x7MNatJ`ei030o@@GQj-Oe|HkQ>0gj%>Yr+-6^Oaf(yZmdO z5m@{~&lMCTomHoIjJiSNNgS4H&R<`cQCvFm3@twgBQ-g>$(0P6Whq=ZGCk9b%ebv@AZVsl?Bk zY$*UwuqID89f!yHyBYX2PHP5*+T)p;|MIT9Lo3DPVFWjDr~!~lT1KO!KFUf)FH_{` zKfl4qGSo@AG!xK_Sg>lajq>EJ8BzQ|EZ34;@;me-ILBxQ{;_{3YT0hdz9ZPoiYzdW zNS`UI=jSho8$a77ff=<~&KY4_dEx1tlk=As!TPyox3n}uCT^0=n%R|}xb>7B&_sAGg4}Zy7F{Z z7)w3N1@UuJ49zetb#|nAB1>*z{D9zQJxXcuLO)- zth2jk&wJKcLybuFok2>PrCMI_8?}ne!IRtf(6}*3uiS-?9M615!FbqAx#*}blsxcE zh2;6#)Sd!#D)OJEZL`C}N5r8H>!VwKLIPyy)@1+WuTVmtDZL0wyPSWXJfT~2%VY0l zI(nT_fR9f3v*&X9*Y4H~nOW_dwAL#0Fi`bcdL?^5SLzaio?KS$<*_j*6RHZI=$zu$ zelwavSU3Yf#=?wjfo@Ziqyc&gyYsuyUDukW0RL~xMl?hbO#nTyvSLtf8D$sW$jxJL z18F@(`zNHD65C|gHFN?C)6mfoYiw+cmzOuyLaGD%+c1UP?~uk*;6Oy461Y2k@ zq!>#4u6E0c*J+tA}PYjKezw2S(Qc!S88sbD+j5TT7 z3|-lZWZ_{rlgWNtTVEfXpHDXS(d?K1G&jMlz=pwT#8r7Aw2WIBE5AAlUwa;7MA5QD#>X&UyI4n(SwJirPj)U}nGJrF)g4I84T`e8os^ei3_JA(yz3(UT%?sy2Rfod`@VEc9 za=(AMp=JwCjAYg)D` zsIb-L4N1hLft;xbE0G28JIlrAbpAmrolA>=~w}`mrGt5NBAl}ig0XhsxYZA`p z_D!w?$HyR|-;HcnV-S0SpJtV$aqVuR^hf>k;oPJ}Bm23q=5z1WKiQ|FyPs|DuqZ@_!RL+!VhdPp5rEw*0u+WRoa&PnFP6I=^2 z(%%6h6)pbN`)?0RKCHnz-ykn#&;?b);(;3Lc}xC zbH^9+)+TO{T4YJOx!G$`hwx;P z#z8&sNDFka)3!}5L&DCEC};N3zMB}Z)C1^d<8;%>gMKSM**S~lF5SgDb*7j3VX zmk)0<;s(tBMrUHKoNVIchP0-o!Y;7k8)sXSg>+GoCAf8GXO5lWwlX9ZKbfK!qk8-| z{g(~nqTpp~3#t`Ysbu579*rgOwiiD3v>SuAnJ1~LN353i$-+vI-~Po{?7ikyklBH4!V2199u>9e); z2o5}!XDS6&*Ck%&fa>f)U`BZA&i1r;wh!SsS{|!%wYhoy(4#)bWzw0X@tj;Z#-Ygz zFJ+I#@1R1Dhqlu(2rB>-W5OQxot}$3jRIv&A!MwO5o=3Xm^lGa0~ z!jh?9DaN|dJdWL@D#GD$xBKrJ5GOYSj=!lTjLS0P6eZ!y`VxZn0`CgPtAQsUg+|x= zbC<}TnhVyzY1J-J)lH7gj9(d1An)6w=U9HizPJV|=Plq}05WMz;n$nlnzn7Eb$hbq zhB10-DN}ag;?7VfF{zQuF~>LT*%$}EDKe$8&(WZWjW#HV1b_D3e(&&uSh=G3nzzGN z;XCu4D_Uk|ly|lH`Cy-8^GO3sQ`lg`$XAqWUk?18YuJhkMk7;G3|U#EfUbca{a>+t ztE+C&ERU2<{5BR^qiW!jTaQNk<}44CrCUdcm;GAI%b{qP`0N#dh7Fr^>Ae(ycBG3; z)Hm7E*%x;AbGk7@2MxSO-!`DTXlMeAKp6zgj67u@8>O;q;y83z1hH1MYt2rca^{^) z6p}NBNVbQn-YHY%?=IDUEc|X@9nP;zT+7#W8``jY4)hERR%foAckVj!v^j5kPd=UX zAi$>#Fun#m&uX9C{ihF?<-$pGfHmk zFuZM;M$OrA{7|yO}<1f}6p6jlKW{t67mfnOXNM zWEo=esYMg_tE7*tuU@oy4N1(U{Pt>4yJn_BZ?g#Q+aaGUp2}CUdZ@}79FSWbvCIg= z)Argw_0-+BKuSM_Yz3hupE}#TaEMWGx~<#?%*xx34K6W11!v;Tpa~^?{glk}*Z#yY zwi!X%wl|8@eyNhQ{&wajYL~-hdl2P+}3=YoRTX6*j+XEyC&Tzg9qMQ@n@R_v>&4^-s%fR*bH z6n#H0S>CZ-)EB=cz(jL69DapzYN;p2QwrXJ!uohB;m)4(cYZRiHo$>Vj{%>z0BmUJ z0GXZEHGsTB4SaukC3&LMY|>jR6$@?DiXv{ zr7^wIoTaD#%AJiw753k9D)nk(n`(*pK>2_O`jlSa}3#doQu9FDzIozeQ! zh=T3ScD$f!LaorYv`(Pq&GtB=qy7~Qzx-rM44wWKial;|jJN5pES4hx*xU9cC<^1d z@T7vY+;G>rY6dAQAHZ`tjN+ZrWB`M-{q=4|Lqnq*kY6$US_o$~z?hI~!uVuS7d~(J z6YcrYmU_%G8Furb;aE!JV_8Cd40V;TTn+!w3_4cl{m*Q7*C!iR!U>E@E|i7K-K|oJ z&7Kz7m8~S!`SXuu1_*gJu+t9Lw@F*g(GG%VoS>}X3+MP#YN++VHO&hu^S`+;H-T0m zAj*+4O%5@v+s+@Dr(I(1c7QxR)mAB_sSVl}SG*oIhNk@NAs{r)E1@q)Q$BCw(nSAD zlz*$!4V3WNft!+ci+uN`WEKCRnA^g4e*biEpZOzx1jeiO$6G$sh>98p*$>PWuI>;LqFeK&!^OdHT@e*X2X`|67QT6l&`OCz(>R0@WoR9$WSV#O_8!>$p1rFPmPw^Xj{-`-=wVEGF!}(rR zzLE08THZaK?WVEOdjwbnX0U5#pI1+vR(jzrtJMhh=&hbiU_$<~jcaugDzuCOf|;Xu zRP8y!mGwQS?N+aNHatGadj4$;D#4cF{2FmzFpUy(zJhk~wZw|BASQ{VgrU}gZO$g# zI0IClqh~k>jRyd+!jLV!gUvkqRvqn}oF2W!WdE8$h>RI~k-_-_$QB^7AGH@!6v#9rXJP*p9-4VYcK^rSp-GJrdmH^oo3xuz(Y^&xa9vYjKSrlAA7rMk4}$ ze5m@gOId^|akYiQEa|)_5zXo(mi(&{t|BloLav#OSha0(6W4?b*Z0B&2x-)gi8#N_ zX(z%aVc~qorKvu*Z4>`uh5Hf+HKN*x_-kV5{@28A$jVscKXi;uw$_dWW4CXUK2^0D zH3K_;gnF!A9@g~s9w6Z`i1Nj5?T^9TZZN^ecid;|O6`rLQ8hp#!Tg@JO>9k&0kP;9 zR7teG$mK64YjNPx7R{4U={@G?DS`p^rW91xLQFr)K0VY`+Z$Vc_ii_cuyVFB)gB z;3+9X-oPDzMMIH#KahK$-+QA06pYRz>@^;I7QDHL;X|ncgJUTKQ@WN329sMSmL4KV7sfRj_UK3C6a%)jB||MuYwF z9UT+bp4uI@st^S)b)yI$*cQ(z>dO3-!Y+K;&X`kuiNFsM5Wx!UuD2R-*kwj*H)v(p zd3%O$A$*=<4L#z1-5e>zZGE+23U0 zFoUkdnf`z0HIf=TSzE_MeD?PzL~+=FNd3}p*0sK5L)mIwxyg)*a&2zCR+;@fHsaf~GU z<9&jiIe@pGY1g*ix<<;Y3mxDfbKTE0Ggo~kQ3SnyfYW8fe#$<8O)2osTg3R*gYyo^ z=nP-eBeWVD3ttwC@+es$$WjD!sX3tX7miW3DA*~*EFK+;bWFRRf8hPG>gI_QCiRt-+nAy z7Q9jEz7yYd zNPQv!Kc1h@D;vq{JQ9MjOj_`ti2j7X8?Lqmy6cGRO}!8q1G)nku{m}>_dpq3>rocq zL71eZ*gd>2f=215-2MaYtbtAoyu2x}0p>cPs1&VS{f{+a$eW|WO%tzq5DKOr+qf#p zp&}R%zqfR|I1y2kQawaXqsuq!5s7YvP4MQ1b<^U88;`k6=o(^x^;!n0prC8)g=qZL zdOba>?*R6cPScMj!L?-tX4CZ3j%CuIr{GnyKf=oMh?RB+`-Wt4Ks!+Y$YSAYqEY7I zbpT8C8s1yU6oFHuV`z$UZ9AtdEQOp+fV0D^@RjZh8J1=a<~g?QFhSRc4;SF!by4}l zOZI8suUH|@s7qVKt*T9w?^nmuKbR?Dx~&*ezx3N{^1L4kHsRd-i;ek4EJYCqf-VyN z10qDAQT>;kcdAYYz^EOlqA<))rbkC{s1xpf?;+OJD>DDVY8gd4r)=}KefTj2g0BWa zBVZt#)C$vR5ce_iddVn)mTNEum`LTOE@yAE8EvdRWnZ(m70rpdlF@353I{1!6*33< zbaoZSxO#hAJJy267@z_`8C0|QzVD#OI9Gn#JZ3<01t8Q37z}g}#I2{V|9BR7Pfj7t z?OXm@yQet1eMa6kOLxH^3lJ+*#>ZOKhz2-QB-X89*NW8rRF3zbCm2jj}cj7n_M zkgSN41{l+sNXuQc7neh%+ZPw;ANf;#XQSV{uY~&ACS!6>zh|p0UeEp@5Jw7Ohf$4N zpq=qA6Z`cIUG(u_Tk(K9l|9aR{$l-XYsAsl3&t*DnX_dgp9VjI@(>3d-|!&bF-lX_j45!(){*0&gN#2dDZ#I z1D7I&^jYIMyM%$<4wUwIpB@I-LyVL^Z^$8u3qrRQgu*lKGMpnK0#IHMEPfPi6M2zi zTER$SUsA$Ec#!|Q4}v}p$jOk+mViK~`+QM#jY*@Szj|?V3d~mk#OmixkW7%EczCBM zLQmd`$y!W|$Qw8!BBH9d_CR>lt)+Weq}tim%dAuuLqr^Dj$$Z;R5UBGP?uV{8PHI& zxtxSJ&@%Lj=Q+AwqE&y4p`=KCpss!Nwhwg1!`$9}(-2i1haH*j&_hG}(I<>N#C)?G zQ3d=U=5=r=qAy{)ZbFrKb2`e=4dDN_DV3&T|?q-xws_CGPVb7n|lolL& zP%Ed^$B&9o9?O&|{DC^A|85>UCEVP0#XJpp5R4mCh$Ri&3@2dEthRYHvN6Dv^f%KD zvaNI1>+2C}L;H8$l%Idvp5JhARcCCwlnd!lU%@Tdrk%i}^Yl!X$GD!aOZ@s~7YT3I zE5BNxE9t3&Jqukvd`b;5Q$ZQoniPOtVG`z(_dKLr9QnHI=hBr}vLDm5?lGpKfr_NG zpMB4d^*u61+bho@%5vWQv>MCy9-r?=%FaXUA*%_`!wiWr_=<9e?d z43dsz%c@#upkNk7_Sc08F3~ZqcHAQHGwfl&(>%E2##3B4O<2buGG3wa-M$;Sqydyd zuZo#Jy>%>_6eu|}J0n9OWO%JfQQvd;@D`~jSDAW&+gkcodE0o4>dD{5vk4R_&at`V zQw>6_0-^h@)aB`nZUgckMy9BtR~Yi(gk7~46V2-_a}kqW%y1{nSrDb*nFS5teB*t8 zrYrcklkma0Gr;-j{+9PO^_jN36Y%LZ0KA5Pmb&7cf1AiY?*gsd;`E;6%XiZM;Re@_ zz0~&wrvA ztd}{|U63=L)*O;NUrGL?+5c`(sgByEk8#C4xwDTE-QAsUi1-F{xHJ%yJeYp=Tj0ji z@P3~1Zp$imD;PM%DyM=*(h1c@dv4Dt{c0Usn&HR#@KM(lSGM9Q6aXFrhv%UdoueLz zPXbU$Xty*}ey~e52w6(OC@+mtkTHZOzCDF~)xoK#KQmG1tjm6Y`06f~oW(cVfFzEomv`k|! z3K0R(=*#!64i3-w?dJ2Brt)&nB0qd6XbTx%7)az@kY<521~vjz!57q^zSiC%xyPQy zk_Oj_rnS&0lvi@^r6{lMCkx!b=W6F-QUnG$~IsIh;5?ygqxVSQARc*0(jqv5s94q;kAnXIe?yD-*Z;{&zIr%infGAcVoe2z*uu4B@KfBFowdw2{Skp5^CWz~p#?^w* zRxrs~tr?!$$L7IiOmTR3GwjKaLN&Z#Hb0A4Zz| zQ7=oc6r`iJ$B{Qr+h)9~9^ZDN(==Wx7c3RlcJnHxolRFwDYdt_ik!zOCzgmrQ=Rln zS;&qJV67-! zUv%lE*L$C+ zym?d{P-*=gTE2FCbzJ@TI;g5)!KkX1P2Ft~hk|i9B1fw(*xIO0PEfufYsQ|AQjk49 zj7QX9xPPo{hlAO|T;?m>{52~ipdhNj7>C$%q{sN+; zcz-_B#NqE#WGq?z7;7}No(-h-^6>H!;!e(S+d{|}*5BRU#Rn!O{!Zr;dI>b^*D;ON za_wQFr$!a|+MPCma1A6=%6I8v4cUSblwB^kJX3Vw(JBsm8>@JdfKR5nDiP>udA?xs z?k@(&aL~w8Wc$z4uq2_gOHQlW}gbTI6xs5R?rZVI;LL*MOjU7U?BZlAJ56%0OnffH!?+X zh5)TQY6FN#u<3cP>-!MOYs=X7GyQQ5F82DqVBI_pZdb8w7cu>?uw*{sz z%e?UH&Uk*fGeSdiE)U42)pXyjX}e_D5*ZBKtj_hh0=iBZZDiOKe_QNfG(HZSyc>af`HO8JJ+{KK>2#L(~DCO+&9x z4{<5c(5*TUvVUjjHVQfk2a`QwBT8U!JZ->$Esam4Y8rBLYDoz}8SudzyL0(cf;K_p zA*T#$!g%|3w|ut1w%K{~>|a;?qu~u`-RKvltP}UQ2C_!E6H-DL zOV_m{Izyg4!&4?whUeaPCQN|ma7-8dt9_yHKZrInfb3N*BW|FUZxxOj@&!2$G8mk< zaBLjQ<%V@B80d$bl8U2fd$e@2%$ne(!3FarzI;5q*c5r6J&8;1$zqs9XBQpJmAjzM zI#3z`y}Yli9ivFbC~YPrYH;JB%M3+Hm{Z=B5ly2xI%9WFFg>p0-wkXzL#A;`T6RqP zxIV*B+VHDLr!Y4%zixwEmI8DV{5Zy4g|>X0YKqwh(SjZnI*rB&(}6P=nW*SU3L*RaTngHqFJ z3f>6!hrKBfcQF`-MRT!}pjbvyr5?mpTGUV`mwiZYQztY(lQhy?RKk{K(d#bAryXfod521NqKm#WH-=a+M_I@fA z36v}7d0MQv4fR-IF-Y#~O?nDHdWH(MWWSdVn>Df=^U1BKQ+LvCua8+R;}DK=q#%^MI<3oxnYJk-VKj zM`msrg~&QQIROqw30dECbaLL*+n9U2#+*5kP8UsN5J$FMmg!1P>^Pa}uixF(K8$gt z49evj;TWjYp-GHS{?dWn!}Mu|)?cVWsBuq1Z%7O{l#6?x7oBRVD6=0^0e8eB#x0^n z&Ue*uy#()nT$-)GtLNt7x%}`dTzxIG4#j906=ynfGkq^BvlJ1=@3%3Si~Wl_hw8`-CtO=%9zwLpEmGGb=&dQ^>AD_&m(mozq(<8m2?ssJtI%E z%3f{FFeRoN91M=cAg-4)HT=mW?$|x0hG!pT2?}3N-DmETz$ItYA?JL7@^S!p{Zz-R8?;&0 z9bz>J2}j2mnxEf0&6_URcRgmhWTslx7DZUaz%bz;m}P&F1M;Q3z zAyu=1;v>=_c&?V?re*Dcx4}2CA33K4EKpOWH&Ew=PN?FR&hKx8iQ{+3Ow^lATe>E4 zWV&OTdh&?fK1jphZX(QKMy$7!WD-vLMKsR= zX4xeW1hDyWW_*%kRX1Jkr~2Mw&6Kae!uPRcc-=0@KG61kXB@-U>$~lN>(N5ufUiRA zD;j@B0@XSc@toz#wh6MP+KWD~%dLAVa~4 zy~~E#LDDcF=Tv@HFN>-K+%qDx_~*}`{`Ady4-;V(Iu%K7n$_C9ivNV#8^;>ui>k^P zGAi5E&+#;IlJLu~)lEmh54ApJwO;E^)vyy9*}+!Fg)AA8KmQKGs^YV>@WL0}9so!0 z^K)nlPK#duRQH9gkTb57-VS&)Av^5YR9>`>PsN3Bv5bxksGv$jz^0 zED_2zG#0^vYh_39cI7t2TuZ;EbI8>tCw3sMUjL`$T>=`sgW0hCzdypKhr`LfSS%r` z;ZPTg>^N$rHHx36 z2!C0!3a8>s9E%^N)Z^Ny{R-DL`Syw4Vq%iOF-Uh18W9u}X~FaIc8A;B0)03|M9%B9 zU8l2Kz`s3iMxeeFoY(WPDaZCpAWLwTk9z?BM_KBEPkR?mT??B9T7-0k!DCtPwt zR6*9K&RX09#{r3X)i_P0gzlk)w9n>vC&n_39VYrqQzpyS{5>;qRgmQl+0vQn_GM7o z?wFC*E7UnCOXJAQlx-Sn%vHr!uYiO2U~jJ&Ic=n6^6<1-DSc6cJf&V^P6}TmE8BPZ zvx(Z%8ZHHs5tfsERX%yq6rG3OG2W{!&DEdRL}zdMA;Gm)PNC|Ci0O5RyaDm4Y~&2k z>Ul4;1olbhW?GbRH?N+c`(l)(GICZUrRGtHRB$*MsDg}D!-y?QzU5D2%N(Gt->U)=2gwhpxCfWEpaLcG8$BzuK*)XPXd~Q{W^`kNZEtVX5~kuR?099of$N7E2rcWPdtqn%ubC^L1mI31;1qfejY^68%s=2eOXI;Gwl~1KqPL5YhY-2+!hm z+>5NqG|5UZxo}t2R`o75P{tk8VCF|!x*@u19J8I}GUzChZN!3gDpc;YnQf)t?;f+l ztiK3KVe@=Ix9xOCJZa52;s&8qTl5jw6p?IL{2=5waZrS)PxrWTa#&N)KRc!bNLwWlta`rY$>gqRE$A2`Kp4#lx(N%oc5&ADseVgcj8*463zU<%*{pjK>lZxtWBL0b~qUyND{HyR~ zV_jof`}piqQ3hAV)i~2ps@p>UotLj_^5{c9VXmIuz|n1rq|YCR(@&b*1Yy70-%b~% z-wyeL{5$Sip$r!0jAYW0PFVE7kth;ZXc~cIjp5x7tm}g1K@0 zdSdTx(XhAid1TCfl9h-Migb>gQ?P2iJf!Eo{SFnK@Q@B`?xbM0)7b7xJVb31gBkP< zcz}2SA>%Xu4z*&8rvu7N#mJM&2`0cG8FWm8*%5nb#1Pia%I2lYp{8mouq{#8A(0Bn zeyYxe=$3Gihk}}9>`)2l2!IR`T)pZAldpFJqBAUb-@61P+I1dgV!UA>9!|_fj;XMg ztj?wH`RJbH)B!_Q7M%kZ{R4>Pu|J>)W z!$JT})MC-W1B{HLA3jY2zW!K$L_clLi0a_M-iGzp^vbdu(8#NCV2FwNm_t&+QX|Zl z9x;PObSu_r!(9Hd!NNw8je^uC$1pq`sM#c3#e#r88mE;|pCh}`W%^ZpmpG9XmU70ltM;@ep2BBhxBE5MO8^Gi zTJU*YP|0aKFmD`92*X;tcQY+d9QrS0yhEp9jXNgH_01`pLvNN+GeM&@#*Jgi>Z{XD zk~$>B@rDU_RBuwSS3{M(olB1lX3Z9D!Ytp3xpd6!3OzLqKk2vQF~1q9M?uXKBtoFn zU_}%LI1*|3G*XV+K@MUIm25(F&k6kB;O+woCR=^NLzG^QQOT##6n>w~yKfknVXqP5 z2Geq0DlowotX8YukWgQSC8`>l;jDfP^LVK?_cL!v9No1x-_Hnr!fHXR^9Nmm{}U#scHiG-ERBi(_;BwHz_x?$TtItUTV`y!=(-t>xRy zLh->f6kD>s$KfYIAWd)!g5_A*OAY%KDt>{+9n6}v-|@Aj_EartB(<2fJ=LZ?G$qAR z-eK=dLrUKrN5GZa?*5%uC$>8L3h7N#^|Kw^#NPM=7B7&n9S9Lcd4m2+ltf3yRYauyVJWvkd(+70N zMw#0uNq~@TU!ej+qTDc``o1e4AdN(t&h|VN&;uS<)M z%1#??nk%cTjR6@GAkJ)8ORM5Y>!8+`NFOYtryzVk`dbdj!UoKRuko2CYvuD-3yA(c zmyUa7xQdwm?X${RSdR_2*Gaalq%35Mp89r|Zr32}g&Xm{NjLzM%)w2^uQZxP=i@{V z9iqh?qu;D2Ci!;}p?ArVYtaIMo(aIofGBoVk$om~E@69&f@KkAk!1pVodi&1fpjAy zl#8d_fQK{|jAU~8Nx?f6e~taS6*phnQsTon9&K1nXv-)E$EEqJMK_}e^05vK9GRqr ziTuppb^1G=yPo7WqQ-n z4g>1pJl|jrYxkQ_gar@LvJiRqNy$`c%2naNxn^;w7BwF}ihO;J)s@bR4It4|$ zyy0^np-O<`@pgY0)`$3i%r+VaCn~qbMr%yC$%YiGdX0OAq;W`@-WVxEvsHL|VXT~@ zHk8#u2pD_o2}Yo$sJoz;66ep1SpmNv1iY~CFk)hc!_@&#Sl$t!AhWu-L5bnHoLI*| z_yG0sh$$mlUkr6k0>2)NDOzK;EZs7$74|1OX? zE8ptYJ`8{E1D;>pkbvToKwT58Zyy*P_R_zWtz*uRk=|L0C82vcE<6L1O`Smv#Zom& zEmq5{JqTi&@1NGz(;GC75u)zsQopRV)W~>Aa{ozRwu}_@VSWF+@h*%?A{bhn<~+Gq))iepH++60Lsb-#d&*TUR~R-FXa3S6UiA8HCH*rzuqz zCRG?oz=^qkmK9r!&gqXRr@@)xkpjW;sY`|@Q%RAYkxv{QZ9LtA7S3iI*Sy4K-jf6X zyvqGW833XAFBy=tMjqjj37VjTsV`L%M@+gUaBVOGZh;$Md}?awe|v+SuZ206jcJT# zyQ3DEOv}Z}MP;L`@75{mflEhRkKuWs_lKDGP-u8mT60GALdEjV3t8Lk20v9r&9v#( zQ(T+bQvLl@@mfFa?RLcv{ZQ)YR0e z*%9t|67#3*;BINVBzI5*YsG%&L4V>|{mOy!qt3sXH)I$|+C74hhHsJGC70XB81Dq( z&7%~7K}VM>(F;k~itaJ813x=mPPLe|-T$zw%Z=MnBv>1+bEnnD+Zc=_|0Zi=ovpV5 zOxt6GpDdOpXvLZ3jMCVh-^wc3W9q(Y4%eDuyv~ZeVnO_K%z4gq5a=kQ!}^k;PF>FU z*M>iym_zPAOvp;&)@^FMeP0iq^>6D59}igdjJ#(91|@APpQhEY5Si!#3$zEPjUc1QkP}A zDu?pFU!5g!gDGy|R&%dw;Sd84Gb`Ip-c%%CUUb&y%z;Z1Hw-xVge<=^E45Ki;(lD1 zn(%%z)1v>VzDvLavn!^B)>@Dnm}RFU*Xt_ces?JbGejkCNrHJ=9AzwtONrx5BbLLRV_#=E0UT(S_bObdPl^R*O{Z+!)8dO zkGYN)yt{LWZ9*jt{!si;hu)rqk?J6o-ra8cvo*VI(H+NN>e~Mlj015%)l|7KYWtPX zq2*u$DCuF5XH{H`>y~1r3|PN6()CB2o2NEi8hIh!s$jt3VxVe{P_SB5SP<%%>cLTC z`SmE3|K0MwEV&HpvzS1v@+qF+nsI!kxh_&He7!UZ8+od`Oe2(Ue4UV_R2_5`*--Pu z3g?9S5)_fC0zrOWs%nM6h9wwO3(7=@zk~^4|E8KIH{xxU@yxJ-x(4~Ow@01rb*H)M z-QH>=U8q0;uX)Eo44t^(Qa$p=^SlEdg4baOL4QzCDs>gg7PQtO~O-n&JQSU@mZ_{d$6_4LT4|bH%#C8R&YfWIS0y)ST!cT$JY=k=r+38vbgK^8J^oFN zOJ0?U_U~)C?bey-KuRn)P;;9LcVw=?w>vkv(*N7Pc8uIX^T;p$5sNKJ`}Fr7x@U@r z;h%X;>P%%t4I)1QNn(k>RY_bOa3Rf{T!NLundGU2A1Irl_sppueu4? z?LYkn-;%<}Q+4aB>4VD_Zib62tydmg42!NuTOD>00eQvcs^b)piKkN7pmdwQ$ZpU< zt<9YPD>uk2kviWP<$8GK6o-I>HY`)r9OkTwh99UsDqjB2&=)k9)B5OagxO(N_}_JVU27z>ouI z8h{~ubJCU5vIgwzxFn&?ySsdGm0m|U5G=B}Gm`LUur}PH`OUFV$Z90A-8&r3nTr^iP+ zxV4x0g+8!v5B|o&7iNK{ACaA1JMlQ2gj!O!S~7egH|$TZH&xtm4|3^#iL+Pk;F?X$ zvZaNETfe$<6~%?Rz9VCi=t$9U=HyI_&*EczVVw4mkk&jFkpwsiE$cfZ8X~fFlWDig z;gnG2iH2$!8XBUxXYS32cJwu)(vcG^z|Ox&{CzRo8H=G9YwKaI*|n$a zH0D|->bg9L6Ts|_`w+-lJNtdw92y*aR|1e@V^`Yg6L$`^j*(Ue7=Wy(f2F{u=<4CA z7DP@2j1w&gOw5z^!J45_qLrc(L$(r|OT`p==Hytd+^;ZWd|@my$2k}RA2G`&0V59j zHO*zVnsUx@HlsKT4eYzGVu0lI9 z6AQZ1UyUMV)%&wU1-W6WR`JWn9LhO|2}Q8WxGhUxC#h1E@zK&2F~cvrsii-Bj*T#b zNGY{?S%*1|Ve&L>TerkW(8wb09O51;3BhALB`xuq5|;UNQS-u}y|8K#5U6dQX`{LF z?y}paS#lZ&I9fKyidyq@ck3_FpX4`#B>m*-T`uGyu0j@P)6%&Lb3ZQ_?#YsdxN_jK z0I^)*yBew=X{l;;ACOF0Y7(a;BayOMq?w~&{&BlMCwn5Rn=W9RtUDA=vH4&`ki!0P znAyMyW?LOi9>5ggZtQ0i!(7l=g&v?Dja5x!eTNaL&qNR=2@K#s#bGt!g!;Uq7eEH# zLzzaabbAW>C5+H_d$fhchgeJ(N5MfAkG5WkQ5&GA+n+4;r2tkARe?YMf&y-Mh>kxG zj^vh~3$ZqymTdMU}%tcSGSlhDvjG-kUO`J~uCZ{dX8=^gl%4iva;BT*I4jFzkCd_Ugw?Z`84sWDg8r_o zDd1c;PRk@)Epk|7g9J!M$O??)O<#nm8sSMh<0m-$u8WI{7tcGS`(XcfnMk&2j%_!y z>^U*EIi>XI#csLQ6j27*rFuNths83*QwF-J-PJX zmd9wP1PaOxmi?ClL76dwTDiYSnYmQqcLEl_=5p0pF`OHn2qs!v$X5%7$EVxd+jjvi zDm!_-7E<**{nySDj7XZpd~Lw9h`l~_U)0BVwdzIyl0F_Vr9*lCZaTZTjevLeJ9P(X zyzWMARIN&`xkAtOXBFcIsjSFTgZ{r3z!w!#Z9}I&CYdY7>)cNrSxbNClc#6Y$`~)M z7IvUL$)tO0kyIKP-tcVH>S$IR?J9Vnjcqn97ktiBw(LRL?*H^a!(K!gnF-u2^OGOS z&ifEKe}#8+d6tL?n0KS;ytmZ5#PC)Pl3|%FZe8}cgX7`k`S!B_>b5pclbIXZ<9Rh9 zWN}*LaH9}O)s18GMAs(oiZsK+P-?=9yh)opfC*HnyWC`9b8^4c6};CRidU78mF|2N zuHe3VQg4K(C|R^dLT>OKW#g@td4b~saHXwOxqz4MK>pPu8Cf>zr;xtiq-rwOW5065 z@+oN^6y(TjcFVY=)oGSz++t3rU&k~5!wQ-L)T-BV0a}%5>RB9t4B$v;_}zv5Ps7uaHu|gn)gC zKmdIdQTT1J8qQ5^`5>UptJeLVq>$xU4#(-mA>(xE{$+ZIWCRZH5D$0BGS~WBgwR*QH#o96PeS0ln zUWaI_*}@Cl;=H6O{tkR5z`~>pOqgygc)g_7YVCYp;gHmwplZ?#c)v-V{ke1NG^Vw! z4M`YONU}dlali~Iw0NHj0KQfGKwQi1ZhnbE`s%g`K3mwd6vn>Z-sPAuW3nTzg}4q< zysFLI6hXz^SEyR`{beKz@3*d@G@|+I%loay9-|Q9j=83$7vZF=s|w*M@uHI>kOzuA3v@?y+fLCVBu>SG zU_!>U;=w|b?)9~k1zBQQjsCQBQrzXUXV6x~w@iG`mQ9f!am7ZZ)0&&PbRBXYo%_g5 z(eV^g3#!AV3TOM*diJqWb0~YB)RaY(odNOy&K|+GCgXZgDBeafDIc#UFWWsa(l>JQ zy0A#`(kP#h<=ts1n&a?=eWG=PeF;>yJ8&%a$ znCkKqcmAA5eXycsX0qAymwPm5C`}XgQI`hKOBeUWnnzcETW-F4Eq~xGeBbvILUlZ% zG6e_dla2eXQ6nHXCsHoFkp2s6@LdOQqC9p)C70ai(AKGxnSnl-&b0hRNz6}P@UciW@v&D`~^@#mb zIrE$d6@KRQ5xUB3Yw0qRV^RdW7b=Yhy4u;rmWVv;P@*%?YPuJ(Q-$jOkw=fThmNyD z)5&~RaepjcBBxn5))|^3F!G^g2PQXo+nmuKsNz|t@o%6>OLYVuVE?HtyL={Y6g9cwnko+pH3X?*2M74-Ba4rB}U8E{JAQQ)rB(-=BpX%Me3rh!{cI`XP5u)@|G}J77xY-`PD&b3;qzf|% zE3~3=l7dheK_N`4u=gLckC3LoGgbUa4l)G{PMw-dIK+2Kr$Q3LCwWgOoKOS$?X~Cc zKdHXA*x8H6fa2mipU4Bom;&W2S3SMNdkVE)*A`)x z54MnUOdTvT8x@H+q3lD5d(5d;xLBw6MLT^IzOO<6g~n%3Sq?4Tex$T0qN1BF+p9Dp z%Io-9J-A=GVpHzdUD_&Ay}CK!et`tYjMZL+YsCZn4MuW2W+TAZ;Bk=%?j0F|fY_*E zCcbWhz}ATJ0c|69+y_j5-_vpE^bzLF7uD`R60Q02K7_5J%H>*5vk@!!_#r=nS%Iec zfVZKgbD!oeo)U-yD<>iq!5jq6$1k{@nso%P5|a#a!d zEVMkC&+?fce{y#?T<%$WeUVHqUKSSr09M=n{ z$<&_Z5VE(f>~oa)cB6vsvnwd9BEg{GE>2)ZblFs=ow>9H-DSDoD(GbRao8y-6Q4h+ z1vB+nOExp!T}{a%?TQEp39Z<19EoBuq#0) z6JF=gr~&9on!xn*w07hPJf_@^%U{KSXV&6!*w!&}ig;>jYLED4j~L{?a5cEl39Rww z^H*Pd-8xOtYu>3=@p|4TKHX?9P-LM?rxVk6{9>TL|BaeXqJYe)>SJ2ugO+0f3t|S^ z{rILITV2|BQN4Ex@(t#$pSOf{(TPyhwPHN9dCGC*m@Y{G0NI#X1|$VADGc`Z8B%k= z^+6e}6qVOCq`%xvI<4^2s^P%>oU0NRLrT5OYg92hqiD)k+bc@~s^Zs6Wg*pjQ4|c6 z?K(R+=!KNa<6mZ?!DV@(DPT(r(xHLO-&R15vKfyDXb?cYKZIQPtTFMm8v^%G-=Kw= z=OEyo5}R9GE*BkfG7I0wT6CQvXVcf8wmc^FAManD?k1%KA>Yor&f3-&hpC9?_b4?K z3Rth%r&jl!OWzzy-vLF_OBy=AX+-l?M+!9=PZ+FFF=PsOe!ASQDK9S%7|&H-7EC`! zIHy6ofQfx@F6VMy#1q;_JHcU&j~TW@r0V<>kH-5W__b+3L2#do#ud*U;4b|3X=feN z&8PEcm7-3*R<~F(s(;1xcd&8mrpXz!=%AUN(e-{E@q|w#v^MC)XjnH*n*RS8sivNktwCzJ;!q!VRDw)qp_W^G~3D{f+w_{(uW)S)%W@7K*U zPik~rV=W2>s)ka$agh6)jIU2?eBJI!MP$l$4qQ;cy~xT@f4VSBS4mGxNT`2?3y_qc zThoBX)?VB3|A}-b1)Bb@v>&Y?`^A*1UrSaB*wbqApuK?v$|^oSh|+_vW+|T_CW=0} zc1M`oS^et#@P+3A>vzvpv zrix)?)vgMVYi_rH{f$alm+e>$l&VzxPxW%xmGY*DWlAsV(`JS z#%}>H;(*fJLhIDXO^7#*1m}c)7k)AXRAsBH7I3O9ZB3eZo8Q@qw=JHcT7l=B$9AG{ ztr2ykNdE;eegpy--{Ox@`V^aGpy&yx?pu2-YUs?}KJ`&iL=rbwhaM*wOC0jkH#oCy zP%gE`>a)v;q$mX(K(!rVy}bf?%6)aR^WGb{Z-$sbvwpvXnSwFq06?9450v^qb)XOE z306q)*!DHae_-Z?apYgG7HM67jUS9El?{`5)iv!en+u$>P@0Mta67}D+EK>CKRF+Z z$n{?ICk!ph;~8xI+wZ09jc&L;w#c3D%{vh^e909&=A zP@k=%-JbN~BfT=|dFcY_HpLt`=QJ5rIm3z?j9$-kLdJ=%X}%w}Hz@eW>Ue$1KCU>C z3jloX0~;y9s;^u9l%xdp5VwQeEMpeS zh078-!U#qr7fLkqrz?kPTK?A()X1p0i{L_1Y8EY7SCo;+t;ZLPra`l zR};mihiT_f3d$qmLQ+4Azc{=C5((!U+=j;n8?A4&;Nbq%m1g41Qk2T%r_hJK>-&I#Yf~_Wg$56w*o+iG z`WThz&0hx&F-83O^Nem-9$@GDz46@Y+WWQ~d6KACb4*Esl2gUQ{MYi$n>X!TYNZ=*U_6@^ga6(l3hhcp(VqY^o?lv;!JN;o zX0WX9U|Su#4}b)s_1IBr^oNNQMzi`(6 zdW#nYK)o!kzFYfn>UYs~mh(2gc|CoVIUrmWUjKajUo^n~RaDFe27y0w;r@`@hiS;D zj$o%GH+%sZrsk#MKIS5;m9=I<9^!joilo_`1zUE>44pXyr{a_#{f?D zQ_w~2ns(${nyhVga0aD@iGMc!m#@ndC&0LP)6dAK1^(h73P88j{B-JtCinrd6tbog zT7E&1tzeRD5^AA+5^5Fgq~k!D8DH6(nkUlh#AQ`=!GOAB{xS@kw!n#c`J6)_-U8^Y z0Z&P%Y7~NI$R?%;jkW#&G^2_)LNooUz!!Ysx}k#^{Gv&^fz)Yag!9R>UOMMiM8-yy=x*>mEki)8*qp=%jd{2P^Ur}>N6(8||GV|JS zIIU~R@1onm?O;X0&H2Q3X`k%iAQB6a%YXAlV6vONY}^{)5skEkWd89qfZLc@0$V{} zB8gD z>73!Alcz219-wGN5^4kc(;6I*&(?|bY@m;fZ)|h60zeSJCQzslMa*gxE{RyD!fznp zx+!Mo$J{0doSzE0U&7k$ZvbZ&%CC3ZP8rr6>J9#9Yb)UJ9)JC9x2OGh+L10dnY)kA z69(@+9N+C}-@#O0s1nMj*qHjXx}WpnX%CRWv9ITMtOxSv^a^)8_x) zqG@(Pp{m}}8+ULRs78065{gDej_p!{MmYD2%by-!`yQg`**)$mI1s$)%8Gugu2P>;uE|g zp~LWV{j2mM!(!ceCCw>5HRcl3^Y%dMUbYpT-xB=2-CvNPnbo6M0Y&@81kc6xy8z{< z9sNoT<@#u!t-T=LD;8&yeHrRMqkntba6o|BTa|83v9l4i54`t(04#KJ;^&*BZ!qr2 zW_Pxh+E}0J$ZCpxLf7L+y5Ay+5gz=UED8GwJJes;-rZM&LUZDjpvkajF{k#DqK1f= zlr*l0q+bs8Ehb09{efD>(ZQ{Z21(c7t;(gOroTq=l|3m9)995Vad$B8*^(zPg7-4L z2(uwq_{`DHGCM0HX|BMwES@G(Pq-`^+S>bish<};3tJS`e`M@u<`r_sO~eCqgohlf z!^Uft_5*alT)HGyN8;yInZcS=<12|{voJt76x<5(SKj!C{U(gD4dgd-pAnWb{pjT# zbk8=nC0lj5DMuUdL6~CuTa7A;NGUrYWE%~FRQXa#|AM?+$R^_Y_n55sEnSY4K?q}; zX&!YyASps(IWH|69H@FS3kt4LjQO_?nGFlqJRu!S@l{(@HQ6?Xhut8NY^~-ZYkP5( zHb1?_f}G$5Uz&RievcWNPrnbpeQSd|Z9M+Fh4FiNESH+H^I#4#rB87IL4q%wU5je> zKr50lz4%H(fXw<&{KUv77s1aa<{SIUn+Ru8Uw6{4%?HHO8XW190ORv$R=--` zLUnRLkgEF-@b%j7H^DxNkv!2~A(WcS$r&a*aekV*;EF-r!qh-d^zEe!K7a~L@uR z9PNtyt#illa(&gjW=_5W^XdjKeT-y0eUFYsh;U=q5@mF`?G{~VSAk{hy_q*TJ_GJo zmeZN+DmJL_8-xT8yn(CzE;AlL{)SQ$SaF$$SS>!jAKj0voiL;RBXv*P4BeHeWC|=V zDB+)8%^P|9_8v!Of=QV#PDA&}Xo2R@nx>ztwL}AWAAPP>stsHDmcn=UMuFq7 zS^G=xUDs@#BzcyAto_PTg| zHG2)+imhcSlO;kS>7ymSqvjWnMb1_Ac)HETrrUXk)*xku!%+jUxU@#>TIus;0q3}1 zG3?Wq>OJO})N1>0KFd_I*g4qa2xq($U#?aR5s-cMCG?RQ3GhG%;0Ll~0o@avOPhqC z(PQEOjNp=ELBgRQ*>|=oUBKX{B|?fm4||a7*b~VdPcAaYH&3E*ip4e7m|yV8nT}MB znY6k2r2?_y7<9+8_uXW!p;s51W|AV&)(>{WJ-RaqEop*6sPaBr&&3l?OV{X3j*Z2c zlnwvTVIL8*sM-j6H-Qgru(szHt}~+kP;Y?&nCWN+>F7{~w=LA^c=2Vb+Qa=N=&Ogl z)jjZqY3@T{maBDHdplrQ?S%E%PWqK&+qz+~HS0_7p;nUJL-+yhy*MFV6{1*i|?-#b%T-(YPAX?;?cvr#O(n@e#Fj&yyJE&nI+|g;SRb2(lHPu zbxQKRdW(9y1{FFF*IEI-evSu!ES<1Nxzcy}Fw}&ljcB1B`$WrBbK~RXN&DsC2UKM! zRA5(^VnKP)C#=G$Z|Z7>-f^c_2^;(%&SZtg{y_3|AHbJUZHhdh2Pfp$TOJ?uY0I?bHc+M?-jlo30?y=AtdNkWfeaMO8{_K8k9_XUjai~{OhaL z6J@3S=cHuDox*QB-Q8ySaakbJn~U))HrmY$mDqT1tB|TMk*zPLBogKISp^f|wP*=E zCCQ>53Ha0lW>PAHpfbLw(-f$2gBy2Jagoi%>^H&<7$Vl53zPEqa0x~Pn*5~i?9>bw zOv?S$+W6_XU@eO7)zmug2C#noHDQnthB?9T47(vkbe^(yL-k0LIcb13s+?CSbCv|B zh^<R;m*Mkgr}Ro~S!cz%n8Hk8t3@~95j^GS_c%O{+iN|?JlH&)XgYK^E4!nzBE zOUi7nYVWA9kW)X2rb(aiv&abs1Yh8H#gB1W61#NVZK{F85)0TyTC^En2prI#{e=e+ z;CATV{Bw05*>-cDOPf|-WM&_33X9}g;@FH}KylkU0uEt(VzzNc?^L+Q>c(i{Xa6yVN zoPr92nsW5w_nzP%Q86`sSi~JlmnH_CjU_b)0f?e))nF%R<;jC$F1lmO%`xj5H2*n( zYXChQT$SxAY3k6@>1aVvgX$YAfBvV&96hnK`;!NptQIc%G$H?~pgYdkuZBnfbVoQZ z{X+sUeX3)okIux?ysK>=eKtcwES_6$;j)xC69h0lGS_3n%@RRR4Mv22pv{h0E=| z0)PB6RmPZg5QbDd)DeieyINiK2_3gxHHE4PEa3lgn!KKr=+gdb%G!m^?2C1FJ0}zP z*^0~Zox4G}KR;VC=mR|TS}m}W7aCS>Wu!p|6sj2M+pgJ6!Ge@FZ79rMRa^2;&14AJ zmnG@>_AAVxdWUIVr{&KGU{+gtovU!pWj9f`0E7xX4(c+rB)Z(ZtXd8L3RLbV{g@~( z;G5}&xET4Baw?d5z;zBX8eVCe0(Gb-`iTovJpu6$B0qDYZUbRoM8Q!fK+Mc@w&cx& z-@cdjK>I^W7Y-fgzA<)kte^9~@3J%h(tAyO0S9!|#&8udVnq3C0kV5tf9hV^#7?oS zUqF1(b>8?m9L7Ej;D)JdLyJ47M4D7kuXhl^#wT2ldgr;8E~+goqiWk_oWOW#XSb^~ z@nAwwemn=DsbQoeDb(lGgY=SozHg__n7lh>?%i6T*F**_}$#jB)9wwCIDeqc90ZcYP8d&+52@c4+ z2+Lo5R_psv@8xr#=R=Izp%qVz;33cMe8AvbWy9*f*uf9tO$~o><-d(~Wm{)sD@@N& z4@L7emzcCf6H8z51-F&i4^hCg6V4^S)IC(Z_Vgr;?YiD;n0K!y1)7ss%akMll2Mf4S1v&jEF{)!omFkSF=D9?GR$=h^UJHa zzQ!lgt*dKmBmXMPUA%&BcNUo*(leBTf3$LEQf7|+N#~;tWQlBjWm7q_)V`i95Mrf4 zjEJfL9Qy&a_UegUwS!k~ldXVuiE-g1n!$X@ux4&M*{hgk+~djM@XD~{o5tOA1hA}h zK4Ql&NQ!%hI&Jx-@>(sY%*c#_sj6`fJ`KY1_o}jH_ElW?w^Z0;r0RrC)qFGN04|-C zpi-FXUESD-i1E8x1~5P&V4zB#8@BzVuz3$-&y|04f0Xs*+=60UUFo_ngXao2H}|a; zb0622Z6#I!0^5{$`^yJY__40FVP+>+U?o=ZYUta`&!s-wwm_VDv@}^l7pKWuSH_OW zWWC*V={SCTePd(eKz8bn#=V3jr@eB;t@(yf;5Kfj^q~;ueV;133dUEyvN;@DzrhQ%_9l-ap|0NtF_gO#W6-9=i|3x@gc^*y+9SvjI=y&0}&ombvKPWs&r<8hn)7mkTClEPOl1J5Hq3X52z@rV|~X5OqMV z85wH`P$HRlQk{Z_Mq13=98-YL8Izp zZ|0O7ligl~)9p?*LKHf74)Br*l+6bMlsAW>?;V^u#OuNo4~=+BECVN#mGTJ_K9U(3 zZ%gA4WUGxTgwnwqqfs8neOWf>%%gptV=?K&I5yJ2&+NdiBS3S%1S&f)B!D)OJYPJP z)UgJ~{Z-3MYWt|LeQ9--N{Gv%DJ5(Aw-%i!aOUwDhZeU(SnnMxaQt2x7x9fJ8CFro z^Hxn6bSw>IYPvGxDU~inl2T82;IzwiLU|qqlQTvw=*1G@pya$M3Z^7ynRk_l>gu&f-RfB@-!i{wTKrfH>+AOZw z8+7y~Yu$P8%W?Vv5)W}t-H8NRL-J!oudU#ul5VVu4Qcb?S{c@oETVodZW_uzWX%Cq zd$gV+@V_46`Sgo-e)^^6Imm9#Ftz8+q}&nrzR0l#x!hadPjP$}XSA}&*ZzUpjBout zNfdVJL=e4uI%c%mcFiw}4EPgf0@j%6p1*s^Itkd8%mGqi_2R#{;pEoG3qj8v=l$Gg z=S5?lmmHkUc7}bS9of;?P)}(u*4?RqNp7b|F`EBu3AE@H-BtwFjN;a$k-|pAo9$fY z{>{DVNs5}aA2~vPyk3oP=th;iGN9sxc3xe1e=8oa$+CI};IM4*?um9ZWzfmQg8RqV z%iZO({pFX<&ZBI|x5)7n8l%dq2LVk#0hg)=3l~#0AW&)J0Rhxw@va$Sh}Sj3dnaFl z%yWB+ztVM1SBFh#SDed>AzsoU-syYGf(J4Tu+!x44nux33{vk_t!}cSkL>A32MrZ) z&i7##jFX|wX8_ZKuNwU29wxxZ7CPL0XWAiFK&4B^J>#f(7%XZGzTQ#>>M zTvAn3*BAVCI~!(Nb;DfWDUq>iMqdWuKv;lN!j?$iaGhhR_EU3vP7AM&fA#3!gT*Z!^J_qaU|%mNo_g8P1L8 ztEp3StB~lAgRoTIW4LsZNCzNqPs%X_BrJcHW9|t5={Ws;XwV1In;ao4xYUdCGx~yS z%u_~=`q~|o)0HA!6V3$ z^@dYzH*+!Ide^(fGVcS}F+pMxaMF0m2I)7b6%Qxam+~#K%}!R95N}`XmFK|V;0h|i z6%~`itv$-go!0zLm#rk~#JK4b1!(V|x?lao@-a;XbUc%}g^B}ivHaWb#s}CPmku|n z_PyRT>51fR?rj=gw^-ds{#JmjyLS{Tcx1KH{{iW*A^%{ z%CZs|)o!67TO}Z+GQ)rARr5DV3qPQ3W5SdX@6lx;GvUVZr-;(6M{U5OGhV=G?pEQu z8`F{aNU9HJ75h!%0MCBKXufLwPWN_(;Q5x*=^!?1aHnK2@ z^y+w<=7*-Ls&YKNi0vXs1&*ReAjs^S;No$vQS*snuSIYq2{rTW zc1=V@xHW#c^^H0+?Bf#r@4cO_*KW=~1^zVwk0QO-7XQ!tw2n(W7x`Ro#K;u%)`=!X z%Cc<*%1Uwv!$nIS9HG%i%M3Tk5p8?4D%~@jfQ6MgU`|rN791*J{poN}bbmF~5iktD z+uCcC*!Etv;bVHCz%se+6M;FjcS!+#dO==~lFFyOgQe$iww6=+shdkY{&+RDC6ub| kZ|>GCjtQY3k=ScLk8iQ#hI_*S7r&NT4<03b;lZvX%Q diff --git a/planning/obstacle_avoidance_planner/media/obstacle_avoidance_planner_flowchart.drawio.svg b/planning/obstacle_avoidance_planner/media/obstacle_avoidance_planner_flowchart.drawio.svg deleted file mode 100644 index ee067e07b2f1a..0000000000000 --- a/planning/obstacle_avoidance_planner/media/obstacle_avoidance_planner_flowchart.drawio.svg +++ /dev/null @@ -1,445 +0,0 @@ - - - - - - - - - - -
-
-
- use previously -
- generated trajectory -
- when optimization failed -
-
-
-
- use previously... -
-
- - - - - -
-
-
- trajectory -
-
-
-
- trajectory -
-
- - - - -
-
-
- Callback of trajectory generation -
-
-
-
- Callback of trajectory generation -
-
- - - - -
-
-
- Generate trajectory -
-
-
-
- Generate trajectory -
-
- - - - - -
-
-
- trajectory -
-
-
-
- trajectory -
-
- - - - -
-
-
- Smooth path -
- (Elastic Band) -
-
-
-
- Smooth path... -
-
- - - - - -
-
-
- trajectory -
-
-
-
- trajectory -
-
- - - - -
-
-
- Optimize trajectory -
- (Model predictive trajectory) -
-
-
-
- Optimize trajectory... -
-
- - - - - -
-
-
- trajectory -
-
-
-
- trajectory -
-
- - - - -
-
-
- Extend trajectory -
-
-
-
- Extend trajectory -
-
- - - - - - -
-
-
- Select object to avoid -
-
-
-
- Select object to avoid -
-
- - - - - - -
-
-
- Generate object costmap -
-
-
-
- Generate object costmap -
-
- - - - - -
-
-
- costmap -
-
-
-
- costmap -
-
- - - - -
-
-
- Generate road boundary costmap -
-
-
-
- Generate road boundary... -
-
- - - - - -
-
-
- dynamic objects -
-
-
-
- dynamic ob... -
-
- - - - - -
-
-
- path -
-
-
-
- path -
-
- - - - -
-
-
- Check drivable area -
-
-
-
- Check drivable area -
-
- - - - - -
-
-
- path -
-
-
-
- path -
-
- - - - - -
-
-
- trajectory -
-
-
-
-
- trajectory -
-
- - - - -
-
-
- Apply path velocity -
-
-
-
- Apply path velocity -
-
- - - - - - -
-
-
- Manage trajectory generation -
-
-
-
- Manage trajectory generation -
-
- - - - - -
-
-
- path -
-
-
-
- path -
-
- - - - - -
-
-
- path -
-
-
-
- path -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/planning/obstacle_avoidance_planner/media/obstacle_to_avoid.drawio.svg b/planning/obstacle_avoidance_planner/media/obstacle_to_avoid.drawio.svg deleted file mode 100644 index ac98f159b50cb..0000000000000 --- a/planning/obstacle_avoidance_planner/media/obstacle_to_avoid.drawio.svg +++ /dev/null @@ -1,205 +0,0 @@ - - - - - - - - - -
-
-
- id: 5 -
- v: 0 m/s -
-
-
-
- id: 5... -
-
- - - - -
-
-
- id: 4 -
- v: 0 m/s -
-
-
-
- id: 4... -
-
- - - - -
-
-
- id: 3 -
- v: 0 m/s -
-
-
-
- id: 3... -
-
- - - - -
-
-
- - id: 0 -
- v: 5 m/s -
-
-
-
-
- id: 0... -
-
- - - - -
-
-
- id: 1 -
- v: 5 m/s -
-
-
-
- id: 1... -
-
- - - - -
-
-
- - id: 2 -
- v: 5 m/s -
-
-
-
-
- id: 2... -
-
- - - - - - -
-
-
- center line -
- x[m] -
-
-
-
- center... -
-
- - - - -
-
-
- ego -
- vehicle -
-
-
-
- ego... -
-
- - - - -
-
-
- drivable area -
-
-
-
- drivable area -
-
- -
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/planning/obstacle_avoidance_planner/media/optimized_points_marker.png b/planning/obstacle_avoidance_planner/media/optimized_points_marker.png deleted file mode 100644 index 456ff552654ab2cbbf71e4e3829923ef165959c2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 127072 zcmZ^KbwFFq(l=JzTA;WUN|9p4-HI0{xLdH`!KFCG3zXtPiUoJKV#PJMQwXlb?c+Z8 zz4pHM%O5An?Ah6w**UwjGr#jiRaq7XlME990Rcx|?xQ*a0xB2*0Z{@S^_h~x%6#(t zh2knHuZjNr@kO_Yc>Yi7CavS9;b`UNVd`Ru0CaE!S+csCyI5K}xLP~99V2&$KHtP; zqp9O2c_7Y0+xzP3nDhu=3ilgNg0xoLfrNR9BGBSV|>qgKvnRD1k-(-y=k*m44+x^04VHMH6#b{!W^!9Lo? z=kQU+%94mB^;<8TP7}BtBa|WZ5nr&wb5yN+or5N%@$&J0?1|!Y$HQVr+eR`vZ3w>P zKQ4{fw@`AL5KjSz<>ub*aJ-6U(to!7?Jl-2A%c>v4D}5SUdL@$<^QeqAFTe)boTS# zI-sujT^Zuy;{KlwU;k=7TJ0D+IywUIN&S20p0^3Avj0v9!QUW@|F5Ko+0HWk2G8r0 z_5a4>x%Kjr_gUVR|JM3nMu@OGTJ~7oT3cI#rvJNj@HZ0Vi|BfIJf0r?+&w)0k8x6; zwfRqWf2nWa+TgIfvECi7y^Q@I?7n}Jq@*oxIy?le_#C&DIE4LcBJd?66d7`2|DAwN z+rvZiOq!i*Ic^{7>gxL6+Gvaaja}8<)p1Qriw|t%KRTZh{dd#-r@Vg|IKu8=rc7Vh z_xj|2tIzVc@&7}`zl-!=NV9YQADjOr<-fVyv!-@`6a2rB%8NZ#{k{hW2mf!=R7CuL zEUj^MybAR2xcWbWn?)HDj~U1ZI5o}3-GnwJJ?wQP4=enq@)cfJ8?XUkds7iJmrX!iXvp$~9lHXOz<-EpmfE(5YM}j{$j#9GvwN~4){N2gTT~bJ zz3QM=pa9Fx;{5#j_oplNQ?Wl|bz)bW=a8xzr1mIO&?6AoAp2AB-#6M;)2-xcO+wT?vnt%-une zo6dhq#D7-(mrlMSe|hT#7#-YGax5Lhc8)a_s#bzHJ5;3QyTV&%IwOr#?eAmE9U%lO zhhrDbyfD(HbZLtOz53^TdQ$$K1($!H@%ilE{I`eY$SXYdo;eKBPb7f*rqYsPO0eLNzr@|$N-ZLjTaJ473UdV9?km^cPXta3T zhe%QaR?FUs1bX?`I2-%Q%;1p5F#n$_*T|2b1I9W!_6q*8VT58W*~`p}hR3-K|HFo; zw@}Tf*?_$DaR1XQA%7cvSV-w%b=3Wzw#}=6W(G!~lI6p(W{i;p>K3fBr_wE5_DVbB z67QVl$s43|Mb_GM*iK(ReL|=VIES|)HKh!xUle(qs~UeJi_D>0FF=1g^s<7DW%h*=@si48 zr{VR|Or6i;+t{{d_Rptj2q(FBsoa1sCHs_RD1nD#hYUqNE9R7?Azlw)ss|a@24W|p z-$oE{2F%>|F>334|LJihz+f5LFp8yl=a<>~aJlFU7g{w92!Q0}(IH5pdmhg(E%lHD zUu79To_*I|Qh%P|jWfBT=N0h}@%;;gr@$wtUe>>x^}D=e=J%^}00y|-KE3@@(Rp?G zRLRMLcGW6-&4HJZW5DW@0i-2vISw|t3Osx|3a+fRUluIYEnvPF=DmD++-R^p^eVU8 zOkYKZAKmF*$s>AQ_zb%{o?P$JMW-g{3~j2sR|tfs3G>$XvHq6ea-3%JMHTI|QnhLzmRblhHp_7`Y@?AD;B_YXk zylaoAsOB?-GvHI+@xuA+Q;p_FOxkuM`stS&WdE}dZS0#Gq8;c4KwuLsM{wzxrc#JD z_@Ko0X~4z(%A-${Z4O!uMRQnh3 z-|NKZJcqijhyLz+iNAY``q_bE>{9@=2+7vS0|1}+Kh~GV_mf2QJr~JMV)T%EwvPLe zr~W?HM)0{(ST{u(j~Xm-HnDxuLJh-0fpBL<46?<4At+=_^huqxSes-NXrlPWM$?v#(@+X^NH-5O%1|E=m zc+dB1L2S>_ya<{>+{EmiLj9%!*7_cfpV8v{8b(6>FMWL-{l3A__`Fq)9(pT|4~!3J zJx@XdE){?}vjzE=e-7D_JI?2CKzC~+QElV_RW;jb!fN;SaI?jyixn3k|NGMoz1Bol zA18TDNxf_aX zb97>V;_SF->BsiSa@pVJRS4wa4HJZkxYZ#uZf{Xt9<6TH7#lX0jR`*LK4rldT6Z`{ z_2JT29=7QPvL}{+y$n5|(%a$hxZo@gu@X}(yLvAz6W4*9(c%vF+Xd+vV}iYmyW`f2 zSytmVIPndW5jhCK-D(FM78T|?w&}H4IjY_wss=}Ow(D*fs(p1JpZ~AzzK3OP$V0x( z=m@)G=tyepl3X@gCLP5r+dNw0n+GRs#9`T&|Hm(XFsOW;WomTjz*_rz>r=_4AS4~1 zcwFnF$n{1fxeF;sZmlb^#`tkppu#Y@V?qC(?Vk}vM8z=6)YoU35WUKcWSj1!3Vh6` z*UViK5i#w|vx9@CR}qmJRT(2EDk_=>jPcm%e#LYA?)?QOkmPRP5TvE;8LAwq$8KZz zdmzET1;*o>$z0v{A2t3Pvp>M6w;E3sDB>*AW~^W8tn(``9;~oALnUAS!FDXrUOxD) zoOS3b*IBjly@}05DYTLId7l5_>z+z-u)z|Eqwc75>Lp9_GvKE|I?eL&g?I+089h}@ z{f;jed@U7BES>LM_x^l$8R@+^0ffD)xWo69^i}$o5hG@k|5#!;`!(LYzQ61+Q>Wlk z^bb@|EBiy4!2RWXhcWb`K~;hEA$=>r1E%!k?UgC2W4zsz(NLlNkk%%5XLRBEYJ=x* zQQ_>c$~6WWg#noBA5l}p_r8$^47}CeB3gonr+E70E}H&)NDknjU17;D&3QJ0YnL%& zS!yrW$b8m|zp6y=5ddkx-njheHuZeh4^Pp|UQbY!&HR?jhqKv7ly(_5?~319n5TpB0?+%Y)sZWt zP`GW+>hC5z%{Op|H@da6C+?qKI8z>9tcW>sYF(v<`&DO#W1qd0PcS>kU1YwvQuV$$ z2ud^US1D@WL&e%%>%e9EK(W*e{=M?dIq~0uf8#+g_N$%})7#&#=^k)z_*E?f`mH&7 z7?Qc=(|C}+w8Y^CYb+)Yh|#L7^3Vl#DLU&g)_z#iy~l#yVDO)SaS-c2weDED1FOpI z+<$8tbTmNR&LUhqJx;F%@+z(mLh#4l{L3?ElijW`Phs9!S4#tVAS>#Cbf0by#)CWT zaH$0Dw@MnSn9>M@UpjDXs~lfUTM>8j65Mqd4&M2?{NNn?V|AiSL9Wwcz{D>wj^DY{ zc<74?O2|QPoBy0f`@6a0`xRe$p8&xn#FjAXfhpTvo^MPwApP=qVBl<6>hKJoLSCJ{ z9_x=}vbX@6beC_|2eO;q`Uhw%0>lq>D)lg|b6?xfx~}mJZAkth`g`{Mhd-n2tXQ-h zR3TdzqqlAPGe`RCZSb=6NMSH%hIm!2V zbKtKx=r&`;IMUg~@r*R8gwRD|#H=jFFnMefQL#Z)YjM+YMoT8Y!NlU9X(2%l2<4w6a|43uN$~U_zOS!nT*r0L!HQq?ni}G^ zWpCNEy0(M!^TPf)7uvk4WXOYO&^lM}enaqF0D*5x+M_n@(=H2eYDLL#iS5M_Mr<=< znq?H&mlCp@4ntA(r0y=2aQ-Dt;T=;ShQrPiuyOmZ(@l@!lzTh+DYJSFYqYX5xNqMZ zE%c{#R2l<`YjgL~usesTxEb19YFB(e$gkQB+pvJdyjj_!jOYS!j<8m7eB_`nhxhb* zQ=eCyt3&aWK9jT>gd<%Equ@=*XOGx<=g`>~f{2zZ1+uQKY*pPzlAS)XoEMDx1d=qA z{T08_;3q4Ij=cSNR4;y$V@itW{OaRqY5Po1)N1K!YpLXv*AfaUnu=5d$dD&<(fKXv&6~zAYJ+Em zrs-gMnM6wgEu0Cx93tzo35A@xz8124@%@aR=<&WhfPx{DWFpynzrL``V{sZ)?JD!; z@{2*BvqqWP>nNa}Ppy{Deo;x<%@T4yHriX+ep3DP%jqh;@=L}SGW&HEcrMcD{x-TN zrZ&sMb`^(a&gAqtYo0TU6}CZ;%VUI8gF<;;Lkl;w_EC&4QyXTO!mjo;nW-6)Ti7wO$H_cZBCmi;H~dw4zUm z1B3vgMwijpAa8fcG6Jd}OxNP|4MV=d+uLs6H=*Jzb46JGj5)E5GJgv$)0zg9R^S)u zDC+;S+3YR9{Ia|wh#K>O1T;~DZD?Ul*%9MVfHBjjtRkYKs$d?|wSdAiL9)27nz1-{ zy5yF{LfB`?2#KHLcE6v+NRFoey%QflM>1^vH&+ex87bAmnfM2jlz)-<$Q-spNF zJ*I8hw$32`P#JEK&)($|N`)O23xi3GE5B`&t@!5h>FHJEUMV_nsCvINAVDPoAjSoL zu0YIJQy{1{?>HHbq#Ud+aHl#pbbSym$FABm?0p51)_Gm>M$;8P)QrR0R?oYz@)|sW zoC%ET?9xfYXMA)u`U;PXQHpW6ECKk8(z=h^NvAPjhhxlGql<T{9Ba4MnsVH0kEF-^DT|8N$e)1rp1+_7DxCn1wut2dJF7Fo@$yz?-*3xX01hw=Z`Wwpv4N)Sc?D9(ea+m*3=LtQfLu;Q zj_Kw>@|_GJ>k+w?nl~x^v>YnD9NjOeQB_pQ{NRXUjedy_J-OQ&!+%oxr3Xx0KB5O6 zF3UEW4VG;Nh!lb(4OlV2{|Go*>&u}oJ9gS-ZVAYz-goBY;V8`E*T_m)G4jAg`kI$E zX=`vyun7i1??57H5~sMDxD~5>LeJi7uEI&KL9%M@etL}laM_gjuRHt}UnjzP^tfLG zi3CY|m2H<>kn8$hmRJzR7ceozWL6XLC=@gJVxWMR>UuRKKuiTZMyvtBK8E=U)~G1z zJ<9#LjGL3ZpLAU3_ZB!s1iHe{n)?K10agguGE5%r zoY`5Z2AuDvlWz#51T>Ofv_2HZ?)AjSagPclsKv-{P?dc7QUTJ*@^$`2eC%kd{!2D; zgimoVk5E+;O;tJFv;kq6uzmW4g|6fYRX)$w66f6b8j^xt^oueaz+Fl3ogkI=3d?aL7a&!=_GB!uj8>ROe7cZq8i!*b}xoJHYuz`&^&A5B?pap2! z8mhGDBxpv;$%_x0O!P3QP)EXiZZ0Cnv>^&VT>2dRY7y1b(cHr;k&wyK4AwKr^~##A z44WH^;-NcoZ<)QtJLT$`J0$tFUjeU49pR^ct(o}6xYJXVvV8l!rqh(y>u{R1es>5n4 ze8rKCV@)WpQT8&ZusqFlHK~BPZKKO_iwQ2K5LO}5s^*RifOqpHS=Mupt+@czmOhZRvdXMD&LR;t1v08wRmz%ol`kV zjlnv(G6;^|YaOar^nTFJF<5?>pJ^z|GYGY1_C7fk1{<0W3P72wY&w{gCDamLO7)l; zYGfV|NM@e|RzvwclO)nKRvVQ*kT`8Hi^_-n?xx)y)!$j0cL@l>$m$MxB9RH}N{o?6+vdEEI0Nk+XyO7Bg#D3@2lo@XWlCrdkVm({%~gx#9W%6Zm8QEp zyk@&8Jg63OxqD-^bfMGK>HY^o)vVvccm(xmcpE2xJd7`OBZ8;~n1iM;1{*G7x&D6U z^fZEufOHdJt%Q<3n1Cf%l46Aof%XfZXoy222NBX*%ei3)dtpnG;j-q_&Xg2aSr#3m zFPE>r&K^TWn$L`pc{4O)9Et+4V$5wOopdxo?VPWK2x-fPC+^)?J9T z$xEd2dN6NhVgW|YJfSqUi&YKA;vy++lJCBL@*0oFG2^ytw`VB^BEvf>ju8&$sH9)q zfH&OmSK)E4&r#^CJ(sW!dX-)=rPa7~uvR4ffU=>Ax%cw7!&Z*Ma?u^ta?PFhkczWj zmn}R}=AKxOS=<{~h#g*<)c&gI7k-TbY!@jW($0D+_1lHRX@<_wmBjfHP z6r$xe+H-?6ot&J%ltdqR$Oojde|m;aM$y!?iDF9cV&C-PXu3p0{XB3I=%q_^IDe@A z5Yz(Nlodx}M)l2MnuCZJYN*KqzF>#ohSEtjhgz_r_UbA{YNep@AO&`Z@>AB zv1Bl}?NM+1aUnOjHz;SRb+v!dJ+9;&CzcCkR!7sI=1);h1s%lW${y@QBB!qt40Sy2 z28?7D#$8_<`%`wbu2JM*TelS@f7nHx=^HCbCqwN`a^u+8o*-s-ioUXPf!u^^{Vf~`(91pA-9C&#hN?YrrcZKC z`CSZ{zV>#}92EFYmNBDPgEv(3mxzj)&28r=RGQ=q+@^S4d6MGm7`86AS*2ej2$lME zTkyPZlr+>}ea_8IE8aGEEMsz+m(0?yubRo{~o9f`qVb|16@TKT$2OFJca(6d_J< z)Q^Tn;B7UnmGu#Lf_fBMmvyiL;piA=I|H9nzo%xFlezaWe%zRAkk&Lg`H!dVj{bm0 z(nsniV*{?}47{oj!%b=P!<;18Ub#fOP6Wpy5c>}41o|bG4OQ1}v%zeB!MmQ2MudNb zND_38 zT~a^C-97rH`nGq_&^C4$vgYx( zY8-$=KNA#0FW(IPTsNC{6@CP0_``xXBXFE{X*|WUiaX1Ks4>e&d4CpiY8O)O4KyTD zGk6`ojHw8tQd|tLtOaM`G;Ib9JJmNWDOa4@t{m#;r;RKUsl+m$Swv{N)~+D-*lj&hG`)q)^=ASD)7xJPT+haYH^+Fy=|*6d&G$nux(DHfuChm&O=*Uym0s+N@p zSSLKFe{aTT1#kS@1u|lKPm^r|y(zrU-PhFIe4-s;YB%2O70W8>4Gk*KJc)xZ8i*C3 zrY$gKG$~hb0Z3sBb?MU*$t$

tgWdctej&61~>(fOWm$y3}!xj4$>sp%9WAQ}EuLXU(Fmb;QJK)XaZ;R^i(dDLM0< z8T5=5q$~CDT_E7V-n$YAB@Gda&CypfpqKqxLUYT#1&*6ji`)$=G`jR``&&Q!S zB^&$esirCcSMiX)Nd#E{aaa}77>C#keR zusuT8CsN?MS`~HeoN)tLBJPxL3M9wrZ%|+_!VcXJ8?I=z`bmhoiD*V~@@W*+X|e+D zp7S2cA|69IgB!Q*h`4rH=lNW^!_+8+-Oc=X>I;=72F{3 zQ5uZKYWE6E#7C@Kcq8i&-(WR~@T9Af4zd?J)CVK*|vAQN(WO%3WilKHv?)kDK5w6Q0!PCg0}07Wyu z!i`nKn81flqiQ7>fuuIcrqQ%x)zTb@jQNlXN&Hg__t7pY+=%u`Fg#9HKf@&`f}tc8kSJU=zNFp=A!h;fXqJ4_vobyn=Y&EfA+D zUtC6F%6Y8VWaksH;qeQD!SY!Ep2*lO%g}9?^4)M44A}lqBZi|DaLw->D6O+16S`HH zZHzG~HY5ErvnMmVU=1F=V~<76EwRNC6T%^u%e1v8N>HX|ZQ0dbTJ-DHP$#qI40c7K zo9`+k37+ha88bq{DGYrF+}+nTyU}{@C|-=2;D@Vx`t%C^8wm>COUnTZJCG;bt_bvB z74B!w&zrUwV^()h!kzDQryN{ofEV%r_Ilki1AC2ZFhpD7LUMt`qIc6)fv`K@Rmb

oU!p2_o;|8j=0B?#wB^O={Q-me)B)6WB}EXDpH-$w zu_X4`^NoDj7O`a7I(DhWbht~1(ka~E@Km9?2SqNipKv%65wV5!`5aExPU5`I7XzXj zVu$-fX6YOy!WSGEq&y^oMG1rK>IHm<1J7x2M*TrqQYeT~n{+|3vEQgud5OQi+y z2EpG1AD9zhu6xvU_-PoU+T4rQ`Dx;&528tX9rZhnm(pP~_-VLf4kh=1Al?oUw}#p;&=#U2=502MUgwh~JgTZ4N-br6cbIA1 zah-3uT6QE}YJ_r?rn0iOv_@F>e&<)^3s<>v%Bp$7qImZw%tIf?a|S?lF>7pCpc=K_ z={Ds%tpU3aUpv1mTqpzVyJ>kG6Dj+@L zpv9l0t!GM=|3oqAB1{DlmHAxFh{%`*!KZG>WfW(M)D7fpE>X3Y`s!d$%`6Dqs>nT>4nN%LN5e=A3qFaK zb9U973ccn_Q`@DZN}sdYv7H?@o^s=6*`RnQTKN?e9|}6Ki2Ay~VBb4hv+?7H3jr03 zI-w{ea*Pp{6sYW6pIPzNJ=-QoQJS3A_zqzQIv7h0V$5l50*a!-z|? z3O^?z(JS@zpeYoj=3R7^0Xa>oyUsde6z&mg;lm6DM!AS{oovG?__AB^exn3BzQK8n z&ifNIg)CC`6j)R~mEr_*H(3>cDH(xL)Z#$68Vt z=C(t!ifzB7a}drITX%G<6LoI?aAI@l^+&Ru3mFRBskf_;CSM!Zbld3-M5>Z}r*%|2 z)q4fy+}YxUHk2CvcpY3{#%*TUom@UKN#`_EGv4}ID)X?n{EoIyAuH$Sp#OKQPs%SS z3u8OZZi@vBMxAo-;lg88{w7{>4d>+U-m8i*Nzyubq#uCOASHfsnS8$<^|x30^gx->$d2_=aW;h+?89Z#LSk~ zD!4+dMAapK zs3HtTywhI{!EfXdpoOUX0^Sj~8*g0vt3c|jm*(-bMRe-@%S)Nq$qV9d-u0Ud*rI;jKXt@L^s(q<}IH7@D)!J4){J9d^q#sgWKx3nBwBsvbsLT)qQbXLs=(2yia^x z9tKk6l<=-`GT?CWl{VjWitU&u4>G?PzIB{U=^@mzl#`Jt{L562mkrX$64!{TCZ=b# zBPrf{L5ypKz=oaS8Zc0~eb+l&-=RCoU#2vS&+x=45HurT*W!>^o@S-?`t|Kqc}KbW z(3nL)0FZ*cRJVTNh-<8j_(NL+aCF{vhIbz+!!=pNH60vq_w6Em74Q_ZTv5LRTE&4k z>K$w^&ce=kOAbx)C)wFNA60jek}9gE+v-_dwB22`yfS+>2=P{67SG7F!4}g=B+Nsz z>n+9LD%{loE94){sy-c_wqTv+DN`D6Mo2ra)%kijVchG4jwP`F1{DvpVp#t4a-^=~tt_!pB6 z?F0VFdHyGK1?NE{yC?yTabg1WWh|crXv-Fv>wCeN2#|X^UkcAZmsdrJ(I*eoIhU6k zmX8N{`F6Hc0iT3^nr1Fk@Sd}C9`|)cnF7 zN8i0V@x}QUs$pYLzVY1U_ZEmZ&f(nTSayluA6efr`kr@lJ)$2*Cn|c4Cb{uz#l2SB z&~Et!KVu~fU4&eXS}1xbbr+L6X|UU>_q_<}i_zg0<&DS>?koGfl~yQnKR*W!%*!8h za?sUI7{aSdL}C*X%v+h8T`P%qpy;%J!b&3-a=c#ecS;LYNi}rc5MtKGJvFo4A@v&rFR`u@k|SYH>+;~ak;&=_%LqSlW6a-iT?IxBULsUR$R z@A1AuAQ8Z>XHzq6FR9;K<4p~D!UjC8 zT(rtrpO>DP?dmaivTMf+yOLY~i~u$q4%3b=SOP;OyLu7ey6aPW$BF?BuJpaq&6I17 zZ|!Zni6!q#UD(1#M+IutJzsR8wO+1mQt%g!I%aN*rl|4(tWK};r*KLj1XbSoWiD7N zn?nMk16@r=Hg1EgVp9*9E`sBF?E!`Rsab&aBnAxm1h?-V+Bxb* z+_>7?ZH48~BYL}ydoi9W^+G80=zhPMAw>L;`&)@b?_Op#bNbynt>^up6lZ}za}t}F z)n<&%m!fyL<>jd?BPd0CX>NkOK4V4YPGD)ybk1_jZ8S6s**J`JzSC|_Qy(;kgY3&I zlFS2Vm&R2?u4ClHT@)@zB1K`6f~goMJ>ROhBS@oA3f1F?OJu2VJk0cjg7WBen`WJH zjNc5+GoAchzrFCych`yF=!H_0O@I}^NuR4Yl!_DUvF6q1F{EAO(tw2Wbvrv+ zAY-!%pa&-#VKKE6i&yX>xrf~354%DnTQT!JkK+3zQZ&VMqaSo4DAe#00gue_kxi!~ z@3EpZ0mXv?$ChPcq48ogY&|9gg+0=uY15c5`*oC0hBitWt*z;FxdBFqLFYr~(r%e& znCAArpk?|sQ_kr0nKXL&=lc0yP@sAYr&^;Bfi~Rv-~n@)rndt%N50yM(zml$Z*n?K zYOE@CHHgz((!}|#8o|wJySjJYTBWCwh`kHQ8Mu0*J~~=>C2RMT zc%zF{R(EP(zb*3EqHM+O+i~nRcO&VMv}{X|(85;9x_p4x;gW_zrfzXfEvO~d4Ae4O z+N>+Oxy4f594B+<50GH3>v}OuIV99UxYvkZ5*8FrAJSU~8m)se?={6k=%<^vH?_&D5e~yov5+hQAJRusm6gZ!c%&#Nhr>6Wz%hKM zH>X|Q%Z?lsBGyvnG|}~p-0`?HDECL3M>V_{<;Ak0^yEGL%;c*182B6wM;vtGX=*Gu zDpaO+Xw(mwHGYW*6m1uv$wgNyG+Fym+>{K8TuJOMU=0(#SYl0euJ`SW?)CW7F1pw= zoU?Uw6_b;^r)cB1zc{XgpjJztgcXuvqWEZPw_{N?Ti?`d9}} z{-uqUEr`=l+kmGVvhP}i2voJw=Q_p0LLSDjend$0VK9#Zpc^!F0xc_2o%WLWN|A%4 z=^e%y#y#d#o9W7;7K;(VLY zT$OQ?u8+;WUj|#XOC}s_E6XCe6f{gbxHSCm`eeC&Oyyo_dOlmJgBbmf-v23gfRe?$oql=Kjd2y+4|>BuG7Cxb6D`Vm%JxPnx(W4_SF;W@XH;aRD>_4D*`qz`-2 zh1&4ww7zVCyPc-OMtr8&^g*`A$2CaRo>8y)SoK?GY;^D1XUJxU?=)D@zQ|afy0Q*c z^FNWR6246*PY-cQZ-%B2aUMM9Pp0e4g{Cy$$yP-S|DLv#=cTBwX_Dtj=WGRkFMDt4 z$`U5MMSf)_^(hD|aN~E134v;SOTw;OEMIbmsTJWj_=@8@-r22f~HFR_T!Q^MAhau|Z@~Kk)s={?qyetp@#GamC1-RR z@Uw(Oc;6;Aj&LO3yM{<;I4J3NeDftXOC>G%%uC3GG_@GxhNJlt3<3ZgKXFL2aGH! zYArgnnawEIxBE5>y7ZYGsM*RGcOaFNx!5+;Fi0Tw%PPHkLY`*V)bj0g zQ_tc1FPUEp*pyM?%zRjsW%56n@RqfJeA^5RXQ_t5N$7_aqh{Q9NwG#fAa4P>AINN5 z&)eXf;;Ja9hUvF>CMSWy7>&)DQE!dxh*8^ux%a~wSE0~f1Rbx2i@tTfqoQxfX)v^Dfj{+A@m^%&K+?wPOPIya=(K5D zt4IqG>O#ZQ$n3&$XVTR#0U@7u-;0nkM$oWJr3uD; zR0j6a0v^`1u^mVl@Y>~##wOz0#WN3j@yC54%|;&|5$~j>lktA}$_U=2+&(st-Y-9m z9v?1kPBp=wrp^1VR@MTRn|kBwJ9@8v%7&a!_Qi?%Zu7jJjr!N?PUUUH6?KhS!)`s7 z-3`|Tw{-2CPtWHff=wR0eLPxg=sPA^0@>Un{8k`887Jj|h6blfEMn0`EBTAkfQMS% zxoO_a^{C?*kNu)vV@x^H6RSrCuPkSSLl4SmjjN z7pJB2szlr|s!V?0P?E*koI@BN_gb5Wk`*a@zyXyf>5(Q(WZ72f+gxdrdnuk6p;M(k zq}c(4P<`}Rh9#~wtFL`nU3-vtakt;%HTAyCb>?xVP6F9SsdF;y>*)lZ;(n&BR89Gj z<1DCRZUIUf*UtiYhsnq>#BsdkF5PhCf1CpKsaYb~J4$8seJwN%Gr55>&yn?* zH#J*r+k4z+6GK!2KR=gb2vwhtQ?W}ZLCU9saf=pw>0_j!)yX|527t}Xyz2BMUidE` zOlmktKKdtfoD2^@tX!zwHp~r6^gUps)>Pr-5UqW0^vS}Ab2LGNdgKs%5O5ay%~%UE z;U7O)KEb*l4u*$ZAD-SmE$iU;`RbQVW79U@r=g*(@JVFhX#(0vHYWL8Pa4yB2?lEj z%ZPN-)RW)Z!cnhQZxHphxSj)_;esgFtc;W1BVv9_(n2P38S^AlYt{i8WTf*q{$EUa zAzZ8qs$nRhRM@GZ?|ygXol%I8Y}6o{ng=^Rray(Xy;C7+OzTcGhrX&l)F%XlGGmqU zW)Qx;w8o1hZFv{|42i`E#GK<+x$YYkSy^~W3J`H>?YIgt_C2Q*rC+~-cWfLUKXGmb zBV%|N(f!YxQh$R|&JK@^b#ze|h;4<#ARG%TzbAgXD!U`!oG8V1@V~(p7Oa}ip;;X^ z$y=jeG+dC?|2)CoQz;**^lBl6X58)QLhv(@vuH?9zI_NKZ#AnGa(JF3;x~x1x>&&< zS?q&c=KR&-S+VV!J_S4EOhCyw$9phRx%+kr30mp?$Jvpax)|&>%xwJCCnp^&f{uIArWy7(2GU+hnZG7N~ws@PdgeW1!EudleWFQ11mIQ`I$sWYgm zrZ{;oqP`yOSH`AM_&sx>;41o9)V*-Vuon0rsx_-?_&VSca?^|d1vAt(tmI57xJ9)P zLxM_#nKVw@eQ9Y9`hiiO@3>-$6Sgfg*wyue9FsK+ZA4@bP>DaSu0NKh0^B_r>3HX} zbqf~8AKU_YcThu$F7CwWOuVPHn9H#8v{Sxo1UwY%Z)Q_5fVTdExH#e4L<`z?aW|VS@q4ILzF}v($V}W9tB4sFQW!v4Jc^WZEzlj^<$|Y z3ppBp=31{eO*KFF{SbqRyKb^|{!5aiYLs~O$oFHvN_1X=Pfq2@%$V~mMU2!H?&T6a zsR?kUq9-!M$T?CJ_Oo`aJ`;cUJRN+SIRkxzz}tT@)CsaOVlV2G(3aWxM$~pUVEec* z+wik=MnXs{7O^J{DTht5_N?;j%v=2QIWeIu)BcMG>z^a=h8@Owpq>YpwN{la8=Lxy z&#cadOlcqD0W!3&eYtWk^hfXi1RR8$EwPYAr!3O?1j2Pt2CJ zPunO-!|Cu#%_4s5RUu>G3k!U$o+zo$&Qi4}au%P;DH#H3HD0BztSRD4szbk}S9`}X zC1ro)aMQMx%wyj3Ieekh`(QJ&zu;1{9yg=aXu5wik@a-((CYQB;Q*#|yUjZ;4*20~ z^b*iV5}B)WSf-aZn2?J0ruNk1eX+y1-dExm<(u)Aq;FUHR*YKWTq(l`<`P(^+K46+ z3z*0nn_GJfj87%egBYz|p%BWPSPOqdn4+x|L!=pTP4+_d`uSl=4;-#uk?Z83E`9(c4qt>DewT|3stI>tHTdaD=8#!-oQ|Jj+y`|C$5=MF~UB4?{_ z`myCx&@tO1VccgGcK`kpC&)pr$!`@o89wY*L=9*0V#N>yM^PFu!B4X|X^xsfN^`PT zQt0v|T8|;j5wZDGCbjjv@}QIyCiAK|Yzx<0FI|HVQ;@`BJ0uUTKNq7qY#v2!w&sNo zkGK2XwK!iJEG7$L6I}vI<;d@f^}`MpUg#UPb!9PEjO^vBe|${&(MT^Z>{e`VkU7~0 zD>e^!KV_MxuBYu=6gg)j7cyvlEQlKk5Kc*(bEf#>MlWq+IQHU>FA0GPMM`=Hw@EP2 znttNwRR9fR1BuqLdfWk7cbUurrG-xB`TbTxmxWNy6oY~7;=}0e?0zwNOrN`-tUzt13&S;Asru(B4mso+HD&L2ZXLMo0`_f`7D0w)tYgi& z{V56~7NkHSBalZ7YV`Qea^jo@U-^x+VRDjV~jsyYL2)g<`)@JPFgaAg(SKM z4CXdkrm0n=IHqRP+t6v7r8Lrl;07~w3e|GQ6)`LI#ydQLM&Jp zflF-yJjYP4#Lri2$k-IiCnVwgBvQ3?y?o6uP1O+1VbIy~+IUo0@DLW&5rt5zPVF6C zBMzjEtYk7Qwzf46MSBLk5C(pXgpWSLv-pnb@M?+eO_UlvuXwv$?tn*P5T!3=d9@s7O zoa@l?orp{aYlt|)IUOBZ%$VmE{tS%H=`b;>i-XSQWgiY*)g|^6NSDry<1O)?EsW0G zw+40^HBtG_tx%braJnX9+NN^j>#8y7>gJe!V_Khr6s-jEi-uaf>VU|yH9a9)*O?O6tsvlVW9lV`X2Cn}V;QOr_RomRlWo4+XgCs7VaAiYS{EmC&PdmTu}uSkxw1|U`(8BI zehO{c_O7lbn;-o^ax20}7gbcUvtpDp<9ma7B*X_u`{n zL$GHkXwlU2LE?YW5&pizhuNArRR5vh{os;73awJ)lX{G4OiflqJo}4$k?61wc}E;4 z^(>KA&H=Y{LcP2^lRsl)R0oBon%w0ww^!;_lFFf|QAu0v4RR2;LM2*UB+*0)I(z0M z+sK^~)v|3gpPuT_p>--sSsdsrkbvJ~%9L~O_&9s^KH2YH^5GxpF7ecfNtBgYBbI5x z!(RVjMNH`a8_U5_q`Kd|T^sI=)8{7%Vq*91_fwAX&f&C(!ufx1fdBD{w&U#adKS3V z&-+%8?FOZfWJz?E@_vZ_4WDslwPYVb0b+9E=;|<%^1{?__|*HUZEdpP09620Ej?FK zXi*NGgYEUkBx0wN!{0I_PG38Ap}RP>pjyApTCRameLeSq}ci15Q$|Kjymus zr9cI{kj`Nt`+Ei3*x3n2w~`w^*5Z1#Y&);LMg~WPX1eCV6UE<-1y* zqw7xyY=*8m=X!WmS3f5e6ckAS!7}MYW`gfDSzg_sNP^U- zVC`6lr^Ax%bW0n@=6QuRhSv2adw6N8(&*Q@D#b%8)%>+5?h#Z}^G}S>J8;c~$}yI=@kRBE)-DZK`Zd!%4M^veFWn?i|J`D# ztWJblWC8ho$^ej9f-<$3B5F)lYiwd;anq8t9p$Bp+Mo`FhN z%)MEnFFr)pp%lJ2b*pVv2OQ%TiWir)`9PdCv`>rd0GvpiM#hYF%|qF}S8{cPuYy zT^0NkHHuBXRWZVZSP@h)3!CsmsNIK5y|lxNEm&_^7w@DV zm9xTgZ7wv!*}P8?2Nq&eSV4>+t1fq26FMqb+EyWnhy_HR6Ahv%WFc*$BY{$|fi%QG zY{IAXQEzYsmz6M^M>1eMuv;Nxl7)bXW7M%xPbVj56-W>H0 zA#-FQ8(UN7Gd4lZQlZtkNS9Yw^bBdZ_^_=<0b&JMajl(VxN)GVQ4K_C><4GzbQS3J z!?(LTG%GJLogHm-ew|e%J1K_V+Wf#Oyf!IzG9lG19A6a^NWxY4NZVgyP3KxDGVAH4 zO)EM6b1Wue0c^W1=6+5t(p1nO1SCGGBgW;VVup-L2NfWYG0wO}^eu7f+ee<>J;K6O z+C(NED?04KJOjwIn&KVLW8VCbY8B%yU_yeKW@QaS4!Y7*320QPqfDlXiKpNZ7sU6l zNW;IE4wc%gSx2r9b0yZOy>J4wRAx&wSK2%)rHEBE8k+D|U8m?4&uf_=&Y&)sRiP#t zj;7!g$3fg2hMgIU!bg`>+RC0Q_Rf=AYi2y|_H@MsUWo*FIS*R@na6%V-i$Ry)5>H_ zlNIidbzG@HoE|C1`n~(z9q50O-QN;1_{2FgomS6&KU_@d#MNT)l`j^Ka)3eN-m>^U zyKwxMr1`H7$^oNa4E-e6H~853>2~^$2BE9Hln ziW&~^1Fr}s&QWIzbj<;My8Nxps>9{D+bR)k^+K`Q=F(I2uyOKuf))M3x!IL4pTNYL z1~xnUY~oy-g(%L<2)gcu(yvHjvO_jIdZmV!2Q|_{Wc?a7uAKdiQ$)OirTKqSV3Dzscy@R5d~gB`$n3D)aeQt zTaeBw!vrBM5NtAY^h%VgC`o0Hi&4#{h-te7u4cOUec3Yi%rNQXWe+sA&;+1ZGRd{c zQ-WD_Nr)AtiE$vM*f?D#J}hh7>wBSuFb!ej;34paVRU);kU)2QTY2d%K{ zsE;gM=WvtDsFB$M+1&M)L0mJ3a7azhZ5uTvilA?)@YDJ&(Dcb#)%~&wvOetBo4Q1R(Ro#*1yoW%yQ2wXQJ*GMZ=Ra zQe+19^)G*HP1Pu75a-BA-pi1GAf2(5=^VV%=__2#q;Fg1dEF3nLXErJpQg@ko^Oi5 zck}l|;?-|<5Heb%*!2{qcotLg$_UqR4EMPoIeE0B$Cb`>rZlgmNNnZLtT%XEZYa2x z*jde`!Pe6+oVl9h2yf}w(4dM1teWwJ^d-PA{G#dt-iR8Pmdo#F0{_X+N0b|pR^cNM*#ofcR{45Ui6 zLID2#;}p1GX@0X0H~*ju*Ws>TzT-tvhZuaFUecdmH|CSL`8>Tv>PGPe_9^t;SpK_W zxkK=`)BTk3&HmDkRoEec!#JviJ(&Pq-9OkvX5j`e_ZXL0!HWVy+;aVXw!a&b$)t zRFfC}roJIW{g^Qr7BY{lVE*fS@RkJ?+c!3i?J?yeTSzi!_8 zgoclM{x#A<(Ii4GVICp__Qtzpo%S;`y4b2tn$>MqvJ){jB`Z?RFoCl!oa)FMPxF?9 z5x0otmBkhq6b@4sH82wPv1{#%wNNb}arH~3O3w`%G3zA?3uR(ytFjSYPT++E+7y}C zFcE+C;TM?SlB2+fTEwNY@fCGUi6&xyxUVCF*)ehp#ju7^1` zK{p?AIyu-JjaVa?4Xmb$%gU!z_kl@SR`NA9?jNt=V-GlN$4Pz1k4gH9T`xouqX_Nq zg#?ZExY@J5u{R#1QUfNuEvKLrXk5PEIFUiddiVmv>fmWNe&HN>`_p(BW54F8wu z_~;&VyK@=$x_G&J|NRM>t*hhU;4mX7AHEZI?;fCp1v03kV-#%LeqKIpLGvqX9->;B zcXrTWdq&E$-Yg&Y%xAZ0kVU!ki#F28}hmklcqcTAM zvNA-Mw{HjznE|ZtpW8rs!v>le*(~>s&=WkQ?bB6{2pgv@HB4)LhR!4E7t!IXi0a`j zUA;z;rnlrseI|(KlF&*#2N&Gcbgo)VtKYz@~ro&{Q zAVWfh>ndg-v;&?DJI_MD1MZw^&_=Kv%^wAGgt@)40x>1kUbqVrO>}yYT}f+du-SUVG?YLxvT_9;C{Fu8fUCbM)8mZ^4Z>7 zfU4{M@1ec!U;#wU{xgTh`Fz|IW%$H&?F zh5Uu=NoLC6EG~+|nNp{ar1!yrYi>A1V=SoP&z;u2)`<=c;-2e|hkRmFCu7({SFuL_ z-8k9yG|nz}CNV7SW@?mg7XEmSq%|Z|lgQQJ9kg@Ois&IW-AwK&m9-W}2VVHGBsS4F zM3^z+{zOp1ysOOp$5$K@Ee-=^jH)Y@$aDzH5b-CY={&k)DY5Hwdw|G+L#px8`uTREufQi z8i*jK#&x)dx2kdu1=hj+@a`bsV>=+@OA}a6%zYBakjUxAv$UUvCjmuQ2*nYn8AhD=MGac|7x1d z0;>=j|0%^U7?&V|4aaW5YWOc@g}Ae408V>j{)(nguK=182Do!)&1s8Q$uyp`j_3Ar zLFRA3YPY5No|RtL7$+}oGeN}w6ZC=#E@Y71@o_h6-R4D%<95 zx`lg+j>R4$p;2|n>BBo}#;=+l?#JpN(khBYLUm8R#-E7c+VKly=%-=ERaR>B%ALXb zizBm9HkHW!L|iS2vs&Jhg*>6kZBrX+qXapxgfO2I)@&|^$YE+C31V!=85?x-R+NU3 z%IgYNFeP=m8k|5Dnx-k7K(<6vn!Z|rE|R*wi-+NwSZg5l{obSe1)ThVHSD+^-OLyo zKywF5kU~F}@@MFf5M~??qtPw=WnIFe`tBZ=H_udYuM`@~AQCr#P{N>zTqf-|jSuB` z@MRSlk(vZ~DgYiZW9q^O$1BTgas!`O+TBu`1id&OTzO$7UEIbiAVCw8oS1fs;lF3k zTO+P;%i4Kh>;YSB#F}gWzSHX9$3^iwl2qyzl%SRSh$y&^%WvfN-DV~(_qQy(Ca>?r z-@?3WYwb7=(EpNbKz{xD_QT7o+tL3$jPee7HMpbT{hE$L%!BptaDoT_3sSO+b^G?c zt7Ik;$k+#^0cAz3wY~{9qG8mhQg7@ZI+s7*9SCG{R>u&F1qO^;>AH|mVR-%Lfeam|>W5t|H z2qs&qW_a}RT^*U8`D(FiwaC#*W$n7XsZ7#9OHyVu9**bX)(lzqU?v!q9QDZZY&4#t zWze9ETdhqW09#->bIx95YyzuRPgQglj@Ju1 zHiFZevECzQ_IuyJ%C5p*6c5vw)1A?B10~LyYtjT7qJZ=0(?p!tS-obnf_?oRY$R(R zXrbO1TjhGw(#;D*=8;md&hHXr<a07EVQtd>kH_`fZW=M z(aKg^^XW1D@bVWSxBg8t`}Hucjaf$u)cMwKb)rLdmzaC?LLnl38caZEzcXAIzPWjd zmgyjr-8HHCbxdZGr*6t(>?My>zRm1qo8B48O+B-giB68b+6@v^@||X~NSDRXU_z8D z@rb-oqCN>O#;AWG-P``D6K~F;b;OekL(?I~6>@wCXf*o~Ao5!CZ)o9E*(xZlrVyx-Gt?oFTU11KgQ()r9g{~BA{(!C?SSdNYA3AyVgLU81P zFZM?*f)>auwzC`1{VyQdJE~Zb-!VLBi2y71QT?8bM0Y*|-kOIyTJMbKImFwuD zE#15Bx*E3*0iDyREOllNG4h!^Th6vlV*2GV-HV^XAsJu7Vf8??Z+5D zvU@U_Fgu2rFe$3F%m8A>wEG9`^aV<8%cPl>?Y1-%iEQ)0KUWF-*Bt>3wBh22F=`is z4*&d#Lna@Fu-#Dl$0u=;HB~C`gD@-t`&eCE-iJ;m5HHYA*alA69dG2D!bj!2UcR7W zyq0Zb8(n3aKkdvc%`b6Rw`<0LDPb^1$6HzJO>=h0T|DvLl7Jo~5!a=ztI{+PMywo# zI8=pBzgN%tfnaGdoC++Ud`-5Cihn^t1RF}ax(NM+6itXjj3<}*Sq@S(-JoVim-XJX zLbGtv456Yj&72Zx{UO@?ary>~{M*+5^i2mktc?ay|-2+qJ>pIUtTKbUX^a z-46Pe+E?=_>$G*F4!cF}yvE@pqWoZI&1$z&$Ir7;1WhkT?Q7?FCtRID@Aej<2OPro zKD(RM=01z@#EjqkQc@O^DT_gH?Q0GJg#YtaM1E$*{qE99FFUVZqonKU(5_yC{PXJ! zoEqcv@ga@3OA0fFH0|T&;rn>h#6z4HbFW>#IM(I1R*y+~$Bb+1)a(X${==`YFn7tL z@V{gz=xs1XcH`M-$A3c!7y@@U_tp+&g3>>_zQze2auj^0M4sq5f>=JYfOo*~ecdHJ zyhRSS>~p|^A&DTYY4HTrg$m#Zi$vS#l_aBA(v|j`pz!L7VpJ&v|A@d3iEPc;z*?lv zd92vzo7QF85;H&4Sm;8**YI53j%_$@IBn zyIQ|)Gi*n-D4n(udnRW7jS!xZw=AHrTrm<6QgvyoS!}bdMB|gzGy<_Ct{=JslR!}K zS%YP8U4d&?hrc`9LYi@LX2-mSTF)0L}ZB5f_UK}6ox zX|3L988KwpMPH9+k}b{5%F6yaD;Z~$1242Gpfg~;*QB-iL?eM^^Rqse-zpesL*ao+ z9+A`FA*k%4S#{QJR*}dzx-R`(FT03sslJXt4>0(L_L}^PI+Jd2LxcbdxtlDi7di`K z*nxs#R%)Yp0%MbChUY7`VS=T|S|$&qf?yF|L?nk?5(G7i^s}*oE>-l-pH@5ZR3;el z$isHDEVH*$GRq}pRhMLwOc=+~95nZ|ke6WhLGm+Pw$CxcsEJ%-1{&Brbze=F)#|Eh z)i7;9&rXPM)&-}+r(}c1XSdZ0@YGENs8Hb0AO7dim^|=n%#OalFT_5>)I%5Ad_W|e zYyi*R*KwQ`#)B1hJ{+EjA0Ivo2`dI7r$oP)%4?8lmY`>F*qk5<&|lg6ZM6f3`2$J2A`e4Y5xAkyQ>ySb|0@_cR5Eak)%R=ZZ)-;>M#bRsMK{Htmn!gUJ@j`x|3NA96Ui86&@zt1 zliR;Lh7w>eu=XQV8FE0;fZ7>k-dPmN-LtOZr7W54xaQ7$(J427`*0|dVkZ_WtCeC0 z2_e3Q&I;(;*AdjF0DpM>u2>iu&@wj;VH3wOq@_|!fVS<99&N2bclxB>PahtDH!YEkWB*r zHh|KD1%SjFuf~Q7Qr`2Lq6WXlUg>t|AiopIkc>5=Qjz^cY9=1d{8jg6SsOLiB4L!B zqscwbJ9O6Tv4?x`;zdx&7fBTh$cvhRN#>klv6L{*lYGZ&1r3(^jdq#n027ofOitHH z)>mIaL@-#0!PJA1!Rf`4f3~Sc6VXMKNN0gE`w1RI4+TR8oJ{n;s}A%dkmIL2kcBrD zNH}vSXlrZJc|9aiA^z0&dTpx2r6@@duKoG}^gb6M`FUT7O3lrA|9xUHbotx$exW?z>$?g{9Lmre48f=m^T9vu>`Pg5CsHd3qkd))=PH%V}=i(KKccztNg{wtwy*-`mF z9qX!6VQrAF zjyk2C3$h(%!Wz~>m7Ts2Y!AFArcfCtL;FSiIJln21`4m=R+yq=CjI;QU0zs%Duf#C zT7pQn4QSRyC$BO+5nzJ{H8J7hL`pb}G zyUEWi6?r6PUV}=`N7P%vp=Y(RNX@b)-9V{09)S>!u|o1{=-LEc)=CGFe#JnAOC9^l z6X2x+p9h1+B^rQL2S-OHtm-QAxC9vJu=BdO3WFjFABbm!T_Z+Y=hkz;)pS$sGcXtr zHEl4dm*nK$GS8r8YDyMR{jl*mR|`DsXk!Cjja*btHGQZl0z@974dKI%2$^28cRdJ& zUv!wrj6GxzSJl0tXwV{~vw#!#0||+}Lscz6_Pw~Uh);Vrhj+l2HpeNNTOPaW#4V^uwa&%s8zXs?+#XY3Jk$J* zjQv{#Iz^_M-p06zR4JtDiFvehr#n87J5$fj`H%~Ur@+YQADB&8G3_}c<6}h}okF+; zAmOxP;`hN2Iddfv=%5FM2G_7hLzsoYNEjKTNpqzflc5a}6VVe3 zD6!GRQ;XpMNv2r$F7D0j4$4UMt<=HiqqZ5RSLec&9gDt0&GG((zp-0sq0l*&I;#La zEiVF_xQo+s-fVDp%6FVG_o3%33#qRom>MOxq5SzIV|Lcw7nQseFCu1|&;#~?<}&Oc zK{*Ub06~LjAeBzw?fi&7~192-^x zPHtX7tHH)u{=*0LQt#KX{l7r?UV(YTUbs=of2QUS`Ov9N4Pb;-RZOLdP+x1EY^@TS#<7O!|6^4|JpR#j8U2`y62?^hS|0Rg(fL1L{My2t1B!la2s8L1dyW1B&|#c^<*e4Ra9UBrM*tLju2|C(esZlG&_tb zk^tQ>mB`<7nq*3)N&T}qMpo&Bh3CewEX$o#3-E)3WnZL11OS$s*_X5wBNDE~UYnLl zZ0;+2Xpm@6Jgszc7+I%I8F3o|+!0yw*3$`MKI+~@)U2#Gl{yd%7e}zi=h~Nh)K9y` z0Ln>!Fx4uGJL0Kb6{>kBVAkn6p91L{Ctmf6e}QF0K#Pw?k1Fpt{_<`H`Xfp2po_qf zeE=nO2`Hk}phszX#u^62&Ch&BdjmP+6wOuLD>}>8339gfVKXFQgBm58WDeFNi2o?m z{MC7Ko_gwaV(lQcPTweB4NW-e65*Y2Xu0gm+mL?T>?^9EI@*@;GrSE)}H|Tw2D`*BF{#0FOsO3~zZL-RBORDR(eB_N> zM-4y)qus{866NXW+*zmI_9unmwiOT`*Z@DZNl__E&kxO2j_hD^@^hOohQB>A_>KSC zJ-odoA{fFafE(4BlEKf9j~#+7otg+VY*D%Zl9kV6ijpv~>sDaqG57e4S5!FfO8C!H zN)IsSo`2q5V{Iqae}j4-U-|ZEiMudFhMIq2_T+v2iXB#lu#}xhoXyrxIt5o$VfNu} zMo=BW(Z>f>Gq2m*qGn9iqjJ&;XdtVC!UHn?T_K7&Scb{sg3w97nth=So#T=$onVS3 zmaA?OD-N*In0UY~mJW=Hc9VC^<%`9PqZm>g+i|XSFkEc9lIcUwx)$KnL5WXUw@Tpt zL4Vp1?zK1hd!^MOCh|_K0iE;p9<9lO&DzcKJDsq1S!rkqiz-0=HM%X$DwKMZ zoP1noWy%Ypch5WsOb`c~;knILphF^Q{kMPG1#saJ`_3wHehfm&$RC_lmLnGdZoY|n z_CcphO{b!+c&y^^ap^q2MTX-HhIllQpKX6}2o#wqo!X#-3DqN(Nr=V56o7_ldd7Ye z-Iv&Q#!NP=Ov+v+heuFO33IVeuB3$} zm1!i_u4o!5&J19T&U$3MsiD?id!;bM+&sm#7W7yZQTwPduF@X&p|a^n<}4wE68^#X z9DjkCw|qK7V~==&rUC-u|1?-h14b7d@QO&NCbAP%adgj!i!7k}LaSL))0>WtxU-rk z7JVTv-mZ5pPHs}&c+@6}&I_xBttiKzN?a&ptwhL4b63WAM}a&!kN1N{X&X_SWuX*F zCruCG>#52WnOBf%I$nT~M@Jp_RCq-@;KdZ?a>fZ1wj zTbp``BH+R;7g?&|?2SoRp&qpoA`t(u6(8m!d4C?D4S(Y!K<4}SG>J>jSD8~4f8nu1 zP??xhLpn?$_&t(*A1e4w7$^*=!$UVxen zGL7#rojn2-8{Wuq`OOy!{XhCSQkS}N*QrBs9i#W@`K(8ua_DvNLh|R#7kGvy@-ayX zff~{n4T<7AH6bQ2lw;$OboU=uxFwf-QyWWPmE}UV5sd{gqqWIcOh_+0VG0L5rAU*? zJ6kU3w(lAKBz@gK$;8u2kp+S@F={Y{Y}ku!%Akl!2Oao>?o*3Kabd7+yxGXFxopvP zd+>#ZY!K4rHHyzP{TPLzI;U)MGky{}$%YOC;SOBJ&f znDg8iQ+Jw)p*QJ5H0N4ftG|5yzCB;AjQt5)`Qm`W3(Fk0Th@zg7uBgGRITwX+U>H^ zNTY(?{{}q&oIAvg?a&rWD|)Xs>eQq?a>H&sv{M)b4`<}4LaGj23}nT$(pB-P5>Vx| zbrlfB?oz*@z#N`dYvu_xhS3v$ms?r>>bCJxOvP*_mfaw&q}Fk6Yzb!bEDfZ^IrtEP z{f*kfY2%H!`r7aQtGv+TMz;c!g4It`4?K*+m6!Vn-fFiMksV^quGGq2N2&ppR*9gP zCNLz?&?IInF7DIz3j$Z-z>9r5$+WbGcamviPZDzWf!5GWjU=a7Q#ltEq_~3rpk@OA z^HC00qOk`}DZ@CSMjSFEDUy3yG)ab<;w3CPy``#Npxmm9Q~gr+P_XW0_T&;&#iYjF zk1h{;A+9Gki{76$lNF*8RHHy0Qa#MfO-8R_6AxX6o*|tt>pRR7c|Pxv3qotfrebul(11 zP)csB;-g!ctu?zmr1<6RQ%hBtLLMU6W^2W_BrRYaoz2|}Jc|ZPJhp&1YE_<5VcS-t zOqKo@vl1LD2q@ElHFQD)zq;mv$&$}}{Dph&X z6~PRi#(d3$CN;Lxdhrn}#|`R>QQFoeK<6I9XyC^@giYxv5%BgWPyAv4ELXQ~3nQeA8yqra7MB zj#$JC_UyIUnOgZ>)%&l~{D(%FQ%d?Z{tzYed>9_2XuXYT8MLqxqP6;zDMVv~V5f57 z#2L;MJ2+mN$LMhnk03!}+jKPN;J^oY1xZ>#>cUH`%icRZzy2$G9~Cc#YTN&|AGD@6 zkHw?fK$fq^^8XZ}KmH1ufxSyKIp|*4nctvb>^e%=EA^4_+b{ZM8u%Ou+^;?V*MMCQ zcAqnp=<3dv46dL1z(6`e34gXn%G9vhHc}hg`~f9D0}k4+i+HIP6(?t)%Wn)Vpwu9R z24pIsgKJUQ#`+fbzXjUcjUWgA>uT3OwuLdZo&T_9S<2Y2-R(e~7z0kA@4PeTCwKvAn zh00pw0){|Tt1#xtnKy>k6(YrjG1!4N9YiAMtNsQp(!%SpEa3wC~3P0e4RfTXR zZ@K)n}m@S;kz^bMo0TO&#MKSaTm#>La+j#RW>!KKq(UrPnd2&%+DjzEXOYyrLnn) z$eFls0nL;0@}x+%mjwScLDQK515mry^%A$O?B>63bPQ-$zqm%@%|2ybyeCn2pCy$? zP+dSwrAoZi&Qw-5l-N7D`~*^rmiMnU`c%|n$~C8Lu5t6#4HY+zF-s2AN?|;bIVI6* z1fqNp7e%pWCsy}OFX7GYm@%PQmW6Z=#~<)-CNa_5^$w<*p?!xLD9AV>9kOHQtF$Qt zF-BXAq_e-^d%y5Ns?%ptB25FMPA(sli4`1Vt5L1m)e7Ivny6`PAV*YcrY#Rj#n!C> zx?d$36}{}$)d%YxB(?36)+-ildJuzBH5#-G;W5P6G1$lwDKti_K(I??sE#o@l5>{A{Z4NvdA`u>M=h=DT)3o7?HBL>Vvco75r!3 zHT}iUVcPkO5f>Iwm{oM<9lP_}U}}`|nmvEFp1YTpYPS1!_}o!%@JWlj)D~-$ut;wbf(DTkLPsSX#BH%4ED2hAIjdT)i^ZXov<9 zzFfO1-&13AMQIO1uprCnawV5ARE_!VxhNwpd<0Fa+4@gL&$P(aV7^^!m=sHv(TB|I zqDN)GPt)ljs&$>TL7nOPFY7XNrqLyDW4CpCm(Wh@uuI;*dbd)SsOGwLg1La$maZN( zl+1o!*AK3~?l1qYwIW@h6=ZqilaqQ+^J5gvpuL6bsb(b)K2(8$DdDcP($bgZvQ6|^ zBIRc8x{&9VR9~bt97zaSOGP?m7ho)~HsI2!%o^L8Y5HP9Wi)P2XbXY)BkS-JOFGjHg{22bz5P#$w2h4wd>v3Xx_ZZp^&M$1m|2s~q2Raxf@tPNd z)q`P=N#Kw!Fv0*jlYN?ag9cjSru!Mn^h{Ai{RC-)SPTMUjUZ4ozZw=#@kH~Q|W|DXXeTC zq7k>Ywir9x0UHh;Htu&I;)6&*0Wqd*xbWeHc*!Qpc^2njm@yDjr{keo5`>wqE(@E0 zYJO+_)$sIYGwY3KZThQA&ZbdCcBeUC*NctvF^H-6FHgey+~p0|%V*IVhGLh2LUKx2 z7mK=+j)zNjChZiz3>!eBMRV<-l29V{!Ed!RqvoT^d&?Kgi!Wqh=f(2^m)2SFtZOS$ z4Jy5j*`|>~-x6}mVAPmIF_?g4RoR@#)AGYoR+P0&NGej{i4tq7;1t8=cg@aJtC!9P zO%yIRrls7k=9bl2=TYxTis}~!K09yBjcYtR4yrNRL50WX4s^Z>1aVm zEFw+h6Q*nm;gTzg)_4XKP^MI$yw*Hd*>x&ipa{4D)p|9$Hx>T-3mqXvcGM7+PNPUBc#3>|P_q0Lu)Jo6xoka}gDHnC z^4m1i225tmoPBP5mcoDR?Ie%6OcmovWg>|wW~;r}h`_WesomTAA9zO&nS>A#Uwu(9 zMDaYcKQm^7@@zRyvOm{R7Nmg29WTE8s_f+iH7mT3crv<9{^AG2_kA+kjNw`}>Qo1B z?qujnC(&`WPg}sab?23QOovO;)e*aHm{#R!*yZXv@vSIgsjB(mH2Rp{Rw=Z(g@?67 zmM)8Ey{(RxumkDq>O1)OfDa@xHbg2iVaH0Qg$@=XohdolGm^#*$gf|#Has`R-kVo{ z=8!6gSk&JEpv$ga0#=rqmQb%AwP9cIex})rTNhWtaq4@(F1&j?19x@$2n0r8gW!S9 z#)Ge!_y3vS$oZN|+<)~bfQ4nV%sQV|Y%VWv+u8DUQ)sXoV79n!NX=;>e@b9#VV#nbw2u@@BsL04R#n`7Dit+}qL;K}y7$xx8TCGH~3fMu34JK^#u(Y|Zv zOv^A~#O#L>H~a3n`v9lyDua>M^OQRyB_1!ZBvTYm=O|JUuhu|Mm-Y-AJ6JpWv>U(G zr>~s~7J_C*aU?CWdZHb9qxEskKK?{eXePZ<<#R?qMSrY2+37lZTC$%h(9zsw#;)7G zE|N>6@)koXj@`AA`MxsEmYLCX=Ky}w;ySB;^qG|5$4Frj9D?yt%=V852p{{Pv02h? zHiXG5m4JkLrL1t{l|J70RiY_zM?w1RoIRX8X3t#ne_6yPN2J9n!2}ra=Fkc+2c@3; zFBU+8ytGpE5j0o8Yes$dJ2tKNAI0ZzR{XCsCKaNBMG0B@j0qFn9N3pvy6w@tJxCV% zTwn2juXL78kZMcq92$zFM)exB=uyKz4}2hkMxgup`L`?u=r}ZmJYF-qchpsfH}Oxl z(sw*9s{%r!zwk&oriXJ!%`#rSF)NY3e7bHIfO9ahT#ULLcp0F-ic#lHr$}C?f_C70 zPK&LsEK0tK9$vGf7Jmi4Wm85f0>aUWz_`_*h%DadJiF-!_Zc-20*}Ahahf^*1^I;f zWq5r~5x8)D%-a(GCC#vXlUGx|GPO^!+TBrpy2{k!1~NA8PPosSUF`C4 zJk!0tFCC(XPt4mV_}iNx_Xaf>FGgH4a&;cAHfzUxRb|*%b4_;C0cBpC+=@EG>ikcV zy?g8->LxiKdB~89E=jd=mwcvQz7EYdSb_c5L`TZNa>nLVp>qV8u83m|DyXKnSyLHw zpV_5zp})Y>-lS&FiJY$wi;W(mVKi66s(A_O^)Y}RBEnmz0@_{-O57+wfJFBQg$b|;SL~ChJt8C)(~2@pSL_uDWc8E(L<_s@uWWO1&@lXI(7DY z2VY`z6sT$Q>JfXK@5{t5j-mH0^D9kYe_594#u*T2E@|*T$odMdxWXjLKnTIz9YSz- z8VjDF!5xAV++BjZd!W(a?oQ+G*1=sHcV~NM&&de_Fe z4hu=D#T{a*m!gCDcHxMQEg|F4zmV!5ZdLpFT4KxK`oP6YFlEwx-*?c#J#DfcFF;x# zcBa}&lJW1oz&9^Y@WO9dpD2-Y=v8k3yDQ?ma^Y95IS zTxz9alz8KeWNuLu!}?p*w=q@5;vqw=Gh|yrsa0gyWA;vtro}CR;wtFfWbFBiyMwh6!dJDIa&U6=3GYNu z!SNaq{L`h^FWVw&L2ma+xkAguvQLtoL>gpPZ+mdB3w2`JxQr7Mll*_zr5QUkQG|QH zf$`GiXrgGb(OfSZVvt;4O9~g|?Km-UNz2ql2RX3N34DPh-aL4n&o+ zhYRJ#AIh=(x!EA64u|gH_PJaPJ_EbnQ1zO%)?Ux8<~Bx|J;wRFQd9))M5spC14%9p z03pF#dEh<}(@dOU(x6oTxB;&qT(7F8eYZ6Hx?2X06nKg~Y879wt1x3h1>T(x{nVP> z`2*u)aD63&B?!3a9dq{NtV~%BhFl)(kSv~@-&_dj_p?|?7Ofg{L@%=9J9>)pBH0V3 zM!pnX$F5_Yb@cJSnw@xR+oJua+l}630>szliR?wBu0XFDFui_HnLZa$fiFJ7?p6HL zXPC-Zl9*x$t{zcuLs5`K3et~z@0~^1H!@3l1%pTM1Mn(CBXB!BVoA?_DHO>Pz{#<& zv`n3~M6JhFFz2ZrVN$^LZdPOHS9FEsby2NoBjT!_>Sv5u<&8OWFcX}Q(kE;i8AeqZ z33lr0=8v4q_jis)UM+36z0x}O+ZqZ1OP^yD*4eMtRmoThj%LBMp{dWeZ3g)>w+kf{ zsqtjWKr@kx^{B1&$T&u7m0bHcFHV4a}VQMKt zc_j|^a>c#j4!;YF>aT7NzUi74E=Tm6{-3BBLh=c7mfV$pMVym%FUrlj;ckDKW)~lU zVb0a~Nf{j@xmc6V;sKdD|Gm|jqN(%_i{0GYSy%JDSxb(jp&EYUaIrfZxzpmRmOG~@ zRcQhm0}4K@EdhM+jV)XNhX1+G#0uKP?&lc?ycfhSMDt+LQAG2@=9ExZ-RnOQ41>O> zKMS9&sU#|C2K14GzIeRmsi#*PC!lHpfaNe4fPV&O5&kb@G;{?Bv!Q}9#sDB1=waMW z^w(L_q3cpH9}ORrssTO7w%^9}j>hS+QY5h$+Tm}aEQB#USoxCI07VFh2M40 znmd;lJF!;h#r!)!L*um0#;-~D>DMUWIsNu3dgeJ9E+Yo);a3)e$@@SNzo^;xhvS!| zi>81H(T@c!_d#q3X~Wn9BrN43zo|)No0d(v zh^8-J9s}^jCROW3h@nSc%UdMOuE!-(DG)HJL&iS)n*mC2MDSn-W{@E1p>g`{rA!8r z`n$$1;Bwjha!k*02$GqS6Oqb6m}E7z91gw$FTRQ*>cF8V(lpZzN%)5on0q}@!Blsf z^B%mD+sC@0I!7CZP8wK+8oQ$8uRNw!PQw-%){+lXTOB`>#+_zzB$dt?R=%X1{!CEd zonr+G8I)#>m6uV01Oi_z4v$^hi)>Z?@A>RzbN|!x(NhI`ucjs@~P`i{1A-9iWL{}KntY!V)c#h4&xMKefl0KUH`Ey zvR1D1<;xlH*Qvg#o*#H^e|O`DgEeN9Olo8Gxu%1oG%D4n$vkBahT;?9oZq_1Sxn&2s%0k7}$Fa49;*T2;(^OgMgWJ;CAcj(a2 zr05=>Bwx6RPg|2m!CMgP?NL!llli03{Uqe7Ai{lTTkp6Dlj`Cb6E+D<(q-;S<iwx6rL0k zg>&cFd*1i}ylb(TeK`fA1XJ8!)9RA>ibHmKwOyK41l8yMU57xUyD4&*LF=`vS37u} zVh0762Cqpj^PxMEd2UrO#^+MdHMeNwaYj|B<-JCoE zQbv{?MlqjoIq=>23*M@2sy--n$3YzOH%SR5%5N9r`f9O@@XT%HJ;@2L*O7(0h=@5G0SoEmh*DOv5Sij4 z;Yn^X&2Rtfo4hPD&fD3>@jpoEGJ=aU#Bt?}MwQ8Pw!37=W^YzUq@K}S$+UAy+WCde z+<3_A*R3IxoNZNR>2Oq9D*e?C_==Okf4`yZWI@;ntvo9v z#^x+Yj49p04&hr8yG}uU4i#ExU*1;9DPLEsVB9~pv&YC!&^m{PXDlX43$%OrrNl6Y z$6>>TMCMEz3W1AO0$Kb)@LBH_M}qG!IQ2XEG!3F!KeZN`M;_X%Vf|GDDpj(H!r^gTH-M7Vd?VqE zPv}{>iff-?E4NwTG9(DTjeds1pD|@y5s#j{6s$9!rPDSJQ!)%&Tw2j1nKQ!0hQovv zB^iVh4O70zBbQbR!$@FDV}dBbU`i^PDA3&$iO(8r6NpOk^U8%4yTS@Ey|@4VNg z0cavGhl(CIkK8dy*YNMjL;zi2vMP+{^M1}-FFmPQY*n`WZCL=;^$tq>TIB66`&FW` znWFgCi}`W;YXfSxt73IF+5atc|5=r2MJ{J*y-xjoIXSz!zw%jm`zv~yjlrnKws3YC z7D)SXfUsrW+?%VY11!zh9}F15pHTmH&+Ko8b2goR_g&fkdQ+%!8;jGFAr_&zFB$E{ zH(S*2*S_6ed=2w-5omc+erpT+>=l91gfJAKSkQ_^!;d zU8Z4o|043*UTv4GnG5YKo&@`9j&&+3GGyAhSKy4sy@8z9XS9xaORmzDhdgf`l>EdO zItwXrl#}(g##LC9C@T(Y%z_+y1sQK7H2cJ1U2m~sf5~k?ZsF|1AcZzLOOa8v-}O2L zBxEEp91>>(y(bm?DzyB8)c&&g@b@6E)IzWiEwcVn~&gpr*05g^y5b2zBtWnABJ#-LYZUFmEf~$Wa^}p zpqF5=+!bKetY_lvS8Dc(pJ-8vm*#2keNs4}vI~eOUNLU2BGu+ay!&+U-xSC zv_g4Gdap5aS|19=arh_Fte1liC%(k>G%*8_^&LFVi{!EQ_FS78 zykvEUNpyJiI>Yjgr1*pJf_{LFVP95|tL5CfhhU#oTl>SfPA7lHWpoHWQC_y7qTpwS zBQ%WQ@SMh-8s#QtkG3#AF>}~dqlZ`1+?C9uxEN6kBBQNKk7zRf0&t9TN{36Spzj#C zpdJ#Gr7O8-)4&`O^8-AcY1!f)@;RY-z8_V*7Re-+@TFem3D$Wu|K=J|j}{IptM&9| zSLDCPkitwHrsgl?7A0Uu50HGdI2XhZH=BaY*fu#~(lLtDv=_lDzUJ&I?)LO5nvkUi zR4eF2KpX<4$+~G)2p^$yr*(ciqDmn2F%31GL+4((ceJCxFecusx2I zaQx^e2Rq;4#7JWWGQW|~iC-yt8vFYHU`zfZ1*;Uj7YHrtpdE5!7NeEeqP9Yc3ktIQ z*c+T9-YT-awUeL@PF}Nl|G~GsdwGe_G~0V4s9nM1beELwB-gZR%ttb1 z+f-tT%tFX0OJZURpihH0ucs4VexmHw(TZWM<_G!1K1&Fznv=*u zYj_gzGw?xBgdU<;aEo6@KZ0@Vy>8s^XiR*S{!s+|+UNzUUoG8CWreZ@0sDVgL~-If zKo8(Zj?qXF&FoY9B?SGV!$mCEp1Ks$F1aj?eB0zhd$B$JY3BK$s`S~wd`$?}A73H; z&NGsGK4}I4ady-xW*)oLC(SWS*aM~O!aX2#?{bG=o|K)Olp>F?_>YfsTbuJ~e&Sub z--U6E86~T_?x3T=3(S>PXpT=hK}f^i@a&+}(Tc@v zr+1$>))!h#KZR}ZH_3gh{o4LdcbM9idA>s?z9>{dO5{bjSMJwADf@bhznD^92$`(5 zW+)@JrIhw>%6PB+s?&3@Lku0HJq!uDys_%j6?QI%3ia|>Jc3t!$5%=xG?gkZMJbE% zTpihE%Nd__gH`_y>$6reMSw|8Wg7c^$hK`G*Q$Gvi$eyVzNHP%*6|C7r%JblggZqG zW_j24CMvo{hzbDv>4qQfZtvCg_7;J~6PIor=4?5!ToQfjmg*w??PQqzFXVXOF( z+87*xFCHkRBvD4Ss743~(97i?Rwqn^#VKi0AX6wmRx9Q{ZdleGqd~!cay%oMRVg}V zYM>8pAIszl_L2PwH}rr)IHu&wNXm(8@$JB~-S;V_V_%V|!-WFVbuOdn*;QD)59_26 z0cT7{uT^E6>_#fm#pPYAxgCGlzV~0RvEAb&1+~2to&E^Gf20RBx`Fs-!qWHEUe`%~ zkr4q8OpoS@*|R5&KM%*?60~f&W-o$XPg%6P3xo&KAMaCzu666$+Cn>jUESks2471H zcbu}kh@wx*`i?|8!`JX%H5Eka3t;chxtsrv26M@-{+1maG@V&{t8a5SXkgP7vJ>LH zHx-CD(Y*bo74EQJmwqDqO=fwZT&8X*m4p3ixq7^eD|3vc^Rn-^6?c}EZnZtoT8I?2 z!yi6f_{sslQ|{%G>Ihe2>0|ZfmTIQSpI2buyjT}FV+0$J;Jm#8;=7Y^@Msw zO9XB^llt88QwKQ$#XC}*N#;mu`G=%fM&mM3f&QmlXg*l{NfwL_2HB-RF48~JUd=7D zsLdyBCp&NLATkSYZrnZ|T$I$f<<{q@h=Su2#>Cl1{VqWI>{JDzZ}%s&I6BgD-}hU=;3pzp8Kz#`J1f0jwgTQg z(T0-vU5dx7`}D4@$&wHUoG8>lOI63oMe}Tf%h5KLkbh%l$;QJm`eCD&t`t7sl@JZ9 zLQb;g)sAW8>nNpo&FBw~o(of>wCUgHu$i2(w+b2dM3=9tI@+^(@GruFn{l`8qiy#( zkDZEkd_TB|_N?{@8sGY3PB6QjR5kasvk0Ye94n4cvi( zkH1E;I83Y4%cE^Xh?wlbqw935PPqY4BLu#m;+vmZ<+61;_Pm+|X&s7=MVuH<(^}U$ zE0!H;KO&mg&ZnO%r&LA8#{5MqyEMygcmwr1t1HU|E8zaiiFUm*;)Uxmt&!O=QT)*) z7b5>J$Up=Eu}^y{;&RGgwlI&qgwNK=YXqzb2?+?3|1Pcu6Rfq1>^>i-)rrP-ZgZ$b zC`7+EI%_lNMt{<+_v#D8oN#afjGp{&cp3^LZN1)T!%MAWuSs*l5P|MByv;hEg*@?T zQyKd&JZycmWU+|Vj*1<~B=PCG5qxfhZbSo=_Sd|kt&&|GFREx)lzk}1933U9E|ILE ze|>xO@YZc^UA4#&5%iY6>kqLytkxQ3g2Spnoz-JVD?gXf()mvBae;%Zqq3xZmo)C> zPp><_+rp}1s~5CKApn=$-r#S3#1ZSg7p z*3Q<`+zPUYkmQlS!5FFQJ6Z8>Sjr9_N8P$((a{VRk#u@ZP87et_)Nh7o`-R#!adW= zzW5P3F0#wCY~s}|!u%gN@{lz>t9J|dIJU}vikwzIf!G_@xw5%i#F`$7n1c^*2Hg=s zPeTqzyPm}%0?c1Q;HuYQCObRfh$lZdduaE5z?!t;$>8!_;v2`~g%mh(uPBGLapaq8 zU~l%YX~v6vM{Cl+K$PHjxtJ7`4(t1y-cfmkyeky!9pzNkmo0WsJ(pNs%ft=V{@j|j zOShj*&Oo-Ts?Q`1E)_G~O;QPJ-DALh+*2=UzD)F;74H+mgb^k>eu2ZX1IkH^55Szb zTT~^-=5c5Ht?ILwS!}NdAi;Q0;%QW%swcZ|4qJ@Kv|hSsor?zYw$PEvl@hlx$80~= zth9T}eomCjIzFjgK6CK!m{5I`yK135SSyZ;CCO%|>N!E>TlA`TCLKL7`ky2yEYkxz z`0-X4>ii*g3qNW_NZ9Yym_-sRV_n6jenCR1@0erbdj7-UU=^Q$APqth#^6`Qi~EZ> zEpI8W$^3Oi-FKDwZE!uA6<*Ln$p%53JiXc3@!?ixe|%p)PocwI1w&0PzVKQDZNAAl zxYUV(MZ?Ll#=Y>sxR4(Cn_9?})lBBHYt{VOO=C(b-tOW}iopIh(eF-PzV1xY+!==u z=geew#pFcV@5FP;jE6%=gvq8UBfW{)-7=r84pMyV@3(6ypC5K@a*)YHh1o zk5N8vh@9*N#3=knpdKNctMfE=o?#0_gn&MWF^B}+)EDfrlJ$&Ts$UML9b)iuODvKX1dpj1QS0+4RG62(4b`XUY;J8iZZ|k{Oehv| zqcNxjC`@x{nle~hb^@x>8LF~sr4=4lYVQUp&eK05cN{Jy>*sIKP&Xn~M!TtlZ?L?_jr9QK>srjsPTV0NP zqJBH2g*2H$E*9cn)2PsjmjTb7fq~FMCrjEHgAn+xf-B!PG-coMep4u(65-I6DnRmt zOi2K)?lD@agK^Sa7X85~bHrbfT7BaU-T}cF2vV z<=F+p#h*%mu=Ta7SYrJEt_4XDHT$bo6lxcxG zKhH`kw5;1j~0 zcRs2T?TvMWHmOzj^_L-u;2h;75404NiAO0NlcHUH-{*{7Z(VvY8K-{Wga- zm74JOeD;ige24y>(z{u3XO&l4E`VJ@2V;;uYd^PP;7TwANSZaIcp-)6FF?POp-9bB z(71C0Ff`m!h|6k_YEC6O{w)f+#HG_41ZBfM z9A}OcVPamArdli<@X@!b;s;7FF)LAUxa1s=vw)$Cbl5~GfE%;xxko&HHfblgRItgz(=mLlV4L5cT zeJ>R#%z)7Ry&uAVMK2a1iNK>sw*)Y1Z)>|GO3CQ`pA^@BdKw1S0(i^k=hsbs_H45T zdhF`I_`u0c89|jMyTv!4M8Xg`@ymh?Ksp%6i z#-yL#)uS6suXzO#oj^rB-7@c#6XSojDb)3%y@mKWf%~iftt!I{Togrx2#odNR6#Dj z-En#!<{L{=n3G7KO=*8B=u;7nZ8!H`dwYM|hn@F|Gmm;QpTrHGTI6ArSF#Edlczr|RG+IX;`Cf7T>+s1ZWc-}tF^Qt{nsN}$qv0j`m`iV z+U0d-3jMA8$u8WN3|9QIsnZYZk4y9OUUHQu)Mo0Wt14%i)+gDeY>vCe>QglP(3ZPCZY#S$QaBftpTRjFHTsz*RQ&T)?HKk@ zkM8+sRJJ-04gtHh9iKTauA8n9JCu{|=|{GJ^LRgOu^5jOnfd?cK`bU<}G$6riGi$@m*T zM{L`?FB>F?P3QYQH}q3#8#y{0#(d<(6gIVS2e~oY$Uu*$+_~G#v|qz@V~1`K8fc_) z3Igp(yw|sz%&}QiFUXp&2$jlEf01NQXDP;aP+kc^tCh5(EeG0Pk8cl>xgy=&TX}2aW31{bF|)oj&_s{a&-0tN!@zwoD#%sizsZdh)M@j8*W$@zs*QeH)&rNv zdmD5&It0&um_hnQ#ON<+ZYyQ}D_Wp?s{h|^C6=sx8Yz;`=@F4jkU9AUJ>CglTi7M* z-_9!TP4Zf%V{Zg${o7VRk?bO5{fvNs1@yk`hz#7g%Je&BkPcX-SolM)o|QtKH@e5K zzp!JgXyYUk!Gn^ZoOC#huHv z-CgtF@ggPG8^*bRK>h|jK{OrVJ4(yvK0+8?o!|Oidw($4s+pGjJX`S7by;t`wk_Ec zy~+QRu+ZZ^8Xv!Wy$D2u{k|WNyVk1|ezAZ342LP}JNNdfwSz^}PONQpV($+7h;3YS z!=1%Ymz3rNkT-HPWd%0R$eVO&CNKCkVUN0P@P40mc0T+!TTn#njpYcJ)ScFL!o1P; z`wa%4CTE!{-oFZ3On9TwTN0uS2_{|=>?Fjf;sNV4aga#7U~8g%sf{HC6SIF_|3XsqaU>Gs z*LE{sd?-djNvCd*0Wu9`JVLZ?73km#S0rNJv9`wwcE?^;+&T)c-c_GVO0+j^YACoZ zinv^%4hEJ;NLjd(W+9n1_or6G?k5dg#$eQbGp$g^yT^O7J}+soTl@@rALjR%j1|vM z?Z#xD70ox#>NaaKyMgjrQzb|s^{>in29Cwda_AWP7=S?l64X;0X^y?%ulWl zS$S$DLwARG{K{=&f?uD#P3+DTWyGd+tis>*Y^knupNI^Y;EGCX^2*Trp0rCGLB?-d zMLa88blfjKtwXD5XPX!lykSLTG`W3!9OZCiQ>Xf85$+vtM@$5+HvJ!GiWolNM0$}v zf9q<+SpLfP>k_SY z1v>s#rYiVL86LF4{Iw0|4k~fc;%Q8Q>xihAosNNXe)6_!mKN$ZYQbtLim73}8qzu* zj@kE0aB)$u0;xn2N>%JssKhy>NMuA{*bMM53cRCb6LfO9eJGypy1xvtt@5qL>L#hD zLFw)1c6D=$SH=pW+19-}kzlkud+*iSGn?&HRt9@UAC-H3}9=m#Wz1PL(Ssj_we_PG#KzA^%mEn1* z1EH!hSj@VJ2#k-?ehQs$Rq%evv-TE|+#NMSQu-@wGP0-R^w!$>Ezc7E_5GHNDM%`N zPIdCMNz;~?7ljR6_)XB|IUrPl=76d35Svq~5>y$(FJ-;US;?iK!7$EkA+LcXwn!2n zPoErQpn_C@<2x#C6^#SyRzLb@2T1gA(r;zXBkuNi(1!~{KU7ZA-0kqF@|9hyabQ?du9?JkxcXdj|11@BNjNtlO0#LLoZzuQ=vX*L{Ub`7 z{aE3ek(ju5p3{+{xW`uhZ9oz<``KC747yQ|Ji_2;AuZlTh{h|5j?y+#vkIaSyGY+lIS<-ybX_NcVYA_xlE=T zpK_if@O!h-07xHG;h4v|r)(_yJv8LI$M54Uw1`OD{XM$gmPHoP8HpU|1|N8m=!Bj5( zI<4+idBBoxy=TsT@K#_l(teN5dkGDV0tpIDvZFTJd}uM-dz?YRT@EBvT6HNSGLXB~ zis-BF9oDuH6V<+W*R61d!lRyxvL-HJ)l0nvHWj6Y2t<2Kw@WAxfQ8oA(joKwH5IJ4 z5$%myYqikgFqPCu-i9XA_?&~q{QNwB4P8T_Oq(Cs5~Em+DqIP%4w0mLA*IB0g{fmp ztGaW|A4+LlnGgjc-;YPXzP>yS)FO9HBY_0I@UZ~WuI{Jv1G-LHzaj9rr65TRXfg%z zpW1)CQ+!o0=4VqO7oY~K_DvF6uJAF0$h0-{ zfn3=GD2kaB8eWx8=sz*c;M{@T-{z3`^0d$Y)_bYy=F>+8<7>3)ou2j!LGX%}&{~g< z^HLR3IzcLeilf{My){M$p5E)iK}<~nD0?V6S_log?F*IkBdH&S7r$?a>PQK_7R)<@3;I%MC?#HzF2$bu6M<)ycoUv8Z!Z5M zmLiRh$3%@fW0mnD3wdnu)vg|X*MBe~Zb@oBmOlN4zN zFFQnMX~`TT0Glbg0j?2AjW+!ewVtbFDn{I1g7mt})R7w9*x<|tl8a&-ieaONuo6!c za`$~!_d{xd8Fo=F%N2*F*kwDkZuQnF_@BH2wv{D`l!02NJVXb8fGG#Yn8L-(?40Sa z<2rdO=nRRN3~WLAK!jGH_eLf#r|o?n@C6sQ#yaCsy`$ZO-r*WC;mxh#5aRS0B{2Mw%fgUz~)4ZYw zloH=wZjIz&qnecu3eC?RZH^3q7#L&mSM;T`gN6@qPTq_HTdLHhEivr3Hhd^}km}60 z40LJl%ic*t-7__YWN3>(jPW^EN!OjADqxcW5rmi58eWb25K=VZ90fk)xFyf(JD>6( zaC_dTHn8WoC}cWFnl1oUeeDB^v|S|FraE@yc6NfOtIh@~OwzYVaUeDkTE9cVm5|HN zQ?Rf1mB|0kdpPz6f3M!cV3}i@lOgJZ^Vi9yZoP82#qEap2i<#go`cdS3i+53Xkccl zYPZbktIQt9qaTSqm2?k@&_ivK{>p>p9e{#xll>1LDo|MS)_bwkRZE$( zGWJUjBU4Cc_!;q3rXx^*{CH?E(kPA@?8m`{)>1Oc%K6$jbYpr=c@0+>d97C z7LEidZCVZuzVj`*dg^kmnyxSE^Fd{#k~ocJ^C1s5-$)j~bR;i^3SZdhv_&nSu}GiiZ<8!@ zm&uyNPV|mSnsm){r8_1OXQhSzYyVy2y=A0*%cV!&;*m?y+fa!!7K>ziP`MeA85>{BX%7#VfiRGEmLmJg=9j?cp%wWoYTy-5h2@lTREYt)lUrE7~ zu1Yqwv60d~Sq`iQiw!r&0PCfoz%r`5i8BS5rx2dZF;WT!0D8zbq`V$?~bp z4e0(c?nQsd`>6I&Sb}mCr>Yjv>j)e@dBT8LD&sMNF>5=wHoaDpgWDW|B4)7y#4NM_ zFm1}mUN!5wkNG|TTl^AgTIoSS&-Pd;PHgOz=465|Nyu1Rd@`)m2>X~a5??7V04z?X zER~gDM}3R}Es!a!S@IJzuekYvL-f4;JA_`#Px;NI(xc)z)Wvf(_L(h^<+zBtMcINQ zWYz8Cx&)VrI_;TW$+p$Dv%%#J7_cG592Hy%#;|#%V@JqPYGgWL7~7Y-wy*?;PuO0m z!I{tQz0$7nT=FcZs^qNt0xwlc)(g#9=!P$kc0M?R4C(e%$`_t|B&o@324|ooIz=AJn^Qp>RAZJ$iL$9+nHoe1CG*xhW00)5(+80*0Hu6C@QgP~q3AgFXeGP2f})?Y2<^Q(^o^U_PgZ8zwkcCrjaragh&*rO z%f1clcoa!n0nCOYS;zkuk=zGga84_a95nWQ zZZU$&0kLhh6ww!+$=}mGRM)@&apg0)_A=tO(j#OKJ#w+9-{sgWb#f2<6Mg08D{qg# z)3V$avo+!;aH`2le?YIS3=@xDx0X>^EytEjn0CrFkvowx0Ql{sqkeTV7V2<_$<{v?}0}?P9 zFcwtI^(t$5zLQ7>pIgPJZEPD zIhBr0ym+qHwH6jN)_w19^IAmagc@KMEjQiu9rF5lv@Agp@D&7_cp}5ZNVrl;wg%-! zfbK(o9^rKf0KX(sHu0Yi)AHxLIrfKy z<+n{s&jS;q2{l0%x%>!v$E0W*GvJxb@lX^<&833Vmv_F2=^)KzTz@_EyO&vq{HElyLa-hh6yL#-4f$l$PFjsbBNLy; zI1`_Or=12BvNrGqhwkU274uvU<5~N3wI1Li^dIOXEbEa8E$E~BON%h0U_8Wb+aDisHr+6mk@e`qUx>>1QEA6+1ra6Ok2 zX08f$#jyw*61Sko{q+3%7Yos!PvNQ(z|feafHdx{SA*_fO(g{O*db+JpT6qC47%V~ zK^f%L&BuU=5p4)Ana*cBpw~8Pt-N7T6ugazzS{bwCjhn>_0098GZo%ISqJY&AC5zB z-bBYCt42Q(UW(NgoYQ3kDoT*%byWc+)yo8H4}WSRy|3HXRE=PjI{dtPCr+iN=h_j| zqKIb(jx=$%?+>%yu8vW!JA_8+CrY!Q&^z!3has;y**K!TTruhV-(p%doE34!C<6H} zycOnjcF|21X>3i;yOznAMk&F+qh2%+L5(qA?U%`93gbb;oIhtDp}!IXCWIvzXz;!K zibv3eZ4gXHc##F zh5=a>dB7dvj!{KUGtB~x&2wCP&6sQFkz3{1vVxPyK#5B+67eFJy19upo?aMReSc_%@7yL+=n*ETzGl&(OvjyI=Ap596GOIm$QXKT0tfJ~BlmGN>j|_&)RrH|`jtYkufL%bZC;S@?Yi}DK17{;4OC1yRIlb50UB?>NB+9L^T;$H`o>Vmw z4dMuVMo+A6t(@9qn%gE_Dz3P6Z}ebGAyyFrcUsMyy;2MEwZ(a*KAhbzlwoczHz9lb zd{)bHL#?qsEfF;6y)K;^R%8>uec=r~Dw=TDTWCI0mc6|TF0UHx(WCjEI(?q%Cz@;U zHVtp{l)so=(*z2|89ru|21saAnmX3ZYT!F(qgaIFQNqNGn12wkB?~loACHo9X<$k$ zgK{$ZgswQltWvnUefUJ~Bf+lJ>7CeVF~$CxNL*>hWTvsOBNtHLU3%=cI9d1k`SZVe z0dj&DzEjrjgr|Op6vQuX*W%uqnDG=Y$mD4fwpD=2ux0zELFKZL{5nrHA=ZGACwe#( zH`xl7qMSAzhLZlvFYaAis;`>J#)su5f8;|x)DW0OiXj#&;IE#-N=J?{^y4G~YTSP! zl&ZK@ifU(7);-S3Fedxy;e^}IL+;YEvi)^%g4-W5i<2W4Inu<;yATrsD{$9pk=%wg zj|rBS*^o4XDcX*H16u1Vt~Th57oK>Ev7CSRMa!e+LtcM$$mjd*b<`+yXb`?+1PQ3c zuN`kUY3wlBuzF!x zIc;lJ**DbW9`5-gGt^o&Y4<@1Xwh`)l)3P5$!PyL)dBUBKD&_~y;TXKVxax`Tfxgi zEcjs32mZS4eV8b6bV>xDxR%oI&H?c}_Nn`Jxu2{-pq zSJnEifd`B@f>A0-f5QUUUl-ooA)LvR6mhk{1V$U@CjAc>l zgkEjfEhC!EGUZ$!fKhE&0;O=kTKlF-hkB+J)8$(5st-cJ-)ll2wQUPE zpR>rjbV96#lIYyl3HctqmWjJuA47f=>)GapiMv=wpEI2_ISafRs6Rj>d%oproxCKl z+-LNrqe$P)VV=m%Wj%I$9rHW=Q4U2`SHH%TCsM`JTqiw9@AHbyC6ICTbx?KXAu;6E zrN{=l`Vk48`OASx&hzlXab3(FdV1SBhrO5Z zV%ufU4Ck7OpP<)y!&;$(UR%&bg4+n|TJ~M%?vppMbi^THd@=I z{JD)~xk)ti-bi<(?5K(AoHKTO(QL4tGGhck8*lyXn3vZH2#ND*N=8>b-nRVIV-4tD zw)$G#|HK-|AGR=a)xgGUIJqF z_Xh=cm(SB}$UNIu+rcR26W7e0VM>qz_OG)iIT-rSl@PIU6C86uH^kXJpIbz$ZYTw! zqN_4^T(_87n88J$PAI4TVq^Ke#EW3$Cx`KXJW)4@8huy!vu(M`x{IGR*f8RK6Qz;p zODnO9*g_$^z34QZb}Eb2`f|CGo{t9M1l`H#h<;_=H??*9<_w;-5I(Q@$F-CprJLu< zZ6A0@v|i6&o&vXKA*gf6m)m$8B|+rIJ$U)0G-{xAkD77n;(*KDAs&FvdtyA+#I>#}EX(yx>B`IOZXa1XCTpubGd#1Ce`1}EteG1WRGl%Ds{nJH=FiB{ zMT>QLt*PhyCatmfPcyzFj&F);_*8{_?!8kcHedgCD*ja1r?xIoHgM>YwOwnE-}{WQ zC3`UMeo}5__m>8wC*7>G&tF+`_4b78{fOhr&{r-BU5~QkKbLUQ1bT@ndYe}XSR~QH z+@tAXS zF{<&OVoW;@In1x-tW8(Jx&($huamq#YeqofqgA7(oSm|7lV@KJ`n+h@7%Jm=&(s4ngo;su<*s{)<+{nOjafH#3hKRDLr}25^I4~&dz#9Jf zzsv=lN-@Vsd*z4M5O+dn4Rv%jOLQicPaNp=dc1%44uN16E9Q=*-R;6;S}3oaCn{~| zx35@O%T>rdb<7{8rl_;M&#NNY%;!x7ovRoMGqU@Pm7q~Jgm3x-w5pBkKCDbZbA|C<)3vYFm7wl__kp}+hr3zpj%R*zkq)cH1N zz;9CLb;fJcuplV*?K(8KC)}AHXyrb>&gXIQJ8!~9h|Rv8MR zSns;}3hq9vU^#^1CS!F~8<(GBv)*y(yt|@Kw9B?v9jmjxUDv*MEmW369AD@2*c3U+ z_03-2rH4|sHdIr;u6mAP*(hUv|7dFCI~I17xgOS4gi2WcY%+fnW^Jn=n!wpFU~~^W zlzz7j;V#>nVos^f-yXuZui>YqF}nS}i}KR7bO?##n7{t3zvB1)^hdnr*98xXI1NQ2 zgv4>>;=Pm(bG3fpu6M^3b);ciS7%Y$XZ-!mTX?huubpiS_g|%k?%Hw6{J!7R##P5t zap&J33SRc%={4%By|AVLn-K)b%;$goMlZx1Z7${@5~H6$EcWU0!b;^aEZb`MSBLP- zgTK9JCJ@W#QFH5bU5e}Te`F!`R`u;F%z7H%KmM1)#5Vg+n>-8`g3>B+C$;Quz&bYA ze_{4<^Y=s5Hp{epk#ygGmkO2t>?wB|98nz zQ{5}RhkWt-$@XV|bwdTbA;IU1e~`Xt`u>q!U&0svh((=$_AhUyObZ054paW}SCJ57 zs7UcTT^v6TV)n&90N1Bj&vKialj}*w_eGr*{PQ*Hy!Z^LEoo_=F%}3R=sA+msSm#f zpp-)DqCv*VLXMU$;s#Ux+kd>nuUg5mo`Sy{UhwYai2w4xUKBdtYEb{A;o=Vz`9Brk ztABdC*Uv?r@{cw1OVmvmlbQsKy1#V|D%rDX)}>6-kMf)NfG`c;g5~(;mYp?VY4&7!L__+Qni0>$yTd|xERdf%kcp{WmVYE;R}ZT9Ip<9F2;JyX!SDVmH$ zoBY^rG8C>`-|TufZB%M%&vjsPVk^X!8_AUKUpVq)9WClp2OnzXQMwR(|O%bPLlzpEGI!&J^W?k!kAOHXCy=$;7 z$yFZsWz~M1=Y4kfy|*Q`q}BrgdUUr2kW64(29H4qkD39a37(FL@dUP+`7=n^F-Jdi zCOn9rHjfDZfk8qeg)kCEFc1UNz+ezCYIUm{ED2$$)l&Dp{kZS*+Iv^!{HV&kSFKtr zGi&dvea@BkccM;JWo2cql`AtVYkfPjIA|G^M91^{!1K3(*LFB-CxpkJ#q38j+UB6y zn4dd4)3CJoh4`0m0pA)}w#%Vs*DxWKV=@_I=yj3BVZ5K?|G7+LEM?}zjWtzbrvg(r z3X9n<)pTHiXUD*^mx1q@+Lom~OGXUm*L<%kvG}OdS*pL%I6}*ukEu(YfAtFR?VG@> z9C2qYtXne4`t|oYP-CDqyPwy{97%VdG3fhK*?xcS3h>=qz?)9ca*9859oXQ{VnFVz z`1k|loW2VJ*ah$o3p}_;1?&*J7f|oFX+IPiW76kz4(z@Tc>O-`@E5z2xee_8W61T{ zXQ#9pXZQO7UFnxczQwg5r1E}}i^!kU&12VqqlIZDGUd(dkxC^I0 zADHo%4{6{U^YY1GQs~PGSUgEjx3%qH;V&AJzM+>ApT2Go<46DsN@`eCNxQD>>mcdo zv#AsZWbgEGdh@}I)06H``V2Im6Umhccc@6@9d|Twox5-v@+AeE=*kB)d=Mu&{3#^I z%Q9x`_=rlM&U_Hd!3S|U3#aj@&eX4x`2c3ZyvNL~X0lMAz^V!!9 z$O~%cplw-m_QyP%D0rRb?U>$2f2Fo8$G`S{s5WNm#Ms!~vrM8x`VLsEzP>t5^>*Vc z2=_P{mN^4Wn|-z@sYC6XU`Aqb90!rr1{p2s>uf8PQ+a$nK^?Q9BW`Ic&j1I;a59D>} zDW1Qk=p@KEJ(tEv(sEGrpymA`jz(kez2@)$1))t(_hwQV6p4xqM--Ugh&hyIH#E$da_vi`Jx$CVfePeZ& z97>_tJRvenicinG!lMo3jwQN6VWAmN%b1-+<=6DloTa{UlG5|(o1$(GHH6Yso!zw>t=8Gbn=yn)ZXVUw`J%Hgl8rB?B8SyrPbBALqIN(8%y4< zFHv7WA#~g(k(e=C!}~r{*6H=h2GXpD{k?r`pWVh?_ne;+IpbtT)J)81_910s$~Xol zNzfanL7kt!irV{&NsRx!QhVo-Y@{l@m> zwIzcx&rH0JyajmVwTGDG6ZCDruD3Q;jwy@s_~ZANGj{^;Nl$rcI>RPO{5t1(juf+{ zV*#MwOYv7P1^(s3o#cdmosPvU_NcN`sNcG59 zce>WuHyH74THDs@Mr_($fD#-bonq|WR=FkU&PmD#pNSF{+O%|h@qOW4It{hDE$JdT zbfxob(}WEPdTf ztQgyBWfEiKm~u<86e25^+VZ^mNjCF^vuoFuMBF`1b#5Z_BG0GOKG%g~SeOM7By{Lr zDhKUcOH;a*0H16^?DQw$H~~Cz1+!;iS?8>={xLGQKWW>>7`5!CL`QkPh zYm09J3HN;Ta!E9qDxp)6kLhX>Q{Rly%S9=>UwL-Q=|s>aq5mgD=6iP)LW(4qb4JidU~_bdbKx^{F-*gX%woGxsUF*Vzco7mZXM>#`B)7zk~ zhi2PU2`{%#yavT`XDwiBKxbGM{fO=LXXgq&@)k_{+4cT9)`n|UJ(XuG?b9j2KJ5pU zb{<3QP)u((JamQ-A8jTh-UfyWIzHO^bTh7rvQ4u#7uDN%&FO! zsVD5|R)!_N2K>SQ)J)&5k$ezQ#MC@noBAfTIxAJgwjre-d(8KmyxO(ctxf!G3-YwR zp<|t0`qCgo+I-iVY_WN`<2K=DpvB4=8rV7cQsKImMyM>>eEF92<$3xB*NeoF27XdG zwvDd!^Vu`D?z9alPi>GII+t{i(vr$VJMRK9_K6vc`)n7ZGY@n7w&5eOVs&j&KVq(R z)lXCSoOVrgruQ!zx69c&^XL?kdET<3+cIa|X^!rB>^HCO%OEO!1dUJUMMw|ryzAK< zKG`LEH6^WL+5$iC5Z3kAF*3)J7+U-ArA5O!#?w^iknXWXl(~RFDA1nD9)U1obflP#-h+#){fAS#zFgW7TCq(kD^&n*M-X z1~K>YbRv*V{L9#c@P}miv7^b6U)F$)ilu~1^}SImJ97Rzg44g|^OM&h(m}}_NA8r{ zuRm++I@yt-l4W1(w7_`7qKG}Ix%|q?CPuIs=E zY+UvQO^J>eUDV6u`bXX}n_1X1Jq*mCHUmZO=IW9+#2W?R4Cuh@PQo73Z)$xQ%&O|3}Y)MiN2Svzk*>$6zqLGr7Z z&CcOOltfHXoqS{ti_@0AMYk6k$QZQy(#`XU8C3BwpRD{oDUNi`({Bqm=g3piPb;6; zatm#3L({Q|9!eOCXH4B` z8=eN;Tn%e)o!$d^63l;)z9&3zq&}RIJJT@3W-pR(ACWb!?vee{wd*&6aZ&(je}K>2n<2OP zbcPPM(RQ*e*57l3bH%rHq#qY?@ZQ^$c0F1kWY z9#R}5T<3!!?c5hfO1}+ga!7eLk)7X%h1{UTVCw`o|Y3_@ig z$zH<8B#S2e6N#uw5IZ9Nj|c#pKr!z7o3}YTNqIxI%n8vdAzge(Rs{ zPt8|7z;rG9qeGd*p?JZ4N5>_njeGcUQtU+sS>j2DUz6f?Xyd62JYPW9pUN4Er|GHX z)p4Dkg63m@{2-tG>Kn6g&Cc$8I@`ooMu`v>(zn6v92*-~ArWhYRntwYsde@QBQhk&5TDy19bl|!R`7QMuJ5&!Y zCzny1btdVmm6>+DOoZ$#=@j#$3aL#?btPS#*paG;@x>@*v9K7J0S<70;b2%Lb11nJ z({Gi>6;fMi$0D)Qu%2iAh#w-1N3gK??A;j*3}66b3^vv`00ZQQxoRVmnqmpq1W5N% zoea^ADbew(&2(!6$*)3|IYihjS_~P(uU7$;SeR=xM zd6-lt;oeD))73BDr3bZ7CaK)C@{HA4N*ic@1{%#Hwq8qdrL?v5c$gMfOM4N7@&v+i zE~<;x#@g0*UfCCo!*%iXD_z^SsXo4YeYVxo^@X>EdGtAstt~hwA>Dj~$|l!B={AYi zHe5cwmj>-+MY|{V#X6=;+XN>n7tvSJPjg7b)ET$6?eup9M-y3nI?rQs>3+9$P27cE z{6m{2cWfLfylrUC{@C^>*(uh3F?~T7h_z*m{X+6Lxt;)5PZDw0f1uI9Z3W%U)_KCsSkc-b zm5s^@;rhIrkk=<8^xZ$G+d2k+M3!9>>l@fFxtZSl+cTA4c*C!2ZAMIak2+fiafAk) z?IO<7aplR%yy5`WZ0+ldg?8b}qoOOl4o05UmC-Lb?Q;JTMnE}Bhsy52!xAAp^gII# zi+GlGz6_hxZ*n~~S!4QPU;jYu+~sqaVfVZs8=%W4^*x%dKAlmIxBK9nN@&jv1-st^ z-OgMOiOAG8u=^q8!_%G<$*BGV3#}L`vvh#zx4cYdkY=f0X2FirzTL%@W@nLe`a_K= zk!5@m`;q6l_qw$?o_y&np8H`++Dl=_MgM0;Mz(Vqc90#+bdzRHYsY+BHheRSd^3*b zxv#|;N_ux^g?(FFY@Wx7WywH0v1LQbJEp^p*=`5&_3gFz+IdKy&~cjx$x3w%$!dTz z<_sP&k9gxmmzx$gFJjX7=_}paR2QiZh03K3@VuowHCsvdHHpL1_r+Nhw-%JuS2o&) zKswU(HWAy$HHquHU(%;ZJy;Y?WDdP-bh)(&$>ATPQ|JYohWpYFz2LR2@4ULi>U$Dx z9BYet?C!I9lb86mp*cyUdgrsP3HrG;b!R}&u2;^p z$)tgz1cDr+w5SVH!okTvWU2iEoTXJEGo*a@y$+r>OtFxAgttjx+I}kaOFEa@HNEE1 z)52CsFOv2z6Ox1KX2EA4)t8vdLth&QqA)aIl(Qd&x#*nOZ)4eQwbZq&=)$xZF)Y{9Sj zY)J3%)q9dp8{gOQb$wGphn4vVBMj1k+*bjzzCc}H+PMIf001BWNkl(gV=I0@O$BYW-X ztUbRTnlA$tT0Ws;P7W;+hhIAmgorLFewTT7P29C5cbo7%V47_6<}K}G;!4+~>s-FJ z^_BG3SR8-`Yfze6<&muIovgkY?P) z>JoAmH7!Ri-LAfI=d+*Bk$@HDXBq=8O7pVdn%u<{3=_{2LFAJUqkE1!>O8l9i?o;F`P{VHsI@e|lNqW%w%CED!%n2|tJ+QK6{Z{Pnk7Mvl zbY_xP&m?E97T>qIw0vnQb-XoDhdkFq>vMTLUtc8Y!F3ek>~`>Mnt~G-l75`%;C7Za z9)}-m{TgpCT|lxIe@>=~Ogz5yJcbY^)dzAu*D`FeOGYx;O=6}p4wE7J!@exDyQd6y z{as~7B}rGa?UbM`!;LX<`g+vcNE7U3`fQzaGX+v0FXK3ZyFchpWl(KXZb!)xhWW5+ zXN|~_+5ib(#xiWl2L-t}*&^wYKqhT`*Q9jmY@IoXtfKlzBuJM|dY%srTV|ZvPcnpf zZ4n$k@=OcU%3VuavsG-~Z4!5(5s_BTP1BOn)$a8j9~Y6O)sICGTL+Fq-+8d;;3PD# zZ8Biyvc$+H#p!y$<-@#sYvrIF)BB`r5U%;s@*zftCJ5PCD;Hq?a`GLA>fs{bdHBLY zZAnX;o;R&u?!0S~LzAOv9H}n&$|<(5SrlFA+h&|L5$Y3~*ek~7O}DnuhD=>j4^|FCXwV+@j##L19( z)df)f=si$vKYTAG;EuKW$kT>!&eN^b^A;<&){fM?A?xEK8MQX)BMc(ju|&_AfjcbFVv z>(o}A)Q|`fiTL2xmaz<*FMo-!i6MSMdTH0@AhMF6!?r62Ziqx#W}L2dZd-OOZ5kGn zE>EKi#L6GKXWnw*=RA$JXP|}Tpy3+P!tYzuhF#TdsZ6yzrF-}_E!~)VLUOjTNqNV} z(xiU26(?q38>{niq0Rhb28(SB{A2Fd;xx^>iB2JX4NF%G3(2dc?JHYlpj^AB&6l!} zzLFfCL47T~P#O5*NU|)7m^@BeoHpRI%e=N|5+`)eanHu$vdx=LlX7hfS6JGb?DOd4 zON(EV&LNz)fi`TjXc@$m>7A-`gYCteFXG_#0RSM&3ulQjg%c*vEmAUzgD$T&8O@gJ zlD?^PgU<-(yFGI80Yvhe9*P<+(e{n>J6Pn)n7zrmLKs?8pPvX{ytaJ?dbz}9ZIQf-+% zPHMSxYop&yYTweK?Nf91a)MRU0YZGOY?QkFZ`xjhO>#7A?Ua^<6gNg6EuKbdbpe{6 zJEzAqZ;j~iZ9Klu-ZZ?6AJI63N|Jphsr{#OKfX8TW51Ph>xt;#afGPvt4h; zf_&5O@NlB0!4FpG3|~>-AR#|<^7Q(BIZEPU+L^Aj959n3870`pwy4Wye^a*gJez4w zax}qomX5Y*vx#D_$7~W=)I^6y4$ZdEmXo#XZ5jH;#EEe4cUPt2e{_QimvExllA@`hffeDeF!)MWCZ ziN0DMCn-)_a1MW(uY@MHh}91b?`aG3%E7P2$SK8_(&hKGsjvHPqgL0Y_Q_?5?GHlv z_~NvUkQ_ey$Mg~NUhhipCi?i|_`>-$p07}!k|dcrH410=EPQ1B>)5;d`fEK*OqCEA zkKr#vtzO5}^O*M0w5;1kti1E2E8IVIkZI|6rLU0Bc+7qk&Erbt5jrQ~j<~7B>8S6T z4q0tAzsk3MD7d^DIUvEM&2{4fN%4SUhK`hez&YAzSRQI$QXB)nv)7>sS-|t|0-^pQ zVS5@+(pMsbv^L?X&z&s6Cgm5BR}16hhISt({%Cj`eWeGx|Fs~Kug-CKwfZdGucaC4 z`&x#&R2qPh86i({c_}iXerI_$J$63=5$)%$yV*K!gQ=%4$xOGhqvGA!B$H!J-4eU5$O{9GA|LeEfQ>ZV*hhug0$>)n3n~xT!ZAg0f^ogmfS~}XfR1ae0Sp-u3_nrIf z#qAnOM~T1H+bY5mARA|R@#+hB`YTW4+2^0ZGcP`kYe!dc(_F(XdmSSjO%v+%dSP8P z{X_9$5NaPQbKcm=jJu!cj_>=i$rSM-a7y55FZKBLHIz zdV`)mdsdUNJf4y_s1i7$o~%wxzwP5tn_*b|EBY}T_X#1AWN!1CJ_9e4v>66$=@eS%ymhA?OtEpNc3PaBNiy3L!BUPugmx#fX|@rY{^jwpJS#V zcgDCl7S+n*z~f3zotzy@@!HmT9+JiB%Jnns9ME<1rOl7qMo5Mjy{W$3!HGZ`Z96nW znAgeZ>bWo7dD7SJX$$knLiZF#iKoeaT>A1nq&#_8$i7y;#g4Qxp6?ejfnvDf_8eV5p9j*WZKp zM8%5=Z}Wwizu0PFnk@6=*F@KO;>?4t(&gz(&Vr_KtZ)p^JwAEnyBvR0Y#q{cmfk5` zxHfJP@<{U(2iFg9WB&%OT)l#$(IIXRuH)z>hq!U$25cX|*%xrWe~&Dl_FbB$Z6v0> zahuMIF58MP?Rm<8*J-|&(vY5WZR_l7lZuSS7+6>s6nnK^b32EgS2Vx2eF3Ehv6iGJ zyHxH{o#t_TI%_tk;bpqNd>Qzs7d_^-7LC3orL{|6pQP>GDa~ISlSyMXsV;O?uch-+ z=lx_K8+Jo3li2hv(0i(fbI+f{nY+)Rcd7@Ron3p$=q0%M;!TWS7~{#qCvpCp&$m0i z@yRXKS7~NVtSr1g^YvxEde$Zk>gk8-bnF;{mlXxC&yp;rSdwh#<6$+TP-$*O|I4rS z&?~+@!|hGw<2IttWp_P+*#ElOIpQo!3;b{I1a^K?=nkypRG58JC+jOeMqsw>C;i#C zbxL{iQI5gE0LXZz_4^NR9qM*BsQY{A#yNqcn7NYwn3CSSkY)SPX=r)@}iP-9B^I$e2% zmmF@qLd2ZYGU(!iYP@WzKJ=PFRX&h#tulvn*7W4p+XN*mH9fhmG%nRm8i?`xLYqcx zwFNCt-a*l_RvuavoqhVwGqbHNJOr7Hj%^UWnr*dfN_cI_GNGPJD{M))JrV+AD?rTkrq9usXF9>b!2z({Fpo$X42*xNGN4Wj za=8UPMCT;WW`Xu2CZ##NcwX9jzt$GGt)ypoXk4xdUXx*#s62y5x(BjO+zCjouVWov zgz9L_^%DQ)S>Rt^@@E%?kd9LRT058SDfKwId4zkucn|J6eHYg5UlYfac4)DE?>6#D zj)$Iq2w(ZnUqSXdd8w&|(NyQybeh^#y4Iu($M%z&Y(AN%{&w3Dp_W<;L% z2GdzZJ=;TOvZ@~L-ZIaLDf6JdKZB}IkdquSTiY;Dmp`k8N#qVtmyOrooP_&`tOfM# ziKGYJ9*9q@5qLh5VY$;?ile+JS2j&I-_|xB1n@YMiR;4&4sGTV*fHIQNG#3XT_8qh z$<9)R=Wsgvh&da$-nNs_$;IoQ#KKZ&_1XyOf$1dGb6yYV^)_{W2vz%PGI2dLl0$Mx zh0+e4w{2r756!-YUFVPnXIz(1eU{?135}@a$68(0K>MtaT|-;jgmjaqx8^_=v8` zETxc+{JJ)#)W+3KY+MVTUHCG-EJupK-{5cXUHC3J&zR>A)lYj#jCmGF`7^v5?-#?T z!@dU9{-kRkm?hRu^T^RT7RXd`*a%M9>FgXDO(JuEMs3UM zASJNY7C{lSRJ_@@Wgp3L#;-5(Xf%ScVuhl{2s}l zC&lB}waUli`uw92$kHK@0DI#c!{J)d>@DzH-(az|2PB)tliV0H^>-X4#dqWm&0$?O zx~DS6fY)8i!nJ$agaIZ86CCXwO~0>W5(6_f7z_r;wlbIl18gxFwDu<0Q=EY(*xQ&H zu`_)}*UHEO#uP(0GFzwU&rGAqhLWv@!y$UM2UuY8+yu$}NiA+=SvaXp^W&yli%32& zNB*H%I$}o9{op+9yn3E|0LXtdtV==aWMo^0vmYp&t&g$1LI$&t*O=sS+}=VbF??GW z&VDBo)m742YWPwd?ZtT>eY>S9Ses+R%YhPUB* ze!c3f57lda&9ZB4gUg_ic5V+P4#-||5K(<%ZGK$(8dU9Sl{i#acdY5F*;9(sHn?0g zFRCxU)|9xD$Q-SHcWL8!XWVi9B<}@{tLdYaHQl!fEl=MyN#CaFH{IGsQ+*{lq=C1u zO>6l{aZdtS$@S6F<@-=tTHH1e%L+0!uPWw~}gAm6`$jrokSCb$px$>mPv(`40Nrkf(Nj?o!pA{xAu|FpEkU~K!L zaj4@XrdWTgow$XC_+}1{S4ny}2183zCY)MsRJ!nybCa6IbX|r$C&j@}r6Qd|HumO^?gG&-}$Y?t8`ENGFrRUs=jB z9`@_;-KjCyys!ye2CjeZI&i=AV%i~MoW0U@UwJnP59FJr1KhF$42A=Yliu`xn^|BD zI4IvalQhM8&tkKO!l7UK8cb3&@>BUXjGa~fqvQxj=?K@;>vefFnGBFkGGK^`-9v4* zHg0bjhnEj=^TnIUvJ5c5V10m7+o!O$zEWj{Oh>mI z+kCLFwwS%M*{{zUe&THPe2g)WqMlzVQ?J)UZt__exfa#-CEH1Th}NgH0q&dgZIYZk z9S&_As^!hYX`TV}YECms@^m#z$Ke4K&NG*1s1k$<6sW&oNscp4VA10)b$$TF%myd7 zkI1r+r*vr*hHqTo;~=qss*NSbwx$m!?|^FK57{`hb+OzWFq@r3^OAI?&UdLkyW@n! z_1QRvbHafW z9WIPw5#r8Aax8+(cTQJH7rFseS>~zNp)j6bThQ`|*<#X; z$-}4XNzs?;<4e0q9?P7F0A0iSL$?U=@u#+fnon#pr!bOz}`ijDId z7^XuE1_M}Y(L*1n2WNpa!I|V7HhLQXfbn>Y!^t7~=wo2kklP#y5@ZJ%&h;-KA-{n6 zQ@(Vhq(c)dVh_o_DV{|+1INhi3cxquCvh9ks@YK!-NsW@lhyKmR87YVPhBuD@ynpm z`%IlMb9tS@!;1g12u)0a1PLa18YvPC?5j|GJZmOXLB2iFSgyI+_aZ2Zz~CL_UdZ3c zM8ah|f1-W)2+n_b3$HsokN&e{3X}y70gUfI=e^g!VB?+*oO|LNu4k{s*|Y2$XWH{C z)SkvI=-h_ALuq_dVPCG>-p%VsPMt+R2PRoobf39JZu4pXU~>zcK96y3afm0exBnFK z{k(AK_j|}~j=^v+-4EA>FvegF>zIr(V50^7n(EwI8?qQZKf=+?BV>6&=xl6k;PkoE zNRxEhHge=h(-dn5YsmT;MuU;NUH5bHv6%M!lE!SD7$EXGs@?*{5^S)-@@vxvKvXGA zCX<5LVaPJFq+!S&lD_=9luqcpE%^8b-*L#F?X$fv?NAyDdX-r^e8$c)K*=1st98d!(!*UHwH&!PwsNIqR@xo{i%>a;W-@r56Uja~hfbZ#=njIn2^ zE-i|A>`U#}Rr+1&yNFD{;x;}Gow>~_L9Pwlg$>*lp#*R@-cSvwCHd%Lb%)#E z18J61EiL&*oZ@ zerO`cCuA97`y>hy@18GR2Q0Al`Ma<-JeYppV=@rD%pMqHaPc)4@wv-q@RnD!Tt(1Z0%ZwE;MivixBC*k>vy9_G6w9z_12lTe}uTyfbI;G?CXxZoTcMHXDCTCvbdf3T7^*JH?c82@7m6EwvI$(Q9Yc#Qr&i&vn#!a zJH#Xsr)x*BgEr&Nr!Vc$o3vxM56wR7ir@gM^_lAI5PFbljwH!}5V9`~>#|PCbyqt(@>l?q1jmKXPfjVG5Ut|?@C`=q*twyOd6EMOkRruKZv%NgGxlIGz~0^-*4EZwj6uKO$I;PIC2P@vN@e0< z(pW+oXK417(w538^8CH`zE{a)K~TN;IoH?4(Vk88+_Essu4(1&^u5%9zFJ*vQg=ho zWuQ7EM@XaQAZ)u0yEJK^B+0GWIVNp(Tp@Ns`UI{^ZB=W(#uOy)!{;8x6IbS#t;6Ng z>iRr=ZK%F40&WB8-Cuj|c*Y#(|MQC&9Sw1JYO%Rj_Mry2d2tf}kZ$NpuTk9nrE9Qx zj?J{?eQ0mRm4$=0zp^2JlGS!*lAjr$Qop6AH23`vq8 z%d#nHon=`Oe*#!o72L6po9;a?oaEQCR2%hZL9F*zGxqa~yV# z(bvK0&Gk*nEhF)o)N6X)H5SnqsN0ygWvO2KW@B|tR&r;*(^;#lKB7{4*`&@u-;BFu z*q9P`8mZ&tr^`lK_;n7|X&;f*bzA27hWaF@ue59?(ERx%g}3b_bfB}bxRck(s1162 z?HGvDH?(yDE{j3c>96T55n1%y?WMj;(q9Ve;@K?OK^srG>rmpvr0vsDiZdr(ZeK26 z;6#?MUej}+t}`D=bA2^i`|A8dDApkN;Qh)6=Ow(^yt$s2@0)K_Ha^=_dkK|v)#|no z$G$oC)jATqd^H;bvo;OL#GRJ5q_3}zcc`y@s9bVRtAAWR2Z@}G(OI*z=e%_r^E_ys z4e9Ues}ZrSm`N2jla4H9>AwO?MRC0W6)Ysd6HsZNLLvVhj??9)-| zcQw08_e{31ergC@ug{7z4cewL37)%k3-=x#!jz=W={LVQJ^>D?-{RrgI}tzUD#d7AAL{AM>+QLJsczl zvc7Gg?Y@~Ldn32C@89%#y;)yU+AJ}}K%jE!micEn~*rvWYvXPSa~$W1bmz^aUlRUTZpY{fQ&EGthhu**i!Chug>6 zSZl|=t*icve-A8X7Dq^DN#9tVY1}TLecw)7K9cLYXkUFCHs<+o8v|9HG!le^>l@Np zx*mb|NFRyUK=Yu-A#yhK{WF)g+e`fx4fDhakywpEzj5dC(riqx0gLG?IsH4#n=d>-BKs#tppunY`B*f}8gMZB)lYg+pJn1oHq8|OH+ z?0Y<2=q}Yy%dSarrFIS>EuL3szl?Uw&!u-Ie$CfcSs+a}(94goaqVChvAn)FNP$bm zH?20W9b)hFS}l$K;beM#_n9-e{Pfc}`;wP5)lP<_BiDt-lj;P7bLpDYPNn`rvNZ!G zDBTYd+$DaO>7hSXg8>D}T^{g5+^Mk|~xU&20{o7PC0=d)Q!CYump5 zP=eA&#^@e{ua0uu&J9NUvzaEYoZKuxx`djAEoL?K%l=ta0)6v7~dG&fw$H`9Ty!2L-RdZm{0ug`3-#+j*Hw%~3eV zzk~L|;yMAz#*~cm*;ylXmf5CV`;BpOYWf<_Jux<3CUHk+81ha$r0+bA!sE7alcgiu zBJMcJvFurfT@YDKb$0u%?aY@Iq&iD_Xg2n}#7T}oZC27U+B45DR9~gKAM?MisoQE_R0z8QDU&NL3yFJ^2i z*^*t`!WK3+H;WhT++y?G2Kti}Svtbg_6zu&eGE744V=eWzycGS<9h!PH|-Uy+fC#s zeo;9@9}|r50=|lI`ODs!-li%u8B2Ef(>lQ48ytAq(PJ7-T#AfUK9mIl8k!igYx4K^PoP&_9>}ZY4FP9MWEI8gw1Nncw|gWN&>d>^w`b zN#)4xt?4T08C&SA=E~heo@aLY2S8# zEy)&>r>~FWX@|~3eRw1aQm4z8%%*q~3df-%bP~4lmo^SwKt3nZag$h%WYCB#H)z#f zKBbONd-*)>nOF{v*m3eocBXm*x}EtZ*?8GbV2%e+C3b+Yok8}YnL3)CkBhwHPFSh4 z)ao@yQ+fXCy|z2g123IuEEz=1MxQYZC$~&VW+3BUOV|? z#?`!^J|X&=hX6~7O6i?Q>bDSx6Z7umv%3Y(b<|(K^a0>2e3oHbI>$VpnC`c;+t@qU zLv}htvIZQD4{^Q{o`o$2PWW;VF9c$lADq+Q{kR#?vI+T8nkNJ|lK` z+O)1~V=-wf<9!;R0IdHNjjwR%;!WdDf90&??`-UzLsDWns+s%hG|vN=wNtGe%Ja8g z1U`>X6vx<8lc5&^HVKRGnmfbyQs6k~IVZ z!8K@O!IIz(jfDWg8x8L64vo76w*+q_c!Ik-H15#2ySvNBo0&KBd+S^4th@Tpd;8Sc zRkf>XAAc1IDdBf(1aA0EU$#84GU&cpTjV?bzAZ)YV-g6WXu8Grxf;lET*^NQQgTz@ z`h%%r=Me>^+UX?`u#3Q2p;#MF5u&v)jr6bRQIbKy&8?l)we*4OGh1%q{bex3BX4iaHP(`Js;+ zW?wCs(!0d3Hq^(*h-S=rXy9zYpsp5;X}gAR3%_yjq2=yDk)U7$8}rbKCQN-tRT%e9Z`U^ICu%MrKdPxjaR_Cn3UZd9rzC z{<$no;GGTWm10o;Cl99;2LCS2O73AO69+OJG5e()1+fdryz<;$u8vM?L1AFVielMJ z$~)OvPZCT{*I$qYF6Q{oDd5+6Hi|;_{DHd+&jPLeZzEnC8z4>`@(~1cCquWDCqttT zuFv6cWi$@xy6Mc{E9Q$!JlfsK>c*T-!qbR{Frkvwk4y}5)m%B$9EAEg3TRLNnon*m zW?I+hMd^m*mho@9c<4&3NmW&dZJ%oV8X1whw;b+;%Bf6T|7}q?6FK+*q6zEMRHgW4 zMrettSjWUpD&rxf2yp_8-i)T>0SftB(@TZosV@a)oOMhow$IU`b_r`LR0{IgcS)Q> zsOs2)^X&@BB!N~}9>m^y#p50-m;j+xS8tGj1ytw6uk z#wGCBXTu_$H2v#~IoVSavg8cL^%2u1UD|6`b^QUr{t77}A(AD3MZ#gNn$ZvfH?_w! z?W9NS0$(J*HR6pq9QGkk?jp+|eRh1n5Y+sGzTo$a@qnVY8Ih_<_Ta6#adiD9iBwK} zhRMoGzaosd{YE!@ni;chNd~t}wA!}GDQtGlg&(m$|1o`f%hv;iw>stf)2K?-c7DcmBo` zIkt%K3)%S->Ve5gS%|co-2G}ql>Q##E>D8gO$&$T3FGIFEk60jENg`b(D&vp)H zZWA=r^i=`4NBse;Gaw7N3%bB=8Y0Y)-7C*8O4x#ua0$tV`Jg+s6q|t?k`MELNJa)t zsno3t+QE-eJ$AZ?`hGb%)UuT*@ti4wp;021%8`fWnmjSzB&wJ@=&>5|N5~nE_?cwP zP5{53*PaLas$8X;Z#LQ=TJ=CpADjv);=O1uflJjs(sSn&uhIk$w{Yp z*?4bm)@Ax3v7&Da)d2T~juU-=aAXDEP^NiW7e}}>INha^+o-j}2ck}3sI{z1-h#uZ z^ly7HT6(@k1l>Xy%U&BI3wg_ry&+H$^-o=3jFue`A!>iXW=L;<&+tmnc0Kw)#$~H& z)XxtGN<5ZRx~`t6A>QSKH%*bqNd~!YUq-Oto7Vy# z)wO~CSRF#Trf_g|QkIz#x-~_Dage}Z9I?qB0gn*UA0xDWVp+)Vc%#?@hG`ce%ncJ| z+m*4(u9Y>6BtLp)H1{`G6~7S5B(=?s8C{_b+8mFa|_!U=P>CE9Y1u9GeFpiHsF=V1!FP9DSm!Ea5^*3iyL z=?Mf;8FlCNJIe|s)b+tkI78HeWp>P1>4l-U*V<$grQ71h(M~%pC-uz0_h;}${OexP z`>QhjlD6o$qYk*_WWyPa8B$pj2u=r*7HR(aAX`z#_&Cncw+gR?IKEB;k9S0?tbE0= zCk61@!C!OI#LJ9=m-urQHddsxC;TT}iX5r&!IPC`iAqQo&#qipB3JPmc8_&NU=4!t zLdv7Sw)YoeAsr#PgCzgYdkEjo?Z;9Qn6I6~T9CF@i^cEl<1+5Y@W+OzVa4JQ$w61QhxR0;pU$obt`rVC*UccA&0dGO zRG$^h!q+g?lW?$%3}#&n4Yn_myU&oD7fh{6vmHdt^!|2`w@@dw4}eC#$Fy;cH`a@= z*E_nVk~npkQ+K@Ozum9?2KU;Ma^yBQ%CMK_gMZ2Q-V&PalM1tFJo%z0mA45`dBYSu zFe+-Cr&8cOO6Ta~sxfNzIijqzmyv9b)J)oyZU;sOvp;)Ju$?GkN-uei-!NRTw}3OY za7Z=CPSe{SiD&Gtt1*uRhjic#knR2bXJ=HS*=#Dqu!~%qJ6OI z>xiAMx)wF!vK!7VIxWy|pC1?eC^Pca*644#6MfsNq{VkV6p#e4Ho#1tO7L&)>ph%K z40^tvcoVi6EVjx!LUl1>hYC-N4OkdgZ~Zds5wG~a9K&vvyrcYiwL-V$A&)|y2-B6Z z`#)wff-ijETkYiA_{A_3E>@%S;*hxs`_MgnU|#*jDy5nvW3{n)%kLOrRVPt@GJ$h= zZ7;Nhc&Lr+Ix2Ef#T$k&<#N-%Zq?;icd~q^l8$NW>}TLU>Nk_Z{`4djy=G5V-Y)-G z(Q&*ohm1=(CyCm^t>BHEUwHvG)aBvy&byW_lW_q!F}LK;AVeH-cHGYc&jSG)){!kO zg2oylCCXarS`3MFgErBOqpVW&vlPcUp~Pz&!=pFWsJoUIhPB5dP`IS;d6GJM->DsC z8?^HaSOyhoKcy5)gi7?q4bp@r{EAVo2XP9~+r05sqhGC*6k?R(w$PBuD3v!W&ABWc z&&mYel$0)Ip|}i6@1WY*br|Vg7bD2RT2JLgrkz5k zSEazGO!!yN>>MLR!2lG7%pC0*eP=B|Z(+7g&N9g}T83&-OQ|Pl`oPy>F&2`?4cKqe>iot6 zPbV?yoM50-^7oMp439f#o#x?7Q)84>YKDyYQp4FH?Ebl@tj&QG*6M-LFdTQ|bQpD0 zE<6X_o}v3@8f4ATh2{n?mC?TW?FOE;#j48rHd(AOf7%7*7jKB8;Oywun;e<)t8t0Z zOIF7VMXBYSVH`TsfYu|=e(~=-C3e@=B`hu5lyMTxncFrh)IJ}*T#_@aXyjLkdmMIR zf%wp;sGlYQ{KA0jw?m%?Vbbmjf*&1rUK3R*%oVypbffpN|i zS-CJfYL}CQRc>ZGT*eBHm4ek%cSzi3p^wfsY>H7{t=5n+HT9nL%Cwv9vRi{N?+^1v zX>F}A7K?KCG|Ag&%MVk#?(aS9@3=D6eP2GDhI+Z;I;|5CsRIXPNWqfO^m0dN0QH`y zC~#D26HeB+zxFaYM9TGQ+G>xl=fU3bc|)cUHaQ0r`WiZ8RS>vIvuU8M2Oi4Q5If1- z(=?ObHXo%#4XfWMZ=Z(gh@YzjOeTR4;JyWR23zE^NjKD$-`3^;^jaN>SI+bq@O3cw zVSY;&h5K?xVn?8|@tp*f0;c`i>&tQHg>0GJQM9dP$O?jMTUviNlrXi#Vkxn7yb^x% zIR&A}gLrQRR3U^ZLuw!O1swM}S(p1K7Zmy{Gz+(zZ(i;ooofx4k+O zGdTG&+!71EjWJUwS5V3&j5^@{y^2u_-pPG-dE`=vGpc@ zk5PoAd;BPOm@}8-XZ^?&6?*MWi^ zdDfT1)7HV3OXU{YpnJ=2_UU|d0j|=Aa2%vfM*EB#(R7VF+%wLmE)P+8Bc3~$`WalT zCh##5cv)DHwowN9_LJIBWA+Z3QGKM)-36{h2f(oqvViY<7vvOU<$fvrH`7Z?(1DGb zI7A7pWach9zDIwJrTh{0VYdDDqoawb`*V{3-av@a7~f?i*RQ;eT`sjGt144B(vMx} zk^9;S@5qcI8yV+5-15jM+>l=_V^P@cZ4EHAN>WV)pe8KmHb!b^1)NPxUBE z#{VA6Um=CJG>JRexlLmc3gl@$rvuqxHCZjFut*=D9xN`a=wc{Q99=IiQ|*8YGb7*H z)TKs=(qtr-Udz4--zistatxIuL7u6PR#Z#Zbutl!9#!wQ5mAs_6Zyn3=Po8G2Ye(GJkwSVZY6v#iG}u*%CHNXV-R-!2aMz1A zn5YkmSBxnjn3y9QK zvL+kyltyixPNMP%mOHJLX{R2=b$4rFjESO>sT_}_S)$$f=tR=!=+<m1@pX8E& zHoJ2W@IVmdM^UeU%kO;H9){sTu4y^3v~kVHZ+i6rW%*jdA;RCwwE(0!56`@a)Of1x zRlVBuG&H*Z`|J(~iqLOFC-uHQtw5r!OULv#n|$u^1{71Q?gmp^&oLEe>PQ&IOKV#( z9cK3&4c478wd|ZtJlNp}fzY?Bk4C1?7l7@u65zx3egVo-kj(Y33=Nan5u>j_CZip& z|I!JSyG+$l^-kGLJL4bkrd*cU)?(Pj@I;DS;DI!OVW;_cI^XxWVk=^He{7lQA<}3!~1HK3E-@L*18&oD@NN!DuE6M=Q$#_n) z_MPRPsoJ0{M#sHK@@a+oL~ve$@E?4J1|_H~)rmQEY;DE&i_1Gv8H&e*Kz>zL7OO${ zI&=vypZ7q_g!KHhhlWX)4uL8BCUcU17{G`ZdcMk%pvnZ0A>U~p{-+{@J{B|EQREVE zKx_KYI*lr0(Z-?ID;O_Lg)#)|mA;4CHXFoTEI)yBECY!4DXR4T1w$<9Y`M0wf5MtRyjK zd-6ijN3hbhlr(t*YxZI?n{40Om|3al5q-6`~N>RMGb3B~_>5 z>=imB_J>^~oPZB;yM`$BhAKiL*`k(Pn>G#BH9Yvn&D=~>5E%e}Gwd=b&k(s+MZ zxw%>VZU3jIkQ17pwN}Ksmdr8i=?*th$7q)C?cuT*M0S1DsHjBR-or+#x%}!)#zUvm zY->x@Fd;Xa5TJ_&$$J5MwE$xSa&^Agj|wrT>mggyWLHtT>LR+HeEl^GXY8#*7E|O= zZM)OSRXM1FPI)*CsQQ&Ra@*W#o3uWT2zJ{2MtMLpR^{N#ZfMzpFHuNGOX0< z(iS2U9m;)Q zRP`@odbKEzl(SKDvI~y1<27OFE)|yNB@Qn~P1@lvJJHFrN92 zn!r1+{;T0*@db$yN2o!2|EWiC_dp!g9xbo;Gv|Z@1rL_(daGIsdR-Oi?DBkXiCO9T zHDJt!uj1WhloY+ki6%?VRSURQVsV=dJ#9pvHAi>c z)E@XBBQFEEUSF0_n0X&ooMew0z8)&j7ft?pAz3y<+TN8vmM>2_F*sQ#k42E+iDq5= zoT$D~0as2gr%)XXA;dS7m`Hl@3keux8rJRauK~=udl{T_x`no6}`USBxG^ARySl!w*A(?jk<|V&P@7P1(znv zrlq;yYrH~Aaw{DV+K6-~=Y=jwKHT#C+rZIfJ&eK1-#81+lu=c>s`LzS#qu*|Ku#T> zC|sZpOVhX5myfYt*gou-g?Kf7LYQIWDWjlNC)0`WDGh_*_p0izkL@mq^bBXP9XA0K zB0w4uaM0n>n$QnKsW9GxfK=Xm{}9pU1&sxON!;m&+0pqP{O1Pu$)@r>^NR5btcEHB zP>T|5;YsOZhqB#F<}ll4*LjY0T~Tq3&+&V@F)p*}unYVlmT zdx)>F!Q@0@F67{I1rO#;;{Aqp_ry*(lDC_$`9NK2h#=pY$@VBpH()+9oF;-Ra z>g&qqe+0G%5#9%Z@>nBu=4RI0C{!N*tY}6UM^`>1{hW=vH=&TyNR$hn%^v;STG!qb zlajT>_no;1X)4KM%Y~}$vyS-S3ncN4)^c!r=!cvkCZm*LtgnD!|2L8s$aD4WIi=AVbRva$9 zL~2r~Ce3*`fIF;*paZ147`Xm2_Yb^xdlx9?uMH#m|6>by;S#6so|&JI9U?0J3rOBT zA%|m`gnIHo-haURDq9 zSI#xS6H#yCuH@o8+T3m#^_kAYg5?xl#1P8w4(YqShfMb`kpzts(20%N=?QMq8N9eh z8))Zf3O;5Ii$Ve})iw$0t?J~`rzR78ACh>E^A7Ij zz$dGi)S7O_lbNZ)5jos$2miFJGyyKEeIi4Cs`ZPU8k}3pTk;uHul`y0SI)LcVEi3F z7!aS7z{fm<1C;*(W_r)x_V&<+V!x4C#f%~N^4B{?(3{ut1J8VdPS7m<(C2(=*GMkj z>QJJX-uFuGjfDG^{c?F_89wxKlt=l4^qODwzfYvMMP&k==m7n27V(sFL)C3_D+`$; z6Ki5U{(Ob8T%Ho1yq)8ho-RTGrPqQfMwHHga|(hVWD)ncZMX)52X4wAto&1?7?jNZ z=fwZlv2R^IXI%^jAwp(lu1JV8>0Vf!~T2M@=r;=%~y--LfUQsvU~02sKnmI4xyn{v-&rn3tgM~e$MtVOewTkOsY4DTy{P}sa!uKlJ5dVHkaVWiO zg_rfVwTfmn$k43maU|MqCVUeS4BfgrU^+b|8;d#8Msj7zI)2>Z_{3GN0VrERAb-XM z<)(n2jie6iTl?!SQ;m)G7L=l!n~($^C7aHV$)eyc-x*-i;H@xfnwCGqtz4@~+`cfI zaLhqU1_~#Ik{2L&(WL0^q1--&>)mz%6Zt5bj*YFs z!`ry#j1n~za(t-w0*fSC*p%YCX!j)YgEx0rNh`As#+aE!cpqHggyY0fAOx4X|4JMG zD}4XI2X_0>^Lqf`m|8;~&Pe}oh!58>m!F3FNLm1npse|}hV9@p(yNKbSj~*r3#tv+ zvvzlM_yWeyr{Si(@`q8HK zi@|ih9l-kFx0HM^li9dQqX}(u0p9m9qCK)GLF%BKCbY46HKeSw$O_o}uV8M&nQC+6 zfgq3`U(OH5e@rS(FxwL3_B$TX=0o9jJ7})9gE?TgQy2bpeDgl~Wgv8OuT>ypLYuRA^lm;>Z7S$db1-d>#sSWxccERQyd>B zgf9{E@CSE?FVs|T+HCV@0=R16aYSdLcto-zULBmkzYZuc&hW}u0647Mk{PSnq$k)=e>;%sJoIXhg z?M6`-wMh8XHEZn=<6KSWSymE3wa)xOQ6`Hex{;+2l@D2~$q0eVI%)7aZen&?Bl6B; zG^kp#0>@^JJi|MvnLp-+b8C~^uPNY6Ge;FTWf4s4mtwcWP?*5o0J!Paj}Fu4Z_{Wo zyMcU7k3rb`PHA=EsSuYOFHPWo&1Kay$!uzb_H_2H#p_M0`kbflWO);6I?zO{vgWHT z+XVfh?@;8|hppz5Udr$6^u#f-G{-q687fgCskxK*j0!_zd$fLUea>SX(~NTyf z+qXxzUYJBy%}P!d)t``Hk*jEJjTY3lqc^DhnZ{jWKIuDPOQx+X?Rf$rbMX89JoCEXZv^1#T;?cLr1 zrzn7Yg;(kf7C|2B*fh3B2tugd}T$ufWBx@k7QN1v)cO;I$@2Y5K;b!^Q)w&8 zAs{3jDx|mzrOX$p-4=ZnxwKqIYrC+zN7duF^`I(#Q$Fci#T0rHUXae*toUw{cxoL!!U=oHY`O7>rx`rHZ1vO$9vB*6oU?57L^P`)f|Hp@^wQcO zxigzY$KuQ(wvj?;P=^al>8MUVF8x!i5|=HYy*P*rBPajN@#pj3doLTdy)~a-e@VG^ zz@vOKt{@0pdK3~ih{v_$3GTOLN56H(Q&W$6LJ!u^gH(VJoGtI)-tERnXdUUo3sE7O zz)2djfg(1d$p5S$ZfKVE%}Z2mEqhnf486;Qqi?$LHic0oFMq~WQ|fHAjd##Zz=3Ta zcMJV<`JKS~-)aT*zg4y&leM#34^4%RRfS6L<`;Hvv4iRbn}e^(j)b=8joiGz*FYIb; zn3B!Is*=aPZC43hmL#3CuO6w{M;{fVz^SN+G=D{Sg$25~7R0ty8&IFWk zNyU#X*w^kE59PFXwcJ@433skxD@y#|F1W6;w^D+P)@gbxn1!Ei@lb<}$OHnu^>M`v zsoRxwpnV?2Y&%)P+9Ar zd~SX_RccfBK3B75WZuqUXxNtfvVu-8&P8)ASeD{1;qafP>oy}k5#Em!HTqR4bL_T^ zA>}i_*Lhd+&+5Y73V*o@#kRw~v{74?z4n=d@o$wr91T3f+;soS)(DcI*IuW+p~Gs+ z|3$}KijkP3-x69u42Zj~tz!WY;JEy+X(1XQ6D*@|`MGkA>I#Tjh4KjNz^yL$bq}Lc zhJ{PHymt_ea+-{+5xclT%7)n3fXk7DtF><^fDsF~tQfR*^wSP9qW!|CKwXH7!lQ;GfSRoO1x`cgwSjCE_(%3 zc0Xn4fw*;+GeYx3m-hE3Y*hlJO)Un-<{074OIS->2`-5JRigy>;iSf(5lLHMJaom2 zPp{QFC^+l~Fo5#if3Hr@Ezxm$W_P(_>Yr$;{yEyuOL|X9#_> zPJb@ieTS@~=@}m8t9P*8OSr8?@-`X?)kIrO9_NrtmsC`-EhqY^K7d6T7C>Peyw+V= ziWc$14t#?jKWj z9=-9?NuO5_n>V#pHFELrMt+o@tgB`>WAoAz_M?#c9agdo^IhcV@(t_1&l{Xl8uo~2 z@#mRNP5d#^D>sKnlq8m_M_@(x*{RGZffW-b=Eu|fg)Uc{>bv4WzAVZwk)OdPX%Hp@ zk@)9W2TN5X8mFw!ui6Ig zR0&qT#r46!3!Q#N%J;M`vGc&CRCFyM0T6+-&IU>`GR5sItliIzj zACbX(!!tfXT~xoL|MxsfbUyIR`7X*ft9e~KfoY`DSqizb7?X$W9k1`G%M<&Idt)1^ z#P~reO&^GE-FgoWjdCCr=4FF3rX9ix8H5J>Pd=IEJ}*2YgHHR_T$#3#A~P)_}l{)kW{%{KG9KN2wTx!OfC{aqeeqy?!@>Pkz-f^$Z>zH_B- z;#Evf))SnCr!@`Px0|!Ut$|klxcgxMXIh`=ZOP&C^=fnQnCItFp2?x5NqmO^ZT_CS znuXn2*c{9osgc12Ub9`f`hGE}L4`K6Ev`AKL4kpoxnroUA3Jlr0(xUN9kuq9HDpld0TIZKuk*-@e{TDl< zSQ8`Td$!qiKs&voeDd|@<%Tfr)wwO&XYAz*5NcT?2E%eN=JIqi^~D0RM7^6#LkKWg zoGmXX9*qasFP0i56hk0e4+jmjZ++%lFnVLV-Cxw5<9b_j@4LY2GluQX&LpVp?%@Nj zhXw4he^5l-G9~YlX2_q^a4P1L8oN}GLzZB4ilM*RE-2Z+#|(YMMd?J?mhjnRi&^vB_x`D*US;X$fIx`1L(YF^5Fl@8nB)=eQIb$5#|+L z8+D!9;JCl^J%is--vk}dn8=2psdwhI+e!rIIiv@;7I9EP;hpT7W*2o@zs*eyI zSDE{MP}Mhns8$g5+UdVs$NzZ$(>TiOth&)zcRA}1KUH7Z?_xGaLPh2=1&=*3?(Qxq zFH%B;KuZ>~>ojGv)0^85DzZiA#U#Fub?Np`%K;t8(OQFitUwaBHXXcZGc3%T<$39t z{!ARL$0e&TX%fZ}*RYwD+nT19nH$i;ORZU1sn2|^!xZ=P&nSW8Q&-O&}>AN(tL@wb@jS&-7%l9I!ro%tVc#iXHFm7}wmv3rBqbyxz@5zB5 zlZhkhK7kctU(z~q%|{2dlo^v`yhug%eqHnc!iX)viD-t~2s!sm_U{Or^WG}0-4n~+a4_$pn_Y-46n z0FvAMC<9P1f@mXvb@BEk&YH!Ya|P{Znhs|<#RLSfoZF0)oT_; zR=?eim`g{gw*-_|)SM^r9p}jfUrSdiJ5ismRbT$X!N#@hHip@IdleJuhtbp-2|l(@ zhUZY~Z>pY);9lA%8C)%)DRfbTehqn@koO)dsgXR;_V8z=L`B!!#cfr1oR5i)KrCLn)je94EHLJv*<8m^vZ37Q>JJel!hcV#_}{6Q9xb(HcH3-;nA_PD;A^M~ zC|D+TtKL1$mCXDppBx~azC9<%D3C)PmY#bukuSmD6|WI(X)-T< zBW-}bE9>tL+zRcN@2cizzlZo1KOk`@X>wXtt59lX{=G>~j?}}`Jm-SfAmVm&^$4(Q zdTD{z4_1NqGty{;emI2UC>WWBP?>{7L;IlY zBo}hxCef@T9x^eYauXCwZ;ls+s&;K7{iTJWYh!vx-z>BcQ}K6(M1g^%z|@fq(Fd#z zwA#`r?*(10Rt}m8%cc7Vi-^hwsPYq83aHWZ{>Sg{C=>|nc}e&gl?uagpTlHgxT1Dm;iET< z_nyOje$%>gcU*WQ1yYHETfAbUL6l)7{8P`bg{3ccvkVab~cPj*7q!TQ+wF#8^UF5{t z-|~|2dX6fbFX$i10Cq0ZFiK9C5~caH$#e2pSsqI6FOS~pUDPJppnm^%FTfxA6Xv5( zo&H8G=U}OYu{Dpb%?!Sz)a;1!e6Ut}tFX;$tc>!bNE-%&R4;ZvJ^xG@Bw1Ja8~6xtsow0j_a0#(y&TW` z0?ABZTU=bs5{%Ik5Xvj4bW*$Eld^;JBQ>R>A3ja~sMo!|{OBBthkqRSA0ZiX)g%MK z25rJ^$W(qVoe3|XoHvFjxPVC5KuR(eT_J;(OCu#Xg##k*_EaE~;gQLzEwC+SwdeHWi>LA>z#s=#j8I$2eZ|0YOoen7eUv8-iu=DOtseCIcm<8fPY?_NnFRB}+A z1RhGOVatTwzjinJ3kru$T>#V4@E#XBI@07^Nz3dN{^MB3DhQv1XbI9$ZBO|2Y+6cNQ%8qLnE#dP<(A3K@RT8K5e z6!F_>2yzwSj2WLXn59_9Tb-jEEvwS9PGpXW7y{&+dSJGa*=H84#r8I<{_*pmM?Tmn znV_nzZgKG#S&+GIxxO!9fJFz*7}PT=cTEwx)~R{GNCpYK7e*?o?KX7BgMV7yr@cpM z{eD&R49>eB;ZO5Eu54RdP;tB6{JT;?P(rb6{c!q?Mu28&0Xte48?~)xAPq+a*Y1|g za>V#^I!||5v82u&mPoX`e*ivUS z#0~pVpuh$Ww~hh4wEuSR-a^K7^1eFt*Wd56)jC57Hg<)j<(4MXm>p(EEet!8^C!&% zzE{82dlI09TlZtJGgy+vU-ybL-p13QksaJTpnJdzo}XG(u}O_t4P{!4QCF^t_sy5N+csTZNdPtY;Y>2~4#S`=5zULT&iaiH#N{!E$;4qiF zdp+x~Zm5G#p6kLsA6)EjJ_~4}uZ60QdB1yDqbrLEHO>T(MJ2B+(@Wsq`tXZ^wrnT2 z#3sEXRE>ZAYO&GCXXR6UvTmqkfF9^FmW-x0srWvtoCy+|?=N7$@7O3bBDz%T;kBn` zNZsA-FPNSQ6pZL*NJk;vX9>kO3t;VSJ&x`AXasvYM%c>fXn-KLsa3fvBL$OZ@nv|f z(k9;G_?D@7?;3;p*LN4gjMGL@TC* z{vh7yFh)j}71qLFJ(&Pgx6y>uicb0#|%9QUsSzUeGpC-yxsOtJL66S*X zt-m^2DaHlr@aEde%1Wl@ru60DOQo;o32qPaDOMXdXjeuiy8jKm$UlRH1H~884tzgG z^WG5Wo86oin-f1ZHM>N|fR5Qx!-p_u(GRLB9tV)36fCyB?SYh0c+)g>*<@>x=X8KC zs%VPUf#p?>)`PR*>`nG8WtHsCI;}bvZmHTecm-$yrwYWQqJ1rdXwJ<0KRslYj9#_g zigh;jlrHj1B2MmZ980shl+6OOCb7YmU&q3Cm8q{hOm4r6(*`w3b$@Rbg6hta;)vr& zrNW^aRVrB7jf_^5O7KF?r-q;Wqzxq3m^l=o=<@F*V(bB-Yr-#?Ru4GK zItZ&6JfK3^{6;AuL!HD`_R)kl_IQ~QyXp27Vzj9yN+s50tealqZ=it%B51apnP(#NSUi)zoKeTpZix4v`S_A92+9` z2$mn6QAP7afZKKmKQPyZ^=QgOcJeaorNrV@t^m0*6E4#lHe`Jz*+;)lLd0SG=|T49 zuh1NXJc7aVX!d;ZKpygMO2-9c*m;J#GlYv5SUE(mYu%l#^y_t)IW#bUlvYy#ciJA@2j z-_}Yy3NOKrb)>qC;C^B!I1_Utv=cFROH^i?xO{K5)VrX0xtgyZTwK)t&SA%#18a>0 zBIa5Ps)xmo5k>|l*;Ref4ci01m7a`5Dzo--Zo@-No!q!>W_tznZf4JZm)}|2IolPZ z4AuPZO&)2q5h*zE`MkxdYE31@y>OWz(E9Uy6_s*Qrd6;I*# zNGr8TAgX)y8X>hF2(JnV68IzU&t1hqEBH#!ZmS)(OEu{-CtOH)@?`(+q*ZRH)7%84 z;P6w5rgl$9ozR)Up)ysz0J!*6^S*TAO+M{F@ehtyO=ioepU|WIv#E>zfHIT9$LYr< zm|h$xt)UIoW9{eoWytHwW=E6~ixn%JLrkNiiQv-?UlPoL_l>gq`_a-KVCrNR0%hg4KUBNOV_kQZRCr{3ca|HTZi2}>9{Klq?) zy@1`x>qe%zYT>(Jon0Bi6M4d{^vpEtq`kBClDk zzFM28YUy_WVb#|u%k`n74k>f4ig+L@duQ76Gv9hYTP<~;?AFOSg6;baS{!kZeVHgp zuK!up#D8Hvx_;VaJ`KhU1_m?&4d^dM z%Y;oS@8J8;kHP2HcV81 zeWFO=WI2{!21I&tI11l&U5*C3@hp8?QTuIZ2cNI2SKfKXk81Tmyi4IfqFJV);m%B{ z=2eq9Tm5({(`=-_@T;VLC9ebZd0mg6;!OkjiRIONEBWw1mnVUqkeKZ*M#+TL!s#zu z{8P|MZ)J&b`HmU)K;yo)VcF$kZb{o`vC5Yfn>yElr7VvtY|G}Z5)$wRQJWJYU%c5S&E)_y58(hSfBX zHaYoo=`slfCDrhZloa>3`1T9AsbctMBO8FFZ!{3z=PsARm{J%&rApU;<40DupHDS5 z{H~v(vG5$MEaiMpLi%mpos!o9{p1rV*~Q!7)fGW!WT{m6iuZUY#CGMaK8dt#l8~oE z?6{d=<5pm2D{$*+tYeoXN4rO%Ar_6NDEOCZxIn$)g3*K9Kr`rxRo)7n9tP*^mBt&; zvg^NcIp?zJC9giVn;sqexph8d$*6>>{yZUV#9|SiU*?<61=Xeg#EAo7;#wcgK@` zDKl6MN+v6MN8>4)XEm1XyXW0&<0=tAY_tz15As)R$i{DrrP<~aj2T!m8U5o3rq;r#F`_^CW9`TK69)9UX-ko>D z)w2MJI}T3~#w?+diICLz66RR?Js5F4%=H>?#=q+pjwp zq{zq9F#I!|&Zh5sN7L>;s%oAUlA58g7sXMTX{V_7GrE#+Mek%LZB+xH2L$Cd6Ha1BliI`z4E|nc-S=eYTbumMn-Bm*uE6zdL778yt|*(FJX6i(na5`Q%O~^a@xappGN}0Ri+;UPmW4k-<;Eq(Vlh%N z#5CbC!r2#&e0JN@S}b*+jq>g50_2SpC^8-KNB0l4=LZ)Ee{8wazE9mid(F7SW+LqH zXg>!A{dWhlN6~8$-X#4p<|8OZlV*3T@u-UBH7xDeKf&7%6Zlkb(jS=5zZJ5;)27w& z=OAIbM=b9Q*>-MSy;pg zNm`f9mxoqFGIYD%&wosIEt~FBsTn$7kKSm1EPVDZ=G1fp^Y36)j`4b4ra%Y8@0+!M z^?cUQ{AuP6cWfZBjYMedu*jwQFeKO;}^~u0&28!4y=$Lg2GUS9e7L9j5)BaG; z-rKY9RTj8A7_M~pxO`)dzs|>8acETjmEmg>@XYE0H#Y2S7vTuF73b+zHs79Zmg?PR z8>hvOH$Q%3ORjykkKT!lJ$|~Xnp)K&sWZ{^d zOamg3)oUn}NH3^(_*TnD#;|zCJRD!wvB;pMyoZ#mrx6 z@FhUl_r;ESHBO)ODNfPnA>kDl4%*P}rOX&a(Qq*kL_i+zu5XrsEB1A6;l^#V3PTZb zBso?582q~}!)Hzg!-pRc{jpdp6W zgY;?B-v|r3oUjDt)_?5Z`z>)e?EWfx{@p~a| zcsqQ!gt?|J>JObN;aV3Xl7U25fZGGISNYS^lGO{iW;-I{y;`T4wNq$nsN6xHFg>_d zbP|`Iz50)>TYguYxn`ZhMq`8>*vPjqWA41>&5L-(nWqc0IXYW58THox)udTAj{l*B z`cp2)V%%`yvl2$nFicJ}yqpR@BcP#49UzXw2(vJ6@7H|0_xFh+4vRRMUo&0%9EmzM z#x-8VI4jzOWzro(stax3F5-!mpJEZ$r$r6c+_%ORVGrnbs(4-(EJc`;1Z)))D!9AO zq4COa4Lg5Wm@$OZf~BepFZCD@u}Z2W4;Q^Cj3lRjYLkEWf``s#4TraRFU8?-W zR*<)E!vfMc@AE;k|-0KDP()O zTzd`+N_#&KA4akPcvn~$b9=1+5?rX5z0T;75*Fj?9q!Iyz@E(!MOzf6ND8e!T+&1G z+`Ps+Z$s@?&lvSdYI2Qrg^E)dRx3Xey3w85a}v4w=woeE*P40eXOq1O%%7_dEgC%p z$WV`M^gncdx%S(c*-!F@HRm$V|BdNWNZ9oN?LVF}pXSJoXO86Nef$g&ul%6LA5^E3 zR9zKn?6rihW2N&+uDUj&;CWiPl;2mu*jH-W=5+bnqH4IX7B5$J?K?t_EOCD>CfNly$vU*^j-cZ9Qmn6gk{Ror(bLsroO`t%N z*NcT1v#z|-6*uCVyoY~pE3;OV6TnBj!hpDBFrjQNFHF)7wsLmSk?zRtYAhZL=3Yb| z3q~0yHyU?ID;Tfu8SC&aznb$~0)e4bAhJ1WW@m-Ed+aC_%HPFW=oWk3-q*_caA9hM**Wu zkjq4atn&6gQyon?z85lIqyY1I^ru7Y0QaWZVJ)AHPeGaG9&WzgCZ$-0!l-bZMrEtfp--IP!rK31P=bsuBR9ELa;(g(a{)=lY#OR~mXm!Qa*aD~WuJ`xizMA9l&PQUd4(nN+_VY@;Y_PX` z5Sid6Ez-DZWbe;$x$B8**sDWg)ys}xaVuopXK=9bMP}l3ORoQm4aVue%yS!lFe>4T z#>eCTPzaAl`!&_TeY@sNpYBxm?oDbVfbb^=0$?-rk@JD06YxS)I3A<<=c9L}2C-X4 zhp9X6wD9q?@FDoA-|_k2L%Uw~@B&gyh~hU}(h9pZ)=W8G&&QOFUyXd>O#Rum5YoFs;hm19VuP0cwpDY&+K7!PHSjL;nI9 znUkr+Wz$}>Y1dm)(!~{Ebj4$zGT3>sNs)snk|8xi(0WmR6UvyQ=YgvCYGK>}vMIlTXZ-FG^7SC8L6J%{r{;{zt0!tu|T!(YEWI=^{YWAI@$ zIB6IA?RIrRlWUkgkH)4D`-P5UlN-cbd6+RRZDb_hoqWIz%by;^Qh>b&DYraAM2fgw5NK-8`t;YS!#=Tph}FX+aDXsJYaC~@1Zd~9cTb107rV9^IiV-hfLt$qzuneQL<{4oEWLE zCV51Xd&-y07`n&dd{o~Kib?TbN7n7P9J8#-EpuJUn^c)*9<}e%U zw-zB91R6!9;DVv8l)y=tt*h+Xjl0)wHA94b*c-XDD$S7^ zULFEZ^n|evhJ5yq^aRdzbN1J7^EpS%E%F_ln6E8HbD`Px{OQL18n5S5GnT35VS@MV zElwsyzdzNgQJH1g=QG<@7ht!1jTy-afa7FGS`s=DahDJ%|IFTuQv%BqSi)FnTGc}@NYe< zk`12`KFX^CUE8&Gm_N?Hj<>dEcIu}iX4e@ zSLbC2ncJ{)0JenZ)71U2fDsbI;&VZ)gwKMkn?+`bV~2MgigC30O4YByzZLQAUzAC? z?%khONJx**j)v)G+Z`xn23J{-V#9blQANA^M&tTAd-R`nLrpTyE*(0F#f3ifH@k)( zwxo*ST&kb81_keaCsAFqIi}-pj7uu2RnV+n+=a~BIGsM|)p|Kh6!JS|*k-LU0~AJ8 z3j{k*(hR*j0yJ6EokL(812MNOcKsIlY;y*%36L50*U^4W5E?;*mrQM5bck^rFhzL; zit(7;0pEqN`=ksN`0jD%v~CgNvz`z?W1%$5Py~^mmO*6iuZlFPQ^~XBu9(<2l$T*A z{N?#{F~^|h2D6wk@h8JP6O@;rH6S)FWz!ixgz=1+s|r0FaR>;nTXk$NrIRpA#Sp!V zL4!g7+(tzo3@sdTuq$2kJe)>qO$IsL{FD0upcB6{+kdte?33AgRk&+0@etNMg8PnJtWWNyl!eD_87s$|=xFRHIyw2Dq_&eghS2&b{ z4OKx2qu2Bj;Z;L<4VIM5os?8evsEN%-MKZqn@7x)2y#1_>}S{gINzWfvLOvu`Ae?K z5o@JfwqYs3tni7{35`xCq_$SQN!vo#cc`R5HDvMJy(AIztY(^5?NI|W3i7JY%}tKh zT}-bysug+9t94t_??|Nk!E7HuPa#yeMwvzzXEro z1!WXRKnJwq9dC5H56+x+o7nA{2PS-1sh0DDvtY68cF`=DtWi~jfxa><=(lSPvEU^_1>hGbS%+b7MCEoTWd_ zHH^PFb`J};Z=XIVcZ$xBd1Xa>3Es_%U4t%Iue!%DCGDFmW}qBo@ex#}=w>Ca<-&Mw z$Fq{wP80O$Djh%2QlsV3;yS&>=T9}Dh3qVwMKXz}^3pOOjZWktp0k&xXWMCdb{_aE zG=rw?3T%9J7vMj8Dn3L9oYzj2_(9`6;AKP)?%xh!TbJC+D}{5)Ps$iZZXB*Xrbz{m zj~#Ona%RvR64_{(CGuGbQN4SX5O8XZw@enE` zjq)B}53jMmY|GxiJicHrXUGa=qWJ%dRlEwAfAeoIz`yMk_KH5CojZpMkjMa8WIF{V z#a~s{qoaWlkYumt%R3oCbCb{tf=dso$odRE7Q#btSvBIgpc#-2HADbSm_}U-fM2#l z|4f7N5I(#YcRq?4Lm^zSM&adkFo-~7=w~iPGQ3QKs8eUr3TJH)FV<_jD3gq$pabM> zOP&=>EP41|9A=uoqQxaYm{=HHLInOYNw=g=q(cWm?$G?P&!NwFCP+adOm!A5orG4g z^}Y{B8zeB$H%>;s3Fw<79&jjmq~ih(>|aWJzD`^vCmWbk_OLtZUb@^TdETITfd`=Y zywQ6;rx9T|YV#7@xUiCJLLKh5K-xN&XJ(d5z4id=j^D=k-Ym#Gyk^%_cJP`zrtYAm zzSwuK!|3extxu$75w+y(WO2Th$_3TkT^f{|3T4*Hb!(&=7)CJ+E7DCn@<$tcl^Dat zpA*XM|DC+tWlKyUWubbkQALf?zG5EQ-(g7{ZI_6n?`cd8C0y($k^EgEX^}RjlAc}H zk}P*Or|q_d+4Su%cyIfdFx~w~Gom<*OG_{FD24W$8< zkGB}|<&cEuSBms>(nNZT&#a=XYC|8I%82knCp>UX6cnX3;{LpslFR8ot@?|0E&(377u$<~@8GCYm@}y!A~ScxE$t5dJNKkuLgfRdCu;1#j^|6 z&^Se?A?1G!V)17Xmb;D4$3L)K7R_hVR3cy`LvJ21k7fT!HoMT*xlIM)NgBUQz1Ptj z%V%s!5a5NplOv&s*S@vTLiZyu@lb-qeq>52G&OXWEDTOWfAuX0>C_OIwFlm4|No z42Dvqxa+%jOmnlo-p*lQcKtP1rncn1oW$LO3*>m>95lDwAwsPzeIJ~Hc*~BdW%bf# zonuhuF^d4Nf`S6-8{cDj7V$=BLMHywx_)*3)Xe>h3Cn3#my^{?Gb^L$5^s&7p)Um= ze9D`iwO-BWd~$Y}PkKYY>@Ag3aoSON8#b%OX%}b2>4Z$aA7_!vtShhSCoGL$xV*$s zx7}~u(Bn%eWS1VYZ5Sz7s@w4kXljm7C27NAUhvLceVvoS1RHTGJK7B#d66;bx-c+$ zg&)JxV|TXyj{gY}YYR1gLw92|#1*-a^PZ#Ron-D~Zw(=3 zu&RxMi!h|Q3CtqJQjfwt%a!b@(nsGk?B#k9*&MEFW-Q+LtZ;BEn>L9JwPCu5FisExR4(_`tTiOVzJBWRPR5s$oCm^+4RKKk3!G(5=bplYKp6 z-gY3x;Ou>XtM_sK`}C$uYzZ@|M!X@zmt>e68x#-hfj#Daxj;agFI(ejL;~CH>qFv} z=M~~J(|q9RKEA}%e;W0T@wmi;T8$WsJ>JDVJC4DeL=8$aq~P`+@o%=-I7;0-zT7#H zzyBvI*CXhlz-Tw7=V+C^&P$hK@wX>E!QqMQ*#1NNhP6YWZGOK}K~2PZ*ph-E(}LqE{Jn*i0J5?HON| z+s@7_`!czxku=(&wSGP7pX}Q)@^+1Tm}njFZrC(%D`5JN+tHm$6%^5b9S*4bq&L49 zs*xYk8qRw-#PAE6@yi2Yikc}XlQ~J1ki}6LK_BJqVs!^fkdgYOYfSA2M{T1&W`%*MSe&{gwz=Hn83S10CaG9dc=si0Bg zVWGZROSjn6d3jgIMwGd;K|3hXRdRLRdhVkKTtL>)zyyg2_7e$ z5E^GT-`QeM?YQDy$jiM{kL5SK9X)9oHquBX{MQvYVp-DB+J_Wv(pC|ui)SWtYWrQR zp2_VWF<}bm`)|H4DEPitZy4Wt5;FqQf`7eXy;y?eU`tyasHcsB`))*dmgog~g8lSx zl+2<{jgs0j0CKq_0whhW7kC5BCwzN%dro2M%;H#GmL5Zzub;)y22kBvP*y|Y{P!hh z866$jMpa?O($~wHT*ExJ$0bDpy56`p9ZPQ{d$;sN>>XRQD~3Oys^c@J%$!9X!02VF z`whza9GrGD?*A3p?SOzURmflZ zms_~|!h2Dr^6WNOw=QW~HgQv-9QdqL=7HdIev89cu<)TYXuPedsf)08VS%XQ)I1Al z0>1uZWdwo7RIZ-YK{-_LH9%$lKC%<=O;1P3k&61P_s>{O!_C{%?jrx2fbWE!-YGs7 z-Uz<^_ts%#$N~A8=yukPj!E~% zzizlbxN-EZ(oK{kZg{#z+eXR!o&S>B4Q^ka-)AMfE^SaVJR80Ea2Y^u*aTz~KnOI% zf75Rh6j>6%SG$kM2ck$S_<>}|XG^LBIegVFSp{g>8$nBDjTqRs-n+2Rg?^*Snf#*F zZv^!Zv$SxO$@7r!2lSdP^dHu(=wzFskU?n4vI>ePlr)-40s~BjYwGjU;6km~lZe*$ zg++6s4`%ftDoNx1yr%L+{V**wb0%dv*IDKAaVNffUl(Y4^dlk%O-#cE}a=wYkIUFl}IUnTaOn`PZ$sFyEx*B8Gb;p_h2^xkgh)n_0KyB zeTz>35V59@rHq?VOPl^ACr5eQJ^!(>(`Ma>{n3ArbQ4ul^x2kcK-ad>IcQUW*hosl zeYQjcS0&t?%WiIq-PVUYJvqKBnI!Rx+ zatXYBlze-PL>T1K9D7NS*RBbDW=BFqg+IC1c9D_#y~0pMUJY<$HDSC;=x6*C0E8MA zNN^3le-i55__^Q|p5+nv%v-yMKH#h+sf@2cE8pBs26l1jH&7~bs)$r9Y0z%s+^&}s zNG)$PHPI+{u`ol5`j$Doch}5418Z%#msx}%0s~@kCIEuFBBtfw%(>* zuMuKvwTzFklAz3;-bvzevZ)g^5wr=RV0H2#y0}vG0z%ju!*{zD2m{_0>vIHY2tBnRci7 z+bSzy2mC#F_WO!lXvQrs&7uW<@@ z0q-$~m&i$rKNg%uLi|0d2>73eH4LZA6kZ`CuW!I%>+6I^I&R2HdScZ08H>j>T`kww zbO^|TFeCnFIWZ~hNZ~E=Q;+q60fjOhtKbwXZUJ}VRk@;-ox`KmmAi(gbjGhAibB34 zj4klS(o@>NBK4GN1-qXOi4M3RW)q0_@#1O(=D3C`pg6Gi!+8Py626W$RA+X$p|0eB zJ`tKlFS7%Yg&td}%_y(ryh}}~db_azqpBNfAlRrma%bati=4JW|Kl(t|tVg=YT#QXfC(2Mg<&*=%PaU&G=rhDH-$RKsf16V)p^o!JGRQm z`5y>b7Y#BWJ?0Lm7a1y*spNn@K!|`d=V%N1?Av-Xje-0j2FaZZmFp4wX7Fdxfh5!F zdb)0WMPC{j22iPMg*#Nq{Z9I==y`gTXqnZ_Xg16@t#H9p=BkaLM{i?Avs7Y(_QTlj zB|ffP%?K@uPDaIOM+u{&k@u?QxJN$Kc(}IOVNG>@OX1F9tKQ4f86x#~6f)v4Z*Hz} z7UmmP%l+S~z+6swk|&Gu;mLL{?=kb26Jb`iq$Sqf#+Vp~c(gIbk+H@sz!&I2UviVo z#%KFva2o`g3H{tg@z3&caPqe-0GsUkQAnapGyMvU>fF?#ds$5fnB7$e_m=PCnH2wu@H6)f-<0V^M$nMLq2 zqa-yQ1gNiTDp@h}GYzkn6DS4IG(Pi+nI15AtB@MM;irxc7n4xZw&6N@0cQP{2)gu- zFW*T}+3Q1nJfEw9%hDKkukD>>e4FBmGrWjC7OmD0W(Z<94z@usVrrC^onROT^{E!J zCp7dWm$^-E6|lxNh}WB@4VSQ~A@nNaH`oIR*-1^ltUo;I3H6%^W#z!0f1QvgcCwUX zyI_i+glooD&a(*EwG7p!{o8;d=>p6*!Cu!+uM*`MTl_j$AGoR>#uwff@= zEz5dU-xq7oqoDQV5LbSe4~Fu~j0>#4H9>dn=MKOq>8XRKQKup~#oC1jlE~<)Id*`z z9G;Zi^YP84xp5rz;Hs9|m0D<}(g=Ku#~jJlpeeOZ=WpE^Xp;;*(`tOMtIn|Mh$_F1W7)P3aC=Ug zA8}59Uy!Ouw;yE>#WmA^@qF~X?=@ed=lQR$nuJ6 z9@Fond_Fugxfl?YV#uZC)bBdFkDc#?t~+oDB|QjG-wh6UZ{rjRd2?Bz^2;2`{R%Tq zIL&30Ye)M$E1;ca`g^3VH}@IiQ(*{90(XF|af{851Up!^jLTx+W3&;oUZ%MuRk^#D zOaHkA*P5cVw^pbBu$`UTqni9o(L&Sr(p$Y{wO{kCcQzL@X7BOy22lr`8j} zC!f=RI9vj2<&lL;^Y&5oTbz+zBuG{QM${ANp`W|kf&N-G*Vp+aA4ugo=zCCSo-MJy-G z`O-Ov-|-2Ksw;&j&zWwzQ4iD5%1g&_4ySH41v>QP7LI?53)I7|${1&zj7whg>1EZ* zF;h)Ye@)zosv}etlClV5t2b}(vW@`R@(n;zT=|@43S6;PV48w>Cd|y1`Db!H9BVs= zidn|;{%i|gahV}jb?^<3jbdyg8qiljdHNjfj(7gB5I619MTyycuFPWxx0mm*Rklf> z@5t}*=W&!*aqOih2CDH`zclnh)28vy#utbXm$g#$X!YmVx3#A&oY(gPK|i>&56eU1 zvq@THYN<}Yu)MnfV5qmsbb%%kS8PqRSV|LPpyZXEAC+4a1<_%Y@0z_d`W!@t;mc;7 zTc%d_D=O|Ea_j~qM+S@kiwBUB0_v|BOi>Rb8F%L~SjL^*Ux6wrD~T@e-=c_11{j*A zTQ`ekczN~`barmvBx77wDiVacnS!b3Zr;8xA;-O;N9WKBCVjEH)o; zZ?2aghf$t)7dw(B1Ya8cApt9Vhcr64=&JDv=(cp&Ep_g@>0mRc&+<6N)CHx^b$nvf z)+H<+QWsMcUsp~vth2CdW)<-9kOS~|o%gB2-M8zxx9t^vVfw0TQ9U>32w0GtuvC7f zsPy!U86!8-4yRYggHLtwPBm5na!6rmF2p@w7bMk+y-tR_SOQ*?jd*O5mibNve4z$X zwyx!$YnsBe0Kj$sqHuS7EZOxNS7@<8H zpt#jR4dp#+uy5ge!n+$>vfkL0>MhPaI`7yJ@9q3pd0qog^9N`PdoH#etbj+g70TRFcs(N4%&e{}Q^{B!wERhsKPaPkqwYUnv4+1gl6Z__yrNG4I8 zC8LPBtY(UobN|o7TJ4aqPtRy>LZgPTgqhF|<5v4YjJuvsST>@7@o11w|E0UkeT5=P zR}E_0bmXQh+PSnuAovi^tnWOp&1K}zEj){^Q^i+{m!g=xjq^MendMh+H^xoazoPP- zq72}cEY|?!JO<|D>UB}wafkAC91S&wJ@Q2p48-RSWy#wd>@1WG5Z=fk*tZ-`SDcEr zy!u1De>Aq+t^sZOdD^fR@l>CjT#kig7zmn9W0w3?Jm8!Yp7l;ObI{@t8sJE7koWlT z8~Skx#961Zhcd_U)tfAuk8OlAFvx{VL-;T6G2cW?l^_7LNfNB4jIMq}VfsxVs9}lV zHlUQG?Ua;|{$+EivZ+$k8OTHFMILT(-7JS$EVUbN93A%FRGleQ@lWy=ua;S2cAtK3Sl|VojWo z3g6j=L5YL~Pv@8e70Q;wp*3U`#@GOEoyXL(QvIooEqFL->me{{O^_L23Da3YnhEe7 zZ9?+T8@h`RvBRcQc8#$yxR}FfHP0rMyCTRI+@uqJPM)XVOwQJ~e?CGJb~lE1Te&0O z-&mvmpm-(_bGQ$`VeTvC<=tN?^vvZ;&T*iVhjS1~d_^|#LF19ecX0f6fk!am|JL*C zL%aVUV6LxM?>zwzp{kKACXPTT`30ak@eNl?L*iyV~g7~V_sCVN#6v06R3inCN82hL;#l;kG5|j7P~`f;11q; zGa+VB*RL(BrSZMQtofB+H}zJ z)r_?RbBeZogk&LEOEN*YdX;qU_D$%qogR-;K9)9ILP_h6jlpcsywClY1v^$aCYwx( zrWSm;LMx~y+}Dp51x@^+rw^zC)bGBb9{vJjyg6u*EDgrKjJC8EBb-U^NV9RUNTs%~ zz5Xe7JcE1yVY`qR-2hJgZd@HySDTfqdpIK|2v`GHAsQjb*eew<@`$LRLx)&({5(JQ z75GHsAqQ8=~rB5!3W+Jz^Vt&!{+J@-a&5;=YEte|BY^HeshfVosTp|rM0}qd^T$YVOD?I5O zdf5j`5~$vId98caNqW;L<8ei9t1HTQYs1U#1$wn5PBM|O8Rn8mQp~v!hMTeD zOr9ag$tl1GZn3z7a4}d@=a|$Zo15V*7}~_a^uXt# z1!YmqmT=Lv?VnbZp7U{yx-LXGT0{d}Fwz7ctS6kU|1ego^4VCw8J!-7|BLbv+WpKw zVBO*FEQ+3|7Q|rJrLEA5tz7O#Nz?s_7J?7L9G1z|ps8181dXbtSWl&B9cFnWfR78P>@(mWy{7LOT1-`lZ*-cU1pK zTAKGDefIwc9l}3G>bgjqenIKFSqzZv%2z|0*F~S0Z_oZdNF}`n1sD%LWs`DywyZ}s z{#8niNxo(LgOW|aao7H( zH(8wWgEepAUo&AM9sGuQgn5mle^me}?=K#aR9f(ur}rbb(0f3AzI<~TKBw!4itCN& zk4MS)NXm6?<=#f%(4C_(Zc%I}cwvL#{HhPSHYa}G9J5F-H;AHNUxu&ym+pyY{>&qo zAP=X{=%>$!kO)f?yxtJ1^y5JlO|?`|AaMKS07vJ}+qIxBOq*uP%-N2X6`;o_G^h^sM(@>@@v7d&|S3 zS&=+rD3TBK-R~fC%?fG9waDgDd8_xsLQOsKp`BZV{jGQpCG{kFYA`AhxCrm2e0?q7 zpD(m%?hA8Jj6PuAlUblFh-1UGcY)`Rt@YDK&L7p@%niQ1I#n=A^wjaf3|d2I-Frtx z;YRvlu+P(BOqJ+J>i}I*A6pFj*UY>?bA3v$FibIKy^M3e(N?IsPHthe$|pljrgsya z_cS5dUVqXD_onW+tpfS}jjR6+NFWos=QW!F=6^bc-oSTW`M$#)UOGIb5+6*z^3*iE zOYqJ6YXd0mg<*Mf&-Y$uNcLd9M)rwdMkr_hbx_FGg`FgHEdiH+b1 zyL~^qt?BCEH}`1cp}u(`VQ}=~@-}^4b#&t1dAyH1d)KHyh%A^aOG4-3CwEhGJ8?W^ zH89F%?;E=0ry#tdRr#b)TmG!?@_6iIX#;<8e2(^Ogj1>z!&c8?^<`bi)D{3(UKVaV zFA#03Ys@g^?LjoTt4Bz}r!5ZPktV%ayuXZ}Au|5iUM|x-qu-)VuZGaWYrTj;1&qDA zCPi420?BL1iIy>7h^i$m12rU+zhx0D180BGgfp2|qm4<)hv&|{UJ9c<=Di)V0{a+l zlk(J7p=5f%(0(c`q+b`GcKmKx5DU}bAAr})Z8=`K{bQfay08`l z@(mO0lz^b=Gj8mi{rJMaLpfy;`|D!BO)SSbumOL{xa|C=;a?T^Knv6YLRE+M&tY+R zCXpp@!p>K2UZPrf63TMLf`QEEdDL$|m9gRV_fEH8y0F9|czJSL>o)SMR#p#m_b?kQ z*cK+xDibx-G3JDVHmKf3H}_C6lPR5l52`#E<@ovzJ_doeRYd1gb<1%2*Eo7WhZPj2LNTSt&*)gBT z{mYwNKs2t;?TOA$bMchg)IVlZ!KD~ogaCfe?%8RUSe1+Zb`*ioH(3Q>AtuJV9p1t| zu34vOU`3NYb6AaR-6@qImN6%#lATu!%s{3YctNRuaWt(D)2s6Imhy%X{~r6#WcfdD zz!ged*0zc7b;{Yo$LFoUn1D`Wnq;qE&or^gj%#gEa6Zr%s#SCNe!}S0ROg2W6wvpi z%|dv()g^&B3g;8#={&KTA659qoHDbwK0iK?5dK0Ktz8Ez%plNqztxc8H!Sdx*btVC zI2r@H-L{!^AUoL4BiRjq8sH$8Bw@ra=MqD;QmbXwSbmTn+=}rQx_^#r6m}DdD+u&c z#JirN_YUG|eX;k*ge-(ycwv=uK7)Q_y5IhYNLTy@^_-H~$l%*U4P5;}1gg$lGM;uZ zpCM~*rlFi)nnPg;2!2=B2S zdTgb*Q`P1&tU&-x2*Rp?V|1{tYVhO2|GZ-`(rpQQs7rFXN4K~AvXceIu^E-x`it{4 z3<2+3>r)xFW^p%0ItOi+%CKi1VG-TyMN$0mM0kNfXgVNGPWK|_SbwTV-JO@xUfz2Sj-$N*=Jq}gdy0~k2x=Ky*#~-fMAbkS=jk5WufX4k zHO!$sgldpLQHj_apzv|7{lki1`G-bca6>lj3g@w~q) zaRB!l8YJsm$rX?<8^-0P<(#6i;E&>nNnjRg25`sAocOyf?4dVp!;Q%gBR0K$lFs!r07_BnK zQX`N4o7M(Werp+%n2%-6=Q@_8S^)7_-(K*U_C`UsE??6-A>|cgO_yT;_x3g_h@!?( zlh?^_%1^lIle+Y(B5EaZNaK!Wb?#ZM=0zdUWs>qL#qoVIDetQxNw8kw`MRN!!i(}w zS44+%xr~{{RLwt3Q~yhya+_P$21_*A$iIUl=tCc*k4Hqr%{MI^zEi9Fn`En?ONwN zF2zsOt!&{{d)l3rSFfEv-O#r_<@=H^O$;W|9at%&Ar}7?g_gm-RAlSge;iZ~4c3jR+D~ z&FAwH(k~KF{P&?1dJ2W)PA8Do1qB2vzmkfg!`~0ZSnZ@|IDw*YdRWhh@L)=SfWd0n zgQ(hjTFRhc_JKcWIS!|2>)J%SSqK20(hnH=?CAE}|BJ47 zaEkC{@ zU)-$!3(5F?bD82r@qAW9G5Zh3P}Nv`x0+Bs&JX@5URZh^=b3)2;{|dPgM`#lWhLvO zA!uNaqEQ-+hlBVQR#RIeGoLJ*fezKTePQKp>fd{O9_KJb|?0nRKaJ#JJqCm-szlb%wWGxScFSA_>oydI8DE(O`L-tE)irexJMu__#E(m(`BQfNO=f9Zo@hhinHZOb!cClzhqC&Y3eYpzd);l=ykeO(^L1_x0w#pgG|GgyzD93&DWu9DwU+Jy$Y2Nlv&7BYCP7@~O)<4V{GSdzf1mMT* zQWBd=*E(SGpD>t&%VwzPa3P1VsL8igYezeMm0bmEaioaiE@irZagu4^&PbGa$^kxG z;x-$YKDD!YX4S>C@B(ynQ9;pn2tmCgcfPwUrb5ni$JFy<7vDDdKDaAtStCXnz*GcC zs)Pju_D|+ZyIO{yNSaZA=C#>&q)Ka2@PWy5)!~6=R>oaKvuC;bDKzCBLfsL%ge8Mx z!@g86@?ASyT$;KVm{Td7Nj3pPY&PIiV_NV{CBMeGVrC}wUnDV(7ZuU2h1SdDBRMnJ z!tajgLGq|vdOz=;Y}c-v z7Ly~3y@l10q)pUe&I~166P)vq9hmL=Y~J_2CVe0@Wpj%ofxwEG+M2P^qk5x0LhZwR zlm3LhqkTv05P21DK+R*DeasMUFltz@)^ow|v{0$}_ zKlc7raFQ+aE{v1Hr46#D`3?J)=n&^82_k4r2?*My2vbEHGVTqNRAsA7MlU}Y1IB%Bs_k(?p3%+V-h^suUmJs(hn%#|^@>Tg{&yHb+XxxotZ)y=<;62$=hog-D3$6^LpNTc?^ zJ6G0F2E6H~5vHc6$L{P@T5NNaJgzq1``F)iuaU+J3jR8bE&)oWbAPt`$YF*mP|rJT zl?V|0d-a#w2`!ocsHtP*2(G5zsctdFs#q|Fb@VI&@%^C(eyFLd!cq)Ckh}}xT>+GH+*0YQ*n^DJ?+sXdWW*QZc`P>r| z(F4#T1kqla`o5doj`sxOV;`cPbZFQIx=H3uP-E%;iSW1=_K7c)=Kd?Z>Y8|-bAD*o z^E_{c9>7DLO_@A2Or@GaCAVlOvI)(VUtud@sD22Ys-5bg7}d<7$jc|t|0Ed1vhI54 zGw^+g3gfD8>6C&E;qX(wWlIr@J`xLiBrpBde1s&s#mqY%e$cq@_W>VYqeITm%4N*5|8_l z=hBL=udBcw7BbZfLM=yCDz{7du-n=>51$^aIXB%Y*U7Mfef{9{_05lWx;EK=w^AlY zSJ#I=K`fk2*ig+y$Oa~U7mPA4fu-_CFP>Pg$mC(4?e+zbbnnhGApzvU0%xmH{fq=> z>ug*~h9s(D4x;;blo+Vk2@0?Szg`Zb>STL#&3WhUV1vNOpj|b0{t1b}-wJH~BXUqa z9LBPeou8BklcPJWkm7v!6T=C6@`e0b+evx(h8j{PN{xTIc%j5tx;jQ_aI#JO@tmTJ zD$C&e>4&Q7Ed&=<;dXZ(4krftw))QUX36vu&rT{`i5F4aZZ{`=V7A9V^MEjfd1`tL zbcURmZfSH$MCizt>t4eUz$_Olz-LjfcjM!!c)u@iY3vulo&BSlDyrYXpNs;r=KAFZ|E>Z*Zj_nNw~aO}66ebtwt|HRbXyixZyV%;13<31L1BEQ`6 zuF?5fhJuO<@3|R!bt`y8soP1u{O`OpoWF992Zn(aZT=*rz%j6%7O{L>(Ko2#zn;%^ z=w^tXITQiRnPQuwsN1jLIs>z_tld{=z6c`mAp9-wu6w|mTw+LaIOb!NT2@lYn9@rV zm#&0g7m*2k0wryjSKd^W53hqnlnGfe?W zALp9h?ie=uu$J6$r6GuPlz#uHp86r{>gLD*zYChc&2ChZ`=Ej%U#lw+l{Gyowy7{) zZ1);kvZg@~R~mM6?XJoxKCyL7^oD=j;&Le+m1YDKWQs(B0eP5BS99%XR9$i0+Wg#^ zkd@Hm9PXve zLT*QzLU$l{QC;_!L6p7%HQzd&L0mtzvxQuZQD%E(G_YAC~~uM3DI zPic$t{mp&73iNip=kIlJ6ZdlXf1K8bak6m#9MaVmeg6nvkB{rCgb}J2Zh61Xw-$3{ zThpYUk8AP;Z}!N3&%aDx_(4ZhJ5CZZVw5GAZmtsn1_64Ub%RgbK;#xDA+o#}_NfbX z34zrY5ucA?IkP=`6$Ti^LPk&etM) z+DcbF2>Z8F(k%YkrtWM(Z?feu0fMKu4T00aSyI@Aj)>xL@*U1b7$Jcof1S_+RB0^$ zQ1&b|3@BPm=PQz}3w3h_hK3Lt>oFw{!IbQ-)q}q=P+#yE_OqB7G4|R6UqQ|t7wuLK zPmC8Gg>L$vAL|T6`)x>N>z2&69J$ixGZ+Zn#(S@`o4(z*$Htc8r!d!8?p+qb=NGS+ zyRF(wy-m(E>Uf)<1@7NmY}PXDb7=l8*7}DZc`D4q@v@4+YH^9`2Oj-`?JmD53cpee zfcw!Tg&zvka3&0U@Uv^E*G(Bc{5MBX5?EPJejTK^w)x?{sDR!q46fghZG2e+V9<8+ zRpiSy!B6`Uv(nmYEt>Rdq&Z$a&GZLU@LP=Yby4v}l3NKfm7XD`z|mn=Sg)w4dx@94 zg-M>Ba+YU`!6qZo0&j$-^tn5HHf&%3GFc6(?+|!y)1i{uGNo8qU(u`Qkn-hR!}Mg$ zQr|I}IbP?*z6=!_kp`L;14z%%38boi@7#IxWuk2Dj~#ISWA>YRE6k-RNTY?9orkko zE%E^zGW%cAWW7iGi$9;Up4?4)Tpv(SEBn9BIeoblIsfaj?S_286W$ZPCh0!;5%Zs( zkN9p|6DR%YUE@BKog$uX?~%`_gDt=*y@%gNa?4vw+tUc}X6L0vV&n;YLV?iLA$yGw z147$)B#BsTd@^kFQ4O>6mog96ldO3V7KDxI;p40MCPvKYpWa3J-l+rc@JS7Yi7(A7!9#*v1PT={^ag1V`^3|P!L^!YRb`1&Z;43+$XFSj!Si?%axm7$ z-+cAjd0i_il2L-RjTSpUay1u^G;h{a+;s&z3|!Q<5l?BOyS9tyU(bM+0~@w(lFEQ0H|uYd}LoO)WR<0{9PeilK9VNd2zbjd7^KZ z_=n>F2d_C-w)4-Q62I4wx50GGBAZSBW$LbIcF&R0&-i_Fv_sjZOe!p~sK?oc6(I;7 zxqPxk3`i6c~w7r?}qvC?Yr7{7lcD z*G|K8TT)*gN_<7EN_zyqwPIW@U%b}13waO!lbg;0C2+!`M^_K!01#&QIu~7=4MGQB z)4yV1zE3)ryA+RcT+J;%rX^e&8i9#MKkYi2NbRm@J~-EvT8hn_H!j8c-MUZ}zjLhx z5iMn=fTwa}>9mevI>sLT^AIC1q?3ZGin$t&Cr`$=;nWF4B@>egYVWOeHo!|Wz(72ZUX~!I5*cK= z#mHu;Epb*ZMkURAYl!{41$9JJY#(n26fnr{w&FcG?)&C7C?l_n=>ATY+#yV`;BCc; z*-)tYm5B*xF7Gmru|N;WqE?@yg)rlH$Nd2zc005~2kd$xR?hX2eaQXH_~-xLb0d(; zBg;CBK7uB9;_%lM_2%tem|AZGRp=#RzEnBQ|Lu-{+G3$anqmR(e={rQ>`!>` zg%K?O$E#0@=mzfRw;PI@r6ocim)`g|q3v^9NnaJT$TS%x+KZRst0Zj;QQRR|I(LYE zY?i>ozkXxugg;5++n;|HkmL;_6+50R*KF#m5Dzm5b(8Z=vUB6N3}xu zjJ14TqS?i^w%{mR%n%E$_qY`|T-Rff}luERI`5 zdWI!b$mhf!0It-np`*(hd8DJ8H2jDElQF;yT=q=F(YNfdbAmcF!(p=k2zZ1gyB>;p z@RB8m{32CTwdr#NK0{cVpA)EM4C~xBQ>N-#I)IOTnW7Wb$rdfIc1Fl5&B2|fB<8K5 zYZ^7x2`i1y6|zxd-^RSH`gb#SNyOXau?^fFTtL=nO$p7!HL@7DDMZ& zd=uFL$2AYkc(21dpj$NltW=O{|F!NhVZi&n+f+gUqsM6mPh=#TweZk*Ko;r`&fj6Z z3$Wl#B%Sb802 z>fEk-F`xz4i@6ee>On^PQu(4C>yq;K`8RMaISN$k;x_JdrwpYvxYdA`Lv!I+oRHGe zg(GFpk0t-m=WF1NZ>|d)8LW@xJl^nfEMWfbdD8z*7`@g(W$CE%X6T5}@AoC-xm!ou^MFGVLzSG8 zsi8ZR%qW;$PKZ{JULz}kw&_Ekd&R1t1nd7rF;j;>Kv8anxPS|&4t;aE3Lkre>DYInkKHW`kp ze&hZA-d5d=zpQxE0_?Jr6uKPD@cCh3k`DcDmN7lIzz7||q#-PHgPLfIts91$o}@@i z%vTb1Huui|u?u7tw35s9Q7WfzAhaZATno^#x*+uTr6z(H*s5|H$^fbKO16=EMJX@xd>wAAy<=*^gjTYN}S0#AIE=$)!s2VJ6|yqRA{2kZ|i(#_gD!y zDnQdz%qW6t9*jrVlCfp(yUVLW>aJm_Pkp)81YbQ1s84-((Bp5-E}-ql4OWA%=DhI{ z4R98!(Mn`NWHAa*;S4+qq$xkksIU0-BPPC5cmc%leFD80vvgzxmMo$lb^1=lu$@bu zVZBrD7%X;3)FxVz^Q=(~dG6ldOi*Q`Y6YBE&7r0o^)fU>Z|M@4%1Uao8(NezeY3l) zDEZng28^>4IB59Cn#;uQ_crE#&@kOo^sym~R#g*W$sW{e#g>jP`GXtgtNP{^_-Tbs zmiD%{RZpvx6(e%QU;5uhyxIRhBi?&p(<8|p$~S)`5tq9jmT2s28fKOw-pzE%H^<={ zec(?rqrAY3xzHZ3S<@By7V3b-bG#DJ=*$@?7=acJ0XB8Y;>0kp`R_gWoOAK>^=$(V2QaFkR{~Z#t0+(0qGr6cC8T9Yii9T8hJL&k^wTDR+9caJ zLCQI%Oa{ZfYu7SjOA>sGZbI(FZSWKtx`XVuG}W7Nh#`w1H^; zXGNjEeGS?siOFmct#YP0hFjOisXhC_kt6d0G_TJ~3QI?*BO$7z=4=#-ri~z2aO#}v zW9iS7>s#njlJ~3yT4ZAX54k0;g%n%Q3fh*rd;w)sby%WZSUXwxi2;A zTGbBmOdZc92!2ev>RJcvhd26QgD0vDhHgu9T-?7TT()7zXroObff@I1!)e1SRIr1| z5B21z>R-HNT9G>FjJ_Yr<(5hs1-yn=$hsDHFFxTU2WjxA(-e zriY}<(~!<{HsD&e(Oz>ahR%7KefLL$;=S#{y|26JRgww26d9Ba?X_=wFvqrSSAH{O ziOU3PWyMcalj^i^vdDxq9!Z=ib1re%NJP^Zt`KxPNW4{6Nzn*c@|Zso=vB>zFEZNm ze~F~SGP&Nt{eByVtHE#FGZ$w?SFD znElHVTl{OOj(rEMiVNYuRJj7Dy!FaTlT7IQi~#m^9F-jJ_UR4ERks@d-%9eA5+~nu zOLB+sS$lmE(o^oP|H`>(S1h`gx$A?}^ z&{vFO0#Ix9%n84Gt+|wEw+2*u7p|?ANcB^@rrSgKVMosncSUX%VX=eMQjj|hjEyNA zPu3Z*=>&^Vi)`RQi{I*FGijmcZjKGMbkj2}e6FAzA-EE}6?F`4+xIaXP z4mw@IzaWA}U8Wkis`Za>S2L;|^u19oJ8F$Ey4OK3XXIHz!OKSesRL)4@jXjUje=H+ z$elm*cTP_TX%w%$TlN;^*t18wkny(W^(WVk#^hl-dEYJqEW=ec>fiW$-6~&EeWD#c z$taI`gS}8j`kup7CY}V6*_hcOd0kT-JWA<=OVm=t2G(oR6x8a+Z?~;sur)4fa?j^F z+tO!OP0rxKHSk$3?o4=4)qjI&wDPeyz!J2?vwF=K*<%^6*05WGYbGCqWNo;nYo@B_ zi^{4heqL9pBPH8_d+9e+`bxoOLC(veY&kcr>#=ME*+o~LP-N=au|RQGLw+M%C*g6f zdgT}<4K1QY(5R+Okst4$oaa!QF&gxiMwnx2Dn0%%I-2yc)D$HSsX9ZydKUVPT6Sc0 z94{o{|0e%-^$xd_`<6UWN&m(yytlv0ss|qzubehnBJpD;fOhPGU~7bs=9pH~+=?gsz$H2XK~GUS|V?Qfs_hZwp3*`LxS zH)Qlqkse23h&TLbIf)9?7}$$s%0@nY2>)UV3o#U^RGg%?ew)RJX`_aqL9EHA z&Uf2f;oBPDC0I zP6qV@my1Qz<)kO33Agaia33LnQ43HNs@G<^uh)jjJ+(q!2T}nHEdGXcU_=a}=Aji_ zZ9}$*neyq>F$pcmuw_UgXa1#DaGF613sWAu{xAK~LyoRMt!|1U zUO<{&k^zT-SD^xI=7kmvjwIaDxWwpu7I;Z~B|K6q0jte^ zwApnH;!@q;eBLTutZ@3(iH>-Zv`H+24~GBep=;?-lTcv85833;1OL_%@SFal;&Y`) ziSNa0i-L0vkx7ZG-~GC5@YN-6Q}!mH)(e}FQJ@I1tSX+Q^thgKE<*>ms79r!xD4wz znopx1E80a@Ol1pbF>IwZ8iwP9%Df!XVy$Oy3EE;ZxmClW-ZM_WDo-C9DX+y&+|FQp z%xG0M_$06X7dn}OHo});8N%uT+WjY_dMt8FneD<-it=8RjMSKF_??rC(o+>I59Q_s+$T}2!Znx|h*5KBu{emC-` z#_u#dUJ(X_dH%OR9Z#XNBW9jfFDV_Sgl=iRbVrxgUInPCR= z8CV!3bPePWXrrUUHNlkMWKv#fCSmnKq;lm^S@X03K8h*^rpcnPvMWVefHOeo96GMJ z1?3NCV&By1O3=c|RB52f+B}6<)5eQE@N9sy=~*-&VXB;>XhkHGI<)8yHoe_Z_qi)X zz`Z~xOo05fC>h;GDXK|Oz(2cTj`bpA1Y7L^X}VAv!64GXJFg{iyN}C#$++3D2Surz zqkUbeSd#=E?S+9o@%!@tNlX>c@5&`DO@R(wax`uN9U%m2UF+y9K|xmHR^Pfa{%9vxSnKjm(H3P+HPytO_f zAbSSe-hBN_qQg%x@Q|ja?puUmq9^H?qOoZLo$hua&|o}Dr)=lc&CZ9=B_e~Aq0STWvxZJnTfZdQ+8zSqE;DST58^Sz8OTjht? zdVM*DaBYD)lT@c4#^-k&gB5|F?IVtsd?wDfhS&p<&lSNr@~fD|NYWkI&gd2X7K?`9 zznNXVQtPlOBp{`@7SO&MDJHdz+W`5XLTq4Dw_sOeHU(AK+Hx&uF4fS&-xg3#-1QOM zql;qdO);lHiHe|(B&Q0^-r#F$49}%&qoZ zZcDguSR>-0zzxXgI&DdCWJ55>g^|m2o4oBT&>^GL8rpV3}iA4}^IG^5B$tJ7u1U7z54hHy4^2m%?Z7O7zB;a|CLu5X8uP%A~k4WPVg zs=+>IvzU(DHRRZfOZJsk?;@Ix7prYB4OA#1k@y1CXsU^yA*fl|U0^0ndZtAqf1k=M zdi$Sb=INZ3)nG;Q;cI{nU_2Afws^ma)Ej55=@XpbRigxX+@}8oL#8RrP5>O3n9KZL z2^2KZpTUjVhA|S^=+mld=o+x*7mMc`7_+BnTpVmXDT)>>v|f-Do1s9@N$Y49dwfC3hAiF97u+!74! z9xE-gb4qi+9alL}2()Jol`ugQb1R>JD?x1rbErp%n|lRIF0M4px7{c*`PnzdFkMzT zd^5k`XMMK5T;dSISrXaPenVSLggXZ_3nd)Oib)^M%N1aOpH<&obN!BKCf^Smv;bbZ z-$*W4t^$a^T^&Gp*nIWbvg@kY*ba10cyJbYYJUus3-jeZLn$TJ zp>=+FW&Q?8>(<=i%of2TfooVz}`j|P7Dx5xDD2S_Jp`aKb~vUjQ8IQ0R318is+&twZnS^pCrN^!lVR<&r%{sb`ich&(@$CGeMQe@?>^=u5j7&d5l>A zZ*H_}wV&gV%*UnVH&FfvfPB*bnUlpIm#%zWX^=gc`LQ`km>KPDQ1_mmw2}K$>d^)u zKr6;E|Go20$Ifg=0V)WU(aFa}Ap=QlKUpi^gu4MBA6~{c%0?pZ@xlpUPxCAybEBpC z<&TLUsj?qAzo=owCsNNq2b^6_x(1xxkg(*$%o_daA|TBB9#wvt$bg`9@inH}MI#*8 z=k|w1xl%I0i|xvikJ)>%oL7H+Yrs(uK28r-m07VU!1nNt!O2XMWkmN3XDz)03!eac zO^1&}aBUS+ETib) zgW~nXY!Nkkj*hnAjamM%3WZC$+b=%}4U+tlSLdetTmT5Aq!amx`st@hEDlRg3nyONa zHb0|5Pa_5MAlm9xtJd7HB)NP7RvI>#jI%z^a1h@cvNHmkOHvIZGyHhLzPZ3*G@q3T zCe4Vn26ai4de~X!0?;>@fuQbY<4OgDH9%Rc5vC|W<68FR@Q7R1ZLBU=M5GBXGaaX7 zmW>hn4gC>t%@)$s8fzbS5l~SPK`cP}a?Xu8Z#GU_5@m)w4u5T4D6Sw>5K`i%&jWNK zOsc779sLTaS=u>DnFa2BC7R;4+QlDSa^EJty;%i^RKHKRy&f>@2n(3+-2jcA1z>?p z|5+XfWT?yXqIO{139C?MRJ>A~Y z)?@zgQ{_2|=#z9Xdudq6CR3(STCPMtM5&~TfK$B3{1Gy#+%#J=ID7L2%(|KqMTy3r zr!xF(pTsGxwkm|RS$#1(fls6lb#u^C&Od34W#c1SLF=cU!f^w;r~7eKRZqX^9aWIW z0AJ5AWUZ(hhG_$8uThEviHgkY?cuNK$FR~`BG1!CMeO2BI=a+h$;m3PG-#XVI-rv*NC$FeGpGcUg3 zq|?H7hRHDF|16bN=vepA!SpUo!`#Kmj~iU)h_b7Nd)HYmZ(4_d?^Vi579$3@>A>Rh?4DrULORDGl#? zB5$&%EARzUGQ*!%SXv3@b12HS(NaZWQ14-=MBUtwy`BMzc%s<8Va_L+u|b1E&+4HJ z_=>u=3^R6;VpbuYqLjs4Qt^~WNqokJZ&**a$>t}Cu&DhoLDoW#eQyv zTDkC%#(fn)k*#z^vS!#G@mZuK9PwJ{visdf0E|E40DF)h%SzjLMHYR-^E8w+@zc2; zJ97WAnbW_7izZt`?Z$I>^X&ZL@Cl@?PduCVu9D6?HuTW)n`#Z)agcJ#D~}iWT`Rk^ zw4wu9862S^A*~3wYvMbt7^II#^oV3unvBGq8X${LR~o^jVFdto7@s+vtJS$|bFzi= za3Vl(Q=LY!1dCpVnSUC`qrTN$#Wg)N>275Q^Yh%T{%Km9VC%#)(z4K&=!$J+DJhTLd2e%0ql9xpXC*{d zF|kd9(KI8i2_W5VoSrsGXs{H^9t(eANqsPMjWIqG2!dJt%GW zkOaTW*H@Vb?#Zf6!sXD+K+3S@XKmoqfH6B4Yy;z4E6*|8XV~X_Z!?=PJbr zp9{OC<)V?RZFs#K$uE>g%wy`9`oVBXnt*pvHaJ#hVe?MUb?-bx$|6ExL9)cUSf(JP z^Jg`Dq-KWG37(~RJEHfybG~32roDj0dQ{};z0dtsCFoM~In;`(y@T4-|9uWtUKx#Q zK{HevxmJ9f<4QoubG*LSdzvGcjYyd%U7`P8QK_u@f*fPbdYF`@UC9YpxX@^;j%rIw zy^w^~T@!4*N4Bw+1*f?3Yv%>V&5S^M33Jj*U7IC)w@NZrNhL|TY6;6#H;+1ea0qVG zd)F@5$2s+-dM&Mvaj=to52WXZS6>DX)Uz^{sW$55XAU;bk~`!sL+^@?c!J@jaVrmbk+ zX8YI;&jdgoKU3z7Ko=tZ zEmT3QK*IbrLLs7hmNmW~Fp>i8iqV8Y)g?B!@p&|FgmsekZZp+DXIE3((AE^H8pYWl zjlNN!@-1d#AiA^4m+4|{r8KG%BP+s6a=G!9BcF%C+qcs>o!@yp~U)C zbTZ!T{RhkWktupXw=wc-5$Ie)@GSYs*-3KT`{kr+!Jx1UpL&C5m6P~lt?BOZ@9@Uz z6`yL!*5-F5{(Y;v6(r~1^W9ib*p^j5_1dwVjfzsUawV&LVX0|`cZvXQ7r)Psz34v4 z|M3Da0=y>Z9Xzkz&WolE1rSDRyv!N!K0K#!zzSV?T4`X)Ll3H}6>|i=;YA3gCxtR7 zl_C^4tn>*-B%CD7?PNxl8&=AGHM0stYv6>YEX9>3egB)QhFDKl;RKoM<@Q~~bFL4y z7*k6+yS4NsX$GzszER4?nQ!h7R(LAmS*F$6?RWFL4MP3t#wxm7fub-#fp%2A9Tcj^ zi%XBJ>Y*&A0XzNy;c(g^;l17Mwok!24F%fIZlnL4aD&xO9-D$pq&>jN z{0tmme*72qPRxA=WUE^%gOJ-}B?x=Jr5i98*~c2Xq$uzTs4(@xOVA{Uy|afz*&l-q zki%K9h=WkTXkvHXX)YN38~BYyOIm==ZyI&$ip(4Fff(a6If}KIqzP$~ zhaRXK{FD>SOr4yRuJ7pX-ZK0B-iJqWUL&KVNOtup{|W#6V+n18MarDCv*6Pv|icNC+xxc)u!)0v6UTIbDW2G&rv6pO{XbOW7 z#{bU%#~~m2Z$-^w)I;gH&C}h4d2jR|oenDtm#ZNY~MbXby;>#OX`fN zXmMX}BXh(%dTb$_o~N?&pt>dZeP&iityfAr+nQ+tcN{nu@J0s-Z0?4J zvmQlN(077v9Mw6m-OTArFZV8|Cvw+zW#OJGMdsgnI7F?TOgdJ}=v7hIlTJ#Kw3wTN z8tnz3kcA}cPA(7onJKs3)vW8?d@&3h^@4|sc_PNu+DQYwQD=L5;Au&0J>s~m?r+gX z8wR>@h-<{Jeo>S&!J0}k%ybpHQEz3!kv+(s3JX-Hp?^d_F2A*s+!IyWq4nV|QvJp{P_b1|i z%@+iNS3R8p{0lZ=BsKXUP{cU8;qNMCX-erN7Mkx8R_U~tM&!83R2?H^5LzKwwaots zinUX4BB7pr_Z;_H`n27a*!jArclKWma@Q>@+eP=)-S#*O9%8}^nQ3o>T$1y9RP*bD ztQk9P42i5083q(NgU7fA?RlLfH8B@T0{)6xD);nlxEpX)=73NiAUxOz{^Iq=-PKe=E?E8J%u^Z9Ek)z(w&BFEVUqDCgip?G>D3Rd z?4^s26L2!c_wNBh<5U z8g_Sen!B4m{~jq$H(MmI`Cf=IGCai}hY($9J(g?zO?c{F1A($nNSs$IK=+Fc_|ikS zNJkOA@Au(WPNy&FnOXlV7U5a#pSs-j|NF&gJ_4P@U41JND(D&0%*tEd1p5Z)?|bT)P9!O1oh<* z$U0-&$Flg8%^rS58C1$h`M9^NI3xRUgIH=K_E7OMEbvh0e7#`HmpY~Cln=yUS*zyTXl&SHYOrK1N%$j^R?IR3(7M zlF0sH82O9h?|_g~POn;bUj31>7y*iLE5^fK*anQ90`yB!iwWIO}2z`w*Cu$g~}8OHbNj zwlnrx$6MnAcqPDYI8CW{M47Lt9YQm?Pi{JALo}@7N@c1T!?s7{mZABs%H-A6_x~<& z-j;$>$g!k_57TdM=(qstes77+ntN;=YHNp$4wCJuc1F(1l|JlYwk0j4#9qX3$#BfM z%+WKQHdyNFGNO!5ahH?zy3L1^3OWkWSut`ht2IH?Kgypx6s>eSg2oa zA#kyI4Y*g8ofqFC#cK9eJm3 zbwi#bOP9S?or{AwW0+bgQHrIqnG+D2pih28H*3ktG)oDy%_ZE5=R1`rU-9 zul{)0n|o(+HCMvf1NbTqqZ>+EZRprvM$NYA7`qxIJX)cnCKUFB+PpJA!uM<4*w9l= zPa+l+w~ckldtvQgi35A5!v@^BEm^`Ggz4`zWLol@X9lYJa^fHD$sv z)-`DIpiEM;Y$23_PaMCXl5sSL_Zuf5gl2nNxao;b!AgI&{8m!7*OWWrl@O~ zUD(XTV^=-IzceW;^S*Z!n%KpZ^)B4M*D_*y&Z=Vi71ebO{+}90ma%Zi&g4Mv%L#v z>f5sg?WBRGR#L7+n-RNJK)aXhdQe^sEuf1jYN)dmM-Hgt}d>(C+=L? z7F3}p8fP*jwJ?759@gWJE^@yJ1(=FLZe3MPmIdD_^^IjA>6YFeAZTK{x9B|r2tGLk_N`&h?h_Opay|P)#_vgF} zh~9z3)&jYgX2)*Tv2LkhJmNVKA`YfTV&aRl{BpC##`QL_wa5 z%1WuO&vQgOjz+2J5!?ntBuRUgUvYz3T86>=_ob zbv4K-V94yITAKU$C@2@?vMMj_K_Tb^dJxlNEpE?1t|;a3+=A!jK>iyll{(|!@uo3} zE*!mJGlY9YIK_7^_MYnp74uDlLd9iD$*OO<;AcRwnC6-sjU9)Q;gMjw%^D?k(!%}- zD}W%Xy&@tpV#F9kD5NTpVCKsV)Gxpi8UGsE6i?^B?cCS@6!;p&$n%lOEi%BdFV1sH zfw3uy#kFlQWbgvak`Y0r|1Q*Gw_*#4s4Z4A0`@$XGVTiT`+@dCb!8a2lcW?%MfMrz2 zGCZu}cZQL&*mMB=Sniim3uuUL`G3o^ps!?O910W|IMJFOvJ`&$P&nY~o7m093Py^( zG)vGmvL>IPB3K(2f}0u2gdTc7d9zRJg-4Jt7O`b!MyF6Ymo*vbV8K{jQ)&hl`)WZY z4C$_APE!v%NkS2b2xC~f8~^j{@G<+MNF_v?6Fg#N4t!Bd^hLQ^;uHdj?AU5-=VBEr zss+!7k&)y1e8#^9#F3}BXXmfa2luj3zMxA@tA$lom8VfKcAxb3f&N&U@Z-zH`2u{MaAY?#|Ba?9R+iS%9H0Q~uI$aW||` zTy!HGJlJVDctU*{tMAo0A9o>ZOkK0>X}H&WY|jf9oMk~ef&`REnVuIHn{-UZmY5)G zjn<8zEroWS*RehcFB7F$JJq6=ilzLs$K-82QmWUNdK$oes!vSvw%N*zsU}Oa5z;dH zpHD;_*V|pSY$#l`tumGodc~83RWX2vkehS-dQfO-ofW=IQRv!;KS(B2F>Hdx>7%;m z0leOqE6}Jcm)eU4)6A>I_XRLCzt~2usYEqomj=TNBdraa>tmcdJU3Pd~ zt$MX;fRaKni~I7n+zHNWqnlJ!JKzA(7y%EB)@!YqVdAsThaSwWf6wN?kd8Jzv)5mN zg6(oohL++qBn7>1WNRke2=6rSesy<_?ua#MXYr+?v&*BS(qGGUs~Jl7f6x-;No2m~ z7raB*?C`V)8Tvl4|xsmTR3)^U*G1k>FHp*2fo-?q*y1wxIKT8h**C84Q zTgN-F%j-7-U(+HKup>|F=idd36<)XuAm`H@JTo*3Ea6q^4x$LJa=?e1Q4DW}Cfz zq)3sv#KPQ0v+v-tWNk7PmK3ek_JF3P_wZy;OrHgB*j5?$ty)(yw6g69=EXSYoV=35 zFQ{e& z9Z9Vr6SPkS{plKL+J}nXSm2d-N#QpN?_6P|AVFICNW%7hw{O1KCrUG#uc=~jKUt?= zMg(ccNjp8tc<&SYSj?|o8f$D4{xYY7qq0e(UR0P5N}<#F%KU-6%<44!R07XeS~aI{ zPj$yV^Syv>UE7d3(_WD+)f$v=>Nv&wgWvR7!vVV;0p!;gmzG>!?gH+PP?&*M;$$kA z|2Ekhm=#&|hb=Hkfm76_Dak95PM4_@V{~oMaH^p(5FrpaQLf}N0TI@njDERtG{Jyk z8rXheQ#aCOeL5ul_EpFJk@T#7m2(v7-ZI9NC4Jpgx>JQOEFL1&Id~6xu{%ZOdq!&Qs>&LZz7?|0%$ThhT-e>BPE77=Kiqel4CR3+8n zJ#gH)59t;1nC1L>;u&5pl+S44?JhFH^bO<5Fg{Cj62M={ftXwL{lvUkSmtHDriKOO z+qORVB2v)BfG>QE04DCK8BqIhTval5_5(X*>mf^%Ia%q+UU^|f+5SXXqVdOjy}iBe zy##AU1YP#(k7)x{VpT8hBd z>UF6L+P}n$l=`rbfYW-a779NY5+#{sbTu-AQL20&9KBt4!~n&O$Yuz$0xQk>_=8C8 zjj8KuX%(#N>`=}mR`FdPXE_yta3Abr$b(XT>YOcF z&YWF^{vz95el)ATP@cjHSMD_;xd2?AWG2^=d|mcxbylC>T-;C&ZgX@wy>dc6ll=XD z9toi+%|xoeANurRfYfYS0e7plycEr!d;_noB^V<0oY12g^pc5^q4F%;_J*<)dAwNZ zA)2R6B|I|1&O5Z^{-=sh7cWY6n-S3Rp`g+(x!oqv&RLIJK}oG`=z5iy!*j^&lg&PV zB4#mh=zY{@m!5`n(Q*ON$`j!-dynJPP1iK zewjC?vuTIDvt=7fwrQPan@eq}&ut2CyIj<=pDaDU`D2*+%yd83Zo!OvNUzpckzDtD zu?&8ZWj5MetV`>H5yaomCHLGyPaRq2$C$Byzh8)P_n;C1km1A$u-V(Q=$~a`z+N$+ zQ`TzDb(SE898Z3NiR}iaYT<{Y6Yo@Ih8X9! zjO7?SBx+$}+7$_o9AFDxYmx(|C^S&XVaQH5%~ANmuY0t%^V$AzR&{MiVDZrB7MpCw zOWfV^7jXK*fwcC(ObB&N7B#H-R1 zF(`6x$?TNFy1dO9U)1cH(~Hw5{)EIF+)s*);=E}xqYk=`3seOVi|C${R6YXSm4f8D z9S<0p+)DD*^L?dc6?vf37Uk(OQ9Yzil@z0)>?icR7C496)xI2hE9A1pK6YC<;I$49 zi;2%*&MWQh_j?&eDbbxAmM4nuyX=iE0Qnz2Dv_VONY4?ZU{Of5duJ=9k)r4J8iRnW z(V@h$xrXLIwj0L6(0#9(yu1WKi5-QvLqm)?7g`?lF=|PU;jlZe{rFoVK^XB~^?Q<@ zU*E+_rUXB|b`R0yY5umt(>S#Um?dscoSSb5m5NQpR)31@DQ+s=_)3>IWSMg+uGy>+ z!&V30?tdDGX_^;?Snt;EDe=p(j^A9(;kA2rWR-78MPFLIYmrx_)4MkMk!Y2-E`3%T z*aKvA4Rx`pFN&SfORb8n@{JMblm|XY;=NTx6g1VHGAXCxPd7;jmtT0Mp#Mbs?(yAq z>g(6%xbh1#c*1|fMqx7E)q;bbt2)d#0P9`hPPb{jpHubfmWtv{5k?eMYBMNmU>>T( z+nURAcr@*vuhB^F)*GW0lggyZ-H%837N;m#x<|Smg1D-j@jPEkfXEE_xjeuOd0nKTi-SL z3LEVNOzixT)K`YMK=TQ$9(?lA`;XdL>C{FtDbyoc`XHrA3w%3o+2yU*_O)Y<$R~-! z4%|;6{d++VD_~;fZ5=?F)%?H+EyYdpHiL$+q?H$u;sY9m07$V0V{elw(8#Y-&9cbZ z>je^Ep>GvnDLsg#949QP2<|XEjpuM03pkW+y{zUXO3@GL>8xukOdEN4K9)}QJ!lQ= zNd%Uip8uW}AlMQA6GU=oTA5NaHNv5C8Z={QG!K4hnYgDUK?r!DPPz=jw9zwl>kd@@ z0(3v)v<-BZk{6<9HM@(Hv2&6usJK%uKu5bKEjuS|B+j>X)^cekfu0X$k?Yr(vf$$G zzN-!-^>**%dm+Mtlij}RazTqqw)3cm6&-y@ir}_M3d9o8>7BEJ5DoqrTv}C^JZ(HD zW|y>=dT;B;e!BIjTBX*t9p`38ySjwmn3^xdb1FktJAKTC!7w?+0?ciBbR7-7Pi3Z_JKG`dpt)|CDwjL08D3k#-Cl0xieV(ojvHyfB9yhBK_6OhhLIrJoc zdKX2Xxcy#>crlHZ5)3sxt1_o7QFAw?DWK*h1`v5a^4rUv0xM6(p$rKkQYF*`TB2~t zZXZ3?2ru#7Of*0I=JR|b;K&!fBX%C@NVMHiMix2Y>C+|QZjzXM&xK)Yrs3!w-e#4S zZ3cUmo+d}w1Or_DJ5Zb>+CD|+f&befo=JZ_L+Wyv7lnyLz$2yERFph6y`{8qudw_i zA*N}0Q48lQY<3-I$5RB}Z-IRFHMvnH8J{fU7vd8zh0b>l;us zmS6W$p7AQ;ix@mQROxBYBi>QTJAbpr(W6flX4?T4*`6iwt61vRmFQOsHH3DCYs9~F z?~qy*XOE(^tQg~$G7dAE&&yB)>FR*JBl3kx+?G`Iog-e?SIvy%ng_&F#7lAsWe}3Z zyjXMYrLL2r{#YBAy1rE~QsTyxxEuIdT*7P4oHPhfR7dhn@TCjQ;^<`7i;n)E_!j(I zL|aNmF_bv3whUznLZ!iunVMjCdO7PZ1dW^9>S3z>#R_NXLSAi-)VtX;L{i8lTyIpq z`v+vvg5dD$Z_-;l&h|}`rxxBSIS;s1D4k)vK9Ml0C*hjnCVIlTyef=RWyL)DeYwnA z1G%fX{6_I4wGu7UylYX1GEm;zPW)2EFrRn5l-yJ7i2+%2;hLI;;b=tzLV#Y;$lIcr z$zR864q7!&x%zh&zQt8K`pCYUxUN~+j2`8tFlvjbk`BsT&)EqN7QCmYtGq(jE%$loe~~TSxGUC{#Jb z6O-FixVo3`lV~xzGKY)AMHz?Jd=w}0&@GH@3C$^i#3Mh$MOOk??;IA`Ts{%bb8^_tNl|Cet4db009}_Wm zdnfX>R@srgI}>;1Li-82W+fWAU~?}T5JR9(wB^L(v(!6*ekAk85msAm;f%VH07JY9 z?wk1-mTB!(HGp_%);<0nt|n>|_6qKO@fin3**5wSp?1!qu`#zJpWB^gk5!njRG9_`A%TJ) zZsdB&kWd@Rg*X~l{Ilk1P}?Hh6ZtIA4;kA%8FxB?=4_UA2LAqMqd zU|%b#nyuBoGFa*a$_k$sK)gcP1lJtTJ_0|$UA`5D54q5OB3pDB*E&agPuE{t;O)UL z7-z!MXDL!~ugdXE=vjd=pLw(5;gMWwswf(}c^Lgxzjp!9D{yPMKbFP-Gfc0eEBMtL zTP06IqEeulo3ijG%`yKugQO6UR${pGJ(M>e;fhQ#BR~;nGOQ~xNaislL&Ti#YPls% zaB;C)G1WNZ|A>CPJn5c>_H>D1N_D2k)7RMk-pb=SF(5*jzy=Xx(9dTBc$2x|i5=20 zRaA`16F8;z-3^6TM+7kBa##WkH|af{m`f>ki`?5x40L=Fati7`=Ju7O_xfwcgMKei z7Io;ssNCxHArE^3x8pdf@p)a1#a^QX5cS^#KQO&#jihqFA3Y`;{d4U%=V%O`c(C1A zEqjIM>Z-j?0;ReLfJ&uxEJyi-FA7-zbHznGJMPl$<$sso0OnRv>AIG352f8wU3+p= zQ}ck5rnB)=<{KE5uR>S?=@^}dYtuuSQt7wp!08{iYvNyr>QR1BX561Lf>J@nbRalJSvWnBmX(V?%P?;%97E_|F2Nnb9PTQOwmaA)*3@8IR$4|T@cLGMS+ z!7(IDoRqm`TTS_;FXb(=RJY zE4|8C#T^Bju8$;B*#PYhpL!WJpO~t+B6t9a14A9=8%_4}5av`v)nSB-JX_G!k&}#yTk~*s!`T|-Wq;u;81d{PefUMyWVDv2GQ zsdL2+o}QI@Sen9xv1tGL)^GAQg|NY+#y(8+7c18AdwF?2anU+DaxtTx5YJUryBY!^ zm!s(!PUQp@l>i!jinP1XhO($}nUUQb4n5x&T9QG|5@mupLDy8Z-0fav7%;gZCf^rF zH9)L@=tbGMhb+{G;Omc*Yy4bdM1ZK#(*rA(^l^5rPE0y#So(KhXUB?dF%RYRRj%4} zib`pSl2vYhaXWyFxJYV~k2@A9M(S0gFXv5@>F8@xb@-Z5ait$&ajTKjVq!5}ecMq= zlBYibJ(~ZdrfweL$?85UR(S{hnPvHh-~87JubPTI!@D6pY=e-s6s}kiZVpBn4!^MC zHkOUTPXbiNW3f;Dcl)%s^8=OZ$D_`l|zSo7Zeu5olsWu#E3Z*hf3d*15XyI;@Ox~{hi z0{p%uROx1FXWrh=D1m{%dYn+OVvQx7Id^4DeVu5hm`PCTIs z1?}Z02(=JwP3C(b!h1TkPl+09gvH-!v8&pfy*`9w6ue!yebd5EyN6W4apa6VF_BZN zHSU_>xIqn}egSLzVcPVN5G1}7?c6JNhxK0K!+1Cmni>MKXST# zf^`Jkn0!8d7)EWkoGkqG?iqg|KgaSNbdkbKZPmPx%eBha!IxO--6ObgMRRdB28P)+ z1i1ea3siV^@X1yZY45h?k!cdAK{*m;gMEKZ$K_dPz^lHE9;9H?jW@pXOYq*eK@H=X zA&44BZ(I@C8{OR+$rhN6@G(`EK+lcSvz8L0V^X+Oh92zv?4p^30{#W=)hZ`^aR?7t zW3mt$*d!Ilc(yevW$j0><$hvosruV{X6QZvnzbz#SObLztL_qH*6(s61GbaTqC>pH zq=K{J6fROa*f=x=y~~xo{aE&Qy-4Zr68NYGU!2^RKmEbD01vsmH~YJ^vFX}o+(nVv z-K_!((B&<(@5_xgVIkq!qcNTc%w>Bfvd-ZWh4evhgMK39&n>em&e7LgR^PlKCN2AGZK z^CKJ1{hR7;sTlo$&776y$TkZMTB-0!%x&#7_Q=|5eu;1bk$>d;wKS&9N%T z2AyHEDru_Q(u9^?3tP)YjFhd{g#=)~#4MfvKKoo+a~fbR50?%>$}fJZ|Ji(NaJLa- z@U<;D9LGO@9XVH=)5+MulNH#BM6&pykn0!c*hycUE5h=R9}uZnX?gh#TxRH<-Cg|U zR-Qpo9PMD*b(Umc6G2KZ)2b&H`@LlpALZ54ijJL6wxa8f*9zQh63LDeYPU^7=Q(^f z_v?j=P|-xdAR&$oIbqht2`A{w&*mwzar)8WWm_2!dQ6lSRJ$c5m`Ls^=dxLfT&xOT zgkJ3mQiZeqe|g#dQND(=&S$f#YHGT0&?-@>a%n0t_0mx?6`@+tBu_s|xXiMR_*|S; zUN%MVT^U5cOJ>L~GirYs-LLG9H&)z+ZO*4`aG8deE-x_N!vGU%$ES9%ZqP^~kNz97 zlC>b9&B@X3e6maR6@FT1{*xDR10ba?_HYGZb9w1VB7rDe%B0fL&xqG9GwD83o4DJ_ zZMwp$uKx#tRDI^{U1=kW<982jBM~>nN3w|tM1c}DgZEs#qIvE zG|MAkyMt(lbR;Gd6}Tz8(B!*aJw$W05;N$3Q>=d^mu=AOtF|5@%kSJV|y#fj?;p*T*m=^VKEPjrAQZz`Ps)YnV^D_pE8Y^-!e zo=qs6Q|65oYj+)e@24E7b`WRyg#@9ZK6Bzwab`_vRfqqdyC(Dn&D8)W9i+kStQRY+ zzkl_z`n-72jw>85#q<)_fLYXQB;3fxQvIQYI+vmPzmb6Bl(m!Dk>H-S-Z+2UA#R{W zu1fCs6c=l56Zq?99IL{{^75OGXD?<8iT*4>nd8bY=l4n^>+desi~Yahb9&$k7sw!t zRb73(|7M0CjyQPV{fBqw>qUBA1O|Q+4mlaruEWKuDw0_f|EDt|ZfLUzo3m9~Ja-Qd za@CI7S~y()>BnRjTydRYmfLA20fczI){%UkmUn#*2t4u5`zdLUIr?1#QKM+v+hnD=eRf7fI y{2!FXvF}KRte?=op0xkjcZHhse}!RL0pBc7v2eWO3q2n0r>Ux^Qla!L^nUpy0@Ve6N9mf_jPk-4O!~c`bU#wm^QM zx=G7xVIY6}Ff1ZaP+pgiXMCwCt{zM>pzm*g~iMevm=DA@!DxIQFJBtJ2b;9&_r02pygV?nFGpN>%+v0tM?c#+S$3n;Od9d>QjS9h|?33Ea$)w zd}$225d5ulSJT_4Zdh)Nt2i#0{%7UuNouMXE=4fT)%}NQ{|VJ>boxcYe~Kb6Im-~I z&hh(V1hO<;pW8+@EvOe_4AsI=tYHih^wiweWUFS+br<;O#WJgh8u2*?;Bydtdr^;h(yOxD0D&#%5!%dx@o~%Dn<+ z%kWc7kmejS3^J&;VM#~u+FQAXh3VFnK;P~4fxSvdQH;9PgoxVf9Mvn1EIA9K3)Ir`LvB^cIK5tjaE%L245E`AnSCy_2a zcAGEU2Osb`W?gY2f|V48vXY+`A3bHu}D`y#-R0Hmogt zr8wo&tzy=@-S$9_>CZw$*7va>d~k+S#{&*Zz#nrTyf-0&eu~hEE#tt8HRD`oRh4-7 zy5Ch%yK}+X!yW{DFN80h#b#GcnqRxgZN{5I%0$gk)(+TV)w zC&9N9s^Z3HSeSGwjDN@aABUBWc$Sf#v5A072wH;#4R_7b52gSQQ=AWn@?NqLn)2HH z#K>}e=`N0^R9KJI*vLPr#LMOhw=DcF4l^x4Y|SK&+3q?ag31497UD{hObF7DmKx{n zHv61}rd|)1(&o5((Xc-+CL$l~3WHZ2m>%bQ3|MWku}Y4z3@i_MrqbCW-NqfREv{F;TD6%|!n zT^%9cmsk0)v5Qec%akT5vcCc-$bOzp)lz>5m!o^~+@^BMhRB2xSBmHyQlAuRN>K#( zs`8Euv+`Zlk(mKM#VTNi>*I6?pS)z5%BxhHWvR?t?QDDT(b;RFfYCu7Wu@Le9%WI^ z;C&z6l+dF#k*{LUL)4Y12APT%D;%e78`Vk*$};naTqw>)7Dw%GKXK#)20`4K0q70{ z*&A&fb9?hA0YQCbum8I!hz=Z|`;bSm-cG1ahzk75aac^kd|M#c!_TfXW9Dm**{ent zCZ9mB6sMAK!P64A@FFV#b+iVf7k{v3sX|*ltU!OMi29~TxOmO>+Zj(^k#0$-2A4LC zY^jL>vQHBG0MbkB_1b#-)?If3lfwO6*rJ2|b?jS$eGP1U6qWCCjy8ljQUG7ITbiPI zi1a1SzL!@LsP3($#xAT!4bu3TO1%}H{YTXU_B)rb|I*Vbw-wb;61;7~RCkXSeOa|%(az zJL6Q)n&&TyplKHaBnGi8C4gz0rXiC0ma5S?9iv|^RBD(q%zPV&Y{`+n9(Oh+%S}dc zqczhu(I^ef(I&*NjCqPdPqnb8l?U`5+2#k1HVfrVN1u-0-7%m@k!`fnP$-jy;$_9F zc;qghxJ;Tflwt=9#_1Uumn<(9)YVCGB)(N9pc>6zt4cgfvgb$tvfZ{CCFATOpAfj@vONMc&99o*rWI(Yhu}XW~ww74Tq{=ZFqTCBz!rH0#VS~KR<(#r<`Z3!) zWX1biuz&q$p@;PE@U)W1ZDAXnoFlU(ejDWk1{<6*6>e<8%6BQ2rc2ra-Mr5Bl!GoG zXOfiou_Utw7OSEy^>)sL_%?KLQS?1nPVxvN@(%(!*=-O^z1>X?U%B2tlh62ai00o$ zcv|eDK-G`Zk^^~xP8d-T;W@eHvO?|PUf1L3VazFb9OkcYPL}r z?FWSLdD(GhyOSlA)WAm0<^j1uJAd5Enn5>9w5qV?*QsCo$t`7)KMEWeNL zF1}AxkE#aw#b)NNTG-epWO_NC_HT)m$dwLRpZNtmp7pls_Lco-E4Q_Twjf^rcfEU) zGP-k}UVX=xTEd~>FkcJ89^rZ6F=BO0Sp3qQaC=eGpTY7nEd^8jHukSSV zDx4~2Y@3|h=Ik<(jHXG@Ub;(Yjx2H%&a@vMwMk`bWN-HJ^6qmfB{C?_YtP#>Q4}3? z(};ZS_(kcpwh$OGzml6NLyp$l+uKqSz3etBkm%dF-iTt_pgwVIeUFdo*ICy$^qb5Qyi0qx!g-?bs6Qj>-}aUq(q zeHWQXwC-d+h?_2GRbMAhr<2$8sh3YV2{zwLjybI&K`6~aNoi9F;0Fd7?FSz^py)pl zKCpHSuHSS(cL6DMBnhfG<6sdHjmlC~4#ed**;=b_#CalUMPfZ4G{2Ey%1HebcDqcD zdV9LWmWQ#0vT!iAZOs(S71j1Bc*BQ$IiNi7552OBShMDnvOH+B`uEo=1eiBZYvYEk z&jjOS3N$COMZ)3e4G?y5V*~TX&VGUQYvFNPRKL5MLBH)rr<$hL0b9$9VNNoapYs2W zu@GF%-jB#oNhK(~%o?~E^SCAPz}VrwOF=n~=3x1apZ}zTt%#Y|eESEz#pW7mg8{oJ z7_z2brt-T)`0OCm6ocZf8?Mt=tk0`O(NpKZHrm(ZP{35OWKV$lB-Scei7t9us7U^6 z>RH-^QvSO>m-n;OER>;i>QvjUG&hDpR`pAIWlbUtB<`gW!KxL_)ApQ6lx#JSZT|8nQq6+*>#=toW{a;t-|qFcY1|;Kp(Ziz=|%s7E6=-$+yPw6Gwk zXBf($mBRb0*4vAT1I_G>sU~Ww-F%OzI-(T2DI2~aE4L!y{#vR6t^(@o?6X-+W^7V2 z3W@?lj{1g{KG59Tk|=Y*{NC&v5x?!_g`3{4yFgsO%82Z>jufHE?do;G99bn~gs>Ik zbHs`ctQB%hG$$`%Jl0$X&oD*hi3pq!LJ<{-b|20~kA1}jxRn?ZEn7tI-VcgZ*d4Fp zU0yN3^c++pdjGIJ82a9va!EYS3#w;jx$B@ZA~I4=tUhXD^sq9{hll&DTxmO;!RypP z?;XvezdOg;X-o5q#7$Fx$=;aH*78GE{9E7u#1RFX*AqY&&dxTom8@gLkO@uNYlOT=SBm@oy{G%m z6SLA`%OZ+CPM#n!HWm%)Njw-dK29>OO}Ier7be1b?ulCr6_;iL+zvc0IAf?O(#gk|lpLPJfzSl$?RCYZXql95TTG8~{h~GYaDYw^a;1B>6h_m`GaMb*G(~9osp3NOL%AiPQQTd*0t_DQ;vv2;mw9!JpPt_Efkvj0t5v)0%y%l9}$*3vTWra zLE?Asp<)0DFZk7NDvxy=$l9mtNMQNCs|ntC--4iRTy^_)AJ+~_gzXy`597;!Rh;oGt|jKA zW_m$7{J4W1df|TU_3Poy%kN)yaGj7`!Q$1$bHDv~%irWTp}MOc`D0Kvnv!Yto@!1|;9xrL_35s>71$DRi%St)#+`{Lap7}shSvLq)_-;{w*0NqsHr)x z=?{y#y4pzEIkf>2yG-_sag;&zyFUXYiHVuBwx6m3ch2_8^&HogKQ?alM_W>K2G2(+ z*2^BUXX=YtxXzl5f?aR?g3P8iSFesbE^sJ&zkuPPNp*CJM|7REJiq=ylhuEO|4Z>W3YD@Wqr{hiIYQyvj{t54Sg{*4pXc9{@NGJAhHWBO`V0|TJOP{M? zwCb*7GaYwkO=q&}L5GYb zYraNoi|CO?rQ9sVlQ6)aeRz}4$q3hWZ&avnnCam5BVz5Tlyh$LdfG1D<6U)YK;ddv zPSv{28RYSfs_P*WOQdRPb-@W<8xMh-#*2LfK3)V0kG0b_-2Bnbe7w^UUVvXvIy~$@ zK2SYE9~WN?_(GhFM*krF?rsh4wHz=T5F9Ty6oBpkS9hQ#F7$fp0Bo=LQ(0}{y_q$$ z4qNR+)B>SbKcK;|s|M(W5t&!l$IH0;8ff7%d=+oG10l69>*0*>>ikR>wOD&!Gk7UZ zGat}}$X4iz2hn1HoLW{PT~~zdSKU@C%gp|9dLDN3cIQq zq_G6X+aYQYOOOexX2f0ldf9n%;JpCpt?|q+=-PcS0y?*LK?wl^oDnVvu?n!<(%Qxu z*|6M`fyUW1UY%T4Vecy*Y3n0zup_JK4jp<^pR#>l>F+m%xNev}T7)&4slM zW6#{34s4ojc?fVZpz91e5_d`C5qCMWwtXwKxF+@YvVq6}1q>Xot=V<0UG;8&8|0wP z3*gOdd$>AsnoH1HbTK->y*fdwMsTt1jRla``b&mx}r!!6LbuuVv*-)WoC zfZnAKK`W;l7Hk*ia(|1d?U8tx>o>C6in+Icm5w-JX-w(u>q8CWmE});n>l{E77lUf zx>C0Wn!Ysyus_|ct4*)bQ=Dv@xN{A)s*jv!hWpPx6%IC7N607gDW@A?rx{;HZl`hX z8H{n>Xf-!^!*8juu%i7QZualix_shWTZQ-q1a4rtocOZJuoXMCGV3ep?Jer!C_U}exVwBYFl81;Gyob-7c?ik0BO^~<6u3u3M!pCO3vaFeX6o&o z_Wk?IPTesxJ$`r~RbAWnnwAXb`@%2Dv1$FuX|(=3^&KQLHhiuA%?gD}8};p<9M>zi z+C271b;`6dnVu%_4Q|;IRvwM9JG^|WJkRn@n^ioFyuNL!L?d9W1Y6Z;`s z;(kqTrL8?gLBY=xy#J8UyuIu*+j#NA4)){f2$X{pAo}|funPY{_U8{N0?!G0C$)Um zLd(&91-TF2Ye70}^rp$R`!~`l##Oky@v-V?0Pz0XB1r6daSe*T3V#KKI?60VE@b>R z>~311fhU}_cNx&Xt~Ge!=9NpTqu6({Y!0EkJKC0l09V}n7w?0O%RxpFkNsUMj^@t5 z>U&RG^RD<+&^a7liBh3 zfWFcSOl{bl#rFX*z7S;mhPZVi)D?ot-6$Bsc$U+9OCG zY5nC+(@1@bkB8H0Jv~oHM@Ls$PQ=v>cVXG>E1B(s)6=iV zKO_pm*vOFCqni6(<t9QEz(84ZU8%`u}?hacimw<`& z@CdZ6!_uT_r7U%wjT$~6Ax3lB-8JUS0nMk4*Rnq-9(3zH@o`E^t(zPGObFFP` zA~b405{37DFIb8h+Q%9jBZ)kuBYZ=sMQPWNaXDq|zO^{KMZVSQem@ZG)|FL^g#6+e z*He*5%B3AL#A4DHM&jO2z_yc~S^Nv^oh`imliz;r?4Z6W^vP%x(&G7`3n{2;8X1D{ zwp1xH)QeFRCy##{-AzkNd!#h?3$3k$NEy4wC| zV@g>~bV8%n408Z`4<%URRwJmmkwOap2}#NKys|=%5ZXQ)qHm`+hQVDoDau)W?_bzF zz3U#t^ZgW+y}v0O#dXe1;#Gn2^vm`@%W`iMI}drNrQR19YR-?Kg29Pejmj52U-*=V zEe5}MAd~(B3@vTD78pzYO!d=T+L4R5DtLdhXQ~%3ltR2+5tW{zu>7Ca{x-)hj|txM z5Ro6-Ri|RmPyMB!Kxu5@BMDmE!-fvLfRhpIR>O}2)Rus`jRy@JMwcNJNqPj}9IPFty3{j5b&!Qa9AZOw41C9On^fUr3B#L z51P*&+upe26rNQtlsYaiU^PhMtSnT*o+T}d!!ta+a>wEzv~p$GtxAsT@e;Ph389wD ztMV(5|r(#N6s3e4EWlageiY-3&}yu8YUqr-Vgkw-}`_Hc`w2tkcf;l)G&K1R7U zLy30W+i1v44)CV`{QP^q6q0+m%qqzZJnd8#1zRy#M-*C{2Y@zLQqw@r$?54YPOE~c zt-S%4Pc^rBTP84yrEh*o!hiX}pWp?4+|Q}3tfX$f{Q1YX*TE~q`~I*V+O2}qFjY1& zb3cgdX#&Kkmf{Gka~l*B6{YgyM~Le`%J>ZZs&$au6iSCK;k0l5Fr~=;Gr`A=)-&l_ z7`N|}Rw7@f)u)7w-Mh1O(-V}NDR{5q@t=epSLJB{5=s}xd3b4JCaOs0y@J@n!hW+G zxioT+St?1o_M0^UHHZZB!6!HY0nu91PB+~-21x=>>MSR;hYzd z62V000f^S~-(TRS_v8CSVWyr>)nzt?vZLA$xZ4eitxbNYgch2*Hyu?9#{o2#Do~!p z*&*i+GJ~TB^hA>yiGJN@R7vTSjX)Jm{JeQhZITw~UQdW1qDpQ+6EL2Uv_P0ib| z>^T_;9}6cmC$JT+KJitaRr}3G&{Zv{!xzJRigqgQsBP65oM*^Xd;RTlw!0%lUxwKj zl_;kiiAe^tU05lVUy1go)BQ!MBT5SW~h^PwO0zM*ggS&0*k6v~Xsxuy-ftPjUc&lG4(tHrevk zt&s|?lh~PmmC1dvxSEDe(bKE2Q)TXbSX}URm?2 zwzX*@p91c*`U&>8|ADRV>hAXZh>BblsruCY?rDgBj$FL%TeGsZV#eFWxM%O~9W9b9 zO;9XX(I5#4CI&uZ9T$H-KEcv07)hqoiH13j#sa;>C`F5F`Mfz8#{ya_pe(TzpGo!& zzVxH81#Z4va2fU{C;Hi5^U)e6RXOwUZGXZi4hegId4(ym-voRd8X8iUz;PM-OUj6n z?vQFCyKU<@Q9j0$z>enhXfgFAHyWfB1+?lcb zgUjZ4$i3_wLRh#g%m2RiiW(;UyCmy#HR03)Dz_hSuLd4lpx#9nC0*}fvH zl`Jzw_bj|^L0ZCUK9|?9W3qIJ*q+{`qr@Fzj*P67s{iGUA>$XNt)f69ukez*A6hJu zr93lS*jp`xkLUXbgw|nN$C3MAE4mpcgv&k>{pA-Xj?ZrrVPEml&C-3o)-2z=KZ1$6 zBi;$RtVk{MU3C_w3VDni-%2IHv@;F@Bui-*pEvEt9Ie-~PKw0P^{FZzg?9+7?U%*S zyn9(%BJud@%k)n-+{t5ImzJ)n?A#h4Ng^MeJi+OWXxPhX8$NvNXyp7CwN?TC_FhIX z_Njl9p9{s`I*;D!|Jw*e3jIOcA6EIRc9Wi&P>V{>qoq@Y=>O3I1VK`C3ZW>6LA^(g z+NFqIJ0RV<=i{7YRrBZj1+3?^Hcrqbp!p}ZWjqkrle#U~@d;OjlECkyaRD1_?D5dG zR>j5vo~CdCJOA?&FfyCI@rR*i{WMW!k-XgJOP$Nz>-;;>wvH37zDwID!qLAU-pTN` zjc7COU_E`Dgp6Bw>Oe0J2YjEbb#obdR{M(7EW|<1C+^Y0a>dzJfJOdRspD2DXNCKE zX|(x9ZZ!TMFMe~eDzn?q3~-4OafBMuEHEFJ)0)oeeJiR{FEpxr*`&Pn1DJzg#r2XA z7v6uPtVuO9P*>@QU>^VQRf9ZiLH9K>x<)|yNEn#zgi3PSSfkE<5w zw^=7g6V9ci&*7V!Pi4(RTwB(E4x+bSa_ve-@-;=gmi;ZK#ZN&WIV{k5iZh`+A?g}9 zTKB{8Hc8=a0^eH|t$lldrZ=7Z{HGQej)yr9#I&s zrsms(zSpUogfzdtL4ql>D60j+*W%iPR!`PFnFP~zpWyigkY!X_1wwLb0ZJq`mb`iS z`pzeEqpE(#T#g!*I#WM!f2vgKy@@$QVPoU`R>T@F{w2(Bt&q>KNVf@neuvEPQ^*55 z@Hw!gjG0)J3gW-DkK~~Lp&eYThH1_It^p@(LKR;mFqWB$e=KBp8=*ngsxT)YKr)W+Eq~4dLlWL%1H(Eo>MUNGj^YOkr6^xwmA1bys8ucr(M?w~( z9h7;x_yVU_z3B&Eyy*Rgq&hsGDn*O!FS>n(t3fWFN(l`4v0TDSvBJ9 zUhY)C2<}nYnDd8UN_ICdj8Gw<=xkM-E}PFOdqrD+4niA)L>?D}$pmvDy^e@z>l)CA zvuZ}k4i*hG&$T0)bWr+#xjZx40`K(nGC59nXA0C!27@`AX?L>F$YwY`d{}XvZKgnr z1?tlP{WILn6+``N)^lqiowZ6rsd+sa8dQ3Z_l(XMWQ4AAP=JA_cX8E?J_QLM_5~sL zIxfd*Ax~@{n79Tr#l^sk=ld*;fA`YAcH>)rEK9Sr+Iud#(C1>9a6YW#E*4R_JfV&k z$6LeH7w5Cy*66p&!mAcP)a4#Hw;%>zt!IL76mq&Qtpr^OQHjiSt*Xi$P5f*EVfMem zM94VI(C3pvFSH3^A-?=lL|f%0wTu%0G1|F%CI2SX6=PKm2d?TiEgm?1vW&lc<$U zB%>&+#1rN!`%Mr$N(Co%ACGlu9C0<3UK{Bh48Et(o9bEwt z)&pgjmunrK9jr@KMWAh1rnhhDjjwOQpagqsSm;066mN013XYnN&L|C<$q#nVW-mp7 zkYCG2yH=nG8=anpcte&r1K>&<$R=#wopsz-4vt+jw<-?BJ-JOhx^RM3X0+eyR=%sW zatlljN1W8uz{_O1<#g!8mD-_KDR^`$iLglsQFcjo6o?Oso(1sQ#Fim{uZ}92^}fNt z;j2aTrfV3zP)?{;-^mj1A|)mH8x@wpRZ{K^fOOiC0B+~g$r(Y|xqM$-rU7uie)32 zn^mJ<$-m-PB~@$1*t|B@9kc1mm@hs&`;)sNZx3F%qGvr2Uz3{dUIX?9IrAQ%dZ`oT zYsSKxr`&_5f=pY_CBB-AFcp*0(xT&3mD>@AJ?}Bt2yJ#oPDv>~hHrqRF`W+(kk6a!20F)cD~zJaA;-!}IKn9W3%` z`os0Bn!_f!g`|tH6I_xhG4HHAklWl`IGbU6AztvwGVHChNRY9x+OC`z@oF63ToK^u zF*b8%<(_$6!{=yU(ZhVz-C@!|4x!1^>U1Z4C)9K(?S>H;IM5cg6fCx(wAkjBy7M@er&CD8I8XC0*OR{H0OXlcq z`+*b4vsp=2lxYJgDxOyJ3F%PveDnH%70lK z>xQ4~^f8~UpaV;9lrK%smDgsmT)b7zIH^lpowl5Z7xc59pFSXUj~Rh@NXAR}{u6NA zg#1V1D7H&rK#r9^^=jqap&zO{<06t1akq_UU#wa`(mHBYaY49%4u$7Nw}b`G!}i5% zh(c84z1XU1#fWt5n!@u+M8Z#-^zi~>y>`;tV&|dgusNHC>HFtg8Bm7bBXLvjKAI7R2JibaVYXB$LsZp>hFWCpd7}%u`+n0a#Bym-6&Pl{+K%Japn1C;tIiSU zwz=}$-YtS}g2#~RmlHZthLJIj#>!fb1l^n;qj5+`7g~UDj`DKW3O3Fe+r}D)%u}`W z?^7>bm+07LdYbIFT0XXNy@y;4TM#&|KV*59%O(l3Rk2OmDo^8*UR``50h2`9g$h33 zA*Dj*=sX&q=#jx^%Q&YP67<=N zrEV4t*j*8f^uq2Mx2mVFgpRaR%TW%&ealxb!_s)jwmcpkz|9Lw*3K}o*bmIXOgt#5 zF?J>_&ty~bUy}`BnBr@23=~Bw4ur;#n*V$))BlYNgIg;n`a`q{d#`@cqT#9qEN3v3 z^n<$b*k*_86Y#jnPv7QyHkn$P!j~LTKJTx79?2*!Ul!}-`L;~ z_R@u&l2LosvMCR+^6>1qo}A)W9r1{X^Whr(RldVonWC-{0@sTNAK@0-pAb@ zP{_X7P422|toY(Ocdh62Y0CZFUkND^pm`;Cv8Hw;oPJCK5A@5_sRs4^Uc`qR8oxHb zwpe{Vmtp1G15vMRmb+hB8-xYe^HK6q;EsP#s$VLZ;)*E5?yLszzoCd_P>`DE)78^6 zbzqa5<<~W?-b9dhAL^`J;8xr^92?#@Nt`!{5G`;Kg#pYmOwuU2RtK8GnRlX@3=K;a zqLk~2XY2*0mVbGg6l%zlTj~eAPZ*#FWRF+!=h>{~_C8$mh7DNjIswz-SdUmp~j3w z-6pSxcyPXnO`o|%%g~T>m~XihM`|xWpB}hCjVp5I6H->Dr)LNm;KH6Z8j5_vge_yb z#4qzkZ$!qjBPRSPY~}jbXN7uxQz};w$!Qx zZ1@Z*Vk15jD%YE;Ieq%$Pddu-%%G@@fll_Bd_n^Klh_ZzyTz6(cdgXPKA<7BC#y?W zYCj1L)5C%Q>Bux;J1r(AhD%tZM3m>fkJw*I2skP(MfS}me!Nl`u(jDn!rmpD;J$Ys zoycHnLxB3SG2=D%2)#=Pt^IeyA?Krha@SpKsruM;OkG1hKofyD^=V65c;nnBZ5>EO zHNyVWo22~3pU>H3bqJJxm}p?42^-riH)oZVz$%{SydOlF%oU~i6K4QIGf zCg&dJ*yP`Wk#|ycFH2(&%z;Bps4z3(IoCJSz*?A1_Z(bY2 zx6LKqux_j58tfOU4$7P5a$z%B;ZS|0&z+j!&NHWW))Ibj$WkkZXrOKzWV z7S*7i{hWOn%3qnnpj@B#>&l-?%Q{CU+cTWH)TUD2V`P4wM4l%^CGGF@3#>Z_q=QzRo~o3y)Vgr zyki+h>#VDZ)@k*g>gUls92btIU8QTb+_HZ<@Jl=8`J`|W={t*+*X--1YD^{>!6&_v zdDdiPNavNEK@8&kT(rK_eVMq=B zbNz6&;9~FGFjxtB=c*D`#vR?ii&@Spj*@Ikz0Rp&*CMz?5de{SsZqVag&ofn%Uy{& zqt(!ZRI+|A`Bsv_r;Psawg|wO#5*1Wbh{#Bcia%dnPyTX!cFwh#7w7({UC`Sf|{?$ zVQxmj;8OIF5Nkn!+j&@!q-r&9YO*2I!BvJoIZBmkKue(9=JNm-UzjPExbVpIhs^Ka zd2WbvLw9lJ=jSI)hgvi(_yoqgI&WxnICO4C=BodouiuN;@8>@F5|k$X+r>=qzv6r( zF#GJ=$Y(lSaOMKf;H?;O2{DPl1GP?Xm#jH!A8UxNXPh8_fN*+xH0_3t=Xv~DvxICq zf6l(i>dn`F!?4y?{-Yyur5Sqc`s`qF*O#j(?)xq|NNeBz%v99XW^AZ;DCG^AZE~T? zbR8}<fkZP+Tm0nRvHV9S_pr=%tCz}1_> zM*JBi`8K+hjRMMGEcZ!JrPis99K~R06Wj^B-)t@$4-e4R6V_3*qw**67z+E$dm2={zffZulxq$9 zJgBG`-zE;Lm1+IZex|J>eb@HdvAOo{+tM_~ca4s-O_96n`BJ}wVu2ex3BO#`&X!@- zK=W(-Dh3ydzalwu9;RnqG%$M?f7fQ7SJ7IDRB{!9--8Om8Z=A&}DaqX~o0wqW~9m=>fP)f$$`Ng~` z;!TSyH&~G~)=Zf2y3EYxW9?i6cMK|Ie%8)IBir@yfx*ts;LgPS`;r@pfW+!XW;IT& zUhI^uwf6!RRJiTHAaKaZ=?QM0$cjLm(lWFGQS-}Eny4MA`b?Uj17i8Qhv7r2loOZ| zxESR9mOEd|o7uC5TN+5t>irVH{+JNb1W%-YqHaSV`%;~ZAcI@JKt1dbcWzEMMHb&C z0VS$reEvhMHt(QXQ{VpR)s68Zylba&q2#(<;)()!wBcySHFrv79&Zzqpfnxnt^XcC zI3ZK-h;Tq2IT7e%HZw?ke^TE#@;iGMzGdY=buSY=F430&7|j&t&J^?ZnkHuM{_K| z)|QtfV6tdc`&&qe`gEsOuI_*=trhPTS9>Q;pZO*}p{BgK<`#!2?@{ zetSns0KGzEmHP!cjm)fk(FB|l+5Lxd{cFZ{e6BF68C>*{aS5){-pxyCsw;c~WZo$q z5iC3+q;Q3Kj+F4~O0=HI8MbHb9)@-)SGa}5zKf7{Cz{57rkxRW`^VBAj{75aLdEu# z+)=2-7wDpen-HeDlDLy5n=idELk!`mPpT3_58hLh0;bm(d?itU#*B(;Cv_^Cw>Hm- zqH!}la_uJ=l%FZh^fi7~n(60xJps;QOqEZ|a8Jv~kksQYOFmt;^Ko^1xvlxaxHBXF zWs}seXincT9YQ1jB`dSOowjtgyTro;PKb|e4BvHSj{m%P8+kUOlQq0UJ$r;lH! z)_y;!Sjm7rhrgkzyF130;bGy##OGY*KOJ&U)xPJuQd*KJsrV*gda$*Jrk*%wp$>+* ziZi5MVB955xrS-{LV~4HKGA*?Z=zmPX>KFX00r{f-{$7{0ZI6wbn^D*5Zq9|91UjG z#@ZohYkUnmx`chAZR*r_s?j+LPXA#O$9pVC_S?JqM;PX~C!yf2iR#`{aUX(X>MwT$ z2z$YCP8MV?H)!eOKtAewQPlo-1Tb7o{^ClX@k=8vu(gjblENR7C?%8x1uiKZy27GM zK09p-m}OLkl;jdHlhM#vU%i@Rih1!2OG1r|3^gc-mcrW+t&&>9!SqK27f+;g%{ca) ztt3$iSxF>-V#n2IU~tsC6}tp7aE3inOrZXgocx50!j@2uToi2Tx3aYoGq{u1UmVZh z>JErdqAOUoO$3vY(Z+ssSK`>`7M=d^Y>C%BbH-!sc**s_fdoC%k2W|YW_!#9PMd8(uuF~a~{ zVtN+Ebv^p#*$3&^7kKlFHVr2oba#^y57F{jEt;gq^2@A!2WJ&`7wTCmgZGW1Hb5kI zzGYJ2{d_b7g@tjIn0uq8+^_iO_3*IWY_IGTl0+@2UVZp-rkUE}aTS~h8zDqo(mt?0 zBz6f59#xNVeWK{$JzV@AY>P(E9=eX%(p9IB$C;S%GUYiSgWy_xJS^DZ>%KRAWUOUc z8XEE=pTIrC^XGU4cEAQBDJceQRo$ohW9J_unLaMs(rdAx0m$lGr+Pl& zrqt;g2Q#T~HT=3qFkkIKY4 z?jqZmh~J%jVx(yzv3Ww{1zK^IRAqka{f(%^?Fj?rT*#HU4X@!)ozV-x4R-)!3%pjw z!<#Ohup8fLun)g;PhYmm>AE&b<{VF&vUz~gR`Q%zK6Rn`^Dsz^X_Vq6VY4L^rNIGa z%>5(<>~NXe#e2Aa`nc3=h0=e2LCj&8wE@D*WSjqa*R!6p3A5VAi*y2sjlu7SUpsY* zjb$!uU==C$l;ca>$n)V&go(fW!g2@Z9b2 z^-Aaa51Ee#fh|4p@RhxBJ94Cg4-m%wI-4$2IsPc&C75ixNaSzKhh!*oQ46H0l!!Qy zx}E~gsMPfIETIEOs-KEFBsZa59=Y-GM-dLAfZWDCWpRU>2vQ^6{$X|=VPcmHeFf77 zsgjQ2RO51PomOyamA3bdZD{LAsUfg(puAe=WTd>~!7BFjefFtEtnr-)*S+-EZ}+~y z^D82+dHA1^xlaL``z&KR5*u5|U_q}F+}Ir%qrh#=(?W@SKnIx8xLx*8`{p!LyzBJJ z+NO4Z^KqKRIKY9X1AHCcb@$lp#R*n6vZfjg9N^Kyenn?MYCy_?L)R}KZ7KW;eOigv zVfw(K#6dTSo$?{Zv2C;@+HqP|$05v8ks({jIsp*vu<|vZnf`4yfqSjRC_l-oOkEz> zR|S$LOU0CPn$MlNvGK)M9s9KxYv*IFV=SVgm7s~1fYZY8+kwfiz6jdGb|<#cCMRvV zc<|9&JzzEcR_l8`AT}%eQ~aB<@AZ1r=i&)7i3@+2GyQ^yg~WVtLcIX$iWHb$%%Urm zyPro-y}gFFq0t$g+Hu*z@FFmLMP@e>pjzKFSD-UJVnj2q#}v0CVR_F<6K zgR$tGCKSR*?Y`T%eE+fY0Z@54X5(>1>U+=^BOd)|AZHwL_-BffF90Y_vra9h+m_#V z%ntQ3)Ny^tC?S2|2tP|HA!SJNIgJ!u1GZ&e8_IQNXy+pGX*k3Z%CE|9Z?zk#{g_{Ax6B^E?x`Um09%dE}`_jr9fh8yGxd zb;L`JJZmmF=h|8%{futL6oq=Xs|=_Bh9oKZmx-6^l$X0DWC(C$>c-LlQBd+6cHCwT zYkic%pP>9kY4uZ(`&z0LKJ^k;aIXRArLDvGVQwz@9X0Nx)<3<0A{i?EOlpQMPrfhF zWrof@DYzSM5Y%HRT+E7*GErUsdC485 zaHXzHc@a^s_jZ zd)!(B-sMyZO`d1Pz*~;)G8XM>f?DlD4|h*BZy%1(>6LXpAs>G-s8;KA0S-@J(jTlE z-@YXlKeN8z`0Pwv{VSEDC26#*1@+_;DIME2CQHR0_ z;Bzme)dsFStX!9C^*y>W^#CT%*B5{kAdc?9*esp;qls0`@*`S|_V&+FA;weH0fu6#q7lxw{MYuUogo6qg7MSt=>=dOHa$>|6kqe@>!L3wWZ_j>_c4-gOs19_1C zGOOsd?vzpeTw)G&QmjpN&H6My3v;sqNF$qSzgaGzYH+E`c1ycruS->94)MbRl0!pG zD=xr_6ofZIp8mi?=yY<(>-(On_I^i6W~Hw>EOv(1M$JLfXU&fma>ROlvp{CTNz}~r z3ThIZG&e!8{)c=+aZBN(lKHp=jET}qZMga60JJ!an)h?=x=3T&L$sw=vm)@aBd@N0_$w2fL}L!K=;gBj3|qYlUJT6x$*dF~$s8)||{rllJXp_ysE;{`}$& zZRHD$lnp=WdJLQp_siMx+f~{CCt)JK$mXsq-hK_2Sk<^p+~<n?JE?b zRttj*{GI41jlM?)(QQ7~MrG$62Wlt{*Pt82xFsA$Mn(s^CZX!$V99X+X$}^LJl1R|GpFYf} zd9D`a_bc&cusa5_)ThD)8h)8-F%$+=zbC%OPiknQtx#-|`rM@ha@XC-P`=>u@C#MF z61zkp!~e}#i~je;#L+6U#1t4AxX+YBd@fPa2#N;(t&l^Q*gQ_mzFQQCqO@2yXynVm z-W-iA!H4Gdcg4y39HSh^%HuwOe6R3OdOmLy}+KepQgqf3>kRwv^UPgCBy%C8SftiDD)F?}kh z1C;Phd*b4vtga+ASHe`*>-d96zPV~5TqhqEym(t|KUL)>SL;_Bx%J=PZOp##-BkNA zvlWxMeCCfQ8~D~)__Q-F;AL$--*(*cTwyQc1q=3Xat~(mNvAwB;%ar0k!Fz6ntW2^ z^tK{#8UOk2lcu~s9W5jRECOv)jAkYk@iR!JCMG)iEf41A=3eIPD6Cm?v&=%~eCyWom4k?3v)8yW_%^dCL8LA9ntYFHy^~ zVp*`(LWXbdJIl4J|L@AO5?LecU3}ME^+jIHrrp8z*VpK-&QMwvU7k0SkCiRwtBmv? z?|_L9JM`jr<|Mi>SUIZ5T>Kq=|N7JZYwPs4eYdO1zuarPS5B5s_S%srEukN`@=OwR zcx$v;()ZrHlzp}grO&_rEPeCCu=ieCo$`W)=huJj{`66F?(b)o|F+*ynAY>M=6@xy zfX@itxbpdX>up8mi`2FKx7^=3Us{xbAw#n>mi9}{`QuQlz-Z5qad?$N1&rv1@h6@HCLt^UWS8rg-m;-dX^FQZhhaDzM?Y3KXqTmQH1>W)iI{L-e zUgaQ2vN^za$Nx_F33($~wpjrSm&a|Ge{>GRmE$KqbR5g;$*tI%lcaAuecJNtmoF>; zB}j%0_l+wh_I_iy;=1!*l@KU{O!8WO<^4-@S+)kVsUB(~A6P;0d)8GrP*y6zLeEUx z|Jcio>`}96rhThWpu7x`^^r!V?e)*+w(w4zg+ngs{36j;Uk1n+OxZR7T#MPFE9#D_N`W cRZaS0|26r_v@7ZTAt1+ky85}Sb4q9e0Nt5Fr~m)} diff --git a/planning/obstacle_avoidance_planner/media/smoothed_points_text.png b/planning/obstacle_avoidance_planner/media/smoothed_points_text.png deleted file mode 100644 index 2e87a616fd021968bf446f98501e593a33e12e9f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 113393 zcmZ^KWk6iZvMv@F+=2y{Kp+GO?iMU)aDqDo2KT{&2M_K9cXxNU;68%{Cg>nR2YKv$ z?!9N9``()$BWt==*ZQivs=B}GZ>q|&*ch)c5D*Zs<>fx8At0cBLqI?j0-!!$LHuPc z{``UBA}Ox{cz*c+%)_65letRkxT-r?x_X#6TOe53I{+=-xtKXySlGK*JGjD-yG5TH zaoK3-xJo%&n7G|OH_CyXsQex26798D@A z(z2x+R%9GC=brP8ZMzu2v|wa&X!~7*M(Gx}0=5_;XMZ(g&Y?%izy3mgGL9>#*ZAje z`yXwGNl9sEjvkc4bnoB4EpL0ZA);x0FJ=}p77-P7>S=zJ`g9Is%b$7kBeAXa@o4%n zs{8SRLmvuIB1@qWfk8qfatE=nA zr0V~O{Ppjv**LjU@}tKG_|gW-Kkuhj&5Zpmv26dP1V z?_Qd^yQhQDaI4zM{%--dpyQ*X(_S=ceGjgG=&km#GnAX*KU6MEy!)402M^Z}=b4I)B5>_<#2@kNxNW2kYO0zyDvbw*G1(|B)yN>kUHtzaST=WKcUmo&8An zpO#1u{qS)^91e$nR{D=8J4kxA-hW!+z*bI*uF(ERR#w)bec(S~EnUj|>o%&?KBv8I zd=mc@o3~Yb7Wxm&N~>v~&Hqn%=EAPO40RCd_4IHpASl@Ozj2@Z|KUFI|1s3$>&NMb zw~%kQn3H+`t1J6>^T*-~?d}vY-^=!v@P`4zalc6wdl?Q(e@~HNe|&7Lq<`vGnnBxo zg4*%rgz~y^6;^ftUvT3yS>ZtqC26&h*giR7^S^$2qC_pm4q~=ak83Be0!!=9m9FRJ|?o@h1-_gWsN?%7}%bPcAru~e2)14}u9S6jFHx7`4NWn8tCYIN);{I{S@VBt zwhe5KT-|uAN+0W}K)=pze5_A~b|TcQ$+Dy93mO`C6}>;La}oPIr@a3lavTz&Vx;D_ zY0==U>bueLaJ9DH2};@6FsNfS;~=G>J32l_Je`rHKGXKU)LvTu_?L>8d4IW}@aHM` zmtID=+SuRNynSY1*W4At1Rf_PQB&L%)(`iKdo(Z{hS7aD6A_+tFQM_FxKDPa|d)dy?;<^*kHE-QVR$Z zd(V;3SPkDKLJO+~S>MR||B>}M8ziBipolAC9vZL}robVK9WJmL%a@J4`JEqI)mr$h z-Ta~SU!yI~f3h2O6LJQtYJL4LD{Ici{oZ}(Vy2ymY}%KW%u8|0w(oQ4jyUcbse^iT z`TDdFY**Uv{2)8H$g^D)_1np+c~(TQLf1WM_@SHH*I5+BHta#);Bk+yuW-$8(T%{^ zFTU35ktoMULv>Uvo{=oa-+qO{!5Axbg^#namnp1eYx?G<7ZC!K>>0m0i@v^Z^)+yv zAjz6Ds?bovIK>tFQUz7Kfn?)jJ&ry(p4}qe7#W$?crM_b`9J2QM@;-|pyw9rF}i18 z61)GM^Azhhll}B?x0e5G0JP^A<`!iAuTXJ$SyLr-o!8BNz;AdBXF2RBgDf?|4!=B& z+s~yKT)kg~=MDdPp99ylyOvHCnZ9_i{ZrTUdb$-{-}IEX=9_(G*m4wkokmsY<8<@H zNfEWYvSR7t5`|Cuve~37h{n@tMCfTaMKEUkS(w*wNR&;l*x=Dvsix%w=5ca+xn|>i zSAZRmPHh81fcsxd()HctsCXyEmrpao^5^Jo;wOJx4P%e<4 zKb4>J&&u1NMC46=4{xP}Z}y#jX`-5-Mv1#U)3EFU<%Znls?TW6R4 zkCUw`@t20zAEgTC%aimykpJ8DmO=|ROg{QvMvpxOvS(v?x!yE)I6>K(?SW=d#skLX zpiO&PW*z^?^DComP_=KC7&7=EM9k4^`A_-jltH(s2Kwm~AY>Hbv{{Ug7w}r@8l=K zufaAtI46q+64Lf4(sRqlix32kpHo2S}%4d%1EtQwD5 z);6JixDZ_o3*B89+kl;J4u{SiP~R>#gJ0LyMvlFTL?{AFD|TR*oVt9d z9+^DL%$<6B-ErJ%bL=kXY-Eu^()uO!>cOeedic@wmdV4+_)mh~^mQv7yhUW6X(S5a zt$x`j(*NbBhiUgwae2K zWfUi=nOueRhnfYE3SFOmUp3L8lgECZrkex%iAKL9iSUl?W25G!+vUWzKo6?hz3aEj zH!i4w+8A5eE;%V7)+8Zb>~>Gv#gBi?AI^Cz+9R&gvo0pff$IP6mi=hRHL7e$MjTeY zG_&%(2Iv=*Fc%dKjN}Y#M3;{@j*6RiFx{Xc#S1pJEZAYv|M^g8n4E$iW!-YV``b(X zW2KYH=>0iEa1V`xaaQolcA>YIyRdR(;*V033ca_ZCQ)t3U!22g!`5K1N09GZ= zA)0{7YyA3_N3b&b=$RYuZQ&dUPVg$V;+hUBJzc7HK;|mL^4}rwAaqW&D?_5XKTVa_jd4qXFO>}~C>W3O`yzJ{P8!CuB&Y zp`(dggp;BK(HNu!s}@ol+O93UJ=dfXJ#M@5-x#h;^ak!{{wt*X<)ghzyS~uV`Yx=( zHGgK$t@KhJ%|RID)hzcR93RmbpS6A64$#HruOxK??^aJh@H0HX+2z}D51IQh zN)l9IxwtB&Fs@!>8bA^?Ev*fz?n?&Jr~=_C8K>pJpB=;!QQwy2gExYAFLrvI=b_Jp<{>WO&w?45|5a%4@e)Sd|f>iD6Z7g|${&_E^$K(0375-WskZ^J1g|I#QB z$2Oh?advKa+TS@zjXnCmvV&(xx}3Q?RIAtR$ipeCYu53p$0ko|lL~a%BM&DC27okj zT*03M@Bq?n%kBu0(e+kmt(&D00WPl@OKCk1-ghlB5cMu8X!0PL_x}t=LZqfZ`bEE= zodTZ9EH{%q8X~(~`8|8Ob$=)!sRK{nY7%PpgWvQ*PF!sN7{nAYnYYK1hAIV)J6Z%f ztY)?Fo!ZCN?epV^pML%PrD#PqQS+lF>4#a%H<>?==v^;}FReJzDKHjO3!7R#PBr3E zFri7B0v&Walaem*1{USIY07h#*GQlJ&IP7DFQDb*~->nIrLe)zTCT2F8d z`qR+a9Nebd=61lM`#C3RssH@4#8xW3wa`N53qn-sYKkLo+WV}}SMCWqqYJQV+;K#8 zgeZW_gsB8vZ#6EU@CRK*1&L1vuWKCfU~BoJY51Ks9-PpjLtJ}Lk5so7`OJGDku`IO(=LehLDjr=au`&9q#zh@N|4kcQ&-+QL zXYmZoQZ^{)JJq`P%5zV11B{Tm=O%waZp>ak5gEVlO1#8uwd|~{nPm6ML_>3esko(# z4v&=N1wHxpv8A5Kq+;Lh@}*-Z$U*#7{PxNJ(4r_S$D~c~1>*r| zjXV3*2Skcu+NuPEGHA$oz@W0WqRbSIR8xX5Tq;Fro(to*5qZ{v<7N)`j$u`w%^C>T z(jZeMG3s@$uPG2i&2$BaObIwFo!04QLD&;2W^d>KZZqxnbcw}e325+4%VvRcF^h&) z`DDwMRqm~i>r+Sa67j-zh9vp1_3FbDVkTP9iH&xCYEyr|-${zWJ@>4t+DiBIz%Wnt zmfs>Vhl4;;d`TVAE9v!l1KJNis#XuOJ*g`3QKf7o^DUKN_=vXH`7;4$jw3YFq&P3= z0|81pq(Mofn|7*1$!DGky&Q$^Jd4X$do=R#g>Yt6i7F2_$&TvG;y0MHS6bM)?R*Bu zrsPqZ20yA4nwq}YZ=|aeXW!m4>*)oZEPo*8Qe$v$or5gd+dKtPbl{>uclM1i9EeR+ zvM)~}*&J-EHN}4F{Bi;kDXdlD9jVd0l+q;b)zJGs-&NMBeV6oc(r+3=w*#klfr{2b zOA5e@tAeB}_#3I_D>llv1x|TWGIO%tfwAnT)0RE!SELNd!qal+!LkX#r7Fv8VvOY8 z7}Wh)rPC#(Tw|<(s-BUT$y<&i9e*e?hf?Rg!>|bnGUBWR7N^WY;&_%B=LNHqC*Dr) z?J+J6*&ECa{6I3-RW?o7YpXzUpi4F8_wf!?iobb0$u`>;9&!=g$=vH?JPZxA1AFA! zXlo8d>V|V*%GZAkV2FmxZ4ZhGXBlVWjhyw8Ub@7VSyV{#44UEhztzL?%`ktlo;XXe4fRfZG|H|WN|5qM2?{Zdbb7WjK zWbTf9Kp~)%u53Y@}VNUODrTmqNd=+%D{Wf!d}s+W47a9D>s2a z7;m}yN}@oUb33>UfOUbN7RA9vs}$d2m}M*#QQ(J^!y*~c>6*K4{qb~DjcV_Ivpehg1DI_Bs)mz zB=k0FO1`Zw8&=Vby|?LO-ao0mf}L3kpKvD)&dbSpR1elLbq&$jMZGgcu}webE=|a- z96>;*f}LMzDvH`p!5F*1#&K45c9wQ_b^{!u;=0L^mx!D(n<7(Qvkd|y1{|pMHj^{o ztvDuXIx%vuK6~fjbwIcJ*>A3z-?@?T3%wn!6HjIf1ssO4DBZ1uq|%}sta@Z!x*eaf zRq1OJO?gG>lsSWeJwnY5$E35G25u@?oasO8KQ)ASP`%Y$!a|n}-^ZO=n4kK3z04qs zWPY29hh*_7;OhVe*lU(yUy{KVTj-l!hZ6FyCI*GM6Y!xnOB(O3U2>W?j!6uPL>W4~ zou>Wt7dOY$w(sr6r!j~a>#eKW>9xg>XX1NBq(#r6+u(s>^Laa(a6UVYzG1Z26O;t2 zGhmc3@obMJHEWhOB*miFXbJIx!S-q4xeweFvBL(Q4X;+wjeVoJo)hDE26-31{TG$K zORfSIvKmjZV7wl*csvNM zynz~}p9Bwux@W9{3r;+u3%%WXThOFhcGo3a&SJL$V~vN;#MK#RS~X`cE%gKT8ZEeZ zZ76?!De2##pv$?cyl&sEy6C)klW;hz2T}tk<~o~s+Q=yI*N4?axN7*Sm;Td!oH4yn=7PIX2Zh7wphGM zatVnuo^ns)hnkuu^?po6jxzGRe>Uo9VjeXy>qx=Yl&za*%#mtoZB?aZWrtXuzq3yp zcU<51gCHRk$8Bh6Dl2Waqo_^j_?DAz44tCe%1RE4xH?vbt;gd#IX~EIGH8zei26EV z$2$zqd~kRn_hn4r=KUb3e`C$z9i<8n5qMc>Z<7i6LvR)!tKSY6Z+)}V;JK5BZ)<1F zPGro&>Rx7~Fz3Lj2IIY`l47*$_N^wDI?n$-*uq&vT~c}uQeS0ZzUnvPI{-B)3tG2@zx zySb4U&*B+5j2CBL!fTcx9?d^t@MJE(W^)235?2br0^;#)kM?phg$d}|kDwu+vkrci z$}SFfLn-p~AYQZiv7x_~!q($R>YpvjV}2Xg#uyp`c5>GmaCu|Zak(f;n}~wybFq6&orz=?>0+gOOO!SyA+!7zu zeRr%w6)pzKM8cV40KDA&eBQ&xI^ToIXnXb>OkGX|U?+++8dxq6ij>#b=wwbMtxYsj za0+T4b(5wN_k_JvVj_pgYqM*rBO+BdhdFm$fWhY#T%b59W2n4CSMinWNB>606U1ZC zo+K@6WvBJ;Z7xCmt2_JHNSB%SZmkVD1!UkU{;+wTQjeS4;Q2v}iL_l90$m#}u5p*?GID8)J2lZZ#Q&(xn{|KZSq>1zi0H+Ez01~pk$cDK9!e7wG+ z%S3N31!w-+-Zu@S^y~RIXHjZ_-LpRc`^jC&FETK zHm1FvK5x*GGzDLy3%CiwroM8bM$vPkn+|Q<;s;=@kKtJZbhymVpyw+c2dxI}hT)W{ z;IP7&CAWSy^gt_oEnTzZy`oxPS_Splg8i3PGr8Et1KeVfKvJ{qSRPU<4rDp!Ff62e zKI}z|Tff2Z^8Z>WkJ4U%*LwIEOb_JWV1 z`B@%sxGBMOcm?``DnKT002MkFJ@*CEi$GRECyP?}Dmx1>9U7>x(=@HA##&{Cw;!0+ zaxn5(gM+UY2wciWsIXAP0gPRWStyAi``-LmHfmS+Fj4v z3mP5@b#&(~EPI}r^alr=ZR9fz4VK99_PQe6Y}P@1O6u-ToO5M5V0}jLHfW@nZ3z*>!W7wRw&F9(}h*-CrQc z5ZvR)KVZ(I*c%)WMZuP{1sJiESNg`MS+UH4n!?~ouMxmUM#qS=@;VTg2q!ZCK=Qls z&QJ3qKCD$WE0Dh~U-0r5j(ON-(V@73hsyXEOzQ_Fi$XFBnYqPAiy;?7$~Vds#5R^Z zKcax^?4QbSAVa81YwKLzCfY)(bF5aG$D9@5eBlsQm1R09jFH(vRd*!239PDc#GhJU z+7X8Bd0h4ifOHVA} zn-@w@fSY;U)+bl4Ip`R&y+xdpHUXCvdicTo4wA3HRyIPl2_YMd6nY(&^9@o{jg=2) zY}u*(Oj32Mwvx<2E>x`#A`^}oXEgn4gg(Zi89PB%H8wSk7O91v(6e5%foE=@@xs{D zB3XiF^bJ=@#b!PBSW$dc+G?0$&o2S39uyVL#DTY$K2L!;@Ei1Tf6s0}1ly`}1q$Xk z`QeN0*(n-q{gWfMBB~-}_}#y+aH4CbGiNJ)iow>d^Qe5wmMPh0i1fhe z&^=bbCr%5UOnsmDr2k^J{l^t+k1lBgnPZ`^9Y(i z24pOaYBG(Q-~CZDqBhyC-?VFaYt)~0UAg`&!*A> zD;Xa4hP)#AUex!-W-l9&6BWNkp2Ge}7b;~wgGjy9elsDmBmi9X z*qR$~ESa=t`^?2HC07aOy;oaHpHe<^0@Sm~ePNuiiLHIOx*xI*63TEGesEx4HU5j& zijPgdpbY4J*)DLfSZW@D;I?$L+v?NCTT7u_sWmhoA~8Y!@*+O%0g#3vPf(q9My@eO zua7+>dSnPp-@!K)M7A5XRy9-qW)j6pB*lIG0seVz!y{L_l>nvf>x22s5~LdySQtwS zHnNF#)n=%#tz(lnTdU+G{mLM3HmKHK(Te)5(V$RG$Y+CYBtcqQ+JmOtP2f1c$wjz^ zKTseAGWd3Qf$C6NVj?1oa@?-zu@#f2SKb4+8dIs|$AZG>>Ou(EAKp7*0h8BNM$4Ig zk#XGZFpd3faUHjRCa!W48^A#^P&QLz`bpP+8^KRlBkAAx3}d2%&dQP^e?z! z#eVBY4rQ!xVVj~Pxj+9IM2q4qeEBOF+w?Nk1?TA(B065zMGj36eh}o&U~G=iQU$k0 z`s;+16IGUl=~{oad8*WBvDi)gGd$<3|C_cw8m@JvfO z56rmnN&U@8`bt;22X@6Qy6Kc#CCECM`FHf|shq?o&=(fE6Tv~~{T`@xSbStrgzE#w zT)nALTNzTBl>kDi_X^@_%3W}e`}0$3If6CpWA%(4ergZO0HJ+7n$WiFgu5uh3+DJl zC&SpQ@@)iy{-6QIUtSce6FTFpxH>tkA;Rpxh&nhIeS5)tTR&F~LT-RJk9@y!$*AN} zI5|lVlQRajB*juOzA`k{O6IO{DK&n3Ezj!a+_4^7^pR;L{Gxo|64^pPN`}Wi*%hwq zVP_lbU%KOYrWas`HzKR27-Kofi)^7QE|Qm-OhJ`tauLCRU+4NMnLB4_adKK1^7!yd z$kE`%)m0RUhl5N{t(5X$t=LA9 zu!a`|xxN(DR^&*tO~+~Fo4$+B#$itH9g;ewB)$}VhW+N3 zC9FbHSRsRwTzs%b-7Fz-eQc`E}DHI|cCluWiv ztS8(4Qlg-L9LKP8QLkHJXA9OpHn0If$HQ%qvU$+xSvxUPg4!;r+kh?ZGp%3xb1`L7 z4=b78N?b~>5mxY|;+05kOjtCvrd0#NDKuh>MVMUXSc)Yo^3FUYDc~9Q(w)pB|lXSd=F=o11D@(NolKi-c6n-3i7^s z$SO0GYws~CdIra;I3{7nZ0|9k+2Mh4rxF|0B+P`@+^mL3h{<5q7qb(~>36L&uNiy& zB!`I;I4dvRL`|h>-%-t2(JrifdRqS6;+@4Oc3`>f74k-nbNT8|+E8(04ujVpgs{>Z zi8B~EUG?gHZ9+F~`;!af@~{~;XAKwppupcbsaLI*!p%*Awoc|io{8%%}ot>j6Z zuuMwdvBj%!Q-b!8^7_oWOfJ&i&TAz3SJ&!_hgF~LI>@DlgJij`z@!K^SfJIPVf=i` zdfzRhxm{@AA*K82Exr&Ym|{QN`|7PVFsrG}O}Q~^xWlOS1v6w-bB(2NFSChAdZViy zeCm!F$-#{JVe8=fB)!$DE3xMM^mU=KE#F0aQ|D*q`4Gv&rtVkbmsHn5MG8`^D%#SG zFJ*3jqNLY#JVv-)0c^HEr`Uhppb6LY`&!+r3GIt@yAC?ziQh9{G*!eBIE|V7B$K@7 zl*)@{(}r&MK4&tGN$TWi_#$!D6+aW@&A4-IHG(ug^bgD4V4m|#lZ)vka^4MpRXqjk zLSw#4+cX7XSR~e2BQRuI`U0=g&iwluk@EPcL4AAqc-At*{@bO-Loe7F7@z7s@#>cj zJ(mAN^Qj6BDTUwEuT$Dy(7kn-H%A|~%tW(&uXS+R^r(Tf*3@V@+0Y=nH2;!DOf(;& z=ldAKrsJHf_pHTO(BWxO_d>(JDuUV&Ph4`Cgj@ejn&zD-KEAm2JEKHJqo4I2nNitW zUjZ}zis=;zqD0+W2{v<4JpGy`7EKvkw1h~8WRtve5V3X%ibJ^qukI;5Q6&@@3ub&; zW=5#zu=*_4w?>dMU_3&a%j?9J#66h`6nTv)u=qK&ZZwtBnKzDRVwW^wu{NQanMDA2 zH><=|Dm-KoD2>O89{TIP;{%wr%rpJb`|x5glf4sI8`Pc0>C*sh~S?fcSgxaUX4KkJp%M~ARXUD^RWm#FqTfkio zvtOxcLzV48n|)|}B+%6@q}=wPuAr>`f+M#4`NX_=nu@hNX;X)}x$sg)s| zI!;qZXGPO@QWPfcfl8($z{=hIMcx{vQ;(G#WdOJybnbY3_U4l1ADpZ$%t9lpV{9zR z%|7d%3Ua^eQ0G;L-1B3#ZyGCB)Nf)B2C#>_e9=>tymxPKxmoo9PF`egBJ1g8a8Sl) z;Hv@g%3fyZ=zsns=y`u;)=}v-5<99WGm3&3YFPs?LlBPYV{BhBIOix(rkaCY{?W*M z9m_$-k1@*~eR0BF-Ao_Wk|<0)aO>Lv6TFOPc&!97AT4@8y&qF`K;p%1K(44%t^#A@ zTl6B_1aB&4+71nDGR-T=cJVXV2zq6dz2G#iq~+dVwnfvz7$0wELDuD#`|!pp#?Cm! z=&)ZcZU%Pm5T<%QwVCllI^4y9l->zYYDn%~Y;Hr{zvbvP$`zVndp$SFKCfTTAm6@= zoSyD-8pcs$^zLzjKn_P9*Urct(CdwNb+i}@idR;9>LglLYVOAr4 zFoaglqqv#KxVFBXFH>JVua;u)oqaXt8l)XeJ7MEVK&;ylb1yKo6eR zDd_{xo<^cX*=ZIFk(sRYjFfY-P8t+djR&i#`VbD2-Z4wcL#N^*i2{bjABFs4{|p?W z(-@nr&|9>S?_4XvPEb}Rb~#P7kpDC>z3~*Ts>$PKKx^s<_QYh$j(-sC@N5)uGLjp%FN$A zV0?A(_J_`|dbmo#&UI4y6C9w&<^FFQ@JU$88pS(+oqjpmW~c zfs4*C2o!t|EFc)Vq`Lg($N?H*6{CH~LTV<5>#sS!QBue1TdY*-z{Tq4wb~je&IePpSt5CZNi9B=R(gGZJsb$Gj7=>oo-c|&=D^GEk7^9z>FV* zfFPSEH93XFy@m|Hi1z_7#1=?v&Ei(&2fmkno54u&g)h+smUG` zatUNyP1Ox2vpjY&u=~#IC}242iS&p} za5Ng=X3wqs_?#1PQzr?lp9m!lm2)%)dq@$pRXNilZJ;E@~GI9qur^;=W#g}YBL$3_pNT>;}I z1pZDmXPRuv>Y4F!cVBGCrSrNYHCnQJIb3^87mOzM+UJhY(xdwu;0AKzJ9NP{RrEsm zzJ%}TQ%`I9=`Y&7efm1#Vd2Nu36lo18$wtzX3DUx=yy=zG?ETYWiP=DC;vFd#6fm{ zVM>Qup>I!Aw#Eg9ub+eXe-&PIzJEpBN#RvHy*MiBLFF6EH}1fRm0=eQJeL?M71&F- z8xHuNZRf#tvNdm&6Yw-o^grWK7F1{kM* zDZo<1Q=|)~>*X43z0o&a`}iX%prrH_!S|}wvaABC-+L4X+F0^>_UBQv@l8Pu849bp%D zSX&|R8ur~~t*cL1_%KYP{jSmA`mXBmL7=HVbNHQPLCd#6&Zd4%15Ya5Dx}X1TV$H7 z(=}CG{stifg*j6X#pz|anEjc4cSLuQ+OxF_WqAvHPR)1QH|_4#D5UIT%}J`|YuEwh z=;hNASYhkuZMFP%0*)->@3m%8;yybOc(HHC#Zk5U#HtnS?PwdF`SEXFx$>zO zV-2@je`vJG5Z`8fCvnxp>`3#;INo{}+HZ1iDWV!Cz~zrXs~UpNTfiRyCFjLzqxELf zXUe3W0zNdEvLCgfkL5_WwB43H4J@uiz|@r+BXENY-n1uRR_(PeFOF*Df%Gn<97# zZ`F9ZH+-30AynRfT!az$rEun_6g7O&a1#IKpv{uadU0bY9Q*rXvO`A-YYaAIkQ)>Uy0g%=M#7 zwWUffp!S`Et8?{SymdDYav{$$n`I)Sor8nh zVNT}2!TgGkvcVFk4(f1%>!jbfwh7-M4K=zdD7U~Fxi8V&GL2BOX1#yP^2l*{6`dJ(&-Oqnmyi6&)qB$;<)aj7Aijh68(0pu}e#F}?GnxE%>m=R54iCK4u&!RH zEM)IjiWu}kFT+Q4eG@G902-2&eMMZF^6}qwjt8i#0uPM)?88T*k8It(a4`#}b=2Uw zKj?*7Y7>|kVz0@WTGYpV^i6Z@P4tyt=zOJ-1S&+Z;%KX9@TUavpk@@3Ca~QJEM3m? z`LAIwzlHn){|45v>SGt&r505+;%T0S&AQ^yI%dxI# z16BG=R36K!%hK{_ewZQ9Y=1l;4=yj$>tZR09%dJ1Wg?L_|j;7(bZhehoq_+5SG18d{>h)-$shHd-s_?BJ!NgGCq8(gOh zAd#v##%A(~EZCqg&XbL2oJqY4QAtv%Sz>p&ZW0AlC16ymq zLkz(lv>$YnqEMZ51~;XI2Gu)6^kEFV%`QvCP_o@w6c&?Dw{!3)9je7DkM(j|)oTy- z5*s7X{vFgmiu8GBvCI|_r={e`5{TbRuW;--wUwz?78B*dGidgOU008Y)Q4s`!NDBw z3reiV*(QM*I@{)<7fD_#!Zt;(&e&~K7q2lLD-wt8(Oq2Zjf2dSvMus{Ey5(8)7dgH zy1M^R<2dW&#NvdQ`N0iY3i+I-eG`;++N@9|*1zGr3*Trc$J44eE$Qe-5I;+cTH zPzfVnJ~og^;Nq2zi+#+Vnf9BghO|vSCB)uz`wUGvrZ_;J-uX@Xj|e|0@#av)Wr=oe zr)eFS{>w?%^yA(<9~k=A<|VV66jsi; zOxIMiy|rbh9*Tjf5kcm(;$nd6+U>0S3tD;gc<#buM7!?mP6{;EE<@1<@*`Y#r+jBl zVO7AyJ>edO@P*Eu%d-BTj*A!}nEks(8u!I!m(%(Atr8E4@w+5itA|~sYF}~$@%u$z zy%3s7SJvGzV(n&#vLHlrpdb<>+#HX3dT;o-&~+B)7!`{Tsp@LJ@lbFhz_HCY}xX3FrZQP1H)N7&a+Cs!jItUCbgV?i8Wk{EzOymS=6HYv1^Oe9wUJs zf@ws2y=_g=qd0Al;C}M5bZ2&S=3}Fz!^YNfCANXq^=npV6cc=i(#PqmcaeXlJcSaq zli8K)5cJm0Zj>C>9*%P`o!LAeZ(KM%6+o3tSEzH0GO$yOp3iN@+P-cc6Fc#Q$q*iTU$M)v7k!E7JACHLV%uLG6Uk5 zU253ebFP&5ucp6DUkB4&_)`~F=0kyLqKR7n(O(-=u zS8FI>PC*nZAFbX6)Iy=Q2gxC%BWz2HgToub&h}@I?vq0GtZP5DOAgBvtk!yfX8h)v zgP;}A^kPdN43fvHU@6@@5>Sh%jLXbeER2#VzbvOdq~&N@OK0~wG!H#vuaVx)p7!F# z;me4uC+9K(1*Nzsof}i|=1SW&;|W*~>uJ-7U`*iB3YYXIeS62>w9PAW$ z<6$r0Y$o+=C#SO2@uNZ3zjtKqE5`dmmKIJ&4Z2+Jr*AK}ahE+D66E^WsU9+ScDQ_M z%<~cFieC@Cz9Eb97^YZ%B$X(c=+M5bnN71}l}~n)8tBaf{Gg9SLzX#8^>ugHP5ru4 z;DaQ-TO?fRH>8ScFgQqr=`r=q1+TKYWWRdO;j{mn#^mqI(GHV&?JL|aNbj^!Ztb(9 zs`^_nb*mQl3Tc0(FMY$8$;Y4DPt1Em8as>v!^e;3{+5+zBJg|PC~Vi3Ch}8F_(d{; zMq}<91?3o((@9~*=f-t!MlTShJW|RkT72QW38N_Clm%b`hEln(T6*u)DS@mBbjwh2 zk~HZiPBJI*uHr z)PsHAM4DW#Zdz=>jiw&#tA|Z*Tk$L{3=`e`wRNBNNm8`WSXXDOQCllI4~@G2ywVlz zTKI9P|9c*+z5z1BC&do4!1|VKf7-IRGB4?9pediuh6}p7g>vCM*m3$RsprmyuugJb z2jw;^A5I%I>}gcvMj5}3 zGxY0xUUzm+Pf9g5jMg+fwUtf1P+nvWoeSQ(cqeXsHKS!YxyMyu+twl7=9P2M#;Brx zJ>{$N!ovXEx!qo7rc z+0mCpJea0V*hH^l1i>@blf|7u)c!D~2&4O`dSO}Rn3^D3KkmHM*8WeL2^ua3#VRFJ z%B9&9&qv)NIX-gDn)dnIV&(XqB@(8c<=UOXU=M;%e{NFlKO3GMI{4@X(OpXZefscU z9IZXz!aAe9-sAT8l>JubQABx)QP|ICgr+;p%d9UUOod<27o(XXXfly?oF+p(%~Izb zaj#0Z&@)fTq`j6#S?-dIOhSuFLV%QElA>g9620|dn}RDT$61R??IwZeoe_@ncHVd! zidmQmc>!w{vaYMkb-CT$8m!yY&H2w|@Alo7jGHzQkP^RLEShGUqwoe|{k~73I6bq>@$MUi5_EL!=FPcQ}b*R1d|J>9WYX|s{ z!aCh&Z>9Mgelx@%f^Urr1op=d-G~f3cXV2*&0kw%bwag*W_iWij`-oUgw9=R`?`y6 zwI1VrcL5b5RlCZXR*9^N5YO^u!Jeg0vFl1s512R4y80WVp0@` z8rKBD*cjI-7lH7T7|3CfRlvDuU*u#Ne{JQxik7A3;z!~YhK$bGXglsjiiADWdB)4w znWy+P*SCbwB8z-7Y}rXmz6`rMorEn~wYx z0T3(RZA=hwo{nr1t8~*FpCS!Xi>P~3YL3RR@HAHU0U+_| zmwEKK!pDM_H`$R;B|J5nL6bGePK}cJ9-) zJ=a0!eXGDPHta-cSuZ8yG(awS_UoR+=jJzaj2WIv%&iaAc|!g4=CRmTY_-wmq|wm? z?1x14EW$Tb?7N6dk*;BEzG{1Z>z_X)f>5zvaa;d<>zcFq>j%VMgvSV4{R?v1a2Hoz zE>K!ZIvwMm|?9h^MM=HUP`a@2^Uf{xF5VUbqi3}i6b6T71Wla9eE3gmEs89_3E)c*zykj zHP-*l<-SF7e{$^4wR7{I3P`g(q|VzJv87Y_ERYf4z`NIu>)LdHKwW=1+66pOh4`&n zh*a?`BkAz`T17~yUY0dl^Ida5o|*I|Ly6}-fiNG;H84jI6mrMxxDIukh{$8l$v^c( z_7yGJ($4U5+u&AU#(LwJo9TunUNx=+auzvkWWfoJVU$1Sn;(czSNUSHuJktLxQ*rY zQW67*j=pO339{WC0mM~ur!?&e8TE5k3&zS$ z`L~$4lr$-i)m4aS@52b5KX*wbzjq6xtzF~0i)#cH=Q@goOd6^(JKa+S9 zbgkpNL;io*ddsLdfG}AUclY2B9D=(`aM$4OKEUAa?(QC(;O+_THnr13~;UtR0F$f2uwW z*gd()!7))fu@&c|)K{XTrFVoe@;M7>J)Ama7{Vph$;aX~i>9m0V;tvqgV;tteU?yE zXbWPv%K^!?K+ey8C$4~psRbjXj%sVM$Sy6BeEkScJ(fSMGdBNPtLfz3DX`Q}{tGQ; znjOX3?5MToXu5aIQDwZhwk{P`P?tuK#I=Sr?^fquw102qw`Cgv!>-l(!Z+n~!@NrDOMP}(8@G4J@;PpNCkZQ}n7QAUPKlbaZRxPjdv6#?8eG2Ix)Tbt-oEskxLCv^=sbJr zeX|#>A`M)0(1tE9Usgq4%672Rw)i-C)f>;s;vMpskm`#WlW%?7oNiHS>#qthm0FxxgJZz~Ur=%n3tsbV#k+k_ck1~B!lxQ6 z!%b-@tByIqqJU}hQc60S#CJ8_w!#TVFyoDsh6v4<*8UKZ%Gg0@yu~M;Mq?xEo_T%y zNP8_Ya(;T{$o;q!;dp8bkl-Y}*7p|d^^!_1wRRnF<2NJL%UF9{RYqVI7xq8udJMP$ z3BI2M9IT}gvj-N7)&GRVLM8l%dxogozJF6qI{g3A;^&86@t&4P#`meI?VGwMyetJz z_ZNEg55zgs;9P`xo5Al2D!S^moV`S99l^fMd#_g4V`{DBBe1niykxsD}4 ziod*U<1<|%QOvt)FhDpr(P{@T&{;;PWZu-|jS&@>_DxyIHCbE>yRGb`hAO1mVBuGRMq=>lPktY7ui08*`1Di}ndOpo&afD94VlSb|3dsAkyb z8H4DAV)Y6wqG4V~-|c9d1w4FuJ=9TJCj@Tw53xiRiGoi2E}#GzZ-+}U0X?Ts1wNgN zhN}lc%TBJbca6*r*2AsCjs+q!J`|XuI_K!9>1i822|00o?r=c(<5fucJYap!y8VU??3 z+Q=l~fslIneC|Gv-XB=am4CKGE?bLUDI9@DE_6nG*Gj^@Sq-%7ex80YdC1b&%$cQQ zv1jOLq+4Hfg?6iu#SGUk9&9m=Uz_`HUVXM+uLIx+MCS@Y|G6Xo$Nu~OA+BCU`lRh~A|_x);5mUVH&oIyC;$*@^d}Pn zZyMKd$JhnE%~{3v4_|>9sa9U9RL;#S#K`R_KV_9elRL!gA1ek3!e-2RaU z7gIaqK4>vy^=Fr9zLCayi|zApv);_GlxdEIZVq>5WfhXaPv7dQs#-gf=0=;`SetE? z%V{7{GiSNt0d;79651TqXOa*5u{U8H@<2s{UJ1ekqZx9xH&w2xN<~f`FU-Kn*yZ^4 z*iA|&Efq+vX}mxdX7c;`nhm0@&9y?Xm@f1hNmJ94mw-b|vrN&#%3g>LJag@L6$_a{ zS@xSgVOF;(8$Xh&oRcwD0rJWWLEJ~H?M>&UKk3*P;0KFJfCUxWz>H#IXTnu*PE#)* zs5=7EQt?TMIZCsgZ|gBFcz}}3Bb2J2@5S@GsBQ_W_+lsY^KSF#1x_>VTxix^V#AXmhUjA~K?JW!y z+kDY~i0F%vU2A3-aMJmw^%_N6n3aX1B#~3($$oTCQ>c#r4TPwg^rSr7L{x;cedcn+?une@8sy> z%u3^NVB38Eku>yf&fS#0dj{lVegv4;;k27+LbfW}BLC|`DmG|$1z5R9zZs)J z#RvsCaFgEW`yARdhWX*?KUpx0CYjFh5%$~nUR^-s?tKJ|sn$sVE&cK6;c4`N%-nlh zpY=gy`i1Q3pB2`_z1O868sXy7e<;ZR1FtgRQ^WxOYml$@8(&xodj>w!jC{V5aH#@U z^)VjUPJ39xaa!j(*Cl;5G1+k^LL1)$f2Wf<{>(JhmSUP;W-E|fOgom(oosJZ>Do1^ z!6m;|piAO`OXZazkJLjTQh{gzUwnnU1frG`NiqFE#v~+&J5w9FkPzidg&p*&n@gv< z-OwUA0);b4LYQ2k*YchF7HC;#)i%5cF($Xaf)3ZAcpQrs)D9PLRZyVwyYGhsGVg3mF_kM zV$dSC3gqn*mjzpq42mp3QLy3S=d}s#Y=_VMT74s&X|-e&*+pOY1+uLBqB_|q^A-$e zJy3BA`eH+qr`kzTL}eX)^CCp|WyCn+8y;?q8rS&Zsy}%ExO+ZmaeDMSf)9HUtpbB2(Un)9@9YGkVs;~yk z=9@LnI3>n^C&zGglp;^TMeokA2S!vx1uXcj1R%W8pkr@Y<$-X|5XTAqrLzr z1^##zRzrwKL(A-Nu|kow+4a#POQ=c>lMzp}pbu^t8YKw9$?>xX$=O0Qp7B5Sf|jNE zCm5L-r^ZgdM3k^u2$uC|=k%F?j&iqhOO*0myqpKu12C^jIBDsy#wU(iz_yV6);M27 z3#%BUK3+dm9x;olCjL*t{11WnjKo=)e^oE?q4)0gBs6a< zTZtT+{QU@Bc9^du;w$^i!5W{{pP$^1Lg%+wHQSQzLg=77h=p=y?7YI<@5Zr~#pqd` z(hjG@kT^Ht`n{G6e|sU=fF!Zg?f%r>uxV8cVX48CEULOi43e54$VSOchwP?d`o+%Z z$xfw2uuQ14E{1umB{9j07rPz8qUJ)v*F2#hXH+_va2Ja!)2NVyN+jnyp+hTddQLQG z-Hc#S8RW$28D?iowFNp_iKGgSwDzb)T$68bEGwV4 zKl+gXZ4o7P#?)WJ3 zS*t@Xf)JxoR>WWCRe`IW*+dH+7Ah!hW=2bnpB|fTc!@MzqV|(A2BQBM=oUbhM69(D z-aNi*ZGIfTgkCT=d-=Cf&mA;a)?JdD6%~hUzoFQUSm4(MI9+tD=2!wib-g}oQrkCM#gz*g%j91z3#)3Qdb%p_H?1;Y2^TfoYiAS&mAveCG z$vrPlYJuKc7p}e4jWse0IHztNUg<5Y_R!1jw(4AW*}gLp%O`)Q%Vs7tr%z7#B1)pd zB#SxX#IGK2I1DwYt5e{+pG4l_-!B5{AJ_JhIc1#<5^6>fh9E`&wjR~{R}mkWZ%*%c zcgOTGPq_F2cVv%OBO?8JD3wQW=b-;}bOuhciR?!h-Ld`;7JROquV+krSud8o3w7#y zy?k1p3XmqH-JcHL%aV9jyLuc$+$x&+>HE9m8ASs-3ztYtYOYkH8r)lVv|JZR(~=-& zyw*v;O=F#TfS&ox5vmU&lgmA#YakNz(L68E3U0|c0ToU25{{O%l+#7uH+iM3SsO@O z=Cm!tE(XdVB+geZ3?T|`|9OBWrjL>a2u)#ax9noUlhtQaTtX8(t4W)vQ`(fwNkP*K zqs3o$r5^B6t zkv??%U%f{tMOV!jcO*#Np52Qs093D~D-9@m-rp5a9`uWT8IDXnH@76i&NzRtK_caITzD$<;>?ZZmy7&j|AS^YAW=V75&`AM60f0@Q0FYG~VSjQe8Ix%M+ zE83huY=)9BBYgO@7d})UkRtMt^N|(PClL7Y@;ILef|D_R+dCIpv9$m@eShn{CR{M61raowM z=V_I-B4g;k?yBb<=EhCa|4R;Ym8kjwG>F+GZ-JGBfCJs?ik6;nnxi)BL~QSB_lV)d z_Sb|AM&0JhQFR?10!w~Aa0_JKt8X*}eG}eVgr83>tNp32X<@)P3b)xjS116lCv9v% zpCrE5&a6rRi6Kqlc-z|El}G6KBmR0$j$+fu;jxsdrmGUsv3juZ1{nQmy3rjJGC2E& z{6p2;FGT9Fh|wnF?w{hA8XG(8E#{?)4Q@5yY(Sm=4X0W{N2REiOtriJSaIK(^L-0!Er2!2pzF zt5$nAH6xUNAnsOoA#{S>Mb}y{sgCaWVbk~W8-KXaRysAAPy~VQhS&-DmJ3Z=?}wuh zNW4b<<*th6Og4F^BYEl17l<+2rFbI*F`SW4e*C+W$Rxk+?WDv>=_&c%OMZnIY%toa z%``jg?CQF}zd+mp_nF#aPIqO_KvpVOj~_0%FJ8)@`I>ffGSav6FYkf(<4UjM33oc- z1KTSf+<_*WjU|mKj?m2ZXfeJn@&cdlcVwh0_(qeW>_2(FZUo+!{@i;P>;LPd90=Vz z^U!x{g7QDa;4x3(!rvUrifHY<2 zDnJsZWjus2{v`#XaL!GYvH^OM_*`{LTB*f;*{ImG+tqr!jUFkh&2qSqs!uBj=$Bhn zwKlk2TT%&!Sd6C4bGx^UF@g>SH6tMxL5G$k-dY*bdkm2KN&DzM(y*~qeo|dyXQW+d z1^Q_d4Muj%$k4FR32CT;Lx3tvxDK!>($2yk{WX}0wH;H)z$emWd{02@{sMt82m})$qAURjaU#B0}zF z{XONk^>T$ki=?x0NHvC~>6zP?sh&+OW=`wF>0s;43EmQf^eIYOMcaO;o-w$Qtj7eP zi+8SjSdEd`bS_6M1iYTjpkbbV88IZSY2R}nx`ptdE2>iohNYU<*v*Pz!TC)QJ0>1K4q>7aHo4RIc8h@O49tH zQ`>0{<4pj+XuMS5j2#V?7=dYX5R=#=Bspt-LPddxWI8)v<`UPUaV1LQD9>Sw_H>e( zS}JusxEKl_412CET@oqCqJrS2qmoKpttp;mB?D?|i53*QhzK1_WH}VoQ4T9gBppXr ziHE)L$0&@>T_M1L8v)XXPH>Wn>Fik#y`HZ1hO!xberHKRYG$lK*1<&<@@~15HHSrB z|HBwqUAt++Ui-~jw0kcvf1i-KZ14$;S+*TwyjDhcx9}c03hzsa$l>xG!pA|MaV&+R znjon918*&ZF*jx=Gq3N@pOUsQP!w-^ zf^*q=XH4^?Os-WASn%;N{Vyw34s5+}g}@Cj@Qj4ZC5MnVa2d`7M^ZJIZ6DZhRmJ2$ ztd`Sy++J(uwRSQ(o`A zoI*|3=NWyK@8S=cuMO~IFIV7F#bFcLKsCKzK4J^E{)-Vudw%K34vX@`O1?Nro;X6k zI~O~_V2@Y#VQ$%`!DhcS^;^5$eNn17K65+*{Q}JHp+bU*Hz(ZA)B{=J1TB-3tJWBn z!J~d&J>4R)NVDrDEE0?M3sYj303f5m+vA_MM%W*!G4ggj8m~6HVou2|iQFFL{ZX>V!z_a-g|-xyglge|6PO z`Q_W}-1HgAuOq_=pPYMr3Og+=mX>WM4BNukU;Vvs(vAM{h!k{j(kHQ=&->q+u~n_3 zW~t-rMAu#Sc+r$Ju~Ov)4OU2OA!b?u8+U-?T4jl!1j#ld(3T}}6_8j`z>nC!zS*pB zzj;$)A^ua|seUOBEPWGQRsrLy z%J`*6)YrWGyC=~5U3?#nuk^du5-7itLHkskV=J9v7PUCT*0bC~8Tjk{oA-=wsQZyO zY!MgGL<%*UyrBJ?Mjmay=a3ATBgBD_%)c{AeOK3V6nt+x5Rj>wlA5c4u6aq#=wiB4 z@%6NCmF6h<*Jq+_pmO18FlO&18)1Sd(P!*0^L%hG*gT7!|NgA)AIQ~sr17jH(9!16 zUpfk+{8=$|8R+a$uxjQ()76*OYIB`h)oz#zCas|h=rDiZgRNt0AI2c+3uDqEm1G`u zUC+>yz;dvM{5Q;19wxffmt(;vZ`iF*8Fa=c7=Wl2kt>+JYBnnzL0ghPbj+`(K-A3D ze;op_Bk{blh7(OLMUX&_FD4|8`bI~4YUW~qPa#f>8OSkAlJS{q8;q)|>c^Q>qJmez z>|a2q)PKO7AR4f3q0;-(ShnkZ4JFdNGmXw=ILk}U{q>`^tK^~PE}*Y^(?I@ZzNLqu zXSr^2x(#$@LPSyPgXlXHlR=HHY=LYRsttd9tFRX*u)Zuifr3f?dzefYT?4Hu>h2>+ zAT0x;=OCr8Y z?UE5Y#%}-Hgzn$9AO2kDzDk;!xdnMaL0*lfNmShr`)mMXI~o#vM!Z$5*GPb1vF91R zJm>TQErD5u#uAh_JvF}$Yp?g%-M`2QFc081wT8l@IMvz zGncLRZR+ZX)85A`CXbDrc065ma0<9Bk&H%vN?5{|e`padp6`f=Wy`LFO>UJ__|DXX zJW^Wbrx;0&meH{KSi#%=lqVE6up1Yij>30cfOToCsv| zHUK3y0)058?0lsD5E9yy@$e~IF=dD1v)FIaQ^2rH7s+s?%!LlYV@GRnM1%c7sw5hY zhn0wFBfw66NTMA&9cn>O=TF-La-kKve~Nw*xw{{h!r7or5r7v~l;=`bQH2zwD5R}L zy-QGhy#@*HBvUbW_R9)fHb>O&)>b)%HL-tKZjUFFu`rN6^QjPOy^k~`3AzjuexZwB z>FX3ecv;@)i1{H=;%E5PIrm&YwAFxM5U2~;bun-~dazgQp?wzOiJCHpulvE6dIIFD zZ9)Ibby4Ua73ZYb$wv;S2}s?l-*rrk0ZXTidLbr&mfdU+5;9k6C2^~ z7e_#_VnW!h@BTlKMuqU*npPgpaMJxFFMamK_iTM=kK`c3*=JO|!c~zBG)E`jNn9I@ z4I21p%ionB5FsqjZGpcS8UMQ%z;?v=sKRH+y&iqWsIO+WyM4z?c+FZ1As4@3R{>oN z$uVrG#y=lAlhw3An+<4jCTy!VM?ymC0`!||vMMlXK0KPqzdk+=E%DeIfuV>P++`Qs z-@769dZAy^yBxF~FagLn%4L#Fu7QCD8DqBznPj;t#3GbE{sSXUz8N0EA207wWdGo+ z|3lFK?xOtsL;`pk&xR6f#ENC-_4B&bf0^khj;}LW!!*JgpTwPSlow5kzPn#~QLGmZ?aT5-rYx{ufwYyG5ORN>Ke82f^HA_rdB!6h{sVP{>;kry$^nnyO6cksc_cY8ZX z&?rqGd$kiy2&ii)oi?g7ZuLl#5e~Qk20eKDuK}m5UT6e}&SD#aW`?aS-B2@Qw@^tR zD$%HXiV9~L4SV$|!i;+ZXJ%l)*P*f4;<27XAkWRVbwzAjIohW4NGweib0uxa0@|Quyq{mOI@@lmNk#|@ zx!2{TDa%SZNh>|X54;2gb6Ibwizc1j(5hCqtZeZz2eo+@sk?~!+h~`{wCn%0P4~OC zP)18}az);7QX^2J4JQ75PG&{9)-TXzXyl|u`8sbdYba6JJvtCrGtvMV)Z4G$CSkA7 zdw78+I75q_d~N+*lOYvcG#;!Vvr#1qN|c*)f(-fLVHMls*{l}natjNk5E9y&Yk8*~ zYhCai=(@iA@ODq`JG1Rv-zr+6t}JV(s7Am4noV>9pcWdo83SigAwkguV&*(-nzP$V zFF}-a%qx%#%*|1x@E+ph|1kd?`pKg^z$`V*JRYB>A5XQ>qvT?9bhhv9jlp-noFwqc zVoQNB>&}W>q~xM9XeS++9|Z|qU#=V$U)nYVUnt;jemqWo`6uvS=hV~BiLUv>N9q57 z_& zkShOOQ_~0u%iw5+O)QwK{&L)0wG|=~4Z*fh75Q!QdFs9{cJ8c|%XeYzeZ69A5s(&z zYTOKmu(tA8TemQQXr|3{$b^4;zd->bS?qON37e&ggB3oYRnzu92VK6$YkP(tC&evf z+F7Gr*7nKa8UpdlXXZRtTYT?@a8gr0`#a-P)evkwsgR1J$nzEWTa=X8P8I7|uy2?o z(;!!oZf?@eTd0Uvd%OFMn=MO9W&9jFZ`)84e=qZ42|3&^H(_nM=X|>eE}Ifw>y&T{ z8YgVD9~H$RY@|95`)-2<%t|GhDi^LU-5`vu{OF1x-N-0(sBYTiU-~h_-1+7KdT8GK zp=@Jx+S0S#CE6s6D89}jE?Oz*$e2);3t)}TBqqVkf=STR2k#MhSQ(be`OIkEvQ(2t zj}Xw)+a8;B6R1+{OUhz=4;4@O`2~CXj|YU==zQuBFV&1%G^M1RtSU~boR8-fx9k%Zqj%Y8X|j>=yK zf8T4YXoV}?BnUIN90&#GJK`~w%Ij?*&D&x&3tSMpdpPLr41Nx@gL?i63qh98{n$R(X?f3kP4Cu@eX87e->dK8m}5< zIM0%m|A%D%AA{siu?{}<5%_ozbHUvcCIa~0F)KUu4S-%niW2z>uCQO9LZuUE+m&(J zY-RVQ_48>%N6;a(T`WTG)X2-;`p$*}>#DesXi4xv511sPi>Nd+^Je9{HAL`T*cghJ z5Z~j_gnKAJqy@z0pBHSi%lCDZaKh*`i&{{JzSP!MibgNva>h%4SN*>8;$WL^*?pd~ z*7xUh*~OdW8=ib_2=z4GPj20o&fZQNlJAPYn#08MAgqw1TA66$Tq~mDxX*QIldJ`$ zw1`;6-1@_0xw=2@-~hNfYSRrcS_9&qTk7hMaId zPpH>y#=D6a!KHB0VBTS4nIDL>=<(|gYrF2xZbJ3I{!lK#s#AVxC_QxfH0nWmUhiYd z)7*IRz#}0F0|t$g`1=i*Ape8g>dS{^`!?5J)U?j? zm*@4z-UHLs4W(wWCrcBI{)wjOg$3rwrn7joZ*Hz#@x_i1y-ghI5`Pqb=2%a0xjmn2 zvixJqnP}}e>~(-$=3BTTU0AIk4Zvq^{$)0T+p=kOYfvM??}upPp>3OBae^6&Ij|on zof6BSx1+|+#$(sMxV3U$!pbbh+Jcr(MS)<3^zAwf4plM>8{SN+h^nxdiQQCrugkcK z+AE9gUV;JALY2JiH-XvN2j_HQw;uJeW9=C;u<)3X+z2|eHA|Xo!*RbI?Ge+9m$I5c z-@-)YSGE(Cz@kM|xesBhyIKKyiCuiGjBXk( zrF=UksU!ybOfBOHN}HiiC604cFJd6F}6l$s>>(efK*vY)XU6p)Rq!9-_Y8NE0P4q~AuZe%OAP>@n&mib%M~^I^-gUg~P+!?E z7E&{fTl5>O8p0W&i@s$FqAD>*juN5(b5Y)HCkyUcy`+)7Q9Po9=q(qpM{q<)U+rAy zQWC0;->K^%kn&~hQ16;3YynhPvaHkG^VaHPT~aQGnh)bp*oRny)Z|VUMM#Wjk{Ear zJAe*brVH?Qv?H1NI7p^k`hA^QlEU^$`~My*R@dW~#WY`514}HQJaP1#o8`X5k<60H zdfVm6me3d&@XXqxPXi6Q*WQ+ZB$}F6DY)O*qAEkwD33u~3Y8#OM$_||75MCXF{;*Oo}F?? z5ma(p5j*Fd&UIi^P1X1iaC{3WNzX$**DHn$;2}R=KO|+mSOQ7S|AHg_!fJ|&9E$0n z+l5C?vHV&5*s%s(6{@o>0wq={h~?V9zn^M$;*3M&<|1ooEfoasNf!`G%K(El0vKz= z1qebyb5vfDNG4fKN>PYgi+>t$$#{qjWEeh))Qm3B@nB<4Jg6nJS>3NoYu7H9eCzJ| zQPXUWZw@Etd$==~=Xdd6=fpEy@A<9s$A1%-V@s59Ill6X3NX-^;p++U{*C~{W( zUlJKVj_VRLo1&cy5)xfAPF_)kIRnNj{ZrIZed|OhZhwTvU`A|z!B+Z4jwPPBr2#WS zL9PwZ>5}iSsH)pu_w+<*TYv zT2DLTvrsKe6(^EN!cV0+I!SPR+SgNeltRlt+Vv)dZ~7vRP`-dDrmigW>ewD?NDYFi zkn7>5b3se@s59C!uT807;hGmRZT4x|)mROe+$2AWPbqX?ma89_+cRPwRhyzCb#)V@R8~ZeZ(Z`J)ph2y0VUAVLge=8v*vpi3Vo{gxfKhX z`rF?QQwVx-R_V@n~RwFS0=^e6>Ix z7vQ0**$>;T9`vnE*>L=>^PD^H(u>|l=C?P#7sdJ|H!juhYXTJWG<(cc`C;?tz$o-> zUtS7%*U<6Nd6bzXnIG7^ur}GwtS%5@`L(R=#4|JqCh7yYX^I($Wgr#7NP>KO-xfb1IFAAQM=(PD?y3Q2Dv6vdeL7wA+KYqve6a1{RDzybCouHWD zBXMmj`k8Qnp5adCi+d4)Z}g&e%@|bTSIT5>$q%H&F1~K<02EX@TYZ_eFws0z9OcDODg3rK5 z;(r4D8R`EvfhYV2Tk1qz5`+D_7J2we>rUFY@FTM!e-|m?$aj)2SgmaZP<{l01z(+_8+p*QB zDtBT76{_etYf}>GO8;-pFjrS|%?3Q#3Xq@e$V==ECuhwg>^&wpBeAxgYrw%~43sND z{25n0V|=XU_}nTbJ&-S9Ap>J+U=>p>#|X%?SAMGTln;T=&#Z@qLLA0DH~*~m(yVaQ z)%O9X>=Y*j_&i)yqp}87$UcKfS@%+XrVMGJQ=C>Cv-c!yLEEFP>D}@orm~D7Za1|X zWZvN`qf=)f9p{Me8k>2c43ZyxH{4bl>T-VB2+t7QQP-=Q)oRa#psV^ni7>@?`w7*2t4a3EUIyd9$XHgN6L9tlsiKj zJKc8wt2fOQ0&Cq#8vIKsMGDGV^!b-9mudJn=?aEhUuyUR?0$#L)Y;*G51U7- zb<5kDwr7PINs9f6X9=4{WhZ~l$WTtjJ1;ztxm(53PX4y$@Yi}V`uBWOfnRlqD^dH#=hN{W zVc_*A{yyU$Yr(_g&uE(U9`D|c^Euk7x<@X67?Vd7fncewgi7}OQuWi8lugII9yQ^N zF9Jw7DD?A_7 z287=<7hcS?cBx3-1LSGh2B9&l&j>6s)1_d0!>JV7Nk_41lnal?<*h#}a6kB2G3(*WcI6!Uc=Vax+Q~Bd?DI?@2p(_1AYczkkXO zOf>GzMvUJf5J$+9+>~#*wZe@hM`-@}1AfTr^Njqs!unM7k^dPtNIU(%#tpc*-k*G| z|E{0>Y$Ln5J6-3Ur>>Cdz7pOw^ADX1ugKOGg>m@3p+7^XPDb16gt&c*Z{OXuiOBxN zVY`k8xTCWi)Gf;g?ibjC_}JMo1rYuj3=n1v=IvZ~5C_eFxzO6{UnVv#NjWK(vk z;d)=)vEFmLwk9g&@VEVG>(xo!zx2ycwU0yats>y@TjZi_9*94R`(ED1VVz&vT@^W= zQmja;+gC>*K0P?&D0t3#!!QO7vWe8$4TOt3qS}K#V2#5;xO!hrMWLe+JB(JMI%%5~ z*w3H9J-^i8I)zkoQlg4a$z?p|2C31GxZY}F?27*5&d)J`hhvF1>$j56bF1C79qn|z z98ranKm36AhbFwOSAOkMGc?950@G-^OI~a3i{C@j7g6XRD`|z{Q{iWNW9-}#zy zg-;9$+LK4dmYs7bIBpV&k3Z9@9qInDi> z(Ue6Q>tXPj z`;i6Ml-ueS zS;>S|&DIMVI|A!mB!JkZWVi4|l;|IP<^P|z>npD$Wp)v^Duj1rpU}pwX`U19E~yJf z0|x1a8g4UrdI611wPy*43DgMMRTJE^z46L6M6v8ppa)htP#x^LsoE5;bHX)0TA=<` z;>4$Cl4dbx+EB>kkcV6H4Tk|L^{o&nAW*3EbQ&C6k`R7tO9{kYCA zERRqgm3-}Zdo<4CzEghPYMc;9g8)lIr)2^aGnjb5v*f(9NkCW;Ufki^rDFgPc>)JH zvUMj`h~_Mi4bJ5NTT<^W)3TFTIBfe|SP^O{owq>llH&Nk14>`=32mat99Ix)LVa|ZNU&r(-(4(_wb78jV z3dHpYwS5^trRT+N(;sl~9T zX=jb2F2Y@gR~IL2#dTt3X<_2?4UWZ!&mdhr8BOR?X>>C7kJTBSZ-=>^;Q=b)X(Fbj z>QzG#zj9M#GgjQxrY#sL&9p5MpGw-;tO{I&{RRhIoUz}E?Ea77%RhnAZGZIP%f7uB z_{ToMozc8K?BWE*ExIieOap+Wa0!zc4oE3w6IuMN$CUn29Cirw821}|FFq_cV7AFq?cBQc8|`cfo+J%BD z=)?geM8$pII_GcoqO|VkY<>A$OYZ65du+d58P^1mgAGPG0WN1rzLmgNaK02n8@294 zopt7{|AQze=kV-3F#r`E*^yIF7xgW<+mY2SSo?H)+vPa&07)D3vIRZ1m2wozet{xz z?w?kI=xT4rXQ95R{#=p>ab5;valWl=$0wdYSb91H_+@y^_hRr7o5h(=224bSg_(K{K?U#H`g} z4ITKR{ep~+Wvh^**gw>_tF4WhJ51WYCUUw;__%s_ohx|fOTwuMg;#==jK>JZMO(++ z?yf#kV67qTQFOV+xy+1(Rf{7>-^|7f951;xAGBw8*mn7`gxnp|{Gm$OGrK|zUxRCbW~oyf8pNm zFzebn5U{C#me@I$GU#{NKC2LZAo|t7qU5OErQ^M$kiC8M)ZmzigArjzzQnV3$iEsy zoebQ}uGK4tO!G6_Ado`!^8SI`pbDy8wS?A)uC>VXu{L8`U+1)4i>ckdJCgDq8r^YyEr!%i;O?p6moi)kv$?62KV4-Kp-mASfJvQ?uxU) zX6?e?rkABDt}c5@&rwUu!^zbe%gdhSHLw7e-SlK^Y~)``5NRKQ*=#y(#rSNH@1+nQ5Hvb1t%7Y#n#7=ey2F3x%bU9wX#745TSZPaP3xnTjx zWrQlt?~E^U#2MgQOgVbtzP^NP#fjYSl8+sy2ke$f1r^(8H>7*K5&qXAqrV(1-)66T zQo?-whnUwS)a}wsLm^edH=BS!%H*@MQbJKO7rVm>W5>tAQmw}U zPBEm1srv6Mz*IL5@yOJ43EOefh`)2fukA4upJC(8$f(%Dm$Y-+LnjUq@IFjg%`~?$6+JebbLp+nHgHd+23Bv(xFC zp+4cB6AUxcN*n@Km@d=HlVPC#dyWT?YBpDG6{4htaIvZ8ocI#mR3oGoz2-Idm_=!E za^qa|Zp(bi1)w9FZ% z7kHs!zP|@v3DYCk`b$L%2EF2!&q|KiY1~K>OSm0$>J!u{0r(c<2jPWtr*{il%dM#n z>kkvykE?orF9V=Lj44$19sbP0)IxD5XDII>)Cx>EeA&rKQIPR$T-dUbINwj}h^zu~ zg%!6Rm`3v4ImEjIi1FS2#EhHwk({e|>)AN#!y6#NYKIOD1n85ys!5pGmj+M#gwp0Pg6X*Qcm?J&@22b8==(3N7*@ z8sgI=J^e%%*h*3gmww_md-BB*2`7;<|5U$HCjB?s2I2Rakr_NNF9TMoW8wY^9^VK( z@I>a)8?6=ua}l7NEdKh~f%qttq{;>&qLI|FEUAe$y@WY#(26IC`Ex+5p}K3qu^G#Cz3;ay&z zzrE$RkGrai0}Tf6v?WWi)l5FeqkZe0t6+}eI_*4<1ojfQ!TaNSY=@m)^~y!Y`07;h z0x;5$E5wCQy&(NoOUI_#G|hnNh*Sz09Vrb_>*;276%pz2{^^UZoze{Z&}%g)+Zrz7 zA^h*fm(km61zMUW$p_-{l*!_)lhd?(L5HKF^Nl(zzwADirtV~JAI}E=)pP@v&jtqu zE7!-oucIS)cL!{*$8%~w4sZGBJgz5eD+Bm*=5C3$a5Z<&GMw<&NiSQ|>8q;=)+X4e zQuBI(*?m6>@DbLuw+oG zs{gZ{$Jze3=aB=ihF!~rR)xb?m06CgHSsQT(XWh^kWx8DBa~XDFWgJl!doMURxHR* zy*nT@`Gg?A&phKtF^nUv>Ht#v@>Q2#D?Fo`6r9Z7RUuFoQyh2M>TpR>35M2;5T4C0GJed-3tE(Z2} zPx7EJ;3#st_s>gMc((&&oL?;~W3K=dpXl)=&%X-&Y?hkc#DEd|&t)PXTp%oks@`cu zBE0=VipVze_(fYjo3Ms$<4m~x*7>PmZQ)3GH(vb^mR~U+)XJC>^IbP((vl9RXD-o4 zAmJLC%;FmW2O#*8?)t)x{MAZLA=^|TJ#igCOgvJ=L-7Al^%Y!kM$48Y5Zs+$L4pPg z!7aGEOQXR(c%#7`g1busH13|pf;Qf`yF=qT%zAU@<^F+ht#iIQCA)Uj{!Dgx?&I%$ zZc4v4LkR>wy=;U8y-JL!ra`; zsx49mq3p{UYeO;7t9aeGiJ*{ z7pb7al%~YWvB0#`S%wX(7AkANi(~f*SvecKk586@}01R>Z9B zY547)zGF^#`@z{Gw;f`hk(=Rzp3x-1QR7ZC++BQ(RSoysIFB31oxFd03uY@>+imnd zj@wHVZWQ3RCTm$0dvR$U@wLExW625WsHBca%#bNewh+!{TNoCRv)-wjH*H}&(NWne zc9W<4AJfdASOMRzk;yS^{KvxC*zItJlmpBvYe+q zENM$mgO5H^6(W*!U{t${HW4`|$p9es0DM+yav^RkjBiSR|hn5f?o@+R|Z>BZcf#KaYmwC-bMDTm+5yD1F9#mF;1XEJeCTA~3c z3h7ft7EPks$?k)-cs(;hNuQ2-oeK{_fP=6@pECksU}%$)^E~}j((I#H3|c{M%&?nD zHS+KNs#sN#N^iXMFXn<2n>I)gH`ytC=oP#5(5E4=MW6G?tRsx@TT?l0`b}* zUX~F7o-=dc(92EenJ21>7bY{erG4VF=MX?6cCyQJog4V6R z6p)4ro}~)aU|!#Ndb^Hf@;L5ax4MEyU|fpoM-#SwyX94$cSl@3^jPWX!K#+wk@TLo z=$26~M-)P(-Y+PIU(6qG+b-h_?F1>o%Tf~5|KmJGv4aJM=z`83>|l*kck}eEzbnj87LAh!$?R1VYf&b7OZLWF1f}7A4gfl3#o}zg*jW#-h!DfBP>?Cr2U)4 zGm6N%giKSSi5H=?{CJ$GjJ zs7kYS$BrkuB&yG5rO*^n*bV2`T*tae{TXeUYrSa$i+>}7CSgz?qvf@}?Y=AGa7WYd z3J!Cu6AA=Ih`3R^{H~LfRZy@ok6ldwGmY?=9i5q_f%v{WFk!GOdr2)#<6ZEOpD65X zv0d@gFUsR?WzM+4`u4nTecq=M<=qJfx?oSla!9zErweL_&iVtu=ll9}odhf#CaaKy zaJx>WbQ|wft?zg`!{~~o|Byu?3Tv3Maf=Cw&T6c(lezl0>@C`|aJ%}h@PHX0~T&|vX<$mEN~k!LhH8xbGO!`2ZQMzXb0_K_3~G%6TV zJ@3sdhZ`7{i|v2Ki9R2UYWp7AG#OKJS+ObUsY0JI)2O-HJc{i@=PwgYlp?Npa94Ea z-O5NzkRw5-sbdxn+V<#t#Jzz*oalFn6LI@gb8N@ib0J>duDy3`V@`n7jt(I~h?&fg zqsT+(_&J|4y4f)#Zk75Frb0=cYeeWY~f(uKh6w8)PZ+O`IzR+c-cg_`?=2?{&BN(%S` zyrS-c&h>&WKFO(a>ebefsv)NXz)HX1(f4ncX%r_vDi_eLcHU+f(%fjk(ke#5%I5s0 z&)KA$Xg~jsa2e8b;+MF@Xsw0Dk8yQSeNEx%o5=Vu5N!PY>!Re9@oQ_hk4j zxon+;LLhnjXTNt+|K%?V-}RKZ1}iQ>sZYV$JNEl|G{49Fj*6_12dtCxiy20^P1zAo zT=-2n^8n2}!TRzEr2tJdC`fy?{mu4yUNNQ7+gv}rb7~u$2Eh)MP6c%|-H*82CK$WC%dSDB3AX#9Z=%SO3UhNs^Kmvq8F0mhsS*9W*^lF~B14^iGv_aJVgrQOeM66#tM|KmUXv3{f-kORO`T*(db@ zdS~ARS}81dxF}f+CWuf`lGFfBossWoX$Ktn==W5Pi!PGSanxv8WF37Zd`HK}u)(Q; zEb_R0@}*r3Mg{*=larYGToKmUl3&i(702z5kyF)SLe0uYo<-SX7owX>}Mo45UZ!^C;-rdfjdbudh@8bp3OrALsOSM<{TcmLrl3W}Fp>{ZVoACOG?JTs6Gh}X zNaR<;^5b%^`s&65g)t`t&P)%CyZr?{VHD`ST-}JFfC%hh@@({PrndEvLCX_(S0ugmKA}DIv(-Y!JQGjbdp7UQvn|`@MgEM?HqhOa< zhq7!!6aW$7Tf21C0#a6j-2esy+txG#<4qzE8)2k-6{4t4Z7lm6j)~(Psh5&7vlOVC zz;ec}DxQA&oYU!9H7jm*ZUH3Lc6)a~8o~QP|Hkbz;5f#0?do=h7p&J~m*ZtQ|Dl_N zJar{a)8bCYQ#jX5XndLc==O`Z#g8M!X<<|@>5N)~zNuGSQ{1OR%h?~$W{C;Yh^rx9(0Mco(i_|qnvG(w0!TEIr zh#lRjzUOuJAgeGDZ>7^uv2=>+$n|z?Eg+XP_4iDX3D&A2$3)ijgzNi>Lokfy9^yB6 zxgsuw6t_p&mDDal$?=a_`E0d2{#kFFAi#gdP z0{NV{T}Gf8lW@>89Hh%frlovx z5o7;&c2l8&ycS z+?f-G1Q8c6<=(v&*i-KpKX;{iJmNPYOJoZDT(CUUZgiNk1Np3@e6u~!>m&WM(D0CQ zWAae}(Bg;_#d>r0cF&c+_|MXfpm8KLoh8CO>RN!I`$ogQqgdT4neJ1y(pxpiyyJMO>fNs#NPNVsoP1MK?l= z-U3Ja9KLOjy$koI;o-t1Sg#&pnD~jWd-&>=Yy!e3SFtdN$o%g1AtTJn5ZJ)*RbZaO z9gL~R-1%}xq38#pe8Q>f^y+C6@gLLeJbBZ7Lvg-86_WR}XwU|dv%_J>r0z3G8#R%N z#+E6F&DQ%~@w##Xu-SJ(4%yVr3K@3+5JmN6uvV6tm)`t;mlaqYc&Twt z{`Br+k*Kq}kIL4GV+9_gN{4M`wb=)h1yR0M6`#bV{VjnNJTZMy2Bkjn&3U%TT3 zlhk%yuJl+_5m2mZ%JOxCI|R0XaX|Y0oqeLbm3sQ|1&+Pl)`6Qr<33u7hrPwGrLDg6 z$8FAQ3c#l?5W5_b_x7W#Epj$B%uUl?yBFgbDNwul67?DMQNhsXC&hA*3vsvd**cpcYeww{vq%KzO+uBJ~Z8?AwZ}C^l|rGLkO9 z;ft2nUR$qAxOdQJe8cNw=jZ#6gFTe%$`Gwt=a(~V+x5LG+pH-KOQ40nEz;9K_2CfLW@@bkpQ(on=MVF@+ zrsnX`W|P}kkwPj)Blijj4{cXR6^=8TBe7jkK27(KiREA&Z1&#NVtdZbP<5wR;b2vd zQ-Z6Wemq;mfa`YDqz2HTfJ!Gn;)`=jUANhddYi_cZ zcuKyxIYeJuu}|zAOGo4poL-JFc2BTK-U*cqiGRlP%?g*H{eRGX;0GUehgR3K%j2q^ zuO_)(=so0PSInOs5%%c41)r9&n2U*|GVhvL*F^(rQhs_3NBE*}N)MS+??Xw&cv$|<+DQ_t;c~z^e==c5+{T^9Ho?aj-NE?V-r8^jxxbp z_>J0>bP=FLH40@O4gqc>e|E`h$|isCmZ zhH9GY729q5cT+nk^$yG24^^j{=JSnqa23a_AoVh2c%DC#%fMgzSX3~I0?j3B{TuI2 zti=5+hrCpY48JDuW0L%QS~iL+O-kN?&$mdDmRaE(XQ} z)rv%kcnpy#Mi=Mx(&#vrpE1Y2;9(Fs4)x9GKV6T=&l6w`eIMKznptF8BtWIlNd&&> z5136?NouCBWb5pEt~4^D`ELGnaO3TBzQrNpB>>*{&dMP(31W5OF(!j(UyBHem^uM_ zhnKyJ9J^9pBRS(gksMhJ?PjcN;3@lIHNrR|N}( z=#(`U)TIWMm~_l2dVhQX2EZH^y<_z(UHm>w_*=ITCsWI->yv>8Q0bWRaIx}?%|DR z#H?KhEQ{K7_nO5RYG>n{DWrdI`k2B+)6w=KJKCO9N{VUk6_*GYk_CDV7PCN zlw!RaT>jQTP5k>f&^$7)E3^YYw7X#Pu8}~5U3vZ=DlDq==g=a@Llx09)F*7JhQgrusJ`0jR+0KNfL@QCiIt`r3fKws8>m{-ut1PHs61`P! zTbN_QpSd=y*R0pS>|5w_mv5}tQFr|Uxo#vht3B;?yPHWh+P(|se!##C6Zg9eI^Be` z9B@n{mT8awt?Qe3ZRpdN6GQS2Fh=3uSexbK@n3FV&+{9F^LWRA9d5omdfi%9&n1p; zT~A^jd%;|W=#bv<7Q%*X?_qAI#iK>^saMhO{8MyffehK($c~;jNJwGk1*hDz>1~Pg zz^JW;aGp~>wh_hd1}fQ%%B7P_w$yl`75<;zlIUfX_UCifi*@(9>fXgG<`WTRd-eIF zjh&UYSdI0?Ji%<5)}@RH_NPttLUN)W@zCF;Xlw-p6{s}L3?FobPxwQ0^q)%!S9x+Y zIdGsDbd=$c$4|EUUY%UT1LfJUgES4`O+Si7wSIXy3xa{0qSq}8w7PjLCK-f(oCH?Y zH@mA9pqMf2=sR_F1^3!#=2a8FiBdLJ7ldq1tiKs5YUdZGJ12Trs9r{^uKMKcSo-uK zSRn3S(D&8TL^_oA?5E;woMe5#s=7S;BMyuc@7_qS&LYU7MLFj+xd!%6yslN9U}ci2 z>96G>n_T8lXmjM_<;`0?HDc6^BOl4M&B*TZ+2#SolJ-WWt{U2O-T8FLXmIhSSXSVG z6}Tia!9kXTiB`#BKlQljCT}~IYRpATma3@NDvsp!my=b1nO4^>6Cim{F@jNT;n6G2 z`;L|314l_N7gB(F!>R88%iZnewntPJB!OJI273HSf-2dIKo?@E|H@3K}rDM4Jyqn24%D;MKF zLx1)-R)uc;(!09lUkgWb{zzV5zp*GHHe!q}>iw9su{d_7jkBrv4nM3L?33j-Y2r}x zzm>!BV=OM}T>MQRm*%>cCmmKuQ&G8)vdER8Tg?oh$U7lb4z{v;yDRRAQdRlG(}n2U zk^z;%rOEG8nWZFJ4ge!o=ftKct@(w87KY*9AwRA&*k>IsDR3P)K0hzp>y%%hFwEai!#wXU+(yx? zmhF!i!xMv%dW4lS&dLkb)g0Gb>{{XB5}c?)4<|TWM7~Y#C!YAXmbkC8QvYugG|-8@ zC6e69%6-qhH7h$t#uaR!$nMDXv`kTX#j8zUWG$Cal9e0n1-s`OsDqA7GV-g;{Xw|e z%X&}_6+H2ctaCg^gO6EQYI38BoJ=qFUL8(F6<60p^%R*JJI%E;eyJT5*M{*P;&CY8ihfBKR>IYOb%TJ$Cs1i^)q_3=*r;$6e2rfpbb=vxj#^uKs_Ca(yW6$@=$6 zEGj&o4!EQ(9m9{JLyUsN7)PI;%_t5aY0WfhL`Cf9YOtRlf1_3+V}b9(h=YVOZ}~_{p*3M5I$H_P;s$`%C-Wad%l7c`^xC%U4&w zNjc$m-=5|>T&`W^3A@IqyNmv!SeHK1pVv@wc;&_ahzaO|9GwMguv|=hT1+^k`0DQV z2e--N%74h;PU_g+X+NHBaOikomyJ!+k&J#$iteJ%tuoB5d}l#5`8WyyCH=&c&be55 zpMXDwEZ!7hulTDmA!@JH?m&O0j?QsPjpV|z=aM-_W{z(?<$G9PIbbp}DeK7+;9*YO zWctV#rN|inYY5IqRdl7u;$ck70`6Dj?JBFnk64RQP2Cl7=%%HSui{Y!Q4d@JL&4@Z ze`d1F)?3ty$>?Rtztf-Ceo~`|B~*uTlGJ!S;&zFwJ)WIk56~~6NYLW`f2R|S*l`Z` zF4|w9|LRMZ*R3~6b`I=uao5M?@}o0ZA$1t7tcsk8T2Mm@QV;!+2j+w?ngB-~OmM=r zTwP-H(TLL?#Hp@WXg$1O+lXiw7G6IXwRyl|AP~EF!t&*P_7wR&Xpvj>idIjSlShT? z<~2?`q%Hf|dw{u6BS0HknR?S{!mEOh?(k>V(iQK!%J~$_Ox3CiaPk*(nij!|K0^rW z2ZGD1%X~olg?jOGb@ua;vzTu(SamOwU zB10EH;lAVEcIBp5RBts22wLCTV@W*s0%egZ+MbdOIG+jS?so=fKFs}>fiNAF0P9vN<=>cw=j3H_GGvS_gbzIJz1iGCgymNF;P#0qXbkV%88eYTr!6`H-WUCvRN ziNJqa+1a|*FBDFqPe7LB2@%6*XrHy|%3RHCY_#4;jdiU)zqAq@z};X5nl72o_;>T zAYl$mC&l%8vz$%d?hpqH?cP#4%#j58$gT0dlCvJyyccuG*D*i*6RbXHjLRjqzk5+6 z+Gfnb6z)-flMmhAzSXZze^W8Fe^GstlszU4Wb4B)2=v0rZf%~mw5$%Q0&CSs+s4eI z7JrdDT)1{a{Nn^&w8DQ(yTItEqM7NK-w|UD-;`7;vxU(Cv7pT)8TRD*!^s#`soTI| zK3MX${e5-ImD{c`4=39KdqUWrTswqn53sk@G-Ecv-FeCzmc!bYpJ2edaG7)YX#5bW z*T1ONuAebpGpB_rZrj@tCF4gZ1BlCgdaWG|i|N+w(7*W?7FkC&Afg3#O7FF_hpXr8 z-UC#_1af~OL>Wl_$s}rCrm)QQ?R?_HbrAZuuJedItX96B4rqxyO9=Smkh_^^Mt9Dq z>L`~*dwGeudhQ<}pwcW5nZucviMe0uy(g%9>GMAE*WD2JClFo<PrhNy27f!@R~u z@8YvI!OxR2gzbfDx2N*ds!EO1b{vPwzZ}jadM@}Kww338^E;RTZwo#5%9K?GaDzkD z7K-S^s;*JU8Ro5w1jagW-^)<+!C$#s;fb%poJO6gZIN8ZT{5pxq?U9_SM1) z=7|rYPJ&WZ1x-$LL|7a1BF+iLzqcUv?v%Eu4$tXYxl|BSq>oEDC|fv!$1+993*T?( z2G}L~zTXv$3GWydz?u)Gs^ug*ekD)SDMm!39B6B1x}qIM@0H+fn@92uoPK!un^N$V z%Xb7|u{-h3BCE;Cy`9YAs8;*PcZaL>r@__PqTt&Moac>a0#ck{{eBj5t?PDh1xQY` z7r1gj{=GFvzNnEsf(N1CzA;7F%s2C^20^UW>`(0?dA8|R$L%N{#|ZwQj?1gy{oC=f zcFBgP*=PXwOVN7oNf3{yB{o+_olga*Rs6~EzMNP`gNKX34sWZ4@&Y3RvK z);HuVOCOu;v4YLX12XdWg_UsbfLmq7>`~>>H6LTrriqMU)G8QPf4}=@MAVG8B6_qg)Uv*uAM)eCj z+^%wuH>c~B?R0eSkdykiAj#Cxg9t>>I<+ncP%w3l5|r{Xq_+GFKE9Mm#79ITeKl~z z|1$8gA9q<>BWqbmmjdwh-(?e%ve#K_WZ82SJ#qb0;VIV21G+Kf;YaGAMlR3a<>FmQ z5Zf*%$wM1$j0az(UM)}^lYR zXwK&evV_t4G#T2ZZoEC14=FB)ByPU)1?72vxlboQXA-KF0sQXwCTQiK9C*0&B;#G)cohMH8+xGkx!1Uv8U4<|{je#g}* zEL~sRE7(-ip^2tSanMik88$&^x#p^cx>TJm2rZk3?UWPheLwvRB_i{Q*TGA(1{sIt zH$_#!QwaIUl;KT!5n<)#hFwn$Rt=m#Fo(olnX1@ZJRmhwRzC1Ik^d=i@|Itmq4T;v zIjnmjXKwa}@*{jp4A@{(c5W=U|i5;rts!MBCgXk8-trh}z_ zY=lzRI;4&6B_VQ0$5wW#zT#zV4Q^nf*Leg##=TahrLif9bmpaT{2aaCQsG2MXFk-a z>EEoVdCFj#n16}f=>p5rvvPR-j6!MP%|LuvQcmW_sOz)zIUHKlfeBs{LfERCP#}Bv z1f~*6>(2ei#?Oq(dEk}%k@;qU=KQ3sSt8X79s6sDU(zAmIU%ps`cU?0Kn`#$gf4__ zeDBa(u}#(}vFVzbYXz^5BbIM&hQ9PFFiM7n=a8UOs%+MZ!%0^w>4fJEI)`sCH zZ%4kFz|sOvwzpww`*UxO%s?yK%Vt0OKB1CUQ0mun^*Tp$A(|<;FA>^huq$CCN`=q# z8U<^)S#a8wD*K=~GOxS;-xAXY?wQy>8c*qeF|qvq0b2{bHL|;4@!V7Y3sSP96|?H8 z0lneu;F?@w)x4T8~ zqcFmQc4=uK@E<207+<8`4e=pD>K$iFfF z>f&{d0SjMk>Q%R##LZ--J)>6s1pq;naJZ z$}6_u1=P%K=ek#F?7+Z)ZRXxPzw}h(VwKq8vp+PhbAKXemZ+BunxX{Cy+@gf+3Ogk z2c&7+;@CW*!631JIWvE~K6^$}nK#uT4dEhEA&OT}mz;$2#yW!_cSq4vQ|fe^91~x_ zif==`;ej{e7B(X~*&LLy#_>)B%oU)=CgJHUC+C9{Xb}l;cjzv6R)y=?lt&Ze!(3ir)tN9Q^Ksna##iJL48c6m$YRGiiFOy+q4;quU&6R zRk~X^I^+rG;0#6H%u$k$*0SH8)C6y99fi~$dN#d} zDCaAbRLnv3rQ{g8rshP>7vq3zcymCP_^YqmBVWde)XF92_fDNvx#N|>mA!biz3MLN zP+Or_ZbgSZ_i}TxnM2X7PDNFevAm(g-PmZB!2$U$9_|WF`ALm^Sj8dn!pYc~r`g`U z;r1U00#&B>UxwMPo21>sOQ0hJEoQJB5kMHIHf3Zb%TN|NsE$hBq^u<)l$$tpwXX6& zT+z@wyKx=%i`HW9)Y9Hcvf#@mEnv&MHh!xsS*_Vp8ZKJtBcOjE;NSNEN0tUT-;D2B zqau`F3v2hg%g9E8-&sa+CR=|H<{!DhW~^gpO`lHcDzsKmSeoqx+THnsB($&X?!q_Z z>~Y)Qn+Dj5PtyJdk;YV}#36r(B&438Hj?tDgxc#j8ER@I6p#Cl8jusz6fvgNPgl1t zf2_(vTLRp*7+JD)DTH^Fe5m(}GiRd?_>-68-*Yg!;teI=Ii~^2h1mbhG-XLAE@Bc- zu<>HmS2D%rIK&{L9&~g6<>vMfTBcIJbT~sK!Y?#G=P~g9(JVbJRm-m%lwJc=_x9K7e3>u>o$cyV?O;2tFC#rILH~Y{5ic zl!~JZa10KFZ%vZ&$ySz8Mgv`Lofoq|E!iHwpG2QFuQOn3++1vNI?<~OX~o5`=&;v$ zdEt8j9kZN+GX7}Qx7Ch%=tSgU-mIN%xs%x{n^OmxXF6|O3`cuFGM{lfI5v!08BoKR6Ppzg6A%_;67&zTXNfmH; z%|s3`u57*I%B`XFZ1(&5-qK{Ze$)8JoL-6S5HA*=rMEz{sxNh<7OJ;j|4+aZPmGht zzo8C0Ap1GKEQ*r&x+85@+pM`0FQm3qmxuk_x0{uKgh zt9Em7xw9Z{in2m%U6~ z@~bc8<3@IV2-2M4KCpQ-WR>v^FnMYLG=M(O3KTo3v)R32i-~aa{VpDJhac5P9HeMk z(QxT4R6i@x|5*{Ej%zZ&1sHvdDdUbcOBU>;{qLchUuSm4xCElS4*Zac@nZ}5g!wH_ zpDCnB$)q`nG52mB1j&T^Xu8$WaHzN#Q6;|&f=52u7?v;UwS8mg!j{kPm=Bk(26#51q_&z@En@;a3iP7qO!V zF+TO~lzjsD;UDLMtl1tdz63h?u6(htZI=i^s#il@g$)6hmx5+pIrA$B9US=kZ-h+! zW3WFik^GB$A$$-dnREm4&i1$oc0TQp+)$E>t;RRw=!`3E=S~oa$6bAfj~--M;fON$ z62j}cAMaQ!bf`94EHLbr6H&07H>yNviWbAh6TFeNSrz}=(mRu~(HYl#nf`}ZD=ZTF0Rlc@U zo8z$ansTA<3xZ)~58A!?-tUt;6;_Ig^!dl472>c~vdF3K`)c&W|exE@jsHC|Du&FBucSoVO| zK;gPMj4bT}{5|gQo08$11cnmK(Xoe?osNHsCI7lR799B876VwJlUFq{AU8nG#(Rb# z_83(5!2{hpYJ6YXzagD&m%h2j(#8Gnl&E*IDJoCd1R0XS@9Vbs>bE2%qCPAeID|_L zv&tWrGr?;-xOaR0Ss)9C+qa8^w}P-eoID8stYK(4qaFG?rigo8Td>LLitF;e?=^Ts z8)=sO{{6ov_^DjRr@5=rq)0Iq+}SRkj&Z@k5&UMAB|2u~{12A(W`xv%9CVxnj3Kib z66SS&O_*%j1fdHGi>CGMhVP+$=DNhhF=LfW3ZI!X>aOTO_8moy=e{Paq+@4HCfKCE z-0DvB7dwrg^eY!DYfE@b_Aq9l?h~BmZ;tMrR45Ic+7MDs!cGF6vX?GAM!u%|820Uq zm(OZZ`i4Z(7(i*XT6Aiy(bX}2Tk7u`YCe>?TD6Q^3j`g4AlcA?_>83~KBA=1AW_}< zPh2A|UftQswhuPNXMvcn63dtr75382Pybblbkpo|3U1>`bNCHd3Z}DXjv)8Mm?A?pMzO&%q z)8_dSNX>yr8XB{~+#b#v1@fCAtUXORufAREj@bnrm*zlRTfL$=RFk}nz&1Au<1ToUiozIKMEn4O5@IA6(l2k2%s!nIVQ8B^ga6KP~_2kq!L8 z$o8@A$x|aPV#USTeaoFLzbnux)6*u=d!8c>lUp^TKG;mNsFf}^sU=8PFP0#^YJ3(b6lm&aDcD(<)4`1?4 zsh(_>U0O7Ib{?pY|8AA8KZ$B5NlhV9(y*XFU$&YUX~w7jWV4hklZ8$Qx#|5s_&{)6 zj>$z*#}?dcZIBbj6`C~S^m&rroNwF8w4kq6O<|YwQyzJYEXLgH2O{^JNv%040EKWa z9z|K@Q|_!%g)ru0BkX~5_v__IURQJPGZx$oyXV!m+CWEu%d=g>_H}ca)n#RF!=g)r zw$mZj*Jc#niIObevPv2vw7w@I=@D;%;!_op#>$Vh=34r?#}+9F1uPEtQXPk}j_$7- zTWAc-@m_Bki)E&c95a-7NTC%W))}9NNnOdB8q3vC$wy^(T@qGKcKp!(`&e2IN&IY zVwjZ5vY~&-5IvFocHuk;6Ws6-i#h}{-yn?-X7QrWrrkLn_J#s zW5_6L?rW1iXk%zZ?`5tS=p}(x%}|1InE*+(B|l0 zIPe;}@rp~2Kv;Kok{4=g73H>Q>gX>!w4o3qz>#50^SJjE1t42v*y|P_`^?nmnXYea zjJw53&896hmnIcJPw`0FE>CWDV0z7bH%G+$@CiXk&^elQx_|qoXA@IX@MO}P{1jS0 z8Zl=BCo|amuL%A)(4n@>($k5N5`j23zP>4f z8lq_mG^?>ZISAx6!W(#W6Af0mYqzlQNWd54%fB>$hF{uz#BGJ4iu%CXzPJnWiX_7% zMn77PoI@PuCS5>b4x!zXI*iN)dB*+)BvMjaSi$cMkj6QjS&^{eri$5lCHwY_YLd{G zpz~O^23LtCle%JtgeVf@x%0VR`aeRifU4P;0ZIs5LnewPVa&-R1q@Ixz580uxq z6<4mql(Byr9&se)lHIh8(b5-kC`!cVZF8!u2^{@(z~6w(sU7)iHg6ZNy&E#z#HbWS zhiYS{++v^_^;dejjDF&J!EO7tWH@HG-S-L?qJR3-O5|xJlDTIJl6>RWX`tY)8^W2r zW-EDQlo$qbGW*Gs_n%4NK$Xo#Tg=q`E^i9cXvsp^@S35EjXM`y0@&GkPX@h8h6OlY z?LE}3ju0ei8z#{QUAbW%-SU%OYNr6utjtuJh~i5QQ;5k^ONlq@Bu4#0E}V7Hw_}i) zNk5)pB1M$bFF(upw0o-7V26^d?bvGN-KSeSN~zE7oj-XRM|wlHGL7ek!wOWZ0*<84 zzp!TQ+FGnVBzu_C!KLd}W&<4xsN+5a$l*?A!&4V$zGL!k5?E-EgUqm}lIm!eT%G<1 zbs`YZ59g`Vy=G;PY6NyrsCEjDgb0wT$sUQ(5aY>-{9SjvsoSu~SF%W%79`b6wnl{p*Ro zrnS05>GY~Xu1h|`t7U#Ih^Jx0TUy`kb@Y`I4sjwjBCJ=d@kz%jzuX%d49y8DcA&d_ z%X|Q2Wx5+VZZf*-KD5qlhv@$q02b~r#j2qew@j~XZLe^d@9{76b}i&~UEJM0UX?k)$6^u%SOIYx zB6Z4lZ9CqNiVx)Xwyfevqc6stYyQ$Qj&}dy0@SZ=Psy2T{ActGfohW=Q8{sLMnKop_$ut98!=RUrjy$?8){I+A?;CN17Zw@B z1{$KI6}yT&GDG$vD+G|3+oKlZEWK9zN!-UO#$=~En?4}(L;xv@(H_mQrFj!^U?=Q& z8K}8MdZtw=$}u~0wS86-YTp(O*~B*fxN__3b7w=FNNxA8fmguUJiOP#m>IiSFt2Bi zi^HJDmPhLsUF9y%0e~lI8LUx%%dRN+iZp-PC8t)a=iucY@$=PRO%gFY-5w~nsdl;I z21>Gb5gBLt3R^(5|7kgrdgXH7I%YI=x8)^XpJ@hgr5HUwrV9F81SEYLP^q9HBNIGK z-20UPr~fk^4t1Ni88fwxT3#)mw8zR7(;KR;eWf)w)YE79r1h(DQY#ry^UQP%C=m`> zu#*63ROV@-*CyL<^S9+I#{i>h`@<1v4ag4N*;+P3w*$A+EVOqqR}LJ$RE6^pn*YZ5 zB?p?!sQb))v@zgfF%$2W`QF|z(*tN|U!G^y9xz?eM2#uy71PI$7FW2jXKI#C$GAI- z-FQ?!rtB<`e#}4b8|{5@yp1K=JP}Sm;Y}w2yCFWOpJBTrIPAfF6u1r$v3q#ry1HkL zUG>OOV!e2RUUNRT`+lACT=E-Lx*OODdn9;B@}D|6Pd&za?!0^BKSbe|M}bBp3hy64 zA@Zt98FIIL#03_;o_MtO{wwmi>yHbp?XKkx$A89;iQ>oqTqqAd8|wIw=<7bm9{A88 zDmbZPiHe+JQV8r(qT8ny*m!IXeqGXN^Ym#wvs*LvRB9b`{oKN!I(^IY66!zKlntgn zzc0XSdu&0}nwi9JMXj+-hW-RyTAM@Uen>T>nXvg$&O8%#GMXNxqMf8ogmZSy48)vZ+&f8zYpCN`|EDIB6t@Dd52F+x{HpTk6<+0Fn@cla@ z2kgY)%mH76=h&w}wscrm*~FxKZjwKA>=p&juj0k%S@LP|QRRj6*|GnT1Si5lkTvq9 zdu6waYt=gYsU*OEb!E3|Uit2H2FKsvCHh6iw((eth>3(B&YqDbf&k$B~USF8}&?*L|^H zsZygWJFinFf4^fF_cmKwd{Jxl)Yd>}_$K88;&NDvXSlmrw5RJR@sWV`b45BXB8xIZ zp@MFD!DXSw=K9y=`59=3J>nqr5N*})&ot+VKg#C2+I{Z?p5dJrmD@-5I^nm7Ca|3N z0ZSk39ITlE=XMonV&4=(p&(NAf`Kl+k&@5hc~@ z570kI6X%BLVGDoq=6xJSziql?yIq~Wn{D=jg>JiQJ zafGYGiz3*bh1R!s930oh zSWY537F#qHzRDtvUanrSL+ik|t%Jj5txqK);;+05@YNZWM5(}c+pD01x$L;8N^Skn znYe_En3`B=7uvcQW#23VDr`-wNbyBv$zy4Q+bJ--U)d&eB#Wjz3CV-TD7TG@|UoLcW{2 zRtf&2-;Kifl5=0H35US0^W1))(R_|T6qx4(oBy-!I0v~yiuU?#`rJUMx)wLS>zDz# zQ=aC0E_=F!zf@~R?dj)oKovo~b-5NcLw|{U-hGS=?;N^7eGa>(@>h;YlS6FLAEa!6 zeHL-0^>~xY2{@LgE?C!nq`emO_*Qu&Lb=CJebs4`JUuMDk zHZxj8z3i$eeb7$uDd=raKr7?61Mrn*!RJ6hn7Yue4oa zeS$~{7MGH_2ZXd-qd3EyYxI8FTgU7ubDvOyh-K~`+kOFhc*v20SS1Lz{Hg5xi}cbkjh{BeR# zmGP}NWBYXdiRzVnWwWQN%$5lcg|1GCVOa^Mt|g2PcVFiL{zA?_Qz#)i3#}yc3d^e- zoF#f5W!;$nb0eE$x}XV!^BZde>v|P9Gl1EY4bMi=kVrNl@CPJ?+9K4MO9I^kQLST&J5t z8S6*g3#^SJdi>`~mwnr$$lkY^^wJkC-^|_#-qIBzqkJs78AnMO?3{uTgZj=c`FQ`T zt8BNG5b*opC*+)xX+Q-h^z`cwH;7frV|Q#s^0Z^bk}6E~%wXyh&F>1k_qx-a_mvM8 zM$ZwpP9m3#?WqF=FYXr%ws3;wcBp{SeL|JiXSdEl#EtVe^Rq{lt9%E%oW7IP%fz>) zjzK^EHTs$%NbLe>16GX^CzWMu-SA7x=OlO*iKP*PetmcE-@(e7P5F5gZJhYc}eHiTKETZq-2(INI^M)OgVkZ2G5kHUP;(kwNp@SYB0B+*&oMmvI+x39ue|$c+?RvT3XAw3 zoUW7$sT3Kx4cAA}O;E>g@b5KKfFFo4EFuR}eShs>yI}DS5O|RQp+&Caut}UHwaPo_ zDe;T?`$i`WdOC$QUVKbCJ|zIUglvr-Zr^zVhF~VkLPpabp@WTS-x{ZV)dWn%z(|rt zpA-&^ek!s=d>sUpn6mPj3XxteL7t8qk!%6lF5y|htl&?(Y) zBPUEuNRQTP$MiJFp-u9AJBG!vgXK{W#@Qpe&V9}!mg$uWJD!5X5$aQ#=v9D%g*+w3HLJ%Q6iKOcHoU)Tm+O(Q!LWeG>{R8F8jn57|VI8O#o)RQ#7Vu;pr#hFp{k&+KY4*^3|c=hOY z)@Y=7cf!H#}+ayD~s2f){di5~pMh{kw0gy=OLYN0II zKHq@uglbxm-r#pks;ERX5A(5LZ)bG*d|kEkDIJSxkG3Of3ZibgVM+{y@QfZmL%|R^ zOQJ$QV6!(q;Bf@ZpFUdRC*&3<&k4m>^dJTAu|$@o<3Qu!dgN%x(M}(_%lKzu+}QOb zNI>$(7-S)rom%`=&`b}}nXtPC64WSUdEfY*poZ&1#I6Y}=k^Ecrf=d;(qf9-`dl;z#!V+>9|MX@6qX=-f7Z!W`akEeE9~i zug?F0`}kz(uAqq$uXNyj>FW2RTO5%Upb(>e9kFfn4IZTwgiiZ(Jmo=BY)G`NT(Exl zkcF2W{l@Paz6VR7KS9a~{IP13&_(c%6#g6&%q`|FGhSFCrN{arun5U=7&jG4I5CAW z5&I0VH5BrijLTrZeZ9lTv9{tZ(NT8C-H{06siDM2YbADcr#3ZAa;E8=bqxQul^VgD z8rg}NFn0@=PdDB9G`oV(U%yJ4`y3m+I%v#nvZU0_K-{su1NLQI#_rhu8%i}l0$la< z*%UZfgM-jpy;`@27MowUM?w7HRsUTgzDs4P?9~oUK^59%m9(n%#1p-u{*`17`(WWL zAbhbm!!pyq=Ek-y7L5^0m?%B)>T;!bvZ-T!&s7ud9Atn-ffVb7iU{UsNoj>wyY4VN64}$xKsE7GB zj)k4=mSaU1m{=z}p;T|${56eYMF-2*@*7dNLv6U6Zj0C7dG!MJ?LBtNkJov13Bbcu zgm#}Y66zBMo0wm&f2iwWCM^tac|f8{QY1D;0L%@BfgPN666`iJVg^=5@m4M$b1S(% z<}|TlsN+eYSxnz~z|3e?90MLHiVL9hzUFe)FJW zyMgsZY#=oO`a$UW178fz zh53!~$Lz08HzqJvn+dq3e-$%shn`0Jii+s1 zBZ)=aCYlhfbW#4hxn*o@?{6mX)D*TnI~ievOm*q zI*YVZ;wyZyl5olFYI#b>DyDC{BUMk{yiln{F8A-h1jrU!pv@z_jq3D6?=ZW3Pv5R* zx}kyng*+%NJ+(}|AV%(Zz1MjF&a7x@Ja&vcBqI^ztX z2PYUb+uO%Gwk!oxd=Hox&s0^G4K?B7oInz-sol415gWK_|0lTWtTC7I*NzV#?g&HrD1&_7hQnaG15F z-#wF7^Y<@xnOi8ZmxH1R?ylYK&>8ol>H2sA-qFv>j=^42_h-+0u->un3Mwb|>$E<( zUWqN)HxgG;o=0l!7{|Age1jLeH&wPb2oUH-Ok#%uBh`#ns88^_S^Xr2)(hNJp^Mxq)3x;n*O8^Ab|6_ zON#Mg)|TKl14tgE4cTql-trEmu{h{K*86=DrKbEoi*{HEB6gT^e<3^GScy$F-oECO zny|9F@7k@`to+iQM~^C3RDcjPKKVlUH7c|)-ox!%U4(FKKi*4=9QtlLMzFUIqB zDSpIjoSvs!1Rd82C5_uP4d3my(o_QM+A4!@TRh!Q^lmM?`7*S8BsC5zEOdK(8z~Amn<_($u|q_SJAIq> z1#Yw+OY*#KtWTbW$0AI?IJ1Hg%P$^Uy$Vn19pQ006qjx016e@+%7NnD$aO7wp5q&ag2hbNb)Z$-W_j0;B_k1}rr60p}Z^O~VO zRS^N-A|)UE(*bvhuNZi3DS%VQ7rbKD>rQ(TTw?~!#>u)J+~;{BkU zHZ0+6x~V=M)+jCaO^p2DKB?W~_LaW-<;Pj4tE6Jx>gN8}znCKawsbUg(4XNlq`KGK zbO6vZ`Z-E$nPYzz1k9KEqM^tS1X>8R4PakwgC)^lU9?&?2n z-Tlg#yJZsB`a|!ypM-=jeZ@yly%FfX5Vau3+YrawBUC?s(hK)mBl_0M-E15ntEorN z{rweJP+m~i>-PGmRJvDn9VCe!zerqJ(W`liJDy^vQhbW-9Y3}JYDT8ZNpF;VIU~hw zwCgfhXM;^(yMsObLFOEQMr5p3{!xI^n^Z+UIXCm(yh_}p-II1rk0t)SE!zQbwK0mN^y>SV)}%jzib z%TS}$sW@{|V z(Jl`+FllKTnYx}Urv8Q0;Nsh?I7`mu7sH?+ z>FiogaPr~b%*$am29*80&l3WP9gYbOCCMebZQlTvx44xV=w(@>k90mjpS35p*t0iIN z>O4ORV-)$yF6R9P;>>)zd@-kvpp4KT7lGv8WBZWD0~Mbr`y(Bh75_>a9rM05NFFl( z8rvHis7cDYKUb0{gnj?2&mp_<` z$N7C>kp~tqg@MtQhuDrBUqWMFjsPL|lhOnEh|*HyLcK#qNlavekE&Ri+mS-yJ!dJ} zV*PHn0Z11mE|CnInB}o$X_iye8a*APPj~15c zGrg}+*S<3%Z3jv<;t%wD>yB-0g`TDEU!%gy`$P7~b>_&`@;Mk|lF`y_Nk3o{h)lQo z`A(~prcWqHCZ3w6UFFR4Ma!5SB#d+!KmyK zc{Jzy-3V_9`WWW6FFWX$i;IihN4-^>(r9)?{^->Q13IgV!9S5@d8&34eUh`SJ+ZICu#eV&6DtKxrKjIa7hf~t0qA>2foTHo(*GME za+O-_3V)J+;~O!Nq1Itoq{l|@WBSb9SMup`{k~U@K|P6HPgif(*Hy3;UsJZSj((18 za$1KqSo2B)w&JBpx2(;#L)n7-ks@)TAHKCEbK%{3i;u`@hk_(q%chV{#U!>l`%aEZ ziHEuBX2#MuLp&L`WFWTo$9L*lW#!d}+9M0#aqYm`Be}7>Hg8MdYJYpQ%REUYMQ>i3 z`Lji)_8w+3kn%ujo|9qv0(?mGq^db|+nC1OXGUBS4_f@R{YuREfw|x~cF)3MneI}b z#o2$h;QS$8QW`#+ET-}&<~TKy+Wm-jG0Lqx{P@W_{)M-nx7uv0DYFbOE%TOGpxXu& zx=QbzMBy;ct-ggW&{qI(Dmbx#3;&QU64qVQS-0?Kk(H|#;|DcCdrSXiCqu5kX*?po z)@@KzIcAIjYhpz@iNo}8)ngL01-MIQD)eiwyUkQVOtJYFwo^Tf2^K&6feMkFwGDT z*&Wc?{p-CDL-UIu7JE#An<hr z=vYoF4Og3OH#Q0K8C=xSyl7{u!oK#+qqEjGhJId{M^gLAWT2F$?|-#odvJRIgY)5r zp^oqOQEsE?qh`pxX2Sj7Zv+|gDmnqzH%{+jISx6-6FcIC^_nz< zla}xt|D>!_jO^|rRYqV1lOG%9U|EY4N{jTAfAm6kN-MaIw&ea?ok>!O+UVlQACioq zu@;! zG5q1q`hbIFn<<_U!amOJLC+Sl{P&}x9!Zoj{CN6-G(>Vmr+pv1#!YOgG3Hbxvh&)p1llNbc=fD6rZB4(Y<>aNM)>dcSzits*++Q(Qud9hlfqf&xa0NBpMguwx8c27gJkSHl7!cG$FKP7-Zp!y4YL|;{ZkjK z33CsnO*xgaK2Ql4S2q*4o})S3hBEvD%PTJJ@B{=q=|S15KQeJmCTypra|ACD z?X<20-e`RmfI2>hj$%lb47RST_Ou_vC)R7elb4^1v{aN>$+EkUc_R|D@BRol#c1p~ z*eS3t15L|O?sYWMdp8$pHwS1DlN{uC7@iWbo|^FGZHNnLa}c(%f>)s?c#GL0`p<iK&M0rA3UzFC~CXl3;^5Pl8T#EM$w|#T>}~=&*<#xE&eZ;w*3uJ zuI3@qiLZPmY(*)6;i89*x*l#-q3%irGQi%I$d{osme^41PMEhn@+h+sRw1N5DTFbu z$R=SSqXA`I%B&+(rv_7f|7LrCv3XD2abf&mwfnBSA9{`t2B45}SKljVTkxIec-pMD z7o#~jq(miOoV`KMfFl@4?0betDpI>bdb=SNQX4xZr#mx|!&OG(gDW;f}sDJfc1Xu1|{Gf>doj2 zwb9A1qJZf+eZnuif3J%F?;hi8_ddi~25*$Acvicxncz513b*sX` zQ!sM%2LHx&*VYi3#{Q#vQ@0GM=>b^(S2|3FuE~)R`X+?-`zHp#b#MIWl)8~%=cd@v z*`*U|01sm9#hGPjxdQ#l=!0)%k}z#-A&TR3&})Y3m;#x8D7YiRU=LOLwUy}a$*rRV zRc~e(%oD5?Dp?HAXhrSsxm3F5wiTbCKo5gA)w9>bsPJu8n1`h^{5$`M9KYaj_Z)Fo zFYJlx3PIt*wILe}sHC;HLc3mJ6&(gP!ji{i5w{GvZw21CaZ*7tTE_nZ*q|5 ztG`|_gGd7j-wc7iQ3qJKqiq4eXJBLjlr230l3-gjGlq%r!}67df$aYHPuqQM^8>7t zNI-op8YZJb@Wje)@Yo~PdF`;8e++=05t-i~-#E6%E#UsjJ0#Z=1oz~6{V35H0Sugf zqjv{bC|P}c;HlrSc+<#o>mapZuZXx|@~H5dqgN0ngT{?mKX9ph1pL%eMX_RF9ib#> zITiDo-XSedJQ&J;}lQYBajfg_n`DtIfWRe0jUVB#n{FB7H zr_0KO1^VE{PrxV1VrS5kg_QD4TkdJ|RicP`9CGn?_@ zl`DVsT<39dR@LgHaX{i-oOpzpTC689?^|}MUT0~z_jVnOADA9jGY9@} zVh-?bwL&+ir4a@lFq^rS8mU4^xZ3J-S7OwG6v*3Z(n(S&K~W|s$R)jXL^0;B;_Qgz zM45W5`hGnvlW+jzWF~hEhi(6m4#QoM@0o-ifnflc+g5zz4#ICgKEn;dwvF$E2~x#k z>(t`?)JppgTAWdefdA1r*17roR=AS_jup4wQwuadaHuE8SHv@P#{zD9(p$B{Z%hZg zj8q^R0{^O1E`=Fs`s|c0oPOoX%gful2}b9=0dU=wqut#A${dfNtu4J6=0YZcfp+tZ zzC_OPnvA}*TVrj|_Ji}l^P5H}9BX{>vTFEU!M1%H$sTG5h zfybeHsop1?rvdPb>FN2`-U^R@374mI%&Wkxv5q=)ih+^#u3&>nu_6h>DzAr_qgJmaA=q-^Q;y{Et+5wHsFYUxf9=u4_lKSu6 zc0C;xQ*nvPVGVnKovf6U@WujTl5f?o7zG0*#NMnDpHC8*g1Rqd@bvuBmN5lq679Qx zqeV<_Yj*zO*Ul_-9vghqWib-@&#DjAULu`Agtpf5ac$;lRn%%L)SfMdksMg_8Wt2^ z&-DS9ycvXB#@5zWdT5^1$manJXe9+5)IF*2+^uG+Uko&R) z*v5wDj>6f6n^LxXy=2mWqaK6+oOj=JxA!V+qKH@xY~!}Gw)NMDCQKe*)&r{w7fLMn zBt;o!)U|%Op!v(1QuId@a32Z7`u7w6j0_*$L|Cx~%kG> zne;FXz7~Gr_y&5CG+jPhIdPv)m5Fv=1`5HkJ zef+)a&eg!4xev<`1`V{>B`<0w*!GS)fJ+tmZEsJ60WVy_fde0q&q=T7Ydl1=wLj>i zGi$>E1wkPE0}bL?pB|NY4n&0l9elNNM5_z9cz|zkIPH>J zlkGm@CXzimWR<%{K=EZRI z?CH$_X78U||5r%8D9ARD~qdGqZ?qeOKiuqqkGSH z-S}kDC|MhnR{fYrId3AZg;)-7g8L1tNfJlsVeLm2Qt=#9RWdO$-9qD`O;mf zMM+nqXM4aG#Ps(J!3+kPB5M3W(~QZxBy7d$pq3gDb8T!&vMsA7=BLu#5{HE8mU%u^ zysv-eD@Kz@ZuGjbEN%NpQqZ?q2A8W?`_vDs?*IWu(*3hXehz|nITFK#pzfF9Ti=%U znV0JY0TDNUxVpy+i}z(zhZ`KKSau2>2EEaD#-Hbn;I;i76Eks)y^o%_u`JB7MC{ZDTvn4ICMHXUlgfn+CY&CA1wRtFilhe* z%+{T|_t71}a%9lL6j9T6`AE$T{*A8P3(*XXY^j{I#LMl>w7=gy0vMjZ>%w7F#jdoAM?wc-|(59YpZO`;1G6YuNn8BWdRCZrWzs8s5(kaXSJ zwLil8ZplzXR{$%ldygU=(NrKRz+phYML{p>{JM6B?FXNEXS;0ym;N$##g7(N-W(BK zz^Myg5D^g^C<4OMntk)?)_MUqRDJkxJ+ohJvIq7QFNZp}-#d%?+L*rB=?+4=F=>1O z%@$vTTz^{W?DGCb+JtMaadPWSjK12yE3vsIl6+dLXC~tP-on+_YsdemwWW)3O@-7w zFtLGKFHqX0V%pu^-z(gV0KR@7r@^s7nm<2r(Y&Qz9FYAQm)4baoH^U2aqO$XadKi# zRCzYyNqj7H$litDFSt7jQQM%z{7X7 zX(%5J1{T96fm7xv(bJ34R~xEF%_tqP<)}Ft< zhLNf3ep<)pA{{~Io`i=%ZSW1hbUSg=EuF5*K#SV*?W2{AKQ$~9U1WY{mPuZC`q+AE znT2;@V1%OmRJB;Bl8bQeqHsJ1sIf;pD!w8*f47t?eygOi?4}vfblY zalgP%#E(9X)a5r@V7!pj9YFNEhiIK{n?i<-1bwrD#W04bKHT7f7CJ1#k||x-;mp+Th0y@4aqma( zCD2N+A!=`S_(%S+b2$1kNNc=bt!{P!ozUTYT63_wZ@#vxZ&YK(%)+~ImNpp2?s*&y z-h5O%4y-JMvYwPI%39WDC^g)tw5l8)rAz1g1?|cGYzK*muyO6p@s@S2%65H16Mx{* zM)<9{IeL$Z?w%|)rzJYut=0vzF#9MHiqsakhZ@K2HtW1!s{8#-;*wmK$K^?QU? zdnRLnavfX0xZ)hTD3of4-5RG7QxV(T%D+Elc_Ybns*a#7fG>60tp;jndv)QAjTE9n6n&%ez+oM@_wm7Jsim2ls4%`d&47RG#rxA|MX;Wcw zBfSDu&5Sx+<~3nby3Dt#D>Y-;HY^YH;;!%#K$o#(0e4*gBE2#JPok5{!B=HJYi?yo1WerSU1_K$IE@6rB{P+5Z7XmAc*PwO& zvogZt@Q6|e7tq+1eOi1a;6T-`%)$h^%cR2Qfk76Z295UXs4QXDyCi(vt|;N@WOemL zpl)l6yL+i!@Ifrc)xxD)xB=%mI}z0upH-`cOG$V$>N4g(+Q$&q{w@ktk(lN}CR$$1 z7Utz$ExD?W3to4pZIM$v$ikVLYz6WRD!VK(k?k*>=C*OSX;jRouh3u$7TD;<3=XTB z)*1|n@Dkn+u>pl8Bs&$c!ry)=84{IVn-3G^sxOujL(23L8te;~%v>k>VwP?#)+|?3 z(Ri&vyexG>6>Cu$E{olGpkb|te*Y-=*Yr>ACSV?)^rdS9T#co zrdW}RodF5H+bBsI&Try|ASe=Kyh-%x{(*d_bPf!7w~Y{|s%+CkJFPvd(xP|VT$R>) z4QtvQP9u~CjgJmXDb||tXf+lR8zhWOB4#m#=T8Wl!PKgDT!?C3fGzM4fV29F`Fg_=d@^hw77*izdK7} zP7!zfRCG;Feq_FvCdZxwATVd>HOWvrLQtv+UQ1$B|A$(Sfpv$KTC23za%;|noaHgK zIbk^zZ8%8Db=V?iPt)RFrXv4sKawI_9=Fb>?I=+%4AodSwYmf>i+AFGzb0B#;WF{~ z()%?|tZ@FV8v7jOh4=z2v>h^tAA$;v7Y~6jhr&990i70d(kp+-NHC`oZT0;-keX^t5)%bF?RNq>cEfdS1 zlu4h2vj6iT%ZNdJ5X{8~p*wT7Zg;&$NP_Z{HZ+(wOA1y?f!LZ}pFTa1mzr|!7P<1$ zi}fVCAwpN=<;G>EtNm{Ri5%rFQ9zGdfkW)h^F{DIDvNvlk`%MNZq#Ubv zIklAN(Ez$!F&os;&ji<&L|27rPo#WPJy?6>GnQQiNyr7mzu-;(ushNPOZ6^5&FTXc9P*!8#yNi2Say?B6%b2avFehT<5~&ij+AE=U8x9xM=fF7%CXsD8Yu(KmBR{<4eNw($!wiT)#c|ah=2k=YR)U zjPAGtEIYQqDR*#IqDOAova@cRY!lGDSsxx1=feF*T-5DXWzw5(y~55$cW7Ei4*bNZ z2d`r1S{6FFL&Gv>Ti}8rZE{Vt^=7WYM`U)>_0h>v_@Rks=O5-;Sl@?aLd{G;x>{BR z?KtU|meH(_mSb0OlVryUprO@RJh7aj%OaUcM@9S5ypW+UsVO)el&2Ev>T|>JtLgsN z)T!vH>4EjDhk(%RAmbfbMlf@J8Azfsf+>JphX{r;{Lg}R;X96WtlxwS&^WDpx86c8 z^*uN^(lq4pU&skA@Tb*-1E061{~{-HK|A9eP4HIw`!B;YCc=KfUL0yQHJf>U6hv+d zSRX>G;-HwvJ`pPvb%;8`{WviUY%dmWy`D?-Q4`Ct-n||5haD_^k%2N~Hj`HL}?pY){CqZRurF z;(T?PW&DkRpRoD^kp~?I+_=ZXJ5(I)RDWQ2d;?2miIlnzBxix^|2E@LI|Q3KQ&!EBD(%9teeV8tNq$k58EioDwlbYJjH zQl@hAq}5h!lrn+bh7zbO5PI`Q_Giu$%eYi%jsb#lQ;H_zWfr<}79f((pP?xPCU}SAd5{!*u;}0-0+f`x`2Uo?LsDtg33WUV?tE zAC|&ael(9KkKUrkKHcT#aP00NmGyXFCb2J@up)PxX53$k%-MPqZ09#MbRC^H38cow zpP}#!grIfeZCJCBx22?j4m7V8qm@G&l?qXy(`g>lpIvsJDG74iu2 zqj>PtF^0j%yha!|IG+`EaALT^PtYoM5BAhR?ooSL7?P!%PVM=dtx`FL2Yj?1@=Erk+_R zQ-|;MZ>PtLOzplV0v8TtxwhHf;=eu>_|~>DIssjI~jt08BaV5{}1voy)hmE4BSW-_3W(B^=acjQ>ft z3YC5#EHITQl@lXR5WKt_n?67eP})PP&CNfv`%9bo*(3I^ZBJ?2qHAZN;3{Njq7~5x zabVeb>_!|fa2~NeKF$}^t70UI>%NpnMXV*8lSF96&ZI}(e&b#C6<7UP`l8r+<@-++ z$_Aq{cmkS}o->BHd1e4{ZOH|XhJe!>7)6TX-JWGTkp8c!2N(F2WBj?U;HBNaUjt?-8<49Z>0=tG zihr*)l0l?}6Z%H*UT=aDsS*=>%zmk8qRp-I`m86@gDK>crXj!uV9^++k=1P4k?{*W ze&Ssa&{0*%cLkgiO9&9oHf8;2T;yfqr-2Zj{gYVs2bJ>Dh>clwE6ESt>*Wx0iioRx z6ZqV5HjvG7a?_*Z{#_KQf~9S_nS^H*H;O&_sfr%;owY{A%80*7|BXj@y9ucj;R z!}0R5?9s&2XthQak^kn!Y|*L$S+1Q;&!)hVA{vdt`x6C>Smh5X^RNP?&^q^Q^{38D zZ;a|iKbXYytAf_oKj560p)>t3qw`eZ+O>VrOzaqhnL)EogGcEQBfNOt&3hetNc^wy z^45H0S6@}}2XJkN%ux_Bp%zuk@K>T_^HZbV)pc(t2WOlE-aq0})A4ZT{%E0Q>u4C4 z(RknG&I{DckZ8q_m?@H&nyqlwY27i5N51;>Abmf*{cHCi8LNp;N6irlLugjuL+_;6 z358yFMa!Wldw|O=_!awTh3XCsXTzrE7#6Hdi-rcZrNl0UHh;qTcf^)Hl6s;Duif_Y zZJUI}UYc^{mjoe)9h}x#c8s1&-;Xa|v7L*pI{N~Pe>Q?=WZq?b3fPkJ<|cVUYUTcW zhj|1Cr-pS>3T=sVq$R%9En;2bqGC97A5|UopBWR?XeqV|I8C6AYiyzj)8sTOeX!qP z>HdY^kLhm~7?FZgT-NT&2o8>B4lBbfY@$KH)kszoRIH3^9u*APJ4E7BOJ9#yZF!ue zdlvHu!#^RCm4YaOFqIxkQ|k#yJ&tG|pLFIPy8ttarE>g})suZv*kN11l&LaXGIBhI z&h*qZBhAOr*>&hHG}1{W#xtqQfs5Q`6tJ8q2dtPQYcU*f(Byy<`NmfqG4KlqVhJDW zkR~yas)pUty~Cq=-^X@f?VmMH=-YN#udpoGa)Wy-q1!M`lPi>Kz_Pp>sCE5F9yYy( zSbqC4a?Ci&G}LJ64{`^5%EVME3$-*g{m@m$9t!23laZ&`hav}ury)3#20>BALS+?- zs*4ke9Yd8~I`{+x)4BlZ5HDRaa~t;%#}U52%USA3EDvk-WBlcX4mYMY+0CT&;^5y2 zFgh+HSNyzmYh0q?n)17Tu&LWbae-mgrod#TSK)cMj>NIH*k%;!|EOAY$WqpJba7#O z>ro;MEr_<7nrv}&j@I8Ht$bR}mA8@5^#4cnA*GCWq!k9idV{ruGl$t#N}Sh;&7Rk< zc>nkTi55};8L*5{AN38^>nHFQhoR;%8uu@5iOuV9(!qkk=~U*4WSVr*h`FRer<*OY z>k5bTBm=jRQO2BO5hgko>IB#?6D%Mr`;*8tIqRCtz$E=F|HQt~wVt zGxbRl^Rk`adr^a03+=1EEAO5Q)**s)CClIs`%~oMINvC1cwyL{bR_v|W4nU<-9%Vc zPHm14dzy4IQBWZPPxpZU`WgCbh3?3CoKZ)`I951rOz}ucB{Z=@AJI#tGPzb>96;4U z{U!ZKqq?T;*U3Xvz8tEKQBvhQ|Kki$WWjCw#0zYai{6syCiF66_=4Lbo5J~`f8aZuB0DWH2K%bt-2e%b`>w|H>3nbs)CQ~xa;8YSf zZ92-K6O+SRIX9iu^c0T4wuBwvE>`wc-I`JI`*ry4z<45LHsb681&)S)r3IF4=~~Up z62_RkS_>HMFEF>!{xMz+QnqvpxH?Wn5JcCHduR4y@C z(MVxue|a08Z?tf&$|T~nrE^i$I0RY^u^Jy_V|b8qxiEe7(F&W%%UuQe_i>bAnoF5>e8m!PdrdtLMW|(k z)8$%K0(=K-vo>4~IF>1hNA0%SO2zK+o8SU93!h!u6DXNi8((cy(HV}}vMI1~& zvkWvLB51}qJ8M;_Loj@Q{ad*!Pg#6Y_O zDc15`risxZ%JJ+i?F;6R0InVzNf2eM-Pub?}NamCFFc~MV|VyHhB^V%|3fCkDn&b zh@wGbBX?uIjo8l5eXB_<9&+V|8G1LG#>)X}w{Dt01bHAwbNRdLb!HgS?y<~gF8gpS zsT(*;Fw2cR+REu;F+psCZ zWrU~oy6b|?$HDP*D(~|!_uCmb{uUfW3^Iwnu*cN1>4tmtqE<8`!fbB;`AX?4r`Qwk znXM)6s+!*aOnG3tIexKJFwp0EG3-MWW+shNn?bZ^MjQ;BtJ`ZOEl0@ngItl0BRCs~ zoRAc8ksZU(bxTC4eOaVAv4_F8>f%Ijy4U?buD&@s(s$W< zqKR!=6Wew&u|2VEXJXs7F+s<+jfrjB$=B!Jd+v9BcdcICf4|lBK2KHcU3(k!h%eC4 zk^Z9^)^M1LKlxl>;vuem(+5ETyFEOl$X5GT>z3uu8FM2gJUaM8IRDR*A!wi!c8tzh zYE!<-qv|5)#pDkyxCauRERzfTd6wNOy~y~}7`nC9Rc_Z#+_janUvX|7Q4?(>ibj9D zr{XLVv7ac$B4U!Q(pS5sZcU0)U>t*0wl+;))3)keG;{)?#QMhU)gX7d7=3Sf2@X)k zJZLDaLJ#Kq(=AxbFShth5v_NIJ=k+~$g~wgdl{{Du&as48n;^zw5*bp&abYFymZ;w z*{|PnW-8VwD(s?c2$wUdAU1vLN|WuI{*wiZ^m@)lU@y=nHj~S>_SbxSdxi(*rX2Ym z)Uzq_M0nac)D*XN2l%jqyBsJ6zv7yyMAC&M;eReC{+vy$mYV1NT@|e0LXpA+t+v>8 z!o5PaT~j^J4~3!BtYit46Hs;jLtS{(GGb7A%9&hSHD~3_#60S7URK<271_6nPFp+I zv@|bk(%_*YHPQxG$^8w=YBYZ_UBPK-H40Plq{p0Y_LG47_yA+t{`YFa^e}lYBK6UZ zF$n(sU(1wOx~5IM7!xh>t0k<*$H$qRVcSCSY*AyS3wA}m(dvUozQo-_4Bblm-7p!B zPvhS_lvO|ewIo1&jW=C4ere$*@;?}P5T3z0DU{bbQ}dr6OryNc7Y2{Egui~?^1+BG zq}VnC8{>ivTc-ssQ8qY@ntqS`uv^F*^ z6C4enp9U@vL7F?~M)O})_+PdSXHy72ipz`o><;fL(6=FV`|{jLdKO5NuoKNT(yT{X zKef4s*M9Lv=n81(;{$vg5+qfu>=$4aas=)jFCW`Rn_^_Z`b(7QVbg{vDx88~$QIT; z{!zmnqw3fi(5-iS#R8ww+At&f`yow5lMT^)?%?C4l=u3%~i${*T*;c5e5e z%N4Zi>ashlrvM`VTCoAg(PixE*I7GGHup*TM51s=H8|`@xYN_*(!DUMxwS`mmgulq zoE>Slml+w+N*^lo$S_mWkK{db4Rwdnu>dqiG$7x1quV=_7^BoiuR8e!Yn+_K`J0XmEq3U+~`s~=i1?T)Q zaauD8%3El~bBan|5TsCtGzwV|BJW>$X|)W^{F^1jN{4U|T!62DtdLZq0}=^A2qHS*;diwYK5+?%|6|?6-*l$ znP+rW)mO{<`r z8Gae|FWNH^s|PRsM^wNK%BwPHnI?~M%KUMA&(7Tl?HiX17Hu6K#@PBuS#DtzVdf#M zXzQ33%(oMvR$`OKI+p^KJ`DTXOi;?FG~`J9FNK`X+pGZb z$Sjy))y#$1*B?(E#H<&xN!$@D7gQXMDFXow5W(a0`pI9sjE;}`g~^uQx|eJ^>0RAm_~3pM|C^q z8UGsH18pdsL$_qBtcS@Zm*!+ zjU&7u>@R#cR9QO3@2%c}@2G<9%R^~EhcTwQ-{!wsGJE|w23tA}Vp7+fk>jUJaK=;5 ztM^yM4}H?DZEa8*C+kkHKSarJ_D8XNN6E=U4a*s9*71T>aG=G~XPizh<_u@c3UoHO zW=Bk|M!fMfrKsCs=62fAk_+ zwBVN$MevqP1Rx>KwKQg{oP=c@dl-E!ioGY@)SjM!c%Cz|kUs4tHe`hXvbjUq5Rv7|)^D zP{$;4B^S~+uR(%=-%Xy$W-50n7Q)nPWk>^ILP-|d%oTX?*R@<-PZHOc&=cgZ!A;=X zN?c$7(L{{JRBmLgBd#wUI>B5FpSHx)+qSl4*`Fp>LPbv4H3*9_J_PSR%6&!|5D8vrkL@ zn~DD0xCSyeH?-2(Xbiy7>8sAmL%U=t zMYJHz-%CKLPbAO;PVrZe@x)ZTh#w0&SP4%OX>Mol&rGwH&^VsmpIfyT!?&Nm#7H6s z4eK;$G5+=At*~yq>dWRgdEGL6wgPQXS40IvPtO2#3({*j(fX9p+GRYLV8Rbp%G!h% zh4`}absaR5&XRaEaYwEE5+RwC1KkV{?VKI9fAZ_7E0@`BciS14c;HTF24~uZ1Kuy& zWlF3gJ`qZ=deeInLhv#rcgs+;ta&jBDZAk|L&&#w|I%7OPdhfeb+T+7O11iehyUuh z(&YXEO6-AN!;11vPdnm%K;y1Zq4(nx%Jn-hcaP0F2ZDzQZ88-|$xFnZf@=OoKKB z;gWcuA!xfx6goK0Kj_3;`mv&i?}~*^PV)pinE1#2fd4==lG1i7L0~5_0U-Ve2W$a< zq%b!uwO@Y0quzpP?xD%Yd~eNFHq?B_0XY=bOV|?E z@RHZ~6V*7E!ij6VS?ZnPGOok8yVj-%&p>Vs(PFi-FZ~mGj{Mn8!ViJjz{hAkcI z4#$hoOL_5vUIe*k_qIy+{*MmPmhCorFh4;ub)6b|>`;mQAC!-3#>^I{uO#1eLp(=(AC+tq}cJn0}kyyhn98EmjL|Jx+H7#_3d|$7i zc24E4Pz(YvO+f+70%tM#O_}Ch)`n|)&)KE#b|}_S%iPl=T10bNfgSwB@46mVT;ZD$ z&svA}8Wz)pnjkC#52*_e$blaTGup8+ki0(Om6?hqYR-HTFWXvla;(1#!x$2zSqrz&J z#r`O*AGp}oGP;ppNHo_5UXq*B z#U~z%^H{80p(`@FLzTCJ^JYPDjmVD`K@<-4-!3&VXz(X{QBP2J}RlC~sEHN`NC0dY4=Fm*yUQcger%V1E3&@Zj%5+K@NOX*c4}0o~i4P zC7WF?nUg(jYi$e7`KR)3p^Tp>f*R(Rx{0wPWOQTR;ab!rJB)Ci-rQQD^5_Pw2-4*b zoB)z>mH_kMuZ`~Y3c~TX-{|50eN_MV3&+&rn6ncFQFw#&h_*%N7wQZ#H(REFIx~Fd zU2+<9W!g=tQ)8b3;*mk>`DZ_ZRc2O6vFbi#!xg`-#3+loPgnP?ls)8vm9Gn8{4{n1 z^*EX}p_w;?*82_v(g=~ULx1y^ctIVSS}mQdvur-D_>>LkD4Px?SJ#PUNACpF(K<>5 zJ9vJ52Q`w7JGP6y>c^#bk=t;QXuEr4o6TOjbE(xGP-7e2@l2L}h_FHUcCU3(^Kzu} z1RW=O4yGFT9VPOUGVii{xy{u#&&bc}_i;!|^vbUVG>xrK2z}qrmnm;iigIVH2QMh% zv=C%zYR^4r-?r6rnrY}7IS?o>(mpaH)`pibe%2~U<9}abz$2M3DYpRsvX4g$EU?g@ z6UxKoAz)Llr}OQJbLL4AXh}n_1SQv(I#Ex3suagNzwg^e(y~3rN4(l@tlk#_uwQum z4qU%WvOJPx(wl8fKRcGN{_O*nf1-QHGb$Ez#;M&I{`$c`g&Tqo1{JVPA>Xe0x4Xu*TkM`8pv$3J^`-wCrA&D8 zW_oOy3zoy| z;={sDp4lKjM7m`B)EaScGOOak>qHxnGGSh_P1@k)caFJ1o!R2yp_kYddJksy5Bb!k1QT(rmR)pZ>?aX8OK; zd!4a2hd`4KF%O7xNy)HLlQEC`2#ugJ(L!|;yX_QsoX2|`XOZCzvRydH{%DL#r7xT7 z()!d->Wli;Ft^92?cV<8xncI~NlX{3ola(CmwiT|CQhmbFJ4=cQ2yXKjWO zX}r1Uo96T8my%^UkAoW7s}4`?@jsR+EE3ghJEkfn9O8b642^D~57?e|?$h91rR6{F zklB`9J?J87t$g3ctTLCV@k+RI=(P-VaW}VBwkC`hY>!GF+jkW{G(CKkM?1t~DBp}d zTq_y#xQ|JL_ZJuORMCDS#Bd^=h05$ZdvUe`t$7G*vFI3F?+rcl>qz1UZ(~||Htp&D z=f1y+d73c27hiAuzGEMP_2YY#eb9bpX}1t{^pS`6O9KN|^ia_}=(0oQBe*p6)FEYu z4*!88w^()?_zCx@^IFcP?{{~%n0z`Tp3$bDraFlSn?F|Q`1nXu^Bk7*Pan}X0)J;c zaY1+JYsnhIZhSKdwC~tNI@4c*2Wl$w<^xZ9MNOirg@0Ce2C&!0Sq*D8tHMh6L7fzJ z<&KaJWO|Ww!s2Yf8Fc);0Q{T5v2!v+AGgAm2JNL@ zKlwr{Pjqopdz&s2UI5)STI1W^&3^PM9zrM`i1C`Dt;gazlH+AGUqp??l{j|}m)+gp zro;Ks1$BtPH5MVF{{Om`v@3W^#Tq!4!33WSE+THGkgDadWML>+a@NF z$wj@8{c?xu=1%Z4nj1^>o$`(gF_jB;a+3{@t>7OEYRF}aO?B00E(_=p-~raGLQoqw zoakgyeTn@a+ST$u@Jt)9r@KBdE?)5P@cM4+AFg1r>DfwSMhYJ-e$g`Ju23^k`=0+yms1A^Oez3X7VpKh!ID z&agr;92~k})oPBgC8xpZ19bt!@ZAaELVHvGAAur7QsZq|!zuFx(H{&emLMTf3r&6R z_IrmsG*qOly!ba4Kspa{-!|f`?O7!DV>AfTD>iK)7OD0r9uxK5JN6mS|8ko3%uJrq z+}~NoaX)156+o-PW9FQxwk5t=yl!mX4gP${I#}^K5?%^D9CQxZsRCfhBq}Yvc znl8t!u0A&P{|51-@4x@|yLszsO zx4{m02f%~f>Ip1+ORL}UyEl%{mAB{>igFstx5)&X+4&0EGf9aIhZ5-kby8{fDPIE`p?jUOEsT>dJFrr7 z2o@>8*ERR#6hiSi;3LpysBm@?>}2NZiK|n|UF7JnZ!6G-q(6J|Rv?e*%O)`rYS@7) z0(5w#t4XL%{&;hPrU>(X)x&lZO8Q>Vg>r#H4854TmjPTF@Yj zXrV`nUa3qU-Q{8U4+eFaq5d{&4G(NAl8`7Z5W>kNOXb=Vd#3vl^fkQ881!y(9I3(yT`>|TI3Dl{D=`u&8L~NZ zg(1&QSl9dP-R+mp#}{X@dfRl%m~yH$$;6@!ebuQao<27e;zU5Rbj}gD9doJG2qon4 z_=*-0=sFo|2jMtKQ;L{i(ji`%wU2(;U3Q%qm1V{p&p?*TS+EkPG@EYZsX@Facm)+V zi$-XCrM?S23HrUHCzt}v$w&pmZ$i2oLZ7HCT^+9vT6LPw=V1Y$S?6c~0Yj~+4ji8E z=MC6vq!a7R7P9>L?z7QuZ`$m<9Ve|}X6!N8Ah1dt=h=l|c$WFR)kW<8cZ>S6y<*~) zK4!-i8Ox~>>)=U5&%02z-RBdml+mjhyEjW9CeXiF%=ObMnkT6&5ltwz_a-hjhX3&V zo&2Ta7cyO16a`)>A^`VpN>JKpyg~YS%y_4AMUs2Ma*oc z^(t*jKRe#EOCkhlr*@=CTk33Cd6I@xdWJ%|x8>^7i>aWi-(8<_*UB9dMXiBHFSr3p zGUtDJRhPEdih^gwRZEaXo1hfBFdKuCR%OUgscru>EAq?ERU7_{Ka%Y>j7&>LOYrUP zwk_nz(JH#}j_CMn-kqNNeb{C7LdB?d%|581!3W5Z@VDaa&$HSAm%MBGwp*2QTtF3^ zX?2-vH#VLlj_XVRXNY|%4p3(cpvpq)S$k{)S8WwHm(b z6FOk=9U4DNAYF&1b{}l-Y}r@nZ^Ikk-Tx8qAEvLIhqxSo02%jEu8E*#evsVf6HjDX z(Q(4ArV2o3IJmkdi5=Y}2<&|weK`!@n`!~~hjc8x>b;nlVkg_6XbnSdZC0i_eR@Ni z3JT!CnRiUBR$tHbeDo&#$&g8Bv)P&oxNvt0DNwccO2>V)6P26?HIS5={9J?U$ebTx z+;`QaKY|N9>lgmSl2V48W)uC{c|hdMPgx##1qhyIm1Q4$+gueOnvs$`@4`>PbXQFKH$Ws)66RSx%G7sB=EM9CRA%vktEzC4+rlar?RCxTs>q7^`lLh zu;*k#HwDFOL%@Hnb6<9ra(ZnogLrVi&APDF%>4RQsNMR&e%B>9f6D#M@?!;Yl|=2S zVP$K|5lc^CZOmmH_d{Re>GQY+q5gS?SGya*sfboVIzLIA24WT_J7wpnfV1W>k2(lU zi3B{Tl>}P-`ayuC!pVRUuh-aa+(&$yGocHWDCpM=>_oOr#e-5X$)w|L!8cY5wL|!^ zy81=S{+n{m7N<;)7820;>n%#i_>Uqt z(gYGS(N44T)r#Pe(1|_z_{j$gnru5(C+F)CJ@<3bD36tKk=SD3&o?yTq>wy52T^ao z-``6xOGVY05T6K8^&d3pQRb8}Z$|c*q0=FqhW7YE`rG&4%(dyy>NGZ^c&BS0C_EG6 zoCF($G0Ai(_1;4UShD=y~_lwHUL-MVmmFq72T+- zmg6uPpz&p3+!vR;FuI&=2YGPyqPuTA0XC{T+jFcIZE)}3oNHb1EWsMS-I7pVd$aO^ z7ys7#rkMd)T69>tDXNESoFf9S*-N=_Ng0S2f2Rhq&}&lh3TPp~B~jGcKf6MyU(FY- zhQOS@y4eu$fz7%*u9R5+dTv?#F1QuUIN=W52?wRGQTlv2lkt5yAU1DtThLG4qOexI z+Tk^3B(R1dHhrm~Qi}F5T4P%DJbCR}vb5*il)!H~K|!YfM@3itSkEWAsdO4hYc!e>@@ zjUD@h6?>J_P&UES8D8)}cDQ){)?>+^H>1v>JX`8;P`RvoRC4QGE%qvfcxaB6eA>y|ElBCW7<9T+()r+IH?FwYO(@-}X#Efuqm`FN zYk1HFuVc(e;#-%+BHMKZzBYha1D5#D4!KH1&`?Nw1o;Mc$>#li)^Lx^_992EhFmJ| z`#XPNr_yr{gQ46ssc8e&^i%q@nY*0O_QOkmGv@sp-{E*r=rGWu>B0cN-(!U1>*48} z_XCGMBi5Ff%GU`>NHXU}n7(Jfh&cdm%>>TCtW_sPl{JseBV`ZQU=^c5vt48lD--Cx zXxuiXPIfe}23R@a3LmrOt4*QI_0WS4$%^0?Mo;Ec2^Ssbsu-D-E~Ms*EZSq`V3&}d z$q=?WOjY(ATt%%a>+m_HZw9*0r-&!aDLi-9cUH9a!7A8#;2-5QBN&DEl=o?6yo8UX zib_i{Kx6xSV#j(Bc;7->q~s@8@Fue!%~LD&%+4}-d3gaPa8QOh_k0Mpx~Bzl1YLP{!dD=b@0D)bh&?!L+azz zc@xwY20|k#F{`JpM?N~dUNkPHcMG?mP=BYAJ&`3-hl19kzEzCC>Lqf%PW*Q8n#Ts_ z04|+aq)b0GtubK+>{%I)5v{#@1VFfubGr1>P=)_+bQz7buD2#n74Ya=+GSqJQew_l zkNIuUw;oV?MGA97YN$fBt;X0y@Rdlal*^Q0D$)@ws#*rxw8RmS-Y!U31f!wI^9#?B zPCLzPx9+8EEAO?)&3BoV@vfCrl=-7WQhpX^uy4 zby!pu)M4X$KBrBUZ=*jUkj0j<}?$|2}L7?kK9j^0QSSYeKZPcjY7_FFDZp zX4@tN;SC!!X5E-{<<&ZB4bape5GGWqc{_g29g@EG{G-~@pj~#ryBqd< zPnkv_f8iCB*2KxE@TNzWF{PA25LmnCcOaxNp7vSyN%aTm^p>1}AEj)T+13KI=G zQU4##sXR*6mM)qnww_5)g5NKYT|$Xny*JfL-t_!(7!H>&uY51LP-E8rnCx$fXM|>z zZk-dz04RX^NYt}E-JfUO2_ZO?3RY(>#T&+TL|9O_qT8<(OgKviMYO0H%L~N4#>wCx zJAuRZr+5_Y-)#>`DmZLtx@3r$JKSuQfQ&eNOCxL2iFJj~*P&GjB^6s{y4pO;_TwbG zfr8t*&uGfGRM<)PV+9HT$UQn5;u-;)fPp2vNQAM|a8qEx^0Ff^&-Ao49em%~hsw=$ zI^~>CRLK^y%;Yh3WX;G7!bFiuaq`8n)z=>G|abE;lj9dXniBSrXD5zk}B`hgkQvr_2Sz}jI!40lkH~hSLMm5csFH=kJ zBx_|L38et47%pn6{qgFa8LHf1J3_V9+4L6eT{J742i_7(2pBuo4x1|M>{Q#Dh87w0P34&Pp$>+=}0AQ0X1I(e%!!J))08K;^CMZ>SdUdulzT?E{Y!ACo&| zpP3HAZu9?uUV)PH9h+Y%fm;IG8u&Zp!xQffb4bDBR+BHgQ9FbF+hy6Af?U-1>OJ5f zKlk|x45e&L(F=Ya^JAvQ_5OC6D3n0dtQHofIzG{_kDCs=ag<#xprl8HVhx-mVz!Db_CCVH0aD1c692vGiEnb`Jy4P;u;i z)uErNe$0(Lfw!E3UalD9gtmO)<^v-EH0! zn(tBNY&1ZCK&F|JV&bC74YRn~V+Ylua&R{NkPvDh1lxaS%ozs-4s?#$JpIa?lffi2 z)nJBy>j~7~2&BB;`Z{2%R1E?all)x_Snv{1x*?bI(!k+~v>j5l;+U8kfmdiKL2AJ}}jxc3j;!JxFzG)-8 z786NU)s)FOxUGwQr3yWVB%;bcB`#mWk*=Cz4Ssj3@Zynb9>1y96fa(YR`1zo6cY@K zFAMM0YnkYIWcD7T$FqCUZ0fj|T5GLiXx)fxM#Rz#B)W&hbJB`vFsFW!q7_rYea(>bl2g+%wm6z(DEnucw#A0ggtppKGr${F z_Jt@0YrS0`Ms)F`WlEh@pEj&8tgx_f%&QEeYn=3cgVy-oeqe9~y_-8jkb4*rvyAR( z{QVmF(o*XFm?g{ali|Kb&TV?@R_I^MlLP#lr+2=u@Gl_rV(`Dvi>=V(B6j5#!*vHW z;xr)*DP^(CLQx{&z>jOWd8Z-CT98vFnvbKE|fKnwOxDk)i*XmUng_>UGn79I}Quqb$PT%rlJuR;XFgBeIrm4n5 zS)@~+S~d8B`Se>L=KP#)DNq^v&7D~@R!PKe#*7nd`wc{k8gDsYB9=rMs8Ojlj$X+~ zHh!x{pOx$50M*^Dk?Z;p8i_t(gyq%|-p0Xbv=zeGc-BB12UuN4N~(C6WxPj^L3;M( za+OFS2~}vLK5C=y(hnDXU@Bup+q%2PM^)Z|vUiOT-B2&yRymR&MOg$* zJ1I8qh&;`jt$s^ld~``s_ZQ!ORNoiReoYlCUkexYL-Q#Lqe}WgI8ru{a9I3fc7!wJ zKmmeVRsoaJe5G?3YR`q^l&d-Ll6u0b3On>$eq{nc!s4S9D5d@uOD)}=Gn^VrKvW>c zqVB)q{aXzJ5;F4z5kyW-p6mUYMNfj-Xlpo9T~fUOU|JR#efzQ>wqj1`!glb>6~P~f z%x`+=(q19{vn@XOo)vETItz<5(|vyP+=~iyIW-MO0{t`ctX_ZP`UCA&8Ya zdZz2D!S7G(k;k+6C#o)+70#a;nYoQ;@-P5Xl~I$QQ$-f15Q91U1LTKVywF1@&9fwR zvnTfAR_qmia_*oO(pk#Nqfcrcs}ic{VUzHb4b7V_yhG{jwnYx>at5cILWQ|#bX#n}2z7*P|5jV|WUupJezttGAHx#mn(K#T^d6CHa@F7-7Km9@Apg?S}2@4Fve71Yb6%yyC2T(<0xe6<3k8|c@@&&Kw|pcVPy^2Qq!p@XY} z2z0|)D{_oKH?ykKL>Cd!RJpU&@F$Vm6 zd(VqwWAGmn`Es81Z`WT!Bx`1pB#8I4*|>1vxwz0v4(g1D-KZfZ1D}$C zCcu|v@6KXH+70>N0l@{gK9QWF5=AR%naIG!z>NhgpGs~kus`Ox`>JvU6qt$^_{IyB zZ!sc+Hy_YaaC@_Hg@wdKl19O279pyVy}f_X;4{}1lACAk&s8?*4=SONRlS5&3BV8V z)=*4&l9pdzt-$M7)7H5pw5&?k&Z+^kHSBT>)zQ<9Vn%hFY8Z>r+q3tYk)lI&%-)Ez zxj$!e&xyM;`#CTVy7oX`NA>o&sDpoT;_ar^$dyshW-xK-5)~P<;)vAgc+shv3><}C zzg76mGnptIWUY{V9E>j z#~q($r6hk_xlqnLGmDZ@=~L*eox)teW2xi68&jS~3M(@A<WMV z{E52Y(HnI)!mHnOQxM1752lzTAWJt~c&fGZzy|VZAEcCF4DcU^)u79?@}*l>5&lW} zC676ay;Y-KV~a2_G^FOYah-y@LtDw~Bn$&u?eTsMg81e;9w;dte)Y0X!jXX~IV@DJ z)Tl>~;r+hCkY38gw{;W-M@`OM`?{2wIP%@7CWesZ{k3~fw`+)j-3ddJpY|U;JK;CN zIEybxQl2an-#Lk*gys3vbuaG;iI-GfH$Mql3@GBT`-GKBbcsM@Im+`aC#-l0dfP1{ zc|7D3=9ShmUd%?N=ws62{<&<$BCaQQ(HYn{C1wIVW`cJH9kOnTbCaJ8^hjDH$pus} zbDZR|N_~R?G}9)2U*9C8fdCVRk+1C0?Df=W{l)sq56%tMfoGxCLgBf5B&Odit*t~e z^PyGl9+mYu&2mw`*%GPYHA@e&rt@{$o9Sm2){@+G7vpFVq7B`f^C-buIihFv8_IKN z6h93{(ENYe(dHosSt^?G;-ngEe;0WTWLDYD+d}Z58uY~bAgEH?Sxqdl)Mgv9lQpOk zlUX>0Qv3!ulafJPsZXH*JQpqFYF*f_#aveTesmsKkY_x)9NZd*gjT}80fcl^`0+s% zVQ>LRintfiU6GVV3J~5bVtyTvVzXfoT~~o{tCVJLLKROvPqSh(7*(v-?onwWjPT?2 zpnXjax3_t3RY|M#G~(3878)uer=CkOiQS`heY%KN`R*&El%rj!?t^*Rqm44 zzbcUOu)!$xbl^hN1WP0;%C#&_o?+5S!tvByX)ZiYm(m&4PT{Uxj5UhzM(S~CJKN^^ z{cG;Y7J8gQHAz&u1h~Ykeel--1WJkoBiZD9SU%D4UVO8L? zzs^ z3)*tkDNEr9z54?DMLwHLOUvvB-5Wy%NzIPXdJJZL!+_2q>c%(=2N0i*YM*O6D|W|r zKo=cEC>j*a{{Vv>WfBDZWUoC(Mk7-v9`$b)w;7(Pz7kR|uQZOaL0f3$u(J`cytOSNEC@)?+3$LP$K-teyN0una3qG65a&}IR0rHE^<={)=k8N)Q@X*@{9#j zt3+>Dft$V?nS+ZSicjDj=Mv!Qcfg~srEhg}kGk@FR_#0Uv@QXh@3zw*ba(xFjU&{lJP5i6%HcH3Eom0}e;N~WRuB8GE}o%VLQ zn_ZaH#+9cs=UIK-ecR>iaiP_Q9XR+#2SQ!C>k~y@GQ4mj+;6GJkfc_o}on@QlTIEsa;P^|8 zU-OwzdvO^L6YHE6toN|Q(#VpjhB0$(^`hp%i+4L_10)I5$DJ)j0#7P8RwoN*pryxA_li&7=DU`0~*8o2MT85TyG5ncW1v6~l8=9N?>=JFJBew{E zX#6eca;GNMX*n308Ar+;Z>(>vJXSF78>=;zF$e6%TpXpA-LmiIU$ddu)x{3%)2jKQ znkFlu(idw_kmP6_6S2g|LA1b$M`IIbe0UiKu26nR39vayU~NkcWs|p@E*E5*OCzR8 zRBX(O9Je^QW{8N}7iR0TffUKT$JFd1M%9o*jaDwF(R%sXe7J_fJjN%M!?D)LuXDxG z#&An6ePyR}nLra1BPgPGFpFHxzx4glQSQvgq`SBWIV6Ji3aTQS10l#@D({MYcVZ{U zv`!LEaS*AQAKzbk=B|Y;6`p}aFtbmET#)Ucvdep#<4`HZjyF%oZ=;EMY{7}`Ri+_; zb<%!db$S9BBDm1LsDZvx(0qj-!L!p{%c3Z5k~3>8u}n`J*sQaNEE2>0F7qaLsNdAr zm3NUNQ%tVar?acK6n5yqaM235XdA%*pFe>J+{sgwvjAX3L~mhm;Wb>5yF*GG_kOEg zHcKHxlXh@%5USa^HKB$>2>_|Ocdz$J z)0cc?gjaW&N0{eNUT_KIt01ju)gtdMmkegP9|6a`l=q(}Uu0?7Ox};$l}H-r)c>C} zNsBSAJ0c)J`gz7j(aqoULAG7|N}B8LH}tU!ElpK(PmTGC9+*lR^PP0v_rthB9Kq>U zGir^n@VAdcE{)F;R+Uu{Exg#=gCLEw;vaicg&tqWg&?}SNHD>;5vP!T;s7N^7@$}4 zBFaS@nnz4h0?G8~9bPpW6Z{+I(7FDKbC#QoQf2Q?B%F6izVY)Q{eX|cp?2(l+` zv%|rQVsP=A96iamENv*!Z$LcJ1SLQ4All?3ubCJn`SCAc1StPottsw2wzOtPj_)Fx zqFW%>{61v5r;BCc23UhpCy(+hp;R~^Fg}E>5E)3%Ukm9+b|`bdz2OV;_pQC)BKOyw zQgLaaZfN}0XM#WiaRHnNVa4bKJqj8}4NJ&w*b110HJw2KvUlUK1IGX6s_#mvzXKm( z7TYKONM(Gfrts|cLI_Hf^mL%E=YeoRjhOTQR(dQ z^GyPQL5@3+1?yhdc1&A&KB$L61yspr%0ky8hFWsoS>#v6V1dT)niz?Z zEx_E_mH*)V9gcd;oB3Oey*++2>mzP~9K$hSm9>A=BW5{FRB5Csub)0XEIUVx4p|cL z1ifMF)%i=iEAuJA3L*K(V?cT)aVWe*2x0i!$YgYd zm>y&#E`BYMW6xt@RA{LxwBRGu@1bxiF&dNcN_m>YvXvqtO9Y}?Va(S0=v}fTm0ngC zN9qg#RBNk_3^kPVAJkSgPchr@*?6MDj6dd-h<+qgWM6D*x_Cit;0%o~m(rTb_@P$ z-~o=EKH3Q){+H^|3bvEmY5cMVhGI8G`Vh2SX}0c`YroHHd@#{6qR%`jkClyJ&tE;+ zQyeUDNk_d4Qh&sl5<0QqVS=@sjEo{!s3Md@Zt@9HdQY##B~#CMM1XkBOGwwF{KnZP z@uPIV0FCf_KS=*<9Pju@ebkG0%u$=M<`P-lbR=jwTdjWg{&O=8fjnx$D0nq+moQfT zcYiH|y9+XLHzy-p;#zLC@79P|z{t9`$G_GWa!zdGDcrwUCCG# zQKO}MI094Xcf$^wafsHc(qTqOJFXV-Y}=;LLsOHwf@bL>4D(a0xKYBN?ZVhAkN{r> za{#FumWu4eOVBu|Xv7Tv_;rFJc?FCVYJ@H0DvKy?EO+Y9iwmQir`0qGSzGrJC`;nf zEcFzVkcmS0o6=7Hji(1`8-mo!CdZ4h)HC-5SJ};I0(MaYb?TnNQ^yE~<@tT@mr{z7(U<3<_k%lVOrH77~ z;{>KtXt~lx(O5EBt%Fm0M_*O_FlNYT8fM<+4uZs%DpDGuk$9BlyP1O9CFJdJ7maq# z7>A<3Bd=)ALZG?WUUgp>`#{6tJ4W*M7W~tqkTZRjE@&#FZ5OUsTfheX3Yu_jYuC?O zE*m{$8z7~-0<@U;5${jo4cr`B zF`86D${9xTrqrc-0Ks=CGsza6Z+~dfm?P4p5sBIA+j3;&NkB%jL9Y%o8jn_jpx0Gf zk$ry3li1%y?U+wYKgMEVNRg`5Os7w}Fo^KhNc@2l$q{&q(f9d8e{s*{oe1kEkEIry z@&*7`@DLi9t#fCQPT$GlhQJez*2xZmpqSvTaDu##0oLlf)m zS4WmGqj7}CJUVKL=^t~!LJ)sey1rv^_r$r~?F!nt2nr`e+)|!u6H%SMi;HABce%4^ zk=h;&nerFSXz49Tvubr=lOl?#x_Hu-*I9arhcXdS&^vJ8EbBFcmbf+FR3EfnbqtwUATcSk@B&oWw*G;9D`#32}ZZm6r!r~0)EoAN}oFIx6 z=B#C53~KUseuX-ovF&_|2ct-tu`D|ZsYUQ>Kd(2{9xEeh>Y3>VxcaJkgmB%I&sgJ3 z_mj##&@hdt%j}oskeQVNd`ofI(r8I)NttE78LO>=T%59PeT%hC%ekj3D#S+~jU;kT#vr+53OD|SCVKL_KD6b#t^j_oT1dJIOwnPP&Fm#8;^hw(wb z-LcM1e=qNjC#S5K_n6Pu0-L<=kp|Ng1g#7E#%9=w3^0GY#iEuk4sF+DmO#*t(>Pu4g&6m5sxSoY{(BCzO|> zN}l+?#7YN<-f)4x%$?k(y@$3IIdA8o`zj=Kvsv(Isn2|;D1U+nUVgf=UpF7c7c_=PCvdF$*b#i ze&hKi7bxAA0{(oXa@~4IjtLXkbHRENTp6THf296`)wy}l4?_Drx9>hvfJPNd3vrvdDzjOLKp#{*gR#8qg%=CV7(a% zCC1%a7WGaKhqJz4#YH%-wR*+6krydVX&hBY8y%3yJpb`;aGUV_5eMJ?#S!in=A7*l z+GeFtw?HI;iiJdK-%4(Yr8uRppHA`R*63xV5?NE$%akD~h4HaLxY!JA{f612`NL3v zVisHMApNYM@v-l;6DSQc1-@}&TJ}^rkWUMm-D&&cO~2y~1J3I5KBMtFcri`!X7AkhYyB_i{_1$Cx zlwP-iUSfUu?oH27TKwSu);aqal(4-qc_1w|p+Rb?nL^9q0zL`XFr7P;3GWEKxDuq(M_dMyjIjCzR-8J0azo%c zbqd~TG4D|iLxL-&S$qTmyEN8PoZ<*y0xEkMTHW!IqjB0i2BU1lM89{ zDE8p?iK32t^oVjd5wAE#5&hRBS}v(hx3Xv__f=hSEla~Mb*Lp#(ZSsgL;a2m4B+4j zwsm4_%Mv!EM6#$vRtNUK!2z8RI(?6b*}%dlE{82oC}kp*i!u0O(8BR%9<)$L%Hf6c zr2h7Nk$GfM2g!25&TCm`karl@SilECa z0Yn1vRgM4b71omo$cn>b&fas5pV+Qx`)&~QH#wBJ5<6vA@ocE6s}BnXh>Q)48{DGh z9y@u$!|nOB6tk6sje7uvJ}`)p4=7tLo8XqRNWtPQx_`5zvAv`$Odx)g4xmQ|*%)OX zF(w|FC}Cj3!F@Q&XwL`wv9fyZVHDF!Fh>?J6VC!^?+8y(c$O-@s~)%2*icC&ZYD6# zI_(;WMh}pF*eeKSeRdZ^fO%Q$=qNr~>2~xvw+czC7&mVOW}!gQVo4_y(t7+%Wg2HM zHY*l<#0<8332pU)<(XVICn;r~x92d3>Di z4mQ`^qgru5{7a6>P%v!WwV7V+7sSbBz|6h5Wj?|d%f>B; zd6tV0rQrZ34~3BS!>D2D`begCu>SMQ>EKc`_eZ1de@6aL6AZ?246Rzv+=qiLzx{)9 zzqnK{z!`DUWcTLYI%n{Bxcd8t@{%bot!>Iz(t8^daDO3|Ef_7SQ5kb)K(NmCk=DRN z-v(W=e{u_*GR#B2HV1gNpO=Jy=sT8)iDv2OM{XK5+|cE ziN!3$dab4V^S+;`KOStbi#-&UgBOMvCP_;e6DrU{*Ud9#Zva2VaE%RpiWd7Jn;Lys zKjVJY`&fy+AE@z3G+pnb^F=*1IK*G8RCO{s@A~bSV*@Lr>9$@8;;uy^Nj^B+i5wLb znEm>~Z&C0YfSPt)CqjE3sjl(R7myXN1_=J#kc-o9{9}U8baLu-wvikA;EH@`;@OeD%nwFK@c} zKwZ}CYf3*X|FIS8KUOlWdqd|LCn0LnLxF0&eytj5{6bDS2KkS=kT|#iH}(Y>MU%(m zwTYe+4i!L}oMkPQLB@9D=~D+9e1Bi|s;AOSyp}z8xYuy1yruW~a%f9GAdFHllAaI) z7x9_(cg(2Cmse=r6X|!cZb8nrg-S;8ZNZ|1$#?*ih>CK>=*JW5 z=vTQR%ku0(1Y)9Fp`s|NP)QU;g6@uRn*yngbY&yI#^cGOM=L02(`NIj!;R1!pF6eb zJ3ZZb0gjzIO&qexJ(RE}DGs;C6hG8IXM`r+90t2}KQib|9(0V*@oVAjGG$}?TzrSv zb&ekn`zgFUsqZ@U&E|g~bCn}%2eD%PnJTJd^Iz)uwQX&lL>!}MVu?f?37_Z3wx<05 zICPP@J5`FrF~O9DssF1V&+gk$c#9O!^!wZx?*7&HGlZE)pub{sary`EL%uPTPGV9u zG1lAen`p+>mA{*kwG!e3U_h3TwmFCa9{>LAwcuU{qTOvJ|;+!6T0mNz&c^p)IvQY2_M0-gNvA7~BTjUfD2;n=3hz ziLYib!x&Pr8rIh5&Yu7z?clhY=VsNE%qs@XON1>V>K${QU9H#Jxn4c?86zc| zQdt0T;30aVVbGc6$yZL5ulMHL-;D%ln=5lHBGN<#RKEXxyyUd}96)9|DQH3;`MDwr zkCf54D2Zk80@_$Jw}2cnUb$XwE*(F;(qtDLbmEO0~2ND65wwR z2MGgqYMBm5jm;q?(tOZfWhY!pxCv&24giV^6O}BRB*|y{CF4JS?`L7ndhCAh_`48c zP1a~~>*RO}d)v}@UJiX^ z)rl{Pu3yxO&`Qw;vH?6fvHV{pTjRbAg;&(L1aaRXTi|1wF@@Zrq z4OH*W{I@BbkWBr{8KIZERX8nX-zWa7@pEQ9#$OZspf9KdF-`r}FuRxGyprG;z`20e zsJh?V5@MEcoPf#=NGXman}V@r6Ip@Z?%V%G@yFqkP*5Pvm}C+;OX2Zy_&rp(!sF_6 zm6y;bWT9vx@bfMy_pXVoXHgBIsGSHuC){^2kTNz4$nERP=zF^S_v&EG66TJrQ~l6S zvbNx@48h0uv*Eix<-C@8l2D@^n_GOtxDr`6zvZcM69mOmmd<1BhnXwb3~>#jdkIgj zfxBGbVF^;-fsgSWxsI!yhr?frw0$(7$UNeo3wETOSN4B#v~d4;i}-dT8}XR>=qiuM zY&$>0wblTUTDcax5Yd3Z`vh*~hZ)0LH(Jx@@A`i+zdZL%Mr7Wlz1`iYR?rt87)MTA zKK%PuHo?jz-@GD=Z3|Y%z!pB4_!?YCcwkmsvBV!1j~Uooqqf4Oio-zMmlw*y|2d{q zM8cwSRfR0C2&#{)V5EbdVtR9X5ygtlLrH0uP{}C5D6BqoR_awRn#YwVtdVmxeg9e< z+UdK{ET!XJXMcOSZ?k-=>#_{VzdyA=7oGN$mtnNQ1-di*1bqSG=rzxJPagIw{;i{?u4Z-|TLTJKh|h z6TgkyeJ!Pw@H!CG1U74r)_4vr4#rDcG`S9UPi&C^L!rt@9USzJM$rlGEp;BaVsnc> zS|JVfMolA2``5ON%+RWPi%o_JJE0V@MG~N??bz6rS{IBTrxfb-^atBlf!3WL=HIgj z0h_Z&$Yx2UelCpq4hizVdBiSXM8uPzm%81hueJm*V?v`pdTwmXmYrbFp5qfgS#~cu z&&TBM8qaC#`v(yT1?=1Z6PEuI+1bFGd@fs^i~7B8VDs03+w5zN?kJ=ln&I0Gf+9cP zQ11K3PtuKnD|_r}X1K2KRStKqYw9k~su7CVw2MQJ+V4|I?9=6OU?vhQYJQNqNt_a+ zX(hiP)Fa#e6A`uSn?v{59wrQ4&BH$J2~!Lg>=myWGeFVAqY~_BUP&8?eZXtcF!fO& zSr#Txpok^A2$h+cyXZjC~fesxL8h!YYr& z%-8N5+DWEY);QcAkRi>i)%=iaO#@xQ$xEOu*woLhn7WW5Lyy;rJo-~xtLkAYG zhF$Juq>RhF5qMIPAjOGw3%RUQoj&=736 zN3T>mJ7kXwr(!xQ9|xsYw|v55)!I(T7TL)VQbZ>AJvI+B6}<@^_ivLU2k;r-p=9q+ z3k+-X=grwWate^kBO(D;bquGts_9(gDUBy)x$?(9 z@uyWk9LK#?uV%}{2}u5*c${^We14HRy&C;r5)01`;2AmdDf2Lz6aQw|FH)ibv5^E` z5sal@IxNqVkk}n+r2e>$s08I00WW! zug@9Zp8W%Ew$_tneyR8ka6ceXKy*5H<{cH@FORce@pZbAuC5ZuDwrsxgcAn}q)tbR z|ArNfUjwXA4GHqfBg?K@W#RHBU*k;)>zDB)=4pj6w?~73{f2TW#ALC)OEd#`r9AHo z|3G&HK={^{i_fw%q2VXkBDxJ@SygStRBk5e1U~s7Y-P{IS;o-?i#T+kN(EZ+!S}I7 z8<8QoI3Cn^r^-5$RMF*5ght_!UQbOHf=4rMKmqsw%)_%>Wo*;{DXCeZ3T_x$Fx-J_ zD2Okaenu4P@hoLg?K!O%OhYvT#7ICyFA*>bcT6DKh9x$RS zGJE|vxVyXGGH9Rt!Zoux>Dd@qqJ+~LlV;BGIU^I|k>QFf7*)9UFtV|#iYS(Ay1Y-k zqPpRY{l%K}t{XNxnBjh#%<4b20A1x{=^B57pE@|}7p~Z{cFp(4x9#T)GmXhuMSp+a zQ=h>9G}V2}P)9dZMv#w|z);eM6%5V&1?T72V9bHNtGh0{Z)GBEYl{B=X!6r^MHUK_ zw7=;$n_f?Zg=)8#P$o9G?23t%841RR&`Jcs(ZXqFC4pfBQ+V5QXO0D>BUJR1%%gj$ zV8zF(O?6d&(F|(9qK85ZYFkWtj9QI;&^wrp%E)~wJRDQh=@cdkf}~k9?`fJ|a!vM# zBf}mIS6<->5deRZ(>O^3k^91PCPqXB6N^;n3=#(<3nlpj#u{j3>|-Cjrz{&S7ZV^_ z3R<5CsF10LsZk66D1+X_LEevoXcEc%2}tA-B;Q6 zj~6l}snfrw^jUo0Q|+wn;sj9t7uNq@;`|>ehjySZ*v$8ipY%nm_GNMDkou5wg> zwPQl9<90Z1>w%D|{xj&3OXv&pesUi}vpm=?0jaTGIh9N4wDX~zdSBPXogvF1Bby~6 z?$|Rnz&A=-H(~r!)%tH`Kr!#jNgT$?1~~P4CppSZnFhT)E)lf;v=-d)O)Kd$e9;{E zfM&c8M`B1>mGVEBanLv`qaIHm&9=+GO>QnON+eum>7ku;4}4$hhiH&oEg$)hG1bfH zUV^el5tM*`bP?Raf+ANVQ~({BH}}E#WJeJwsfZOE+bU#LYTYq|0!0uY6Wtb5IFKrA zhTnPWX=!TgmRn+T1V7Cg&~TjHOGZgJz+U=Y{iv(}sx&U%Q&^K{xb3s=XDG!Fc7mP7WsCvi&9_TB!)oY9Wmtf7__^ z_&hL<;PUm~{eq*o;yzDr{COksBRG`G`>)~n=7Bo;x$PT2g}}o(yRWtrvpT7ww?&K( zkMWDI?8R|1?^1A7y!!iP8lvA7elZ3_aMmi0=hAjI|>G*!b~JR~8d?Z|V2$H~pUnsv(HO7qgtCP@m8zm3K~$`=~__ zw|{NfYf!)A+c5sFqmSrAvO@DnX^!nGqc62YT#+F4IaHV#Mpk-22{vFO@HG2{DeBNL z>flU$1_?M7jzTTO9U_2f+#r1ZfeFWGYE5#z3o=g7XU(1-xuH~|YgQ41@s<=a^qC?C zmOxV6X%d=5u#p2SlSQRjzM#`WVz&%>W{;o@Df&#bm68XZ7g%l09>Kvu)`ddmknu?8 zh26Rjx-fZ#IwBwa9a17^ZvzJZ*~OxZ0+fna?~j}&{sLrR5UT$OWDQzk`h1&qfsz}F ziDE2)3(j+}amwT@;R#(+bXk*By7%IJuBZE_%N|(C)v4sFP@Lyvte@)wgmgE8$?9OsPdf<=O6UXggKsIPY1q3z|q*btbXV4#aou&bzHMK#V@13%B!5JPPWO^*89-+qkvYY~LV&7Ky_Aue z**q;nH+VUl+(9FWQNQ2ZR~~FotMkBuJ4khE(21XRkpt1pp8qgSP6;y{IkFFoGE(Sb z-;xa3B!pgE)i-1#zK-*|t@gNTen;Hlr67qzR_U<^TR+G5z5D#~d1cZNgN^ljXo zjPrXD>B|BgJ3#SCE#wa$gr8sXb&b0T{Pz;D7ST?g79dX2y?@YA^ zqm?b&uB=CR^D<59c=MKVl*KE?^uCPq(6ip+`?*eRbk7c7R481SpQg&!hls5<_Of`0-Cp~rgAk@#%1*n}evG{lTAq8;pGl~gYH_-?!zb0KCc@rbJm z&P$c8=TC(`C|X!>j&ai}4Zzw4$YJb`W4USl@9qknMDb7isWoFT1w52A)Eb+f9wCwN zC%2I__ypxM+&N?Pg%H#tVE%m((swLzt{{W48)rdVd|qy^bn`?fSJy~ZDIRo0@TyB3 zDHSc`w)EXPS4slKP$Z**pa5B_4fxqxvdJby@mpUC=9p7KvbIMs9C|7HlzAkoo^OVd zDy4^BLZv!t9NH9DUaas4bYDO{C-Jo0`@QN7fWBUx*gi@5&pAL~W}2ihYRCR9e;TgQ zvfu>O4nF{jgpapkX#U4L2@GZ^!Yi_S9>d=-HthD#=-zxc9@Fe$U|E{AALBOv&dck> zP;GEHCJz{Xs>vZq2njL__i~R!!5sA@e--b?(xQ^2)Qm*>N)hRq1*2`G8jYJs9*gWO z*OGD)votmL?W!Zk3hSPxO=xqT!f}X*y-{(XoiXrq;jm_+_hcWJ?)dCT(2lrzfVV?Alk+ z^lf%m4X54D?#0CzZR%+zXh?PJE64T0Cgpb{GE z)P-bS5r?bA_a_z{-Z6sIZdlGv8msc#Zv8i4V!Y&lO54?|rb0Zyzy3u{?JZtoe+m&~ z9|D^Z{J+V4Ocw_*pbCd-W0=ke#umLM(;Yw8zeQ-**> zI4OU<@7clk-4Y_CUzjuHUtO$N0)%4GR8>FjJJPL5N0 zwwgJCUb^O*FC9uFj9QdYTeRvM!4|`e)wRl>CS3sk*P%G6c6x4o_AnMZXH(kSCv^W;BHO_lNjE}bJ;@O6`BrKKu3P$l%F>NTnql`kgUNSYbgTf-aVXS9-rF7*PDc#%z_ zZGTF8oQW8r0JSLRtA56?nxA-PlFHXCzZ0Va;rl%C6265Zj>gvuQ6uVKGcI*3Esj#~ zXJs(!=wH7)3y?q0-gD8KsVFBF&?;pxOU^?O3URNiU*VVZAF2AY--z>X*%vY1h-cfV z!#)4Tegx$I-9-Ms-3lW9`R_N~)b4&SuobhCw2y6X3bV;Hxf;BazYD18)zQ6FSQ8H> zPOmvgk!wb|zUN=^SSA>TP$C5~AZC>CEyK`kvsZfzDLIG}JY(AA@(D)-%kmFyMUY>J z&fap$Yi%EL{QaGu>!js9J=qlPgicE|+$31q(xsX`;)-reKlH_UXJmdwMz*IswqlSV z27-qqlx0?PkvjvWg4qzPng{~jMqGX@C&4JGrKdCmcNpV0g*g#@DU3-(Sw<3o8ySfc z2|*|H3@iQlQ+*p8R>H=rSTbVN9$2_9${&xeTvfjWo|6l&EgV8tsHjx43LPCN4?3=; z4%%VZ9$wU(OE)=^L*o3-qa{~~$~r`5sVZ0xhbwaRa|r)Ksun>crok#^8FJIe zvVys44QX)oYiaiA`E+U~1ph>);VZXIDO}6}`XM78m01p_Q$FFGf-S)bk95DiL$R!W zoXfk7X!&x;XcJaaz~v zGWo5WR0O*X{=xk_r%|0N#IWad`t9q!;m8i@t9B@pfB`t2#r>}SHS_kcHt2tbQUO74 z!;Ig4J?;rF!G10;-B%lG?>KSeZtl0cA_eRtmN6a-zanwEvffxe_YQa9GjU2|a7@d8 z%-nF2Q0IS5{_xl4c^jH^@I2@VPFwPx_(SY8KnoK9kNx~hT2Co5-6LWh&J9Z}>@1v9 z8RS0Pj0>Y0wtP+9$`eU&@&QfD;vY!|l2$S0{qJnC(j^KBJgZrr+0zG5aAoNF>eCw^ zvcF2H&p>Ojl$>_3-H&QcWYx`sObc=&`G)pM=tU8!hXyJ?r6<;O2_dNC9( z!b+X{CO0Kj`%d~u2P-ua!r_nrEqt+6k)-dXze#B+n^2HVM1Kbu^(>ZC21S@OW_StH zXe^@S!e2HJ30ofcd;8?mgAA=B^5XZ>CZ(QMNqj0nJiP2gMOCg&Rp+*S}l3tIM&$C2k58su&?{L4FDfHl)QFEu|iyjyTY!#AlP-2cxM&yYf|edGvf1CjU~dAY5T6Dn2x1WJsLp zH;jY@$MZwaSGiX;DsiBl!18qL8+C z58vm%HihVGtK}psK_X)Xm2+-?TF=kYyQGQU+|=Rgv*mtG!xtAr|5>|wE2a-hPyG3G z@7O31yj-a=&X`bN-FG(NGQL(kr3*I~z?xTHcbv24c6VDFcd=q-)&HIS(RQH7TV&dK zv_h&);AI2Y5}V0E;65jY_6rWZA=J9J5FvuBj{Q*^m!6Jv-8qR#b|JF2GE^I;Br0@s zosziS2#(|yX{LyCh41RJWz{kV)1q_h4y_1Ym=iovNXf!WI=JqNnqUxv= zLy2Gw*=Sycg(8tItLzqdJI`BH`z$4tvZte~vuRmZR%4%5go)UYtEnN!vK*03n)OWMUC)8>s$pxrCHDeF+j`zQJASM2WW-@p%X>9}azUO#ZMoA+*#C z_PhA>rtsW-$+Z7YVYUry)nVajHDSj9C&X!Va8wL4MJ&dHVjm#83YxzNnfQGN58Z|3 zXWfrhhst>=R6vLLb!iW5wG)nH6b+dMHY~tr0BI*vGyF4{^FVa8ZRSU%+vOcQZZ^q^b&$rjZj9 zz4~}gWoow+{&n=o{lCPqKb-z_r$%H%Xb=dL$dG8=*QP?C3*=_Y2`DL-QVErgH7cvQ zJacGH(~{i0mwV544*7p_qTM!4m;MFsVC-TC+Q5(8UH?6MSG%3!J3glfN53TYdUmK{ za9Vxw#y6P-hObQvUu}B(O;z%KE;uq&@FV!;dS<7N716&t#lQ1+Y5_p*cgL7FWqe$R z*G!w}`uyk7*M7RKJhQVP#k~JlV}Z&&4_OEZ_52{E(d8_SE`v2%M6J*;m^9vk^-aCa(>Rw61=+p2sq8wLq4*!6Tge+|Mnt?GI6r+(;8~DQm3_H>Ikoz*$*P~e`yMA-4Lw}rTzKMei9NwIJLzogg;dhLnu^TVwE^}E`zx7($F zJqh0ceC)w7d~Gx#97WzH%bvNEQq_peBn{wlZytJ&%-C0ze5zx-%1gOJr&?-mfoJzZ z078gqP-&6rePS*|g)hrx+~?pENhItQET}m8$v3ry=k)KI#1i~E?U6lV##>d4;(mqI zC@IjJ1T}*KT_wH0I6bORiR`!5q@rc z#og4|GmuxWVAA$2xQ!>rUvS4rQcc$21xS~}nN|L)PBor7(~sHKuV3D1 zdi71Nu`u|O@bH~ceE;KQLrU0ShV6=cC{Enc+HFVUBgqb{O?if4mp zyAv1$pgF>0QXWYOHXkw941?j5hvOzRR1L(#Lb9hD7#&F>@AcQQLOA+(bOi7@V^+eS znJrY}teNy@tpPoPTGFs1`#FN&ct5~6{clQL=GW~2x)y@7+kG?U_vbJ@7 zhAH;)GGM!q^kSlD0;cZgcKc53NUP=my2*h z4-2T)((t2oj4u>(xKt^FaR1n$A z@L0suzDBMjtzuJqGor5UJ6uGjb5++4G4H_@CR0cL#p;9cZdm&4yQ(3u_NDzu$Tq{@ zZmvpj^EEb%@3&l?<8ji-(1NG}^`bb=K9ZnxKr(b~vP}!8zffi|lDFd{oepLP3PGGi z@}M}H$q7IbqP439*~%E8szxAEE<>g`xJG$AD2U0O`#C+Tlmw-!s-%Wzs%bkyMP?+e zv^yeexQmJ>%hI;_z!#urn$bmUJ$Xb#`(qvV_D`7(CS_wd?I$DTRefN(-yXldkN1uFooVhYJ(*~PQJ&zkOy_XJk4x#P;egx%^N0I~X ziqZy0RI;Wc#EIV&G9TfGh_W_2 z?y`UAzPV&^l$e5Rd5?fNTnd9o>A>Tcl!UjFG_1#0g4+)z{S~Pn3Qun3zMUDHIJOqn zzNm*TJP$Y5sbCx#Hfkmf7ZIUg1$C$#1Yf5_wfGnV;y?W|g{7&Xo@Ph@klnv5nk}}VQ2pZtxUC=AhR?JD$zO$bg;^0@w zkg$U={Xg16D&;h7dI!5=z2)lF&>9S%&2uq@<3pkQnL!OHy#~VJxibhEdt#-%7CQT6 zgiz43L;n3Sz~o4B60Bk14^|-xnsOA)ltcY@)az|nd_&=65U(@dAl8j0Uu17DF zkg0Sc7)TrwF->Y5$$obOR4-?r;(CJ=@p@f+Fv}Znhs7^S><4UtN%ww^-C>abjKBYt zsD0?$j1tvbE7N;m5R^w1sP-MHA-Fs^c~6_)%t+lwNy4RXG}Ov))SY-3^?M;S#7rQe ztT-TyTlXCq^`bsBU)~qOlqO5=vlLM^33doX31pxQ!G)m~B}zoM(ir8^>@u;GCk!#p zxY#<7M}SS~m6&kvG_9}2Uqnv0Th6O(P4#2FNyru{aE&(Y*n;qal_4Tytf1$48K(LBYciU8zP*q(tiSIX$VGotIa#l4w z?pozK1gjL@0MqfSH!~$LTJ$C)_i%rve3Su6P`?(@$wV}?l^NkP8%VTIUKt$^8QCYg ztS0Yi94Ze*q$4m_EB~==garSm79igWj&s~P>1%uAU2|*P!g7~uQq3`AJHxs$^}6PF z+vaMbR~N|+wB;S{B@T*1-|hg<$;cHYCRfQkxsq?a&R=X2c-HXyYm9J`t;=Dd>d2{M zgQ>+qNC(KF94{K*o!y|>*G4^2Z|~=irt-=Y@LbTDnrXdwm9&H9lm@MlV%sLn>)&xz zqj7?oI_gvMbFVyxDhg+OZ?)%AP93JO6dQLdDQ>$@o{Hu~=N|5d15|0JtVe$SYz$W6 zH`BC9t(D23wO0#_*7%9}DJmIQ*J3@61{iQ09nm4j6s3ddEZMNL@B3=2QkkM84J;I< zv!5#;ZVOg*J0ntNPJywSP}68!-4l2|vl&S}`)A9aZTmdg7LWMG0g^iIcmA@vFP8N1 zIx&_;V}E_^*bMsXSG-;~Eu{ZT?>kMnvE${PdhYvQv*!oC z!OsyYN0&#n{IBu)T~9oDY`mxq;3DZLp6C0t&dz2R1M z)?#Y(oUupZ-iq(vO$e0$`FTjx0O2w8BSoIw;F|%Zir-P{1iCDZ)ciUL{wf))$Qx8D zK$+{yUKZ;JBz{v{^68~NnK~r8)vvFssqU(?>oY&(2#?HW7F+pTfdg_`qgsd$9Skd) zA4@fcLN!oJFUCmxxVxrWfh7tvpSHo`P(PLb9W*fs5(Ska7t}4tP8pGOWoG>`Bwz2~B!Ym*U9tppCBk&=;>mi2CL@@_imG^96cT_i^G1;LWQdr0|cXjm;4!^90oiu&z7>j!U5e+u>V5ucB-x!%k? z0oFf%vTKt2k0z|FZt!d0>84Llgcdkv7M^kMeQ*Y-!^3j=Fk1$hA&sr;t$Mq(rmcj( z|DcAE)l@)6?_`~k!tCB=k)a?(HkrH_R@j63;4~!b%>41yy$HaGazXs=-Vliy14J{i z=U~tBi4d$X)d1|FH`m1qLq9;(KuS#8EIk3AXlTpey7vjeWwBk~zlt(A%3w=kCW4(C zS?v~?o6;p#Wy^GJ7^QjrnhLwLYz0&__0=092iR&v$8zik=Hfmat&~wHRbP4edU4*lG$Do3$2d4Tnw1XO&*?YhAh2FU};(vRctz;h%!~)29rdUF&w!y zPe9)Rzx>zC~M35VcVfp2f^3e7wt3B9BzwHwxL#cT)FnHb&=76*ZHUS5_J~wG zj)eVxYU4d$rX12?A25iSrrrY<5tnv%Uo>B`uOX?V%uI|l_3S5CUz8|8KSr(`YF8_LwFt|Avv|a(D~4M=nF zirad_$X70n3Qm*=5xgKeQsgV*Zt?HnFF`%toUPkXAXyI=l1h&WZ(bQ)8Mpr2>})Xa zxckjvG~z*!yg*u&u;@ZIeEi^7gr`|GeUB`PKNIPRC@dvXK`ZN)y3LIhVGQXwcZ$2q zKfIO6?P>Pbe+ilb zSQeF5)MovHp;iQS$VP;)3RhYkmppf)SIC__~ydvUhsNsE>4mbWF^sQ4YvBaE60AD*OeG)uB z{V+7Ie--1J5nDjdm8O4poJ*3;^*?d{hMY&O>)V}>t$P(!ym6qVe<6QovmVxwWg0}2jMt5fm^H`o{)*Bk)KazxOK_pDXKj@Q_E&|92~veWw+d=`227p zx?d$iZUab1QtU<71hq+js`j64`&fY}zB9YO#NI7)I1o&H&-6ly}EMh`W&I&--uu_*=eRL{kDOYmUMg1 zumlSif8U-p`4(NZ#&eyYyrOJpi?9e>{lZAZR_C*5K&g4oZ=d* zBV$5wHvKhOt+C|cPQC?B;3rL=KKY@YxOBd8yRIK5&&kh4G)u%O{4ch7=aWC-x3|RZT`%wRYmUPIE1MX$L+-XKm^@GK>_+p>axy^pTD9RT z{zA8XKJY!ob!h1{8(W_mAQ8usus`Y*YMtri@R(>&LZ-0ACQ=m!S|spS@hUdJXM`H* zC){Klyuq*z-f4zUX@V^_hSPj}U ztu5>!1i6^g0<}r)n~4eG;6B8$BR0c6%`&~NvC%~Gw-ASp(%s{vf17w5Z^?d6S{sIq zJt}xegCN51`-79N(B(ev-M4uck4nd0LYBxo|9&RCa#JDT`mCR99D2{jvgg zp@>V_RyOlf9KLaGGc?d@r-3w%njk6HdQA5Z<^Gu`lQo_}BaAARxLa#?Mdc zx%I_+HWba0sgpc^ss?Q}PdLtf1Uqg`Dlq+Pzb?5Ck?VVZ^OhYe#S4 z*etts9ZLy~U%5~y`p9ky#6HU(wGFp&@roAdM?Sema2Wb7vHO?pbZ{Jc8p`jtMt zA9m|y>*EjMN(tBTBK0TQ@mnkTvEdBrxbQqA0O|lOtb_Fa|JT-6$3@w7YXj2K zIY>!M2n--KgbyVnF(3>fC^3X|4mE^Ihjgci(%s$CAs`)sAS2DtHSmqk^ST4x zx9>mh-?i7e*WT-1Yp-hwV#%1*J_9;uaA5j|{e)J*A4@UJ!hiMI42Mtm!g~b~q14ptAvcnLT>g(|mo2*qUmYL~C9A-E;7QpLz<`p`vpL^tZacvHZQ6LBFst z7seK{BG3Br+8B7oq5X`0p23{|$x6OsugC;y;9#f4VMlQM8oSo5rG#caQ23GK>(DuXu%46LtR2zT7cv+VYFnt`z8pCu%pe15M``Go!?Y|lYa7`o(#RPKeKonX z6I>LC@lXBzC#e-><#_&Qpzh?NJ6B)CL725;{1l)UDFw0CVX+SAzPuvJyCGqcA^NfI zeU^xfjA?B5;3VhVD*8-%jCpr{*bwizcM+!hUI?aGS5y?wzHG=^sE2Dy|&@XYL28RC4g5?xl=60}Z?0dCEH7$*+;eIxbD zc1Tsp9qm)+TC1k-sWOV-9D433_R8dkgp~Gu^pBt=%;MpjmLNTH9lnSXYz4yjH|k?J zM!cKjiuo~OX7&wzQzJ>M+-tRL7yIYEWRxTtnhB8m4a$UYFmaa^&Ek$-gE2_!@X`)z zBFJx1yWH<3(~GxE>_}V$;SzKFG5*q;e?4dkwkUUGo5H-r<>}$?)Gh15=YhVwUhq>~ zsyx*(tyxiSX(H?#NQJwrvq)BZDPYP0wZ-b5tEgtq1;G;(*mu5V;Jiz~ei>{~^o?(+ zRB8*%y+xv()Zmf$my&6l2vQKkzjbvG%;P6Rppize%GJhPP88aNiAYnZtY!OElcDMG zPeFpd?JS+sm&x{q?32VrPpHDmHXkMSdWY1fPwFLhhaR=ef@+SV4ecggI#DYbosZ7s zoo{^O?cwCkGO6;t;}KBlUuBw}fT?F*q|x6RK08*U%A$TP$3?=?EqpRAK)9ggj}=&~ z#P@X&3L!bYxS2>$lJ)V$cJ9K1cpZ6X{KsW3Az^Wgi6^YBULy&Yh|H!?0i+`SR;<&Z zwal=bDcXHh+JK6L4>uOM0tN)LVR!=jqMzd7mJn&Geg+d(M1T9l38vC@j?m*$p*@A{ zLxP3WGnm?=iF<>+`$pQHCOT8eaL3(KLE-XpQor#9u~RmTuYrHA3p!x&jQ1 zcsv`^O5 zbCjc4%Wm(^_UoQS?~EN>oM-B!>}T^!(P)Ize0ihqF%w=^S3Q7F@sQ)`+lNmnOikiu zV~zxm@Q)rojpZQ{KV-)We56@huU}uoU&g8SNeLx#zNH4uay$B1++2e22~o5yWQgmC zd8*+Ff2FCfFA<8Iy>lBl5++UA)Ko+WCd=H_llCX)0G~>07DdHBDff?a>=^3eRADlIc1j|+apKlJ- z_p&bDsxiy$t=IVbp=)!v*j8Z{270A^ou3~S`mQ<~3s=TzB~KNIGC+g@rNF3u>iAx> zsILoG%;tN$cutBruRA0_^iK_;#|KH8zx2~i3H#y=)qe3Sbi~v|izxY2k=Zj*nj{4Q zfbAA9lC+X~0ablkdeDpj9R{^@?y0qP%_%)ty`rbjK{(LWLcr+$&P-0f{}t|nbD_Fu ze3kYaB z=f{M0OljbE5#R>t!YzU2Gn4lOMhx{B=ATG8DAcTsE3yRZbLk7`r%`d>xi7ZGI;9X{ z19j)sjD1rWaN3@b>+Ku#3F_({uDS>#mBU#_)24<~hLvPJ7Ml-=##3sJMpZ)E8D;ZA z5T_yuE_FU4os5*$dRlCm>^qF-3%>%%yE$Jqw7TCikV;{Bkiq<6ZPyEuDW@*R?WRZt z!YQX?p+2+xG@d{}H1w@Z`A@6%^@bI@sMEt2P--i6ZtC}p7zzjqzECwB3e=TXag_lKPY!udTm8mF4puJDE>2|GD+veD?cQ8-Ppw9R*Z@;t}G)8KVblUNU zw`QCqYgAospLwheC?<4FM0)YtJmmcLy|z>2>vk1&Jz=mOxh0axO+QKFA){#oWu*S1 z*dbxuB*A;|M*#+AW~ySU1Ha`Fih(H_g$-v(E1^XD{AU!MT+sqmyGbtlmwf;fFy4xH ztSR5zX04{S$W|olu3=hKuy2e>?|4zlWRlDk8McuGGp4hsVv(Mr%6Qu9&0GMoeO+1a zYP;rJk3BJ|_Cy4&ZZFTjIFtv#0jh*dh`f>ep;#kOYRpC^4p{bKW|eVqSFLUcJUAcp zWL@J{+|>t-BJ;m;!IQoWyOla@X4&$Els+NhrhY9whfhO1_$xnFRq5}s0ou;fzZGr8 zVa5K@aZXQjC(PXxkJ?`4&ikQnU*7S4`Q+PiP!f?clSue8EE+2%!=#bT(jWbYQb2q? z{TTpLd(i22mHqg;xo7D?p*JaBo*aO9kNH{3ffn`AdElL{vU=HM^v=E5Wd@iNg z)ItBd%m*jI2Ac9DcaOGDsVDFHS?eYBvlXWnKaRM!PfQ6Ld(9l)cg1pV)&6o&)=B?f z;k3w*nLmo&WLjuCv~+yhxalnqoQ_W)FsC^zSiVC01K)AFU91sWyOn0NEoRx_u)@;UuC0(?K%5JM zNb6hL3=_Y#pBXLtn~+qXgXQZ?sQF{2$xionAsER_Q*+j6rlLcbW@*U-m|K>iU4dKm zR{-y@>lH&&21#RGwaNse)-TzRBpwrn)!B0Mi1)iSkX2_!M6FS%dOlj)J?yAP=c>GK+ zSdvtn-86Y5!y@Bjf7$MOjH57%%BOG|WpFdq;1%z$wFd}tGS#W+{K>*{3@-qQu$Pme ziJ@h!1p6TQrgWBHDX7A44d`Vb6pxx5`egW)8rfX6I4c02Y#yyAJ2D2jLu>MDYAzmu zmrl%G%NfK+9>jA;*#?Hr%Lp9P3R%^=Kd?;|O^K^3aUV(@;}cv8gVbLpq|?TZ=zq`j z&e)fd`cm@EJ!V3>495mFW2lhT-zv_7rvq1JSMS5?aT&brq8yX-D3cH=e4P;5meCB3MrK!P$78B!}B1g2) zU%dQ3N@1##L4Y0p#f7&YYHn9Ac~>-vPMeXrZG{l%K_{cyq%U{1GjNT zd^8Ih1vvluLwISCn@zo>B>Iz?Y|)+E_UV;|fx|o@EjazKZ33HyIC!JwG5EGEB3!WM zVto9(0(H1~N#KS$lWIWWk&p*;33;V>3NxrqkRK`Zdc64!Enr$B)-;gz@+($+N75?qqc+#E!*<$JANPM$wth}KbU zpHBK4I`hx7C82XbO8mg2W?1_+tQrU&@m}>Hf!~1&H(zeHXoOJa~U8+t2&Yv{_;o zG>i@I>BOFG58<}p*xAkUqJzF$!oNT!N$v=|oScikHk0~3>2AgmRv(K0h6{!FyY!~{ zkfnOODXs_Di=Wesn6SnHw$JF>ZF6>arQkV;g5yQ^2B)#*r4<;bOY~fjuwlApgR=&q zrN(kIr^XIa%PGt)d4Dw~+-<5J>$Fwe>RYXidOGKn-1VTvOuLV5s%EUa%rjXi^c3PN z5VUgRPj@zrPw()nuNwAMv;S`Ch)Z!GO;QH4mzw?tj$7|1f$RX*9|eY_Zz4|-qox1| z@sP{AVSHVvav{#MXB=U|ERaJDLQ%n70ojR}q!>`nT{OXYd#}{9>|X#9G$oVdvt;g| zvf1!;=~PHUR8|Fxv$Jk>^JE1hHB6_SFPLXk*tU;K5v-j*g|uxp zvpl|%85Gk8DybU@HX0aOj#PQ}qo(G)?H^o>@FkU&rAVp03U4|*(k!Ws>KY-1c}{9C z?#Pef{a$}_$R=FP0J0hK7bu+3LlJN|lDdWn<}F>Y2qB{<#>m#M10EjJrUp^4{}^Th z;u^Bne1BeskCFO46 znjT)kGUYX>OIjvg6WCr-Goz}Pi3hxZ|n3$s^5Jr>-Oqj>lkYixx%(;+vr>= z>0wJTE#=DR3hnX9X78a)j9uf6APQF_Y~Rm4AFZ_BJ2b7DD$3p{V9~?EVkiVF{iXYv zH(WGv)Bet}2qYJS*^Syq6@Cr!PD?|I$r_n}O6D@ROxsu=vzgk<+@;hI*3)2@GmT3t zuP?uMepy1R8ajrzhn_?OW~Tw8`;m$R$GGcLHlShV7}j$jerc5!_i53g2CH_E%(%e} z^AahLF2_WSqUPyO#L1+5p9P|Z80((k&RQD}ScEY8&5+G1O&G3I<(Sqb@si-mGZg}Y zL}l4l-6#hNCD3!`R2NYu=BcsY;;D843tQEOl|a(0sIK}wazj6}v`^leE*_<4&dbl) z?pc0ycT99$!nI!Z!09TeRYWtWGsn8K=SqKm&Or8Tu5n@)(dlI@0;iKo%<>01(96|17%}#8jvNX$p>%9Hfi*OoMoD``&`rOj82}5 zxe*N*a`U>Xk7{t6uVhSoPZYH>UR)ymSFnRZuGp~E>{M05)7J+jI-_-|#3RM`d8YdF z22-PWMqdRA#pG8IQTF9Y`xX}y`^s+2y%A$imws3>#D)tXJx||Emp+Vk&~g>dI=^3t zJnJ%5Rn039Ail9sVDUsHaD>sWg3p zwZwesIfu)ctaq3B=!iacEDe}>rxni)fK~O01!f5P%02`imY3Z|>h=Kz_>HX?tV@_^ zxlA1FzZseExJBoEvfy_!=2!EXsDV2_73f=9_`xH;V7BwS_Lb}lCsA{av$Oe8FPc7A~|qij5M$?na` z>*FBFzBB}hyl-z9WT0ExF+Sl7QC?>$xXzTeu)XY<6oQZ_&0oEVDBh?W+*eBD2! zAe@|q7jhSbh=MsZ^mhU+PW4M2SX8%Q!&K|c+$9L?;o^s*kK4EGvuN8Td5!&D3`FIJ0Ot9~1Q#7jI~zu-m5BP5{8}?QL?xx8RKA{(%8zirs}; zhsA61`DPzdr6QJ<($f|{{ zkJBJP$#$mlvxf4EOugibZkNg&^O`5zU&GL7Xln&ect1d$TKX?WT?coCP}LJMlj&TG zWzAuGy43hD9Js$8)Usr4Vrg@(etdZZ2AN6F)dEmwP;>NDMQ99Db z{1xS-ib`stYrMz$9XD6uyk5nE-05#{=W zF)o9hsu__YzIsn~=##a)nCQy-RURjYqeJbD!*8flG@Ey}1Ts%nL&JtS=AlyO!WETRvH`xY_NwAXRqDP#Im;+7Sdp)3>Tbei1O<*VF!y}& zi3+qcI+T;`@P&}2TVwyl?^vTe#rlYN{e!#gowJ}`rIT|1#-(eqIlBaCl(2cPx{oAN*6owg*(uz;efD^IUmRZ%uh)p-Hjayz;Io7e%~vuY zJaMrkitNSYQv9tMUW540N(l=Xn#;#OE3Z*)UcQ^jBB}>KFM^?VB+q?-7ynvCWS_EF zRsL01@RcXM^<&vZo}b_d+!V>7;*TfUrrT@T@pA;^VfPSvA=S}IG0FYnu_Af#+s6{u!Eb||KgaK}n?elAose!eem zbG4L#v=-)e7547@EMxxrz&wg$rY4pGR*3XsA8Y%Jo}Q-&-a8U=0FA+rQX_nx`HSTv zLK)@O3xby(n)z1yC5~D%%VXcy(!Y=;REy>26r3O!f=JYQdnHL}cihgY5G~1dPloI4 z80}xXbXr{b=;z*Ul{CXZK`v+jbtW(fFc=@j39c+Bd!^y46c#HE^$GlIS@J-(gr7FY z->0*OASdDc%J<~_yb*2(TgYC$H}<{1qPUny+X`7x%$MmBrNZ&CobLfSNU`@xu96{L zO?#3f1>=qxgP*52(uI*t_gydGkvUpu+e$!QK5g&Ew=@EQ?=kvW>r=W6;tW$_l@X%| zfeY@$uquB6F@29H3qw}+(ablo)|c*u-7ZAoq9;e0fHl)p)Yp0*mk^nQ37$36pN;z5 z7V|+3j=BJuYifeNSc`j^YLe-?k|`qKtKE!5v_)`U?L&*2rt+w&&tPfvu390|mIGX9 z9Nv&i78AvFLJ;I%p))ZpMZaeUGN?FrAb|q=EM+?>9Nb3s`;*;Hzj^FA?yg^p4^@|r z7r5cFs@gL)<4v|oWccvCKR7+~?sAqf`!?K#ct{n2b8ycRDnb;e{cFpT*KRDHmilH5 zn+CSKhAlzvf&EBDQCtCg{%v+e<+B(7^j!c7{MU?8mvny~pKI{;##>b-8mjOCS0uw^ z5g$bJgjJ{+dwlFzF39#qAJQOyte@qyDu|oJ6C4t0wpK%764`r#8sDnjZa=OUDAY~m zVP{7UmJuxZ{C3|@8Qr_r{g(pHMH?=xz0aJmb7MkfnbNy<$gCAo!Bpw$9{AxF`U2nL zl3zFUl!=U5M|j?y6a0S1T}0ZtYC>B$w^s2zCODUuDOsF9HIx3?F#(&JIrnWZ*OcZ& z{a3>gRX?3CR1P|6qKGA|F5Ri;(I6v{0YLewalCME!g)-a>lUm;@ijBdKF%4m$YI)&CTTBI(cOdl1q^c`pd?Fyx9v z;+S>1KwyN}Bt2Ze*nEvvcr@1MICArK(V4f>$JvJaF=^bKwm5lKkDB#Xc5eI`yXvOR zx)Q804xS%=Tc!Zm*}+>sO1&@oue&fA*2|9RzF_n$$a|M`9!5F*UG;YXD@o^zrBpW4dsztX{HLDSV2!aO-yA zTfybs8=QPz+AS_hSp1fAQi)Al2Sxhvj+!qNb@hZ??mJXvw9!^hcd4D~Bhdl(7;0Q^ zbth0&;cKINV%HHmNiJb2mNrgoaBkr7daU^nM`=T;a%Iw)HxhpxA@YrD#I_L`b~XZs=?}u{3Hc@9rC1EsRF@W$d3X9;@bZ8a^ZnQ3g*_# zyEl!=GfC3!E27-G>Jc8_K!HW+<6xKpX?APj_SuMuY|tkLoXU>A=~n-&kvsxZfn4L% zah`5ls5Z-fb-l0zl!W%uIYZ||Mvmbz!AI#JV#mz(FJT}5#7Q^Oy!J!2&?U#q%!kII zAu-2dx#l;KK8$x~HxfVTLYrlV4^z+1AtoQ_ZZ}R=ZRfvboGD&^PkM){TVK3fWI3N- z?^yGC{nzSx$n_s%8qVzh(fec5iQc2E8_Usw?jzuBMqU$f1R>KAB3gR5+e{Xz+I;-r zT#B8I%Y_$zpqz16yMpYw`NQ<)<}V`2y_OfuY62N!Yo@$czw9L&0%>;ApMHA$BK73q zc!rdEr<6p=qj0jw5|DmikCIxv)zkOkr)ZBxZiy|k4_~>C19EDoK@O(0=F?k{3Q$U3 z5vUv%H0_Ryk6+@Aj2a0UC@wC}uKBVeMLF&)mOd70_UX%``$N^7dkm`l5re6N7V7HH zC;#d!BX_wBvafl_s!OA+-2i;dph>LmSgCZy7&2`KZ<(ohrYC-H-q!S25>ZQzg}wcJ zJ{)@7@+s#&(I&rLvhJ9Ba!hpUeH>EZ`2*nmS?OYidTVaLuh`ewT2WmKpNpbVoVn!f z{Z~mr#Yc%yWkVl!+R%A@+!{692yLBt*f!SJ@9Qp4(C2VGeW{|Dw(5mGnaJE%8xtut zi1I95u8_^s!Ul-w_=F>mN4SghZn_OJqi- zmD=&OLtwIi9g;>wL)8MwQZcUY=Fzf7HZppT#y3^2zMX1QF>|Xu6;Fxsb(7wKL{Kv+ z+P*%oLEM^1>PYimT7`5h2@4yMp`eE9ho*CS1yDM0A)eY#vS`W*dn zK1`1plYrRak#ah?LG2aWtcfg(pul~mg`D|#%e|Jym(?1ByZ1Nt{72se_Ks~1S4A!+ zF-nT=kb(RB9?mG{KFQhyUrwI5%)0OEaE`WuPTTXDcQyK(uth*0j2?NC+E_j6kKH)E zQ4;L4d8Q6k;r^A{wUCP1r`Y*OqIh)=k`o4}1^W0*%qluG0ei!M$=I>v-MdV9kf>~X zE%_hK3;0K;!Lb#WO+J3E_J-F5Wg*+QA(Xzr2FC!PjLh0uV8;*k$4vScqQ%o4Upl1o zQ;?qxrC;@juzAD%YzUw1zJg`mE~iDqC-*GRb1dc!SwO?<$m!_*`Whm!O~?NEy)D1Z zl&mWxc;*#deP+K$HcwYW3psgQy4?X-}Vf2?+|kor!^ zwANzYW+!ss{xi0?Ke@mGJSmLOEw4f254CewC8+)DTj}}S`EVf3?D<*md2s!g_ZBLJ za8MPR9eqngJ)zCq6vi_)hy^r{q2t?)QD=MRn#$Lx(Dl~y(32hjX@9caN=gYSyQq!Z*i?M23OAo~SlM_yCB~PRBoLjFJ0i3_c~^=N@%O<#X&XY_T<9GY|8`J78H`WC2ot@e@Z(~($7q}&M07eCdX4bgj` zBFELG9k1&xY9^>)qCyA{hyZzA@-b{cM_ZNC6};4jNNHH{+4+>g_9tvQ9)`X=>fCST z$DvnDp6aCzAuppLl#46V#Jcz$G<#{&c2o0f?fYi8bKWx9O%m7I;za0KujZ{d)|_{M ze`6)J(>YSHwoG11YIo5~ouctBR~A*ZUp?BtYwdDr^KP)(&z<$hK5hb!V~TS5apbX=_u zUXGs+n?p*$_Ylqy9`X;_R*aOCmns-P>W{uK+1q*?@`0T7Oz$b$A0RPn%A-gl?OEy0u4^ax2sx$sS1*m zhJPPt|K$B}Zej`u0plXNTLB>CnmSTezSiYmL%;+xc{C0Ns#3x$d*dndx z<$b23qv1t+2M2gPqwoX2n2y_uh9<=MzEs`a<*CM|^v!UK5_;O{-wYuK=6X2F|5 z^tpU}E80iWyKQVw!i4lV2EIvlbtu~6oBjD~Q|Q7T!ez_nK)$xs556XuCGS+;Uy!}{ zyC=7(L?Fj><;yw$@S-?V08?jY2KN}Gc!oL8b-wj^)-Tr0%@eow4dgX{aszo!6~)%* zvg9j|YrEiB_HmA2CH9owERg5L79_xDVw3{&dx#lQp4ZpcH%BQQ7It=#IX4)}fUDUK zd{YMp3{C(0x@4h_n|S{YNQXS5hhX0Te?{x3*xw}WgT|rqCe3@^x&p?uQ^UaPRENmvT|WQcV`K&GOTUJ!4A@8n5HActSwpD#zhx~ zO*gWrHU9p^i_MgnfL9REOu|e1#afNoZI9NbnpW9{174Y%avfF9zmo}nEMsYZU$EnH z)XD37*|Q10LucZD$+ft+Xkn-l&xzsdI$XuBXuskE&Sb@TXS<=V;EpS;MITi+aDQ+< zyy5m=Axpowy*a8;l9ZQ6#fjoZl8-yTjjmC7KD>DH7%vNXgF363uECR#mzVjqo2ipA zHksUjK+=2Et+2NA@1KAEc;F(JDIo6zp=Qe7{H%qt$@)(AN2&uDR0plcWS;v=O~3R1 zv4F75mLKSSPXO#4#4GJbn2hv^T#u{~Xa1%Ner>@A3iQBlVAgPz=6 zCTA5r9xrZ7`7L8?C9U@FH6N8-?l}bvTj%)o#rU6al-31NJc@XaDK=+wK3I`e$)nUF zm+<^GM2lIfcUKu5C8f6<<`DZwxs-8E(};t%{(>C;p)#X}Fraxc zXXnndvorU3%sc-!d6|2};eQ*>pMbd0`6V*v7}d{O)6_)NiD8WF#jKeP*F0*e#WN-_ z@ZL~0rbC+Jk9NPV$A8e?Hi~K79brhF+3Q9}HCDXVN&PQ}OtEah(+rT!&3$|fyV z-$U$AKIe8T=V->r3AJ5PVIIXc?sg>859nE2W5aZG__-b<-~M|uA}maX{=YWPuz@eA z5)*WU33^+fewhRl!J&U2l0n^M;o*t-mCy1N{8wh}Z`~Ya{(rWCd2)pF;=gU>-*eYN z8DC79kA%}}chP_A2m@WJ;NO=V{(iWD_Zg%4c+9RPI9vXz<+s(pCHP08n*SWb|9UiV zU-f^_2e{mjW6a_b|2R$md^s3E{}(`4qP_k7qcPBd@qYsPuUi-Y4d}n|D*XeH%ID&c zO~PrV^*;fs|6hRI&-Y(pmg4bWTOCHTamZ8!_J3>m&zwH?f6wF8evf5=>>VBdhs6F5 pfE)1(%gevAJXf0j6VUeEy)D&uk*(|=+E|zYR@PK1S1^75{{U(H^7;S( diff --git a/planning/obstacle_avoidance_planner/media/trajectory_with_footprint.png b/planning/obstacle_avoidance_planner/media/trajectory_with_footprint.png deleted file mode 100644 index 1dce802e1c27a2905ae6b76dea2a7260914a9975..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 129006 zcmY(r1yoy27dDC%*W&JlBE{X^in~LgxI4w&tw4d|?hZkV6nA$m8VUq=z2W`-f8Bet zR!(eY&&-x*k31()DoQeF$VA9cP*7-cvXW|0Q1DAoP|$sd@Q`ne@1>?7FCSdR z4`0M@k&w@XZc;jK>W&s}o&XnfC`$)Nd-E@@W-jLD4z5;?ZfCIF!jM87)*3o)5-#Qd zH)}@+3Jq&}bI6xaQ0%PiZ2N6ZY^(=ak!*YiX~h(f>#tx|&i%-6PHs?XQkMJ?KNJ)N zl$@lPhF8|fhOM31ziiOmS({Kq8g*2Ay~Zcawyzst2W8JR@Z`0^NwcTm8Y~URxdqWr zV5cZNB5J=gR=18DJh90()S$)O_xjAZA5bAQqL^kMX?ncsfP;f9+#?F`#LCKa0?lj8 zp5NQo4HsI}4BhgX1%GFO)-QJwaXzVjDv!pZzj&iZ+;g4W=EI<`kj)`~n=->e4#Qz< z=(>n=RAKnZ57uvSa0agep>Jig;IwOv_DAS)*XvKn-*y9h?S`I4wYz#JGI`qkUmoj8 zB@ijY2iBiS;$7f3&}R0JDz)1##)#LS7be6!rD7u!w%)v^4Kc-0^K1QYDxrMep0>!H zltVGa5h*8yU8hMgLl#J@kem%1Hrm~*p2&%blT8#6+1P1xh=s9>k&qVuD+#$oex%x7 zMSNNZ3Ab3Tbo$)EPh&eTp48}JizCjE57h7Ebx?#7)MXeGyWxjoN*tA!<|I{cQNCBi zey=DH@cNu%?%4Hk0Od_J$&X|ohFKu8o+WU|jQC#Yze}tj(vsxR;NT!c)?{F%cI~OI zM^--gC!=NYf9e-P` z-vU36O&QATL$Z(Bj$)eD*2cHUa0&OxnO&R|y&Xk7lCrs}iSvJ*-$CWKQE^{Rw7L7f z7m^}hOl=>qPGdl<+8KV@;Q?NKA8$tTt8$G2b7NPRf58xrc%<0pcwB@HILZ&K0s=l| zU|L#QvUdM*Vu5*opd2lFZ;XXu@J5O70uX!E+X){%(JnP6@Be-Ht zwwH@ia_icArq%Oo6Vgg3re#8=>$_O^9h$zXQwm#x5&Y=?#@R3DofUXkCUHVKs0v%u zmy{Wx(or1bS7cWtZKf$x*>k1|G@m+O=NvyVBoiA4{?}GX8od z#d|Y**@K;~(#YMvH6=6LCOX-F7@79lX+7~zc3FO-2!r@lvRgXqaUKOq1M6{b7z$?y zZJ7Akw0tkq3=2C=5yTCgn^A3AJBLWMl!Iw0Nso(hrj}D}e zV2MR3{6^T&>=f%U1s$oy&oT4O#|M3^0;G3!U(d)PC?{a^jpA@hZQK>;9a7Y)uF_b{Fl97Ec6SJV@*Dpf<*Q;ENcH*7HM>Zy-mZ5T! zRj@N-hDY+WTx`2c_Rzo2WH;-XA0)&Dg&~$me78i1h9oj&|Hb$1FnoSMdZ?~=Y)N<5 z#nS)O^;7=Srq^y9w#aE+xFi-PlJg^)?dMORwouFsh_i`Z4yt5*D365r)+=8?e!!M2 zo_Ln9{{p!ien0)f*|}MZzt(sb{0qAMMVO6W)~NDwDMY%LXGlYbhux$wLK%-?&Pq1CW2vh+;u3g(us}y#s+M zE=Xe>e~%U_eNu0(GWFk`mNg?I!_-VYTnulhR_F7rZ}$SNSTaQZzdKHt7a~3>hQ#+U zaMpPr--{1c~;KI-G0YI>1M<;9Xdxo+N;&WfC(>Bc6?<;ghMn<8f zuR1jUNf3l|-&xI&<`Hn$QmlL&@r^Q+KzcKs=N$>)KZ6e7H{hIOxw*N?h~{Nksn9P^ z8mBIA*Bq|~i5*ef8UKShYN=k}$64FYgb#tAAYxR+`>qw0AexyFzFCKOBHRULaa0ln zpyCac;l=2@&s_x(VsAr%|BKZWnwrY^!*e79wvc!yV4iI!>%kB@~14u3!}`(2@X zkXY<3YL~t4+f_1Uf#@}WqmcvRKfI#FY7j;D6M`7-hFb^^0_9JxTd($`W^OOXSjIr! z{~-(X4=4N3lh?nr3sME-ler?@mcM+TwBF?whzP&lo1JcS&{6)xG);JTcz6d=$PcF9 zAPtIpU~JGqv=h0_&Byod2@wS3T;M;zlp~=H><>;JpTulCMmEXGUh;&j-O=9OUR3C#Wz>JcJL48WpZ^kYc)E1xA$2Zq9%eBu z*ftr(As1XVSFQDP6bQIH$aK7fm=G|%@jfuf=un{{0MJhnaf)rZbc)^k-W38a8Kkjz z`C#BSHy78y;KAgQ5K@DrNEkoKf7$h9Kg~FG%J{$PuvW<<>ivZoxw)3^?(YBVO@HD; zd>TYy_^!@V``z6~*Np;}8KJh+c}vrN@2w4ABhSG5HC*M19v0m&4hQ#z>8kzs^q++w zUXqJW%Y*Yx{S}-u19)Tq&>uhdGEGvN7+Gb^}adEF~2+A zAQpvW=N+eTHc5dhqwUlWy5d>(KYxz?7nLrTQhE>#Av{c4VnwdJM(L%=9ed9%#0NDU zN1R+b!<4)P7t1)SLC?tvRNfr}jC{a{Ak!KHdZ(AiNmuHvms697;Z#WG5PaB6hC~6u z$M^ZiyJSoW`~q+ehWQ<4duLbr`K!#??q|YiK>GhlRgj6)yQA7zScH?m-4Fd|@+|MS z2Tv^2o(QWC>*2TSdJ{p%RWLur7WKWR%y;p5on9fufx7Mw*GY6 z=pqfhxo_jdwOo?8KMYz}xt;Yw%>d^*E$#as_by%(82VXlS+b>EYmdsTy?#H-KWbyG*^oOXLT5ruB3lt7DdILI^1(-$4281a zng1VD_0wDHsZ-UGt&K>RmD9!Lz|dv{=FWA+1MvTbYl34_aGApsFxQ7|v+*=d1js*z z_BX1u@x|}FW@Tj&in%3~*zifZ+>e=S4=* zugln3;D>+pr?YKd9i0NaYoyIL75uiw%?26qEg|)heSC-b-;qhVtd80eV0%mb9PcDw zFA{{#gl~m!3sZwhhgND|`Vr8A$5#B>{5n=v4q}W+Kr$k$M@?&#OBnu%am^P;mFmxj zGWyx04UF2zOw0!!Ro#9aBTL=>_`?iKMt<(mTaVRi*?wJjn~fOuZcL=}!)KxxREhaVN|@ z*2Zt-?GASnH81W@^D(;77h}1n*)fNJwX>Fq;?fr5MiK88&u*U$i*9?7i|d(9*d~sY ztF#@VG4wg^+qU)2s-?#?V$(_J!m&@Smz6Q_2xgVXDK+(Jn&hb*z{ad}~%DY;|JoBVzF9?ULyz1pdfgq~oQg z*?&_)u5tL< z{cRqmDZ<&c?*qf7qLo0q>k7^CO+-LrFr|VN?cbBz?pyfa~+nzriKz^ACC zLyt{Q{GBorg_WI7^qY;Rw$1beX5#spO%}%>h zwdd)Z4R3oCgb2CPYEk-P5kCdD?^_~Kp?|bd!(mP^PN>UcZJoyXCmQ7V6rs+ zfLmc~GTIciuVS}XV!JB&^8ksm=20GeG9rFbu9R70`rUxIHH*+)ewvPgL@k z`d9kgO!W}iyh4yCSH0n^DBiTAUVnX7bh^^!Q9kj)Kxslpu0tnQAhpz?iMQ}>nEafk`P}8za`w%*YU6nI{H>S~}f?g}sbr3^$MOQ92Xe zhVQOapZX_{t&bl867|WZS?3o@g{SB8|Lh1lLtuDeotl6%q37z95nBQ%Uv8n2dfhLcU@PQxgw6hi4%77+Q!H=TM5TY$G;zs=IhCJs}h~SvB{KQAt{g~;*^p& z2>aJvRT`jH+y_TWIXq183)!c0Z=Gqb*ln%nUxkXMLZ2^sca?L5n3#*%UPTN@AhQfE z_l>hQ17p5b5+b3yIiID3PxmdP*C6tM_(XrzTJouu94YdbTgSe#c=@^7q*Q=s_?cx@ z%Ukzat(RrDrz8f7GkRmK(U^Vb9T0Hm?_DiW)#p&_9jYu-jE-0su3FGA`l)f@P6Ljn zB4|HNR{vOSq38PRv`rz=-!xV|dkHStXRO@=?8Vq} zQHnS7z;u$~eFneEsIF@u`T(uI+#gX|0wY*Ev z$3QtsrbO5(FZV9K+S^uTeogolQ+RU-U@dpGYFj+1l2jTLYHO)eoB#CxUkG)%A1?+% zme{;Xod<%%^J(0ZrjfMph1wJzuVG-51A_#0icaxb&{z0#!*};j{^;( zIs^3APomWCpZt|}vwV#o0=zx$Yc*8NY(3ecxV{-GG& zx=yQun`RkAtv!c6*&$eTtZA}5`Enkl@gMs-!WLhB2Jf^iwyf#FS^Y#S1wE`B>sJF6 z>tzHqpt)Fxm1;FcjPSWj8%B$RMPdpKi8kT$FI88mL1|XatKS3g^gB2^(MfloRW;$L?Bgi>>pQlwTHAztV2nD~PNK-)J>#b&rO$z`QbrdlEn6 zv(2;D1(v5q{rVI+l%C`4eD#USmdJ4jKa{I(o*f?Z6q)lU^7QI}b86!@C1KAoKqPnl z>E!FiIxtu3keCYVfq#! z)%YZtkVblz;ATrx9NAbe2!%6g#7yYa+FVn7haRMo)+5oP%46H#D3B|&7%eTLezNX= z=i=VD*k-rYywo+XFMJVv#MG$8c~Q0MjC7(?vUzF!n>|Vssa}h7ku>hLs>Lk#vC*iM z9YPNCBc_ALS5^Tf5=%;WTF$-(nf+b6d(e&t2y`Uv#WQSBJlLYBGl^gG~A>NmOl z32#aJhA7K{z*Cj4E%ccTF^+$RXs$7p<(mU8h#bx*{$DqL$Jtrai_S?GxefhVLi?#F zS;Vc`%!^>gW1+wyBN=3*J~?z?KbY*Tt-jlG(8lC0!pa%`A(KE^HU8DwRaFyN$f?Jj z{k+<=?vjvpOpd3(@zcy^=ZR{MH_s5X!VIT(H58zQ^v!~PTVFv zi;AR9i)uyl+6A*$svP5;Q-j;LM}>X9CYwCBoP~1Y*r#g1Y17!~Jeq-_MM*=T7BpkE z-*}67`Ij>f+g#m_qiW1Da|^v8)D-2sRKh!a{cXLF3QuC~w4kcog+<}$YQOtU`xIt% zyUuCr1$1dVk0z9FwQ%{DNcv)$HSU?RU$E&hI&SWztJhjz{4Y*skF8(-R1=nfh;dvR zi=+vcIuop!=34MCHW0u=UPVJGM3p{h*Vsl{ZM0-#rwk3r1O*o~s8pyzj90Dii)?Ob z_hrNxZOCTuMq|~JWGkkr7n*G(w+-}aUu)Z+Y?_YC;8kol(jsk4k9D!7vVZ7_t3T~F z@-;d(&>dID*2L5V%8raMIwkTp#MA|@AwjTW@825s76H0=9qF7j-#zBY_5=1++=4yH zE0-QUco#Nl-#Qm2g^6nw3LphvFTFgv^|tW>7uq+wFuETeTi-I`w`^o8yg+7d); zJ#N=dzk;04j*JB>n^^)DL$%u%->RY(URqzOkaBMt{Djm`s?JXCCMSDpTr;&HMZl|1 z8n3S&t%XL$(xlG3eY<&(H!Z<yCc=wK>Nhth0OEHo;9Dj&r25N8j&yM1can zn;Q;WWQQO6Hik}cQ9a2UeT1g3(l@p(J!RLr&cG(xhIc;U**_O|w@6W86<%8I8rR+m zPnPD}89Y86(C|9pNZ!$dw$K1UEd#ASS!g576pI;Vnw{Iz6T(1$Yx0A!02409~<)Y%*5?H)I5W6_dfb|g(@_Qa&{3I6 zbCUgSw~En*H;%h-wL*YTSg|rD%vzzSwzCj^WQ@4i$V3@rjiv?06o08N1s;1 zjmCNQA4WZ@eRo~b3&i(xL)UyStuVifpj z|J&Zl&LY4!ZEcch0_6sfB|_P2TvuQnqmOwY0I-6Ex{N5b^*zhr@^VKiu&x4{bATep z?&5VGhlRQHJ1@y6jwKg2zwB}uiEjG7>`d+P?zTUs6 zBCqyqT56FfAk9}!$ScQwJgJx@a@YE_{xKejvVV7#ekUJ=&d~~8`>t!_Q<$twVNlV9slpkUCST%Hy(Y!;ae(@F(4fdee|4!^z^P99r(|3N9-DXuHp`&bJ z@x`maU4+|L!<h87}{u7&#_rtQV&qh7NcZXQYG-&j8MdI{2)ZF z+N{K!!8?fl4t-Q_Fahtv9m$;QT;q0mW6K6^zz7dntD-v5sQ?#i5&y#WQ}lqH&jxZa z@+PteBVtTbOf^yKrhTtgaZ0i8xYjfr3Jre(80;HQkga0Fd4SJ9)>|h^!if}X85!bA zaN|mY6naAkg&2$_hxJjz60z{h`cFBvr3hXcIjXW1n$dnl#Uu;pT0rtDGPM$gTb{KU zLG_q-P!Rxo0cE{=H(zl;@{g&lka86YffC#}Mq3A`5{{_Qmxg)=mC8VCBAnlXsX}8R zpJHg_=;Nl$GBQSKaSReT!+MM<gTCjTjy4WoY+f}0WR z$BIC27lvo%IJHg0wmSB)wj(xxcgk*a51*Xw!&@)l^bg;7Sztqq?|m&umNYYqPZ>}k z`f0F$BXQ^OOT; z0S6bYebhBScFp%)t`l_oVk))BKLl>L86T{M3J=Yp$4~Q4=5pz;SARQl4-;yT%* z6BKkjupkP5-oqH7zan(SY{Q}D$sM#uh7AeN9c?9t`zgjLDLN0P3oGW@>WkaJ19IHb zwNrqy^7V2WhOVN^d~|pt?*%TZ?`J7o9)18ZQ(h80gEg>Pt0(Q0q(-?I4DL`$jbBbo z?9^GM7A|3EPfw{NvMOI1LtL(XBB%aDw9}M8N^l0UA$rG$ofY1hoy*h z!lnK&ClR14jSR8nl|}0`vi;cqt7P|)FOh~VU*DwnN)9daBFcH3MtYxz747rHlu8|A zzgV_64pvI^va(%WQ~k(%n4U(=6*Hn#DwS zwH;Fj86SUPl)2Z3H~-%f zkJCGX>-^UvJiHdIF#wV7R6}-}eZY{0Wc2!Q#m<8tIhnB1J_M<^Sw`S|v@p!4^qlbH zCGxHbBm~CxlYFwQlMz{=(|qo|4~M&IT7mJ(cRtf@+S5R@4K{Lp(kqq7A@fS2s~ArU z>#8ZXX7?Z(XPqdzkxIldk%;W83vlE_v|CmDrdX zHS26Apd1+@6GxCHMawpqD1MS`iVead0-!6GCQ4f|imjoCSw!R7617ojWnt>mKU7GA z1{=0@P{=l2e)h9jE41kZm6#AF65ZqD7(vm%$@T<13g+0G6*XdtNSQfjw0Xx8D}Kah z`OBQOYqYCPbBmW_hQ;?+IwQ}-q?J#jCbYXvetJ3JilpMyI$wrDTBHn_spY7X(XX8U;AlSUw9>=(i+rZ>?A_2)UVB>QBfa zN3%h_VN7`jv*&S?YSGmlWxQ2X8&-Q{txCY1@}Aaxuxu0nJ=+WW;aF& zMJ!JVW5F4baZ?C8nr*}^Gbxye5PxLq(Al@vfq7aX3?3fv#%#>Fb25tFh7L`I3%r^& z?~M-I?GHWE7(S66~TS-e;;rN-w< zTY^z)_F>IRmO8G9IzH)iocOx46;uM1O~_8}zy5wCn>tveTBsE8mu`^ChB0J*P@ z4J`zR6%`g1Hg*vMzQo!j125Iww1hU*ewzRt9!bjvu!b(r*ZQ59CoPE|S}Xmp4qjA) zsAjz@ZJEt&K)8OGWc@#Fq+r2aGyT}OeWw#eRMbH_Y?4xis+gjBQ@hy@eMP!L5$0jb z718E48FBPG%am!2b#YJ~Y!EjFa19Q32s>9r0z=FR_L#zy>}5HN7#Nv8Q7BScJT=OY zICf(wt2c-;C`KtDa3D8J&{L1VRC0#RTNySxB-0js+s3n&Px{uvh6S6n_*m5GT$x?6 zyv;vgLs|`cQWXCKo5K3ugI9RxvttpBt zo6e}_M-lymMc~4`Bp?!9q6s~UI)oKfE-92Zw!w)lUM?uk_m^pd++}48>+FZ)9XjWY z#8y@@YDBq;?+lC|lLzEd$F6wA&=^VjntjQ@bHGCntUi5oiD@oG$e|$Oe}^;zO>nLM zqs#RF<0{)G`6MckwPeKTUNOF!zfu@(Zker#<; z5)*KAy$9>!uQ%IVn~KvT7Tz|@s znWK#yAI6w7r<5=ynH@L|4Ww5mgR45&w!^fXH2<~xPV2p@jUOpT>jvHk>smpcPjo$L zIU_JNo_g6&8pkfh?$(|_dr?@|o*_fevX1H?52d!1cBbYUPh&E%@A)oG#3Y3txW6z% zN@}xu0}oq&%AbP*(0}vRF&_@FAMJM1{kyJ;Smn*^W?4YxzpBgj;J;AOB3Ej-2Xh4Be%a#U zFD6BkJya4dI6hW!j7lpkhl#&&bezq|Sx=I(1w&A>W(evJ1fsE2aI-WK0P{jRw;Wga zY&z{HJ_{mB=bdJb%99~kxrq<4A7TQbFjjF5zC8d|Z3uLA@#*P*@iTi^tUiFz$$rQD?uGDo|4kmDyHxv$GOn!LZMY1`} zvnG-djuR$?0+F?Z`lLFMqWlL9Qk+F{wT);aVN&eWP8p&2Rr0;@Gba$?s{##@7^@g> zeHa^C)WxJ9cYq~{*+1GYdsVL^xPpW+&S3h~9NoREOmbK`@>f0hGn!!L@<#zaiH|ke zA^}DRu*Z#bxxOy%JdIs71v+<7VXzEVQ4K@(Egb?VH zy5mE3G<)FlotA*am*%xZv=#zoJ{`|%kH2pH$n?kYo4V#VjTV-XgS#FnHZApSmgP%4 zcZP2|FTAEEONJNPcS95y_un*iiP60&m&#{n{d0Q8)OB-AuU3$#vi)!(sTon~nOEvQ zyn1(GYlT7ZcTybBw9~CkJr1|avi_mivbnGFwz#`8MA%27(kKl)U9nVbAuzm3Y9J(? z$Ym$&Ditmc;T#1KNCMa8FxGyhst%ecHLUtoQE|Ba()f~G0Y4ac!0p=PSpdk?`a?an zi#H!r#oQg+__~%p>4yp;3oAz=5{sASmrhy#B+?SCs=kMl9v67gYi_Y_sd9h+4-FLt zOC3P_oq|TY4oSj^m316(4wVfxlM_h}I|L^VphF<3;~{IxQ>Q?zPQ2$rU!NSN=kRB+ zPTkIa8xPmR#4K+(^ZVe?5aASPSUG)M$&g~C+O++<{Gi}*CXo!iI9fPv@)2eq^5;F6 zONXBY?9=UX`(mSBBPNvvb?Xe6KSC8{742F^mvxe*B>)1@3pR0_8p@@T_8Zx&9%Ae5Eq)Hr?s9Z&zkSOk(!e=bkLjTqF+wtygg+;Sh zsf1HWXgC6Xn6*e2MOY3(LJIAY(v*pf_$Wpc7(U{Hepi#A>xj7kLxiT7kA*#8BFKt} zZ$U4pbM|ap%o1P7%{7=Y2sJBfHcu2ggjD|{&*E|qCi8h52SA{f?&)PQ*=J;I32c}Y zr&Mldjd|I{(7lVsvCkZdnKBh@Qvj0X;pP4zQr~;cRxWgW&f1S-n81)Y;m6c@9xL?^ z8Ht|g-tK%^4p66446bRk|J)0_xNv4R?n1TG)`4uF$o*ZExzvgFw~F{+&%Rzp;2wfL zBP}F)OqTP}W75`xsB-dDh| z{}aF7?cjQU?QFQ9f{a}0Y{nC$debSfC6^BmBome_-_}?x>7>>zpr#t$ri1Z>B8UvW z;I%|xG5ydqe+kXj)MGRxwbM3t*R}>i*pbuGWZ=F~ouT9}@lD1kw*e}}(F&16rJ#t) z9oc{m!9(Vg>pGV_qshzjI2k{tcv%5+4KElvU9`#DGbGj~1PLQeZrPEIxAdkzCqP%nUXg!7WLtqk)OROzq3#vb6aVt4cCU;)?M0a5Sg?K%TW(7*Zk<;eZCw- zj?;?-IEo?5rTbA%XbG3#V$L_SR%6OMENh82s#435xU{)5QRfkAs5UE0D66@hVGl)H zaE6&%xoCy)YKGR!#P)KWnkD+xj&myJWXZ8PMeg#a(@VFHKuEx4rL>A1Q+kJmZa<|R z;2CH8Q>ly%r9gxFt~IzT23-jB_n=9$e~G=LdW-19UT0fl$Zc3FN{T0d6_wS^Fivy+oH($ZLrOJ=N8YL^7o^F=%^d}S*Kb%N5|IPw#9DE>Vi36k62cCC= zF;RxY@j~qg#D;q-Jk=I(JONbCsLdY`2BUKlwGyLK=dCblwST zef|SHz)H~BeA7UR~_(mKwUa1RiN?Eh1IPmRgtEndM4U>5Lxnc;~Lc=#G6irE7 zld`h=5*)F@J>`;=zq$I0fv_4L=9uPsInkID)cPo_6^ku0;N>!sXyv$pL?#3l+}8k{ zj~_I9EuuYmkbo9rEjH_{V)3+H?iCyt4;OPEk4d4Hxmp!vOpQ!OEaD}M7zLQCjKS5@7 zMb5TtnA3iu7{2^RBF*_l(v*4($8xG7<`6-+7;|o^mTgjroaJT{jU4M-5r<<2A@>Yl zEr+9?r4n$FH3`hOkVNw@)E4}bD4tOyDW{Ot-(N3>Gi1l*ew!$%NYWXlJD$uB-zNUU z0+TIg3b4W*zl(W{IM-0mM9iU0kvnxT?m9SBcSReHUyu@$qjLDUKXbegNIS7s23gjB zo<_}BHiQ4Julkv&h+t14j9amQwP407u^%aZH?Q!-i>>Ztsg=Ms=|+=za)RCURj`}E ze*5`!3-F@cJ=N+*?kV{9b?e@5@=fFo%V&rOB_iaV<-jv_;G6LEYX)Qnez9>Tte1Yf zaprJd?KnaDdz+pEXM448@9O*I!%2}`ZI5Djs6e^~ew69Q<2_A$CnUAJ*XJBb> zNiQfctY_}Hpm&#LagieNI<+{Hd&7T~S>Docakn}~fznhpby}?wQ<_DpX$tncRTJWA zDZH%EHpja&*$;EAQ<%bxv266K{;l2n-TJ9d$|r}($mWZesMe30;u`d(%DPp5@!NQy zK+};!i-g!hu ziSrl<2>XWHa{V;#*tu1?m)d`DDWEjAoj8vLRU0>#z@LBpDGRBOJ$~+~&Au{F7WBhX z?~T+Vec0m4@gp1yrZhJn&mRxY@>NN?%GPE@oBs4w_%%w$96HMbm4EC6H0{(NV)qw*W#1rXf2fj6q5;^kD}P(tZOmRJAEzPEC^%s|J*`TG~ zJ|qjR?Y9&Ok#1dzhhoKIn+Sr)CVcftjW*Ld@&yx>sR0wrEDkF5C&i@C8-vzD}P-PXJVsYl0oJhj-NvKt%GWcbPo^Y5D ziO{IftT9cBbU)ibNtey&IwEB%Cdrz8pyWr4Jo>H%Td@GIiZg?V0|3gkuM`2Zf`Nb8zxv zbL*KQZb8J-f&EVh_SNgz^B2LFZr0nxh*Ks6!#AF-2*$8e(#AUr z`G3siE&T=7Xy`!R7kJ!)KbsWxDX-xk7~9K2XM|Zb+r&@hFB8uc=`{Cl(+4!_W8M4>N{KavcoGMvroQ(b}7aX`!jaLVcUkIcAW_H^VT zt2%;urVjQ;JakDm=_KkjBhg8)2hjs2{)sLZhai_>N|EF) zNJ3V8WxZy;*?k(UH%xLy@SCB2qa;8|B;sUAHDM|;AxIQwHKr}s{A}`r^EecQ%-bBX z%i~NnvDgU5)EI57PwA{cq>RrtE*N)w7Sug5c*B)6l{HjRb(z;7zR@IihM$hs@Wd)C z9M8rP;>kvZ2xD^tKSoTve5_K#{VS(qnDiL#2zd9odf~zXG?V*EbROVFmNv)#dxw?3 zQqy8+TO-`IQ_zlgM77dEpgg(Xv zhH3I}DghZnNEhGw3^p9>Y8@x?A=m^tmYafrxh}5O-MS9K#E*q8bcp|*<`AQN^Jk(A zUticVo}m3l0OP$W)!8NJdnJZM2~~Fz<78l*CnRs`jQTG;hrV!ePyb$~7;##9|DnzQO8TM$Ji$D1(GzMS&==HyY_Vu?URl$)_m|888|G1D58pco-S+Dl%(u>em zkamL0IgYAA7qatPunyl$)~C>@KAE3sA_ZdYbBXiX&+niZPp3es8o8rZCb z@u*os40eoD4pk~W)54;ne_q{;pjmn(_&d*nASI_~n>9En^nJ|{da_64g zQMvYd$@11v`$Vqw|Gh75BftOu-0Rki)_`o^a!P?V>0u5!WoUxXuCp=iQ(&5mwtwA) z;6gY>CPxXUf4lj|=D+f^zH^3ZHwNE!2Xdauea|)Us*orpW8MiwWa_|v%p}pXnZxhe z2ejBL(<)ocg|C&cN~pp|(`J2#oHy>0ybKicWFF)a^b&AIt088n?NqoX$L#rfv}$NB z{!uDi=v~_%NjO8zMCOUOGsz7Ae)~wwv9{5lGAmk?IKBsBCjg4+9fXxRF4&TtFWcy| zisbETw*BkEUL3?trDNZ`;(XG?AvfVHuZMDhn2Rs4a*{1icbFE(c`K}T4%svgKZ1xP z<;@0>7=rrc#Riu9)1A3b{3@uJBmji)(sm|I!p!_~Xi2zs#cWkjeTZyKarU2zlw#w} z3O-XtQ_Zr9^Ethp3ZV*o*l*P2VdWuHkvXUncer zgi-y2Ay}lf=Kq6@0&+IUoj}W-sKynn6)nse(yVK5Ko3{M;nPVCv(6|gkFx#+Idroo zDoRh+Nlem=2AC3ASPl<$U=SHF5%yQ}Euqf!a5h#nfRUTQl)PxoAwq?k?(n+Bh91`9 zNkGN9@m2ctk}zvs0{GyuBUM1hwITGFf$HYy)4cjUGhmbxxVXe#l%8Yv_~X+Pq@S zQ+?2eooLeKALSOOrDj&tIt7%MNrp-3-hn7^;$4^}e)-!CKk$)O+4quAxRv;?u^YX; zP>;UR5X&n+=w2k@#qoqDP7Q8T73AFE-`Qn}QzS+l?F4R(o2`q4cqX=ZL=??J*=M~z&BT<$s2K_`vVxiP4BhXocFhqdU0+8K3`mGU*&UxQrKC&; zi{yewK@^J4NpdcOI5qXbios9Yv_}X00G*>M^xlQAOi>9IHXSmDa$dM?lwgXPB zD$!z5HKFJ=U^azsC9*sQT6NJ2;fHc~cH>8hb0 z!|fJ$%4jiI`-l!Q#E2Z&RBP0RClW(HKKSMojEYyybC&ZEEi1+HXi=2O^#7O$LuvHg z!R9-$O5gB_?Hz<)txpQkBnl`>5|@SG)o`ny+&zOj%|qsCLFe3mWA}zG54)sAGyL zr;&l+9*bhq)D&hl!m^e8m9j}SA&s;AA2zFHMcPght+IOi%)I6x&7A(oqtK`jK$)G+ z*FFkFn4XQR?6B;7^6Wa6XsRAsAg$_sx_8|9`lp?QmR6C2neml$hCg;TTI7L*8IVcy zlG)MO!tfHT+W6vG8&`s{4Q4Xt5ZhUey=siQu41kr^#>scRyj= z<9hgx7pi{bqP>~f?s&L0JNfD)11AtC&w;1m{CLg$S=&-T6W3 zwS6Q@Z@%hE6)0>w%;6YH&*@;BG}RI#ktaGQPYk)|<)=)~3;#NHwVyv_X3D7qq^7?3 z{gK)b*cIEMFP$iS>7=I?E#15o)JqUuf#zo@%$mD05Js)6jAqh;ZuUUPCcZ1uoF?Q~ z`}d-}=O~ySiZCU?DUsqkuJAph;%r-y6R{BCZ=m@Kfpf4T(psI$AS~pN5z&Occ4P>0 z-vz1y9KHyf1n>4vD#+O|O_J}4OrRO!jOZVMV87QA3%KEESZ*GeSnXq6J*X#K%>1XtPd&#G^Aegpg?sD21)g*;UtF zw?2I=JcN@g&O($x4<{yh&jq>}0MNt!JY>q0UUV2vQ2xg)F>d0F4?d`QItqclH9R3~ zNWq&7B~G4J);+sKlY-rT{c~?LSFvtbb4*!XIC6y*m$WHgQMs7EZ7?t+4tI}Iu|8Vy zHQ;vhi*yoW=hag-?+-ebpSpK7M@PgX2j}b@8ejX^Jp1eEtv&V(my?1P2~axkrFx)x zy^R#ASTI6v)_PcD2kyHTGR@$4--2)G=Crz;AR@uvvN}pLO!Pu#S~j$MQ!V7{A%?@ z`-F-+HkB_vPfy+Jj;UQ^;3s-mQbhI(a$ITG=!t#=?9yaXj2)3XR*$r~ zK0iY?cWdJDA?F0tm-0E}In%^cw}NaqFZdT`PQU8aUnEtpBe3%cr!tfzYm*IK_5rQ4 z$#jawmA8A%vLf3#Iju?|tvckISCW6)T(ZqyhB`WighCD4Toi)_-N)qGU_3Vkmb;de z60vQFB*bY4i<%;sYx1uD1*=6+x_;Qk!VphBFqs>b`1ey{Y7PE;g~k78j0>E|bMRMX zL(#t%1ML#-%ryNw{8-i>Mr%|&K6TxH%FO)o{}A<#(UGuCv}kPGnoR78ZQHhO+n8V` zwrzB5Pi)(^dHenDI_LcB)vNz?JypAQ?b_9E7j>hz5C#V5dBnu}@{3Fcjl~{Ya1)#z zk@*F_8WaB{Dv&Ifw<77*}6mDS>4JFNI4h_5ow?zrOt?wRo@{>iE zZH?=pOsJXeityo_6XC#0&#Y$QFc8Ajxv-TvI%XA`F*TYR`Xf*IQILdY1X+WxkC}v|G`CX$cj5U`A!}CBpIr@7 zEDb|f16jJGT%(S>*q*pIos zt9Gt*#HRkS*!1>)uz#UX_v(Bf)iX{eR!O;x93pjw%$JATSj+-aa`L7&#oCaBtt{~) z26^lkt=a51TAelqM%e@@Aq$42k7UP<*8XW+@K^S*#JBI)zbGdiyj-O+x>M9F#ClV9 zntZ--VFkDffEiPJXq&&=jV?7-A#RAr(rQU;THj#@u$^ula@*50Ff;)82)D!99|E4!H+1#3Pe!Xw($tp3d$u#1CkGwNDrlFYHP= zGAYUZ&}8RJoXzb7O!R-CeI3~`=xP~T3Ehq|DrMRjPl$w?^f4;3YB<^^W@k^Y?jW(T zO^=P?{R-1MTeO@~{H}%+F27Ah^mRQJ9A36$g(;4^`wK}VPvY1QMvn_1X2pYOT3PW8 zE%lq3<;#E-&cg7(R6_fOqSPw9KBWf5Y#Z}^B{09FO(#kUHGm=;$rL^V_2S<#oPIPs>0z~!!hP@ejM5{hY z+uM;l8`h}w)=3WbhJNt*#a~+#iv~3wo|^aNW(z)U570bGGGeZ5V=*OLF+^yz-JU`3 za*#ahq4>|tGDyXhYJ&qlktq^h?%|4UNghOE$8CzedwX+&&A$D@s0J@~hIrYv3jFN~ zZC6a#+D~|hOT^7oxtaUFri-de{UooIHRn!`D2GL$m^e%+ba!5sFYJ?pkcAFvamzlgcPM zl0C8~%d4AR@gS<3`KLa%w)}%L{dQu=A=(_|2qZ9YW$D@$0bvh)qR%Z|$E(IBVC20{ z;7r9Z{ce@6!boIfqem!RaG*w(Fu(h7LV88Lde>-@kF2~Ph1uel@MMymai#4gC4+k7 z|2Ux*4H;pD#L%AM?4m0}Nrx7|^i#Tyk?7JHnxeWqQfI|)AMJ|teVp-Hmy9l2q_#cY zaw9)!(=B6BV`Ht-Ou3Zrp)m-6HiYYx?@9^;n>2(|x701g_fuhw@!o%!Z4^^z!i)pU zYN}Er4~noRy`vN0Hw|FC5i(fDEO@Ewq@!0eLxEBGYjP4sKRhqDT=|ZF5WcxAY5c^( zVs*W|aH-&ZznE4{wQ=+a3Z^Hj8WZM-CRBl6sSK^NJ z;=A`e>qLdj=H>Wy8{hKMhaAU&HnY$R5HEDf<655DJNRB((^l}(-Vke(Z*Iu5t7$BM z(e?zofdm$UTGl5b6huJ&HA&0O&9y`*MJ?%iJL6rhWz4~i#Im`iGyrjR&L1KrJU8f0 zyQGpi6i{l(AS}f*6>09a+jC5?Yh{O-Fr!{opOb^WaXRJ9*`5RjE$ivnByu3_2;c8= zR%*`Q|;4-!le!(Nx%Zc181*TP_I%gIidR3f}!3b3v z_96uEe6PhAn3eeF%sk%0-{YJrS&JdhhR=;?bYNgvkFuZKjj0i+6s_ozC*f@}R34G3 zTZ6Ghz`&2@{brK;SR(=nJ3^b>47B@(8)kRZkx?p>D6hAMw(!E;2t$G(Ah+571iDMC zZ!SUatYLBB4<*Vbi5Y9Dwy5TSf)&|r!>`fQbjIiew_^u!ENhK~is`n%VNlNq?vYkO z!Ew67Td|3&21&QbVs69t1>5rVYp@aV9V)ihNz!lhwMK`#dA^n7*(9T}jWlqq8(+7v zAYWhA?`?{O62I>zXo;rbuCyY9 zYATW2PAQg4oOdZI(@iPf;Yp5&f%wmh@G?jE=%_FxJE}#EIl}@7{Pa(Y@qR*F`(hlb z6ds{YBvH}fZY){zOlF95=~E)m3k#w^W$ExlJn%vU4^N<-9kSe^BagtYR8Nu?4}AFk zac&ztq=mQD|9jEtl$)JA&N_evNyPkYnRponc_a^`%TtX9?V2r4xekoMkR>gbYO_;1 zuwh;3TGl2=&(Fu@cq8(*IN^~)VHuI8hcta)BqAwhHeJpqaM0tf-JUI?IkxLro%;Ux zmk^iDEzpjt5)$RaxkA}Oz7TeG&X_1Z(&?SGoT*URM^JSddOkjgmREXJ`#TJwYQImvH_&A8| z)rORw4CCmc@+ne@I^?W&b&1nJYCv>}QeK$gXFkq1T&1l)hDPpYpf4(nQoJQ7qi2xK zS-GuUA2`@((52GC)XQ*>6-f%&Q1kxQ6NN(-LJyL_$Y2`WMUAuD-2vy%Z4Wu? zh7_S1OA6+WJ9qplM{6%biDySO8f`1a)l4eu!s@>ViFeUBD&v-e$rQvzZAQt*?qg9B zPb;Gnc9dn^WR!*fEe4@9D!t3m7wFR>b$)I(W^~|-o-c9&)jAx%gr9pf#qKQiLts6& zR}%#UC9SWiG2Cp`tyP2J$L$&^5xq};G1^;{iEYPmb}LTb9uop8`(QZM2Ua+lfxZ3h z!w?&UBCWcnUe+;VOUte@YMHX1W8yTUfmz(X6n^2A=Sfcsi&{Rpf{o|6)dDaWva_?h zJLTUOwZf#|5o1$;e@A0!VW_1PwjDydA?HPO&|1;{+S(d7CKKXR94$RpUnwINSHLcI zHqhL};JPvs%Hm8N-4C!~zzEv)muoSP<6^(p3DLPXHc^G1ZP--n^Ms$AWb<1i8}$0t zWZ-x#`P}p@QzFU14z1-?klkrITREfv!5`s4&<@hj^3`4;vhqBtd-)yRI%HJA!9$4O99 zl(_k+dI~|&ly!S9>A|JV@CnVr0zCtAXTalCk(~q9=eAQrcJ5MKK$q5-CV?#v9XU=F zOkIJjt6;RIQqARgiEXhSHNqPnoVqYm|2@?>!+zuSu zVFqE8RwKe~8g{VpMdh%SVNKfB*02PhphGkzP9?1xL%5iC;uq4hrr;WU4m{l+{_K$t zDmFI9OOoV{C9)xg1l=|w2`kI@+Yw^oc}eF>i4oA*@V1$7YAEZ(xa%Ttz)CU{flt-R zfI9Ch)%PhO_u;1;^ z+1E2;ecCm;7TVYYQi%jW_ozy6VF_L;m$~AAR_CUC%6Mkkq8tHUL1%KjKb*3am`S-W zemZ3Z!SihYxT~Fsei5&^TF13q+BZ_qB>lMao_Q@M+!(PL%> z>2fHzbiV@_?6s`7jO}9fCFzBHf=t z+nODa2Zm)c<(`ssYbvjp7> zgthx%k%R_|+dY`owj$-GCqpBr7G)}S#Bs3`ObNIQZKmH&@&KYz?Fxcr=+>@Qrr9*- z!!fq(j7%G)m$@B-g!EdFFUWtwzs6Qi{IPbrR7JOb@!om}gatVHnoR$fB7-uLKI1`T zBWA;MHU*OAlUXX9g7s4W)Psjbn8OHiN8aD1;f0$+;l#cbpD`sfG!!mB$wxgq_zr9I ze9kSbsQp~pmw67*k(9#lPVhg@Sia*K zz_8Q6BLg#4VgOWC7Q%1SbzLyR(XZ6}T%1v zIKA63TZ@pZUx*Xd@yxQyt<~>cC8y_wJV+&v?UzJ8@5oa2duSMBuyMMwUqtq}O_H)B zJ+$8Yd`$7zO>T=lpw+z^jKH9~$?2}05KsbDQ(aqozo4SP=g!k+L$Az&pi`s!u7=e# zN%&`^H1R+fzsQrAh%#VJ3e5Uc*Q%6l(Bwn)aZjN;a!jCo`oDD6ItTKgP|0UlvCl2j zS3!;uqF;*l8+*=a2PcAa(Kt=r&!mzvLPtR!fbaIO=nS3mUy{?4r?FfxqRu5BO|}ux z-iqnRdc`g{HcUjJh0;0ZkL>2@Of7h}y_Ksi^}YJ;h8DbkwjPZIX(J*Lcz7SX3LqjO zww&M+dj&+CY-fuJaD==WB0n|~K3q>3>qqi$j|bpYTVOtDn3sK>avv>ApA4OVfdBT~3r{ z5i0RfYlL3VY+X}ao8d!%x^-weq_6uEQN60-3dYG?`{J@bbX+Wfd6NMme82im%%imOFmqx+TOvPjkT&o_o@%T)y z-*NNTJFvce%bJHzSt7NpA-+YoIkZ0nEJaBL_58GI;bftCEA*<%xspALN24 zxYw|&l*&B+W|2?gs(k*Hkj1i%j}Wt>*)%b+*P{U#+cvcc#oh(>uapqlx$4@-C^Uy>IfH`xO-=6o1R77zvVz3F zFoABubO>_enZ!so2x&k7A?YKZTda6x`UuV? z=s5^K_%V&yRT!eM&Pk|09R}RXi9F6IIS8g*M=lDgu1jbLCMrzIFmz>^Kx@3;t`~@O zH54RU#5t#}U7uL3pFY3RNveVg)yhT?$0RqKkT}%cpZna|P6(^O-}~CMh0~r+;bFPgwI?8g7^@vW zC7gqrPm0w@$Wu3BZ9)y^$$V%8-}QKfeu*dF*&qX*0$9$fxhJm~6h9@-|KL}0_r|() z#QAnCLh1#!w~5>z!bnRMD{**`wJbryTB_+?ara;GiE>yN5h0Y$A7(DKvHkK|0qB;h z8(`%gNp1068D&YH+AIbkA7rtg#ti+sgH5+V6U!$h7Fc*|k}9K6Peo?w+U{npNxUpm zb)aMB;gP6s5CVAO;!6|RwbL;sK~LXBU-8BNA)2GR`axg{djc&lMXi=c4WT!#>@>(; zC>eLs-JE$D>Y9Z2JDMboy5tP`iV@0zc|(eOjo_5|mkQ}u5Cvf@vFkNYb@q)m=T*#e z8tXO3AGw&ewJ@7zc4*#{%FKz5rOBvepB*}sR!AZ{2j!pbrO$r3@HRG0+Q{|EGzIlB zncsC=Eepik65qT3yabIhSk)Y>S8bIUuCHZmEJ_93ueFq%|MD-L*Y@}${P^d#mK07l ze-PQ}eu>x7K}p+Zi;x8z3u|g?b33NF6QIzSHzo;O0+t!F#(b>^TixmZmJNwjG;9jpB=>3O9-H}Y8t!i;$fGy z9uGgR+o5`}HE zlzHf+v0*a-iofPwxo>EhPnvxVoHTNuPMs+ME|;{c3hb9>W7Nh1)}Rbp&RKgJ z1RoXFci@?hRh#$E2S#rp^Uf|G7oXnPPbwPS%SPM?hNhZEtP2s(foQ_b8>0he8jN>b zd0K>Dh1@Sc`t2id#Pv7&toPAvcR-x-n75^c8K*2yHBu)~=gPfsEX1devnJ@(+8!M+ zx=SD9ZMH2BD9XB#!m`NS{X$ZeLBmg~>mR8X)22@_0}(ob;LMMa;w-flw;YUPL9pZd zjgYswMDCzsQV`LOR~>=Tw$eC-+>o!slA4iBG?ze^Anjb_N>UB{+tAmTVY7&^D}E0A9Ohx|c^S;zId7sVum&ZyH6Qt9QV5jKusmq~j zqP{YsDml`col_UTJdKEWzsNCMm1Rwx#!gqNJ?+%GldY=HV4Sc4k5q|%Dp+SJXb zst#;kz2ty^0K9f@c}M!e#XW%sh!vPmGQJ(V_NOYoL)a?5ExYdVIsku}XkW)JVYK-S zd@~rI?VY+GsMo5=)FA4OJ=7nMxF5H*3UvcQYt*T?eInCPRj)TM+Z!t=&+iXNdY6qP z?cdT|Xz+oYzq)OX13j?Mu87mI@1L28r=`vvNt2LRE7hl0_VYQHl!|tc= zWM>LyXSF)kis{w7#&Db?Wc9~thBXx$8xXU! zWmo)ss2rJFy4otqmm`R)gP$pSU=}x$MJ0U_grUI{wvZ0Zpg9VW(!>7_`=WN5<0>bc)KJDxAN?! z53AZP_n=A*nNqZp(-^S@!uX+7|5Yvj=W%QwBW-+hU|A>@S}o)Dvv2+k(xXlKvR{)hts02!N>=q-3L zcU3v=QoW$Y_8%wV2+kqUcIFf8Q9NsHIug*mMx-AFiCDDeh){ohD)diX8WV=rR&%JC z_w~Y6t0-htS8`ZnmhR)7fjC-cq5^F;o?(kR0FP~BeLW6*1)P-2zPiKTZ(fv&LO-QX z&^AxAm#8trH1hnSa-ZrPw_SD5UExR2nDTcPKKdUAQ<%u0suUFAK8_$WS(IJ)O{Zax zPN=FBc1ya@8dw4(OuRz9A^(83?{mV>P zU=WS$29#&xb)mVCF!a~Bq?}Ovn_acHu(CM!9V9+UyLH;n5`2n&7!i1XZ)?@EWJSa(!G0SAL;ukcEi5T66d zM0ps?>+#`oYZds9Fz#ldlCnp_GK}Y(6aKApZY_u~?`c$=bqXEKsG>JMPK`i`=YX^=631iX3|R|IG!$!29es8?a^LLK z+4or3_r-S=`stN?LXbXq#$eT$6xbyMo+dAMN5L7)@!OFbrrL$U%o2^1ON4XnTfe9e9lCvT%(98-vS}j{DJ4ZP)mDLA zek$AmED7Z2cEmUnhR)5fhYMQh#h=UbSRpa22&iTreg3b2=v6vCTC=VOXa{QZdL<*= zdIEDtkiF+H4wT%Ua7@cT=lq}R<=yp*8kAQ&>XZs=xet`TrobHjxy^*B5-Kj~Z>`oA znb;1RZgCpg+Ip-5w#e@aDNr@0dSX@i50}Y$u|jI^a>dO)leHekWTB1O4B`Z}Ub7`e zedt|Xu=c4vp~k+iNX@H7UCcpGUz4u+E>6ckv|(S}pX4t6^Mnw__Sj8e5-&{1Wn)@i zjXxCq_rcnw2nppP5aW%rpoV4Sy69k4AIQsZ5c=-me#2~_ zsis(#QPwxkzDudgBgbmf17@&CkX15)R0VM6pH1F2Hn7~)69MkWP1;e*o20*rEqkw; zt?lQVIL z0~WklI3^(&3(2TB`u-5y-JPPtfRk1pAe2vuoY_bODf|E0$&p_Ud}@w%78Vv{*y>l> z<5Mwgljv)0@^Nz{hjcyLNd4LF$^^Rg@|iN1iyDQWkwI%#K~^(i@=j?ZKsd40;*W6> zB|_sq1};o&4nP+v_6+t^G|-Z7&}4R$NlgT?&q}cJV`y{rZ({D%^rj1W!%dQ5C^yY^ z%30xv3HvgWiUgcWwDoV z4kByiu{8PyF1SLD+z=NWJd*zj(pA4E7wWgr^TtZ=0NPlRaE`}SB1dbQlcGIjFb7c# zM+zr&UAQ7t@18dWc#~gazxiAc=T!RuQb4ly4Olg<3Us0K=`4LxTv4u?I4Aa5gG-FKb~0cB3ibc1{efLedfG7o3aY zp(U~+{jMt`N;Q9kuA0dc@HsS;eJ|LLtOcP4rMdd&q&p@W47GDBs}K{p4_WD~McS*_ z|DK(CK-l7!w0@i7h;gnY#KxnO-BR_dTuCGf_w6gzbqbH#QeNznGc*DpyaHoh>d~$0 zLk^-egYhpC-|pWVlfPYDjTeH_VR61Tl##CFquIMZ?Y7u^`m1wuCH%|(G!m^3H8N9Y z(=IDX180a~G}imBf(a%X#^$PAMBcI^ll~nvRLIri7spOypqyhr7R*Auc_lo`cnP|K zSD|I^)v}fSatsB#8#Tj59CxhLD5cRl1*DWjVSHszKMgy{#fECJ38Q zA-GkT#oxoQRdwX=xQ&MYa2J9J+K+@NLKl?mOI`_WWYI>?R`3upnWEiL=(J~Op2C4V z_qcWrvLxbt$av{i$XD!z7YT)wfJsT262MBrYw{_~Tgc-^Y1?-XcqS;kVwo=`J6~8? z*bW&xT{iM7TE|&<=H!OMUUlMGoa3%{yrk=}45t=g_@8hF{^sqxmUuuiPCkBLo+m1w zD3M!E5OL?f7L_}#SWM(;z=OJOTrreyEDiR#WI0OXynD5aO6zygnMt6JOaX zSI;%DHK&r+a0dI%Dc!e0pqQV}fTrB1XJsfu`Lsm7Og%T;(la^r#7pe=fROu+c~I-K zQo;M+f4yyR^iSma=duyC`*=3w>Al&)Kw?{M#csY0ZQ0u`C@-d`CC9r*k-LWC(QSM+ zS_J%j_-WZD(q2+{hU~b_vD5uIrflO>n9MkeHH^*5Oh2fv9Pa6l*#6Ox9w?DhQrQO- zLqCtqGutPJeMRp`bCy;*;{70R_TlSAl=~n{d<%_GBqy$%Td_rRAm8*F*CFIKmab0-nC?*pM_rIfMnVisYX z5|@0lLx>PjqUI!8IBdLdD<7?)sDFYeV|%TcnZ}hsp79Xq+Uo>({a!4d!MX1g=^> z!&4BZc^m`F8|1Zd`VGCpmWE<3>Z1!08j4V3Z~G6zFkmgrS333#EkrJaCZOa})jUlb zGT>`|xKtU+zZ4#71OwK8htN=;`HD5_#>ox4b4~^1w(R`;vP*Nk&srm#3f$I!;<`9- ztChR|f69j>4~=?;T7u0GTRFd@%oF=MZw#&ekuj0Wo)SX?j`YYm!IGy5Pwpbk|G544 zLE41gbj2JikxOC|J8U5W$KY015@oCr>SnC=WAvBjspKGrpTPT(NKE%z<-6rSMO=OP zZL9;aA$`(O)Gi7yG=1HK}! zgo)8Snl|UyCG}6V>ws@D5Pt7tGWkuCN+RQ5(AK3&^H~9Q1RNhmGS$d0U5j#2F5YEB zs4}la?TTWrUajL+DtQ?g=l2jH!b)&A$sGDPqfRDcvC(4Kj99C+?5djJ`N$2QzRHc| zP8Mj$mS$R!4ec^uW$aZ_?L|=RGhdW*_x@bKut5hw6 zE>@WF(emNIEbH6m-4OVfRCmXf3o8>vm=W31HIOp&=Y0QW7t@*sDPdM3sG>8Qd*%UA zq80>~g@8w1|Keb)j%xCbA1&}QW?%qGLEKV9l%Yastkbq)DHlr9@D^N?&oZv^Wbww* zEVe1B@sQ!P8i5P9IsS$-WH?M#d*b~h;?np@hk(qUueIgY$1Sh^3em~9?i6Ih+ROxI2z5NXdMkXhnKIxBS8h&mM89Mn*Ye)Ct@bS2Ja zM;{R)SC8AM1-&e8L7jQ+#cky;j29Z=+Y$%3RH=!1bT+G$Kd(H=rd#M*lGXbmUr5Ev zcxmcQ@M4|v54YEdI<(ayb-mBdiw(b*HqxDE#mx`b#ne@s4_K7IECn$+&Iko616}h* zI6)zMf|Eacy8ez(C*e^>_6xd$D4}VZQ5$JAoSOaPUpoxfD8;~l-B(P6WdU?;lE6Vx zt;IE(3OE(ca^q`@Mi08B_t*`vXX<8iy}0l6=`W|orfSJ*o~{aW6IDB+o+89Eklr#Q z^f;`i4!2U2s4XfVY`|}VrCk9|)GgjTWCBUX2C%xYeQaQA!>YA^XYvn&QUAocaV!G~ z6Q;2nVh*e+oKfm+(%rW@+tF@ZEz%|WI8aAgf;wkyjiFd{ndTdrnnF51KOf;sQYi!? zUFA53EBSNaK+PKHN;VC!NmfY|p@*G66X;q4Z{_wH9tP3pn<+sIX%JLkx%g4PPq%9x zb3PbNsyR}Q6;BPH1ZbHai%&^@mo0S}DBe|}88k!djpZdO_sfO&T`a|G zGs1z%-N0yiL>S-m6``?Py6T4ztghuXGRI`6$ zBK4l=wW`o9n#yQ5s|$lbLt>mG|4a zVn(d;u6nmTJ83Uali`WRs|PGQ$!myKLgw_``WkTS@IN)o>ua?X_SRX9b*gR1&1Qm$ z-R2ap#xgYLp7NeR$FRLwD7^vJ6L>bREU9hQ=Huepjb(lDcd44WsJGO$lH*^abKq`` z!&&mx$y&`_W;UdXL^TZVsfZ^(DzjXbhQ^z$#iv?SbH`{+EZWVgd6Qb^V8PQ}?SC5h z*|qlgAv51ok1xhZE(^`UFGJ}GY-U+|TLSw+D!wfBp2A{XcPRZS7Vxjfrc+N&|7w-y zIgvETIUY+pMo)C*5T%4s!sQN!O~N>%^_5&&E0P$`3#L$(8>U0CqFGyZEYBvj0t~vw zTg%Lh_sCk+jvhT(CDKfllzZoi&+U8GqbZ_-0<=sRVH0j9`f!_n>>Z>(ev}$@bFxVU!7WL|v35S&S!1%Z{r&pm?)M4Z z!4O`tbaDUO9GU{(BgUk8qIeJaBrxqE*33aPv`)~oN_?^m@Q*8}+w zs*i$prE8FKQ=*zT+OA`&@$}-F+;IeKR&{y6LIV!T&k>a#e+K6%z)Y{ga17Kc`O0XeRHjj=S*f_fHPL31cG?K{&0V{~>q3 zk|6pvJ~t@pB1z3maE=SucbGs9&vE9XwI|3wS&XbDh>9cGNeU^*K4f3cX^8HWgf{t~ zTsf5n_=~l78Xf_dfe|Hsn`-di~-vvPY86Fk7{U-G|`z!i~V6zGhu3Wy4>P z>s-@31szh&VNb0R!`=J2v2+qc^puwJnHJIns#)sE|H1B8RXpkYqKbh2GJlGC(OJ>R zpRIUT;?w(i{ZcqN-ku5BVJ@O`8NURm1prp4HQLhg`x_2ds({cpsx1B|e)rh-#@Bgi z`eDY)^-L&&Z?wHIqH&cG4vR|pP83+q)}WJ2?-!A%99ZmrqGiXI_eer3hEM7`>nM@) z?a*?-G~m}+>ca^$h@^yxEh@G6flSWM%$5B#sXMvMPiO@*b7dsUo64#8=)hoY38yRx_T4nf{Cf2z=yhl6f z^7`G=UfJbj^r6B2taNeumR<%nYX)7bI1^~kg|%`~z#9Z8yJ8^mx{dI-GNmKYd*KPo z zf=F;WX%IaBn8{Ng+iL9>-UDZP6XIGjy4;lI0jB;~wqMfPc0Q08()_f%d-CQRp{-)&; zxp7P8v9y4Ij8&uyVj5Mau>}F_^CHzHbg10g2$dUwo*hiGnmf8*EO<8*QRa}a#hxs` zCC?er$pq|xQDUT(Sv7H!-ze{wE$n9{q;?~`=5R>3QMs%p4H^?PBz8W~a$mwB%~k~S zkC3115PF^z!5^F5)6QK1dp^a~*PBKQtB>U#seuVY_QGkCe@T3sKz4&v#(++l&#+~K zReD-Y>G9(;`~1XJ?c*7ws%3X|KI#r(yL31p3N2OZxHJnp0HRl8(4#Cyz$EoMh4Ldn z7VtvY^pb^GqjLDpOZtTm{H*r{3t~fNzn@tJSoc)-jd1J!2YD;8a2{WGIG!}l-w|t3 zo=kdxD|`!L#sCV6dCMwpOM1X=^pc?Ug_IHjQ}9}cx7}+v^YIH~y0A6a5ch}u&T3CS z%@;%DPlW5d*FfAaq+g?InV$&phDsh zb`a>rH1#gFuss)J81+WA6;X=KBk-l?fqq}z6P8pt+c3xTGChGl#%7CSd?>L}YMn-D zar+tA>pM6#!KL2)Zb$RI_nooAP6vQaT1BA4e}syWk(u?Qs?(rSxp9|5Q_QSe5`U&C zN6E2E7mbv%0t-dC@Z@jaKs?2Lvtc?AS{qTrb0vg&;f9+@J~wnV-qF6&K37A)`I`|g zb!Vl55bf--{vsWcZsmDx);3?UcuQfZpi?$NCkM7za>)t2I`k3M=v#^j{?o5MvVC9a zGZDIsc+=v3vQ}aoU7k%poj6@Y){GOC#Yo9o3vX^{hc11;YC4vk{KBL`eyzO3p6y+b zRG^iWH&x5$TjKJZs+>n(K$8G$7%I#*3!=pA5uZ3D-$brY#;tHF`;5ix%nyXll&H2L z_*KaW)L|3)z2t~nBD zq`kYxn7@0*!NGDOos7|xuJh6r$4@fd;Lz31C{Cj&3wc6m;qnRLri^J~gwyP{J>_^Z zG*h+DHlP_1Bddg8O}e1T=CA_wDoDNp)MMTWJFQJWu)Xfz12Pq^atE5pm@ZQAMtCbe z&!@7va0K4$YjhY6Eb={Uz*!&fQ2uahi?(K)Ef)DeAh?eRZjfs#E4Vn#aCK8n zbVR^j)lw^G73pFCp0~|YPA}GcXmu$SYonva`iZjB5E(*lh!2t~MrU}!Z(E}&1|Cfd zf}z<5B6e$Q;g{&4$h)kArC|7iHbfIi86F4drKz6U#!jG{2ZOu3OnSk);fHj>9kA0) zfo+o=O%;qBX90tr^s9oD;y4RWG63Bt;fmiSs)>C1QM2#Z_PIu{bNdr%90oKl@(qtd{Hr6G9_$2d~%q>}VHEm;wB|9dVr@@SW}En~hT;kUsDY>g1Wkme|1q zGqlJBUR@JXLO3f?sTzz4`N9gh)ZP+P8>Tjp%7ApEL!#B*v7%9s7R>t02If=0=~K3; zi;8#FN&yB`Xd$BY!`S0vG63-&Tc|lm_nz>eZG6QL3mqb@y>Dv5L^doBWyX4PFPyZP zGB>o6QSgQoq*;~pd_da&$jHBOJLn*q>MRX$fSnlmfr>z40-`chL6o4S~!5VmfuawvBs-SQ#@7yc_81jy0LhJi8D5Wb*~P{?Ms7HH6rrYFp8>wInHx{ zrrew4^iT4*WuXUD7KNCYlNgdQP$Mu!#6+=t4RzQUG2z-kdN>^Pxg1lrGd8La?P|kj zxD%P52jYTtXX1xlX!zc+&#!@oLqi*>qdrj2uV%rR*jItDeNOi1u3syEe>IJ>$-YI3G6o^GU`%(rVeZSl%kI)X+RYbNh;vt5o9b{RS1x2C)+<;KX*Q zHwgfHLM{jG=p1T(j%V&uU@8fsV_)5PBiP<7C{c%PMP^;8ci7n>TM;c-Iot;PYWPG1 z;ipFcg`4pWKcct+ovTs7m{xB2hP!~4>=wNx;BUFTg?Ygj#wVe^8SRd9h12}Rm0W@S z;>v$;3R1LopA;D3m1_ z%E5b_2Zpkp;rAW$#;&hq zV=Z+-KW1wB{W4a9H(Tk7vfG5Hb}Axk?F{<-z@Fu|^#{^45nU9#cYPqKJ%g)uWS?eP zGb}2f2qWnd8{XI+k1UVY@W)?1F9Dy-L+NYX0y5S}wkQpajg!8bVlXk8;WncD0C|5l zIx;58_QDrao18lw#E)|6r^$0^y4JCmk>!>i_+xf!fDiVaJI z$KgrzlqD_4(w~oA*M9N9Jxg!XE~_Bxe|7P-oee#nH}iQ&*7z%v_8$+I{(g4!XLS9c!~%bt(CLGl$Zh5sVzb^WNB@B8icJV&g0S1 zepM5tr36O}tN|w(sJ6eKDV45l*ZH?}zWYW#EM^e}M|pi@6i`>-O0Yna@)nSJj3Zgb zlF>!d480(`?pePQH$Sm6L3i)Xvf59n$2a@tX9@*Z@_a4-IZ+UbfjOcFQZe{kvd=Lz zG|k1;?JP_CU9ss&@%cKlK|2s4gW~GhIbQzI5Q6i#APZEP9ziP-%7;J2Me2Z<)^avJ5-%wgB zYADmvm%_ea5WRLI5KSQs$H*{{+kz z`R_)8=-dBZX$imOlVD?RkIn>bMm0!Y8m(zoUKv((T=?i z_=YEXF25t|c%sba2DocsS-^_MxExQ-)&&Tas{&suN=cC2u`AGyv2Gm;j4@^U4C0s6Wk=!Uoyyw%eQOPz1@Z- zh8_h;_1%YD1@BI0n&zdPg1`aLHNc~`! z{PovCUig~PhWPvt0kCwzuOL)`s}R1N14Ig4R4w{Ibwn*>mZz2DyzG@GY?W!R7v#rar+VS^*o1=2z zW_eBt=kbg+Xps0Q`AU=BfHucz5#}wWps60Zu;{lo>5(+*YkCAAg^87pYjfof7Itaf zx0meW$n$IfCpX)W)r``C6AztUhdOA%H#Rr;o)>}f_Qj5* zCd*W9m12A%kUIYVX!^>yDEsGYTDnU*l$7q466x*+>F(|Z0hL~)7FoK4rMsoOm+tOb z;@SK6dH(OOch}5!=FB;BMlSGf$)@e?6*`EWoFui~GHWKBZ-6=b-vIfN9o(N6*u96t zUi&c3u@rcHTta^9EZC2UI**1Z)K@xB(BTGWcI07UwWBzKu2=#yeh3qVt-3@x-!Jfh zXwO)_?x?l$`O^7PnDJpNjo8y;A;}3}tt|qWv_4?^TuR}wNDtCc*`1g7~ z_KaOSzK++C7X2s+HZ$+c>rEld27Y;R~yPM|&uE?p4>3Ly>z{$c*vH zLyqG{RS8o64GXw>21|q%s92%`G9c~^2EHKCpfsahEHy|Z`ZberRYAH ze*92WoqiwWB#|`BsC@MHZ&QltHeddw8OE>D7BCcRz{pTN#vPdGqW6I4H$8%}9IdGz z;Z1jIP+c&FVROX7^g%nDj1^9!UY8p&D&uHCt7(*m=48sQ+}hIIEXwmMONMd7Q7`-Y z8egr0JSx|PiR9NrKIF(75w>p&;JCNsbk9H~JsAba(yB!(9MjZKnZnW}%s~$6#GkU? zaDzCs9HQ-Ssa~D4qTL>@_F_aY9pi)yf1hRIA>vr9#90?Eyw|27t;zaq7Ii8-BU7&w zytUc>7d0*hvB=fm|I){R(Ap@xvQ%6_vtZkG1JX3L@pSv@T99%uPB~UyJ$}7SEysB} zUpd9hl%xUc7TptzZ;+t+ST>o_weL#n4p5X@3$VFY4x_6tsf(guG?1$-0vPteOEHU&E> z)4Ry387$nz^mC;=_{9i^@VIGg*=x|P?3Oa+`?D=#uXqybMCO_g_gzrxFHSa$#Zq!F zEs^zACNBne9-8fv$)DRtn*voAmpS_n2amX_V|S~zMaEV?ex5tl2{?Yi4@4eeI#3TL1f?r!8PcZKWUKKD!7Ei>NF=(6ejj+F&YQ(G zl(_3M{Fc`)fbnamh`3b#!!Zxgf@nTUlPvn|{{YvyHX3mv!(J^rf5OWVC~@xmp~lcY4YSd3zec z-}sA}eG4?DgCVYa-oMHiC(cPP+DejMCWAP&1z5)7dA8=RTcX<3| zuZS+yvOj(De{Qq^_Ns$hx*z9oe!T6o=)M)3Zgd}wXuTz4OLVw~4aC-#5GeDWxmTx` zzN|Z3L~bt2#Bk_V)Allw@|B7-ZE7@7exgmhL^f3rjwL)mFN!!zN83s9N(z{kY~fp_ z4~^c9kD5Ucn8fQQESSV7oRU+=?-t0n*3NG|=2of;u|?? z;^w-mv-0{B7OKH~GH2PJ>0GIbp$wL%Gpdw4E zl$Y#fRcCBYkfiZTKS}dFN3Qu}LIM(-eD47b8T_UaG0UIs3<(}Y$J3T}IEy+3R`0Sj z%pO3le~st46bUswekC8od^ONQ?cmVh%(eal+OG3E{hnk# zbRyv6Wa4_~KJIf)GgFTn60-Fx8SS#}N62y5%tPmy%B-$Yo31?#ASkGG^fKvBHnC(X zW0n%nC_$odlF}fNi{EPgv7qPHnp-lp#9s40kkOsdwNUS|MK9)%9l$iL?^y|Ha@+0- zqKFnbZNFbb9B1dGA}Jw0-W$UhYKS%pa`SW%C>C`jHF%~g{k6%w;RgtHc%MnS`cF52GRdavH)tAJetx+8U$Gpp z^;rw^?&)H|X89RGJCEq1D6QI-y~bU>LS%(?_8*-qny@bH#)Hy)EMZ|cA5tmOaXwR? zNYp3~zNT@ggr+!4BURF1)aJkYJB`OLvedAhd2*5(eV$JMB5i;dOpG1S*TmEM-POQY zo|T2Y&uuP9Kv`TihgD@_f7Ra@0@u~~cKQaGW`u7fJ&kVu4WHYF<_(nAnR@J(fvQaf z&CQNk`E)3q_VP9P4>>o>L+XMQ(X*{x+s5;22r$qet}vaoYTygNM%P2P(}Q>lA>l^(PnAG>KNhwr5JPeWYd9zgZle}ik6Le zy@k#!U+98*K7={{lE%N5&(maUC)X0t(O{lzU*iiI!D-10`{B;QRmdN7RV6#FLD^VW zLhx?EB1g8V)>Qd!ZgaTd6m9X;J~g(xy^na0C}Q*FGqAb2S<~w`%t@-dr>7?_#@?l! zFMH=>a-pKKxF>#QdRIpEs`=v-$2T)Y%=}PsA6)~OA8b%4^Zwda;*v>)IlALVxKfdE z^DZ_qHmq!b%c%7pB{7tALUU(c(S#aq!#l$6ad8l66>r~IWNgi)M2@t9k|-c{CRv-T zhB<@6d`2%}x+({I;2zDk>pV|zTeS-Yu%DpV-7e!ZYbQAuF??bKh*>D6ljYhV7yo~C z>F_+f&9P0yWBcC6R;A8~lV+Oq6^AA6St_MUp>aCr^P1V^z|=2`vr}pE`#@w$Q~}Q) z`NrS(uG5344)Xc~#q6s?Iu%obD@AG+6Nw@!N$va3%1JFGalZBEJKzqHr5NZJ>vMe@ z>E)MJ@DzHw4*RRX5j<@4jZs;b;{~;p!sKO&>^|iA z`oyTSPqpp3DayP>^^4D$Qm;+2qZgxr%}2VqcAXUutOgq2$ke|Jjqq(KjP?GT1d{3wclj+bz^0odKu*i}Vyu12W}rtf5ajCvfA(mQ(W*?LLZfmE_T74YWh)OA-7 zKBPxsM+PM|S0o{L{<{b8cD6Nk_A-hwxc|7iog4?Md@>SI78t`ZguPfc`gXx2yv# z)ti)jLW+(@`ezc1f(~!{$cR9c3_qwU=z*DUkiM=ZKjLr+1 zh?xZfP7Fkwgr?gDkeTjDV236kw1TG!sljW-Ep^Al%#idUQgUZ{84DIBKSzC*y*2{{ z13^3`DX8$dZ`Tqw*CByXHt?NdV*`)`#}YD$UDs-%@s{!Ugp)t*gAiSZAyvoK{c-C* z+noOzlsz_WyEAT_07YU|9*yMNDX~Mf8LX6_8oz6*v5wzTC`i#`(qejX21Q!u+X=tl zH~56il+efKIg0K@(p!lKCz)@XGj-s)kH6V54faqU8%gsx(AdsG4|0FVP9q3g$k{iNW;T$7 z3$EV#iyoMYR)TBZ$R*5X;C%MlCH{FqMpb9q-_-4gcQtRY($h|gYEl5IWs&--EI}fu z&S;+lXV`hY14{<(;OX`_@V4A^*C*uO=W#ltqwnP8WXQ}ZARznn)T!gP(&ZA``34Q# zCSTuJS%1CDLUFi!eTIEk&#JewwzhY7x{~$co$7yFsW1NeVCB5l)-{$*GH``sb_zM& z`M2MsBZuG$<3N|GtEWzcQ7l|FJnIQk3ZLq@aV=-W$&elWP_;ngfPwo?Dc^H&Q6=0nWBXi)a);kWr@D1Q{ zcT#V8of1R!>c=9s7_MgwE0Kerk2}ZNp!>c}(}pp@)eohkyF^$ke{0w<2Dw}*=-ymaueYsJg?h;IkGnk-mAbeYiuNXd(uaqn zh;u=~L}8Ow*{crpPwqtcsi&h|t>6Uv^xWlEJ7Sw3r<7-=D6>#eVE7mv%u zftzQLZK`=0SeHIdHj{ljZM)?^2yOIH@_`g6@Q{UeIfLP=F(^NmJZyH5CU|c4v5T-7 z>Ymnkd?+M>b|gdC&jS2gW+lXX8|(t!4HrKFK*>-=x9)fF}adXFm`C-j#u7waQKo@Iy2%| zi3LADG{v}Dc#(S5GLTjHw~GgYG)tOv3=AeD-U1OqE%N!xEHdvZU4jx^U~w~u5Uo-M zD`8xoAp_8J^7V&-pS{Opxf)U3CNcVZ=XX(EW0?^1SKYD!Bw z+gK~U`r)RUut$GBd~!OoDi6VI1c)6hc$x0PYy9mfUrKory$I1 zynNOLK%N(n%K*5(4D3BL%6sc;Y$?RV_dT3QRvS<<$xM&RB6~+l#YgbjzIH}@jpkAi zC>5VHC4|pTW?m_52u_eKDTUCW$~t@KWxo7+PTCs+jtl3=!t=>xZ!>~`8S54hSq);= z+|U&0O<0qzAk8u73o6Atfec+7u{M~B16BWu(8$J9+IJrAP?m3`J&lVY&iScQ^@Z=2 zh$lQ4KD?E@1rM1Y&sXy6R#Uz7HoDF3G#$wFfaAXCp0Ep#{5|b$7OJhSb+hh1>rWuT zC_eAc@rK@=(t8!dPF>a3dvdG#CU|ZSU52sHwZg0nPk3a=d#B?Rn(=Zq%1{t#hY^ zb6JYN?QeDN5Y$b5e4Jd`C7!nwX0S#Ti0U*Xsc%xZ@N8FCKNC=PUe#2-KA0n{e2KD( zSamB#Zpd-S`OXAV-!W;pGeWcn#xV#NknvXaDut3rDAGZgq8Wus$S^4qPqGfyf-GvDGmxICW|hstH@y@%?^RYnXkPO5?VUO$ zpE7D$+M12N{ztWV>()5!#NXMk&$8i_!e`~ZBT9Y3=wH1^f1UHW<%#L9TM@_ty1-mB zC9s@cZXGwE_(q}pFjpPyHR1If52RZ6+s}y;sr(#~zwFK7vY}UCaH0X-6R3t=@r$B2 zzBgy;fY*Z#=k)FJ4V9+Hd_oIV=>Lq}QjiI=rW+za6#Lpw=v^>FlTVl|v8{DHo*gZ9 zI5d1CC>IxWvXUg~I}G1NXSKzO@tZj6XJV-^3w>|BXyE9e_!^6M|2H^u=Um{B(*57L zecs5mkC|yl(r_Yse&UM{pQu+`0fKXPWetG$4+dmqcK(gT*#$Vi-{eO!n|8lww43Zd zPrvv3!1f0E9pY9RGU zV_<2ZTI%j@u9#@=d__mdQz`d7mBfYo8h8Cn0SK#5HrU^;8*QwrR*m@J$g7f%bS zow@Y!(j~Gt{iCrPJh9J7EGxg4A#_2Ln;A|MnXW2m<7p0{OPxak_V=+Rg=p1UR_4ze zdVa6l%n!2z9t)!6J}-ldA@V4og0#lL)qp47S9C1T|1Q53wyNf zcMO|`JdU)zy@~beR1F2LWifPSMEO6(XV@)Zm}Qyk>uJusFCkVu__F@|Uj-fRZCK3W zFVp->IxqH!u^*T8W&0?-)&JIU;GZh*l$*S>fLk#(iukvgfyzXQ*woE4^-+9s-Nbc7 zGAVwvJkETKZv@+sLQB#A(y-IX+g-|Muqq52!D*4{$rw8mJHEIx!gnoEvV&Qb&!GQ)Y25Rr-rW*CS=4eQ$`DSNt< ztdFzyem_e=4r7Rp#SH4V%oVBwkm{PD;xQ+#^8&`<#UBgm)mT21V#G>i;a3tt0ur%R zCG-@7Cr%$G>*2y$XA<;X1jWamu#4Q^j~s-CCgG1h71KX%3Br0h=nPU-;?MXa3*`-z z`ju0}dp9y;2iTckRXA15ncR@qN3rhuHjz_#Ik8-nerRB0i+!WZ`rduW+kNutDM{<> z|L@Q^y+6b7=I<&nA734KYZK?x+h!d)XT+05hFO!pKl4@TwRHXu8Xo`{0Db}Sbpj55X zVIl)^TiOj#m0I>6YPpzpF-6dom5CVrY$3}w`nR7It1fhI3R`jYro3(0BbScLN{klF zzL!j|0RqkS|koX!r<%T8`LQT(c?uYb_i6p<#IQ(#`N+`v^hCXmu zRDyI_b0sk!fZj_*<3%Ckz#}qXm9g<#+i_S^UAv8!&?GZ)O->=5OF808p=426fzVWt zIhUARf3rwn#C-|cfv^drd1iANoPy_L@CVI^oPPJ%qR4WWVYyQ!#et3T_MwO)$WFJb zE*sX)i@6n_suz9+lj?N9dJ;Kq5Uk5mrm(lmSQdnt;ayjE<~4W!tTs-E187m0cMuzJ zo05$a_Bj*5=g|4izRPS0Dx%b>jbKIm5&zq*d2!J5%}pYUD+wQ}r*_ZAb2jVGoz$w; zXVn(;86^}e-t}Z98X+@%4HP)m2yAi4@frn*vcv$e1zye< zoxfc)#i*6kQGN8mr=8k^kYKk@2s--%c}m1q1v2uMn>cnma0V)@SLA*MiJDwDF|o@vTNRu-8%IZXfL(<#ubggf{Qk2H+7|`ub_B}S~J`F0rZEla-{sNy=P9AI)G{KLf{C`>iSpmBlyi7Yz0ZtZf zU1_#lM#@b+q?s*;Dg$&-(VKEIpU#O^K*);_|Jba5=fVd;*vZGZ9NSjrQ)k8AhRUqN zoqNuUOG?Ja%VoCTUnq;!2OSzOmrs$}N;xT-#pldNYE)E$A7uy0~N~-?;!P&g!rEI;%P06UMQIY0f3-SJdB0$YZT)$U*KJ8G&El?FT zQiNaqYu+cI7QuV?cR5A20(lr*J2t;(6q;vg4dm^7-=DYaB*W-l64elM40UvN@o@fv z7fst@Db4A}@(ozH@ZWn*OiT;|=ZqS+Pp`+6-|6#3OGMaAMJiEi5+e+qyu8wyn|l*v zmdaJ=v;vMRmy~X{Vc9JDuam2*Wo~ps97UiGIY))UN7;C2Z`u;WV29(OV! z$Ntetv6uJ$Z`$WS-+m*jfFU$`ZESuY-O`W+Y~qc45sy1w)-<;4nE=J8-;4O%Az->j z$ecUUjC*aeby>2g68RtC!B8c&$yU()+;`2fprD7DF8Pyfb``K53>=LViuIGD1fz5; ztr*G&m3k(YJ?uAit-ye8y+C_?d*{K(Oc}5fSvEdr16H}!J8!go{*bk7vo~9Ak5i0d zeI!?2HF)pikG3T2=R7C*OOil$eZ4^u(DYl0B#V|3;XV{w)UH<&D)_B=`U}-$^S**e zX*o)(WhUzcuicWNsL5Kl_gUz?g}t!MFm9A|zMrjmLv$UgRY9x$+p|~KFBYtFpnL~) z7dsyueX)M`P1DG1S?U=bLi5P0Ix0jO*?MO{K^^Qk)_n3{xk11pOUi;WCqw>`SVI>Z z-cBHIs6xYY8~b*WelkxK_qbBnyQIk2Jizyzr%jHE+z)JDYDZs5lB(u^s9M~ubk`1H z*=)Jd2tgy#Yyi>gQ6BlX^qSJr&_w?PJ7wH5l-Cowt2M?#mx=eYZheNqFgUIHZ2o50 zxNOw!ABcmhy0J{k9D?{(0^C(8hw-}u17Po$CodRiu66NQK3!>iH?J~s&l5)uF=oUo zlSG^QaC^`Ey1KeqE{#wN>ad>{)Rv3s6^(F{bBQmqqI(X1iyX9s z5_7~a(xY9%j;T;Pa%TNqVLyHf77(7(T3VXk6})~!Z=(wK{LVFv*%i~CuI(u=!8k>U z{B#Fox|Vs^rK(6{(LPk2xcz9or%&7E-a_M%|K z(B-r}a!P&B#ff5l0snMpwpYyYsf|@u43!6p%oB|cEU0wbR;yXgWJEyTR@b?GtLr^){szQiOfAw>+ zmB#46QO$tw&{vv+1cnZAlf9k_lYL*;Loz(7#rI0jgEJ;xc1_)1R(*U=6D0Pose^~+ z=CpHNoH&i0Y&P_T@7%PSs~4I?Bs%wZ;V^}s_LqEw-#^SR>xuk0cH%e|FJE3;vJTE0 z^aj=y?Tfrzyf$g=?B$je*KMVHa2N)KD5`3N5acNRYgJxNV4T6?o3i}{h#=2(0iFp5J14e~(F_uE#^vhC;ge=y_wFLIV0Jo*#!9?H&8gZk8iNcb7 zI8Bz;2`PwG*=%bgU2H+tP}9a}KHC6FdU_MW%s~Qo2Xvzyww0)lL7%XF{UGWh~Iy+sS034Ix&!G0L|7pc8P4 zH_X8jm_Wi|y-eUU)$REUR;u}CqnW91VI~93ZrcOqn2%b=AEfv~8)5E)-k;g#pQ%O7 zUT^Qif*+8X^?tR$XC@hb-&Y0_cw7@PBWASxU?SkthpX~V3_1~Rix1T?#{#b^7q?}z ziB;9d1MBc@Gs+}%cn3U1s)2qM`B`1#q#&;q*^!$$(1?>X6{v_07eoX%4ZN!+Bn_Sz8PLb^!m%%gR!*ULIA7vDp>o_{4GDbH%MH2JY8Xb-D#l zyv>!4-vW*L zl`>8QjhVYQ&NyMIVpm54O^d!lO-}xo4r$KLd#G}lIUWiv0CEy;9Q7VW|Hu1eoGA3( zKC3M67c{yihDbBJR|@Nmk1O-_hV@(}%k2T%l3r9n*K1!be}`7ZVQVsOS53$S%=a13 z&TJ1R`<*rK-_?)GBmIZi_UCj>Dc^(O+wRu_Vz50J+zQ2De6pqP;KtqE9f1%^#LeAG zMw34n78Wq5#%%_A+@rf@&d`TF47SV1=i6&-_{zuQc}b)n=8}s436Rt!)l^q*t+oA{ zHBT`$jLO!%JRu{&1iI1?HEx9dBp&_&ByOz@^7|VaYD2H`y8dm>*{K=PVYCq za65tO52wD*kGFgD%>ODgp4|?GANJk}V((Cj)V-N=Hl^NBCm$w@_n7{wLAqWK$}0}- ze+wel_u>@yT*}HW)Q`SB!dzq3!KZJY&t;~VV46-I5+iP1vq)6s`xU2>U~LV&&wFJ0 z3i8Xi`EzO<4~*P9VHgmjezS|%XiMtAH(R}icQt9ueEUZ5Qg{Gdd3~pOKrVi@?zQa^ z0#>RqQ+v(80_mjJhU`&Cx z1e7T#>*W&0$E(GER{rQyUO$u*NL9J#mNT-eR&k%2bf+**RI=C>S zOElFRpddd4U!FvH_k@2*pY?coyR6XfQLd#7_Qb0Gb70ump%*MIgL1WNN&?x9T$Ccn zx5Jjo{9L(W)s2`Pv6jkmn*fKWZF*c)5~+4Pm8<2HAFjrZOVh(o$BTN)ov&u_ek_Jb zN3-{m55bs*so=)_NKMao7!J8Whhf%6twmDriU!U~%S{Bkfa=ROmvy0Eu@Wjxg@fT{v?YDggexcb@Zq3fvuvS2GiJ`55Q?7Cb?z&MG_FWj%f@@DSUpZ}-G5ai9Q ztEq8idil){ORb2(WNI8F2RW>{HGhY6*jj7b<$&*6SDdlE=W(%rP-eEC09?kb}7xzamRB@|xpu;NXl4swoPPSsjS-68L%{*0L1%7xwDbNwV>3_tMPMXTVe}f%>Jd$pEI$rx|OyDDS?JDew&u4 zRod|$8H(zqrDn4#nbu@wWrfwm<5TH>B`#ejy4xYt_;RBnmSxD~aqqojPtK2CL?@Ug zV{$j9_QRT4IP&$=B`a5F!WswgzB<;vO7_~eqUvdMY#y~_tAzmo+HB$>ZHWWMZ%67) z1Gmw;r0ixwB}2QsjDPH_^)PBV;fe>V(GqGSa3xNQ*1Mul==C(NoUFFX1=y!wXV};^ zAfAbH`?XDNWRX}4zRlu?=@%Hg6xN1L2i^dpIF$n{Wz6*PkTl^uVwtgsSa^{+Wo_SY z_~C|6k7Uj<8-m#<#@Y6;nS`+xFtG8dHF17!0 z4xTRX_CZGCJ@!i9um0Pz+V^(B&*aL6vEqa4bAIVDA&!BdRG`TsyD;ZbN1QW^IjA%|A`Q6|7=Q+fGNbwHAz~Ox+$d2uDwLL`p zp+iV9|CotzK@s}2kcLDx88ccbXvWo8J(D!pVP)}SQ7kyZ%oe7fynj7GSD`;f;i)KT zs%9_jz+!$UCD6-aWn@K=nEVA1D}_GS&{ZCP$yh!9y*B3G;kUn23%N&9^iZF1 z+K|QX8#q5#6oMB$OqV)6upjNtZc{}@UaokN9^w8W818FPihjpmq; zQ4Gl}BV?5|EO*`IulEP=mDX#Z+FRZ_?Zm+moXidlOE(qER&5|RJ(Gjea&XohTa5p< zB{6G8$#{CpQl$EgNxleacOVIutOWYv(wUh*f*t8Y$AEnR;-PS87b+V?bA*~OXn|q2 z@LErmzl0Y{bP0jx2i7-3Trx`Db;-QHoD}`@!~B{pF)Jo=_dpMmR?9kwKI3fQC`g7m zYGzeZVbU?hzz)5xHG#g1zsWso(nzW}esYEeFMdrMXt<+1!yAcv03hxbQI?KHtw-+u z1mIUB1=s>;FqKnT=!@bI{w&dIp_rorF3`As;ydO;?zp6)teQyEWoaBEJ0n1%G9*aL zIm8KhYc_^X7d3nnr?)5{iFUF;K6LIToYBIB9JG?v{nMD*KXOs7tnB7FScoss)~Q*P&u z+or*Qu|s6yhT(cvMI;RTFq$7Ixu#Oea)Vz9ro@SL-YYKDsI@)J(zz>60(%oCBqm-| zA_PpJbXO4SnuA%pz$=Q~{4@&PN0XGjjJkU+mGUiL#Yef~R_lvOL#MUC>z#R#JQx+H z*1V6)ffPy9)f$G@JWDrak!Ohx=2qe4{gDDN{!{N+Fw=Ovx`pQofSL$ zEb8{*+c;WgwQ5F8hF$)LSPLq0mr>$*#Sw-jo55^5lCFBXcZ(**R=q~n@<!QAj(v5M^tkHUt)U27gI>AEzpJ`Ea$B%VDIq&ojVNo1l zZ&MlWZJqsY$jlHy(CGnB2j8oIkQ(ozh+X#06A#K6MR<>l`HME$ zqi*hFSYv0cWL+7W-Vr%T@uxzwRJrgOqr#=?+IAn2T}dp;t5!Ebkp@@c15^q=*tQM~ z?*82@!+3*QE{+g}Pa9oYs80l^)Q$uK&e`9^2NwO2L0ZEU>$(oYlmZnOt5@pa50XZs zD=)ZGy7n@F&8P<5T>G)dq7&>NQ#rKd^ZIWU%KMMWJwG5z^?}#uVnI@23@x0>3wQuY zvjbZ|v>gD|tc*VfB)fngeVIvfW7o)6rcEuq{sFUC?dwT{YEc8C9;!X+=fbcmBV5|K zzcKH>I2lIKe4tyEiDYN_J|Ip2yW|v6Y@+`muw`JoVa&)2-AX~pGxexO>z3BDMpxi6 zFXzi6+b2aj%#^?LU;J>RVLsESffDY2kv9Tp)0j(yg`+uf)3|kW*)-7&NqcDY0FpDF z75)Tx=;5+)9(I7MnUARS0*1$j7)oQuu_dIG^F0*1?x-G9;u#noTKgirQr*$?xPYW8 zJJJLaRDp$y`C}v!uOGyKR3z*3uhzJB_b-JqCv=3Q(cRZP+Npohw7-H4WKpqJ^for{ zCAN6z{+>MMV29EF%x zf4B%E9*2H}TF)*HBE%R6=hnk$7g#3=rSySho6>=m0{!q2J0Jcmj5aUDuR2XqcW0Ff zkSrvTBUCigUnSBM|bef&DM%&F5SdxA-_Or*GLtmZrQ! z%tn9*yFzq`JERh$4ZTadrTroYdLVIhGuIn$iE_(F^0;ujcARH@Y}J2T3kT>Vdl^fh z)Eire=~0g%2R-aV?x%LE_I&WVk9ytn^XPSRre>^-$>9qMXreO$V&SaZb|lQ_2g2BJ zp16r*$-c9~Xp^oQE>6$8CJp!*53oYV_YcZ{cFnhw?7nYbj5+XckL9e6aRQ4^T~%tC zsS!mL*Yk0@+co3jT}5w-GRs)Xex%=7mdNu3G|$rel`i>A0;E&MC9+b`9)xWyaB+F? zz^XTZzt7$lsrue0AYr!^M{iQfl>*e7Aq{lCHY*(4wXuc{6)|IdvO);|Wi44G0;vqe zEYVVUmrm}+5$qQ z-U}lT2=IUSSTsvWC+XoyY5$qV^4gf=sTN~ih6H2>K#2}R#o|@&y~j*vAGI76QwAFp z2=ghIYW38Ts1+bP0#kb?eQFf0nTmc1TaZyIm4Cr?#*c(AK>r-}1(l^s7am~0ollRL z_gMgyHz%pw90@zg9X`q#-n1>8^<&tv21^?1G8O{O>_?c$no!)nJO6PDLE!=E7A4FI zk4$*c8)-($wsGYk2fLt}My(#pcG>B`_TV5h8FO_+JKURGlLyU!p=T0pS)E#vvCrxK zq*H>LS>p<+H+c)({F!HokK;~50&e(#4w_3qOkU=UZAWtH#1trE#nED}k<*%%_d|hm zzJqWJh+xo_1sM>#Y7Zxs5WL_;sn}KLG4p9|*i&Zb!>nhHoCEpdrfhmHGuJ(2C9(i0 zex2~Cf@&<{Vz9I@wo#OQVO>5JAQ}rp5SYBB2{3~{1tz~~Bm2Um58pSL(tOH`!0qj0 z0v(r$^zR1^U1ZNw+z=el+J@%Vrxc4efU7 zZiC-;3%`lA3e9cBN<2<7dzKXqiZN-pUGJqS1^orWl+9%JKBi3r+ntH43OKsydN2u) zbuK2{(H*sP^Uc#W=a}+bsp3S6V+d^R77l%H7y56_<~xp07$;S}#EXIC5P z{kvP*^TjCV#`>px6Javm{gZ^WD$@+-!I4(okzPs$P z#B1f4*ET{c%}B`dP(8dto(H}wQJXEk(f7S6YUlyA-{PAYdQh*;T_GxWb6z#9z3h7l zOuSk-{<(6*(eTULh&ti1Bw7cdCA=g$9lC25UNzJ3+%4Sg@X?4KA@MI^KOTR`G2Ig= zri~PQy}{yquHE~2J~%bnYP%!_E^EAu;dY(@aNtTf=yfhUF~<#)Sc!n0n;#^(f~y0P zw1m#^!U8A%JSyCa9t(!9Fh>Liq-m8mSp?>96bP?;Be0nKNEvDP1*@djTVqE)`-q?f z$}h03nf(;276jkh)K{2B#6F=@nhMy+lZ(Uh)TW#CDOsS_$Q2u0-9nhYm}>ZNeCy>b zaBe2POZVoULo&isfky3Cb&n_V-Q6)BJIv*SKz`b zZ5_vs-|%Z;JT(AG5{?B1@F)f)7mN@ZqxNNSNQA?>NU*{uB@cxgAd)!3Ox4PYdZ<2# zQQbyf*m69FzLc1{y-vvWeJB9*8eZzT)h<4V$d+#&GmNWexJL{?$9yIEAht5Q`7#02 zMxRXM6`)fpDnDh#t&`_25FyHx&$h}*vV_(sJ1q&=-V#4;5A&(j^l($;KfQHQGT)eJ zwv{TZpAUyaFy9;pmsU74oHfn^x=f5usc^&E_vn29zJ}};uM|aK{uL5W_7GnVgs{%0 z2)tQ4$7a%xDNdXD5`4(ZEMLGqK-4A&Qqt%!4csH);mIj1#IVl`eAXnzzMH@PRai0n z%#lK!pI<;zT1jk`r>xmUK1#Xoq5K_abHYtA{K8zf??p$7?fX z%&T5A3aBY%e=3T~tRXAbcW7nP$jltm$M#2oqW_KCiJxT_&8(xufXy zjbN1-r)O1*RK9K{1U}7bI<6(2QTcZMMoxxF#QoI%`dy=6!^p;t+IFt&xWb*iG)Je# zaNk1AN$4^Q>svpG-^D5&pa1&Qa_8SCGcr#XLazc-%)b9HW0>8eSM!2>)=Nfm&`E;j z_r}6jV;z=pZmbzH7j_1cw#&{(+didE=1_xr7nHDS(NM+nR^XF$?}mP`(j|8gl&!NG z2lqM?#d8wpV%i{JY`-W0xSXBjil3C-ayN6&Xp+GLkY^ZUz~!*qV#{TddX40pE*CcE1RycR%8>k^}(%P0+7)hxB znui;S&+)w~2-ARcxVx^Qre?|ui>oz>Yo-SW$*MAG-=ziuS0oj=Zze3#w8vXOm4lDTGd!zXFyjam!B*y3e(OHs4y$(sIixNu6!zjvdFW62*Lw8jWywszI6B*B-+qGp%Z8)o1+#{kUD42kOb zBz`#l>O@ z*a{B~@ZbDg9CH5h^#^^py9xqXQ*HaPi)ijoCQ@H#k$YS;J}Uj}oly^E_gfeU0(&1F z7w3FY-dIM{RX47v+hZ5T1h1Sj&fhn+%w7qzx)lzd>LeK3yL1Ri@SFX&?4y8rJo}e080n=+$@7m`SHL@jDDh&w30sCIo-g-!UYdT^(&hXpt6OBzTo6b!) zuB?g|;O=?n z>5y64hs0*_dyTg7K#}*FK0*hQRijtXP@5+}fLTc$tK-Ve-%t?7j5p;BsL{s8Aox{m zQ2fk|n$W3N-gSm@pY-M(`w8M26_|MMe$Oa@nm5xHIKyynz~*b*B3^k78(MmnBCNsU=Ao{K#Kz?6UoGQr-0SpsVNi zO}z|#+>pOPLNyi(5Pc41qP^%Nqb1Yvg-=W_6?ML-ur&K!ULYE_|5z{4GPs?TU(l+x z%PYml<-qq%Qu*Ms&rfHpkRd^=-l2|=G-QQ$4JA4(>Z19euub}BCMq>svL4JyZ8YVC zBR4w$adXzqPyy&Y%A9?aO8fB4gf{Ib^U?%VNKqk`8jHRohfm4ehcW8}d$3Y~q1gdS z;sAfrvF5tLfR`uPm}(Y)xT5j_mT3myI9{@cus_?Q1!y>fOFg#;pEuu`y%(pOMeD^S z%_U^4lJX`a<1pf`)sEG`n?%?CiYxO&0YkdyK~82rNs`nelggR&1%jy^doYgp z;hL2Qp9Q%f9Jhy)1{Fbubi+}Cra~m}@1bjy{{N%u9i!v$-uS_|vDMhNZQHipq(K{7 zO=C}NOp=LhHcn$SW`hP3bLac}@9x<>XI{*_oafy8;Dh_Hn0_+f^;Xi+K^>Q(p$Tl3 z#=2vjoO3HeA+4v%qEi+~kghVJ)0iH%B!qJD>BM(qa zO$z~cfVT54t^J9OEa9veV5J<#LvDRwq58Ciy5XV{zE8!_(GlIGxalsu?mz>R&NMPR z|G$zC6Zi{ZQWI#)vwKM~DSM-Tz~7?K59Dlktp$2mw+WZlFebe$9X_>#8(-ux2F-hj zX!(2I?#onOa<;nxhWed>PmKrD{KvlF>8H{_h(H};TuCxK+E1+TyvY32x*gaiHi$3& z`F|G_g2NboB_Pd!2s83yoLzHGoP7WDenKn|2Sh&I5Z&Fh@TEvc?$O(#w*TXts1Fo9 zxzJSKd(f@_%H87Y5OA^gYX!l}<0p(~sK@|M&L1`^!b_d#4U!H1cLe4K(d<1DuI&A1 z8bN*EDA~8a{C>P(YWiU5QbBO?f;JOz#Y~%!uB0mD!7MK$HQgkZB@e#P|NeL(c<~Xoi1&m{lEgwEHM@m59YYpI zLFTs?Io%r<92VWqJF5N10}BPpe_nE%vl#(ZZ+ zy! z88x51eWJMBArDOaLfyuauNj#bL>fezkIoDFQrt7aJFzI_+GvK2fvCZ09$y)HuJa`#1-C%2MCAG44LP2OdPBMx6A z5!|e*VLJA`FTU=Kuv7AC0!763ds_JCH0D(wKHqjQ;n?4L0ng9Ql>KwG3sJ)iBz7MJ zkSxLZ%QU)*5z!fOeQKI**Jbgy7in3zB%W=vMpS}j7GV_3f=#tZTodm|y8V&Hp&?5{ z2$Yd=ik5Glo~R6xEO4oq@5}GMCs}lhXJ{lsE_M6{{s)*^V;=gLfN;cP#DG+-4mHR^ zC4e@AEmjm3qVgV7Bo&uOl^a^Sn~N<|FIOE(1ysadm9i}^GOO3z9n%B~#4Mnc-WgK; zunIg9Zr5Wq65~qs&NJ>h-_&udu=9V^jWzqGQA9-{amx444;D4f&h^JrMdoU?$slR~ zD(I)B5F$_OCe$Q&fQ=f4_$L>`$tpC!u$UCaE>>+*!VlXNSqdmKxx}%NY&|Ex+sPa8 zx1pmW7FqffZ0mG(77>q7%opbc*|H#M`%bdt1pl^1B%)mu5Cl8seH|XMw8RTwX6DI3 zE1m1;yd`OI%}nIr*nV4K=|-2kBe|OmNVN+W%+ zJRi|y8eiFs+d<2IU@_yFseQ2xRqN+tkWI##N=vB9MvseZLMQvfKRnitjdSUXoR3H3 z11gprSuk#MMdt-!n50($7lMQ1$O44*>qDPb@A9k|sx>ajwiqo!-+=HI*)u=796;48 zXRyu-OJ~vYAoV!qT7`W={&feQcF6KW2u!-}-D~OALhqX^S5{d zf8S<2gEH4`u2=UTAqi23*?kIcutul0p*=5Jlo@2Qf33`&*0&k|+;xnZ%U{y4?dfg~ zYPkMVk);To|2_BVO;<;nwU#Ptbej45ij#p2w5}HSg8e7~ncY?~)&zh3X%|DNag5~&f5 zCF_fw>(a%DaXu54|1~}oFIz!r6j)tPAjU}7P~I9LZ%F6y*kot{N@AfTaOd9NfKq{hUzEQI}` zw=j}hH_8|dby5@#Qk-I8J@eU)v(~u|uI5i%{=36ILmM|N{VPDPiy6f#(-=6=qyA6R z_#Y+_?}1Ksg0Z9!ba|6>`+P)We|1|4z`1BJ$bqtK<3evo)IfGYlxOnOQW3-&B4!PN zfvy8FW-%PFEkyVei->;_c;)v9#DmRewDZjNZvODhbTFN^@cIN~S`w)Qslqy4`1*?6-H=nqn;6O6`U&1PChkNMy2=XXew|Li{674D* z_;Ab1#`2)rO==r?R8leWrv3&dYhyf{+R4r|^T@=Ph<&<<`<^`|w0ANM9m0$uy`ZV& zy9%K+_^bEc4E(Ej z{v-5Hq0d&8j|S~^ax~PloS8jx>j-D+Cl8*BwwVphvr@@&5AS5s)*H>#Pu}OI?sQmA z|H&fXd0CG93U40#ACP3wn`cB7-1r>LRP#J*L3_P?v50U<159=IHV=`D0G>D5(x7(U z>HIV+9Q97oYN@}4mkY9dKTI68UH^TAX8$_W8{M=H6qH{#a6^-~OXZ#kybs=woCns_ zm=#`EA|DGqhRW_Bz0Oggwn{pDciD~7eRaow$!2o$L*_N5GteETos$|G+6wdk_HB*_ z&6J-ZlV#4^3nWtr2Q((lT_RN>UYE?HxI#k9K|V%|h+CZ0K(73Y9=cpKj9S+LpC5^g z$8^;onxnJ?B~PV_2s>UjsV(503V9veCoud8P`u=z%{sl)&gW-Xq4}jSj%ji-CxVus zYt5qfnZ?IBe8L51%yp-euDpt4isEZYB(kc^l~U=BVPdiOw^A**P+3gCum!7J{6jG@~p9jrT0Y9BSH+Bkx*9nA(+S<7_I9&bJ&ow-$sY zB9F2AJ*mB1XLA#UWr8%7#X($_MTyY9)=*<42T|=}R+giqncbT8M|K?!)OZQLWUW1R z-GMZn2|OOv5^z*xx$%jS0@4nFGKGW^&NNsv4%u`CDIC+eJgP%OGV({gHBLKQ&}0R; zn+6qjUD#O%Uu6A|Pn#B}!C}zv)4ngxLJc;Y7=^Rb_;5YwZ+K1ZkF+ zfPYw_>_5%-SDv*R{r7Unb)T_KlUD3$8ib0+TrvzNYu@{?zYGljqi`wQ_hnyw-+b0R zW;aP1T`_s}{A-yZn*N_MPm_OHolUm(B~3$ne}^Asb2orST}mqHaj|!MQ##{y$iSK7 z>XYf($-^F8Qhhesb-|@xjbedD>xCu}+M<@5dEpeFj))B0fhPSei4t&e!STQX zMkn+XD#s&tpZd}=X1v_Pf~dj!fPL>adB{${=QDF}nskBa=+b%HYv{{TA`qdAJjM9S zRrTQ1gSk}3QrpP`GRG`2l_f!dNt9rognKXQ85+G<-)o7qfV=NzAi0QL<@ni=7Do!3 z6f9_O}L3IHW zX{1oT1QFg9&dJiCi0b?+;gS+&3n1R9C~RpDM+Zi>-y|d!hN_5=1tliJiec$%r4Cd5 zq^wovDS!%w!snZkrs|rXopm!hqC=*F{s1@Bi zCx@~aI|ZRZ)#Kca`3NRR)J6RM9Ue16#W76*la3h1i(_N~S7ZclJgXElI`QiZfZ>c7 zF;Z#{6DsLbA!WU$Y)H1=)0am8K9t3fh=zyVm?KdbkoH6urNIiT{BP+dwk)yy3Tqk* z8cqq{&oXS64Y`i)*qcN!AzGwHBg@ZGIg65zLkUbH8Tt1G9=;X5BvZrDqHslrLykpz~`nTA!hPrTP_RLIZ`mJ5B;Nlao7a1VEmi1A3DVZ1=YQkPg4! z?jU^k`}0}v>^JUOI{KxfBfba`Fd%OkLkrE_28+P4U4-(e_;aOl_`!yHQjZTw>evzAz2Sk!s_RxCMR1 z`gO()A9t(+!CNnCAbAC|q?tCwzhyzlFHdGI&b0dTo8s#_4@Xj5FOK$hWcp6(I- z!a=s^&l(%k7K-$Zt0dBUn9*nONd)FS^CDhPtb0_WrP-F zG%eyRE8S8$Ytp6%$^>A~un!I*`+zITMD@AKf-2Tslc z9lt-Pxj|!TE45;MwP&j%g40zokDk?QJ(Mw){f%O9*!IGn^?KI@JqmqTFx(CjZ9>$J z-nFPW^V?l5R4N-Gb*}7X4f=4mR4$$`;6E-sh^{%{@palM8NIC9xLJ*T@Z2l8@QeKF z3WvWLo;B8?pEq|@j4xs5=WsVUi&NX5_*!$*h*ag2y>e-1@%3-e7Ns1aSbQ5UG}rPm zX&=NQX2?Ux(e=G8KWp!(@`XL&po!<4OAuwk6w*>cGUUgFLX0TjhZ+kB3aEY^s5kRO zCFzEjJ0j{y&oxtowSvF>kr+v4F*1y7Olux>c(-f;@AR1tbPxlT9G{kkk#+UjL?PJ+Zyn>yVoGI8d!YLnaK|$ z4>QTX9dK& z;hSs+dt`uW3504Qk}2(s?AIeKHykLc=f+yc1Ra>;=B8C; ztUbEjUj>w?tr;TKU?S08U-x}aBDd(qe3*;K(qLI1eEW37$2uwxUre}zKy%L`GWHZ5 z%VQ*>ev5aHyF<~UMv5O0MQg}Hg?d-3D}4*!xssE1k7pK4QYb(cxwn9cqMeJya2U&e~pxcA6Ok6lb zo?eYYo8%$43ZXyGEQcNT7_F@ofCBq5%&OCEm;Bd^N)_KeAPT@Ej((M-q9to}7p@t= z;X(8r(cpL}0nx;p#>jms!n?7TF4=B>b~dx&)&n~>+aB%gC^$CLmWVy@DkUtROEEcu zsqyD+N|ed`wfQ7@>kW}ipOL)bAU>NqV#kpXNL{JM5WXb)hoEz^Om?o+tsl$wO4Ql* z=%4h9f9y>@h3~0R7jzA;N6AmIpD8z5Dbb?3b^izUFcoP{IGYK6y^dfr8+!QEh0grh=RI}H|Hk?~ zpQ+dP7ufgRAjoWU`z&|F9I_OYO?&$?^5fsheL?0u*0Cel7iuG@d(*ml7Cg3QUKO0U zw4I3DWL;(q%-XOQ}6h8-M;JC#d}I`WhvIP)f2Sn-}I=H-S>OX z<9^*kGjw`IW9P-oaVuRA&#{wj+yAg_hA)5npWqYdN$m9!^EK;rc8(>dL&>GznZ((H9+d^@x9JMB1M|(}#uFIpHur^IXBeG^*PI_c zBR8s^!Btt{EOY7?e?Ee%J)o8_>w6F%Ua0P}=J%k%mL7NEL$PD>2J4`$r?<{4koJrV z0UAf5tVPfaW|P^}tio}Mm?fWjy>;Jc!jtkjiMfrrx$;1+#h3tLsGwy(iDxg2gryKX z_jtZIW~lG45Z@%yR9z|jnR@G<{$8IJ?CpvL;V5i!mb0 zV?xCNRC$Y2m(5t*DR-4W+fpttb__7wHvOn_76@orls+tZq|8%&jn+|G94&}bP{MW; z@Y>dA5^!{=Sr(Af0m;9P%G<`oGXcd$aFM5QDsertwTQPCpUd$=9UDH{kQX?BSh(j% z$ILi468NxXCSHN1_r}RqD>-fWdXm99A-G! z-#C|c7u{yF?;(LP5u}4D}69?_%MIaTb#07>jI03 zm?Rf?R*NuUiiltUQAV{0s-EwgL~}4yyKrcTaJjjE1p`AabL%QZKH?odeK}7c4eH^sK8IjfS(; z?OLxpt`sVW0QbZbCpCo65xRJ*r6XzRoLo9I)CG`wFtlkroYdF{t&q|RK z+Hj33M;R>$b(Ot-LZ8=4o!x7>I1GA`Q@fiKLNr&X!;)6)QmlESSpsmLc$f4j0jus3 zC9J7xw}$}$9c^cdP`|tqqwC{z1ZU@7!}6br?@jtiZ~ae`3EL{XY^64ihqP5rAO28} z@uTbVpq5x(_v|B0?Mfwj%H4Jyz@+70W%j*+Z}cQp_w>#TudOfA7D1}rGg>hN(s!4^ ze?iWx0lO3_-(mVq!M{F|2g*`J)cdu|tN!wL5NTzjja|w&{gAsBk`1XE=UI7I!d6|R zR~iTDF>(e4O6}cD$SVGc1*jjw(ruqvY&$pYHxO2b zx^e!dSb$_2L;c>(k}$@3tE)6@Yiq@nc$>h9E#h>1TyaTAT&8IjrR)bZ+l z+6(aeyUxDgH0*g6{hG6yfO&_-zB!7vbscCgOI|d=v3`ZFJJ?|2XOlIV)fkC>FI~DP zi4Gb0m4JOjp7yt3R+?4L{jG;COxsy`8b@p!5L%NzmcjQlYstxlBG{}h*2NyOW%<+eW&6Js zmbO0?pMxZ|7rsaJ4+O)p1dw5M{S3P!96gbY7}U(tMLE(#k`(>v?t+3>V?AOb#hN_q zU_p{xk2Kk68JX9zR)pDX0iP(gHh6Nv;AI+(MjUIfh{btM-WsX_Ma2JwPov4HQV&?E z=K>ebSB*!S^Tg%kgG)?I45dWK^BX7P|Iq@FHbtZ{W+?qSgkeZmijlJ>qE8(Py8Ut zr<}yN@whMVtcDy7;vR%O(cV;F;MXN zobavmNS=PguPY%LCyL3`>Pb^2_YZ`BYG~CBtNWzECXe-l_`iTbJc|nKR0Xrvfu?ng z7q5NdI?r;ISg`QpEn<-OWb-{m%?u1qek&m)+Eul@u`Mn>EKzvgo@nNZ1sc8X*3C~} zZr2)*aR>|lP#Ha+^a7|fl^W?OeHl*)tw=g(PT{l`5dX`fi+(zh%S+jiRlo85-S_oY zyfQM}IK>$yg|U{j^@>;dzT zm@CN1rA+=;G>JwY`NI?~i3n%JhN zyPhJBmc=XC7U5noN;8sA*Yli;2uV%#I{hh9W~C{ckMWBfn3DOS(|*fJO0D2S#O=z1x zpadM97Q7QnsIs2@w-dNOOE{ORZka|GT3gVbzfZMw_l@x`)f(hVM6^##luIc#?*lfN zdTG%xn_Nj{Z8ei_GQT`(`3jRryB=^6-fYT_FWT1DgARIIyf8AY{=39AHMccUrdH@b zh1!&E?mTf%funO8bjqj7&ckzg4LSuq?E`wx*Oy()`>gq2PTQu>JcM6d^m8u|0uQt; z4zwMpgQ0Eg8*VXX2UwQf-HRgtx*=pdniI64Dd?+6Br!A^Y_-!*!Q5mY`TQ!gYa?C<5LwP=!l8i%!rEMtChon60L=kfTU(0yn@iDK%Xu z=pEledbHQA`ivSt7w-N&gZNSYfuGqH_>Al837cLG zmYz*l`rPsL^WlP-1x*_R9e%J5#i`Vm3R6xU`uQB}3-gnG{_R#z$V2bqBc z4bjf7vZ%|KDXTrL+IQx^u4Qt!D>`1fD#p+@kEyZaNi~^1&|_|p#Rh(4ubxiTkXQxZ?5+~N8-fTV&xzjb zzQK1T*zU9~7j3h{1hbACph;j#5Y91s=LeIud^j1nVyP zzO^kJ14Kb?m%~rrIy2~IKaV_n+C6eiB|&d8#jIpemb@E9ef}v4!rRCQ@+;g4Bo*7Z zox5rM7tQ)XwDmDy?=QTEa-~OLHuhH@pG+8g|3q=p)1O%=-NgSjdKS??jZOc zn=Fw3XA)oN;@|xcJz2NuY}?jk^AWiqq}?6Gh#?`SbbEt zn8-r(eAv8j;WNI=O+;am5(`f5LDKb_KzL2ylD+{Gf(DC_m0jSFT$PS=i_<`>>!MSF zN!PbAxhk98k_T7;cZwfWINJbx>@a$4Bx+n_$rbPW+$id3j1m{Jkh(JtR9M|fDN9cj zjD-TB;}Ggc9;k2c8RHCeVI=IjAkg9tO*{6rK-d69m?RoeTn2oYqz({&bZjhn@^JMm zuXD6B)Wx zNe)8XrIbjR7H-UNG)Uz-oJeP`8|(OEu^fKR>+I}Yw@8G<%m061Ngq|N2qP~WuBDpwvL_(3eI znDS5ag|W6EEOkA43k%6#JPF%E*HK*jZcDhcunB1|x6JhJQcw9U5H!I1@nQ%Rw~f)V zz5qN*p5%KcdNMd|cq=UrsMFh14#Yt6&A5M;SXZ_gk5vT0l|kAnJ4J5LfngV(-VJ25 z4=eb4{zgID-R(s2mSS@=#Zl-nnkf`KDU#|=Dxdcmo@W{RpX|ss#V-Az4pR9K(8Li8 z-F&phYu|g3vom!FZ$ZJtCUXYt1~6K%RTpMZ_$B!CZRa0C=_PMp+qD0JVy`B!Wy?|G zDcs?uiSB{>m<4#JCauDP2^A(uq944y^I^PP`cZvXL7oQtUCgZDQv?$Ur5-d{7PNc{ zeCY9*liTj-@LG6x(=0gJS?b_=1+il^cq1b?&VkP5HUE?Q*TE+-aWf=0_2Q>DzntSQ zOl1JlzVRn=5p_!ag>f!Q}>B~%RlgaG(3rzoU+3_LhAwAF)>f`nF0Bko_vV1~?U z#K_#W`J$w#YWT$|B2?<1A?1`d^0I@Bg@%Y6oZ7WQeb7rzYMt@ch8dVjMH&h*WfB~S zi%y6L;s2rZJZJ?$&y0{;;&HVjnH;wM=g;u3Ux*M8o&wWCkw;!@#EO#!8^LQ6OTXk3 zda(i9K0SGG*mNz|)DP;ky#|KM-HSlxVuRxmnrT!vC(M{sdfNYHe+e5CQ5isr>-y zS)YZpn?nr;CSPV&+M*&@Zt$rrL|78;@rFu3W!PGJdEq_rQw^8hF^usILkDa=>73+t-8o2v3Jk{*2=BbD|E9J0QZZz}To<_+jBr0al<9!Bj* zI<~*VTL-_w&Yo%5m&cB2xl)0=4_@L{AQ}V@j17hI3%=MR`p(9cgcp65=hFT~PZt7E z=X{i>g6GS@@rGD5mpNS~Fu1>LndQcYNIf~$x*qp)#UsimQ!2H*-(@q~doSnuI-GPU zoFH5S`c(7Kw8)*3_vdKKE-I(4!4rF7Oq1XhYsRCI;bEDxJSY+Y_rkwm>d~0vdjp=R z;K1{P-bZ0u(BHDv)F(fJgf;e+<%e_d%k7f=Y{>rDwY^xZ?M%ehdg&1$OO%Gi zv_s;ePL^OHi!OJJX(T5?LTImFDwOwfV3{tHr{ZA7gA0=s@xMonm4PunJA>@`iFO1? zNwBiAc2r~P>k-+9gAHxPKfp}}W@ZDwP7vwP$p=CkU{|NU?67~_u;&RnqN*;)r2JeV zt`<;U9)8~#X=GVBYj^+i_qzK^Dfs%OsawVS5bn1sgiT`H-{0>s8|=r5m%Ba%g7)-- z@AQrTbrnPaey+SYVg8c@%{$emIOUot^Y&#sS&0$kRE<8Q12JX&;*jVJOQGT!sS}K9 z+kM}8=9^}VZX`tmhex!gn5#xlaqlkOVswZywambi?S=bRXTM`{vL;w~Gab)`pm`Q4 z?LegRH$iXgg~e2y+N1RR>{Q@Dx_P51jUnQHFW4s4?I}*LgkJ$@P-L%zV1bV@@vFS- za;vFBBCQywbq&1I(WU03s>UqX9bwRva(^~!Y3jCrso_X*UH7cfv;tU|UR)l?8)MCs zxWwB|rVNu>u%Ik*a~Yb?X5~78$;cfyO~Tykizs0lf|tJL^kVqaqdUdgB*oh}=>l)M zG_&BuiLUus)1=Bv$p-qJOPMY|rp>$8jf;;fYGb=^^UM|#t^wnh4VQrby$dK)5_4Fr zXo~4IBO}AFJLUfI{h=?BJ?J{lz`&rtLR@tpT<{?x=6M5GoclqpnOm^LDL}yKv$7bo{ z)4Vq6CkNrOpklI}_Pk9vdfsFZVc8{%woRfqt=nyhl&i17EPN~g5D}^cug=Gr7kin$Fc(mp3grYNd+AG!ZIxpf1tR2AyyD{GvXiPV zHsCoc8hvdV78kFj2Mzb9>zpTRBpI4uJ9CvN#*l59(Rp?0@@Q=V`<1wJR z3|w(N9{fVJEbb%r9i2_rM3L87h-%*1NlP`)yu9F#7j3VM-$kkLHEkSlzJ$xE`c|bp8b@O>eGPI)1n*G(h z%YW$Wp7JU$ZWfTw^y#7fU;!&dk6TSKBeiOO=HuiHCBQ+d z`APUap#A+NvAWI2h`myZ%9*2{=}i|$$*aJGZDqMn{=YDXtr`d2mXKRQstLVXt^{As z2n5`?9zjwmH6sG>uG*H$W_H8jl!GF@%@vHRY?{D{b1lIPtQx<*=BUwEL3GmB;7h%C@M2m~a^Rg?Jm7xf)=@o;$|dOzkpwfJm(sw$?vPLGk@H~)|Pb}&-e2JcSWZc4!E z6c5Ph*N$(KWG?jGn#+K0#hw;^;y@X)Ub$Su^(&awzP!U`L#I?sI3bRcHoJUTgfE7T zHv5Qnr~4?iYRp|!FXbEBtp6`=T`k{f1#KW#j;{SP)Mp6K?BP!uV<G3DXWHUXzt`FAIkLkIyj)a%0ReM+*RTdwY~UpVJMXyU6YlgPJ|3I z&*`-k8vsjskWK*J*>#9P_>Yw-2*TU#c9!&SQC4YV@mV2=^{=@v8U6Jy@9jvP{c#@0 zD1d@)!$WA2V~YDw%f6dtSxlV|6TUBu+9IDHNr`Sx=`&f%_BSiz)Un!XnkPXo#wvRH z*$A0G)Q0yQo91_k)dCv{Jd@@{I{PRNTcZBN++J@}sC%SOINk`>I zuWB!Yfh&^~Q6VSw9|>>}T_LArEhjY`;!#-})KCNuokx z`kZuqeGQ2uJ4My9A;NCpl1dFE<^(I-?ZNW#B!E9l78d%fegs}~l&TK=1}pG|XHg7cR`@Tg$JV7A&lD4E zw`@kP8SJTJNGU!5cqPacmMMm#*|56MK8^xf;NR`nHee;li6u zH>-lXyc+A>w+lIR`C7TQHelvX=vV zhpcw|P1}l_jPiYw>+?!3A7ADyh8Zi!?r>p|)05mP@wZ2|~iGjTZwOW?b2iXNI+Q(NJyVg;9X*#AqZ|JAP;QJOhF0xR|o_gyJa<{S>2 zNqb1!mLCeJ@7+(iA!G9JYRms}H}BgPWy3O^*(ETjiue$`)ZKfDK`wTF^6)g1hg)Zw zbDQSyMzj30BbRy%f>DM2EU}+}TzLdX2vpUPFr;N4K!(4)%z+U%j(#UH63OuHc8@(j zUqdbEK{u<>ln`MGqg1f%b#JN2D(0_}XFi(h1O*JWiE$0cAXabYv>cJuHB)*c^i1G5 zQe+nkSIy8(_QIM?AQ{70s}XxzCGpNP$;kflb9tp%2kYg^8#so=6|XCSa6C!K+nQ8^ z&nXB-HGe#zp4y>SIV10MA`9)5*xM#M=9GU!k?Sjc?{^tm@hC0gkKy7JRjsg#4|q^4EG*y8JK9V-zQX?( z=OLf>w|_cL;O9HeKOL#qFs^QHB_qs!(fN#Br=)i(YgL2RTGHwSBLTI87ip=hfFFyr zsHvX=g7-JmqlU3E)lPj6!7gqI)^FRwAmJ-1w1KC_BzrXQ&=GN2mdQTDOc4ZuU}<~| zLfcqH<-W@$juiM>k;kMNwB260ml9h7ZICA%`y#OL6%DP}C1@efeP3!?eu9=+R^^X> z)a>x`)!vhQme{Sf$@9!Nj;425l{c__)(^4KlkiUhH$4UIz2aXdlwH6Ib2UDcTlQiO9O!R-g37YT5a!c-zjbzsaHJyath3zr~lt^gN@E zNE641m`mP1=r`OD&|`hqlcBPwe!kGnBA07;Ka0jP+Hf}w&($IJ{RZ#6k{}Ix^>`eF zj)60CF4^Lzm3KF4Yv$6+a>@kVrjql^rSLUTn(&F=Ip)I-{nNYG=cR2#VWiFvT#olK zo+*@>z*xK7(n_O(Uws5zul~+TO9eO9Ab|Xn=w7r4j;c$lT`8|{R8ZfJj)313Kl2~8 zj(lxrl4w#9z->r0KB~FsY8LJsKP@l)2T_oVq z-B|o7@Z&wO`}q`@KWo}27Nt}DZmHjg#G3#)tZ%K&4 z8B$P~Z>K`HIg^!jf9EoPaP*N3om`4Zc&p0a0?%TCzK}*v;t1UQQ`cx03H|*E1GC+} zh(kC^qxL7{N60ojjCsBf=*)>IPJOm$aOSh!@$1PlyVb6^OrR~m*$zOpASaJfPe+yY zJfjWQt0nDzhb1>_JJLb-arw|dC>kx@_k!^&$ag(Eb<8Fm(^6}?B*?e8X!*CZ9N^Ue z&s{_oq9J_z$s-OuMr*zx=*+@7*7qQlzv;Q{2{LpUipnKROAVI_>$_I&j}b|6jz;A;#OQ zbO1G(d9K9G_6+rlxwN5W#nT%L$S*Ff=sz@k)EXAraVZ{rS2hxYG+ZWpp)&I zh)(~>)6B8OGIINysHqpq5xxz~Vq*{axLuP%o?6RRGNB(`%2x0{Y)CHn-v^a>15Z2T z;e<*Y0#COEzV^Hi@I!($3}H=75;F zCBJM)ItC-x&Ei@hGSdL~nE#=^(w06`SdK1kS-$%mDPP2~{&IPah9uakYnGHx9JrdS zUwguC#kQaK{OuG-sis|mOVr;}!gm)5rM0mvKTmP=>qPV%#T*xW=VdJWYhvZZcC4f% zyDG@Uk1ou}+b+8>|Dd+3=|Q3Z1%ZsSUNPc+5p$9leUI9qCC2$U<*Y9FZTadB53eHe zp(RL$6hx}leyzf)36Pc`Et>SbE69x3gXU9&O*;linRIgWF zs~(l|@s$(veRm(OTjh}pgxz0E3U)wZ4AMN53?xyv~AFV+SxeK%5-O?NQq_8o8T zQ2_bUM(X?>Np&(Q?Z7tY&n%iHOhDWnXH*QRx)}xXX=M1kikzPFCC8+e;e#@6F-309 z`FJHq;N>iRP!V>R7k&aAD}uDJbTwr0ltI_)@;Q0jpe>-v=WON=B<n6#}>(Q-1Gw zIjNg3@%&PKD9c!Kw+spH{S(kb^{Z22S!OHX8Iq~iQpwS8Z}Nqas4=uL zi*dSE>UB40QKw(3?L?ZN?uCrO*G57JyK3M_;Hx z0}`Q>hGfowvzP7v%{Hsi|G!BG(Mo+aHVH;SsYRMCllam31P_u8WAa{SH`E`IaM6)k zws!7%*MXOk^v6J7kGE&SptqGVPA;y$jAO0Tlbwvq2OUmp{tNN*EZTMS9a%{*27Z5i zCi0G)sCv5(ezIJ6*^1>Pp|e~M)28OefU8qn6igVsBb>sN`piQH>Uy$OoYM#66sVNa z9nJO_`G_TNl+{DXi}N3~=f4^%+T8GVq?o4EV>@fjds@YxZ~4;x4moN`KwH`2#+mju zFY9pn?|@`;BTQ8x-l}xi!XMVpA;lsr%C29y6H1sCKY9F1_f##QN3?1;oJ8Nk7{dBL zw=8^2?J#A^4f`hV@ecqFoztP&37@88S-!Gwz{~1=(QM8o0bfF^cBS$X*i%h>aUalf zwlc=SjWd=^Z7K47j$s*sUL+~WK6Kw`Mpd*wM!$swYfWcO3O3DrS8^Q1q(Td^=b8ZC zYc2}hfE5&Z3-cYA{-`aqLja{SIilKh8OY>%1(88K_#webo?CzIAYn7> zj_LY#dGE&vi3sd~51cLppcS5vJ;44A@?z>~U6{>l+t_Ja&}&tDL4u?oDf*!2LW0NX z-!MYd8Zn!@kV6sI`P=R?4)S#J7yZ8EYh(qsX{Q#nT#+XcGV!1guTGi>fQY|pZS)@$ zNTZx&UDu4I&daFC3-Th^$-jokENFa(G!K8~Ql%bhWgv+*Z1dT-`63A$KF8<~=Gc#{ z6zj26@BQejqaqcD$REUoqu_)SFtt-uxM{CxX1?)WVEYvhHjJaTTtK35qmtnaC4)!T zC!a;?jF~EB*SOL(Ol6!JpbB-$DD5k^j@e|Kyj(NifI}kkz216^3eoB+MjnE@!u&7i z%BWLX%3^L>(>FQ^7rgPM>fok1{>QUPz6~AzAH}af5AX$6q2>;yhcISq`pK!yjTC48 zCrXn;bJS2YsR!L8cL&|PdbPLn3=x5|gf)a4tLXWzrKdV8vqir2Mub+NN?(}qYyUM@DySgK4qb8N*g9(3^vlNZ7xyx7;yG~CPp^~b>5 zob1tuYwUp2o^)rj9-DFq^rA`5XkO9&CEz}n3Xa&WR54agw;XzidC`Y@zLWL$YYhEK zxOdnpNQPQ7;4HYv*ZCzoG7^59oPj!~=l|1v-jZ&Y)sbK|JA67$WV~&1Qk(;1F{GAd&vr2;~HxJ9+@fGtCq1@88Sca zRHG|A@MIAaJr;{jRADyB?-%GwNdBf@f5h9Qq7-(0mSPJq2$%O$HG@5Pa-IhOmPMGx zo1-8U$qc|q7wJ3wZ=zBf;Oe4bX97x>Wd@{7oggld#x(mJ7kkHL&h##(g0bHQ=5MgI zD*kJ>f72P~82=)8WhPl!S=kVpnNWJ0J)a&ts#}r8WC|CH&RI3)%0`{Z7u|qh%P&bj zhq@KoN;Dye#ZBjSUQ=p04bNpWi4;Q6|2r3P!)n1LfBAG^1r5%Z)FIlHK#yZJr5I30 zM?3;jYrBJ0z#rCMt;~}`l*z5=3TAHZdAFiB1{U^1S6p1ZgI5c3wf59ibEu~xZM!v5 zgk0m(wmL3r&rbJ2+6c!bZ`Jw4IQ#QC%~HCz07)!JvDXulUq#PCNu7S`jDXC+gVvKR zXjdVx@CZ9$-9gh(`gQS;klw)hx7gC>#+@=4M-3`9p~4Bu;h&KPc1q&FE@tG;{z+DX ziqW-a+)&G4aC}H!!q&xi_#Mm)lXAoiA*~rb-@fcppD1e8hs|->U{0n29E7jDQ*T!GZ1S9%hicgY7o90cTXI8{c6b|IXbiGKFKBVC%tzM`u+ZBxjjre ziQ&Qx&$Cx<57PMQv~j|pCghy~f3+G}Cw5?Y8-e?w6)UplrR)@*9Q=WYf(4=t zfvfGZr?O%wDehaWOlB1boi4Wbw%64=m9Tty5glHQKpZFY|LSTzPniiR%B;z$jge*) zm7x3@=%D_eW@|r4#9)2hyeZXr0NqIDx%9F(>z}YDuIrj~6V^aI>q$sHr7D=lrZnrV zQmm+sf0j%)`Jz!-LQ9ssTt)V5AB#n)qWw>dnbv9v>%?`teF!sU&W_r7apBG;drR!+ zAE{fV^7gc3w48NHnwH79ePG&f$;I|Fg1_bv#XM^=o{poIudc22EhuQwT99nlqfSZw ze7E*B1Chn|_xrzsh*shVNAWc^%xxFbpDYhsC%CB$sulSaPy>Xnf2e))m7$u*!y~@ZKeXR>d=<||4TM%+Ktv!HjM?{pqA2)XVHHq}IyNp|rO8c2IN5)j2ev#B zp@{C@UN~T+ zpPwmSVYa#REI(A3L5{+<=NVCz)}J^tAM#1SAvjVnH(BUGvZ+p&iSx&iFAdRf+$9^v z6CPHWVBHc+>6_kUXRXNjST~X?&fY#vx|M8%VX>(iUA`S-l$s_eRRCSDo5(r@yTdZu zWsDuAjYito{6Le$<7|-H@{lo%QPtO#@=Y3LoZISqhdD#FORYj@ea(YRL`l!Sy|fV?NGn{(mSVnEXrqzSwzA@ zEm>!pFfK!EG#UK?87qYE@l;Q2?@aOsEzFBuH`!D9rsB1H_jcER{gjC_p0EDMW0fR~ z5#$EWRjG+nNyKTFGj=4Xn#Ads_QDJNs;1-l?9?UiH`$FSK$L@L`}_NxE+=}r_t6YB z@BjE!=Z*$Esde|rPwNH?D+6@r;y`Zujp0Y9RG_rAkyLraXFmdg(;-`&Uk! zgyG4RSL;>Y(xcj6G~VLwQq6cmGQ`}Sryeu#&;eeK;M<=1?3qF-IJXr@ZE#O|xX!(3 zsfH#>HvWKMm&NkDm3M5-oCh?63a?6+q#J4xCln0xS)zm;!x)r(h(T~D3)}(4v?}}f z39ecOx>Vg@kqel*|<`|a@phRG^g!tUq_eYE=rOCT?3T5<4N#erwX;s2j1~q zIMh7gU-GJUM0LZMxcJDEc+T$|BeT0x4mb&Oq>1i1lwL&g=BBin zQ#q%FXva3A^55=`w%9GUC#Ni+j%-t*!H?CFeyte$YM^f-jNH(6i}kW==#=v`{y}*{4;>5MV{QyUw4HY`#4ORr~D*D5t zqOJ}WE6hoqxrM`i^8(fV(2KE^Sr-LjwZu(jQZ^Vn{H~qKd+U0{a39{SFnsgIHJPrY zkdL~k1D}@Q7-x}XMA*%B#C!u?k}!#SB0p4&!J`d6PEAR+B1uKrP?Bl_BF=|2*GrM9 z2F?G8Zpl+(0i^a!LeNt|WPrY^2RrU4j+}iGT3A*)3!` zn!_o6MU%ztw#zT7Ze>9 z*^Gt4A8cM8RT{SIH@DC9oXQ!HZ`ut9*9@dR7Z;EF04Sy{k?{;RTYU&LDQ=BvRC-S;2~ zut#_M%-ohPwTxK}tF=1r<0_TB9p6QVIFnUOg+tqus|rnjpdh^!kn+Bvm~t^D&#K!_ zP{F7hjBnNx*eK_ar=cwR7GIwx?LiYO*i{4ld2>jFRhWq4Xz%{)%_pw z-gi^;71#eXL0a9ufkrUM(8QBhs;v%&-{vp&e}Wp=Zu2ahpW1pQ%+;LGkb$}s6POJd z#=1|XN(b$GChL=Ezf3wLahJ&^C;=(u$W4+FX-kojhI;CnefR1mlTYAeGP7auB=&0N zQXz3%Sb4PrY8AfNec#&O#fCDo7$FQvzAbJMtb88fNF*NB!Vn|;Pkve?g8|e@>1XY1 zrpU?4F@YkBOy2`ETUibTNqw&T1kuffAvm9JRWlDcjKyBJ78o3{(8~WOpMigopHa+Q zB7qh8bm26w4q8o8J-Q(X)NM65Bu>~7`E*D7%v9v8ir#&guPxQ%3I54i%>%tpg!C!v z#17hbf%XCcEdkh-{m#-@PLv5m94Pc=NDBZGV@qiThFrK$O54qKRSD{p@hC^AeJl;( zWO&ZbDan4rhm_JcZgbbx<`gqTuftwqs6lae-O^s!EstKxBCA9FE7=BPuzrCC@;UjG z1Nor-D8@*0M>5>uJ#;&XkHE>buK*8;HFt&ie_&^Lsnywbcf3G{(eJ;7s0)gfAb>fo z#Ef)w4qH4baLpYjaYkO(A<(6KyejQ95h}wLbaMz#8OhCMyKm7{6XAJkP@+*(K(@iz zfQxg1PSpT>0OsQ}`187+jv+k4P1+%m+?W_A@%=*xw-&|f{MG!CKAF&woMgLHXm{{mWs1nmdsLPsHZt~u%bRx zcpdZ*a_}l++m)tN(-zzJTKywSdsxkg%2!EIon$ET5C06m}>Sxk-JY5{y{WS;188hhuA}&1>U{`!#MP7T;O^Uv2FF z(}P5W1zWROCtn@eHEV%WJR)v1L>}#dJG$ZO0>k2itM_7yBXWrfCgApv$I$+akNig; zOJO3`175ykN}+g35QAt)!^%}c6-J`!KNv#q`Z0|zJG@zILc{V7m!Y#~pHhR8T(^v~ z(7|)WoWwWC^szEhA`JC+WBiUio!p43Cl_5LC4&^4By>Ts_CJ zxSQE^KvGuz8>wu*&{+#SEUvv*t~zjL%bbhR2phR#a{ehZkzq!O#RNv{;<8_0mdTLy zSm>}UBoa=W4QnyikvK=8k~A#5SQzW_l}4NW@yd?t7e87+(5mr9`vsh;D<(G+MG7-gBug6tV?0^Tuv{2x-nV zRmSVj_rA1)647WP)W!*u;z-s0bv*_IEygEn{+_ z>^g9}ls{SU>=$UDaw_~kPHwb($o*n{+==nyq|WvTZ3{Z!sq^F1vt z*%lpUwTMB+s`#b#3HzU1t}L=#RccuIYU^?dW@lc34s`ct@WXhfL)8?M5RUz-0EN7k zela)7U)%xd+(S5L6r+L3Ah97k?IpE*|bTbOP`B+L25J1y+pIwE*}BH4sb>4ub6bn$dx)ul~b;G zDJ9`HDqF=+A-!X$F-lQs$}p#i@@c`16~&z`=ZIm8dxxJ!*sVf~4>E*>7@jUk7JuK& zkAjTX)-sz|vlk&2db?Ev5#5M&e+aU23f-reax-f;LildHiVen^QpE&I>fw3Noe$LG zVqN0jvACvMtH+vG_~R>7c`S|!S^k389Ha};jpHE?zVA2jsskDiqVMPbKP>$Hrg<8! zQmc90jjkxH!95*h@249C~D;cI8h>AbLT!%q3+Qje7N!#-^S-G_z5vwTDul^vVhCt?x6&l>{fUX%qod~Mv&}Pv&u(ycb~# z-qCS^sivFR&M3rJE_us>SNEo1n{xQBC$*&=qZWuIXg6722yJIC!pr!-gN2n_i56|* zBgr1n#Iu&FU07ItH?C2ezcC(qoc1LKc+m$y`qM9UYkXUyaPeWG=xu=44euA8^m zOC00Y35hRK3n?b9Pj9|(ZfF;AN0C@W_ohm$px7Q7GQy|QHFIXjd^;4$MeC7MAF9;1 zvx_x<6O?=))$re19Q^-~G66fwsF?japUdqE?Is%-#`Zt4$Il~<+pmZ{)tlr~cx+(> z4DrWBc~HMt9!iuiHOJXWvNLq6fGsACV+t6%YAAC^Pi-b1K%n0~grW6#1@RW;cW%0V zMp%vIgLq)*6TT@{Cn8Hyj2pjW*)X3k$xkP;cn4Ed6ju2{6zt9arl>{j-5&INy?;^x zhu_sn=E=>mXjnIL4c%i6e5cqin!Ddd%$^L{Gl)@>mWquH6RUQA#U?c*Xf$h1(hjfL zIAQALyAMFpfXIuVvv$GW0bTp}=dtO3rBDV%($Ly^Z&;K2l~q-e&_8%(p8S03vUqes zc8OvBw_J5S+?*5%T$K7DOq~Z6;=+(%ULFwd!pR?Hz4EQSV&fdof>x{E_Ab`kt7_lh zM*7>m$UtP*A!e!W-xp-wo+LHim)@`tVB+oGthvh2>~%ombO`NPuKVWIOjM+zr2|oW}5jPWK42|4l?w{j( zdEf@##n@$Lc3Qp>bnwY6{!J+ZVa$oE*fBTg$xzUCf4V%IydAi0&yF0pXi zEl6@|C-$m*#eY}5#4+1<86h%;+3Qc9~d*zMMXJ-=!=W{?GjqG z=J$$^wE4gMI%fP99J-@`Lb2ALlBA1mfC2&glRU1pwbZ}MXYpCy&bA@Mb{D8~YoqV7 zb=;UO#ha&uhd8wO&&?@b-BsN_Q|W-m)QNgCFrm()*k@W=W5_0*0&1zB93^t-N!0$y zPrjghr8TG0H)d2ty&?v3De`?WJMAHsN>~))Dk`-zLy}PTtaOEhKwS%(!k!hUUI6iqd2ph3T+x@~>d=AygnvdHOKF`^i%X1S>rc504qLh^(q4 zeu-FI$v+2+|AoTB(>T8aD~x32f8A&YyjTnOaLtu|{_J?Ok8qM^?CSuY4etifW*YqU zU5;9ts(pfX*$hrOf41GR@cq5*uy#B6)EN0DA@oHI)k{{5$eR!r*GD<3DHc48B!+@H z{I6gd?pQHcT>i%kpvoDpTdb13q9wM~QU2!4_Lg<(`hW$Gp$70eAElsV9{yvB)*~GM zYr7E<%)H;fei^gkoRRCLatXT`$#5L5d zV9;o-U)fX(xpW`Q-sFvgYIB^YwYu^CM?0RF2R~_ZLw_*|cPR-mhjiJYkqI`lmP-gU zX*BaJuL;>PAclUHYF2?2&}Ye3Ecxep9P9Q9%34Eb~mr7EFVr)=rBu8 zzi2!UoNRiQG~ez8T4L$YXyhA@4W_QEmv8Ib#F{VBPQYdi)F1ZK-z!BaE?j8ovHV;& zs@17GtoShGR5VbFWj6kNl9H9pb(GF^oq7+ufT2++DM+$M_lzkQ z@${yunag5Xqz__H<8R_uef?AF3V&x>>d2C^-M?VXXaF4lDztm^4@a#UTCE&N_m8e< z08Ca_F!dgWn8P~`RQODQ``G;TMcPmQFDxy2L1U0P>GToo~ zmkFUo!xP2n16BAI@KVFOJD#qCGPr=MHAS9EZNAVrxw?IEFh9GcB zw-P(WzaS978CySXTG|&qz?oFR$1zcXldSKy=(roI?Dqm-;B^+46>R=K0a`$*_{#O4 zO)~O@B0~0-475Gk9K!Uz@$35)2b12V=8Z}8Gjj>Z^=2Fn45Z9{-(`0t{LNz#4%&@w z$1~6yNiG4pQze%v4_99!@RPrsO8~|_V8a6@%D~g3P*%0@qD~4t<)#eZl+fnL*6Tm% z`&xIn1`l{2A_3nikErsi5`?S%9$8Wpmg_rit=*Ox+wpA>Sx$CC>MJh2au! zHDB|CPz3=rYDp%~Q8U~2Qn+_Rj??z92vC)fA!-b|op({&r(^vj7hh1c(rwMChFH*z z09@P#Jsm5`>G1pY!^x{hpo;^8H{i0kngAUQQ>O%!G$U3$^qrWwxq02 ze~9S>4AA1jPPbd#Ws;Sx^U*3P?(9k+{G^!%%=kzY87;1~8 zp?x>UG3q9@t7&`KRO~rTkloI>yjVHDMHs zF{s1%m6T_~L@Pap4Y*QBRY2Drm56)tX-C)7qeo^3+S6;*Ty|-er)#-|FV-k(?4N)S z;2&g%_k2B!kz>ibPT{lbufLCS4wya%Jl|ZCi`3>`Y=DJ2Dg$k+lzpm>yb@Hr1 zli{s&=-CD8XU&QPmD@5KmwpQ;e% zllbhS%Da7w55)LDy6cTGvuOoU4Z=0p2y!=VP1H57`OM^j<{Q)fB;|;UnA66Zzo9ZyW!5R)~bSmu-j?1>hRLY42P#nWe+h^ySBGWp_W z5GLP|Z1wxmPWVguEc0bnf9$O;?m9f5LM$k3$RH?&l;P0`?%^KaITwo^s|g805+N#UMa@QZj;}PIx4* z;5M>4XPW|KOeDYToX>!66WtOw3V%|%3f!J*bfZBSJa) zmzq|d?fM;~o*dyD{f-`&_7_~b78Y1{)+FI;IJ%$C%Dv(Du%g>oYA1|Xs2H@RHh?=G zz;+1mot=zWbCVpL(+;T6(w36m@M%>Kf|Ws=n1tbSF6;7B0|WhFo8>z#VH~h_BC$Do zrO<+VxtpZNVH|CHjfrs79{Js`h!>|_SCAg1{UFw)60c)jzA{|K7%5_k#>AH3qNA~W zEctjlj}brKC%IqWouR)(vva{vH#NCnM19(}@zaQ%=%``ns3#S92|7`-Kt*Y9*6?wi z?j=iskOl`{TC62nqUhJ$o`p5hHlO@I4=}v1MqyATPRL;Mzh$LF2K(9jJSXjKy576; zET^3Q)jU7nS4}%WVY^twpduLf%;9^N1=>_Zi(?4y7@L0TRFT+H5xu&B=&uxXwB>*x zGlDnjpUjFIQVPeqDxA0@lqX_XSXkHF;iX>Jb!searYO2h&&&kn=8_>;h=|0$=Kk=( z7W7mX?xTe!@^u?Y%kQnQ;}3A2=iN)-;2@%(1DI&l z2r_@za6cy72&Z}3Y01AT$j*cUayLPUe2A;%qqk@t3JY(Eg^AzQbomBI)@8Fk6Hbk0 zR5#Er_Ef>9dP!fk{1w`RZ#%rcM4P26Gij!q#8cIS&s;+FC7(&Q`mc(53l*|3bV2tT z7FLd$&yn+2= -z4*LUrKPs7#_H?ioZn^0!L2`X2cv&Q9PjJzgJBXOC(9iXS5+nC z_e#I51haw03y(ZQjIKC}b=WOGEf5>S(nuiirE}g&Gz2*4JhZ&D>sP|N#m8ZI5XT?~ zj8fgdewACfS$_VE?S1}Ae)ZMEeNip(nZEhw-{PL_q2PgQM^hEfKz>Jt8KR)vw}8%S z1ZPLR10gy2f`aY}WmOFiVoq1lut+sFvA^g72E9DSZ}qIJAgU>D)ZgYL5qlI+cc?Mn zvAEO>yswmI@lR%+P1a&xTA`rA?sSXR5gAovqzEUuy!g7s7NE=tazD-T^bK8%FX zg7eQ2I&{^zv#^h)`g`dvI;h8NxGgW}5`#XpOYfWV`qoEAqH-xpfoK2pl}6AF4brPI zV<%;+>3hXZv-oXXDZijd9A)}QPA2rIZdXs9>9mZ%et9g`x;9ISE22nfyYW({b-EI6U@j zAdhH)g7Z=oQUx0ZA3t5a)%ld$UKug)g}L7ysa~esk%Ej&lk`%1V-p`d{IPk%riMOq zbMt8jYZ5oMgLm`+$eV2y8i-A{f0TL*Idc;ovLu&q!;6nq>Z;^YZfEGBS#TueKzi z|6)Sqm737-L;b#2Tnp0jb}GK zKQ%Bp|Hi~{=e}&lPLujH6aqp3d1}fN;**%DkWi2;1m|Nh^J48hLQqj@?euzVJU6?< zO#P#HDDQL+^C_oXk?2Pm*zZMI57^uv&h;8^$%u;zL^~T=xdsMsU&v%bqQacX&m&CK6qBhJF58b#^l>KSw0;F$qCt1v(cH#vX0~G za$)2^ZN_N>OMJw`l1n}LhKSe2D5zFRZ}1_W(G4#M^zrEz&5I@=)4Y6NxIWoO>l=Sh ze9Q6U;j{P2b8nxcBdfrtjKTD9F#3S({jlRrd~Ez0#Ed0(y4EMSuqlDdKYv6P`(Fu5 z4tU?$a@yG|y8V95Qa&AgoA=BDHHdtDHj=2@Wj(}USUzHXIUKKlC@?yP8 zGA?J%;38`6DuCouWMyT*4{-R?^my)o5B+PzANC@oROTdQWw*a()gg@wg=M~MsV*H$C>2* zP?Sk9=0MTA6U60sNF<|P5g{_J?kRoQ)m29EHGo#4hQXz=>rAhsA*4|V2E0QXMVZ^# zdFXQ7zGTBKzIJ}7Ue`Z0O$&r56KSNGp4A}=jnzdqe44+Kk!Ow$m| zN};SKGoc z@e^iWN8bllR!X|GbA<&Oj=|PX$yA3}zGh!!^kB#l)FHHvedN zujp$)alJ?&t{qMEkpM|;c#`>AFILk}LfD7OoQ(ub*$x46_hj0vH;b-PS3XC#SCWM{ zw_uKGh@mA)s+||GB=5M4_|lJIf%77+W~7OK9vpG-{OO=IFU*|;5E%g;yVAN{iS(aN zX1wobPIX>90Zd`nAQVfp96^a7TUAwc_XyAkx8D|d5pS&fBa1sVA1glnKD|Y$bknm! zP0o65Vj|=XTg>VBoRzf{c}nCy4>6^_tGoU)%)FEzyW)(xT2jRPJP#WO_JFwrv*PxZ z{16fcKwC%0IYsKJQV=lXvG~lV;B`139D6FrYse#mLFtY`cLa`x}z z59RJM`s!LM>@Z=4LP`%IzrLAc93A{3wi`m6O?3Av|42}b#g90aiHqOmpiA;CCBB}f zD?b6=yxcusyz`3<$66VY+B<4$>SbwCGO}3MuaJf>bLjuGrjTbo>ec8~6cs(^zwUgs zX_@zzFW0l6;4K3KM;oJNH3vIa$iuP@Z{3n^Td#~ZeU*srZQgDhF0Yx9SIWZ-#dWL?3f(y*)wW`AteM)*RL zN-IIi=16s=>V6Sf?#cGzH}F<)>gqhUk#s&+w#Rjnolbu27ITh-=GP$ugC-rnK? zexfL3W?|vizY%i90{Ch$2hp?;!-TU3c1kFSs+_RV z{i2q64KI{bIA7%QjTbA8A7^>J&ZMd3tF5VlBqXRddELLDrS)Q{a^27Jex=q@baEN+ zE2xFBEjr-tfz~piN72C4~7m-PIfEo0IPD@dj_G#>Q>d;c0ec5sQ*fbRUU$bohKm6 z^taiLTO5YY-;_*!0>NZ$O{07&y5`qW8CBuWy*;X}%~U7thzJ3-nS3onmw>z`Di1J$ z0ptoHJROz+(1_|Vg3qfeN+FsV{eP0>A+0AN1;2;cF|a!pH5pXJb%-p&EXQVKua6{@279{3D(>FZRH*-Iwjr|5#5IQ$f!o$^9Te9Wo(wuqdA4+k9?HPBf4 zbCma6vDiIaR9yV|<84%MF#6BcRZ<|S^w>l^l|U%WT47^$e(aEeS1%RZ+}wzN%zriv z#xEZk&D+^iy<6xFQ-ovBsbnCK+i_a_R>A*p+JF9*apt+{+Jps|pL+9wDRjqhDAW}q zG!;$u*5dQ;q<#S2$emzSIAyUbk|5C?lu!wA0WOq?O=-a2{CLs9*Iia+GSqLoxxIeY z8duDdQt)z?R^CLPlm>~5WLdO&G4#9TyVxkAUcfkVUX1I>*JsBDwx-UD)qsJ23N5!D zrg?nLB>;Xyd60*Vrwdko)ABqUL|RWwO|%4yud`t~XWkqZT3btuIsC_8M|jr#x&IzX zN0Z<_30^U;=5S)fjeScdF|c3$f<}A#Ia-z z4Pmq@W$xB-L?vWprz3uCs@OxFlIg{jguN+lUb1_3Kg`u0pDk zx_1b=BM4aEGROrDvISjUnn8S)yhy~OG;RMBV^K{I0!&Niv+SNKQwA5ve@|gW4UZbl zt7bx}>fnQge6}JMcZ3p6O*y#^TXjTrb+KLFPn@{1o}LZCaeB@pwBGaSc${LFmK}n> z;;b1$1%F&%8a;!pzS}?))18AMl=a&p5!X9g5k~o#uU(7%ul!c3p)0Ap5TNs=E7?^cm4zE_ZX=r4$`&~}4Pp@%w zHN~_A93)p&!+&A8>HTP^-r>gk=P$dL6-OQgJC?Vp=EJBuPqP+7I=ABsa9qy!pBW#> zAC~dZ9$TL@^R=_Bp(fY!ZSL~;Y0X65cgxZe5Q{(2GY zL;@OgpF18P%SzVPj6a5k^lQ|A-RhB815_c?B$BJ7&nYbIvr!UMRZZvj_8PMwLJc~) ztoYP8?O<7N%cH6j$rA*ZoQ@n|@#@c?KdT_u2@XH87i4eZD8l9d0Z5BveJ|Bi_|YeZ z!*AwcvKb+g?22n|X^DGJ3ra~d0fMyPe6-kkdweV`D*E~+>bPt0M?m{@ z!xq&>*FqjxPyz3jlsP>ph;Ul{TrP`pO3GHhB72+#5GhoAB=p$H2-vM@#56K5CGEB# zu-9q#1E4*&;>`JnQ?ZovsqEeoOxX1QK#*8v{gO8*S<{`V!~|*hw-sD4cW(oJS%$(w zEhQ#C;84{ZxbmfzJuf7fa}Y?kY1rk8Eg1kBC-Uv0k?j$4Wnj0CjVb=4MS!cV^t;pi zuQKCLG?P}CLCuS5b-0)li<{2U&{>9dURMe8 zMD}m=LoEV6f1wlb^!&`baDfWdInu?wG zVJP;W2IK90vG zJnu}sZqUz9X?i0&1b(^sdqT{lc6;S5Ew5%OvG#oH1xVjkO%Pjup^H|w`6{4*;7m^+ zx|WX*`A>#ow`xS8q1nAI@`kNk8ScU%G64=Z%)|FXk`4EwW=|nwt&`Hr5QilC-sCk; z^w(7yfI;z51k!lmnLJiNoRGIP$`r{hCb%rc>J98eyFgq z{ShxO_@fo4Q%yeLP0S8jsVHhT8^B{TG-0h_?6;|bo>$G zbK%-i9*Eh4nZ!wD^(hU(NCDfSP_Jp@d#ti~8PYVu^Tv&?XRp4UXY8EZA1C!L&n(cmZ|)~r?CafYDpW{chbOB{1RAUpc6e(}b91nx484|t|Kh_JZ()v) z0J%|L=Mur9c>Mygm)HtI*2QZZvBDqGcG!%j8jZ6|9MG*F*j;my)10j5z83Jy-EGXs zx4;m#u#t$STljoYPx@XKpQDS9?!s=yWtqtAl(nlZ;WPebDcgTHE zOmF;1{4pEBUq@N4Tee%_FmTY{zNF+jm&+Co39UGT*PX+BsR|noDy}AGBG#64@@p8u z6b0^y6}mYDn@jw|@&8Q(5P>vY4J;Ymw_tjc?mPEFFsL0GTU%Rg&rLRirt7)DT;*hE zldika@k@g;>-w_srGh$cYD4Xu42UF<cD(ltXY=+#|zLFbXucvu$&PJz9Azo z!$F2emW59{9gOB;Poy8|0vjm}<-g&XRlU;xk>=O$d&P9+f`8<+EIvPaL_Wk7USjZ$ zuH>BQ=BR74HEcD>o=Nq~v&h2EvnX;VOKG8Mrav(Ech)9k6{5X1hfXp?C;{5%4Ms~@ zWz3vSM3$DuKqHj0*^=TD6H8n!1JwWjp55KAOeN$=Sb1j9lLe;3;MH{=wlxd@+^$J5jE#D%BH<<#JxI+kB&zaxi< zjor0#-uqt~BOvZ(7kM?^6I3yTG7WyC)6rtdhf6>xD$FD5ZAETfL)r5^&qw;l=3H@l zdv~9L;rf~vt?Ag=q4Q+2Eq>z-vy><7ghm}UJrHUe&?(=`IGDJ2MzPSLA7u zS3hhlp~OzvRGVyziz+#(XsW6pyZu^P8WD(qK+Nz!C~Kvm{9IqY<9*^^CzsjC6S&0{ z9bH{Q>U7wDE-wC?`zP{+O3Z^8*6X{xyzIgl^i;?QyKi zwv_=xPu&}sz5E>33m%$|2Q%g}UVy>K$i{WwdpmHJB{g8yYZoTD1;)ra)^a_QDakr; zLdvG=j)@5xCxCH3eQa!u`DEw%6DxSp;p7Vi)h5BHDCa11|&OE}nlKts^ zrQn~7lG*kTSaWk!4vqn|xbAm#E`N6&xH_jjjj`RYQf+URBoF4&eA^a{JpPQaWxCM9 zCBEEXiuh?@WsQHdAj4trvW{^D7hR#^-C|5wJA8ZI9 zdZn|pe(chECZZS?`+%q9cuv`AEurP$zn)hcv8E42ZPI3_76C^9ng zU)}xmQ1ZK>pWO{E0NZt6xm^w=aejQbZ?OR~=PLNQ@4R^CaX||zalT6a(=!^XpRsXq zzvf)k5KQ6VT+!C%tsgIoW;?va z{zC~gqn6fLi7*SGFw*ATlxDOP6c+A49tJ;BuZCifra4c%f?2lBwVms;IlkDIHE-mC zaLK?@V!%RU?CDy<0xn6KD8M;wtj*9E zj*E@Hf1n^HNDeY{!0r_Om@H;mvsGuy`FMdHD<||(@G0_@y_--H%i<*Vak~M~9o`G%A3iUhE^|PQ&uKMW3ZJB{8r=`ui`z4+Vwy?F4c%WULB#y|az88}0td zAwT+KI?-fg<(L(unLaol`A?bm_LF!M9v1+;aThF!r)d`vu~@BfVI(C6=Y!^U&MOHH zC=sIemsS=EiH-f9?V>24&p#-V%0$t5K5ry1~)kkB?kED(Nj(J*t_$1siBo3L(co&H71kk|3^|0kvDJl1WIQc~>8erw3-`Ii?k zs_fcY(JT8JOlds?E|m8%$`5Yajspd&h{cz^2N_C(5^o3l%4|Kn9R z#%g!td6eX=5pw0AolN{z{uBJr)@ z9$XrE+}Xw)af{-0A1!57JUsK?J!mUin4z1mPww9cnn?>;)M7oj+zgh4p3n|}jPU!Q z?H%=OrA~$~Xu#s=wmpk8L#388>NH{9EnN8VLkK4CvROWT07z3=s}{NoFF-DFa%VYf zu z0mOl&R%Mu0r1p-?ultvlgfboet0gM%9qE1`2Y@`^v3Q}oPPbY)-K zqMdrOzMKzBgPMO?;kNXNIpyXW4Bk%y&FN(6*b66#QFl8Yzn6mb9jpG;Ck$otdC$qW zHC!2TUzS?1GBPs$3F?aee$QX6Umh+jI{#Czu!u`+DoRUV6ciK$UR9_*DSFi)Q7_f# zKAa_$d1*<>FeD9~n9@#X6@lLD9k?#gxL~7Fo2GVL(fwe1gd8m)y0_Q4+R@^1zU{TY zP#eK}6Hs-YBzbeajS9OT1K0u5?BM+vAY5&CXOOmK8BCm_eOf}%@7s39KMb92J)h{- zMg+{{^tQgqb|&%`5NWz;B}AD;4@R8+)}w$=v|X>$1Aoh>G4~y$MZBfZ%1S&yth(=H z@cFJBh-C)vf1d{Jk&0sF7Y7gjq2}EXD0-%df4M1mTm{k zQoi?i{}k8Ufv0+?hfG)L^#6YMK`*uWIR*8b-!h$T^jyFt?}A|deH|-0q^T;k*o((@ z9p28)4tq)d5GYzM`xTAqz0yO8i7|;bYpD%?W4_M!jnB-0UZvkZapS2(N29}j`J@p3 z#f1S~A}Q$YYnXJu8jE=^3-QAJ6Ih|35DDyy;=(hekIKMRe0ktI(O z?N3XphMig-4;nk53Io{k<~3q&foRMXo~j^Foog>^K(z`Y9e_o-2fPnx{s0yO3Itn- zCsw`-VIJ+kUpLinB=h)Ewh{ds&mm9E##@&>XY4#f`&r$1Y{h4;1@12rsOxNiKLM2R z&mnD|YYdeR@`F!aKFNva65`Z4<&s@DN%k=Qur$&$@St%h(^l|(Pnmh`r`RvNPsZy~ z??~jcysUc@qQuJirmA7jc1&2ycXzLI=LolcT=egWYs%wI_ml(}U2JSKadU^Bot^!w zlivCk|7&>VCb&~j%>bp);Dh52Iw2n38hkI+MM9Ma<$7{yDW~_tUF^)aYXj7S z%U|)zwzk|~I51$plJ=2IzMMZCJh?53Nlyo?&;M#=1&4V_MdwKObW^DbgPJcvH*Bvr zNoSty9eyunDiASdzBQWlv1SF;NUkC2{e&6@s;TTsOh-W{~-fPV@ z=Ui)-5vU!EQ7XJGcv|B9_rc$B8`-mbb*0XoYR>F}Ppf?g$9)8wSZsLR(Wok*_ad%4 zn-i}%+UQSiZm%F`>L;kbY)_uxkmYc&ZimyCPoHF99TX}VHC9ttadBkm>Bd$jfUoM| zg5L;Vw^Mpn7Q+SNW158p6PpdsaDjXl4#pEUp^EJ4Ek>4s=o~Ndx~7DL1l^Q;Z}uAj-D+s|fD`a3Qa`o?eijX_5~g*sj0f)m^qKw71vZX?Zo2d$Ym^aQpUIkoD8X(N2#P3 zj2yn9T6&g8cmEvitS1w@6=$dfJO}$gRXJzf*o9xU9%8B&@exBiR5LXft4#=gV9QY7 z)78xqaN&B%&xOh1a}2Vy;xX~@mtW9a-mlTs)B9q|6_%5;`|Bm~?%j6+VE|RZ_d}g! zXMA*Y#Kyr9a;Brf?)!7?eyFlGgYVX*L7%oGU{S)Jve;=rT2g&k{!wg`sv(|nTT?ws zLkK^EndRq?A5X8ZI10!c+n;VVSK(nKs zE^S<_6D?*%6vSRWq3kY{jj?t;85kVIJ@soOYGa%oWjxI%WP?Zyy5Ii$)0ucMlo0r{ zQODjUs(jzrn30dNwWbNr@+Bv8mDPOBWJFe39zlkO?X3BFnl_@f(4BDVq~hZv zSRCPSRiWQDYZXwgCA^VusylBs@skvttDhKm+}%u%SWE7vD)w5BPlykgav6oAS#S|s zT`kHFZa2NqXH9g6h?B9-QsDN}x&5r19OJF)%(SI*Q^(^*TQlj|>FMWnb=SwgfwX1G zu9V4lDlapQycW>>1PfMCRej_(`5fCuw&9}PrB^sM3P*ZK0m@$^Rmtp;o9*4Df3`JGy-f4Lsv)ovLLa+F(K(DW;C`|)SFq~opZl{IFMH`16$AV%2;yK z)b)kkg_DJ*F8zlHgv

i|1@h0yhG{W$h?nonh8+kX0QupP8%V?3ew`$`BYu|xP znw9)$wu793{{EYL?r&3R@+(8XhkjH>UkkA2|G!dGn~H@6>;EOH-(No|a}I+&EkiU2 zICjX{81)IFY?U}`e$4>34e-K*KN^>as1g+2uYeRqSSNEj3<<#6_P( zri&>C=hKvPko=qH>)*nA{VYvk`ryHH(BAs2B;ml1*y0~41(?>at``Lj|m2IsekJKx-M zqVVpqV=1)^JNr^eK=Vxj)teZdWbCse;eh4%#}5U|lO$T=Kwb9A_6`mP{QYaIbq~HG z$*<4A8%pzMFvc<#70UuZ7$Vq09CW7^R+-kQq9L(=)ED5M8*F`Ffn6AkalFe5+YVM|AcJx!aK7(jZI{$_dZAWnH;$nPMp<(q<{Pt%!7|9|k zH(3X6)!hw-0}PgNRa*#O+sl-MM4i*?tZ&aD<_)X;>B5!Qe|Z1t6~(=*>%BK(Q_U@U zM4OSB(&WCnth6hE3KGbV#zVdy@f-*Zn(UqLN_zE8+=mgZkf?V3dQ($V+qZ8I_obnh z5S%hthqEiqSvu8J-t1fMrX;Z@u5w2#=3Du+5$f_mc5r+7+5&RDT)^o3wzz zOOFZLy8cI>^?Jbz^1iRKeb#wiA0Qazt+;aCL!uSEy~P1_MvJ`(3Sv|Ge_gjtKYOOo zWk>FS{2w15?m6qfYMSa9r>CJo56x$mQ`nu<>aY%?(d1y@;7wGE(tv{sJl5J?%j}J~ z%k&?DM_)*2eVuU_6}a+m>2d?jWg&K!@L&}}9lYMgdpxSGYYrU zXgHaFaiGk8(o4_vt|}Jt(RIaKnbC)+Lof3z+2BT7-Q!8>vwdiOE$0->SUwZ5{iLO? zZnDeZ^DT}8t#BC8+u6*fgMr2=T!nY!v?M}A+aR)zxpyvC$S4-UHq_P5GSfhPN>q`n zE=<6yq|EgtKWF5|#xiK9fy2ISK~|_g#=sTTCsvo`n^&k^3=XHg}9)hQD#mZa*$Er*` zA(ru#z*dGQ(MWcsWvZTfA2&JkKoJ3?Hd#M+#M(q4j@y*~O((-RsQ3ppCG979eG;Qw zpDgV=@9oNkoBkP$Pp&1NJg#u>Rl(RmfG_P9JMh$hZ%*z}a3|dgiAdDCj`ol0kBaRw z$&$^5(S`p9rgNM{2Cm5ff+1;5LnfTlx`iQT{$n{6*QYR~j*acjpe#2+V)L>-YlJDC z@ve~TiYd)2>TEE%6LGUU2nMoMEYql`|*cnT_SX#Q$sA)m)0YRp1o ziOpBU=voxnIm2BzRN_qJgrFa>R!(&-3w>FWq67zZv1c`odSvA8$?;O*+Ik>^H1^Y) z8V;|SJC~*tCY?--rzdBAe9TN!iVa~e2hqo^rY;=aM@`(DF(6HJBXb~#{?ge#ONXXs zB7|TKCcT#tUS-jHRdIpR$M0aR0@C+{!g~rxjJ$++7@gva*56Wd{y1C-da~B09lgHf z%4q3WTm%;v!Qx^Gm@v)WQ{@wsR8`$J_U2dZX2UAQ_%aqdvoP-Vl8i)9*``FI<}mv_7qR{*r+UWw4k=1AT%~N zXPK^1i{cUar+DWQ{UMTofMxc;zBG=o?)Ey^!rO%RidTk-BJm49e)tvfHgcvc=QWVy zB73uu;7AGkq^zlVIAC~0VLuVNdh8@!+*We?uRrok36aH>_!+U?Xz1%W2aQHmuL__?Whn4otV6-Oe^=g6eZoI!oN~R60BBUGp zy7D!E9hrS4vwj+7o(-Wv9QV`ZFgQ4|n^ozAtnJXbJZL z_M>uwcOEFlf|)>{&K$4_#L$9THIczTQND#=-v64eBbs`}>M)bOGa0iqAm-qH-~}__ z-b7lHk&(51|K4AtJhI;!M_sq#UNpR8BAWR#Z9syhqih5^Y^m~n^tvYeq}QWLk%0pd zm}E;_MDrFSCOjh*)_cgIqks(s0ZA(<&)Rhpz>dWlVE|j+L+u0W$>Sw|q3%{hna}&9 z?bomEAQO96hyH)nRV;HuO!WkXPMgmiO`X$w4J;J&S-Xg_eMwRi!D4qcG}wphiU%QX3ieeCwHJm=DuBX^2)J#!ur%>sex(Q9iEgSeZHBv- zW%xwufzDu{qoZr<=s=%=i>1GRO_4VMI;n<|3P3Q4iP*h-M>RW#W|dhb6o}*;Uu1D> zJYE;}vUD_FU)jzp&l<{$wku;lN&9RrKT@%?GmuuHuzQ|YYvA8H6Jry!RW-NL{d?=Ole#*(gK0T``vI?)5cFYepRa zIEb_t?m`E>VWx%-XPdAZDZVLZIMpiNR~;!Tk#viVm&Txg09y&uNFT*A8v&VoOS@qVCYgVp`qO>9RfVBL1c zJs|x~!y61}$O0buZRFjxesu_VpRt3R?J1iy$)^68Gd32y-feH$Y-`RW~JOz9oVVYSXt#o)u`?gb=fS!JM< zC`2isgP4Sb@IiQvPiR%uGJo;y9e&{sF6f4!I{S2*`?mA57GhMzJGF0KVR)(to5Ft} zhyf)!4+?d3geRzvW@eO_cv<5~lc_ukq7D_1gFrlUai#uR*&33YMS>_=HBYr9_Pn0} zLa%nA6393&hTJiK@$bkxUzk+ov8j3uBjip!VxIQw{V&)lB_ASmbt~6?TKErFm0yrx z`>Uv=)CejasNlv!1wAv+as^Sp$()aC&r=s;pva44SPF-Yw1$=^IA#-iHa>J6ilWrA zvi>#K;+!0qX+sK{;N`$~VD4A^KPt^ad-@$R4$VD%1USCRWPE%aoMh&STGGYbBNix4O^;Rg$%h*wU|{z+7{w_Xjr>mx z22JU=hn;hF=!XRry={>RnFJBH3u`YsJ&uXa654-5d9 zY(uRD!SER!;@ROJRZdWdNrs+@SYh6*{?M36IOqZJ`I)sc`M(o?w$DuFNTx9|k{83U)vLB&=-q zjsEa~O8Q3sNn@MKE}*Nh%JxL!nR)g@RBpOZew; zfpIT`-tBGl_tU7XG@o@?m6~d}VutCjn1RyAz7n;f4_`pP6{g3cr-v9(BBn-rK`K%| zZII_sSQRI`rXbr&aPipI*b`_C0JN2IiQRWt47EW_L;PCE{HCI={!$?(*>|$8C{SMz zNU7(~@2aVL`*CVlIUi&LwBOt!n%1uC7+fx=JU-I3C9Vj(hW_6OUFqxx@k!Uop&YE+ z>pNE=3X}9+_i=A0gWqs*twh@NHeLeI1GSM~@@vpP>k7~+U|^{A5DMo^YyPBnD=Io# zmUeYvA@~_@N!7@$B}N?8bL=@d%_&Spx+@y}TT2A?V{Jd^M$2soA69Os!}0@kK#52c zd_z(Gqj%=P%Tc>NP05N%O!dxe8sXm*Kw;@e|;tjwwQ(V99SVhnZcn9_yxO2c# z%8w+verJfV@D3mF{C%1CY)GNo)}ed)Yw*p(mDLHq@mdCTb>*2R;uIYxHQ4tW8Xi8Z z$)7?)La5;=rzI$orOt0|-ZC{+e4m-g0NN8I@k6g5$3e%ZTxg;Xd|X`i0Kzfklnf^$ z@W?Yo91sT63k!+qBQ8+gHVEBOgTNmBpCIwE8F`wVouC@XTXA8${L9M*|1YQEp8VJ1 zIgI!0tMrvV2ske8B_aZ1Vz=*Ag6CHMbt&zssEmI0nE`0**tpNE=Xq3dgv7)m;1CdU z(xEbhXhp3DG=)Q!z@hVGzYK-@Xu1j`r@^|@q`)1&0&9UH&HV#cxp)HJ@ZaqNs7wEk z`a_RtM2$m#I#`gfBXNlKfGF8UY2?GOz3}^ z^t7OdT&881?g@)~*fwRw7|MtC6;dZR_gf33s45enYVBRK3VIgG+QiEZ3!}O#p*`sx z=eQ-fwade#pfE%HS?SXf9vsRYE}iEUuVe`nRZ{0dLm5Am5Y3`Acy?7Y2t(m+cW=x-{LB zdT-qT7lTq7LliLOH5pQ8l#SsJ4M0`1xWI}-s z$tqa6=UJ08N<{?jOww!d?}?hh(|5gqY-t;K1Otl^ZWOld$WiatWGkjb8!J_S`?sk( zg6DJcJAuYNH}R}B80>LL};*q zr%QEPDGhuI$)$sn2_JVoOu$N5wHk>Or2{6*ZLWCta1^(=^`pRda>G~NWA!xyK|zBP zYiryfDovl_mso797cwX3Fo3K#-CkdOoG2x_XXJhZjU8<-%MEehvttXW&b{fgdecB@ zB*Ilr3FbjL+R;jfYq8k{E0K{Y2g=i^szqvJIrHw zzOtOr7kM2L+SL-@&@H^+?mrf{2JzcZWzd`iEwV>p-FGrBj!<5FGRX9anr2`7)3`uc z85`pL#iXwWHV7wVFaSjo_cEF4F3ZL5OP#%R=NU6c8+V)^-u%9_a!bZ_XB8un_o{#y zlVZL*rFC{zu4;%QV`I!dAu*4vaNv*U9pS-AheOfJeStQ*6jmDNsT~rpurSFJoJ+P6YuB19l9k#Uyo9eh^nHUZ-^s%N~)ne!57s%7Z**H_5< zJxX@Lmpkv@O#S}!<<%4ixvxAtIJl>rcZf94lM0}tghW}S*o{)5swo0+oKNs$q3jCW zaV6r_Gz3kpT7dFrXK9*-u4mi_my zoVF5WCo}iZ!(r{MMnSliI$F+ zVWJ*%LgTeai+(WL6ume}wfe}DTNXI*m?q^%mgckkX4G``hmy@D)p*W$|!WQg%( zYhQsj(m~$5XGdFY?_qaI>i@aX$Q9A*po2qg(9KrhSZ!A&anr+_pCrRyTarWGx}T$M z$Y9hTo^@=Z$Mar#FL1g5ZS*$Mnh8NJnH*a{Hf0DJ!`H8Ict5_Y0Z?r4vGuk#KL5-2%7_L`lYz3IsW3Bvb@Fjz#eFu6iXH}Wy+>Mf8)m)@0G7ftPJK?s}6l8 z1!CZqlOpz*A;z8(6ht2Yg01b(60-#|jO0y!jYUSawmkj<3tg)v1-jjL?3E%dO^)iWVh7NK5Oys$SxyGnNawg)luv zd=|89oTcwSKcfY*DyyI(9sG=+KbvEGG8h-CAka?m{h)aPKZOlt9GGEJ;hPaXP(VPP zfq_2Ye_3<;@pz_%5V$Rj6Ln>bUDo{f{Nwp9`wtlzvYw(jIcaIr=MQ5}HayG9{03`n zv_te55KwMFTazX|l}*hP6WlYa>X}FO%hbVDJZwy*1b>QYR-%QTa=>zgKfyo2%U4-% z{;dVBvt^>UVD_jj_8T+IFXJ!K0?Y#r-(Vy}2K==DA8<4t936eNvGEk+A>H0?aTmfw z5Bx_1kv5T$kqSzRwi(1O|Ni~E9&VR0R7pa;eEVaLwPFKWU%w(xa}(n?h^p{a;f{|d zn544(41{6-P;S70FV!tV1PElKrSmyol&dY`V-+tJ`U30YbO6zib&;u1pR-?+|9Oqj zQw{}HwKs3mZrZ3V`%`&^fBDkwbWjP3+R`AafdfE5a%KvEN-9wrZ1NnKGaf9-6UK5( z?2}g+>hkvyfHdVcqs}Z`HBHTxLRsl3pZ_};aw&l52WB1evrby(P)&auIHZD)fB8J3 zO92-OGzw*$7-?&gS=4=$Q!O)^I^6rmqrVDN4NwCO;aR%|7!m!CsmoOGw%)g;UTu(G|qy;tzQWTy(Xt0!sm zZv%2b>gZfro-l!fO_dz{-aLQL!-S+yZ;Cct0Q#i=NU2EL z{&Yl67k~AOhnj9^qwB5`u%iDIlyac`;z!@;lfT2tJrEWM+oDG7-T_0T1vteP+MYEW_wqYB@=4}{_a#Xfp^G1kmxP$a zl>j20%@D5MG*7waYw*LsmN7iaq3i4GeuR;D?v*De(|_+wk~1^AXz;B00we#qEd3c{ z&DSVY(^De*N-icwM`5lKdQ$FWjXvD8sd+y~;mGvbXbe{6^-(0p_#QI-?>r>BP10-L zKRL-ztb7xrvi6**tV)FtS4kdGOpVNopX>#hK-;+hQ~F|U=izg*xZWM6!IV1SIP|Ku z*qW}A#QUGH*Ir5qLNDKV2%WNrXg|}bN719>oU2qX-nvW^_Gn9n$jiZ~5HE0_mX*Jq z7REq`e(_sK@Ko$fH&c20%_rN$AR|Wb%hr&xqZbRnwnG)}57+JZ*cCr0pNma7A&d~E zJaU$~F4ZI5cm!x#p!U>r`~s-kW)01`O-zRsiPn{ZcTgzzzp>jk3L_0vt$&|m{axG} ziiMJ7Zap_5(_QI)>x?1k`ycWhv3+6;yTSx_W+LY2gaDVFmO)44XgAapR8YY0_4`Ai z0MmV#w$V1$!a*x5lMi_{mKGKoz$eYkzgbx2IsWxSq8mLASEUZc2Ruac0SQb6I!MOk zWgDdErzmN{!B2HGB)z}iyn9En$_$!Y{(TFJ`84;Zn6h7#Bbu&Yd7|bjH8pjWNrZgS zZwzf2Q(Z}wZ&22rH0O751i|G&ApcPL)3BHUXKz2ht}i76H%Uz3#3@D9>y!x26}s7qh<&Vqh#w>jErjc_|~`lRwATNtg>9 z(E({6rlH_tlebokw4QczGyCx7qxId@@vAS}%QzR0(BNt~+vfd{R*%JtB05$Lphh=$ za_TQKNCJ_!7bsZhdpspBd#^j_PL064=<5PT-ce#>b1+Q~&Z^m!JkWqzoILgQUA~Ih zpr^Nu$uu~Le$vqFJG+Mmw^oD62+$8xS4!d`o`h*<8s0}~6_#+YY(H&8`KgQ;t&F?= z>mAn*fv3;sL5u^$3$#ALoQVkWy-4pMJgo9=v$B)8*bwmT>>1eHtJ7f_z{FF};l}R1 zkU4igadFZuF|Oquc9Ni@fl#lVvWf~Z-a2={5(!gNQ$Z&gEYNGl_P@A4;!A83GTq2d zNYmqL5|l22F5poU%$x1i)YGGVl7}(QcxHg8W>$axW^H%8z)kck&p|MZK;NEId8jW) zqM?LG2G%(_9q}>}hTw0Xgq4~Nq{Xt4MXZ7lhsTnUd`tg1f!JhtmW_rc#lpgJR-SDG z!|{~G#;4&F=*^e3PT?G(X-0aTl;yz%>MgVGSH!YeCN4Y)2L@-kl+vJ++CKZ>T)k<@ z?dNrF%4A$RuPW+BU`w8EHQd3;$%w?n#8dB>yo8;d9io2WwAblFGkF0uj!peW&aQxP z`l6WEry4J4cG4>E2H+)(@YJC+AkHQlDUsWb-d~JG(4>Ek3J90^?jScoPC&m1uq0i!N)H zK}g=8U1Pwo)MqY{<-4{wpAzy(=^+`rHAA_3M)2kPiuqPHS{c8} zFLHcR>RQlW9g2 zO}h1EWs=fC<3Shx6jO&~+X~uDm8TSf@1#Ed3j2b*XZq3qW~TM^@H-3q*LVZ$C1zQ& z?P$NH#Urli(GZdOG5(k!&fodveQVs(iJ{1$yO4u<`u)LXUBp686n$McX9N1$6N0xd zHgbM3GjUuP!;ArI4n0jz8Y>lqLn9+2wnM!6)11r(g+rUAid4N_@|s~W3!5-8z)L!P zyRM1!N0z$U;_BG@2}et|OZtX)wnJso!G50C_)%fIs!=^N+D`Me1n=v&JqlR2_l^{9 zAK~6IAT+jHZZC_phH1tE*_5yB1P6t&xR+6p+{zQ_N*%hnjB}!cjEebXWdYWUIIU7#;m^2&Y2{lqh=W@GY~LsjX;!LRU#xO;v5m0RNO89|`>)d~ z{c7~TomN-JU}K|f&Y!*A>P_2X644pYLHjXH&6mG?P<3c148Kg`J?_hw2Vpx|lgjxK z8ejzwOsrp9OXPXM+C3s19KHC{f-gU#%5{}0BV_SXunzU5G0ha0n6BTQB&YBFr*X!7=syhh7^{?rZBew!dHENnYeaTl3A zcp2+=Hor4*?ABJcDer)Qh{y$_QY9W5J3dXx?alu5!c`XZ!@{Y3XGhDc5v^ey_qS?D z-H0x&$Qe$ezIW0!?(g$~O{ujqQ6o2}%GV<02p_sli`HrL8j`WYdM&TwUf8+nK5nXp zGH^)Jisb8X|B$TaX+TPtksDm5C1qZ!ZO2)+uZcxL5lA4Qhrz@u&bD`SB^Aa7M=AXrlUwiZ7vWA9qz73*oTLYRRN1J^a zJFUh%dNt1}3TvxE_$;i8s-AbdIj}|5ubv#wKsSGK%a6AKb8{EelkfGB?v77}8FeS$ z;TGKG+uRyREm#?HJKl>>ReeGwmeMMC9s!rUbJQMh;eIu~3N|EE< zqe44*a*S0~CGzJ_mXu7hzTW4Oa8B*PFnFN-76&s7w`UeIZJtbj6@#htjFhAG{rz^Z zWL{CZI0N;<{DKKbGhdZ*o0x#QlY@laJ0}@MSh*SvBQWV#uvk`FqY>H_gDWbae~*6b zi>}T|Ix&!IiqAyoMfU%|)ox9DVyBaaJk1jH?t1KU$0sD9hNjoue&X6F!T)L_RDL9G zE7{Gj{`&Lh93dh9U8Vck?mhkONaquDMXC}!+FZxKOV#)(-6o2q{!%nfo^&rHhz#7W z8CAEoM<$$${L5owR};|OocZgYGc+DngI}x~B(tjOd!HUpp=S8ZNQv%i33f!qX-Hxv z^m+1H;l{EK?C;w%(JBGkPY(wNWf8SnP-~c^;W%Q)nwT*(c4-jt3$oli3{RrbuXDI{ zCGYHn^CZN^N{G-~oGQ~WN%d1ShYld3&xL^;{Dbc;o;=}EW@YzOYM}86J-HMfPA|cz zVv_Ts3|CcQyqkuMtm5K*Q~~>w$>~r({UZ@jyU_4ZiHs%c|bk}&t9^# zT!Nq8-~;|=lpA8sji?D$$@te+$Y0(TF>aHO?6Ai_oQpxXd*gub93HH zS52*nxC4dbwX6u-Oj~0fo1i<`J>EY5+S_{`57!wR3)w=h^R#36{Q^B7AD^t}Y-R00 zczHRi-MP?1TD-CPn7YFfl9u~!H&$HeE=@C9~h(>Q$kXc`z>&U+J6c+K&eULx@2cBI&oso}c-H292{7tf{ z$BnyrD)*Zp=cRKLmzEMVyuZW<%Hl!C4;TQ$#`MO%)mo8pPw{wD`Gnm2pz zOesrs@ryy>!hBp@oJi7#G9mv5qkDI=aIH!d6p5bXZM|IZrCl<8$f0(JZHlbu^Q%0_ z7O+~4Z&&d8uRMyGT&)~mooy$;Ohu`(Px<{e$$CT4^toaZhk_4cx&R{lm82kaTYCVbdU&z~=%x(9^gSh`sT95r7GX;wtqF8G$i zy{r5J0_M(>wmk5x)0}?){;gt|;#C5*OxBgqu(0*XRMIJKdKCZn5bL{SM92O= z7kCd}uM|=1WNW@sDi7tQu5fiQKOxP}StKxcHb+57)Eri0*K3(T;`d;{6f*ap{VI|? zU2#55f72X}`*B*4RSNi*k?`jH7d8n8EQoEDy6kqSE%@3i2ELBKxb?-w#R|{=mXZG$ zGhO7}TQ`yLQj6~22Ujpu*WH3?SFd^3S|UWH!(To46{4ZII~}a$tq5m*MW-N zaEd?7Dku&$ZAeb8rLXCG1>bP-Sf-E!?;@7t8u=`z??zm8(z7d8qv3!_+|4)>nE4xOG=5u zfp7r?_Q{m^A@1U$7uaW3esLPE16z12+56Z;Lu1UpdtMTL7zfA7bjLf>{OR1ng0z|= z*FG;@0GuZjv%AVVc<;x;7iiVjT9|%gav+*JD21zrG)}FYW?jc1efg9k-{O(LRP0FfD zBJ{-co|~$EO;a8WFo-P3QjR*(X0`U*m0y(fRC>q->qq!!VUl8jf>lg!efpFN7z&&CPM&y(>)pyhl~B z(;*%AS1~gCv&wxw-@8IF`?c`b5Zo*SH+iTL2xvrFlqMP3WeP1{#;(}eNq|gEb_Og?>Suo;CZG`R7pOG`av@(+DXlH#%cPIbDxL^4u`KgeR< z36~v3)WeS13PFV0K#B#i7aB+&wYuA&u?pcXB!DVXLqn)l90Asj8~39gD<%gje#)L# znPlA|^yg2PRqq-Zc}`S39ALGGlDZRDaS_|v_FSCEONsX_{6C{_>8Q`ContQ{8jOyK z=^Y-9{Wt&c^cdNql$4Ck%y5)N)}?DBpn+*N1g;4GJ6V@ywLQIcY;Kp|!u=%+}!k##UwL10&cKL|xc-wN-w>V7|T;V^s_#9BJT(K+yx zy>lVh*j{G#lZt=hjX$3UoGOgxNWwO=j%Bfk#J>XxpAxU%==t+b^1SSw=ppHJJ6Rp* zv7JbC$!bTw>C`~q>a&)xC$j}ZAPfp>JysnI$-EyVSXLDDWsL(&; zfJ+6n5`ebt=v5m_d)a|nPb)+9atDT-oZMo;J2C%+R$+)T<==^#yYmOMVjjZ+s>?*uSsAo|yV)KwDc?d&kCOj?>_9 zxAoiZ(8>Pw%}os$@=FkSNi--Vr25lSW+C5t!<(d}^FEA5_dfMTz8{$^pPW&wsf zL0MW_O57lA-@A#x#G9vqtuvDD?sqdXGB!Lh76R?VzZT;6TwU+LEf^ zNaaq(%q*cAakiFZ$0|g_Fq$?+*KPfpc*1A>?1FoQ2&-Jifh5Nbv8^v9F{p_<{N!@n zSy$Cv7p0TYqS?tZ+d1d9@dcnpinmwLJ|DMKM)RvHynJE7N<&+F-h1`n++3Pj(RRZusT$l_ z_xd<^M3X!&mDmss=V?b3**x7SjzYpyVqmele%yt|&&**=>kDyR{(}mlsKAFP3rvPTqFX4cf@14aET~{>)&BB}eD| z?xuVzWc|2NClRKcvSiK6%lj3~n%s64xhV+z&srgv1E=C&@#gzEm1O1+M9>PUy;ipk zmS$SosVcTW5xu>U_hwD5#-7OSL&f82Q{G#UELa*pWTo0O^tH^WBLdijbZud*r@>J4%%}WjF{>o}(k-Sv(ix=hq)7BlU zxKUYC3H#{1q^pfneoGA_8ymbdSFe^nzm3_^BkT$a3Kb`Hp#5eIqZAbph|D2KGg%+F z^&FwLLWx`On$2mkX%Qmdj81Ld4&o(Z1WM*Q@HQN5|0G4~1_S7H(|p+Nh0E5?TNiseA86wo??o&{7xw zv%>vaC(YM`J7E#GB>`!_NTbPXcb@w9?ETVG#yp{IfP=kKZu|TE$6NVW;!W7ln+3cr6km`d+pMKX{VOeo%4h$4{)>dZY1A_UOM*LIF|8m?F+OY_D zI)udC@Nd~YiWkl{Pbzx5#!3Z%Rm+UKF!&Pk)?>J8`$Oc3r>nmOgBH2*t_O^-VpS9eAWI=i~;_i9BoH49Qcs$>lF?j37= z9+d33F<38An!nL2%w_hj^J_e0LP!cc%o*@(JXq`zJcW4)^#C`;I+@FQ)JCMG)%T^TCy9sSq(CVyX{RbTfv(&PXJm@|s zeteLWA@UG8>@;2G&82;p?i6l4zxqNDvs0=JKVc?X$WxqckSK1wQcEkVV*P55y{98P ze@ziuq3X6k%Tnfz*Lu1?yyi!P+wK(a%posD3qk3x(Kmr%{6I2UH~84H&c=W`(kVAO z-lgwO5vQ~O>2Y@=9jXm$8*c(eYBWH`xa~6CrcceyG6?SNob0=OdEJs6bOY}dCo+?D z+YHJzR?mOGW(wqrhLJVetfR(i@IiwHncwG6hGaImxw(J-{vF!@Oof3=K|xPj&lpW+ z!l4SrKADA2y7&vTT_ZFFbq6cqUI7W0=*w0a589Qz-mV|W$q~m|6EOdJ!`Ln_m1_GS z_IjjsyjJkwpbg@!WK2Qf%%5HtC`db=pi$P0b--0FBwM?E4Dg?ZLRB3P7tz;eBdY>y z#KX2$ETpDSz6YOCaVUEg7^>(BDK#l6MqN?%N3nh(FC@b3Dw9-RqMn5v&cEdd`X-wS zvnP(cT8%JMFivBNoHP?jS!Lz?X^nK(_Y7NbTqyvGO{Pkb>SHO{yVouAlU4q%jZ^uC zpPE+2K1cR0U1AUmt%0db1puI?_P3U(YrLH{eMsaV#Il@Az?K`lEZ4{3NZ`_+eGA{k z)EYH3G_`dsVBqzcv)SF@SHy{6sQ7-mA%c5VA=0O7{$Kslk=>}f`}5=8*w^Qca^E-+ zbU>#<%fHt&)_@1qzB~KJQ(;5=9~`j$KEc^M>P-x|jdeu^ERo zldG-S>Y27f7Ut#^iROTIJ8({MVfOS{DNYbzBQ(-p)zbX1GQ`@r)2e%9Y>d`xzc0ny zgV-6XQ#j0==*d`Y>|2C#(jpCmp%kOaODY3Auy`I*H$FPJk*t`@b?dlh`KaVJBq%e* zt)BqL`$gorKKxZwpojuG26NuGA{T(3>5$9ziE0;jX6oF}%LkyenB@Ait@VG3RkdR= z&7ziIOniI*28>f3g857)*C4o3z<%gew>$#9y|C}4nP-#Ak%x!-TWJJ?h+*K)sAX*} ztWk>>20X2$^4X($*r`bWK%IYGYG;An$Kx?7`8@xgfrCW49jO48N;=8x+uKxV%t#B~mZNRz{0#-zf*X672d zpEu{K)l8db_pz>S(k1MF68*|q0{ZAP6`%I;W3!80?*5%h&TFfA`BO=cuaq)){95#M z1hq4Idq>GV8v-eB&H%Q+PTqr}=*1KS?b5|cC?D!Koi^@nZH@D1%tG-{RC`QlKmL4p z-BVLjy9ZdyAlXsHgKr-Q)H2%pS8?hoezJa(*vM`+ml9tD1?C9bH9nM9ZT z_9Iz2;ww9vO%EUhA7tck=8MW*-E*Lo&+h zKf|jbbWKSAp(W%IH17A+PAto}N&PIW(9d3Ert?j1KapK$6#>RW731DEPiYyai&Y0S(L1oh#{)xuDAS^TR0oy-w;TttNE@6vHc zyJcY~&vE`#^L$_I*H4FNUMH%(Y8FtuHnzL_mR*n*@{i_gQUhUBrfw4-Dz{A3b*Z%5 zIRsU!ocfqxaC-eLrmz0rMC3BtS@PsD`4oNr4#zdKI&|uQg!$sHhL;sKFqjbG6Y84( z;Qoz+Iz(&^h5y3_^l9yQ``YC!U~6bwnqNt_(f}LuQ18&aFY2mMfp1iY?6ty3tCF3` zI*aPUFWMQM2zQDPi7>-=K;H%c1L{#6w&Mm3e(mhdr(*bri7r30>q>F$l_b%(PM$%2 zeq_mZWcuf*=*ySTmX?;N1`Ie&RsvCQ&i;R^FDNC;OiZ6ILnG5OF?;~uz1uu`2Z|03 zh0ExwUIhr=!z_uPJ|pd6A! zP_uw-^O013IhJ1HrBx!AhL#Yh$lNyCS?OGHc`>}62XJ*I z<>vvwyo(0_1ND9hJ*LGk0-XOJpI;(#6 zjhyY!ZMcOlun#`39Vj{XJUx#FZ^Psl4r3r@wkEY{FeXhLhb;t~D$H8%DUH>7)=ZkgS5^ z{!a^YqAJX$DJTTc+2nuGu*?(MJu5?3KU%%Zke7o(!=pg4En6~9cn;DV&0%}Z?16%1 zwo}GM~?EZf*|E7{r9GhVXr5L7Bsuv#(#tiHm! zq7Pf=DGw6ae1>f}2!~!L8WooeGUk+I``z3=f^HRP`Qln)!l z2angglZPB|Z5C**+uN?FYgC9VJ>=RK9eJa+K|pQU3pvg1i(l6-8IFXu^CX z>=zQVfGM~ZI+}8{+^PKWXujXgiX-c6;JD8MVgf|+I5bc&p(+oE9-A(92p30x+tj%6 zl=gPr7><6Wa)T8b>-zQUyIro0E&Q?QRy-~sp=CU)VRJLyN=k_ck(9CID>)u3rOt{l^F^&(SGOH}fSl4QVzJ=30nAax zg8|G?w%xhg-tCwoltAeQDOCIJr*xH*p&|;ET3-Hc3*+q8Aiq)|6x2Gy?p--9-=;QP z$dbrXXFvAo(V@_r`=(9|ak!C5hEGwx^hm{T%(I`}cq}hgN~`x>uym-iB=`aBrZbH# z2m!;-04ZL%Vkvv7aYkKkr|Hqf!9uR>iG*KEuHr-Gzt>=$P0SekK)_4>vz1>`;o76prHOcUOnVwXK&x-rUl<(mCNsseUEe(k$pbamUWPl zlD-iW*{#Zfu~&$>)v%PrZ4Ki%IIr}Bl|t!mccSktBfcAbW%AHVc=BU=Z*sTAkh;3J zf8ov^;a(R&uta5+0W}=QdUG~7p?@EeEjqeRo6}hcCUWO+T$IEF>bj*f=E)^l304p_ z0iBhnz)+X^>ecgzv#itr7h$2|G^9Gb%GIWJ4(w9>oV(F1&aYEnn~&~Mys`r&cR~R9 zZW&v%il!|igLv(4sd&TO|HsvP$5Z{k|KrC*qG*_9Q-?|L4u_v`ce{`%u}Q?I(6$9X)i$93JW`*pvr$CpkbG*NDi!_s+xoVgXSZp-H0)tBY;%MQh2+KV3>- z$j?k%qdCoNjmbQfVyAVeBH2VGt1rohdGhCVCci%_z&rr0nZ(cCs8mKBCa|wm-VhbcWEVlsdDx>OFnlno#jAey#3-}02j*hNM2bIhk zRo`|kei(hnCm?YDkEg3EGLUd{RTs9C{y+#J0`3{*kCa@tSm94)b7Fkn6S}+aSGhsH z__;qT@5zUfGHvypz9&7QxfP<$A*O5^Sd_B#5P~OeI8zM@;ER6TZLvnH+(v*a7TX_k z!CD}MElK9uU?Kcf9IpRme_j>AzYTMHeYgI#y?Dp0l<~bpmy%`Wg~faU_?nit*O9Vs zJ2L>6GKaPnhWj&^qX4gHHH&71Tq#knt{Ju<+Kp%L8mf^psXg#)Fgl^d3z>S&r3*Xl zS#8wQ@zZ1ef?5vOKS=hy*+yPYS?=RjGlci9-2N$eladlp&yo z3y3aKN|sqzsIsQ|*2|>`DTOtRjfaquJPVCe=gLl=@INJ#OOnEnC8{Oevg2>|K0C+^ z_#dd^mHA+QiP!BiC|rv24Xj()ob1ifC|iI9zdQ8(%a<=!wzeOP<)Ja5g^p;rq6z=K zefjTB^yh2n<$Qdj855paW~|bO)T*;6uyq6tEF#-sRw3n}9LjfnGMp1Il1uTcHQxP4 ztDp`9#xgE>(WkDYDgl?`WnTcZ_Acw`0`@0HpI>Gf{cT>BFliWIM(qq5H0d7COO zL|d-XL{0sPU!pn)D30_owY@tvi9JHEw?{@xWufUrw6MAJ8bvpNnC)%j~SJ zgOP?6O*cSUDF1^zGrUF8;7hc|6*Er4O{#1OErJQaCUlNSbTBVAj?HiEc)YfA?ju{9 zZ4~>RJv0n{s3lRLFgY!pgFp|^Eya-vFw>u;2CNMn^;=V*0F}i%{LN0XOQ*RSGoU{F zY?SC(=nHPr)Nn#6Yq$aNNnxvgh;v*e0G--F2FfkB(&iF3uXb_%YH)gdLeXCHtG){> zE9HiXP;KQd{18dRAk&SQX6VAzyau*%knkMJ$!|bsH|J~a|1!iqiQcuz)FtCg+R)TX zRbc~Y)|>-6mdUx(r&+P*3r+J9d zmLQP3(+$Z_XOD(M9;44pyp{%a<`ZX|o9q)w45XyZ7aZoVl|#WmvjnK`lgHV?PXloA z+*9qbu~#V!YzPh*f~LE1heU-@F5SeG6gk&~8;p;OL!m&RE!@F= z39Ma!d%=-M!{$mx@6A}JqS%7tzX0{1%2F_lKwd#bCM&;;F<-Bc=jx3oQv0ix=d=5S zcphzR?9=d8mnI2hL~;sYZ?au_m82#kYG_=(bc4(!!6}OQxc@18;8vh$XgATmvobCi zXy)(JpP(t4d+D{NmJQ~L%q42D$1ZR{*Gn+?In6w49L$jG#{h(aI5T{l@b~;Y7pPC& z=dIuyi0bL-HE*5*6Z&=E#)b+S%?`j{fI49!!L_mp9(8h7c7A^bMYrNXU_63qye1gWT%s*4wxmQR%-)$_MKB{hu0UZefR454 zPawZ1A2#Iv=HVoxpLtS;*cJ9F0xQSr){U}UB^1bDAgf~}Nh9~lNlDcRpP4DZ%N!#J zY*pO`+jz+mapWML{6E(+`rYyVe41-Hi%>(G+qKD6h7~4Y7Upv9h!;a#?ksKLd7Kg$ z_*9*6(*{Fo+5X|N?&6zMUL*?QhbRWzGeO1Xo*zISDIG0Fa@dx_aGn(mAK}PB;?Ze1|`pHs_;$DB~^a0gS7J~*R<^~%N*a*8adpwi^kP5wIB7E8%*QcMPi3c4i8r@bGw&kql76n#tWwq* z)uZth_hSU8vRjUV?fA6w5c?1)21h$VQ-rVKlMGMA*C zBv2zWMFV9$t*J!^DRx??c0DE+MkZYcTE4WLo&Cs_spoRT>e|vubrz#Bpe(c;a%Tgi zs__~EBsHujFCbb`AX`y%!TBLv$|ol;S>pbu1&~RAzG?Uu%FWGNP+|Lg@(wN{Da8no zcJO%cv}6NrMQy&X5r=qbP{H{(Bj@CLP<9lCN>e6Z}bw z`lT&Cid~_wrNHW|pu16An?_3vYkgFefWeXF!Gu&xOFG|HvGKwkgXEhz?g7OJ5d`+SKP}GS^Am_Fb4Q zFEeWR{rjBlY%K`rem`W=Ka;WD3N#O?`1*)yl>h0Bzy?YUm5gog@-xtxDP%V%^e7?c zfDD=O0wZ{HfnQV~p^%#>6iqWic2EJE`| zqwW+mmy|Bw1sn>s?W~*5>;ZUP+jNcqyzSl?vRjM?N6Ywsh|(y={5|wtVXL$Y_SMJc z^vuNZGqm}7*#%%Rm&qfM>w{=p7!=lb36LEbP~xf7-I7TX!3Kedg9sI9;Br4?a;$L8VSCu(xhp8$#LieUD#*C zt(6}KwHW7`6G%}2%0gR`&>yHa28G8~F`A7n0tV@<oZG3Cyvf!{?o2Epzu4*(gsP4ear)1MWj-Swc!G4Ad4n%YOmK zLUTYBeK|N(^%I`JHXlevS~T^7u!Olc9ye05qo!UZx`x}ljmib%%F95`Gg&eI#-8@4HTka42Z zZ?86>7iyD?4Gda)6n}lji78x43stt%%c)Q3y_xG8u1*&J9H4(CmItyJbm+}(E`@AE zEclcs25m6DyXog-qovB7!pzZE8{ozlcz6vwXh3tCmEErlIgf@LN?9w`hB`yTgi|U{ zE76|oZ;(4|{-aJA!ta19S$d+t`Vm2~vI>M-WiVH4AF02Nx|^T-pARSMv__6`_A(#6 z36qeSD@=L%d=Z;VTegpKMA8Bc69n>8wPL2@xR|5*mCl&$U&MbkmdKm9$g)qX!?qA& zh_z9$z(op4y?A2BZUFZMO&;ysycy$zJ^dzUr!OBLZXf(fxaFEI%|TJbWw!=aWFLVX z;u|OS^>FC4{z6oiylss({5Kz%MkHh-xsT67nVPCvT}zs@uBC=l1LR-sFCyL0tZ_K19~f zpzzfn{k}AOyKyzb@x(wrSZGDFgsab}N6=}~+?~bVaWcn;Gxp(Ptups^#X&Oe&I%kE z3)fi?8WL%Easo0>Q_UAvtG$dY@%)GbRVcE==3u;S0DcM^i4J=wr2?+O@yqOL9I3D; z?un{XSWQhLDCB@Iqje&w^Yg4AMLGUlpHhv2MlKZU{KE{&@jWBn(DPFEBex_QFe2NH zjGHgRmAIJtI>IT1QF2E(b{2Z)#A14!-4ey5b&kLjMRxsT;F2%wd^phQEf4I110Ja( zZmr4z5Zb{lenc<0s9p1Jd>#Vf(v`Gnc9pI^p=T|+pwLpHm<_ZvhFCzoS})a0I5ezJ z8!5KE>6lfl!m2Fa8|{a;S{B~_-lnR&)Bi0!O!#FuH7c}hMf$5d)5m6BA4>Vqiy#4* z#Fa17M2zp+|9zG`H}#Tbbe-}?Aw0!tzB`9nLebpiZUtw)rJ%7^qM&w4@5wrlgA5n% zAU$26RH$NOV>?L|sCxn#Be1D57>FhKsTr#h1^#Exohzx-ftXpG*vhF3?DE(3JvTx< z2G|PaTqH$0F33!;-mICxV5DdT*m{adGL?O)0B==Fy}xHb!=fYgsjun6jcwgC$d3!> z98C8JhNzpHb5kia4jMF-q$GdF{p|KrKoBsOqPS8iZ0Lr{T7y%tB#R7ynW<%g{A-E$e`b8 zNdlH0n8hi&d}|C#dNA6=`Q2@>ixwH|8P@O-nk))4xL=+)FDNdl`uIV|#Qpn)fE)Z4 zuBp1O9728Y{V8np@BxX=W%nN=&eYdOtIv5O&n>MOeXT$I=($<4835PD482@VQBhN% zTdRiifzP(HSINrM_+CG>3kowNTF=j4*gp@rNJL0P#9}}i$4pIL57PQV@qD6-{rCi!iX+3oik+Ju)x}dn@y_Axqmem7c1!Q7~CP^p(Lzxp~XRn-}(~)=g`mWCf zP`NuGU6hDSV`sw?%w-Uyg>MTB$F~FFH|9?c4nztL#NtfY=T)C4J8#O%``vh689LjX zBp=xH+5KdEcgU9;MNiuIx|JY%PLURsV>?L77MbDvZB}YYXer z!?fr%Y(V6_+z4y8lByi`*gxU-{yw=a8`BBj5}%83VV7an3+t^9P_ajJ-YxlBi8f7a zeyZi(Jd8vUV&Lj{AW-AOc&DKd1t6Dlpl7?6KzN6Y(No~(=YJF!cuB+r+4& zmTHRcf7=-2ir3Z1e%mW0&oUb7z0{uMc^E|OcAoo=*GVAuLowPAtFI*;B$IF|9IilR zp~^{6>}&j$h6L) zE-T1VfPY4l-I{s;U{vXihe!N9p@ej7FoR3IK)%5DxxVwJ@=762g~9^9L6@(K$Ojdb z-%p#QKE*V*CEGxO3bfYB8m@#Q<*bb-!_ZPSv7+}y{-C%4aoDmzI{c zBw<31T75hKRX(~_qCn=YY>dkL8O@NmFh6TQsS3TrocE%8SkHh_`_=O|9VNGaUA;T{ zQt}qgQ(0${qaTNUfh4LL$r;KKIhzOK{kRk(!CdCBvK9VA*8ZX<-pdsfNy}p|rp=vs zrq;1v;%Z&bp?-Wf)oNT{m3j;FMIN5Nofpzrn*2xO`XQ@%v*bi7>y89)%IG7|Q^|Es zoj6Fv;sC8ePr3n7*e84Ct?fs=)1=TL+OW^gxsRjkK4Wy~g3o^j$-?j$$Q*eS&AF{AggMFyu89KjQiHrW0f+t?O_;`9` zD%gqa!O{cI@gW6TpgCxW^GB5I4p@VcT4ZQ!0av1<-M+8$kx08v&133)(iVbvVaTPS zD*y9rO3RvKFl0>n`Tkr=a{ zK4-^GAExbupE zF++1|g4su#dlQ#Fn}Bd@mEj^~;$70Lsw`o>!L;V7xyzt?>1_kX>5&rtDrxd-34)8Myx zYOiqrmxjinj6Zs~Va?RyZHZpL86_XNtr<7hoMBLKhhCNsog&Id^b=s1D+@DRgg5y2@`qBut1mUjba@;Z>VK}Os8n$*B8UGe$diF^s(~^QqIk( zBIH+fqE<7&mJ;A`R;XGP!L!Lt>}Ex#_dJ{MZr7hlscKc8#e zy@VLZ{@#m=bg6dKoPBdb6$N`5HBT9-a*hjV9l0SOa6sk(AW_RPCAzeVoU3r}Cfq(5 zSz5+$PDNa}hcs2$9maxYA5^_VZa93I(QOzoz3K^&9AyhR#fh9Gmr8jAoB$0XcKo8K zNw26<6JenA3-G0YPCB@`V?xK5)?bttJLnuUmaO&%iu5J)Xu&5u&_-)&un&$~m% zoqJB~a4}~jU5P#rP&y+$3ug`?MK>0uFk+ya%7UXOcDKmvy!vhbpyard%Nk0ED26A$ zi8>kVB3`oxL~fbuzOF49l3JL8LJvX`lxl&%gT9q0o6{egB|vrn)VZ>T&Af!a84qiC zQtZwa?{eCX3(gK`QX%1`k8{h_NZ3Y#NcxhuG3;^YNVe| zn)jUEM4iW89u<(RnVR2q>H^NOO8c!hL0d;>)rTB#$4h`vZ_3Kt7S4ec#1w;M`RdiH zMZ{vWllEDl>=N>55qmF~RzJ)M541m}c_v$#wtz0{PZeD~&cGl!M6g6!KVIjgMWIbJ z8hE#oKNLdQMVs9kLUh21R3*0}v+|v=W zC|jw&b;1+i_Zh3F3wGmq@MrD2!&M%86`m+)T0IYYh~RYf7SE{>anAFqCRQ9Z>8TN% z<=Ncs3`8D}ABaa{RpSj0)NkQkuty}wjKb-RsRlG6CKnbLPkb7+n1qN$dx2c*;4Ffg z8VKhuo9P=oY~k010Ankz8x<@>S;2b#_E^XHB9cT69Z)UtKZ-3-?S?Qp)&NL7_0nc| z|K8M!Z{Rs&gStPsDi|)<)OY6rpexjmZ!eCb{Fi$+_RW8fEMB!Y*cVM%d`_Rre?YFB z`a_bqL+CA1DX7AQZ{&;aN*sEZS^$(Diy-k5ng{sblkUbrfc0SZaT}{vkJrJfpxm{(Qyj zO1J5;`_0ZEWTgHdq_-sRJ_+W|4~RC!r;IT0*=;h&(`jjAo@;N)FIgz7cS;b{^&z`9 z&~21FP_E5U&+yei-wS40Ljvgh4$=F)r6Ud;<`9IycqCBf2*u+A&vzy#5{eq%etvxW z+4**ELbWZKEQGzn&2mF_rE!jyk>I_0|6XMZacqljFB;JH$O;&?He>nT{hErEa*vbx=hb+?d4qD`UG$4=>(l z_u2YlEWCUE#V5!0`Mw*;jXs2x!zjO>=lml2s(Zm*bN&4G;&XB3cF~e6bfv$+rF0vS#vy1cviDPeD({;|f=8z|yxikN znRso}{2@3jHS$VAb;Z~>>+I2sysd2~=%*#C}Xz2Ej7jYfJSAJ;RM z?W|a#>@54q&a}g7AjI$M^M0E*Z0>apjXpE%8>`RRD+WWBl~94zmTmKOkH`k9+<9FL zJBTDe+0;*u&ap9gNG*p*?Y#ZE3;Om3nmach$uoJ9OYIDH{PIC^87>xckqT`kGX@3p z>foBDFu$9v^}D!fUxKS_@|qsOBAd-+ zs!moMp~X6z5Jo-?JK!d)c9`Jt$e?0}wuRAfEcfMfXf z8Q`B_fMCuOO)}woqlH-%w)PwuVojl;$A|IvcUG7W99sOp(b*2Vyl7!c{?A^GJO3Ck ztCE-jx4HctTnMqD`0*>FZR!tOGm~ZG2cbECg*Po$In>U*KjDeZ+(-Vp55OM?BDKIO z;Aug72n_C@>D!4UccNW+g!Xj}N1lVfEh<&)K+ z{?f}T>pWDLrCK`urgNS-d4uHaWn%n8j^FT|-_pMz=uB|r@qsN zhw2y6UvXFHs}QmMBjA%dB=wJWj8>JIEa{Ic#j&kUdFSm%uh{KYCsJ|ha&L$sT-NGj2yvdma=N_Ob-@F;JA6+{xS5Onos7IH!B5rTbx(@2*(rdC^GXGR@84 zsat5sJ4lbZh+2nbV?Y>hcw%h-Lu#CMU;0}%90X9OMUNX67VjA0xI0`?p)0*IbgM(e`;x=LJakkIWjEe z0I%zF4LY`2S1v$B$Mbq{)kw+_hVvsQAOf6%^kVng$@dW&h#AnO#gdy34@QCEpMD*z zNy1oE(a|QhWPyv)WS{xx=Ai20)V((bG3iXd#w8dV77t&14Nlj{8#m;#2NH1d$6`bQ zEO~sAA(sfwdtgLUp&r9YkX9wO115MQDp9M0IOUyo_ei}-I1vwIYQCFD(1P&4dCF;K zL$(tdreV@;?JQkB8oCld_*7C;u58uJBru4l$T%^8qSJ~{ozMj)XCg+U4p}-4%%!CU zYk;cm`2|p1oTibIu+xNslv}CK3CV3MveokCZ{WBVZ;`X_x`*(!V??-i2vg$Lm@6RY z;#3}<7oC0+z5tRBkFLYm`>w8NB3V6j_5cD{-oH=UWkvgc9PCZx+>x#e-fP!p=2({> zc-yqiE~ttY6F_ULH?BkexRU=biaKG@SS}L{_S)_xOjM_G^3A9Y7#QLuAWi5o9g8`8 zZ2mU@NXSSpgIj_$(Otoer+kby{qZb1jI7AQZCUNrpqoJWx z3m;=<`rqHT#h~y3K#|jgOt^vHvrT(qzzyi^&AZt%>W94iHhfm627n;hKR1R@YZp`X z1#+3EnGjj4k1-`VXtU9}8phdsgCRCeGE{`5dFI<`&tu?-b&CZ1*Z_1nc(h%7u=JK`Iv&{9z-V7 zXe#R>oI!Nrfok)B;g63tJD}0ETWN$27K5}4xEc1G7G2UsdiQBxD*nE536ty3)8p8h zL-h^`l$Y3h>>&q54M=KGuYG*Q1P8`jQxgDr-tX_})ai(d?Gf~pSC5M=ZT1yBS(LBTNoF_IM!uIq)fR2MeqU4yJq}bBX+M{XxNoNaPop#VJsYr=0VaSrQ2j6LNxQ5#wuKi@<>&xWo>UywojZo|&PS%|YfCZzz z?m;U63+dfA6PO%@Ge%|_4+arI2Op_Fymj1zx6XwC0g}+aA$jp{1$(M3r?9m#H_P=0 zM5&?`jS?t``ctyvfF#8z7`_0^;Z1>;CEcY@aG)yoajBv@&5>hymnzoHl|XZx@bitYECf6U6U+N zb3(V$OK!m@DQnb>w2jlGXWg|Fza#>KF(4oE#&q!X^BVkqv*hhvO(W+&0~|wrLP24b zSh04KYxqx(5BUN3h5o|HrijZ#d+92J?!VU+6{1Ab=A!&JS0bKVi)M2mR(1X9r^b*R zJT3q&qF8t3(OHud1JFKw)ic!WJ6`L0>@}09jux|_HiqwQpT|D??MgB6WetK|{~YcduhNehNE>vyuOxrur>x1}jP!346Sb`V3{#AdX(aI^tEGt=d{(%qhf8>yo_NXq zEvj@Xbs2Pd9`mD*Igeeoy|vo^!+O}g_)kl{QVXo@?Af!9|5mS;(_xz+k%c)#MLaod zj|Hgt{`g8k1Gafpfi)#`;An*06E>rwRtVB0+*G2*LmvytjFMu+H4~b&@E}NN0d)Bw zkgNUMswbaBwZ+Ko9SfvLD6Yw+pFj(^0ATJy;>F_Y@*?w(d!NvP+{ArR zf;2EdXR4qS0)|TjPF9DBO89@Z+FiSM)h80rC=RxY<&yc8755KgqZgoifKfV}@e-_K z;yqS{ZE&hm3{3#FSlMM2oJFe(h_vn_I@V~Hgd{{}NpAeB3P{<@CZJkNg|~$yu^@== z+3YWUqDD4H5X5sui!~W!bKZ_wM2IymVWRmAiNYvx`CGTh$b^wv*@e&R(#?L&HuyR)F6x#UOAhP#I=KZ4GoPznmI}Qi3sMREbYzV zi(z<~b1AVWv{X5l+5DF(E?Sd)tXt)Evn46tAup6NN#Y0Xd7ktxVd(GVF^MeV=__e- z%{IK$CyjxzX5LT$xQ8(^k^}fdyzQlSP!vBHiD1K2ANyVRSYVSX|E z*v#o*KOx`PlN|k>hZTa<3D&&XH*fnEQkdqrW#nwOlu|k6DJd?HC-n3tJ<&yG)H#QN z1L*j|d2?rX+*oz%q0?xs_IKCtPp5UqPy91efS7BSg&@*VS#d0YS-{>P0`!>A$v&V7 zhDcz4^d9>|2gQwKGw*lFh;Od`)xr&$cM6l^y}h06iLa3g3J`~n9?e8+g;y*pMD;sl zQweBgX1J2_jP@p>JE51>l&C-pb@2JJ$D6|Bebsf;svs&L@MJ#8#=hi(j)V&bf$IM_ z?j>f*fq;7EgZC#2r5p8{)6hRwG!*M()9wW?1W!#(>eSl!swTwhnVSkvm|yCb7SMHWBnp)CV`F29qSMlb z1IG)ad5aG)mVx$Z_|PB{)!FtbiMar@iQx4pzE-Z`uky)jq}_*2RmHm@MJS$Z#c)Cc zL+GPdK&XG@-!cL@dtSCnZZvfHnbu+|B_62G9w)as`JykOCbgqHvTJqN-a`-00U@?9 zNcXe8e%1O>MEb=JcA=}QTL-f>4~7#ssVP3ee&W!27IBSsZD&`X0(<&835@L$8-v=< zovUReDtXFPSe~8>);4unW4Cd^rK%sG`v9q|$Oz{IXs%o?bWccP1o~o`r|`iLO}1|e zxmBf6$&zJEh|CcJiXd&@zrN7_V5%vC*r#tb45$eyN)aUxJN`%xrZ&eJ?AW%jp5S{e zNRe?N{t+&FiRfF;hJA)1H*-0M!;g77jqYE0D0!!aFAruR3gHCI`JkyS`fH1|Ln67+ ze06Uyl7MSmr(ia(V}r~BsH8zs;q}$t98uTQVSNYuK+0csOLq*t3j&Dy5`7{<;R(?w zp*&@4*^$ylB)6IlovCtP*>kHo5s{aj>N~Wy3Z>Noqw0k09$Or|>vQ;c+yX7Mrgo=P zz_`Vjm>I=V=y(7j)Z{F9dEn3j{}~qnvnGC4>Do4|IcEViB>CqD4Z`pt6MX&|?n9&p z6A*gP(6Bl86HKF!?cX0C+x;LHo4U#5_btB3MukZY3HJJxmSvpG;)zUe#_+Gwve?wqi zP;t@5n$|jtb=01_vPQ%`?S}mLs>JxVVWxBLny+0}-u(Ao9d-=4} z{7@eA!pg#|Ku*uO%<-npn$6T-yDKZVuetx_yRs>H(I9VgyDKbo8dokiHT}x(w&c#D zNMxI8lfFapA-(;d7x&Lph8Zo0MfuKnrvK_ml{|MUqR`JrDYs9(IsB@47}_ zb0WX+g(^YqyXX9V*8aVD$IN{*_J&^yl|&dc7;o3xWj~tfui1DoEY*XJSC)fTs&>EN8^r~je~%kc0m&eAy}t zRAKrcCqhkrlRS<>eg9Y|(k~FNJXH-15Ok{DV*OU1<*3tO{+)QFQYOnvVtqo>)_d7k zs>9ktXR$)6YOIwd${AZ6O&00&Iy&x;$8V#n!bX!;KXiSyEiin*&5iHe{O;~K_V&Y` z*Y%gJ7Jho0qOM}c1vqhdkui_UYY7j+Vd~KFmqFyHulK?EHA9J(S{Q|*7^!=TEh*{h z@`2Za_>(fw1$;$abYC(vuUHmsK)a;um>^k-(aUSSKSM0yGNof?LxMIE=4RbqU+MOs z%?OPVS}_j`=;aT|?J7WfXJo9TDx`fyA3K6J$ybq`#(8O zRS^vQpl1(fy25}m3Fl`xjq-mXUq^we`^xy+u}wR#@0+B|txA!$W4-f-=waqVd+acb z_diK_a*0ik*Q)2sndj3^HJW+ZaL%#;{LcNDbV8id=$B&yv9C1JVlmZ%bCxs5ukT7w z9pZi8er!_cnZ90*;-;#`rXU0u+KinP$)4s4-bz1LgTO< zIygQta$6MYSiz$c{RWq5qFRoBIez?jl5`N(B|~9XLf2wgNh>egFf7Q{wLc+6`m@MT zeH^_nnt?n1%T|5ux>1On($GZQg~j;GS6pq=>5B$;2(7cO(=F#@YO`n8uN}MHeO&CEi9oKhue zSw%%yKx`_^9IO3Zn`RlQdND|HMXut{n+5MRnJPciw<{$bl2I^`?|m2v>ZZI>X5_OY z>6b`Q&nSs!WBIxPhP;0NF6nJ{U;Vw@jmr0pYiKHo`6bK(o9*pv`2gm&GtaGGwBfOB z$4fDT_^eiB8ADMPVF8*JbrzvTngtP&l{Bg=B{jacy5}P9)@?Mi*BWnbxrp04n_t?I$`dLlfKTMCuw9%XO zGWPUy=n6j0Fyc5HCX-IP5E5|pY*+?Hf*L*88u8NNyEZQ!jp+Dr);N!oq_+C7Zhj6M&yy> zxQrZ!<1v@_7AyMV*RMaDV-2Z*a&vB1-0e|(*1a$aqiU0<_X7iF&mW3c4I^*kr~V}L z{as;d;?CP;UBz9WHL-|Q39I$S>j{?<>5D4lln6%$WIyiAb3K81B6n&OUlW|ec_t7<)pKEF2Aex;ie6pQ&22fDtmwZEagV)PF#rC z>K~Q~|F*I68P6{4kk(bED_MAp%erJJ6bs_Em^qIOpil}mkEr`8uCQ9U{z<{I>!*)f zdWxPIqG3BdhPJ2~S53r?{g!i%elut$D32ZrDb{XOdY-g`;eKUIPLf#7-gYK*+R3+b ztmLtTj)GNKw1IK$DeHZ>HGuW{WoA{fPdpya)|meFBGj+!72V-MDSdr?0V%1AoBZIh zb#pW$0b37&5R(;!oPV=$(Zmq5RW{xNd)CWJU-|C~De=;GxzoZcux;lLS$F%le8?7V zbeS?uH^gq}%8g5%>R_ZkWa_nI;oZIFEo9;x5>QGeeBnY)sx_T81$J)j*>7K$Fhh~5 zrRSe6>*)piT{Ow7+DD=4rd>Te=r&KmPy5Vp=*$%q!Ulk(sj5})lVuy@(1LvPWoqW$ zKfdanG~3!!G?PlGSXGvlF{MXebq>ZsW`Nq+F%Hpx^ifGD9j?r)=ghoHsI#%!oC%PT6h5= zQB+&~mawzK@GmDW+Lyr!X0#cDl7f#Vrl~e=I0(7;+C|JMDENfJHW*a=3JguTCy~52 zp3(1B+;IZDUafi#E6YbK1r+M^6Mt%y{}g?bBTrPb?AY+&VDJR%I=&m@j1Nwc^cgC} zTLekZyqBSVG1S-MD|9OOiS1Am7wre;mpvv|lbI-&R7+N-J=4=xO5AfRhAb_vXYKUJ zwr}F%cfKlDBwbv*Hw-%!7{Hz)!myZ+?fvt`!f&viMnVIZ!UhKU?^QS^xx1!8G=|op zp@e5g5R0JX51$xXv~_VYj>KHwr4l6cJCLV^-)5h@^x{*xLbw)(M+C*d{Coifu(Yx` z;SQJ5bPDU4Wx*=XEE0V&iPJW&<|Q=JsF`j1s-IbtoJ&4fiz3Tzf0YIyLEWCBUyG~F zWvTZhDtCBP*GUafD1R?EcXxBAckcUAU>x5=9!m1EAR&Ua{$>!i4E)mODVgm)Oiz|} zy4vH>mzRWY@$2YceYN`7Evf923v2r5jh>x~Mx}&D@t(;+YU>*r*1xmH^B^ol#LldA zT196L>h|n!?*;$f^Q5^eYi40ln{JttW8{bkavij^jOV>3w}ZpyLqvx*}KOk8?QHc zoWFSS%eQa$i5{9eMk$cE1X^SXKN-P5nlW~`!Gw@`edMBJDoOqc5D>sz0oA zYsK5hlBdpo=y7#qvl-oC`Y3ohQ5go{62pQaXN(fjRn;S|>REqXAV5a8Ut{oe(J}Vm zc^#}BI4hxsMH7Y3tYu%u@H22t%0HDp(srQDsIF=|&&|owUK}~NC~I{r)9c6A_$jBF z5}&N43T*}l&_eDE*di`sFBl#Nx=q-5YA2<$+x~vgo09&p=Yx%njj8#*yf$8NloJQ{ z)4Fcs$3#Qi9a3;0f{t(;49}j~+S@leM!xmM6PCwowcVrd@y3zFTrdkxdaAd%VvO~q z&G1y=HodYwBvbz)2?zL%RI)@Od$ZW@@T%Bu>#+^nZE@Nch4|e?TSY5e#m3f^EB-ad z2C67fbZ3cQeCyZNhsBkZFEGVo8eXkQH*C*iBw~zGJ|YzO6XYg3m(u`=aBW!p#p|aBVk|JTF!g&d?6k=1Jb7 z<}vJWxi`^JmXcRSGC8x&cv}hOqepa1$6SPn_$^X}tjypV5mp|efA7cxc42gpXo^MJ z7;FK-kbCh#5QCMg7w@ViTg}TXo{KScAm|%oJCX`S_$E>-xx4u)w zd2cX+_b9S+1y|I#9|d7Gjk$67^>xOGYMbrKo>NaYQUtvF6O1l95w4fGE|JIVIAcqTjY;kr9eAi6Ev!=1JQdbr44&j_h z=ERWmfBD(k*){+9^N@HIumDyH46Du}f$Qc`I22l{L-C1;2xNHOLBVBk+lD(k=4L~U zT*lVmD?rXBxZwxk!qkJ>I_|ej8QVJ0t*1p#d_r)MMq5p`uLVq2&qNkh-w{_Ir{I#G zk@DqFHF~7yCQQrg!*)n`{J2UhH($LtgTaf@Z%cH~HI${AkBCt^kbt%uZUqZ5gqz&7 zwY6=kTB+fNAv%boTI;$Qh*j*h!L||X)0@uZ4~CR!zjuTF%-#UCa0?CPTYNekY%D5d z!p_mt8yh@&2Ir#yHvYXT#|W86M z0_-pNgYWB}UvhUT^ou=u9iO~W@Hn478$v;%1pw#6Sf7{RV}9q-3!=j+*9xk}D+eJd*lPzsP@r!Uu0099Qb{rul2RC8 z-uUn|3Ki4=Ysk^$TE6^btpslo_QdweNt?gYPd(qRpm4OfoTtWNA>7y+ZfBl(mfYgS z3)6^d#39g98S#y&$;wcRtv;+s;$`X9o@^V-%Sz|6i)l$r>t9;bzb%7Z3K1DQQf+bG zOn`V%lo5*^tM(>ZY$<1I$Ctgmnj5}>Q)1mm*O8LHyI|0 zN~S-O3`J6m@nq^7cUait~FTzehm$`fUr_UGJ4bn=#Ek6pf!VG z)(8?|qKhMDuJ?EMEYccbcK2$68|JUMHHFU7d7&nLcN{>n216{k_0F?B3#G2wytF0y zuwm>hY5d{a;uRQ&p=iOC?Ah+KsWk=t9zCx+*Uz`@bL|@X__3_*fgRuOKvUw-tiwNl z7GJ$~tr5u!z22zjG{I}O$Yn=e7#bJ|mq}y(=Tf;?n|wrzzqQFEA@Jg!Fl>1Kg}KtW33d)aF#>P z3@O3y<*gCGUb}BIwL3RwjQ=4!*>C6ZVsB@$qyrEE+p;MN)k%}7t|0_tjpt16TVw05y*$*FLVpWvM#tZar_gg-Z9QHhJ0BL? z+ZD>tGFTs1eH)BN;rcV~vta?wb1V0R$6AYi?CoOHUKd4FSI>1~JFsIXGw?y$pxAHj z%hQ=e5;BQf-f$8VMP+3ml0N~H<+fM>GiE(H(r+OBkr;mG9Ej1Eva51*A+w6m+8E#D z`7Cqkn)7VD1XVZ0VyaK`A+f#V^{^Scb}1tBwq3!`JjSfv2FI#~$<}xu_`kHGyMARf zb8Gi{u-}doWUX-2RK%=I<^OVnV~+ra?d{aN8D2Pt0e8AJ<*7J)Obo{A>KldG zOA*hWxZx@oEQhXsv0#_EWK^vd?$$(@w^F1YVLFHi++Fj5!NE;359LgMX6X|4;y{X1GUq5^T~lr z!((`2o!7kkhqkvv6gYZYtZtp7euN~&>1WpQgLi3yLj!DG?yUOGSSca_QLk{FjU|FD zF>gIsnDl6up0i}t?49d8|@o?A}vwn;? zcoSzqTEUgsZQot{9V56xtRv3&u~x@B4dpWRG#!k%;f<2VExWrq!(LecKnA5tj^Oap zb&wU*6+s_$wD;!nC**n%*FY5*(Aw69B&nSNe?LW#*z)CP3abQ6wVawb4&7(>%ydOf zaFB=pLb25f29mM-bI<2gg{ljE3(NXiPlb9(MOZOgmVaNX^umdVkM#V=?<*T08*};Y zD!lV0sGmIzZ*jP-ln_~Ha7_^MVLlhGnCCFpn+Mqve<3TXy)rg+2(l<0|B&2}eJ*&LlQ@a%ACY}A3`s+VCRgyYretyV z`;wG!3-L%=zyg-RW(Lte6t+UK({{wPTCQtm#^THPy-lz#(- zC+)B0K$||+!E`8R^C2MM-+PMR@z~M~A70`jaLjyypOq47!}hKP2ArcLv?o~4KEiN^ zl!0dw9q+e1#SR~jGr0EU_wVb-R@@3id{P4sM3euZ4&8$lydWrHab2@*`Gw<067G+7 zcRgF8xX;oBz=PQ$)J{{3NE}uKPJ?tBbo7Gi>k<^|Y>1+)v}W$PX8>qi<)tNo1a}gZ>ZL7_Iwy*) zLD1-CzxS|os;87)7Tla8`0s0D3_s4ikf+|P8#L&6r$)w;Ea_5Xe69BFj^MdK!jR*@ z(9nGZ_tz`2*nFgsgqqV@kGMD_u}3BE-U${vN1q|K>;&+!s1_h_J>TF zm)KsX?EG0byWQbpo=I4%^nHUDz5&1-&S7RUOezcc{43!dvzd1}_}BpTD0;lN$m_c% z{N3>o;}9JTnRB9WSX#!=1XD;STbcJKD0qk@3{p5R$-xcnCB&x;{xKR&wg~c=IWD5J zfTSn^e_hbevBdRj3X(}ymkk;TiGNtzbu6*7u#oyCs0b|1(l}k@^zYws)mW5&T1izE zcT`l{{?pqil*tb}TU&BdmWz@Po4_>dGGo3wwjDnUtm^$;-x7WyG`g>^8sM=sU#}e& zH&}qCZk25(yJ{C4U)63PmA+XjwYf{vY{4F|6Py%yuQDBH)H!QYZOu^*oR+9VdT}Hh z5I!lUcrS)O!!@e1W`6s9P2N2{wN%w^yCZ)sY&aZiZa{n&A6JYLJh;(>up8GR4#LOF zU~-fJCir;&x88hwtWu^-Dt?#)V{o446s23T>n(R&e0@BO|DXC0xcYlEEEISIQ)^EZ67}JZThn(a?)O7R#v4M^v~xuu^bRRugl*~*cot1N)LL-a++$o zRWN}h^}4AkPm!Q0&R1WED*!r)l|=@L=eHY~Xed#2<`DyqZ9pKe z%G6}570qt99vj1$AJ$D)%9c;MOovoMM$K5%MNalCpl@P@jJh}P0NSMd$X;!kem8$? zPni0ggo9AGRnOga`>wgo`6CL{S72kxhWtK#!%|D#k%8=^8B7F=pc$guD(#2F?SqT* z6uc{DT}*#)0&&$iH!4X-W^jB#yO)Pryfx*3~i)+QFqay<*azZ>p6 z?q|4<avy~TBWMx7Gs6QB7f-$l3(w&xJv1_|DgJU(*Bjpz5--S$8ccX$j z3PxuJKYo0AVc%A&6T@f^yrUCH|B2i;(VKjAf-4J8DgdhRPkROXF(%^b=;(N9d|}Ad z+}C0uLk-eGyM1K|oY3E`qgD*h=CHfvc{y2|y`xrQ+iELnP;uDY*;72JT#?`aaXw=8 zYk`69DRMX5qJEEdeA%?@8}WVyiE)UniIN@HyD*Ht(@uJgpFh(B*GH#B+>sGsVd1G! z_wh5QE(-k)URZuvojvD3Q1Y`U#$H) z{-B&75PuAZzx@pyJMoOp0pf%*u5}>^%CUKR)$`OT#9V{4S&*{8V3YT`Gkot!OO22- zTEDJvY7^3f)u1>ismW2-If)v}w#!Rbk`~LEUigbuNI+dSfUjd+kYyGJ&TYn~du}Cz zr^2f?%BW{K1+9fsCG1{ZCL}DZq<}kxY44HncrNi|jDZSofzooKF%*!3Fp{aSmX_>@ z>rjVvyniqEYyBNQtBO!*ozF>~xX7o>I&xj`GunnZYa*8WWKX!t=bK#AGgOD}v`n9q zMsCWJ1e*fq?^cQ>(-tCgYeP^l8yK}HAA_v?@lBwVb1ba_SMEG9>S$ejnqp}Hl{A)8 zLQqU7+*=bmEhyD^u38W?0!r|&kNG1?0faZOMohqqGMeAl|H8Y^;|X48yw+^`F~Ijy zWi0ZCvrKHn?TRHPThTp>?~k8I4t4D{X=mciNlW6U6&zF%v&)75RILL`uPqX{xHhPI zXP@i$^7V?nM!>%1lar=I_^W=9A<5k$Mfsz6gaM5yngQs`Ofc>>Eg%fFw}-CozQ1(> z=nmmZ_|O@=8&+9%J~V(<^x`L7T#DRs1;Cr3u&gv7N9{QtYCt)YnGaxTtZlDm4$7hJ44kubNp||S7yof}Sr+Mm7A2k|4XuV|49_66vZ$a1PYOzvkX-{59AemN z!9E3f$G07J7MB07scR2pdT-;Z^CFiDM@p2Y99?zVC~4`qrBf1hDCAPiWoAM;x%MU` z(V>g5TIH5HCNlRKM^YJ^n6<zL)3nc|Mz?z5Dl5YAdR$xEz?YqBG(H^3=E2(BCU5l!vY6?w9p0WcD?rKuK2@oAg_?U8xEYSsVV?AvUQd16}(e=tXu|`0tgqBqd6_*zXpl$KatL zab1wI@&Z1dfAf#1P{~LKVnSC^P9C@jO}IGf@@B7Dh|zjvDmqEFTVF zHDRAJd#T_USox4kre8i%yN>A@gskUh{z9UiXsz`%F;femafKSoD~7X-*`?g&mu7|{ zSTQH=|8QF@F1G2-p(a$qT-N_pgwfN(1>|?g=2hE~Yk15gME~ve(f8V&ZB`oR1)igr znNw~$%8Na%y~bvh>ZZKpyRFB5@JdS!|1rtr<%}=mAS0-ROV}f+NN}qjWXz%?Ry$|6 zP1}r?4+9}=JxB8o_PZI|De!AX!W4B-x9NjRXnZy5zF@l1b8AM+?gIya<(8{wML==n z9kP307J#jKn`98tY!7G&mmH-SFyZ_?=pCAmXLrw>@}O@7hQPUB&pJ0K7{qm>ER&a3 zZGV}X)d#FDO(NY4=@e&~aiBDvN8`|KA60!*?{UU#+{Z1wp}HJjb@I-2T(E9Z?(rc)#YzJ&46 zE^aT!?=V^qL-!z)Cr*!Ia{qK{lqL_yB$l_rUl}}ZjA`Uj!%dO<`OZ)hp<4P_dkHP8 zmX@RgX&M{r0i-GT?m^V%t>5&m^2S8>7jb0~JWetzC;R*#zOQjVp&DHFFx!QV8(|Jg zHxAQjm)GWcwXAEWkuK!7`sd#Om?2E`NfH|ZFuaU7%%;I9y905SjM`Tqf37-0w-mS*7djbv zcZj)!YA2f`0T1&zZ2S_F$X8&oCJPIXOYo}Y-$STNo?}{kd_0m@SUwRaS9OxEovWHME_Zdp|B++4n8aerV^mBkqsyeASP-rxCkGYsejUGt$n z;;Dyk-TQA%K(`TAEnSfjWN}k0EKaf&_Umof|2tnN!!OaR>9fQ0W`;^5<9Ul_f`5G; z1I+Uy(u4sJy@|aKz3#$Dd(LRXsFMpZ!VXavpXkV!b%6``SOc_^3rmLLLvM?^24!<= zM}d8f5*BlE6t_KB@&boGD#a&w%^BK;s^sFmb6_A_II6OE;(UkTU0+*Wacb0`oF@SF zg3*l)U%s3i%0e0moJbQs&$cwD zm9Iy}W2S2zd~=R5&!%QzmhBhE0PP9|`Ks-6sNAyIXKGxPBA{b}xzP)g&9eAsKQMi1 z%a2N^5R`HB zuE3XR74@#M(KX)^vKmQK7GCcAu%GuQo0dCTS%^OYc4)X*HCL3$xlS5?3at;&!(_pv zbPS#xb<)TEhicewz+FXX}2yuKfriV>VqjVE*tq?|2YHA{DF#>AqAC< zU<38mux;EZXQ(dOuc$C+DN05qqoIYtVoAoe8r||z$K)}8bao&BfIc*H-5v0_uk&Er zZD#`b(Z-eN;-8z3tX6XOtM#Tu<#;dctJHl;@7Dk9 zU(RDprt_JY>Vn-upbszb+kh5R9(NsWvbCcEL(80CZ*jrAav5P> zDh+R3|3PlXa_m#qGj7M|S1*76!+;g1m1{gFR^d7DS^W*sVU{sdw>V$KJn0n%li9Mc zPzy=~?~%iG?cU6qt})qyyfW~)IjIDIWF)v{Sl-JqX0&vZdZ%bHDYrvk6`)W@3pP;8 z$KQX;ySGPwtxp^{3!$yA^dZmxwMs z(043)U_zi*y*fgnOvs!2?%`Q|6nBNil61>1ygOwk<-TE!LVsVXfV~ZgeR6Fq1dwPE zfFu8}PzsYnK&*avt|SpZSNRGgmTAHBZp(7_AJ&JM>(Id@#v46Sf zh53;;-9$Rdnc|j4r8lQrK|6-2M7S$k2sNbNg-lx^|wHZ`H?bK2iAzaJe$ z7(#Pi(NP0Sys9n~=-+faHziqE(^;drTyDq-E*DFg1TQZTUQD@gZ-Cw3h1$$6cp%bg@qZ`Rs%J>`*$mNG1k2?V$Dla1643%~O?s@XK=-mJ{*5-74gu-OBb>Y+ zMd;$Nef=Arq=(Ilq^%%iLy`(Y6uIC`nPr@Zr{GFyv>l-2OtlhYZb7nOv0#j7zbeOV z{DFJwM9sA>mtuHjf3sh~7D7oYW1;*S>0beGva4hKU*i`46ouM9*q?E+SCkU9IK4$Q z&!Gz%iSwUW7QQ$2!X3Ig*>Q*LnocRZs8#=D&d z=Ek=HfIZ|`NJ?}-wsCR)1??L@Mcv2bmnS7Ty2nL$XTfnU<%@iz?+eron_bp6m^-)t34co_V zg{(Q{3T^CCUCzH@4!q!MI0YL$U*@Yy&dbZo|MbB_!uGfz!S+nJYMA0vXtQ0eAz$8} zUN#OJZ1CmpERT;@6UCXYxkaN%^sH^Pus*v{87FQ zy{Auw>npY}^z2-5^QWs8ES#JI9x<`RlL*=516pvky@}aIz#m^T3y*)TUa|Si%z~hH z`q+@feSuf4Nuk#y&j+bw!2gpo$>a=}j84CaKwP(L#8`3n6ckBs;qSCsLI(&>OSMZ0 lL}Icc_=lST<+zEzm!0Qgbvu=O!3iiPKu{{RC + Value: false + - Class: rviz_common/Group + Displays: + - Class: rviz_plugins/SteeringAngle + Enabled: true + Left: 64 + Length: 128 + Name: SteeringAngle + Scale: 17 + Text Color: 25; 255; 240 + Top: 64 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/steering_status + Value: true + Value Scale: 0.14999249577522278 + Value height offset: 0 + - Class: rviz_plugins/ConsoleMeter + Enabled: true + Left: 256 + Length: 128 + Name: ConsoleMeter + Text Color: 25; 255; 240 + Top: 64 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/velocity_status + Value: true + Value Scale: 0.14999249577522278 + Value height offset: 0 + - Alpha: 0.9990000128746033 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 255; 255; 255 + Value: true + Enabled: true + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/velocity_status + Value: true + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera0/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera0/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera1/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera2/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera2/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera3/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera3/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera4/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera4/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera5/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera5/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera6/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera6/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera7/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera7/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + gnss_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + livox_front_left: + Alpha: 1 + Show Axes: false + Show Trail: false + livox_front_left_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + livox_front_right: + Alpha: 1 + Show Axes: false + Show Trail: false + livox_front_right_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_kit_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tamagawa/imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light_left_camera/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light_left_camera/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + traffic_light_right_camera/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light_right_camera/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + velodyne_left: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_left_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_rear: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_rear_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: VehicleModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_plugins/PolarGridDisplay + Color: 255; 255; 255 + Delta Range: 10 + Enabled: true + Max Alpha: 0.5 + Max Range: 100 + Max Wave Alpha: 0.5 + Min Alpha: 0.009999999776482582 + Min Wave Alpha: 0.009999999776482582 + Name: PolarGridDisplay + Reference Frame: base_link + Value: true + Wave Color: 255; 255; 255 + Wave Velocity: 40 + - Class: rviz_plugins/MaxVelocity + Enabled: true + Left: 298 + Length: 48 + Name: MaxVelocity + Text Color: 255; 255; 255 + Top: 140 + Topic: /planning/scenario_planning/current_max_velocity + Value: true + Value Scale: 0.25 + - Class: rviz_plugins/TurnSignal + Enabled: true + Height: 128 + Left: 98 + Name: TurnSignal + Top: 175 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/turn_indicators_status + Value: true + Width: 256 + Enabled: true + Name: Vehicle + Enabled: true + Name: System + - Class: rviz_common/Group + Displays: + - Alpha: 0.20000000298023224 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 28.71826171875 + Min Value: -7.4224700927734375 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 237 + Min Color: 211; 215; 207 + Min Intensity: 0 + Name: PointCloudMap + Position Transformer: XYZ + Selectable: false + Size (Pixels): 1 + Size (m): 0.019999999552965164 + Style: Points + Topic: + Depth: 5 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/pointcloud_map + Use Fixed Frame: true + Use rainbow: false + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Lanelet2VectorMap + Namespaces: + center_lane_line: false + center_line_arrows: false + crosswalk_lanelets: true + lane_start_bound: false + lanelet direction: true + lanelet_id: false + left_lane_bound: true + parking_lots: true + parking_space: true + pedestrian_marking: true + right_lane_bound: true + road_lanelets: false + stop_lines: true + traffic_light: true + traffic_light_id: false + traffic_light_triangle: true + walkway_lanelets: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/vector_map_marker + Value: true + Enabled: true + Name: Map + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.4000000059604645 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 5 + Min Value: -1 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: ConcatenatePointCloud + Position Transformer: XYZ + Selectable: false + Size (Pixels): 1 + Size (m): 0.019999999552965164 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /sensing/lidar/concatenated/pointcloud + Use Fixed Frame: false + Use rainbow: true + Value: true + - Alpha: 0.9990000128746033 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: false + Name: MeasurementRange + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/lidar/crop_box_filter/crop_box_polygon + Value: false + Enabled: true + Name: LiDAR + - Class: rviz_common/Group + Displays: + - Alpha: 0.9990000128746033 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz_default_plugins/PoseWithCovariance + Color: 233; 185; 110 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: false + Position: + Alpha: 0.20000000298023224 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.699999988079071 + Head Radius: 1.2000000476837158 + Name: PoseWithCovariance + Shaft Length: 1 + Shaft Radius: 0.5 + Shape: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/gnss/pose_with_covariance + Value: true + Enabled: false + Name: GNSS + Enabled: true + Name: Sensing + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.9990000128746033 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz_default_plugins/PoseWithCovariance + Color: 0; 170; 255 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: false + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovInitial + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/initial_pose_with_covariance + Value: false + - Alpha: 0.9990000128746033 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz_default_plugins/PoseWithCovariance + Color: 0; 255; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: false + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovAligned + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose_with_covariance + Value: false + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: false + Line: + Alpha: 0.9990000128746033 + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose + Value: false + - Alpha: 0.9990000128746033 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 0; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Initial + Position Transformer: XYZ + Selectable: false + Size (Pixels): 10 + Size (m): 0.5 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /localization/util/downsample/pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 0.9990000128746033 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 85; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 85; 255; 127 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Aligned + Position Transformer: XYZ + Selectable: false + Size (Pixels): 10 + Size (m): 0.5 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/points_aligned + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MonteCarloInitialPose + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/monte_carlo_initial_pose_marker + Value: true + Enabled: true + Name: NDT + - Class: rviz_common/Group + Displays: + - Buffer Size: 1000 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Alpha: 0.9990000128746033 + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_twist_fusion_filter/pose + Value: true + Enabled: true + Name: EKF + Enabled: true + Name: Localization + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.9990000128746033 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 15 + Min Value: -2 + Value: false + Axis: Z + Channel Name: z + Class: rviz_default_plugins/PointCloud2 + Color: 200; 200; 200 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 15 + Min Color: 0; 0; 0 + Min Intensity: -5 + Name: NoGroundPointCloud + Position Transformer: XYZ + Selectable: false + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/obstacle_segmentation/pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: Segmentation + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CAR: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.029999999329447746 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 192; 203 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Value: true + Visualization Type: Normal + Enabled: false + Name: Detection + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CAR: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.029999999329447746 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 192; 203 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Value: true + Visualization Type: Normal + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CAR: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: false + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.029999999329447746 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 192; 203 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.9990000128746033 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Value: true + Visualization Type: Normal + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Maneuver + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/prediction/maneuver + Value: false + Enabled: true + Name: Prediction + Enabled: true + Name: ObjectRecognition + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/Image + Enabled: false + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RecognitionResultOnImage + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/traffic_light_recognition/debug/rois + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MapBasedDetectionResult + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Value: true + Enabled: true + Name: TrafficLight + - Class: rviz_common/Group + Displays: + - Alpha: 0.5 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/occupancy_grid_map/map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/occupancy_grid_map/map_updates + Use Timestamp: false + Value: true + Enabled: false + Name: OccupancyGrid + Enabled: true + Name: Perception + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: Path + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/path + Value: true + View Drivable Area: + Alpha: 0.9990000128746033 + Color: 0; 148; 205 + Value: true + Width: 0.30000001192092896 + View Footprint: + Alpha: 1 + Color: 230; 230; 50 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: false + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 0.5 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 1.5 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: Input + - Class: rviz_common/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: eb fixed traj + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/eb_fixed_traj + Value: false + View Footprint: + Alpha: 1 + Color: 255; 170; 255 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: true + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: false + Width: 2 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: eb traj + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/eb_traj + Value: false + View Footprint: + Alpha: 1 + Color: 0; 255; 255 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: true + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: false + Width: 2 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: Elastic Band + - Class: rviz_common/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: mpt ref traj + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_ref_traj + Value: false + View Footprint: + Alpha: 1 + Color: 0; 255; 0 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: true + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: false + Width: 2 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: mpt fixed traj + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_fixed_traj + Value: false + View Footprint: + Alpha: 1 + Color: 255; 0; 0 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: true + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: false + Width: 2 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker + Value: false + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: mpt traj + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_traj + Value: false + View Footprint: + Alpha: 1 + Color: 255; 255; 0 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: true + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: false + Width: 2 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: Model Predictive Trajectory + - Class: rviz_common/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: true + Name: Trajectory + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory + Value: true + View Footprint: + Alpha: 1 + Color: 230; 230; 50 + Offset from BaseLink: 0 + Rear Overhang: 1.0299999713897705 + Value: false + Vehicle Length: 4.769999980926514 + Vehicle Width: 1.8300000429153442 + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 0.4000000059604645 + View Point: + Alpha: 1 + Color: 0; 60; 255 + Offset: 0 + Radius: 0.10000000149011612 + Value: false + View Text Velocity: + Scale: 0.30000001192092896 + Value: false + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: Output + Enabled: true + Name: Obstacle Avoidance Planner + Enabled: true + Global Options: + Background Color: 10; 10; 10 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/goal + - Acceleration: 0 + Class: rviz_plugins/PedestrianInitialPoseTool + Interactive: false + Max velocity: 33.29999923706055 + Min velocity: -33.29999923706055 + Pose Topic: /simulation/dummy_perception_publisher/object_info + Target Frame: + Theta std deviation: 0.0872664600610733 + Velocity: 0 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 + Z position: 1 + Z std deviation: 0.029999999329447746 + - Acceleration: 0 + Class: rviz_plugins/CarInitialPoseTool + H vehicle height: 2 + Interactive: false + L vehicle length: 4 + Max velocity: 33.29999923706055 + Min velocity: -33.29999923706055 + Pose Topic: /simulation/dummy_perception_publisher/object_info + Target Frame: + Theta std deviation: 0.0872664600610733 + Velocity: 3 + W vehicle width: 1.7999999523162842 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 + Z position: 0 + Z std deviation: 0.029999999329447746 + - Acceleration: 0 + Class: rviz_plugins/BusInitialPoseTool + H vehicle height: 3.5 + Interactive: false + L vehicle length: 10.5 + Max velocity: 33.29999923706055 + Min velocity: -33.29999923706055 + Pose Topic: /simulation/dummy_perception_publisher/object_info + Target Frame: + Theta std deviation: 0.0872664600610733 + Velocity: 0 + W vehicle width: 2.5 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 + Z position: 0 + Z std deviation: 0.029999999329447746 + - Class: rviz_plugins/MissionCheckpointTool + Pose Topic: /planning/mission_planning/checkpoint + Theta std deviation: 0.2617993950843811 + X std deviation: 0.5 + Y std deviation: 0.5 + Z position: 0 + - Class: rviz_plugins/DeleteAllObjectsTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Angle: 0 + Class: rviz_default_plugins/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 10 + Target Frame: viewer + Value: TopDownOrtho (rviz_default_plugins) + X: 0 + Y: 0 + Saved: + - Class: rviz_default_plugins/ThirdPersonFollower + Distance: 18 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: ThirdPersonFollower + Near Clip Distance: 0.009999999776482582 + Pitch: 0.20000000298023224 + Target Frame: base_link + Value: ThirdPersonFollower (rviz) + Yaw: 3.141592025756836 + - Angle: 0 + Class: rviz_default_plugins/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 10 + Target Frame: viewer + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 +Window Geometry: + AutowareDateTimePanel: + collapsed: false + AutowareStatePanel: + collapsed: false + Displays: + collapsed: false + Height: 2032 + Hide Left Dock: false + Hide Right Dock: false + InitialPoseButtonPanel: + collapsed: false + QMainWindow State: 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 + RecognitionResultOnImage: + collapsed: false + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 3692 + X: 148 + Y: 54 diff --git a/planning/obstacle_avoidance_planner/scripts/calclation_time_plotter.py b/planning/obstacle_avoidance_planner/scripts/calclation_time_plotter.py old mode 100644 new mode 100755 index 275ae69ef177c..f0d32848adefe --- a/planning/obstacle_avoidance_planner/scripts/calclation_time_plotter.py +++ b/planning/obstacle_avoidance_planner/scripts/calclation_time_plotter.py @@ -99,7 +99,12 @@ def CallbackCalculationCost(self, msg): if __name__ == "__main__": parser = argparse.ArgumentParser() - parser.add_argument("-f", "--functions", type=str, default="solveOsqp") + parser.add_argument( + "-f", + "--functions", + type=str, + default="onPath, getModelPredictiveTrajectory, getEBTrajectory", + ) args = parser.parse_args() rclpy.init() diff --git a/planning/obstacle_avoidance_planner/src/debug_marker.cpp b/planning/obstacle_avoidance_planner/src/debug_marker.cpp index c517ade57c6c4..a8af96e7b49de 100644 --- a/planning/obstacle_avoidance_planner/src/debug_marker.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_marker.cpp @@ -84,18 +84,18 @@ MarkerArray getBoundsLineMarkerArray( // create lower bound marker auto lb_marker = createDefaultMarker( "map", rclcpp::Clock().now(), "", 0, Marker::LINE_LIST, createMarkerScale(0.05, 0.0, 0.0), - createMarkerColor(0.99 + 0.5, 0.99, 0.2, 0.3)); + createMarkerColor(0.5, 0.99, 0.2, 0.8)); lb_marker.lifetime = rclcpp::Duration::from_seconds(1.5); // create upper bound marker auto ub_marker = createDefaultMarker( "map", rclcpp::Clock().now(), "", 1, Marker::LINE_LIST, createMarkerScale(0.05, 0.0, 0.0), - createMarkerColor(0.99, 0.99 + 0.5, 0.2, 0.3)); + createMarkerColor(0.99, 0.5, 0.2, 0.8)); ub_marker.lifetime = rclcpp::Duration::from_seconds(1.5); for (size_t bound_idx = 0; bound_idx < ref_points.at(0).bounds_on_constraints.size(); ++bound_idx) { - const std::string ns = "base_bounds_" + std::to_string(bound_idx); + const std::string ns = "bounds" + std::to_string(bound_idx); { // lower bound lb_marker.points.clear(); From b93dbc5c3dd5bd497555c5a12a9b2cdd679b5b56 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 15 Mar 2023 10:27:00 +0900 Subject: [PATCH 044/121] fix(tier4_perception_launch): fix config path (#3078) * fix(tier4_perception_launch): fix config path Signed-off-by: Takayuki Murooka * use pointcloud_based_occupancy_grid_map.launch.py in tier4_simulator_launch Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../laserscan_based_occupancy_grid_map.launch.py | 7 ++++++- .../launch/simulator.launch.xml | 12 ++++++++---- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py index 7ed97fe6c0ebd..516821fb3b33b 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.actions import OpaqueFunction @@ -138,7 +139,11 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output/stixel", "virtual_scan/stixel"), add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), - add_launch_arg("param_file", "config/laserscan_based_occupancy_grid_map.param.yaml"), + add_launch_arg( + "param_file", + get_package_share_directory("probabilistic_occupancy_grid_map") + + "/config/laserscan_based_occupancy_grid_map.param.yaml", + ), add_launch_arg("use_pointcloud_container", "false"), add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 70b77eb60cb12..35d8d0161fb33 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -39,11 +39,15 @@ - - - - + + + + + + + + From db23fd3bf50c14e37cfeac5968013c4eebac0810 Mon Sep 17 00:00:00 2001 From: David Wong <33114676+drwnz@users.noreply.github.com> Date: Wed, 15 Mar 2023 14:38:40 +0900 Subject: [PATCH 045/121] fix(perception): add dependencies to traffic light nodes (#3071) fix(perception): add autoware_planning_msgs dependencies to traffic light nodes --- perception/crosswalk_traffic_light_estimator/package.xml | 1 + perception/traffic_light_map_based_detector/package.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/perception/crosswalk_traffic_light_estimator/package.xml b/perception/crosswalk_traffic_light_estimator/package.xml index 3f1bdb6880bd1..d4147643eb7bd 100644 --- a/perception/crosswalk_traffic_light_estimator/package.xml +++ b/perception/crosswalk_traffic_light_estimator/package.xml @@ -14,6 +14,7 @@ autoware_auto_mapping_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_msgs lanelet2_extension rclcpp rclcpp_components diff --git a/perception/traffic_light_map_based_detector/package.xml b/perception/traffic_light_map_based_detector/package.xml index 4da85f41816e6..46220572ae9a3 100644 --- a/perception/traffic_light_map_based_detector/package.xml +++ b/perception/traffic_light_map_based_detector/package.xml @@ -14,6 +14,7 @@ autoware_auto_mapping_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_msgs geometry_msgs image_geometry lanelet2_extension From 82f1184bde14854c3362936016b0847ceb5e6718 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 15 Mar 2023 15:55:08 +0900 Subject: [PATCH 046/121] chore(tier4_simulator_launch): add code owner (#3080) chore(tier4_simulator_launch): add code owners Signed-off-by: Takayuki Murooka --- launch/tier4_simulator_launch/package.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index 7964e7c499a11..8094f95d78b15 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -5,6 +5,10 @@ 0.1.0 The tier4_simulator_launch package Keisuke Shima + Takayuki Murooka + Takamasa Horibe + Tomoya Kimura + Taiki Tanaka Apache License 2.0 ament_cmake_auto From 5ec84e3834836363463fb1f064206ca54863c136 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 15 Mar 2023 16:59:59 +0900 Subject: [PATCH 047/121] bugfix(tier4_simulator_launch): fix occupancy grid map not appearing problem in psim (#3081) * fixed psim occupancy grid map problem Signed-off-by: yoshiri * fix parameter designation Signed-off-by: Takayuki Murooka --------- Signed-off-by: yoshiri Signed-off-by: Takayuki Murooka Co-authored-by: Takayuki Murooka --- ...serscan_based_occupancy_grid_map.launch.py | 16 +++++++------ .../launch/simulator.launch.xml | 13 ++++------- ...erscan_based_occupancy_grid_map.param.yaml | 2 -- ...serscan_based_occupancy_grid_map.launch.py | 23 ++++++++++++------- 4 files changed, 29 insertions(+), 25 deletions(-) diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py index 516821fb3b33b..0a6b459d9f5f3 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py @@ -31,12 +31,6 @@ def launch_setup(context, *args, **kwargs): param_file = LaunchConfiguration("param_file").perform(context) with open(param_file, "r") as f: laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] - laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool( - LaunchConfiguration("input_obstacle_pointcloud").perform(context) - ) - laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool( - LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context) - ) composable_nodes = [ ComposableNode( @@ -86,7 +80,15 @@ def launch_setup(context, *args, **kwargs): ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], - parameters=[laserscan_based_occupancy_grid_map_node_params], + parameters=[ + laserscan_based_occupancy_grid_map_node_params, + { + "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), + "input_obstacle_and_raw_pointcloud": LaunchConfiguration( + "input_obstacle_and_raw_pointcloud" + ), + }, + ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ] diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 35d8d0161fb33..70b87921ecca5 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -39,15 +39,12 @@ - - - + + + + - - - - - + diff --git a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml index 8c8f1857ce279..3568ac7ec47a0 100644 --- a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml @@ -12,5 +12,3 @@ map_length: 100.0 map_width: 100.0 map_resolution: 0.5 - input_obstacle_pointcloud: true - input_obstacle_and_raw_pointcloud: true diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py index 7ed97fe6c0ebd..0a6b459d9f5f3 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.actions import OpaqueFunction @@ -30,12 +31,6 @@ def launch_setup(context, *args, **kwargs): param_file = LaunchConfiguration("param_file").perform(context) with open(param_file, "r") as f: laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] - laserscan_based_occupancy_grid_map_node_params["input_obstacle_pointcloud"] = bool( - LaunchConfiguration("input_obstacle_pointcloud").perform(context) - ) - laserscan_based_occupancy_grid_map_node_params["input_obstacle_and_raw_pointcloud"] = bool( - LaunchConfiguration("input_obstacle_and_raw_pointcloud").perform(context) - ) composable_nodes = [ ComposableNode( @@ -85,7 +80,15 @@ def launch_setup(context, *args, **kwargs): ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], - parameters=[laserscan_based_occupancy_grid_map_node_params], + parameters=[ + laserscan_based_occupancy_grid_map_node_params, + { + "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), + "input_obstacle_and_raw_pointcloud": LaunchConfiguration( + "input_obstacle_and_raw_pointcloud" + ), + }, + ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ] @@ -138,7 +141,11 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output/stixel", "virtual_scan/stixel"), add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), - add_launch_arg("param_file", "config/laserscan_based_occupancy_grid_map.param.yaml"), + add_launch_arg( + "param_file", + get_package_share_directory("probabilistic_occupancy_grid_map") + + "/config/laserscan_based_occupancy_grid_map.param.yaml", + ), add_launch_arg("use_pointcloud_container", "false"), add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, From f210e40ae12841b41d8c3e1a0ec84284a3beaed3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 16 Mar 2023 09:12:04 +0900 Subject: [PATCH 048/121] refactor(behavior_path_planner): change names in lane change module (#3083) * refactor(behavior_path_planner): change names in lane change module Signed-off-by: yutaka * Update planning/behavior_path_planner/src/util/lane_change/util.cpp Co-authored-by: Fumiya Watanabe * update Signed-off-by: yutaka --------- Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- .../util/lane_change/util.hpp | 16 +-- .../src/util/lane_change/util.cpp | 111 +++++++----------- 2 files changed, 51 insertions(+), 76 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp index 1efc82aca1ee8..ca5575bb63b45 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp @@ -54,11 +54,7 @@ bool isPathInLanelets( const PathWithLaneId & path, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets); -double getExpectedVelocityWhenDecelerate( - const double & current_velocity, const double & expected_acceleration, - const double & lane_change_prepare_duration); - -std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( +std::pair calcLaneChangingSpeedAndDistance( const double velocity, const double shift_length, const double deceleration, const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param, const LaneChangeParameters & lc_param); @@ -102,8 +98,8 @@ bool hasEnoughDistance( const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const Pose & goal_pose, const RouteHandler & route_handler, const double minimum_lane_change_length); -ShiftLine getLaneChangeShiftLine( - const PathWithLaneId & path1, const PathWithLaneId & path2, +ShiftLine getLaneChangingShiftLine( + const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, const lanelet::ConstLanelets & target_lanes, const PathWithLaneId & reference_path); PathWithLaneId getReferencePathFromTargetLane( @@ -112,17 +108,17 @@ PathWithLaneId getReferencePathFromTargetLane( const LaneChangePhaseInfo dist_prepare_to_lc_end, const double min_total_lane_changing_distance, const double forward_path_length, const double resample_interval, const bool is_goal_in_route); -PathWithLaneId getLaneChangePathPrepareSegment( +PathWithLaneId getPrepareSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets, const double arc_length_from_current, const double backward_path_length, const double prepare_distance, const double prepare_speed); -PathWithLaneId getLaneChangePathPrepareSegment( +PathWithLaneId getPrepareSegment( const PathWithLaneId & original_path, const lanelet::ConstLanelets & original_lanelets, const Pose & current_pose, const double backward_path_length, const double prepare_distance, const double prepare_speed); -PathWithLaneId getLaneChangePathLaneChangingSegment( +PathWithLaneId getLaneChangingSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets, const double forward_path_length, const double arc_length_from_target, const double target_lane_length, const LaneChangePhaseInfo dist_prepare_to_lc_end, diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index 550185992f1a5..ef11466682bf9 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -115,7 +115,7 @@ using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using lanelet::ArcCoordinates; using util::getHighestProbLabel; -inline double calcLaneChangeResamplingInterval( +inline double calcLaneChangeResampleInterval( const double lane_changing_distance, const double lane_changing_speed) { constexpr auto min_resampling_points{30.0}; @@ -159,20 +159,6 @@ bool isPathInLanelets( return true; } -double getExpectedVelocityWhenDecelerate( - const double & velocity, const double & expected_acceleration, const double & duration) -{ - return velocity + expected_acceleration * duration; -} - -double getDistanceWhenDecelerate( - const double & velocity, const double & expected_acceleration, const double & duration, - const double & minimum_distance) -{ - const auto distance = velocity * duration + 0.5 * expected_acceleration * std::pow(duration, 2); - return std::max(distance, minimum_distance); -} - std::optional constructCandidatePath( const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line, @@ -231,10 +217,10 @@ std::optional constructCandidatePath( const PathPointWithLaneId & lane_changing_start_point = prepare_segment.points.back(); const PathPointWithLaneId & lane_changing_end_point = lane_changing_segment.points.front(); const Pose & lane_changing_end_pose = lane_changing_end_point.point.pose; - const auto lanechange_end_idx = + const auto lane_change_end_idx = motion_utils::findNearestIndex(shifted_path.path.points, lane_changing_end_pose); - if (!lanechange_end_idx) { + if (!lane_change_end_idx) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"), "lane change end idx not found on target path."); @@ -243,7 +229,7 @@ std::optional constructCandidatePath( for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { auto & point = shifted_path.path.points.at(i); - if (i < *lanechange_end_idx) { + if (i < *lane_change_end_idx) { point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); point.point.longitudinal_velocity_mps = std::min( point.point.longitudinal_velocity_mps, @@ -257,11 +243,11 @@ std::optional constructCandidatePath( point.lane_ids = lane_changing_segment.points.at(*nearest_idx).lane_ids; } + // check candidate path is in lanelet if (!isPathInLanelets(shifted_path.path, original_lanelets, target_lanelets)) { return std::nullopt; } - // check candidate path is in lanelet candidate_path.path = combineReferencePath(prepare_segment, shifted_path.path); candidate_path.shifted_path = shifted_path; @@ -296,9 +282,8 @@ std::pair getLaneChangePaths( // rename parameter const auto backward_path_length = common_parameter.backward_path_length; const auto forward_path_length = common_parameter.forward_path_length; - const auto lane_change_prepare_duration = parameter.lane_change_prepare_duration; - const auto minimum_lane_change_prepare_distance = - common_parameter.minimum_lane_change_prepare_distance; + const auto prepare_duration = parameter.lane_change_prepare_duration; + const auto minimum_prepare_distance = common_parameter.minimum_lane_change_prepare_distance; const auto minimum_lane_change_velocity = parameter.minimum_lane_change_velocity; const auto maximum_deceleration = parameter.maximum_deceleration; const auto lane_change_sampling_num = parameter.lane_change_sampling_num; @@ -330,8 +315,7 @@ std::pair getLaneChangePaths( const auto required_total_min_distance = util::calcLaneChangeBuffer(common_parameter, num_to_preferred_lane); - [[maybe_unused]] const auto arc_position_from_current = - lanelet::utils::getArcCoordinates(original_lanelets, pose); + const auto arc_position_from_current = lanelet::utils::getArcCoordinates(original_lanelets, pose); const auto arc_position_from_target = lanelet::utils::getArcCoordinates(target_lanelets, pose); const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanelets); @@ -346,8 +330,7 @@ std::pair getLaneChangePaths( candidate_paths->reserve(lane_change_sampling_num); for (double acceleration = 0.0; acceleration >= -maximum_deceleration; acceleration -= acceleration_resolution) { - const auto prepare_speed = getExpectedVelocityWhenDecelerate( - current_velocity, acceleration, lane_change_prepare_duration); + const double prepare_speed = current_velocity + acceleration * prepare_duration; // skip if velocity becomes less than zero before starting lane change if (prepare_speed < 0.0) { @@ -355,50 +338,48 @@ std::pair getLaneChangePaths( } // get path on original lanes - const auto prepare_distance = getDistanceWhenDecelerate( - current_velocity, acceleration, lane_change_prepare_duration, - minimum_lane_change_prepare_distance); + const double prepare_distance = std::max( + current_velocity * prepare_duration + 0.5 * acceleration * std::pow(prepare_duration, 2), + minimum_prepare_distance); if (prepare_distance < target_distance) { continue; } #ifdef USE_OLD_ARCHITECTURE - const auto prepare_segment_reference = getLaneChangePathPrepareSegment( + const auto prepare_segment = getPrepareSegment( route_handler, original_lanelets, arc_position_from_current.length, backward_path_length, prepare_distance, std::max(prepare_speed, minimum_lane_change_velocity)); #else - const auto prepare_segment_reference = getLaneChangePathPrepareSegment( + const auto prepare_segment = getPrepareSegment( original_path, original_lanelets, pose, backward_path_length, prepare_distance, std::max(prepare_speed, minimum_lane_change_velocity)); #endif const auto estimated_shift_length = util::calcLateralDistanceToLanelet( - target_lanelets, prepare_segment_reference.points.front().point.pose); + target_lanelets, prepare_segment.points.front().point.pose); - const auto [lane_changing_speed, lane_changing_distance] = - calcLaneChangingSpeedAndDistanceWhenDecelerate( - prepare_speed, estimated_shift_length, acceleration, end_of_lane_dist, common_parameter, - parameter); + const auto [lane_changing_speed, lane_changing_distance] = calcLaneChangingSpeedAndDistance( + prepare_speed, estimated_shift_length, acceleration, end_of_lane_dist, common_parameter, + parameter); const auto lc_dist = LaneChangePhaseInfo{prepare_distance, lane_changing_distance}; - const auto lane_changing_segment_reference = getLaneChangePathLaneChangingSegment( + const auto lane_changing_segment = getLaneChangingSegment( route_handler, target_lanelets, forward_path_length, arc_position_from_target.length, target_lane_length, lc_dist, lane_changing_speed, required_total_min_distance); - if ( - prepare_segment_reference.points.empty() || lane_changing_segment_reference.points.empty()) { + if (prepare_segment.points.empty() || lane_changing_segment.points.empty()) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"), "reference path is empty!! something wrong..."); continue; } - const auto & lane_changing_start_pose = prepare_segment_reference.points.back().point.pose; + const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose; const auto resample_interval = - calcLaneChangeResamplingInterval(lane_changing_distance, lane_changing_speed); + calcLaneChangeResampleInterval(lane_changing_distance, lane_changing_speed); const auto target_lane_reference_path = getReferencePathFromTargetLane( route_handler, target_lanelets, lane_changing_start_pose, target_lane_length, lc_dist, @@ -408,16 +389,15 @@ std::pair getLaneChangePaths( continue; } - const auto shift_line = getLaneChangeShiftLine( - prepare_segment_reference, lane_changing_segment_reference, target_lanelets, - target_lane_reference_path); + const auto shift_line = getLaneChangingShiftLine( + prepare_segment, lane_changing_segment, target_lanelets, target_lane_reference_path); const auto lc_speed = LaneChangePhaseInfo{prepare_speed, lane_changing_speed}; const auto candidate_path = constructCandidatePath( - prepare_segment_reference, lane_changing_segment_reference, target_lane_reference_path, - shift_line, original_lanelets, target_lanelets, sorted_lane_ids, acceleration, lc_dist, - lc_speed, parameter); + prepare_segment, lane_changing_segment, target_lane_reference_path, shift_line, + original_lanelets, target_lanelets, sorted_lane_ids, acceleration, lc_dist, lc_speed, + parameter); if (!candidate_path) { continue; @@ -627,35 +607,34 @@ bool isLaneChangePathSafe( return true; } -ShiftLine getLaneChangeShiftLine( - const PathWithLaneId & path1, const PathWithLaneId & path2, +ShiftLine getLaneChangingShiftLine( + const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, const lanelet::ConstLanelets & target_lanes, const PathWithLaneId & reference_path) { - const Pose & lane_change_start_on_self_lane = path1.points.back().point.pose; - const Pose & lane_change_end_on_target_lane = path2.points.front().point.pose; - const ArcCoordinates lane_change_start_on_self_lane_arc = - lanelet::utils::getArcCoordinates(target_lanes, lane_change_start_on_self_lane); + const Pose & lane_changing_start_pose = prepare_segment.points.back().point.pose; + const Pose & lane_changing_end_pose = lane_changing_segment.points.front().point.pose; ShiftLine shift_line; - shift_line.end_shift_length = lane_change_start_on_self_lane_arc.distance; - shift_line.start = lane_change_start_on_self_lane; - shift_line.end = lane_change_end_on_target_lane; + shift_line.end_shift_length = + util::calcLateralDistanceToLanelet(target_lanes, lane_changing_start_pose); + shift_line.start = lane_changing_start_pose; + shift_line.end = lane_changing_end_pose; shift_line.start_idx = - motion_utils::findNearestIndex(reference_path.points, lane_change_start_on_self_lane.position); + motion_utils::findNearestIndex(reference_path.points, lane_changing_start_pose.position); shift_line.end_idx = - motion_utils::findNearestIndex(reference_path.points, lane_change_end_on_target_lane.position); + motion_utils::findNearestIndex(reference_path.points, lane_changing_end_pose.position); RCLCPP_DEBUG( rclcpp::get_logger("behavior_path_planner") .get_child("lane_change") .get_child("util") - .get_child("getLaneChangeShiftLine"), + .get_child("getLaneChangingShiftLine"), "shift_line distance: %f", util::getSignedDistance(shift_line.start, shift_line.end, target_lanes)); return shift_line; } -PathWithLaneId getLaneChangePathPrepareSegment( +PathWithLaneId getPrepareSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets, const double arc_length_from_current, const double backward_path_length, const double prepare_distance, const double prepare_speed) @@ -671,7 +650,7 @@ PathWithLaneId getLaneChangePathPrepareSegment( rclcpp::get_logger("behavior_path_planner") .get_child("lane_change") .get_child("util") - .get_child("getLaneChangePathPrepareSegment"), + .get_child("getPrepareSegment"), "start: %f, end: %f", s_start, s_end); PathWithLaneId prepare_segment = @@ -684,7 +663,7 @@ PathWithLaneId getLaneChangePathPrepareSegment( return prepare_segment; } -PathWithLaneId getLaneChangePathPrepareSegment( +PathWithLaneId getPrepareSegment( const PathWithLaneId & original_path, const lanelet::ConstLanelets & original_lanelets, const Pose & current_pose, const double backward_path_length, const double prepare_distance, const double prepare_speed) @@ -705,7 +684,7 @@ PathWithLaneId getLaneChangePathPrepareSegment( return prepare_segment; } -std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( +std::pair calcLaneChangingSpeedAndDistance( const double velocity, const double shift_length, const double deceleration, const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param, const LaneChangeParameters & lc_param) @@ -723,14 +702,14 @@ std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( rclcpp::get_logger("behavior_path_planner") .get_child("lane_change") .get_child("util") - .get_child("calcLaneChangingSpeedAndDistanceWhenDecelerate"), + .get_child("calcLaneChangingSpeedAndDistance"), "required_time: %f [s] average_speed: %f [m/s], lane_changing_distance : %f [m]", required_time, lane_changing_average_speed, lane_changing_distance); return {lane_changing_average_speed, lane_changing_distance}; } -PathWithLaneId getLaneChangePathLaneChangingSegment( +PathWithLaneId getLaneChangingSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets, const double forward_path_length, const double arc_length_from_target, const double target_lane_length, const LaneChangePhaseInfo dist_prepare_to_lc_end, @@ -755,7 +734,7 @@ PathWithLaneId getLaneChangePathLaneChangingSegment( rclcpp::get_logger("behavior_path_planner") .get_child("lane_change") .get_child("util") - .get_child("getLaneChangePathLaneChangingSegment"), + .get_child("getLaneChangingSegment"), "start: %f, end: %f", s_start, s_end); PathWithLaneId lane_changing_segment = From e36b079979e87cd6b74d21cc870a8a9ccecd34c3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 16 Mar 2023 13:25:29 +0900 Subject: [PATCH 049/121] fix(behavior_path_planner): fix lane changing segment s_end (#3074) --- .../util/lane_change/util.hpp | 2 +- .../src/util/lane_change/util.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp index ca5575bb63b45..679f1ae230f1c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp @@ -105,7 +105,7 @@ ShiftLine getLaneChangingShiftLine( PathWithLaneId getReferencePathFromTargetLane( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, - const LaneChangePhaseInfo dist_prepare_to_lc_end, const double min_total_lane_changing_distance, + const double lane_changing_distance, const double min_total_lane_changing_distance, const double forward_path_length, const double resample_interval, const bool is_goal_in_route); PathWithLaneId getPrepareSegment( diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index ef11466682bf9..9dcf4b11dcfdb 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -343,7 +343,7 @@ std::pair getLaneChangePaths( minimum_prepare_distance); if (prepare_distance < target_distance) { - continue; + break; } #ifdef USE_OLD_ARCHITECTURE @@ -382,8 +382,9 @@ std::pair getLaneChangePaths( calcLaneChangeResampleInterval(lane_changing_distance, lane_changing_speed); const auto target_lane_reference_path = getReferencePathFromTargetLane( - route_handler, target_lanelets, lane_changing_start_pose, target_lane_length, lc_dist, - required_total_min_distance, forward_path_length, resample_interval, is_goal_in_route); + route_handler, target_lanelets, lane_changing_start_pose, target_lane_length, + lc_dist.lane_changing, required_total_min_distance, forward_path_length, resample_interval, + is_goal_in_route); if (target_lane_reference_path.points.empty()) { continue; @@ -750,7 +751,7 @@ PathWithLaneId getLaneChangingSegment( PathWithLaneId getReferencePathFromTargetLane( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, - const LaneChangePhaseInfo dist_prepare_to_lc_end, const double min_total_lane_changing_distance, + const double lane_changing_distance, const double min_total_lane_changing_distance, const double forward_path_length, const double resample_interval, const bool is_goal_in_route) { const ArcCoordinates lane_change_start_arc_position = @@ -758,7 +759,7 @@ PathWithLaneId getReferencePathFromTargetLane( const double s_start = lane_change_start_arc_position.length; const double s_end = std::invoke([&]() { - const auto dist_from_lc_start = s_start + dist_prepare_to_lc_end.sum() + forward_path_length; + const auto dist_from_lc_start = s_start + lane_changing_distance + forward_path_length; if (is_goal_in_route) { const auto goal_arc_coordinates = lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose()); @@ -780,8 +781,7 @@ PathWithLaneId getReferencePathFromTargetLane( route_handler.getCenterLinePath(target_lanes, s_start, s_end); return util::resamplePathWithSpline( - lane_changing_reference_path, resample_interval, true, - {0.0, dist_prepare_to_lc_end.lane_changing}); + lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_distance}); } bool isEgoWithinOriginalLane( From abf46efda564ba8b06f6bf7e45304ba70808ba1c Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 16 Mar 2023 17:33:36 +0900 Subject: [PATCH 050/121] feat(behavior_path_planner): use lanelet utils for lateral calculation (#3089) feat(behavior_path_planner): use lanelet utils for lateral ccalculation Signed-off-by: yutaka --- .../include/behavior_path_planner/utilities.hpp | 3 --- .../src/util/lane_change/util.cpp | 4 ++-- planning/behavior_path_planner/src/utilities.cpp | 12 ------------ 3 files changed, 2 insertions(+), 17 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp index f374246c44b7d..c0598ed7f04d8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp @@ -534,9 +534,6 @@ double calcLaneChangeBuffer( lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); - -double calcLateralDistanceToLanelet( - const lanelet::ConstLanelets & lanelet_sequence, const geometry_msgs::msg::Pose & pose); } // namespace behavior_path_planner::util #endif // BEHAVIOR_PATH_PLANNER__UTILITIES_HPP_ diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index 9dcf4b11dcfdb..a0cef4a4d3f86 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -356,7 +356,7 @@ std::pair getLaneChangePaths( std::max(prepare_speed, minimum_lane_change_velocity)); #endif - const auto estimated_shift_length = util::calcLateralDistanceToLanelet( + const auto estimated_shift_length = lanelet::utils::getLateralDistanceToClosestLanelet( target_lanelets, prepare_segment.points.front().point.pose); const auto [lane_changing_speed, lane_changing_distance] = calcLaneChangingSpeedAndDistance( @@ -617,7 +617,7 @@ ShiftLine getLaneChangingShiftLine( ShiftLine shift_line; shift_line.end_shift_length = - util::calcLateralDistanceToLanelet(target_lanes, lane_changing_start_pose); + lanelet::utils::getLateralDistanceToClosestLanelet(target_lanes, lane_changing_start_pose); shift_line.start = lane_changing_start_pose; shift_line.end = lane_changing_end_pose; shift_line.start_idx = diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index de43052b79662..2547a0e1cd681 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -2691,16 +2691,4 @@ lanelet::ConstLanelets getLaneletsFromPath( return lanelets; } - -double calcLateralDistanceToLanelet( - const lanelet::ConstLanelets & lanelet_sequence, const geometry_msgs::msg::Pose & pose) -{ - lanelet::ConstLanelet closest_lanelet; - lanelet::utils::query::getClosestLanelet(lanelet_sequence, pose, &closest_lanelet); - const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline()); - - const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(pose.position); - return lanelet::geometry::signedDistance( - centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint()); -} } // namespace behavior_path_planner::util From 0bdc084fa5571dc8ab3e2efffd867a134a9e873b Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 16 Mar 2023 19:15:56 +0900 Subject: [PATCH 051/121] fix(pose_initializer): fix launch file (#3092) Signed-off-by: kminoda --- .../pose_initializer/launch/pose_initializer.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/localization/pose_initializer/launch/pose_initializer.launch.xml b/localization/pose_initializer/launch/pose_initializer.launch.xml index 6558b578e6386..86b20833ec4df 100644 --- a/localization/pose_initializer/launch/pose_initializer.launch.xml +++ b/localization/pose_initializer/launch/pose_initializer.launch.xml @@ -9,8 +9,8 @@ - - + + From fd090cb6f8db04e01dd391470b3afe3d6e2712fa Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 17 Mar 2023 01:06:02 +0900 Subject: [PATCH 052/121] fix(behavior_path_planner): reset modified goal id (#3095) Signed-off-by: kosuke55 --- .../src/scene_module/pull_over/pull_over_module.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp index 2efef897b203c..b2f5dfae39425 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp @@ -132,6 +132,7 @@ void PullOverModule::resetStatus() pull_over_path_candidates_.clear(); closest_start_pose_.reset(); goal_candidates_.clear(); + prev_goal_id_.reset(); } // This function is needed for waiting for planner_data_ From 2a23a4bf9c74fa321f1483bbabe566f1c6246db9 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 17 Mar 2023 01:11:09 +0900 Subject: [PATCH 053/121] feat(probabilistic_occupancy_grid_map): add pointcloud filter in gridmap generation (#3054) * add scan_frame and raytrace center Signed-off-by: yoshiri * add scan frame to laserscan based method Signed-off-by: yoshiri * update readme Signed-off-by: yoshiri * fix typo Signed-off-by: yoshiri * update laucher in perception_launch Signed-off-by: yoshiri * fix config and launch file Signed-off-by: yoshiri * fixed laserscan based launcher Signed-off-by: yoshiri * add filter func to extract obstacle pc in sensor Signed-off-by: yoshiri * refactor: wrap common function to utils Signed-off-by: yoshiri * style(pre-commit): autofix * Apply suggestions from code review fixed copyright name Co-authored-by: Yukihiro Saito --------- Signed-off-by: yoshiri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yukihiro Saito --- .../CMakeLists.txt | 2 + ...tcloud_based_occupancy_grid_map.param.yaml | 2 + ...intcloud_based_occupancy_grid_map_node.hpp | 1 + .../include/utils/utils.hpp | 120 ++++++++++++ ...aserscan_based_occupancy_grid_map_node.cpp | 88 +-------- .../occupancy_grid_map.cpp | 52 +----- ...intcloud_based_occupancy_grid_map_node.cpp | 101 +++------- .../src/utils/utils.cpp | 175 ++++++++++++++++++ 8 files changed, 339 insertions(+), 202 deletions(-) create mode 100644 perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp diff --git a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt index df0090d1b6cee..777dda051b787 100644 --- a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt @@ -18,6 +18,7 @@ ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp + src/utils/utils.cpp ) target_link_libraries(pointcloud_based_occupancy_grid_map @@ -34,6 +35,7 @@ ament_auto_add_library(laserscan_based_occupancy_grid_map SHARED src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp + src/utils/utils.cpp ) target_link_libraries(laserscan_based_occupancy_grid_map diff --git a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 49a1a7097d308..7a1a1b13ee335 100644 --- a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -5,6 +5,8 @@ use_height_filter: true enable_single_frame_mode: false + # use sensor pointcloud to filter obstacle pointcloud + filter_obstacle_pointcloud_by_raw_pointcloud: false # grid map coordinate map_frame: "map" diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index 5b7571fa8abcc..dc1b268123fcc 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -86,6 +86,7 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node std::string scan_origin_frame_; bool use_height_filter_; bool enable_single_frame_mode_; + bool filter_obstacle_pointcloud_by_raw_pointcloud_; }; } // namespace occupancy_grid_map diff --git a/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp b/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp new file mode 100644 index 0000000000000..4af7ef950272d --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp @@ -0,0 +1,120 @@ +// 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 +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include + +#include +#endif + +#include +#include +#include + +namespace utils +{ + +/** + * @brief 3D point struct for sorting and searching + * + */ +struct MyPoint3d +{ + float x; + float y; + float z; + + // constructor + MyPoint3d(float x, float y, float z) : x(x), y(y), z(z) {} + + // calc squared norm + float norm2() const { return powf(x, 2) + powf(y, 2) + powf(z, 2); } + + // calc arctan2 + float arctan2() const { return atan2f(y, x); } + + // overload operator< + bool operator<(const MyPoint3d & other) const + { + const auto a = norm2(); + const auto b = other.norm2(); + if (a == b) { // escape when norm2 is same + return arctan2() < other.arctan2(); + } else { + return a < b; + } + } + + // overload operator== + bool operator==(const MyPoint3d & other) const + { + return fabsf(x - other.x) < FLT_EPSILON && fabsf(y - other.y) < FLT_EPSILON && + fabsf(z - other.z) < FLT_EPSILON; + } +}; + +bool transformPointcloud( + const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, + const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output); + +void transformPointcloud( + const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, + sensor_msgs::msg::PointCloud2 & output); + +bool cropPointcloudByHeight( + const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, + const std::string & target_frame, const float min_height, const float max_height, + sensor_msgs::msg::PointCloud2 & output); + +// get pose from tf2 +geometry_msgs::msg::Pose getPose( + const std_msgs::msg::Header & source_header, const tf2_ros::Buffer & tf2, + const std::string & target_frame); + +geometry_msgs::msg::Pose getPose( + const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, + const std::string & source_frame, const std::string & target_frame); + +// get inverted pose +geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose); + +bool extractCommonPointCloud( + const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc, + sensor_msgs::msg::PointCloud2 & output_obstacle_pc); + +} // namespace utils + +#endif // UTILS__UTILS_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp index 2ded71a0ec0b4..248e436bd1732 100644 --- a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp @@ -15,6 +15,7 @@ #include "laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp" #include "cost_value.hpp" +#include "utils/utils.hpp" #include #include @@ -35,78 +36,6 @@ #include #include -namespace -{ -bool transformPointcloud( - const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, - const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output) -{ - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2.lookupTransform( - target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); - // transform pointcloud - Eigen::Matrix4f tf_matrix = tf2::transformToEigen(tf_stamped.transform).matrix().cast(); - pcl_ros::transformPointCloud(tf_matrix, input, output); - output.header.stamp = input.header.stamp; - output.header.frame_id = target_frame; - return true; -} - -bool cropPointcloudByHeight( - const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, - const std::string & target_frame, const float min_height, const float max_height, - sensor_msgs::msg::PointCloud2 & output) -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - // Transformed pointcloud on target frame - sensor_msgs::msg::PointCloud2 trans_input_tmp; - const bool is_target_frame = (input.header.frame_id == target_frame); - if (!is_target_frame) { - if (!transformPointcloud(input, tf2, target_frame, trans_input_tmp)) return false; - } - const sensor_msgs::msg::PointCloud2 & trans_input = is_target_frame ? input : trans_input_tmp; - - // Apply height filter - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - for (sensor_msgs::PointCloud2ConstIterator iter_x(trans_input, "x"), - iter_y(trans_input, "y"), iter_z(trans_input, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - if (min_height < *iter_z && *iter_z < max_height) { - pcl_output->push_back(pcl::PointXYZ(*iter_x, *iter_y, *iter_z)); - } - } - - // Convert to ros msg - pcl::toROSMsg(*pcl_output, output); - output.header = trans_input.header; - return true; -} - -[[maybe_unused]] geometry_msgs::msg::Pose getPose( - const std_msgs::msg::Header & source_header, const tf2_ros::Buffer & tf2, - const std::string & target_frame) -{ - geometry_msgs::msg::Pose pose; - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2.lookupTransform( - target_frame, source_header.frame_id, source_header.stamp, rclcpp::Duration::from_seconds(0.5)); - pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); - return pose; -} - -geometry_msgs::msg::Pose getPose( - const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, - const std::string & source_frame, const std::string & target_frame) -{ - geometry_msgs::msg::Pose pose; - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = - tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); - pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); - return pose; -} -} // namespace - namespace occupancy_grid_map { using costmap_2d::OccupancyGridMap; @@ -204,12 +133,12 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa PointCloud2 cropped_raw_pc{}; if (use_height_filter_) { constexpr float min_height = -1.0, max_height = 2.0; - if (!cropPointcloudByHeight( + if (!utils::cropPointcloudByHeight( *input_obstacle_msg, *tf2_, base_link_frame_, min_height, max_height, cropped_obstacle_pc)) { return; } - if (!cropPointcloudByHeight( + if (!utils::cropPointcloudByHeight( *input_raw_msg, *tf2_, base_link_frame_, min_height, max_height, cropped_raw_pc)) { return; } @@ -225,12 +154,13 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa Pose gridmap_origin{}; Pose scan_origin{}; try { - transformPointcloud(*laserscan_pc_ptr, *tf2_, map_frame_, trans_laserscan_pc); - transformPointcloud(filtered_obstacle_pc, *tf2_, map_frame_, trans_obstacle_pc); - transformPointcloud(filtered_raw_pc, *tf2_, map_frame_, trans_raw_pc); + utils::transformPointcloud(*laserscan_pc_ptr, *tf2_, map_frame_, trans_laserscan_pc); + utils::transformPointcloud(filtered_obstacle_pc, *tf2_, map_frame_, trans_obstacle_pc); + utils::transformPointcloud(filtered_raw_pc, *tf2_, map_frame_, trans_raw_pc); gridmap_origin = - getPose(laserscan_pc_ptr->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); - scan_origin = getPose(laserscan_pc_ptr->header.stamp, *tf2_, scan_origin_frame_, map_frame_); + utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + scan_origin = + utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, scan_origin_frame_, map_frame_); } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(get_logger(), ex.what()); return; diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp index b6b69ebf44391..b26e9a14a2b5e 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp @@ -52,6 +52,7 @@ #include "pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp" #include "cost_value.hpp" +#include "utils/utils.hpp" #include #include @@ -68,45 +69,6 @@ #endif #include -namespace -{ -void transformPointcloud( - const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, - sensor_msgs::msg::PointCloud2 & output) -{ - const auto transform = tier4_autoware_utils::pose2transform(pose); - Eigen::Matrix4f tf_matrix = tf2::transformToEigen(transform).matrix().cast(); - - pcl_ros::transformPointCloud(tf_matrix, input, output); - output.header.stamp = input.header.stamp; - output.header.frame_id = ""; -} - -/** - * @brief Get the Inverse Pose object - * - * @param input - * @return geometry_msgs::msg::Pose inverted pose - */ -geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose) -{ - tf2::Vector3 position(pose.position.x, pose.position.y, pose.position.z); - tf2::Quaternion orientation( - pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); - tf2::Transform tf(orientation, position); - const auto inv_tf = tf.inverse(); - geometry_msgs::msg::Pose inv_pose; - inv_pose.position.x = inv_tf.getOrigin().x(); - inv_pose.position.y = inv_tf.getOrigin().y(); - inv_pose.position.z = inv_tf.getOrigin().z(); - inv_pose.orientation.x = inv_tf.getRotation().x(); - inv_pose.orientation.y = inv_tf.getRotation().y(); - inv_pose.orientation.z = inv_tf.getRotation().z(); - inv_pose.orientation.w = inv_tf.getRotation().w(); - return inv_pose; -} -} // namespace - namespace costmap_2d { using sensor_msgs::PointCloud2ConstIterator; @@ -203,14 +165,14 @@ void OccupancyGridMap::updateWithPointCloud( // Transform from base_link to map frame PointCloud2 map_raw_pointcloud, map_obstacle_pointcloud; // point cloud in map frame - transformPointcloud(raw_pointcloud, robot_pose, map_raw_pointcloud); - transformPointcloud(obstacle_pointcloud, robot_pose, map_obstacle_pointcloud); + utils::transformPointcloud(raw_pointcloud, robot_pose, map_raw_pointcloud); + utils::transformPointcloud(obstacle_pointcloud, robot_pose, map_obstacle_pointcloud); // Transform from map frame to scan frame - PointCloud2 scan_raw_pointcloud, scan_obstacle_pointcloud; // point cloud in scan frame - const auto scan2map_pose = getInversePose(scan_origin); // scan -> map transform pose - transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); - transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); + PointCloud2 scan_raw_pointcloud, scan_obstacle_pointcloud; // point cloud in scan frame + const auto scan2map_pose = utils::getInversePose(scan_origin); // scan -> map transform pose + utils::transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); + utils::transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); // Create angle bins struct BinInfo diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index c594a0be0703f..bdf726ca8ccc6 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -15,6 +15,7 @@ #include "pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp" #include "cost_value.hpp" +#include "utils/utils.hpp" #include #include @@ -32,81 +33,10 @@ #include #endif +#include #include #include -namespace -{ -bool transformPointcloud( - const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, - const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output) -{ - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2.lookupTransform( - target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); - // transform pointcloud - Eigen::Matrix4f tf_matrix = tf2::transformToEigen(tf_stamped.transform).matrix().cast(); - pcl_ros::transformPointCloud(tf_matrix, input, output); - output.header.stamp = input.header.stamp; - output.header.frame_id = target_frame; - return true; -} - -bool cropPointcloudByHeight( - const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, - const std::string & target_frame, const float min_height, const float max_height, - sensor_msgs::msg::PointCloud2 & output) -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - // Transformed pointcloud on target frame - sensor_msgs::msg::PointCloud2 trans_input_tmp; - const bool is_target_frame = (input.header.frame_id == target_frame); - if (!is_target_frame) { - if (!transformPointcloud(input, tf2, target_frame, trans_input_tmp)) return false; - } - const sensor_msgs::msg::PointCloud2 & trans_input = is_target_frame ? input : trans_input_tmp; - - // Apply height filter - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - for (sensor_msgs::PointCloud2ConstIterator iter_x(trans_input, "x"), - iter_y(trans_input, "y"), iter_z(trans_input, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - if (min_height < *iter_z && *iter_z < max_height) { - pcl_output->push_back(pcl::PointXYZ(*iter_x, *iter_y, *iter_z)); - } - } - - // Convert to ros msg - pcl::toROSMsg(*pcl_output, output); - output.header = trans_input.header; - return true; -} - -geometry_msgs::msg::Pose getPose( - const std_msgs::msg::Header & source_header, const tf2_ros::Buffer & tf2, - const std::string & target_frame) -{ - geometry_msgs::msg::Pose pose; - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = tf2.lookupTransform( - target_frame, source_header.frame_id, source_header.stamp, rclcpp::Duration::from_seconds(0.5)); - pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); - return pose; -} - -geometry_msgs::msg::Pose getPose( - const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, - const std::string & source_frame, const std::string & target_frame) -{ - geometry_msgs::msg::Pose pose; - geometry_msgs::msg::TransformStamped tf_stamped; - tf_stamped = - tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); - pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); - return pose; -} -} // namespace - namespace occupancy_grid_map { using costmap_2d::OccupancyGridMap; @@ -127,6 +57,8 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( scan_origin_frame_ = declare_parameter("scan_origin_frame", "base_link"); use_height_filter_ = declare_parameter("use_height_filter", true); enable_single_frame_mode_ = declare_parameter("enable_single_frame_mode", false); + filter_obstacle_pointcloud_by_raw_pointcloud_ = + declare_parameter("filter_obstacle_pointcloud_by_raw_pointcloud", false); const double map_length{declare_parameter("map_length", 100.0)}; const double map_resolution{declare_parameter("map_resolution", 0.5)}; @@ -170,12 +102,12 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( PointCloud2 cropped_raw_pc{}; if (use_height_filter_) { constexpr float min_height = -1.0, max_height = 2.0; - if (!cropPointcloudByHeight( + if (!utils::cropPointcloudByHeight( *input_obstacle_msg, *tf2_, base_link_frame_, min_height, max_height, cropped_obstacle_pc)) { return; } - if (!cropPointcloudByHeight( + if (!utils::cropPointcloudByHeight( *input_raw_msg, *tf2_, base_link_frame_, min_height, max_height, cropped_raw_pc)) { return; } @@ -184,14 +116,27 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( use_height_filter_ ? cropped_obstacle_pc : *input_obstacle_msg; const PointCloud2 & filtered_raw_pc = use_height_filter_ ? cropped_raw_pc : *input_raw_msg; + // Filter obstacle pointcloud by raw pointcloud + PointCloud2 filtered_obstacle_pc_common{}; + if (filter_obstacle_pointcloud_by_raw_pointcloud_) { + if (!utils::extractCommonPointCloud( + filtered_obstacle_pc, filtered_raw_pc, filtered_obstacle_pc_common)) { + filtered_obstacle_pc_common = filtered_obstacle_pc; + } + } else { + filtered_obstacle_pc_common = filtered_obstacle_pc; + } + // Get from map to sensor frame pose Pose robot_pose{}; Pose gridmap_origin{}; Pose scan_origin{}; try { - robot_pose = getPose(input_raw_msg->header, *tf2_, map_frame_); - gridmap_origin = getPose(input_raw_msg->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); - scan_origin = getPose(input_raw_msg->header.stamp, *tf2_, scan_origin_frame_, map_frame_); + robot_pose = utils::getPose(input_raw_msg->header, *tf2_, map_frame_); + gridmap_origin = + utils::getPose(input_raw_msg->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + scan_origin = + utils::getPose(input_raw_msg->header.stamp, *tf2_, scan_origin_frame_, map_frame_); } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(get_logger(), ex.what()); return; @@ -206,7 +151,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); single_frame_occupancy_grid_map.updateWithPointCloud( - filtered_raw_pc, filtered_obstacle_pc, robot_pose, scan_origin); + filtered_raw_pc, filtered_obstacle_pc_common, robot_pose, scan_origin); if (enable_single_frame_mode_) { // publish diff --git a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp new file mode 100644 index 0000000000000..741d333142c9d --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp @@ -0,0 +1,175 @@ +// 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 +{ + +// used in laserscan based occupancy grid map +bool transformPointcloud( + const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, + const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output) +{ + geometry_msgs::msg::TransformStamped tf_stamped; + tf_stamped = tf2.lookupTransform( + target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); + // transform pointcloud + Eigen::Matrix4f tf_matrix = tf2::transformToEigen(tf_stamped.transform).matrix().cast(); + pcl_ros::transformPointCloud(tf_matrix, input, output); + output.header.stamp = input.header.stamp; + output.header.frame_id = target_frame; + return true; +} + +// used in pointcloud based occupancy grid map +void transformPointcloud( + const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, + sensor_msgs::msg::PointCloud2 & output) +{ + const auto transform = tier4_autoware_utils::pose2transform(pose); + Eigen::Matrix4f tf_matrix = tf2::transformToEigen(transform).matrix().cast(); + + pcl_ros::transformPointCloud(tf_matrix, input, output); + output.header.stamp = input.header.stamp; + output.header.frame_id = ""; +} + +bool cropPointcloudByHeight( + const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, + const std::string & target_frame, const float min_height, const float max_height, + sensor_msgs::msg::PointCloud2 & output) +{ + rclcpp::Clock clock{RCL_ROS_TIME}; + // Transformed pointcloud on target frame + sensor_msgs::msg::PointCloud2 trans_input_tmp; + const bool is_target_frame = (input.header.frame_id == target_frame); + if (!is_target_frame) { + if (!transformPointcloud(input, tf2, target_frame, trans_input_tmp)) return false; + } + const sensor_msgs::msg::PointCloud2 & trans_input = is_target_frame ? input : trans_input_tmp; + + // Apply height filter + pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); + for (sensor_msgs::PointCloud2ConstIterator iter_x(trans_input, "x"), + iter_y(trans_input, "y"), iter_z(trans_input, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (min_height < *iter_z && *iter_z < max_height) { + pcl_output->push_back(pcl::PointXYZ(*iter_x, *iter_y, *iter_z)); + } + } + + // Convert to ros msg + pcl::toROSMsg(*pcl_output, output); + output.header = trans_input.header; + return true; +} + +geometry_msgs::msg::Pose getPose( + const std_msgs::msg::Header & source_header, const tf2_ros::Buffer & tf2, + const std::string & target_frame) +{ + geometry_msgs::msg::Pose pose; + geometry_msgs::msg::TransformStamped tf_stamped; + tf_stamped = tf2.lookupTransform( + target_frame, source_header.frame_id, source_header.stamp, rclcpp::Duration::from_seconds(0.5)); + pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); + return pose; +} + +geometry_msgs::msg::Pose getPose( + const builtin_interfaces::msg::Time & stamp, const tf2_ros::Buffer & tf2, + const std::string & source_frame, const std::string & target_frame) +{ + geometry_msgs::msg::Pose pose; + geometry_msgs::msg::TransformStamped tf_stamped; + tf_stamped = + tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); + pose = tier4_autoware_utils::transform2pose(tf_stamped.transform); + return pose; +} + +/** + * @brief Get the Inverse Pose object + * + * @param input + * @return geometry_msgs::msg::Pose inverted pose + */ +geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose) +{ + tf2::Vector3 position(pose.position.x, pose.position.y, pose.position.z); + tf2::Quaternion orientation( + pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); + tf2::Transform tf(orientation, position); + const auto inv_tf = tf.inverse(); + geometry_msgs::msg::Pose inv_pose; + inv_pose.position.x = inv_tf.getOrigin().x(); + inv_pose.position.y = inv_tf.getOrigin().y(); + inv_pose.position.z = inv_tf.getOrigin().z(); + inv_pose.orientation.x = inv_tf.getRotation().x(); + inv_pose.orientation.y = inv_tf.getRotation().y(); + inv_pose.orientation.z = inv_tf.getRotation().z(); + inv_pose.orientation.w = inv_tf.getRotation().w(); + return inv_pose; +} + +/** + * @brief extract Common Pointcloud between obstacle pc and raw pc + * @param obstacle_pc + * @param raw_pc + * @param output_obstacle_pc + */ +bool extractCommonPointCloud( + const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc, + sensor_msgs::msg::PointCloud2 & output_obstacle_pc) +{ + // Convert to vector of 3d points + std::vector v_obstacle_pc, v_raw_pc, v_output_obstacle_pc; + for (sensor_msgs::PointCloud2ConstIterator iter_x(obstacle_pc, "x"), + iter_y(obstacle_pc, "y"), iter_z(obstacle_pc, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + v_obstacle_pc.push_back(MyPoint3d(*iter_x, *iter_y, *iter_z)); + } + for (sensor_msgs::PointCloud2ConstIterator iter_x(raw_pc, "x"), iter_y(raw_pc, "y"), + iter_z(raw_pc, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + v_raw_pc.push_back(MyPoint3d(*iter_x, *iter_y, *iter_z)); + } + + // sort pointclouds for searching cross points: O(nlogn) + std::sort(v_obstacle_pc.begin(), v_obstacle_pc.end(), [](auto a, auto b) { return a < b; }); + std::sort(v_raw_pc.begin(), v_raw_pc.end(), [](auto a, auto b) { return a < b; }); + + // calc intersection points of two pointclouds: O(n) + std::set_intersection( + v_obstacle_pc.begin(), v_obstacle_pc.end(), v_raw_pc.begin(), v_raw_pc.end(), + std::back_inserter(v_output_obstacle_pc)); + if (v_output_obstacle_pc.size() == 0) { + return false; + } + + // Convert to ros msg + pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); + for (auto p : v_output_obstacle_pc) { + pcl_output->push_back(pcl::PointXYZ(p.x, p.y, p.z)); + } + pcl::toROSMsg(*pcl_output, output_obstacle_pc); + output_obstacle_pc.header = obstacle_pc.header; + + return true; +} + +} // namespace utils From c1b024e4772ba19304ff7fe944ff59d8f0b62692 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Fri, 17 Mar 2023 10:02:59 +0900 Subject: [PATCH 054/121] fix(lidar_centerpoint): updated the config file for the centerpoint tiny v2 (#3096) Fixed the cfg file regarding centerpoint tiny Signed-off-by: Kenzo Lobos-Tsunekawa --- .../lidar_centerpoint/config/centerpoint_tiny.param.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml index b7c2faf89c0b6..92db4cd0b853e 100644 --- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -1,10 +1,10 @@ /**: ros__parameters: - class_names: ["CAR", "PEDESTRIAN", "BICYCLE"] + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] point_feature_size: 4 max_voxel_size: 40000 - point_cloud_range: [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0] - voxel_size: [0.32, 0.32, 8.0] + point_cloud_range: [-76.8, -76.8, -2.0, 76.8, 76.8, 4.0] + voxel_size: [0.32, 0.32, 6.0] downsample_factor: 2 encoder_in_feature_size: 9 # post-process params @@ -12,4 +12,4 @@ iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 - yaw_norm_thresholds: [0.3, 0.0, 0.3] + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] From b2524e4f38a2e46b3b9f4a63d1d13e71331f28e7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 Mar 2023 10:43:49 +0900 Subject: [PATCH 055/121] fix(lane_change): fix build error (#3100) fix(lane_change): fix build error: Signed-off-by: satoshi-ota --- planning/behavior_path_planner/src/util/lane_change/util.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index a0cef4a4d3f86..fd9c31f3a617e 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -315,7 +315,8 @@ std::pair getLaneChangePaths( const auto required_total_min_distance = util::calcLaneChangeBuffer(common_parameter, num_to_preferred_lane); - const auto arc_position_from_current = lanelet::utils::getArcCoordinates(original_lanelets, pose); + [[maybe_unused]] const auto arc_position_from_current = + lanelet::utils::getArcCoordinates(original_lanelets, pose); const auto arc_position_from_target = lanelet::utils::getArcCoordinates(target_lanelets, pose); const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanelets); From 948a1d53a01f9e2c4ae3f64e6710618ee6b2d22c Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 17 Mar 2023 11:08:49 +0900 Subject: [PATCH 056/121] feat(control): add autonomous emergency braking module (#2793) --- .../CMakeLists.txt | 26 + .../autonomous_emergency_braking.param.yaml | 16 + .../autonomous_emergency_braking/node.hpp | 150 ++++++ .../autonomous_emergency_braking.launch.xml | 19 + .../autonomous_emergency_braking/package.xml | 42 ++ .../autonomous_emergency_braking/src/node.cpp | 495 ++++++++++++++++++ .../launch/control.launch.py | 32 ++ .../diagnostic_aggregator/control.param.yaml | 14 + .../config/system_error_monitor.param.yaml | 2 + ...ror_monitor.planning_simulation.param.yaml | 2 + 10 files changed, 798 insertions(+) create mode 100644 control/autonomous_emergency_braking/CMakeLists.txt create mode 100644 control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml create mode 100644 control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp create mode 100644 control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml create mode 100644 control/autonomous_emergency_braking/package.xml create mode 100644 control/autonomous_emergency_braking/src/node.cpp diff --git a/control/autonomous_emergency_braking/CMakeLists.txt b/control/autonomous_emergency_braking/CMakeLists.txt new file mode 100644 index 0000000000000..6027aeac76333 --- /dev/null +++ b/control/autonomous_emergency_braking/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(autonomous_emergency_braking) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +set(AEB_NODE ${PROJECT_NAME}_node) +ament_auto_add_library(${AEB_NODE} SHARED + src/node.cpp +) + +rclcpp_components_register_node(${AEB_NODE} + PLUGIN "autoware::motion::control::autonomous_emergency_braking::AEB" + EXECUTABLE ${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml new file mode 100644 index 0000000000000..6019eaae503a0 --- /dev/null +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + use_predicted_trajectory: true + use_imu_path: true + voxel_grid_x: 0.05 + voxel_grid_y: 0.05 + voxel_grid_z: 100000.0 + min_generated_path_length: 0.5 + expand_width: 0.1 + longitudinal_offset: 2.0 + t_response: 1.0 + a_ego_min: -3.0 + a_obj_min: -1.0 + prediction_time_horizon: 1.5 + prediction_time_interval: 0.1 + aeb_hz: 10.0 diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp new file mode 100644 index 0000000000000..64a3079df106a --- /dev/null +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -0,0 +1,150 @@ +// 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 AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#define AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace autoware::motion::control::autonomous_emergency_braking +{ + +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_system_msgs::msg::AutowareState; +using autoware_auto_vehicle_msgs::msg::VelocityReport; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::Imu; +using sensor_msgs::msg::PointCloud2; +using PointCloud = pcl::PointCloud; +using diagnostic_updater::DiagnosticStatusWrapper; +using diagnostic_updater::Updater; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; +using vehicle_info_util::VehicleInfo; +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; +using Path = std::vector; + +struct ObjectData +{ + geometry_msgs::msg::Point position; + double velocity; +}; + +class AEB : public rclcpp::Node +{ +public: + explicit AEB(const rclcpp::NodeOptions & node_options); + + // subscriber + rclcpp::Subscription::SharedPtr sub_point_cloud_; + rclcpp::Subscription::SharedPtr sub_velocity_; + rclcpp::Subscription::SharedPtr sub_imu_; + rclcpp::Subscription::SharedPtr sub_predicted_traj_; + rclcpp::Subscription::SharedPtr sub_autoware_state_; + + // publisher + rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_; + rclcpp::Publisher::SharedPtr debug_ego_path_publisher_; // debug + + // timer + rclcpp::TimerBase::SharedPtr timer_; + + // callback + void onPointCloud(const PointCloud2::ConstSharedPtr input_msg); + void onVelocity(const VelocityReport::ConstSharedPtr input_msg); + void onImu(const Imu::ConstSharedPtr input_msg); + void onTimer(); + void onPredictedTrajectory(const Trajectory::ConstSharedPtr input_msg); + void onAutowareState(const AutowareState::ConstSharedPtr input_msg); + + bool isDataReady(); + + // main function + void onCheckCollision(DiagnosticStatusWrapper & stat); + bool checkCollision(); + bool hasCollision( + const double current_v, const Path & ego_path, const std::vector & ego_polys); + + void generateEgoPath( + const double curr_v, const double curr_w, Path & path, std::vector & polygons); + void generateEgoPath( + const Trajectory & predicted_traj, Path & path, std::vector & polygons); + void createObjectData( + const Path & ego_path, const std::vector & ego_polys, + std::vector & objects); + + void addMarker( + const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & path_ns, const std::string & poly_ns, MarkerArray & debug_markers); + + PointCloud2::SharedPtr obstacle_ros_pointcloud_ptr_{nullptr}; + VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr}; + Imu::ConstSharedPtr imu_ptr_{nullptr}; + Trajectory::ConstSharedPtr predicted_traj_ptr_{nullptr}; + AutowareState::ConstSharedPtr autoware_state_{nullptr}; + + tf2_ros::Buffer tf_buffer_{get_clock()}; + tf2_ros::TransformListener tf_listener_{tf_buffer_}; + + // vehicle info + VehicleInfo vehicle_info_; + + // diag + Updater updater_{this}; + + // member variables + bool use_predicted_trajectory_; + bool use_imu_path_; + double voxel_grid_x_; + double voxel_grid_y_; + double voxel_grid_z_; + double min_generated_path_length_; + double expand_width_; + double longitudinal_offset_; + double t_response_; + double a_ego_min_; + double a_obj_min_; + double prediction_time_horizon_; + double prediction_time_interval_; +}; +} // namespace autoware::motion::control::autonomous_emergency_braking + +#endif // AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ diff --git a/control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml b/control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml new file mode 100644 index 0000000000000..cf6640ec6be52 --- /dev/null +++ b/control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/control/autonomous_emergency_braking/package.xml b/control/autonomous_emergency_braking/package.xml new file mode 100644 index 0000000000000..198afb1018e31 --- /dev/null +++ b/control/autonomous_emergency_braking/package.xml @@ -0,0 +1,42 @@ + + + + autonomous_emergency_braking + 0.1.0 + Autonomous Emergency Braking package as a ROS2 node + yutaka + Apache License 2.0 + + ament_cmake + + autoware_cmake + + autoware_auto_control_msgs + autoware_auto_system_msgs + autoware_auto_vehicle_msgs + diagnostic_updater + geometry_msgs + motion_utils + nav_msgs + pcl_conversions + pcl_ros + pointcloud_preprocessor + rclcpp + rclcpp_components + sensor_msgs + std_msgs + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + vehicle_info_util + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp new file mode 100644 index 0000000000000..77ea7e6318820 --- /dev/null +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -0,0 +1,495 @@ +// 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 "autonomous_emergency_braking/node.hpp" + +#include +#include + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include + +#include +#endif + +namespace autoware::motion::control::autonomous_emergency_braking +{ +using diagnostic_msgs::msg::DiagnosticStatus; +namespace bg = boost::geometry; + +void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) +{ + Point2d point; + point.x() = geom_point.x; + point.y() = geom_point.y; + + bg::append(polygon.outer(), point); +} + +Polygon2d createPolygon( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) +{ + Polygon2d polygon; + + const double longitudinal_offset = vehicle_info.max_longitudinal_offset_m; + const double width = vehicle_info.vehicle_width_m / 2.0 + expand_width; + const double rear_overhang = vehicle_info.rear_overhang_m; + + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_pose, longitudinal_offset, width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_pose, longitudinal_offset, -width, 0.0).position); + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(base_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(base_pose, -rear_overhang, width, 0.0).position); + + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_pose, longitudinal_offset, width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_pose, longitudinal_offset, -width, 0.0).position); + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(next_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(next_pose, -rear_overhang, width, 0.0).position); + + polygon = tier4_autoware_utils::isClockwise(polygon) + ? polygon + : tier4_autoware_utils::inverseClockwise(polygon); + + Polygon2d hull_polygon; + bg::convex_hull(polygon, hull_polygon); + + return hull_polygon; +} + +AEB::AEB(const rclcpp::NodeOptions & node_options) +: Node("AEB", node_options), + vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) +{ + // Subscribers + sub_point_cloud_ = this->create_subscription( + "~/input/pointcloud", rclcpp::SensorDataQoS(), + std::bind(&AEB::onPointCloud, this, std::placeholders::_1)); + + sub_velocity_ = this->create_subscription( + "~/input/velocity", rclcpp::QoS{1}, std::bind(&AEB::onVelocity, this, std::placeholders::_1)); + + sub_imu_ = this->create_subscription( + "~/input/imu", rclcpp::QoS{1}, std::bind(&AEB::onImu, this, std::placeholders::_1)); + + sub_predicted_traj_ = this->create_subscription( + "~/input/predicted_trajectory", rclcpp::QoS{1}, + std::bind(&AEB::onPredictedTrajectory, this, std::placeholders::_1)); + + sub_autoware_state_ = this->create_subscription( + "/autoware/state", rclcpp::QoS{1}, + std::bind(&AEB::onAutowareState, this, std::placeholders::_1)); + + // Publisher + pub_obstacle_pointcloud_ = + this->create_publisher("~/debug/obstacle_pointcloud", 1); + debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1); + + // Diagnostics + updater_.setHardwareID("autonomous_emergency_braking"); + updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); + + // parameter + use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); + use_imu_path_ = declare_parameter("use_imu_path"); + voxel_grid_x_ = declare_parameter("voxel_grid_x"); + voxel_grid_y_ = declare_parameter("voxel_grid_y"); + voxel_grid_z_ = declare_parameter("voxel_grid_z"); + min_generated_path_length_ = declare_parameter("min_generated_path_length"); + expand_width_ = declare_parameter("expand_width"); + longitudinal_offset_ = declare_parameter("longitudinal_offset"); + t_response_ = declare_parameter("t_response"); + a_ego_min_ = declare_parameter("a_ego_min"); + a_obj_min_ = declare_parameter("a_obj_min"); + prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); + prediction_time_interval_ = declare_parameter("prediction_time_interval"); + + // start time + const double aeb_hz = declare_parameter("aeb_hz"); + const auto period_ns = rclcpp::Rate(aeb_hz).period(); + timer_ = rclcpp::create_timer(this, get_clock(), period_ns, std::bind(&AEB::onTimer, this)); +} + +void AEB::onTimer() { updater_.force_update(); } + +void AEB::onVelocity(const VelocityReport::ConstSharedPtr input_msg) +{ + current_velocity_ptr_ = input_msg; +} + +void AEB::onImu(const Imu::ConstSharedPtr input_msg) { imu_ptr_ = input_msg; } + +void AEB::onPredictedTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg) +{ + predicted_traj_ptr_ = input_msg; +} + +void AEB::onAutowareState(const AutowareState::ConstSharedPtr input_msg) +{ + autoware_state_ = input_msg; +} + +void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) +{ + PointCloud::Ptr pointcloud_ptr(new PointCloud); + pcl::fromROSMsg(*input_msg, *pointcloud_ptr); + + if (input_msg->header.frame_id != "base_link") { + RCLCPP_ERROR_STREAM( + get_logger(), + "[AEB]: Input point cloud frame is not base_link and it is " << input_msg->header.frame_id); + // transform pointcloud + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_.lookupTransform( + "base_link", input_msg->header.frame_id, input_msg->header.stamp, + rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + get_logger(), + "[AEB] Failed to look up transform from base_link to" << input_msg->header.frame_id); + return; + } + + // transform by using eigen matrix + PointCloud2 transformed_points{}; + const Eigen::Matrix4f affine_matrix = + tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + pcl_ros::transformPointCloud(affine_matrix, *input_msg, transformed_points); + pcl::fromROSMsg(transformed_points, *pointcloud_ptr); + } + + pcl::VoxelGrid filter; + PointCloud::Ptr no_height_filtered_pointcloud_ptr(new PointCloud); + filter.setInputCloud(pointcloud_ptr); + filter.setLeafSize(voxel_grid_x_, voxel_grid_y_, voxel_grid_z_); + filter.filter(*no_height_filtered_pointcloud_ptr); + + obstacle_ros_pointcloud_ptr_ = std::make_shared(); + pcl::toROSMsg(*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_); + obstacle_ros_pointcloud_ptr_->header = input_msg->header; + pub_obstacle_pointcloud_->publish(*obstacle_ros_pointcloud_ptr_); +} + +bool AEB::isDataReady() +{ + const auto missing = [this](const auto & name) { + RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), *get_clock(), 5000, "[AEB] waiting for %s", name); + return false; + }; + + if (!current_velocity_ptr_) { + return missing("ego velocity"); + } + + if (!obstacle_ros_pointcloud_ptr_) { + return missing("object pointcloud"); + } + + if (use_imu_path_ && !imu_ptr_) { + return missing("object pointcloud"); + } + + if (use_predicted_trajectory_ && !predicted_traj_ptr_) { + return missing("control predicted trajectory"); + } + + if (!autoware_state_) { + return missing("autoware_state"); + } + + return true; +} + +void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) +{ + if (checkCollision()) { + const std::string error_msg = "[AEB]: Emergency Brake"; + const auto diag_level = DiagnosticStatus::ERROR; + stat.summary(diag_level, error_msg); + return; + } + + const std::string error_msg = "[AEB]: No Collision"; + const auto diag_level = DiagnosticStatus::OK; + stat.summary(diag_level, error_msg); +} + +bool AEB::checkCollision() +{ + // step1. check data + if (!isDataReady()) { + return false; + } + + // if not driving, disable aeb + if (autoware_state_->state != AutowareState::DRIVING) { + return false; + } + + // step2. create velocity data check if the vehicle stops or not + const double current_v = current_velocity_ptr_->longitudinal_velocity; + if (current_v < 0.1) { + return false; + } + + MarkerArray debug_markers; + + // step3. create ego path based on sensor data + Path ego_path; + std::vector ego_polys; + if (use_imu_path_) { + const double current_w = imu_ptr_->angular_velocity.z; + constexpr double color_r = 0.0 / 256.0; + constexpr double color_g = 148.0 / 256.0; + constexpr double color_b = 205.0 / 256.0; + constexpr double color_a = 0.999; + const auto current_time = get_clock()->now(); + generateEgoPath(current_v, current_w, ego_path, ego_polys); + addMarker( + current_time, ego_path, ego_polys, color_r, color_g, color_b, color_a, "ego_path", + "ego_polygons", debug_markers); + } + + // step4. transform predicted trajectory from control module + Path predicted_path; + std::vector predicted_polys; + if (use_predicted_trajectory_) { + const auto predicted_traj_ptr = predicted_traj_ptr_; + constexpr double color_r = 0.0; + constexpr double color_g = 100.0 / 256.0; + constexpr double color_b = 0.0; + constexpr double color_a = 0.999; + const auto current_time = predicted_traj_ptr->header.stamp; + generateEgoPath(*predicted_traj_ptr, predicted_path, predicted_polys); + addMarker( + current_time, predicted_path, predicted_polys, color_r, color_g, color_b, color_a, + "predicted_path", "predicted_polygons", debug_markers); + } + + // publish debug markers + debug_ego_path_publisher_->publish(debug_markers); + + return hasCollision(current_v, ego_path, ego_polys) || + hasCollision(current_v, predicted_path, predicted_polys); +} + +bool AEB::hasCollision( + const double current_v, const Path & ego_path, const std::vector & ego_polys) +{ + // check if the predicted path has valid number of points + if (ego_path.size() < 2 || ego_polys.empty()) { + return false; + } + + // step1. create object + std::vector objects; + createObjectData(ego_path, ego_polys, objects); + + // step2. calculate RSS + const auto current_p = tier4_autoware_utils::createPoint(0.0, 0.0, 0.0); + const double & t = t_response_; + for (const auto & obj : objects) { + const double & obj_v = obj.velocity; + const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs(a_ego_min_)) - + obj_v * obj_v / (2 * std::fabs(a_obj_min_)) + longitudinal_offset_; + const double dist_ego_to_object = + motion_utils::calcSignedArcLength(ego_path, current_p, obj.position) - + vehicle_info_.max_longitudinal_offset_m; + if (dist_ego_to_object < rss_dist) { + // collision happens + return true; + } + } + + return false; +} + +void AEB::generateEgoPath( + const double curr_v, const double curr_w, Path & path, std::vector & polygons) +{ + double curr_x = 0.0; + double curr_y = 0.0; + double curr_yaw = 0.0; + geometry_msgs::msg::Pose ini_pose; + ini_pose.position = tier4_autoware_utils::createPoint(curr_x, curr_y, 0.0); + ini_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(curr_yaw); + path.push_back(ini_pose); + + if (curr_v < 0.1) { + // if current velocity is too small, assume it stops at the same point + return; + } + + constexpr double epsilon = 1e-6; + const double & dt = prediction_time_interval_; + const double & horizon = prediction_time_horizon_; + for (double t = 0.0; t < horizon + epsilon; t += dt) { + curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; + curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; + curr_yaw = curr_yaw + curr_w * dt; + geometry_msgs::msg::Pose current_pose; + current_pose.position = tier4_autoware_utils::createPoint(curr_x, curr_y, 0.0); + current_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(curr_yaw); + if (tier4_autoware_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { + continue; + } + path.push_back(current_pose); + } + + // If path is shorter than minimum path length + while (motion_utils::calcArcLength(path) < min_generated_path_length_) { + curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; + curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; + curr_yaw = curr_yaw + curr_w * dt; + geometry_msgs::msg::Pose current_pose; + current_pose.position = tier4_autoware_utils::createPoint(curr_x, curr_y, 0.0); + current_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(curr_yaw); + if (tier4_autoware_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { + continue; + } + path.push_back(current_pose); + } + + // generate ego polygons + polygons.resize(path.size() - 1); + for (size_t i = 0; i < path.size() - 1; ++i) { + polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); + } +} + +void AEB::generateEgoPath( + const Trajectory & predicted_traj, Path & path, + std::vector & polygons) +{ + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_.lookupTransform( + "base_link", predicted_traj.header.frame_id, predicted_traj.header.stamp, + rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); + return; + } + + // create path + path.resize(predicted_traj.points.size()); + for (size_t i = 0; i < predicted_traj.points.size(); ++i) { + geometry_msgs::msg::Pose map_pose; + tf2::doTransform(predicted_traj.points.at(i).pose, map_pose, transform_stamped); + path.at(i) = map_pose; + } + + // create polygon + polygons.resize(path.size()); + for (size_t i = 0; i < path.size() - 1; ++i) { + polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); + } +} + +void AEB::createObjectData( + const Path & ego_path, const std::vector & ego_polys, + std::vector & objects) +{ + PointCloud::Ptr obstacle_points_ptr(new PointCloud); + pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *obstacle_points_ptr); + for (const auto & point : obstacle_points_ptr->points) { + ObjectData obj; + obj.position = tier4_autoware_utils::createPoint(point.x, point.y, point.z); + obj.velocity = 0.0; + const Point2d obj_point(point.x, point.y); + const double lat_dist = motion_utils::calcLateralOffset(ego_path, obj.position); + if (lat_dist > 5.0) { + continue; + } + for (const auto & ego_poly : ego_polys) { + if (bg::within(obj_point, ego_poly)) { + objects.push_back(obj); + break; + } + } + } +} + +void AEB::addMarker( + const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & path_ns, const std::string & poly_ns, MarkerArray & debug_markers) +{ + // transform to map + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_.lookupTransform( + "map", "base_link", current_time, rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); + return; + } + + auto path_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, path_ns, 0L, Marker::LINE_STRIP, + tier4_autoware_utils::createMarkerScale(0.2, 0.2, 0.2), + tier4_autoware_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + path_marker.points.resize(path.size()); + for (size_t i = 0; i < path.size(); ++i) { + const auto & pose = path.at(i); + geometry_msgs::msg::Pose map_pose; + tf2::doTransform(pose, map_pose, transform_stamped); + path_marker.points.at(i) = map_pose.position; + } + debug_markers.markers.push_back(path_marker); + + auto polygon_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, poly_ns, 0, Marker::LINE_LIST, + tier4_autoware_utils::createMarkerScale(0.03, 0.0, 0.0), + tier4_autoware_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + for (const auto & poly : polygons) { + for (size_t dp_idx = 0; dp_idx < poly.outer().size(); ++dp_idx) { + const auto & boost_cp = poly.outer().at(dp_idx); + const auto & boost_np = poly.outer().at((dp_idx + 1) % poly.outer().size()); + const auto curr_point = tier4_autoware_utils::createPoint(boost_cp.x(), boost_cp.y(), 0.0); + const auto next_point = tier4_autoware_utils::createPoint(boost_np.x(), boost_np.y(), 0.0); + + geometry_msgs::msg::Point map_curr_point; + geometry_msgs::msg::Point map_next_point; + tf2::doTransform(curr_point, map_curr_point, transform_stamped); + tf2::doTransform(next_point, map_next_point, transform_stamped); + polygon_marker.points.push_back(map_curr_point); + polygon_marker.points.push_back(map_next_point); + } + } + debug_markers.markers.push_back(polygon_marker); +} +} // namespace autoware::motion::control::autonomous_emergency_braking + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::motion::control::autonomous_emergency_braking::AEB) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 593a79cd2b361..6821388e174d4 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -59,6 +59,8 @@ def launch_setup(context, *args, **kwargs): LaunchConfiguration("obstacle_collision_checker_param_path").perform(context), "r" ) as f: obstacle_collision_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(LaunchConfiguration("aeb_param_path").perform(context), "r") as f: + aeb_param = yaml.safe_load(f)["/**"]["ros__parameters"] controller_component = ComposableNode( package="trajectory_follower_node", @@ -126,6 +128,33 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # autonomous emergency braking + autonomous_emergency_braking = ComposableNode( + package="autonomous_emergency_braking", + plugin="autoware::motion::control::autonomous_emergency_braking::AEB", + name="autonomous_emergency_braking", + remappings=[ + ("~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud"), + ("~/input/velocity", "/vehicle/status/velocity_status"), + ("~/input/imu", "/sensing/imu/imu_data"), + ("~/input/odometry", "/localization/kinematic_state"), + ( + "~/input/predicted_trajectory", + "/control/trajectory_follower/lateral/predicted_trajectory", + ), + ], + parameters=[ + aeb_param, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + autonomous_emergency_braking_loader = LoadComposableNodes( + condition=IfCondition(LaunchConfiguration("enable_autonomous_emergency_braking")), + composable_node_descriptions=[autonomous_emergency_braking], + target_container="/control/control_container", + ) + # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( package="vehicle_cmd_gate", @@ -274,6 +303,7 @@ def launch_setup(context, *args, **kwargs): external_cmd_selector_loader, external_cmd_converter_loader, obstacle_collision_checker_loader, + autonomous_emergency_braking_loader, ] ) @@ -306,6 +336,8 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("shift_decider_param_path") add_launch_arg("obstacle_collision_checker_param_path") add_launch_arg("external_cmd_selector_param_path") + add_launch_arg("aeb_param_path") + add_launch_arg("enable_autonomous_emergency_braking") # component add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") diff --git a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml index 360b15a9d7e45..86d84bba7c41c 100644 --- a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml +++ b/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml @@ -4,6 +4,20 @@ type: diagnostic_aggregator/AnalyzerGroup path: control analyzers: + autonomous_emergency_braking: + type: diagnostic_aggregator/AnalyzerGroup + path: 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 diff --git a/system/system_error_monitor/config/system_error_monitor.param.yaml b/system/system_error_monitor/config/system_error_monitor.param.yaml index 71dc2ac600685..312a2e6186c42 100644 --- a/system/system_error_monitor/config/system_error_monitor.param.yaml +++ b/system/system_error_monitor/config/system_error_monitor.param.yaml @@ -20,6 +20,7 @@ /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/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/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } @@ -43,6 +44,7 @@ external_control: /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/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 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 index 9708456df4fe7..88431dc406fe3 100644 --- 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 @@ -20,6 +20,7 @@ /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/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/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } @@ -43,6 +44,7 @@ external_control: /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/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 From 9971be354cf68eab9da5cc6bbb08b77076b35776 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 Mar 2023 13:15:46 +0900 Subject: [PATCH 057/121] fix(avoidance): stop only when there is enough space to avoid (#3055) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 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 60811e5c4469f..741669f65fdcd 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 @@ -751,10 +751,12 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de /** * Find the nearest object that should be avoid. When the ego follows reference path, - * if the lateral distance is smaller than minimum margin, the ego should avoid the object. + * if the both of following two conditions are satisfied, the module surely avoid the object. + * Condition1: there is risk to collide with object without avoidance. + * Condition2: there is enough space to avoid. */ for (const auto & o : data.target_objects) { - if (o.avoid_required) { + if (o.avoid_required && o.is_avoidable) { data.avoid_required = true; data.stop_target_object = o; } From dd5c6eab84364ce611c9cb9911f626d4015e4e4e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 17 Mar 2023 14:39:19 +0900 Subject: [PATCH 058/121] fix(system_error_monitor): fix dying node (#3103) Signed-off-by: Takayuki Murooka --- system/system_error_monitor/src/system_error_monitor_core.cpp | 4 ++++ 1 file changed, 4 insertions(+) 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 8a4cf3ecbb8d6..57f67a247d2b9 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -410,6 +410,10 @@ bool AutowareErrorMonitor::isDataReady() 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; }; From 104ebf73bb16ccf2da625ad59bce70656d4662a5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 Mar 2023 15:05:51 +0900 Subject: [PATCH 059/121] fix(AEB): suppress build error (-Werror=pedantic) (#3108) Signed-off-by: satoshi-ota --- control/autonomous_emergency_braking/CMakeLists.txt | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/control/autonomous_emergency_braking/CMakeLists.txt b/control/autonomous_emergency_braking/CMakeLists.txt index 6027aeac76333..53a629fafa0cc 100644 --- a/control/autonomous_emergency_braking/CMakeLists.txt +++ b/control/autonomous_emergency_braking/CMakeLists.txt @@ -4,6 +4,14 @@ project(autonomous_emergency_braking) find_package(autoware_cmake REQUIRED) autoware_package() +find_package(PCL REQUIRED) + +include_directories( + include + SYSTEM + ${PCL_INCLUDE_DIRS} +) + set(AEB_NODE ${PROJECT_NAME}_node) ament_auto_add_library(${AEB_NODE} SHARED src/node.cpp From a98e9e8a1cb582186e9337d072cf3410d869e47f Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Sat, 18 Mar 2023 19:47:33 +0900 Subject: [PATCH 060/121] chore(ground_segmentation): add recheck ground cluster option param (#3106) Signed-off-by: badai-nguyen --- .../ground_segmentation/docs/scan-ground-filter.md | 1 + .../scan_ground_filter_nodelet.hpp | 1 + .../src/scan_ground_filter_nodelet.cpp | 11 +++++++++-- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index 6d044d6b47c3a..0c07ce600f625 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -47,6 +47,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `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 diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index f6a8ba4c8a89a..11572772a0d0e 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -170,6 +170,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter double // minimum height threshold regardless the slope, split_height_distance_; // useful for close points bool use_virtual_ground_point_; + bool use_recheck_ground_cluster_; // to enable recheck ground cluster size_t radial_dividers_num_; VehicleInfo vehicle_info_; diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index fa9d3d6d83665..953a9feb4d21e 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -54,6 +54,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & split_points_distance_tolerance_ = declare_parameter("split_points_distance_tolerance", 0.2); split_height_distance_ = declare_parameter("split_height_distance", 0.2); use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point", true); + use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster", true); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); @@ -356,7 +357,9 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( // move to new grid if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) { // check if the prev grid have ground point cloud - recheckGroundCluster(ground_cluster, non_ground_height_threshold_, out_no_ground_indices); + if (use_recheck_ground_cluster_) { + recheckGroundCluster(ground_cluster, non_ground_height_threshold_, out_no_ground_indices); + } curr_gnd_grid.radius = ground_cluster.getAverageRadius(); curr_gnd_grid.avg_height = ground_cluster.getAverageHeight(); curr_gnd_grid.max_height = ground_cluster.getMaxHeight(); @@ -611,7 +614,11 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter( get_logger(), "Setting use_virtual_ground_point to: " << std::boolalpha << use_virtual_ground_point_); } - + if (get_param(p, "use_recheck_ground_cluster", use_recheck_ground_cluster_)) { + RCLCPP_DEBUG_STREAM( + get_logger(), + "Setting use_recheck_ground_cluster to: " << std::boolalpha << use_recheck_ground_cluster_); + } rcl_interfaces::msg::SetParametersResult result; result.successful = true; result.reason = "success"; From 8501e1384d0c40afb509dbd8d26c3240088fca3e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sun, 19 Mar 2023 14:45:56 +0900 Subject: [PATCH 061/121] fix(surround_obstacle_checker): remove unused include (#3084) Signed-off-by: Takamasa Horibe --- .../include/surround_obstacle_checker/node.hpp | 3 --- 1 file changed, 3 deletions(-) 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 74dd2f3924bec..89a91c6b6a675 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp @@ -23,7 +23,6 @@ #include #include -#include #include #include #include @@ -46,8 +45,6 @@ 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 motion_utils::VehicleStopChecker; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; From 4267add3ec861b333c8ccf8d1fe692d5dfb70d58 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Mon, 20 Mar 2023 05:55:51 +0100 Subject: [PATCH 062/121] build(autoware_testing): add missing dependencies (#3093) Signed-off-by: Esteve Fernandez --- common/autoware_testing/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/common/autoware_testing/package.xml b/common/autoware_testing/package.xml index d895d85122ae8..30a27bb9435b1 100644 --- a/common/autoware_testing/package.xml +++ b/common/autoware_testing/package.xml @@ -12,6 +12,8 @@ autoware_cmake + ros_testing + ament_cmake_core ament_copyright ament_flake8 From 446e749d83ade11e244c441fbbe426f03489cfb3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Zeynep=20=20Akbal=C4=B1k?= <55089534+Zeysthingz@users.noreply.github.com> Date: Mon, 20 Mar 2023 12:33:28 +0300 Subject: [PATCH 063/121] feat(traffic_light_classifier): add parameters to launch file for using different tensorrt models (#2794) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(traffic_light_classifier): add params to launch file Signed-off-by: Zeynep Akbalık --------- Signed-off-by: Zeynep Akbalık Co-authored-by: Zeynep Akbalık Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/traffic_light_classifier/README.md | 22 +++++++++++-------- .../cnn_classifier.hpp | 4 ++-- .../traffic_light_classifier.launch.xml | 5 +++++ .../src/cnn_classifier.cpp | 6 +++-- 4 files changed, 24 insertions(+), 13 deletions(-) diff --git a/perception/traffic_light_classifier/README.md b/perception/traffic_light_classifier/README.md index b598d877d5293..81381cd9506b7 100644 --- a/perception/traffic_light_classifier/README.md +++ b/perception/traffic_light_classifier/README.md @@ -54,15 +54,19 @@ These colors and shapes are assigned to the message as follows: #### cnn_classifier -| Name | Type | Description | -| ----------------- | ---- | ------------------------------------------------- | -| `model_file_path` | str | path to the model file | -| `label_file_path` | str | path to the label file | -| `precision` | str | TensorRT precision, `fp16` or `int8` | -| `input_c` | str | the channel size of an input image | -| `input_h` | str | the height of an input image | -| `input_w` | str | the width of an input image | -| `build_only` | bool | shutdown node after TensorRT engine file is built | +| Name | Type | Description | +| ----------------- | ------ | ------------------------------------------------- | +| `model_file_path` | str | path to the model file | +| `label_file_path` | str | path to the label file | +| `precision` | str | TensorRT precision, `fp16` or `int8` | +| `input_c` | str | the channel size of an input image | +| `input_h` | str | the height of an input image | +| `input_w` | str | the width of an input image | +| `input_name` | str | the name of neural network's input layer | +| `output_name` | str | the name of neural network's output name | +| `mean` | double | mean values for image normalization | +| `std` | double | std values for image normalization | +| `build_only` | bool | shutdown node after TensorRT engine file is built | #### hsv_classifier diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp index 04914889f0756..a667d39248bba 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp @@ -101,8 +101,8 @@ class CNNClassifier : public ClassifierInterface std::shared_ptr trt_; image_transport::Publisher image_pub_; std::vector labels_; - std::vector mean_{0.242, 0.193, 0.201}; - std::vector std_{1.0, 1.0, 1.0}; + std::vector mean_; + std::vector std_; int input_c_; int input_h_; int input_w_; 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 44288cb2b69f9..745629010cfe6 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -19,7 +19,12 @@ + + + + + diff --git a/perception/traffic_light_classifier/src/cnn_classifier.cpp b/perception/traffic_light_classifier/src/cnn_classifier.cpp index 63ce0fbb3f8bc..621466206ac01 100644 --- a/perception/traffic_light_classifier/src/cnn_classifier.cpp +++ b/perception/traffic_light_classifier/src/cnn_classifier.cpp @@ -39,8 +39,10 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) input_c_ = node_ptr_->declare_parameter("input_c", 3); input_h_ = node_ptr_->declare_parameter("input_h", 224); input_w_ = node_ptr_->declare_parameter("input_w", 224); - auto input_name = node_ptr_->declare_parameter("input_name", "input_0"); - auto output_name = node_ptr_->declare_parameter("output_name", "output_0"); + mean_ = node_ptr_->declare_parameter("mean", std::vector({0.242, 0.193, 0.201})); + std_ = node_ptr_->declare_parameter("std", std::vector({1.0, 1.0, 1.0})); + std::string input_name = node_ptr_->declare_parameter("input_name", std::string("input_0")); + std::string output_name = node_ptr_->declare_parameter("output_name", std::string("output_0")); apply_softmax_ = node_ptr_->declare_parameter("apply_softmax", true); readLabelfile(label_file_path, labels_); From 8b95d2a15a99c93806b1fe380e26698d9b95e109 Mon Sep 17 00:00:00 2001 From: Taiga TAKANO <53041471+TakanoTaiga@users.noreply.github.com> Date: Mon, 20 Mar 2023 19:03:21 +0900 Subject: [PATCH 064/121] perf(motion_utils): improve performance of findNearestIndex (#3082) Signed-off-by: Taiga Takano --- .../include/motion_utils/trajectory/trajectory.hpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 821507ca9a6a8..29d12ab375a17 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -273,7 +273,7 @@ boost::optional findNearestIndex( for (size_t i = 0; i < points.size(); ++i) { const auto squared_dist = tier4_autoware_utils::calcSquaredDistance2d(points.at(i), pose); - if (squared_dist > max_squared_dist) { + if (squared_dist > max_squared_dist || squared_dist >= min_squared_dist) { continue; } @@ -283,10 +283,6 @@ boost::optional findNearestIndex( continue; } - if (squared_dist >= min_squared_dist) { - continue; - } - min_squared_dist = squared_dist; min_idx = i; is_nearest_found = true; From 14739a09d147e5784fc741efd2734352bc80ae01 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Wed, 22 Mar 2023 13:38:45 +0900 Subject: [PATCH 065/121] feat(elevation_map_loader): use polygon iterator to speed up (#2885) * use grid_map::PolygonIterator instead of grid_map::GridMapIterator Signed-off-by: Shunsuke Miura * formatting Signed-off-by: Shunsuke Miura * use use_lane_filter option Signed-off-by: Shunsuke Miura * delete unused use-lane-filter option Signed-off-by: Shunsuke Miura * change use_lane_filter to True, clarify the scope Signed-off-by: Shunsuke Miura * change to use grid_map_utils::PolygonIterator Signed-off-by: Shunsuke Miura * Add lane margin parameter Signed-off-by: Shunsuke Miura * use boost geometry buffer to expand lanes Signed-off-by: Shunsuke Miura * Change use_lane_filter param default to false Signed-off-by: Shunsuke Miura * update README Signed-off-by: Shunsuke Miura --------- Signed-off-by: Shunsuke Miura --- .../ground_segmentation.launch.py | 1 + perception/elevation_map_loader/README.md | 26 +-- .../elevation_map_loader_node.hpp | 18 +- .../launch/elevation_map_loader.launch.xml | 12 -- perception/elevation_map_loader/package.xml | 1 + .../src/elevation_map_loader_node.cpp | 198 ++++-------------- 6 files changed, 59 insertions(+), 197 deletions(-) diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index c072d4deb3059..105bcb0e76e93 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -327,6 +327,7 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic, con "use_lane_filter": False, "use_inpaint": True, "inpaint_radius": 1.0, + "lane_margin": 2.0, "param_file_path": PathJoinSubstitution( [ LaunchConfiguration( diff --git a/perception/elevation_map_loader/README.md b/perception/elevation_map_loader/README.md index e9288c2f474a1..2cabc2803c8ec 100644 --- a/perception/elevation_map_loader/README.md +++ b/perception/elevation_map_loader/README.md @@ -36,21 +36,17 @@ Cells with No elevation value can be inpainted using the values of neighboring c ### Node parameters -| Name | Type | Description | Default value | -| :-------------------------------- | :---------- | :--------------------------------------------------------------------------------------------------------- | :------------ | -| map_layer_name | std::string | elevation_map layer name | elevation | -| param_file_path | std::string | GridMap parameters config | path_default | -| elevation_map_file_path | std::string | elevation_map file (bag2) | path_default | -| map_frame | std::string | map_frame when loading elevation_map file | map | -| use_inpaint | bool | Whether to inpaint empty cells | true | -| inpaint_radius | float | Radius of a circular neighborhood of each point inpainted that is considered by the algorithm [m] | 0.3 | -| use_elevation_map_cloud_publisher | bool | Whether to publish `output/elevation_map_cloud` | false | -| use_lane_filter | bool | Whether to filter elevation_map with vector_map | false | -| lane_margin | float | Value of how much to expand the range of vector_map [m] | 0.5 | -| lane_height_diff_thresh | float | Only point clouds in the height range of this value from vector_map are used to generate elevation_map [m] | 1.0 | -| lane_filter_voxel_size_x | float | Voxel size x for calculating point clouds in vector_map [m] | 0.04 | -| lane_filter_voxel_size_y | float | Voxel size y for calculating point clouds in vector_map [m] | 0.04 | -| lane_filter_voxel_size_z | float | Voxel size z for calculating point clouds in vector_map [m] | 0.04 | +| Name | Type | Description | Default value | +| :-------------------------------- | :---------- | :-------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| map_layer_name | std::string | elevation_map layer name | elevation | +| param_file_path | std::string | GridMap parameters config | path_default | +| elevation_map_directory | std::string | elevation_map file (bag2) | path_default | +| map_frame | std::string | map_frame when loading elevation_map file | map | +| use_inpaint | bool | Whether to inpaint empty cells | true | +| inpaint_radius | float | Radius of a circular neighborhood of each point inpainted that is considered by the algorithm [m] | 0.3 | +| use_elevation_map_cloud_publisher | bool | Whether to publish `output/elevation_map_cloud` | false | +| use_lane_filter | bool | Whether to filter elevation_map with vector_map | false | +| lane_margin | float | Margin distance from the lane polygon of the area to be included in the inpainting mask [m]. Used only when use_lane_filter=True. | 0.0 | ### GridMap parameters diff --git a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp index f5c294dd27207..1e45fde199f3c 100644 --- a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp +++ b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp @@ -75,21 +75,9 @@ class ElevationMapLoaderNode : public rclcpp::Node void setVerbosityLevelToDebugIfFlagSet(); void createElevationMapFromPointcloud( const pcl::shared_ptr & grid_map_pcl_loader); - tier4_autoware_utils::LinearRing2d getConvexHull( - const pcl::PointCloud::Ptr & input_cloud); - lanelet::ConstLanelets getIntersectedLanelets( - const tier4_autoware_utils::LinearRing2d & convex_hull, - const lanelet::ConstLanelets & road_lanelets_); - pcl::PointCloud::Ptr getLaneFilteredPointCloud( - const lanelet::ConstLanelets & joint_lanelets, - const pcl::PointCloud::Ptr & cloud); - bool checkPointWithinLanelets( - const pcl::PointXYZ & point, const lanelet::ConstLanelets & joint_lanelets); void inpaintElevationMap(const float radius); pcl::PointCloud::Ptr createPointcloudFromElevationMap(); void saveElevationMap(); - float calculateDistancePointFromPlane( - const pcl::PointXYZ & point, const lanelet::ConstLanelet & lanelet); grid_map::GridMap elevation_map_; std::string layer_name_; @@ -103,12 +91,8 @@ class ElevationMapLoaderNode : public rclcpp::Node DataManager data_manager_; struct LaneFilter { - float voxel_size_x_; - float voxel_size_y_; - float voxel_size_z_; - float lane_margin_; - float lane_height_diff_thresh_; lanelet::ConstLanelets road_lanelets_; + float lane_margin_; bool use_lane_filter_; }; LaneFilter lane_filter_; diff --git a/perception/elevation_map_loader/launch/elevation_map_loader.launch.xml b/perception/elevation_map_loader/launch/elevation_map_loader.launch.xml index ddb99f7ce9e1a..7b415f5b2e770 100644 --- a/perception/elevation_map_loader/launch/elevation_map_loader.launch.xml +++ b/perception/elevation_map_loader/launch/elevation_map_loader.launch.xml @@ -5,13 +5,6 @@ - - - - - - - @@ -20,10 +13,5 @@ - - - - - diff --git a/perception/elevation_map_loader/package.xml b/perception/elevation_map_loader/package.xml index 3b99d2c10d319..e809298e4c415 100644 --- a/perception/elevation_map_loader/package.xml +++ b/perception/elevation_map_loader/package.xml @@ -16,6 +16,7 @@ grid_map_cv grid_map_pcl grid_map_ros + grid_map_utils lanelet2_extension libpcl-all-dev pcl_conversions diff --git a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp index 5434447a78c1f..c57934b960906 100644 --- a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp @@ -19,10 +19,12 @@ #include #include #include +#include #include #include +#include #include #include #include @@ -61,11 +63,7 @@ ElevationMapLoaderNode::ElevationMapLoaderNode(const rclcpp::NodeOptions & optio data_manager_.use_lane_filter_ = use_lane_filter; lane_filter_.use_lane_filter_ = use_lane_filter; - lane_filter_.lane_margin_ = this->declare_parameter("lane_margin", 0.5); - lane_filter_.lane_height_diff_thresh_ = this->declare_parameter("lane_height_diff_thresh", 1.0); - lane_filter_.voxel_size_x_ = declare_parameter("lane_filter_voxel_size_x", 0.04); - lane_filter_.voxel_size_y_ = declare_parameter("lane_filter_voxel_size_y", 0.04); - lane_filter_.voxel_size_z_ = declare_parameter("lane_filter_voxel_size_z", 0.04); + lane_filter_.lane_margin_ = this->declare_parameter("lane_margin", 0.0); rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); @@ -176,21 +174,14 @@ void ElevationMapLoaderNode::createElevationMap() { auto grid_map_logger = rclcpp::get_logger("grid_map_logger"); grid_map_logger.set_level(rclcpp::Logger::Level::Error); - pcl::shared_ptr grid_map_pcl_loader = - pcl::make_shared(grid_map_logger); - grid_map_pcl_loader->loadParameters(param_file_path_); - if (lane_filter_.use_lane_filter_) { - const auto convex_hull = getConvexHull(data_manager_.map_pcl_ptr_); - lanelet::ConstLanelets intersected_lanelets = - getIntersectedLanelets(convex_hull, lane_filter_.road_lanelets_); - pcl::PointCloud::Ptr lane_filtered_map_pcl_ptr = - getLaneFilteredPointCloud(intersected_lanelets, data_manager_.map_pcl_ptr_); - grid_map_pcl_loader->setInputCloud(lane_filtered_map_pcl_ptr); - } else { + { + pcl::shared_ptr grid_map_pcl_loader = + pcl::make_shared(grid_map_logger); + grid_map_pcl_loader->loadParameters(param_file_path_); grid_map_pcl_loader->setInputCloud(data_manager_.map_pcl_ptr_); + createElevationMapFromPointcloud(grid_map_pcl_loader); + elevation_map_ = grid_map_pcl_loader->getGridMap(); } - createElevationMapFromPointcloud(grid_map_pcl_loader); - elevation_map_ = grid_map_pcl_loader->getGridMap(); if (use_inpaint_) { inpaintElevationMap(inpaint_radius_); } @@ -212,12 +203,45 @@ void ElevationMapLoaderNode::inpaintElevationMap(const float radius) { // Convert elevation layer to OpenCV image to fill in holes. // Get the inpaint mask (nonzero pixels indicate where values need to be filled in). + namespace bg = boost::geometry; + using tier4_autoware_utils::Point2d; + elevation_map_.add("inpaint_mask", 0.0); elevation_map_.setBasicLayers(std::vector()); - for (grid_map::GridMapIterator iterator(elevation_map_); !iterator.isPastEnd(); ++iterator) { - if (!elevation_map_.isValid(*iterator, layer_name_)) { - elevation_map_.at("inpaint_mask", *iterator) = 1.0; + if (lane_filter_.use_lane_filter_) { + for (const auto & lanelet : lane_filter_.road_lanelets_) { + auto lane_polygon = lanelet.polygon2d().basicPolygon(); + grid_map::Polygon polygon; + + if (lane_filter_.lane_margin_ > 0) { + lanelet::BasicPolygons2d out; + bg::strategy::buffer::distance_symmetric distance_strategy( + lane_filter_.lane_margin_); + bg::strategy::buffer::join_miter join_strategy; + bg::strategy::buffer::end_flat end_strategy; + bg::strategy::buffer::point_square point_strategy; + bg::strategy::buffer::side_straight side_strategy; + bg::buffer( + lane_polygon, out, distance_strategy, side_strategy, join_strategy, end_strategy, + point_strategy); + lane_polygon = out.front(); + } + for (const auto & p : lane_polygon) { + polygon.addVertex(grid_map::Position(p[0], p[1])); + } + for (grid_map_utils::PolygonIterator iterator(elevation_map_, polygon); !iterator.isPastEnd(); + ++iterator) { + if (!elevation_map_.isValid(*iterator, layer_name_)) { + elevation_map_.at("inpaint_mask", *iterator) = 1.0; + } + } + } + } else { + for (grid_map::GridMapIterator iterator(elevation_map_); !iterator.isPastEnd(); ++iterator) { + if (!elevation_map_.isValid(*iterator, layer_name_)) { + elevation_map_.at("inpaint_mask", *iterator) = 1.0; + } } } cv::Mat original_image; @@ -239,138 +263,6 @@ void ElevationMapLoaderNode::inpaintElevationMap(const float radius) elevation_map_.erase("inpaint_mask"); } -tier4_autoware_utils::LinearRing2d ElevationMapLoaderNode::getConvexHull( - const pcl::PointCloud::Ptr & input_cloud) -{ - // downsample pointcloud to reduce convex hull calculation cost - pcl::PointCloud::Ptr downsampled_cloud(new pcl::PointCloud); - downsampled_cloud->points.reserve(input_cloud->points.size()); - pcl::VoxelGrid filter; - filter.setInputCloud(input_cloud); - filter.setLeafSize(0.5, 0.5, 100.0); - filter.filter(*downsampled_cloud); - - tier4_autoware_utils::MultiPoint2d candidate_points; - for (const auto & p : downsampled_cloud->points) { - candidate_points.emplace_back(p.x, p.y); - } - - tier4_autoware_utils::LinearRing2d convex_hull; - boost::geometry::convex_hull(candidate_points, convex_hull); - - return convex_hull; -} - -lanelet::ConstLanelets ElevationMapLoaderNode::getIntersectedLanelets( - const tier4_autoware_utils::LinearRing2d & convex_hull, - const lanelet::ConstLanelets & road_lanelets) -{ - lanelet::ConstLanelets intersected_lanelets; - for (const auto & road_lanelet : road_lanelets) { - if (boost::geometry::intersects(convex_hull, road_lanelet.polygon2d().basicPolygon())) { - intersected_lanelets.push_back(road_lanelet); - } - } - return intersected_lanelets; -} - -bool ElevationMapLoaderNode::checkPointWithinLanelets( - const pcl::PointXYZ & point, const lanelet::ConstLanelets & intersected_lanelets) -{ - tier4_autoware_utils::Point2d point2d(point.x, point.y); - for (const auto & lanelet : intersected_lanelets) { - if (lane_filter_.lane_margin_ > 0) { - if ( - boost::geometry::distance(point2d, lanelet.polygon2d().basicPolygon()) > - lane_filter_.lane_margin_) { - continue; - } - } else { - if (!boost::geometry::within(point2d, lanelet.polygon2d().basicPolygon())) { - continue; - } - } - - if (lane_filter_.lane_height_diff_thresh_ > 0) { - float distance = calculateDistancePointFromPlane(point, lanelet); - if (distance < lane_filter_.lane_height_diff_thresh_) { - return true; - } - } else { - return true; - } - } - return false; -} - -float ElevationMapLoaderNode::calculateDistancePointFromPlane( - const pcl::PointXYZ & point, const lanelet::ConstLanelet & lanelet) -{ - const Eigen::Vector3d point_3d(point.x, point.y, point.z); - const Eigen::Vector2d point_2d(point.x, point.y); - - const float distance_3d = boost::geometry::distance(point_3d, lanelet.centerline3d()); - const float distance_2d = boost::geometry::distance(point_2d, lanelet.centerline2d()); - const float distance = std::sqrt(distance_3d * distance_3d - distance_2d * distance_2d); - - return distance; -} - -pcl::PointCloud::Ptr ElevationMapLoaderNode::getLaneFilteredPointCloud( - const lanelet::ConstLanelets & intersected_lanelets, - const pcl::PointCloud::Ptr & cloud) -{ - pcl::PointCloud filtered_cloud; - filtered_cloud.header = cloud->header; - - pcl::PointCloud::Ptr centralized_cloud(new pcl::PointCloud); - centralized_cloud->reserve(cloud->size()); - - // The coordinates of the point cloud are too large, resulting in calculation errors, - // so offset them to the center. - // https://github.com/PointCloudLibrary/pcl/issues/4895 - Eigen::Vector4f centroid; - pcl::compute3DCentroid(*cloud, centroid); - for (const auto & p : cloud->points) { - centralized_cloud->points.push_back( - pcl::PointXYZ(p.x - centroid[0], p.y - centroid[1], p.z - centroid[2])); - } - - pcl::PointCloud::Ptr downsampled_cloud(new pcl::PointCloud); - pcl::VoxelGrid voxel_grid; - voxel_grid.setLeafSize(lane_filter_.voxel_size_x_, lane_filter_.voxel_size_y_, 100000.0); - voxel_grid.setInputCloud(centralized_cloud); - voxel_grid.setSaveLeafLayout(true); - voxel_grid.filter(*downsampled_cloud); - - std::unordered_map> downsampled2original_map; - for (const auto & p : centralized_cloud->points) { - if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) { - continue; - } - const size_t index = voxel_grid.getCentroidIndex(p); - downsampled2original_map[index].points.push_back(p); - } - - for (auto & point : downsampled_cloud->points) { - if (checkPointWithinLanelets( - pcl::PointXYZ(point.x + centroid[0], point.y + centroid[1], point.z + centroid[2]), - intersected_lanelets)) { - const size_t index = voxel_grid.getCentroidIndex(point); - for (auto & original_point : downsampled2original_map[index].points) { - original_point.x += centroid[0]; - original_point.y += centroid[1]; - original_point.z += centroid[2]; - filtered_cloud.points.push_back(original_point); - } - } - } - - pcl::PointCloud::Ptr filtered_cloud_ptr; - filtered_cloud_ptr = pcl::make_shared>(filtered_cloud); - return filtered_cloud_ptr; -} - pcl::PointCloud::Ptr ElevationMapLoaderNode::createPointcloudFromElevationMap() { pcl::PointCloud output_cloud; From 3d7ec33098a3f00f529a2173b7fc6147613dded9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 22 Mar 2023 13:42:11 +0900 Subject: [PATCH 066/121] feat(behavior_path_planner): visualize unavoidable target object (#3109) Signed-off-by: Takayuki Murooka --- .../marker_util/avoidance/debug.hpp | 6 ++- .../src/marker_util/avoidance/debug.cpp | 40 ++++++++++++++++++- .../avoidance/avoidance_module.cpp | 18 ++++++++- 3 files changed, 60 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_util/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_util/avoidance/debug.hpp index 04143fac29361..157098685aff3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_util/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_util/avoidance/debug.hpp @@ -58,7 +58,11 @@ MarkerArray createAvoidLineMarkerArray( MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::string && ns); -MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns); +MarkerArray createAvoidableTargetObjectsMarkerArray( + const ObjectDataArray & objects, std::string && ns); + +MarkerArray createUnavoidableTargetObjectsMarkerArray( + const ObjectDataArray & objects, std::string && ns); MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns); diff --git a/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp b/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp index af0278a5d3f9d..2ba8ea276a782 100644 --- a/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp @@ -337,7 +337,45 @@ MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::st return msg; } -MarkerArray createTargetObjectsMarkerArray( +MarkerArray createAvoidableTargetObjectsMarkerArray( + const behavior_path_planner::ObjectDataArray & objects, std::string && ns) +{ + MarkerArray msg; + msg.markers.reserve(objects.size() * 3); + + appendMarkerArray( + createObjectsCubeMarkerArray( + objects, ns + "_cube", createMarkerScale(3.0, 1.5, 1.5), + createMarkerColor(1.0, 1.0, 0.0, 0.8)), + &msg); + + appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg); + + { + for (const auto & object : objects) { + const auto pos = object.object.kinematics.initial_pose_with_covariance.pose.position; + + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns + "_envelope_polygon", 0L, + Marker::LINE_STRIP, createMarkerScale(0.1, 0.0, 0.0), + createMarkerColor(1.0, 1.0, 1.0, 0.999)); + + for (const auto & p : object.envelope_poly.outer()) { + marker.points.push_back(createPoint(p.x(), p.y(), pos.z)); + } + + marker.points.push_back(marker.points.front()); + marker.id = uuidToInt32(object.object.object_id); + msg.markers.push_back(marker); + } + } + } + + return msg; +} + +MarkerArray createUnavoidableTargetObjectsMarkerArray( const behavior_path_planner::ObjectDataArray & objects, std::string && ns) { MarkerArray msg; 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 741669f65fdcd..d48e141fb55fe 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 @@ -3713,14 +3713,15 @@ void AvoidanceModule::setDebugData( using marker_utils::createPoseMarkerArray; using marker_utils::createShiftLengthMarkerArray; using marker_utils::createShiftLineMarkerArray; + using marker_utils::avoidance_marker::createAvoidableTargetObjectsMarkerArray; using marker_utils::avoidance_marker::createAvoidLineMarkerArray; using marker_utils::avoidance_marker::createEgoStatusMarkerArray; using marker_utils::avoidance_marker::createOtherObjectsMarkerArray; using marker_utils::avoidance_marker::createOverhangFurthestLineStringMarkerArray; using marker_utils::avoidance_marker::createPredictedVehiclePositions; using marker_utils::avoidance_marker::createSafetyCheckMarkerArray; - using marker_utils::avoidance_marker::createTargetObjectsMarkerArray; using marker_utils::avoidance_marker::createUnavoidableObjectsMarkerArray; + using marker_utils::avoidance_marker::createUnavoidableTargetObjectsMarkerArray; using marker_utils::avoidance_marker::createUnsafeObjectsMarkerArray; using marker_utils::avoidance_marker::makeOverhangToRoadShoulderMarkerArray; using motion_utils::createDeadLineVirtualWallMarker; @@ -3777,9 +3778,22 @@ void AvoidanceModule::setDebugData( add(createSafetyCheckMarkerArray(data.state, getEgoPose(), debug)); + std::vector avoidable_target_objects; + std::vector unavoidable_target_objects; + for (const auto & object : data.target_objects) { + if (object.is_avoidable) { + avoidable_target_objects.push_back(object); + } else { + unavoidable_target_objects.push_back(object); + } + } + add(createLaneletsAreaMarkerArray(*debug.current_lanelets, "current_lanelet", 0.0, 1.0, 0.0)); add(createLaneletsAreaMarkerArray(*debug.expanded_lanelets, "expanded_lanelet", 0.8, 0.8, 0.0)); - add(createTargetObjectsMarkerArray(data.target_objects, "target_objects")); + add( + createAvoidableTargetObjectsMarkerArray(avoidable_target_objects, "avoidable_target_objects")); + add(createUnavoidableTargetObjectsMarkerArray( + unavoidable_target_objects, "unavoidable_target_objects")); add(createOtherObjectsMarkerArray(data.other_objects, "other_objects")); add(makeOverhangToRoadShoulderMarkerArray(data.target_objects, "overhang")); add(createOverhangFurthestLineStringMarkerArray( From 36bdca4aa41ad910235cc465501b410a01b91f6f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 22 Mar 2023 13:42:33 +0900 Subject: [PATCH 067/121] fix(planning_debug_tools): install perception_reproducer.py (#3105) Signed-off-by: Takayuki Murooka --- planning/planning_debug_tools/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/planning_debug_tools/CMakeLists.txt b/planning/planning_debug_tools/CMakeLists.txt index 7d5722d791959..c2bee10f972f1 100644 --- a/planning/planning_debug_tools/CMakeLists.txt +++ b/planning/planning_debug_tools/CMakeLists.txt @@ -50,5 +50,6 @@ ament_auto_package( install(PROGRAMS scripts/trajectory_visualizer.py scripts/closest_velocity_checker.py + scripts/perception_reproducer.py DESTINATION lib/${PROJECT_NAME} ) From 61b9e1e2600677545ebd86c5413cd2b6cc8d6aaa Mon Sep 17 00:00:00 2001 From: Vincent Richard Date: Wed, 22 Mar 2023 15:47:25 +0900 Subject: [PATCH 068/121] chore(ekf_localizer): move parameters to its dedicated yaml file (#3039) * chores(ekf_localizer): move parameters to its dedicated yaml file Signed-off-by: Vincent Richard * style(pre-commit): autofix --------- Signed-off-by: Vincent Richard Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../launch/localization.launch.xml | 1 + .../pose_twist_fusion_filter.launch.xml | 6 +-- localization/ekf_localizer/CMakeLists.txt | 1 + .../config/ekf_localizer.param.yaml | 23 ++++++++++ .../launch/ekf_localizer.launch.xml | 44 ++----------------- 5 files changed, 30 insertions(+), 45 deletions(-) create mode 100644 localization/ekf_localizer/config/ekf_localizer.param.yaml diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index 12ad512557cb1..210e5d049727c 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -6,6 +6,7 @@ + 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 3c109769e13ba..59fd5174fa38c 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 @@ -2,9 +2,6 @@ - - - @@ -15,8 +12,7 @@ - - + diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 6ae8cefc9088c..bd9d22523ea06 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -75,5 +75,6 @@ endif() ament_auto_package( INSTALL_TO_SHARE + config launch ) diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml new file mode 100644 index 0000000000000..322325d239004 --- /dev/null +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -0,0 +1,23 @@ +/**: + ros__parameters: + show_debug_info: false + enable_yaw_bias_estimation: True + predict_frequency: 50.0 + tf_rate: 50.0 + extend_state_step: 50 + + # for Pose measurement + pose_additional_delay: 0.0 + pose_measure_uncertainty_time: 0.01 + pose_smoothing_steps: 5 + pose_gate_dist: 10000.0 + + # for twist measurement + twist_additional_delay: 0.0 + twist_smoothing_steps: 2 + twist_gate_dist: 10000.0 + + # for process model + proc_stddev_yaw_c: 0.005 + proc_stddev_vx_c: 10.0 + proc_stddev_wz_c: 5.0 diff --git a/localization/ekf_localizer/launch/ekf_localizer.launch.xml b/localization/ekf_localizer/launch/ekf_localizer.launch.xml index c716d58bfc00c..ee0504293602a 100644 --- a/localization/ekf_localizer/launch/ekf_localizer.launch.xml +++ b/localization/ekf_localizer/launch/ekf_localizer.launch.xml @@ -1,30 +1,12 @@ - - - - - + - + - - - - - - - - - - - - - - @@ -45,26 +27,6 @@ - - - - - - - - - - - - - - - - - - - - @@ -72,5 +34,7 @@ + + From 9a2769ebf0bd1d2d680d3b2e6defaece99646f1d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 22 Mar 2023 16:49:53 +0900 Subject: [PATCH 069/121] fix(static_centerline_optimizer): avoid to call declear_parameter twice (#3131) * fix(static_centerline_optimizer): avoid to call declear_parameter twice Signed-off-by: tomoya.kimura * make variables private Signed-off-by: Takayuki Murooka --------- Signed-off-by: tomoya.kimura Signed-off-by: Takayuki Murooka Co-authored-by: Takayuki Murooka --- .../src/static_centerline_optimizer_node.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 7187123c1dfd9..5199641a9f23f 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -374,8 +374,14 @@ std::vector StaticCenterlineOptimizerNode::plan_path( utils::get_center_pose(*route_handler_ptr_, route_lane_ids.front()); // ego nearest search parameters - const double ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); - const double ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); + const double ego_nearest_dist_threshold = + has_parameter("ego_nearest_dist_threshold") + ? get_parameter("ego_nearest_dist_threshold").as_double() + : declare_parameter("ego_nearest_dist_threshold"); + const double ego_nearest_yaw_threshold = + has_parameter("ego_nearest_yaw_threshold") + ? get_parameter("ego_nearest_yaw_threshold").as_double() + : declare_parameter("ego_nearest_yaw_threshold"); // extract path with lane id from lanelets const auto raw_path_with_lane_id = utils::get_path_with_lane_id( From 862b48a2180b65cb6bf88bd6afb57d1367b2aca1 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 22 Mar 2023 16:59:40 +0900 Subject: [PATCH 070/121] feat(accel_brake_map_calibrator): add option to use actuation_cmd (#3113) * feat(accel_brake_map_calibrator): add option to use actuation_cmd Signed-off-by: tomoya.kimura * fix a stupid mistake Signed-off-by: tomoya.kimura * add readme Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../accel_brake_map_calibrator/README.md | 37 ++++++------- .../accel_brake_map_calibrator.param.yaml | 1 + .../accel_brake_map_calibrator_node.hpp | 12 +++++ .../accel_brake_map_calibrator.launch.xml | 1 + .../src/accel_brake_map_calibrator_node.cpp | 53 +++++++++++++++---- 5 files changed, 77 insertions(+), 27 deletions(-) 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 b594f389db34b..60d652c6140e4 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 @@ -146,21 +146,22 @@ You can also save accel and brake map in the default directory where Autoware re ## Algorithm Parameters -| Name | Type | Description | Default value | -| :---------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| initial_covariance | double | Covariance of initial acceleration map (larger covariance makes the update speed faster) | 0.05 | -| velocity_min_threshold | double | Speeds smaller than this are not used for updating. | 0.1 | -| velocity_diff_threshold | double | When the velocity data is more than this threshold away from the grid reference speed (center value), the associated data is not used for updating. | 0.556 | -| max_steer_threshold | double | If the steer angle is greater than this value, the associated data is not used for updating. | 0.2 | -| max_pitch_threshold | double | If the pitch angle is greater than this value, the associated data is not used for updating. | 0.02 | -| max_jerk_threshold | double | If the ego jerk calculated from ego acceleration is greater than this value, the associated data is not used for updating. | 0.7 | -| pedal_velocity_thresh | double | If the pedal moving speed is greater than this value, the associated data is not used for updating. | 0.15 | -| pedal_diff_threshold | double | If the current pedal value is more then this threshold away from the previous value, the associated data is not used for updating. | 0.03 | -| max_accel | double | Maximum value of acceleration calculated from velocity source. | 5.0 | -| min_accel | double | Minimum value of acceleration calculated from velocity source. | -5.0 | -| pedal_to_accel_delay | double | The delay time between actuation_cmd to acceleration, considered in the update logic. | 0.3 | -| update_suggest_thresh | double | threshold of RMSE ratio that update suggest flag becomes true. ( RMSE ratio: [RMSE of new map] / [RMSE of original map] ) | 0.7 | -| max_data_count | int | For visualization. When the data num of each grid gets this value, the grid color gets red. | 100 | +| Name | Type | Description | Default value | +| :----------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| initial_covariance | double | Covariance of initial acceleration map (larger covariance makes the update speed faster) | 0.05 | +| velocity_min_threshold | double | Speeds smaller than this are not used for updating. | 0.1 | +| velocity_diff_threshold | double | When the velocity data is more than this threshold away from the grid reference speed (center value), the associated data is not used for updating. | 0.556 | +| max_steer_threshold | double | If the steer angle is greater than this value, the associated data is not used for updating. | 0.2 | +| max_pitch_threshold | double | If the pitch angle is greater than this value, the associated data is not used for updating. | 0.02 | +| max_jerk_threshold | double | If the ego jerk calculated from ego acceleration is greater than this value, the associated data is not used for updating. | 0.7 | +| pedal_velocity_thresh | double | If the pedal moving speed is greater than this value, the associated data is not used for updating. | 0.15 | +| pedal_diff_threshold | double | If the current pedal value is more then this threshold away from the previous value, the associated data is not used for updating. | 0.03 | +| max_accel | double | Maximum value of acceleration calculated from velocity source. | 5.0 | +| min_accel | double | Minimum value of acceleration calculated from velocity source. | -5.0 | +| pedal_to_accel_delay | double | The delay time between actuation_cmd to acceleration, considered in the update logic. | 0.3 | +| update_suggest_thresh | double | threshold of RMSE ratio that update suggest flag becomes true. ( RMSE ratio: [RMSE of new map] / [RMSE of original map] ) | 0.7 | +| max_data_count | int | For visualization. When the data num of each grid gets this value, the grid color gets red. | 100 | +| accel_brake_value_source | string | Whether to use actuation_status or actuation_command as accel/brake sources. value | status | ## Test utility scripts @@ -212,9 +213,9 @@ Update by Recursive Least Squares(RLS) method using data close enough to each gr Data selection is determined by the following thresholds. | Name | Default Value | -| -------- | -------- | -|velocity_diff_threshold|0.556| -|pedal_diff_threshold|0.03| +| ----------------------- | ------------- | +| velocity_diff_threshold | 0.556 | +| pedal_diff_threshold | 0.03 | #### Update formula diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml index 6cb118827e8b8..c7ee0a3a62330 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml @@ -17,3 +17,4 @@ update_method: "update_offset_four_cell_around" # or "update_offset_each_cell", "update_offset_total", "update_offset_four_cell_around" update_suggest_thresh: 0.7 # threshold of rmse rate that update suggest flag becomes true. ( rmse_rate: [rmse of update map] / [rmse of original map] ) progress_file_output: false # flag to output log file + accel_brake_value_source: "status" # "status" or "command" 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 e7d6be502285f..e2fc1b3a37362 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 @@ -41,6 +41,7 @@ #include "tier4_external_api_msgs/msg/calibration_status.hpp" #include "tier4_external_api_msgs/msg/calibration_status_array.hpp" #include "tier4_external_api_msgs/srv/get_accel_brake_map_calibration_data.hpp" +#include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp" #include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp" #include "tier4_vehicle_msgs/srv/update_accel_brake_map.hpp" @@ -64,6 +65,7 @@ using std_msgs::msg::Float32MultiArray; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Float32Stamped; using tier4_external_api_msgs::msg::CalibrationStatus; +using tier4_vehicle_msgs::msg::ActuationCommandStamped; using tier4_vehicle_msgs::msg::ActuationStatusStamped; using visualization_msgs::msg::MarkerArray; @@ -107,6 +109,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node rclcpp::Subscription::SharedPtr velocity_sub_; rclcpp::Subscription::SharedPtr steer_sub_; rclcpp::Subscription::SharedPtr actuation_status_sub_; + rclcpp::Subscription::SharedPtr actuation_cmd_sub_; // Service rclcpp::Service::SharedPtr update_map_dir_server_; @@ -132,6 +135,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node int get_pitch_method_; int update_method_; + int accel_brake_value_source_; double acceleration_ = 0.0; double acceleration_time_; double pre_acceleration_ = 0.0; @@ -239,6 +243,9 @@ class AccelBrakeMapCalibrator : public rclcpp::Node const int brake_pedal_index, const int brake_vel_index, const double measured_acc, const double map_acc); void updateTotalMapOffset(const double measured_acc, const double map_acc); + void callbackActuation( + const std_msgs::msg::Header header, const double accel, const double brake); + void callbackActuationCommand(const ActuationCommandStamped::ConstSharedPtr msg); void callbackActuationStatus(const ActuationStatusStamped::ConstSharedPtr msg); void callbackVelocity(const VelocityReport::ConstSharedPtr msg); void callbackSteer(const SteeringReport::ConstSharedPtr msg); @@ -357,6 +364,11 @@ class AccelBrakeMapCalibrator : public rclcpp::Node UPDATE_OFFSET_FOUR_CELL_AROUND = 2, }; + enum ACCEL_BRAKE_SOURCE { + STATUS = 0, + COMMAND = 1, + }; + public: explicit AccelBrakeMapCalibrator(const rclcpp::NodeOptions & node_options); }; diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml index 69a65a8d540a2..c664158a471a7 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml @@ -16,6 +16,7 @@ + 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 e2707a51160b3..1910631b11e53 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 @@ -59,6 +59,18 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod RCLCPP_ERROR_STREAM(get_logger(), "update_method_ is wrong. (available method: tf, file, none"); return; } + const auto accel_brake_value_source_str = + declare_parameter("accel_brake_value_source", std::string("status")); + if (accel_brake_value_source_str == std::string("status")) { + accel_brake_value_source_ = ACCEL_BRAKE_SOURCE::STATUS; + } else if (accel_brake_value_source_str == std::string("command")) { + accel_brake_value_source_ = ACCEL_BRAKE_SOURCE::COMMAND; + } else { + RCLCPP_ERROR_STREAM( + get_logger(), "accel_brake_value_source is wrong. (available source: status, command"); + return; + } + update_suggest_thresh_ = declare_parameter("update_suggest_thresh", 0.7); csv_calibrated_map_dir_ = declare_parameter("csv_calibrated_map_dir", std::string("")); output_accel_file_ = csv_calibrated_map_dir_ + "/accel_map.csv"; @@ -201,9 +213,16 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod std::bind(&AccelBrakeMapCalibrator::callbackVelocity, this, _1)); steer_sub_ = create_subscription( "~/input/steer", queue_size, std::bind(&AccelBrakeMapCalibrator::callbackSteer, this, _1)); - actuation_status_sub_ = create_subscription( - "~/input/actuation_status", queue_size, - std::bind(&AccelBrakeMapCalibrator::callbackActuationStatus, this, _1)); + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) { + actuation_status_sub_ = create_subscription( + "~/input/actuation_status", queue_size, + std::bind(&AccelBrakeMapCalibrator::callbackActuationStatus, this, _1)); + } + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) { + actuation_cmd_sub_ = create_subscription( + "~/input/actuation_cmd", queue_size, + std::bind(&AccelBrakeMapCalibrator::callbackActuationCommand, this, _1)); + } // Service update_map_dir_server_ = create_service( @@ -481,12 +500,11 @@ void AccelBrakeMapCalibrator::callbackSteer(const SteeringReport::ConstSharedPtr steer_ptr_ = msg; } -void AccelBrakeMapCalibrator::callbackActuationStatus( - const ActuationStatusStamped::ConstSharedPtr msg) +void AccelBrakeMapCalibrator::callbackActuation( + const std_msgs::msg::Header header, const double accel, const double brake) { // get accel data - accel_pedal_ptr_ = - std::make_shared(msg->status.accel_status, rclcpp::Time(msg->header.stamp)); + accel_pedal_ptr_ = std::make_shared(accel, rclcpp::Time(header.stamp)); if (!accel_pedal_vec_.empty()) { const auto past_accel_ptr = getNearestTimeDataFromVec(accel_pedal_ptr_, dif_pedal_time_, accel_pedal_vec_); @@ -502,8 +520,7 @@ void AccelBrakeMapCalibrator::callbackActuationStatus( getNearestTimeDataFromVec(accel_pedal_ptr_, pedal_to_accel_delay_, accel_pedal_vec_); // get brake data - brake_pedal_ptr_ = - std::make_shared(msg->status.brake_status, rclcpp::Time(msg->header.stamp)); + brake_pedal_ptr_ = std::make_shared(brake, rclcpp::Time(header.stamp)); if (!brake_pedal_vec_.empty()) { const auto past_brake_ptr = getNearestTimeDataFromVec(brake_pedal_ptr_, dif_pedal_time_, brake_pedal_vec_); @@ -519,6 +536,24 @@ void AccelBrakeMapCalibrator::callbackActuationStatus( getNearestTimeDataFromVec(brake_pedal_ptr_, pedal_to_accel_delay_, brake_pedal_vec_); } +void AccelBrakeMapCalibrator::callbackActuationCommand( + const ActuationCommandStamped::ConstSharedPtr msg) +{ + const auto header = msg->header; + const auto accel = msg->actuation.accel_cmd; + const auto brake = msg->actuation.brake_cmd; + callbackActuation(header, accel, brake); +} + +void AccelBrakeMapCalibrator::callbackActuationStatus( + const ActuationStatusStamped::ConstSharedPtr msg) +{ + const auto header = msg->header; + const auto accel = msg->status.accel_status; + const auto brake = msg->status.brake_status; + callbackActuation(header, accel, brake); +} + bool AccelBrakeMapCalibrator::callbackUpdateMapService( [[maybe_unused]] const std::shared_ptr request_header, UpdateAccelBrakeMap::Request::SharedPtr req, UpdateAccelBrakeMap::Response::SharedPtr res) From 6b436ded04a56c1eaee24a16c63390efac678aa3 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 22 Mar 2023 17:46:48 +0900 Subject: [PATCH 071/121] chore(tier4_localization_launch): add maintainer (#3133) Signed-off-by: kminoda --- launch/tier4_localization_launch/package.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 13102ea5f9b70..7c15e1be21be8 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -5,6 +5,9 @@ 0.1.0 The tier4_localization_launch package Yamato Ando + Koji Minoda + Kento Yabuuchi + Ryu Yamamoto Apache License 2.0 Yamato Ando From 94073e963d6356178e1c64c0efd06c5510695bd9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 22 Mar 2023 23:09:41 +0900 Subject: [PATCH 072/121] feat(obstacle_avoidance_planner): visualize bounds (#3094) Signed-off-by: Takayuki Murooka --- .../src/debug_marker.cpp | 44 +++++++++++++++++-- 1 file changed, 41 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/debug_marker.cpp b/planning/obstacle_avoidance_planner/src/debug_marker.cpp index a8af96e7b49de..2b0ddbed8fbba 100644 --- a/planning/obstacle_avoidance_planner/src/debug_marker.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_marker.cpp @@ -72,7 +72,7 @@ MarkerArray getFootprintsMarkerArray( return marker_array; } -MarkerArray getBoundsLineMarkerArray( +MarkerArray getBoundsWidthMarkerArray( const std::vector & ref_points, const double vehicle_width, const size_t sampling_num) { @@ -141,6 +141,40 @@ MarkerArray getBoundsLineMarkerArray( return marker_array; } +MarkerArray getBoundsLineMarkerArray( + const std::vector & ref_points, const double vehicle_width) +{ + MarkerArray marker_array; + + if (ref_points.empty()) return marker_array; + + auto ub_marker = createDefaultMarker( + "map", rclcpp::Clock().now(), "left_bounds", 0, Marker::LINE_STRIP, + createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(0.0, 1.0, 1.0, 0.8)); + ub_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + + auto lb_marker = createDefaultMarker( + "map", rclcpp::Clock().now(), "right_bounds", 0, Marker::LINE_STRIP, + createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(0.0, 1.0, 1.0, 0.8)); + lb_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + + for (size_t i = 0; i < ref_points.size(); i++) { + const geometry_msgs::msg::Pose & pose = ref_points.at(i).pose; + + const double ub_y = ref_points.at(i).bounds.upper_bound + vehicle_width / 2.0; + const auto ub = tier4_autoware_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; + ub_marker.points.push_back(ub); + + const double lb_y = ref_points.at(i).bounds.lower_bound - vehicle_width / 2.0; + const auto lb = tier4_autoware_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; + lb_marker.points.push_back(lb); + } + marker_array.markers.push_back(ub_marker); + marker_array.markers.push_back(lb_marker); + + return marker_array; +} + MarkerArray getVehicleCircleLinesMarkerArray( const std::vector & ref_points, const std::vector & vehicle_circle_longitudinal_offsets, const double vehicle_width, @@ -308,9 +342,13 @@ MarkerArray getDebugMarker( getFootprintsMarkerArray(optimized_points, vehicle_info, debug_data.mpt_visualize_sampling_num), &marker_array); - // bounds + // bounds lines + appendMarkerArray( + getBoundsLineMarkerArray(debug_data.ref_points, vehicle_info.vehicle_width_m), &marker_array); + + // bounds width appendMarkerArray( - getBoundsLineMarkerArray( + getBoundsWidthMarkerArray( debug_data.ref_points, vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num), &marker_array); From fcbb3743ec9c5e3906bddeb762a3fcae4a5e6a22 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 23 Mar 2023 10:03:37 +0800 Subject: [PATCH 073/121] feat(lane change): support new framework external request (#3068) * feat(lane change): support new framework external request Signed-off-by: Muhammad Zulfaqar Azmi * include direction in some of the function. Signed-off-by: Muhammad Zulfaqar Azmi * Fix the left lane change not working Signed-off-by: Muhammad Zulfaqar Azmi * fix naming Signed-off-by: Muhammad Zulfaqar Azmi * common function Signed-off-by: Muhammad Zulfaqar * style(pre-commit): autofix --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/behavior_path_planner/CMakeLists.txt | 2 +- .../behavior_path_planner/parameters.hpp | 4 +- .../external_request_lane_change_module.hpp | 3 + .../lane_change/lane_change_module.hpp | 6 +- .../scene_module/lane_change/manager.hpp | 7 +- .../scene_module/scene_module_visitor.hpp | 7 ++ .../lane_change/lane_change_module_data.hpp | 5 +- .../util/lane_change/util.hpp | 16 ++++- .../src/behavior_path_planner_node.cpp | 63 +++++++++++++---- .../external_request_lane_change_module.cpp | 2 + .../lane_change/lane_change_module.cpp | 41 +++++++---- .../src/scene_module/lane_change/manager.cpp | 7 +- .../src/util/lane_change/util.cpp | 68 ++++++++++++++++++- .../include/route_handler/route_handler.hpp | 7 +- planning/route_handler/src/route_handler.cpp | 45 +++++++++--- 15 files changed, 226 insertions(+), 57 deletions(-) diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index f7b6c7150de50..8bd768affd3bc 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -20,6 +20,7 @@ set(common_src src/scene_module/pull_over/pull_over_module.cpp src/scene_module/side_shift/side_shift_module.cpp src/scene_module/lane_change/lane_change_module.cpp + src/scene_module/lane_change/external_request_lane_change_module.cpp src/turn_signal_decider.cpp src/util/avoidance/util.cpp src/util/lane_change/util.cpp @@ -49,7 +50,6 @@ if(COMPILE_WITH_OLD_ARCHITECTURE) src/behavior_tree_manager.cpp src/scene_module/scene_module_bt_node_interface.cpp src/scene_module/lane_following/lane_following_module.cpp - src/scene_module/lane_change/external_request_lane_change_module.cpp src/scene_module/pull_over/pull_over_module.cpp ${common_src} ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 8277ae102b312..4630f2f324e84 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -35,8 +35,8 @@ struct BehaviorPathPlannerParameters ModuleConfigParameters config_side_shift; ModuleConfigParameters config_lane_change_left; ModuleConfigParameters config_lane_change_right; - ModuleConfigParameters config_external_lane_change_left; - ModuleConfigParameters config_external_lane_change_right; + ModuleConfigParameters config_ext_request_lane_change_left; + ModuleConfigParameters config_ext_request_lane_change_right; double backward_path_length; double forward_path_length; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request_lane_change_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request_lane_change_module.hpp index 6b239fd2bc675..77f5c8cd4dc79 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request_lane_change_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request_lane_change_module.hpp @@ -47,6 +47,8 @@ using marker_utils::CollisionCheckDebug; using tier4_planning_msgs::msg::LaneChangeDebugMsg; using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; +#ifdef USE_OLD_ARCHITECTURE + class ExternalRequestLaneChangeModule : public SceneModuleInterface { public: @@ -151,6 +153,7 @@ class ExternalRequestLaneChangeLeftModule : public ExternalRequestLaneChangeModu const std::string & name, rclcpp::Node & node, std::shared_ptr parameters); }; +#endif } // namespace behavior_path_planner // clang-format off diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp index bbdc7c14435d7..12f9c1155e423 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp @@ -60,7 +60,8 @@ class LaneChangeModule : public SceneModuleInterface LaneChangeModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & rtc_interface, Direction direction); + const std::shared_ptr & rtc_interface, Direction direction, + LaneChangeModuleType type); #endif bool isExecutionRequested() const override; bool isExecutionReady() const override; @@ -135,6 +136,7 @@ class LaneChangeModule : public SceneModuleInterface UUID candidate_uuid_; #else Direction direction_{Direction::NONE}; + LaneChangeModuleType type_{LaneChangeModuleType::NORMAL}; #endif void resetParameters(); @@ -198,8 +200,10 @@ class LaneChangeModule : public SceneModuleInterface #endif PathWithLaneId getReferencePath() const; +#ifdef USE_OLD_ARCHITECTURE lanelet::ConstLanelets getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length) const; +#endif std::pair getSafePath( const lanelet::ConstLanelets & lane_change_lanes, const double check_distance, LaneChangePath & safe_path) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index ecb2164855bb0..666a8c54ddd32 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -33,12 +33,13 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface public: LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters, Direction direction); + std::shared_ptr parameters, const Direction direction, + const LaneChangeModuleType type); std::shared_ptr createNewSceneModuleInstance() override { return std::make_shared( - name_, *node_, parameters_, rtc_interface_, direction_); + name_, *node_, parameters_, rtc_interface_, direction_, type_); } void updateModuleParams(const std::vector & parameters) override; @@ -51,6 +52,8 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface std::vector> registered_modules_; Direction direction_; + + LaneChangeModuleType type_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp index ee7789c4040af..a5f74529cc073 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp @@ -28,7 +28,9 @@ namespace behavior_path_planner // Forward Declaration class AvoidanceModule; class LaneChangeModule; +#ifdef USE_OLD_ARCHITECTURE class ExternalRequestLaneChangeModule; +#endif class LaneFollowingModule; class PullOutModule; class PullOverModule; @@ -43,7 +45,9 @@ class SceneModuleVisitor { public: void visitLaneChangeModule(const LaneChangeModule * module) const; +#ifdef USE_OLD_ARCHITECTURE void visitExternalRequestLaneChangeModule(const ExternalRequestLaneChangeModule * module) const; +#endif void visitAvoidanceModule(const AvoidanceModule * module) const; std::shared_ptr getAvoidanceModuleDebugMsg() const; @@ -51,7 +55,10 @@ class SceneModuleVisitor protected: mutable std::shared_ptr lane_change_visitor_; + +#ifdef USE_OLD_ARCHITECTURE mutable std::shared_ptr ext_request_lane_change_visitor_; +#endif mutable std::shared_ptr avoidance_visitor_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp index 7ef20d546327b..cc5efbc835e84 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/lane_change_module_data.hpp @@ -80,10 +80,7 @@ struct LaneChangeTargetObjectIndices std::vector other_lane{}; }; -enum class LaneChangeType { - Normal = 0, - ExternalRequest = 1, -}; +enum class LaneChangeModuleType { NORMAL = 0, EXTERNAL_REQUEST }; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__UTIL__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp index 679f1ae230f1c..91ce7293cda39 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/util/lane_change/util.hpp @@ -80,7 +80,7 @@ std::pair getLaneChangePaths( const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, const Pose & pose, const Twist & twist, const PredictedObjects::ConstSharedPtr dynamic_objects, const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter, - const double check_distance, LaneChangePaths * candidate_paths, + const double check_distance, const Direction direction, LaneChangePaths * candidate_paths, std::unordered_map * debug_data); bool isLaneChangePathSafe( @@ -93,10 +93,18 @@ bool isLaneChangePathSafe( std::unordered_map & debug_data, const double acceleration = 0.0); +#ifdef USE_OLD_ARCHITECTURE bool hasEnoughDistance( const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const Pose & goal_pose, const RouteHandler & route_handler, const double minimum_lane_change_length); +#else +bool hasEnoughDistance( + const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const Pose & goal_pose, + const RouteHandler & route_handler, const double minimum_lane_change_length, + const Direction direction); +#endif ShiftLine getLaneChangingShiftLine( const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, @@ -159,7 +167,11 @@ LaneChangeTargetObjectIndices filterObjectIndices( double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer = 0.0); -std::string getStrDirection(const std::string name, const Direction direction); +std::string getStrDirection(const std::string & name, const Direction direction); +lanelet::ConstLanelets getLaneChangeLanes( + const std::shared_ptr & planner_data, + const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length, + const double prepare_duration, const Direction direction, const LaneChangeModuleType type); } // namespace behavior_path_planner::lane_change_utils #endif // BEHAVIOR_PATH_PLANNER__UTIL__LANE_CHANGE__UTIL_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 be99d578e1856..041bf25c86df8 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -204,6 +204,15 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod planner_manager_ = std::make_shared(*this, lane_following_param_ptr_, p.verbose); + const auto register_and_create_publisher = [&](const auto & manager) { + const auto & module_name = manager->getModuleName(); + planner_manager_->registerSceneModuleManager(manager); + path_candidate_publishers_.emplace( + module_name, create_publisher(path_candidate_name_space + module_name, 1)); + path_reference_publishers_.emplace( + module_name, create_publisher(path_reference_name_space + module_name, 1)); + }; + if (p.config_pull_out.enable_module) { auto manager = std::make_shared( this, "pull_out", p.config_pull_out, pull_out_param_ptr_); @@ -238,24 +247,32 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const std::string module_topic = "lane_change_left"; auto manager = std::make_shared( this, module_topic, p.config_lane_change_left, lane_change_param_ptr_, - route_handler::Direction::LEFT); - planner_manager_->registerSceneModuleManager(manager); - path_candidate_publishers_.emplace( - module_topic, create_publisher(path_candidate_name_space + module_topic, 1)); - path_reference_publishers_.emplace( - module_topic, create_publisher(path_reference_name_space + module_topic, 1)); + route_handler::Direction::LEFT, LaneChangeModuleType::NORMAL); + register_and_create_publisher(manager); } if (p.config_lane_change_right.enable_module) { const std::string module_topic = "lane_change_right"; auto manager = std::make_shared( this, module_topic, p.config_lane_change_right, lane_change_param_ptr_, - route_handler::Direction::RIGHT); - planner_manager_->registerSceneModuleManager(manager); - path_candidate_publishers_.emplace( - module_topic, create_publisher(path_candidate_name_space + module_topic, 1)); - path_reference_publishers_.emplace( - module_topic, create_publisher(path_reference_name_space + module_topic, 1)); + route_handler::Direction::RIGHT, LaneChangeModuleType::NORMAL); + register_and_create_publisher(manager); + } + + if (p.config_ext_request_lane_change_right.enable_module) { + const std::string module_topic = "ext_request_lane_change_right"; + auto manager = std::make_shared( + this, module_topic, p.config_ext_request_lane_change_right, lane_change_param_ptr_, + route_handler::Direction::RIGHT, LaneChangeModuleType::EXTERNAL_REQUEST); + register_and_create_publisher(manager); + } + + if (p.config_ext_request_lane_change_left.enable_module) { + const std::string module_topic = "ext_request_lane_change_left"; + auto manager = std::make_shared( + this, module_topic, p.config_ext_request_lane_change_left, lane_change_param_ptr_, + route_handler::Direction::LEFT, LaneChangeModuleType::EXTERNAL_REQUEST); + register_and_create_publisher(manager); } if (p.config_avoidance.enable_module) { @@ -346,6 +363,28 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.config_lane_change_right.max_module_size = declare_parameter(ns + "max_module_size"); } + { + const std::string ns = "ext_request_lane_change_right."; + p.config_ext_request_lane_change_right.enable_module = + declare_parameter(ns + "enable_module"); + p.config_ext_request_lane_change_right.enable_simultaneous_execution = + declare_parameter(ns + "enable_simultaneous_execution"); + p.config_ext_request_lane_change_right.priority = declare_parameter(ns + "priority"); + p.config_ext_request_lane_change_right.max_module_size = + declare_parameter(ns + "max_module_size"); + } + + { + const std::string ns = "ext_request_lane_change_left."; + p.config_ext_request_lane_change_left.enable_module = + declare_parameter(ns + "enable_module"); + p.config_ext_request_lane_change_left.enable_simultaneous_execution = + declare_parameter(ns + "enable_simultaneous_execution"); + p.config_ext_request_lane_change_left.priority = declare_parameter(ns + "priority"); + p.config_ext_request_lane_change_left.max_module_size = + declare_parameter(ns + "max_module_size"); + } + { const std::string ns = "avoidance."; p.config_avoidance.enable_module = declare_parameter(ns + "enable_module"); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp index 3a55935b641e1..78bd5daa0bcd2 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/external_request_lane_change_module.cpp @@ -32,6 +32,7 @@ #include namespace behavior_path_planner { +#ifdef USE_OLD_ARCHITECTURE std::string getTopicName(const ExternalRequestLaneChangeModule::Direction & direction) { const std::string direction_name = @@ -771,5 +772,6 @@ ExternalRequestLaneChangeLeftModule::ExternalRequestLaneChangeLeftModule( : ExternalRequestLaneChangeModule{name, node, parameters, Direction::LEFT} { } +#endif } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index 99c0ff5ddd467..3b931eb7f57af 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -51,11 +51,12 @@ LaneChangeModule::LaneChangeModule( LaneChangeModule::LaneChangeModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & rtc_interface, Direction direction) -: SceneModuleInterface{name, node}, parameters_{parameters}, direction_{direction} + const std::shared_ptr & rtc_interface, Direction direction, + LaneChangeModuleType type) +: SceneModuleInterface{name, node}, parameters_{parameters}, direction_{direction}, type_{type} { rtc_interface_ptr_ = rtc_interface; - steering_factor_interface_ptr_ = std::make_unique(&node, "lane_change"); + steering_factor_interface_ptr_ = std::make_unique(&node, name); } #endif @@ -87,11 +88,14 @@ bool LaneChangeModule::isExecutionRequested() const #ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); + const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); #else const auto current_lanes = util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); + const auto lane_change_lanes = lane_change_utils::getLaneChangeLanes( + planner_data_, current_lanes, lane_change_lane_length_, + parameters_->lane_change_prepare_duration, direction_, type_); #endif - const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); if (lane_change_lanes.empty()) { return false; @@ -112,11 +116,14 @@ bool LaneChangeModule::isExecutionReady() const #ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); + const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); #else const auto current_lanes = util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); + const auto lane_change_lanes = lane_change_utils::getLaneChangeLanes( + planner_data_, current_lanes, lane_change_lane_length_, + parameters_->lane_change_prepare_duration, direction_, type_); #endif - const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); if (lane_change_lanes.empty()) { return false; @@ -249,11 +256,14 @@ CandidateOutput LaneChangeModule::planCandidate() const // Get lane change lanes #ifdef USE_OLD_ARCHITECTURE const auto current_lanes = util::getCurrentLanes(planner_data_); + const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); #else const auto current_lanes = util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); + const auto lane_change_lanes = lane_change_utils::getLaneChangeLanes( + planner_data_, current_lanes, lane_change_lane_length_, + parameters_->lane_change_prepare_duration, direction_, type_); #endif - const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_); if (lane_change_lanes.empty()) { return output; @@ -326,11 +336,14 @@ void LaneChangeModule::updateLaneChangeStatus() { #ifdef USE_OLD_ARCHITECTURE status_.current_lanes = util::getCurrentLanes(planner_data_); + status_.lane_change_lanes = getLaneChangeLanes(status_.current_lanes, lane_change_lane_length_); #else status_.current_lanes = util::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); + status_.lane_change_lanes = lane_change_utils::getLaneChangeLanes( + planner_data_, status_.current_lanes, lane_change_lane_length_, + parameters_->lane_change_prepare_duration, direction_, type_); #endif - status_.lane_change_lanes = getLaneChangeLanes(status_.current_lanes, lane_change_lane_length_); // Find lane change path LaneChangePath selected_path; @@ -402,6 +415,7 @@ PathWithLaneId LaneChangeModule::getReferencePath() const return reference_path; } +#ifdef USE_OLD_ARCHITECTURE lanelet::ConstLanelets LaneChangeModule::getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length) const { @@ -423,20 +437,17 @@ lanelet::ConstLanelets LaneChangeModule::getLaneChangeLanes( std::max(current_twist.linear.x * lane_change_prepare_duration, minimum_lane_change_length); lanelet::ConstLanelets current_check_lanes = route_handler->getLaneletSequence(current_lane, current_pose, 0.0, lane_change_prepare_length); - lanelet::ConstLanelet lane_change_lane; -#ifdef USE_OLD_ARCHITECTURE - if (route_handler->getLaneChangeTarget(current_check_lanes, &lane_change_lane)) { -#else - if (route_handler->getLaneChangeTarget(current_check_lanes, &lane_change_lane, direction_)) { -#endif + const auto lane_change_lane = route_handler->getLaneChangeTarget(current_check_lanes); + if (lane_change_lane) { lane_change_lanes = route_handler->getLaneletSequence( - lane_change_lane, current_pose, lane_change_lane_length, lane_change_lane_length); + lane_change_lane.get(), current_pose, lane_change_lane_length, lane_change_lane_length); } else { lane_change_lanes.clear(); } return lane_change_lanes; } +#endif std::pair LaneChangeModule::getSafePath( const lanelet::ConstLanelets & lane_change_lanes, const double check_distance, @@ -469,7 +480,7 @@ std::pair LaneChangeModule::getSafePath( const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths( *getPreviousModuleOutput().path, *route_handler, current_lanes, lane_change_lanes, current_pose, current_twist, planner_data_->dynamic_object, common_parameters, *parameters_, check_distance, - &valid_paths, &object_debug_); + direction_, &valid_paths, &object_debug_); #endif debug_valid_path_ = valid_paths; 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 13bb4c7db5b4c..458ab20970e37 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 @@ -26,10 +26,13 @@ namespace behavior_path_planner using route_handler::Direction; LaneChangeModuleManager::LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters, Direction direction) + std::shared_ptr parameters, const Direction direction, + const LaneChangeModuleType type) : SceneModuleManagerInterface(node, name, config), parameters_{std::move(parameters)}, - direction_{direction} + direction_{direction}, + type_{type} + { rtc_interface_ = std::make_shared(node, name); } diff --git a/planning/behavior_path_planner/src/util/lane_change/util.cpp b/planning/behavior_path_planner/src/util/lane_change/util.cpp index fd9c31f3a617e..5f9fd8dc8bb16 100644 --- a/planning/behavior_path_planner/src/util/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/util/lane_change/util.cpp @@ -268,7 +268,7 @@ std::pair getLaneChangePaths( const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, const Pose & pose, const Twist & twist, const PredictedObjects::ConstSharedPtr dynamic_objects, const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter, - const double check_distance, LaneChangePaths * candidate_paths, + const double check_distance, const Direction direction, LaneChangePaths * candidate_paths, std::unordered_map * debug_data) #endif { @@ -296,9 +296,15 @@ std::pair getLaneChangePaths( const auto target_distance = util::getArcLengthToTargetLanelet(original_lanelets, target_lanelets.front(), pose); +#ifdef USE_OLD_ARCHITECTURE const auto num_to_preferred_lane = std::abs(route_handler.getNumLaneToPreferredLane(target_lanelets.back())); - +#else + const auto get_opposite_direction = + (direction == Direction::RIGHT) ? Direction::LEFT : Direction::RIGHT; + const auto num_to_preferred_lane = std::abs( + route_handler.getNumLaneToPreferredLane(target_lanelets.back(), get_opposite_direction)); +#endif const auto goal_pose = route_handler.getGoalPose(); const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanelets.back()); @@ -405,9 +411,15 @@ std::pair getLaneChangePaths( continue; } +#ifdef USE_OLD_ARCHITECTURE const auto is_valid = hasEnoughDistance( *candidate_path, original_lanelets, target_lanelets, pose, goal_pose, route_handler, common_parameter.minimum_lane_change_length); +#else + const auto is_valid = hasEnoughDistance( + *candidate_path, original_lanelets, target_lanelets, pose, goal_pose, route_handler, + common_parameter.minimum_lane_change_length, direction); +#endif if (!is_valid) { continue; @@ -445,14 +457,26 @@ std::pair getLaneChangePaths( return {true, false}; } +#ifdef USE_OLD_ARCHITECTURE bool hasEnoughDistance( const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes, [[maybe_unused]] const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const Pose & goal_pose, const RouteHandler & route_handler, const double minimum_lane_change_length) +#else +bool hasEnoughDistance( + const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes, + [[maybe_unused]] const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, + const Pose & goal_pose, const RouteHandler & route_handler, + const double minimum_lane_change_length, const Direction direction) +#endif { const double lane_change_total_distance = path.length.sum(); +#ifdef USE_OLD_ARCHITECTURE const int num = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back())); +#else + const int num = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); +#endif const auto overall_graphs = route_handler.getOverallGraphPtr(); const double lane_change_required_distance = @@ -1153,4 +1177,44 @@ std::string getStrDirection(const std::string & name, const Direction direction) } return ""; } + +lanelet::ConstLanelets getLaneChangeLanes( + const std::shared_ptr & planner_data, + const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length, + const double prepare_duration, const Direction direction, const LaneChangeModuleType type) +{ + const auto & route_handler = planner_data->route_handler; + const auto minimum_lane_change_length = planner_data->parameters.minimum_lane_change_length; + const auto current_pose = planner_data->self_odometry->pose.pose; + const auto current_speed = planner_data->self_odometry->twist.twist.linear.x; + + if (current_lanes.empty()) { + return {}; + } + + // Get lane change lanes + lanelet::ConstLanelet current_lane; + lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, ¤t_lane); + + const auto lane_change_prepare_length = + std::max(current_speed * prepare_duration, minimum_lane_change_length); + + const auto current_check_lanes = + route_handler->getLaneletSequence(current_lane, current_pose, 0.0, lane_change_prepare_length); + + const auto lane_change_lane = std::invoke([&]() { + if (type == LaneChangeModuleType::NORMAL) { + return route_handler->getLaneChangeTarget(current_check_lanes, direction); + } + + return route_handler->getLaneChangeTargetExceptPreferredLane(current_check_lanes, direction); + }); + + if (lane_change_lane) { + return route_handler->getLaneletSequence( + lane_change_lane.get(), current_pose, lane_change_lane_length, lane_change_lane_length); + } + + return {}; +} } // namespace behavior_path_planner::lane_change_utils diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 89e052b439f78..d72a11aa5ec98 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -296,9 +296,10 @@ class RouteHandler PathWithLaneId getCenterLinePath( const lanelet::ConstLanelets & lanelet_sequence, const double s_start, const double s_end, bool use_exact = true) const; - bool getLaneChangeTarget( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet, - const Direction direction = Direction::NONE) const; + boost::optional getLaneChangeTarget( + const lanelet::ConstLanelets & lanelets, const Direction direction = Direction::NONE) const; + boost::optional getLaneChangeTargetExceptPreferredLane( + const lanelet::ConstLanelets & lanelets, const Direction direction) const; bool getRightLaneChangeTargetExceptPreferredLane( const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; bool getLeftLaneChangeTargetExceptPreferredLane( diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 2fe8e3549b661..fc9cb719f9af5 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1105,9 +1105,8 @@ std::vector RouteHandler::getPrecedingLaneletSequence( routing_graph_ptr_, lanelet, length, exclude_lanelets); } -bool RouteHandler::getLaneChangeTarget( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet, - const Direction direction) const +boost::optional RouteHandler::getLaneChangeTarget( + const lanelet::ConstLanelets & lanelets, const Direction direction) const { for (const auto & lanelet : lanelets) { const int num = getNumLaneToPreferredLane(lanelet, direction); @@ -1118,9 +1117,7 @@ bool RouteHandler::getLaneChangeTarget( if (direction == Direction::NONE || direction == Direction::RIGHT) { if (num < 0) { if (!!routing_graph_ptr_->right(lanelet)) { - const auto right_lanelet = routing_graph_ptr_->right(lanelet); - *target_lanelet = right_lanelet.get(); - return true; + return routing_graph_ptr_->right(lanelet); } } } @@ -1128,16 +1125,42 @@ bool RouteHandler::getLaneChangeTarget( if (direction == Direction::NONE || direction == Direction::LEFT) { if (num > 0) { if (!!routing_graph_ptr_->left(lanelet)) { - const auto left_lanelet = routing_graph_ptr_->left(lanelet); - *target_lanelet = left_lanelet.get(); - return true; + return routing_graph_ptr_->left(lanelet); } } } } - *target_lanelet = lanelets.front(); - return false; + return boost::none; +} + +boost::optional RouteHandler::getLaneChangeTargetExceptPreferredLane( + const lanelet::ConstLanelets & lanelets, const Direction direction) const +{ + for (const auto & lanelet : lanelets) { + if (direction == Direction::RIGHT) { + // Get right lanelet if preferred lane is on the left + if (getNumLaneToPreferredLane(lanelet, direction) < 0) { + continue; + } + + if (!!routing_graph_ptr_->right(lanelet)) { + return routing_graph_ptr_->right(lanelet); + } + } + + if (direction == Direction::LEFT) { + // Get left lanelet if preferred lane is on the right + if (getNumLaneToPreferredLane(lanelet, direction) > 0) { + continue; + } + if (!!routing_graph_ptr_->left(lanelet)) { + return routing_graph_ptr_->left(lanelet); + } + } + } + + return boost::none; } bool RouteHandler::getRightLaneChangeTargetExceptPreferredLane( From de8cbdc82897db50e8e0cea4267aaf196d44a099 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 23 Mar 2023 11:35:56 +0900 Subject: [PATCH 074/121] feat(planning_test_manager): add planning interface test manager for some obstacle modules (#3076) * add planning_interface_test_manager class Signed-off-by: kyoichi-sugahara * add counter function Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * add interface test for motion_velocity_smoother Signed-off-by: kyoichi-sugahara * add param in default_motion_velocity_smoother,param.yaml Signed-off-by: kyoichi-sugahara * successfully launch target node Signed-off-by: kyoichi-sugahara * successfully build the test Signed-off-by: kyoichi-sugahara * add test for test_motion_velocity_smoother Signed-off-by: kyoichi-sugahara * add abnormal trajectory test Signed-off-by: kyoichi-sugahara * delete unnecessary part Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * style(pre-commit): autofix * run pre-commit Signed-off-by: kyoichi-sugahara * add declaration Signed-off-by: kyoichi-sugahara * refactor Signed-off-by: kyoichi-sugahara * refactor Signed-off-by: kyoichi-sugahara * Refactor callback functions for standardization Signed-off-by: kyoichi-sugahara * refacotoring Signed-off-by: kyoichi-sugahara * refactored Signed-off-by: kyoichi-sugahara * Refactor functions into a single template function Signed-off-by: kyoichi-sugahara * Refactor Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix * refactor Signed-off-by: kyoichi-sugahara * relete unnecessary definition Signed-off-by: kyoichi-sugahara * Revert "delete unnecessary definition" This reverts commit 6cd13f82868f34140fa1538d43f99d99b9648df3. Signed-off-by: kyoichi-sugahara * delete unnecessary definition Signed-off-by: kyoichi-sugahara * delete unnecessary definition Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * delete module dependent part Signed-off-by: kyoichi-sugahara * temp Signed-off-by: kyoichi-sugahara * delete unnecessary arg Signed-off-by: kyoichi-sugahara * apply motion_velocity_smoother change Signed-off-by: kyoichi-sugahara * add interface test for obstacle stop planner Signed-off-by: kyoichi-sugahara * run pre-commit Signed-off-by: kyoichi-sugahara * add test fot obstacle_cruise_planner Signed-off-by: kyoichi-sugahara * remove test for surround_obstacle_checker Signed-off-by: kyoichi-sugahara * fix bug Signed-off-by: kyoichi-sugahara * skip interface test for motion_velocity_smoother Signed-off-by: kyoichi-sugahara * change package name Signed-off-by: kyoichi-sugahara * apply change of package name Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../motion_velocity_smoother/CMakeLists.txt | 10 +- ...efault_motion_velocity_smoother.param.yaml | 6 + planning/motion_velocity_smoother/package.xml | 1 + ...otion_velocity_smoother_node_interface.cpp | 66 +++++++++ .../obstacle_cruise_planner/CMakeLists.txt | 6 + .../config/default_common.param.yaml | 15 +++ planning/obstacle_cruise_planner/package.xml | 2 + ...obstacle_cruise_planner_node_interface.cpp | 65 +++++++++ planning/obstacle_stop_planner/CMakeLists.txt | 9 ++ planning/obstacle_stop_planner/package.xml | 2 + ...t_obstacle_stop_planner_node_interface.cpp | 67 ++++++++++ planning/planning_test_utils/CMakeLists.txt | 12 ++ planning/planning_test_utils/README.md | 17 +++ .../planning_interface_test_manager.hpp | 112 ++++++++++++++++ .../planning_interface_test_manager_utils.hpp | 107 +++++++++++++++ planning/planning_test_utils/package.xml | 34 +++++ .../src/planning_interface_test_manager.cpp | 125 ++++++++++++++++++ 17 files changed, 654 insertions(+), 2 deletions(-) create mode 100644 planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp create mode 100644 planning/obstacle_cruise_planner/config/default_common.param.yaml create mode 100644 planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp create mode 100644 planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp create mode 100644 planning/planning_test_utils/CMakeLists.txt create mode 100644 planning/planning_test_utils/README.md create mode 100644 planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp create mode 100644 planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp create mode 100644 planning/planning_test_utils/package.xml create mode 100644 planning/planning_test_utils/src/planning_interface_test_manager.cpp diff --git a/planning/motion_velocity_smoother/CMakeLists.txt b/planning/motion_velocity_smoother/CMakeLists.txt index 64778b4b7ffbe..b69cf0d660a66 100644 --- a/planning/motion_velocity_smoother/CMakeLists.txt +++ b/planning/motion_velocity_smoother/CMakeLists.txt @@ -47,11 +47,17 @@ rclcpp_components_register_node(motion_velocity_smoother_node if(BUILD_TESTING) ament_add_ros_isolated_gmock(test_smoother_functions - test/test_smoother_functions.cpp + test/test_smoother_functions.cpp ) target_link_libraries(test_smoother_functions - smoother + smoother ) + # ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + # test/test_motion_velocity_smoother_node_interface.cpp + # ) + # target_link_libraries(test_${PROJECT_NAME} + # motion_velocity_smoother_node + # ) endif() diff --git a/planning/motion_velocity_smoother/config/default_motion_velocity_smoother.param.yaml b/planning/motion_velocity_smoother/config/default_motion_velocity_smoother.param.yaml index b2592316f658f..dd8e26a0f2d77 100644 --- a/planning/motion_velocity_smoother/config/default_motion_velocity_smoother.param.yaml +++ b/planning/motion_velocity_smoother/config/default_motion_velocity_smoother.param.yaml @@ -48,5 +48,11 @@ post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s] post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] + # steering angle rate limit parameters + max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] + resample_ds: 0.1 # distance between trajectory points [m] + curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] + curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m] + # system over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point diff --git a/planning/motion_velocity_smoother/package.xml b/planning/motion_velocity_smoother/package.xml index e5e25a55c4e19..dcbdbf8128b61 100644 --- a/planning/motion_velocity_smoother/package.xml +++ b/planning/motion_velocity_smoother/package.xml @@ -28,6 +28,7 @@ motion_utils nav_msgs osqp_interface + planning_test_utils rclcpp tf2 tf2_ros diff --git a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp new file mode 100644 index 0000000000000..c5a120756b2f4 --- /dev/null +++ b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp @@ -0,0 +1,66 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "motion_velocity_smoother/motion_velocity_smoother_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include + +TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInput) +{ + rclcpp::init(0, nullptr); + + auto test_manager = std::make_shared(); + + auto node_options = rclcpp::NodeOptions{}; + + test_manager->declareVehicleInfoParams(node_options); + test_manager->declareNearestSearchDistanceParams(node_options); + node_options.append_parameter_override("algorithm_type", "JerkFiltered"); + node_options.append_parameter_override("publish_debug_trajs", false); + + const auto motion_velocity_smoother_dir = + ament_index_cpp::get_package_share_directory("motion_velocity_smoother"); + + node_options.arguments( + {"--ros-args", "--params-file", + motion_velocity_smoother_dir + "/config/default_motion_velocity_smoother.param.yaml", + "--params-file", motion_velocity_smoother_dir + "/config/default_common.param.yaml", + "--params-file", motion_velocity_smoother_dir + "/config/JerkFiltered.param.yaml"}); + + auto test_target_node = + std::make_shared(node_options); + + // publish necessary topics from test_manager + test_manager->publishOdometry(test_target_node, "/localization/kinematic_state"); + test_manager->publishMaxVelocity( + test_target_node, "motion_velocity_smoother/input/external_velocity_limit_mps"); + + // set subscriber for test_target_node + test_manager->setTrajectorySubscriber("motion_velocity_smoother/output/trajectory"); + + // setting topic name of subscribing topic + test_manager->setTrajectoryInputTopicName("motion_velocity_smoother/input/trajectory"); + + // test for normal trajectory + ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test for trajectory with empty/one point/overlapping point + test_manager->testWithAbnormalTrajectory(test_target_node); +} diff --git a/planning/obstacle_cruise_planner/CMakeLists.txt b/planning/obstacle_cruise_planner/CMakeLists.txt index c14330fcdb928..3686b7b648c9d 100644 --- a/planning/obstacle_cruise_planner/CMakeLists.txt +++ b/planning/obstacle_cruise_planner/CMakeLists.txt @@ -24,6 +24,12 @@ rclcpp_components_register_node(obstacle_cruise_planner_core if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_${PROJECT_NAME}_node_interface.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + obstacle_cruise_planner_core + ) endif() ament_auto_package( diff --git a/planning/obstacle_cruise_planner/config/default_common.param.yaml b/planning/obstacle_cruise_planner/config/default_common.param.yaml new file mode 100644 index 0000000000000..6bb130e8052b0 --- /dev/null +++ b/planning/obstacle_cruise_planner/config/default_common.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # constraints param for normal driving + normal: + min_acc: -1.0 # min deceleration [m/ss] + max_acc: 1.0 # max acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] + + # constraints to be observed + limit: + min_acc: -2.5 # min deceleration limit [m/ss] + max_acc: 1.0 # max acceleration limit [m/ss] + min_jerk: -1.5 # min jerk limit [m/sss] + max_jerk: 1.5 # max jerk limit [m/sss] diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index dd294674bb160..a9c914f1bb6d5 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -26,6 +26,7 @@ nav_msgs osqp_interface perception_utils + planning_test_utils rclcpp rclcpp_components signal_processing @@ -38,6 +39,7 @@ vehicle_info_util visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp new file mode 100644 index 0000000000000..d018d309831df --- /dev/null +++ b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -0,0 +1,65 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "obstacle_cruise_planner/node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include + +TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInput) +{ + rclcpp::init(0, nullptr); + + auto test_manager = std::make_shared(); + + auto node_options = rclcpp::NodeOptions{}; + + test_manager->declareVehicleInfoParams(node_options); + test_manager->declareNearestSearchDistanceParams(node_options); + + const auto obstacle_cruise_planner_dir = + ament_index_cpp::get_package_share_directory("obstacle_cruise_planner"); + + node_options.arguments( + {"--ros-args", "--params-file", + obstacle_cruise_planner_dir + "/config/default_common.param.yaml", "--params-file", + obstacle_cruise_planner_dir + "/config/obstacle_cruise_planner.param.yaml"}); + + auto test_target_node = + std::make_shared(node_options); + + // publish necessary topics from test_manager + test_manager->publishOdometry(test_target_node, "obstacle_cruise_planner/input/odometry"); + test_manager->publishPointCloud(test_target_node, "obstacle_cruise_planner/input/vector_map"); + test_manager->publishPredictedObjects(test_target_node, "obstacle_cruise_planner/input/objects"); + test_manager->publishAcceleration(test_target_node, "obstacle_cruise_planner/input/acceleration"); + + // set subscriber for test_target_node + test_manager->setTrajectorySubscriber("obstacle_cruise_planner/output/trajectory"); + + // setting topic name of subscribing topic + test_manager->setTrajectoryInputTopicName("obstacle_cruise_planner/input/trajectory"); + + // test for normal trajectory + ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test for trajectory with empty/one point/overlapping point + test_manager->testWithAbnormalTrajectory(test_target_node); +} diff --git a/planning/obstacle_stop_planner/CMakeLists.txt b/planning/obstacle_stop_planner/CMakeLists.txt index 94048c6cbea65..a842aabd665b7 100644 --- a/planning/obstacle_stop_planner/CMakeLists.txt +++ b/planning/obstacle_stop_planner/CMakeLists.txt @@ -32,6 +32,15 @@ rclcpp_components_register_node(obstacle_stop_planner EXECUTABLE obstacle_stop_planner_node ) +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_${PROJECT_NAME}_node_interface.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) +endif() + ament_auto_package( INSTALL_TO_SHARE config diff --git a/planning/obstacle_stop_planner/package.xml b/planning/obstacle_stop_planner/package.xml index 93ea6661c374a..f3311521103e8 100644 --- a/planning/obstacle_stop_planner/package.xml +++ b/planning/obstacle_stop_planner/package.xml @@ -28,6 +28,7 @@ nav_msgs pcl_conversions pcl_ros + planning_test_utils rclcpp rclcpp_components sensor_msgs @@ -43,6 +44,7 @@ vehicle_info_util visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp new file mode 100644 index 0000000000000..fda70779d53f4 --- /dev/null +++ b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp @@ -0,0 +1,67 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "obstacle_stop_planner/node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include + +TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInput) +{ + rclcpp::init(0, nullptr); + + auto test_manager = std::make_shared(); + + auto node_options = rclcpp::NodeOptions{}; + + test_manager->declareVehicleInfoParams(node_options); + test_manager->declareNearestSearchDistanceParams(node_options); + node_options.append_parameter_override("enable_slow_down", false); + + const auto obstacle_stop_planner_dir = + ament_index_cpp::get_package_share_directory("obstacle_stop_planner"); + + node_options.arguments( + {"--ros-args", "--params-file", obstacle_stop_planner_dir + "/config/common.param.yaml", + "--params-file", obstacle_stop_planner_dir + "/config/adaptive_cruise_control.param.yaml", + "--params-file", obstacle_stop_planner_dir + "/config/obstacle_stop_planner.param.yaml"}); + + auto test_target_node = std::make_shared(node_options); + + // publish necessary topics from test_manager + test_manager->publishOdometry(test_target_node, "obstacle_stop_planner/input/odometry"); + test_manager->publishPointCloud(test_target_node, "obstacle_stop_planner/input/pointcloud"); + test_manager->publishAcceleration(test_target_node, "obstacle_stop_planner/input/acceleration"); + test_manager->publishPredictedObjects(test_target_node, "obstacle_stop_planner/input/objects"); + test_manager->publishExpandStopRange( + test_target_node, "obstacle_stop_planner/input/expand_stop_range"); + + // set subscriber for test_target_node + test_manager->setTrajectorySubscriber("obstacle_stop_planner/output/trajectory"); + + // setting topic name of subscribing topic + test_manager->setTrajectoryInputTopicName("obstacle_stop_planner/input/trajectory"); + + // test for normal trajectory + ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test for trajectory with empty/one point/overlapping point + test_manager->testWithAbnormalTrajectory(test_target_node); +} diff --git a/planning/planning_test_utils/CMakeLists.txt b/planning/planning_test_utils/CMakeLists.txt new file mode 100644 index 0000000000000..80bd5e5049ec4 --- /dev/null +++ b/planning/planning_test_utils/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.14) +project(planning_test_utils) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(planning_test_utils SHARED + src/planning_interface_test_manager.cpp +) + +ament_auto_package(INSTALL_TO_SHARE +) diff --git a/planning/planning_test_utils/README.md b/planning/planning_test_utils/README.md new file mode 100644 index 0000000000000..d8447fdbf1122 --- /dev/null +++ b/planning/planning_test_utils/README.md @@ -0,0 +1,17 @@ +# Planning Test Manager + +## Purpose + +## Inner-workings / Algorithms + +## Inputs / Outputs + +### Inputs + +### Outputs + +## Parameters + +## Assumptions / Known limits + +## Future extensions / Unimplemented parts diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp new file mode 100644 index 0000000000000..2c8937d5bf907 --- /dev/null +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp @@ -0,0 +1,112 @@ +// 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 PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#define PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace planning_test_utils +{ +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::Path; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_vehicle_msgs::msg::SteeringReport; +using geometry_msgs::msg::AccelWithCovarianceStamped; +using nav_msgs::msg::OccupancyGrid; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::PointCloud2; +using tf2_msgs::msg::TFMessage; +using tier4_planning_msgs::msg::ExpandStopRange; +using tier4_planning_msgs::msg::VelocityLimit; + +class PlanningIntefaceTestManager +{ +public: + PlanningIntefaceTestManager() {} + + void declareVehicleInfoParams(rclcpp::NodeOptions & node_options); + void declareNearestSearchDistanceParams(rclcpp::NodeOptions & node_options); + + void publishOdometry(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishMaxVelocity(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishPointCloud(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishAcceleration(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishPredictedObjects(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishExpandStopRange(rclcpp::Node::SharedPtr target_node, std::string topic_name); + + void setTrajectoryInputTopicName(std::string topic_name); + + void setTrajectorySubscriber(std::string topic_name); + + void testWithNominalTrajectory(rclcpp::Node::SharedPtr target_node); + void testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node); + + int getReceivedTopicNum(); + +private: + // Publisher + rclcpp::Publisher::SharedPtr odom_pub_; + rclcpp::Publisher::SharedPtr point_cloud_pub_; + rclcpp::Publisher::SharedPtr predicted_objects_pub_; + rclcpp::Publisher::SharedPtr TF_pub_; + rclcpp::Publisher::SharedPtr steering_pub_; + rclcpp::Publisher::SharedPtr path_pub_; + rclcpp::Publisher::SharedPtr occupancy_grid_pub_; + rclcpp::Publisher::SharedPtr max_velocity_pub_; + rclcpp::Publisher::SharedPtr expand_stop_range_pub_; + rclcpp::Publisher::SharedPtr acceleration_pub_; + + // Subscriber (necessary for node running) + rclcpp::Subscription::SharedPtr traj_sub_; + rclcpp::Subscription::SharedPtr max_velocity_sub_; + + // Publisher for testing + rclcpp::Publisher::SharedPtr normal_trajectory_pub_; + rclcpp::Publisher::SharedPtr abnormal_trajectory_pub_; + + std::string input_trajectory_name_; + + // Node + rclcpp::Node::SharedPtr test_node_ = + std::make_shared("planning_interface_test_node"); + size_t count_{0}; + + void publishNominalTrajectory(std::string topic_name); + void publishAbnormalTrajectory( + rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory); +}; // class PlanningIntefaceTestManager + +} // namespace planning_test_utils + +#endif // PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp new file mode 100644 index 0000000000000..342ad6516d61c --- /dev/null +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp @@ -0,0 +1,107 @@ +// Copyright 2023 The 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 PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#define PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ + +#include + +#include +#include +#include + +namespace test_utils +{ +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternionFromRPY; + +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 generateTrajectory( + const size_t num_points, const double point_interval, const double velocity = 0.0, + const double init_theta = 0.0, const double delta_theta = 0.0, + const size_t overlapping_point_index = std::numeric_limits::max()) +{ + 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 = velocity; + traj.points.push_back(p); + + if (i == overlapping_point_index) { + Point value_to_insert = traj.points[overlapping_point_index]; + traj.points.insert(traj.points.begin() + overlapping_point_index + 1, value_to_insert); + } + } + + return traj; +} + +void spinSomeNodes( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, + const int repeat_count = 1) +{ + for (int i = 0; i < repeat_count; i++) { + rclcpp::spin_some(test_node); + rclcpp::spin_some(target_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } +} + +template +void setPublisher( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::shared_ptr> & publisher) +{ + publisher = rclcpp::create_publisher(test_node, topic_name, 1); +} + +template +void publishEmptyData( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, + typename rclcpp::Publisher::SharedPtr publisher) +{ + setPublisher(test_node, topic_name, publisher); + publisher->publish(T{}); + spinSomeNodes(test_node, target_node); +} + +template +void setSubscriber( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::shared_ptr> & subscriber, size_t & count) +{ + // Count the number of topic received. + subscriber = test_node->create_subscription( + topic_name, 10, [&count](const typename T::SharedPtr) { count++; }); +} + +} // namespace test_utils + +#endif // PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml new file mode 100644 index 0000000000000..68ed495cd4372 --- /dev/null +++ b/planning/planning_test_utils/package.xml @@ -0,0 +1,34 @@ + + + + planning_test_utils + 0.1.0 + ROS2 node for testing interface of the nodes in planning module + Kyoichi Sugahara + Apache License 2.0 + + Kyoichi Sugahara + + ament_cmake_auto + + autoware_cmake + + autoware_auto_control_msgs + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_auto_vehicle_msgs + nav_msgs + rclcpp + tf2_msgs + tier4_autoware_utils + tier4_planning_msgs + + ament_cmake_gtest + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/planning_test_utils/src/planning_interface_test_manager.cpp b/planning/planning_test_utils/src/planning_interface_test_manager.cpp new file mode 100644 index 0000000000000..35fe57d70698c --- /dev/null +++ b/planning/planning_test_utils/src/planning_interface_test_manager.cpp @@ -0,0 +1,125 @@ +// 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 +#include + +namespace planning_test_utils +{ +void PlanningIntefaceTestManager::declareVehicleInfoParams(rclcpp::NodeOptions & node_options) +{ + // for vehicle info + node_options.append_parameter_override("wheel_radius", 0.5); + node_options.append_parameter_override("wheel_width", 0.2); + node_options.append_parameter_override("wheel_base", 3.0); + node_options.append_parameter_override("wheel_tread", 2.0); + node_options.append_parameter_override("front_overhang", 1.0); + node_options.append_parameter_override("rear_overhang", 1.0); + 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); +} + +void PlanningIntefaceTestManager::declareNearestSearchDistanceParams( + rclcpp::NodeOptions & node_options) +{ + node_options.append_parameter_override("ego_nearest_dist_threshold", 3.0); + node_options.append_parameter_override("ego_nearest_yaw_threshold", 1.046); +} + +void PlanningIntefaceTestManager::publishOdometry( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData(test_node_, target_node, topic_name, odom_pub_); +} + +void PlanningIntefaceTestManager::publishMaxVelocity( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData( + test_node_, target_node, topic_name, max_velocity_pub_); +} + +void PlanningIntefaceTestManager::publishPointCloud( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData(test_node_, target_node, topic_name, point_cloud_pub_); +} + +void PlanningIntefaceTestManager::publishAcceleration( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData( + test_node_, target_node, topic_name, acceleration_pub_); +} + +void PlanningIntefaceTestManager::publishPredictedObjects( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData( + test_node_, target_node, topic_name, predicted_objects_pub_); +} + +void PlanningIntefaceTestManager::publishExpandStopRange( + rclcpp::Node::SharedPtr target_node, std::string topic_name) +{ + test_utils::publishEmptyData( + test_node_, target_node, topic_name, expand_stop_range_pub_); +} + +void PlanningIntefaceTestManager::setTrajectoryInputTopicName(std::string topic_name) +{ + input_trajectory_name_ = topic_name; +} + +void PlanningIntefaceTestManager::publishNominalTrajectory(std::string topic_name) +{ + test_utils::setPublisher(test_node_, topic_name, normal_trajectory_pub_); + normal_trajectory_pub_->publish(test_utils::generateTrajectory(10, 1.0)); +} + +void PlanningIntefaceTestManager::setTrajectorySubscriber(std::string topic_name) +{ + test_utils::setSubscriber(test_node_, topic_name, traj_sub_, count_); +} + +// test for normal working +void PlanningIntefaceTestManager::testWithNominalTrajectory(rclcpp::Node::SharedPtr target_node) +{ + publishNominalTrajectory(input_trajectory_name_); + test_utils::spinSomeNodes(test_node_, target_node, 2); +} + +// check to see if target node is dead. +void PlanningIntefaceTestManager::testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node) +{ + ASSERT_NO_THROW(publishAbnormalTrajectory(target_node, Trajectory{})); + ASSERT_NO_THROW( + publishAbnormalTrajectory(target_node, test_utils::generateTrajectory(1, 0.0))); + ASSERT_NO_THROW(publishAbnormalTrajectory( + target_node, test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1))); +} + +void PlanningIntefaceTestManager::publishAbnormalTrajectory( + rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory) +{ + test_utils::setPublisher(test_node_, input_trajectory_name_, abnormal_trajectory_pub_); + abnormal_trajectory_pub_->publish(abnormal_trajectory); + test_utils::spinSomeNodes(test_node_, target_node); +} + +int PlanningIntefaceTestManager::getReceivedTopicNum() { return count_; } + +} // namespace planning_test_utils From cf753f429648abb903cda7bbd796223b5d9fd41a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 23 Mar 2023 12:04:37 +0900 Subject: [PATCH 075/121] feat(rtc_manager_rviz_plugin): add avoidance by lc (#3118) Signed-off-by: satoshi-ota --- .../src/rtc_manager_panel.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp index 2daa837ffd073..a08ba8874feb7 100644 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp +++ b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp @@ -45,6 +45,12 @@ std::string getModuleName(const uint8_t module_type) case Module::EXT_REQUEST_LANE_CHANGE_RIGHT: { return "ext_request_lane_change_right"; } + case Module::AVOIDANCE_BY_LC_LEFT: { + return "avoidance_by_lane_change_left"; + } + case Module::AVOIDANCE_BY_LC_RIGHT: { + return "avoidance_by_lane_change_right"; + } case Module::AVOIDANCE_LEFT: { return "avoidance_left"; } @@ -87,9 +93,10 @@ bool isPathChangeModule(const uint8_t module_type) if ( module_type == Module::LANE_CHANGE_LEFT || module_type == Module::LANE_CHANGE_RIGHT || module_type == Module::EXT_REQUEST_LANE_CHANGE_LEFT || - module_type == Module::EXT_REQUEST_LANE_CHANGE_RIGHT || module_type == Module::AVOIDANCE_LEFT || - module_type == Module::AVOIDANCE_RIGHT || module_type == Module::PULL_OVER || - module_type == Module::PULL_OUT) { + module_type == Module::EXT_REQUEST_LANE_CHANGE_RIGHT || + module_type == Module::AVOIDANCE_BY_LC_LEFT || module_type == Module::AVOIDANCE_BY_LC_RIGHT || + module_type == Module::AVOIDANCE_LEFT || module_type == Module::AVOIDANCE_RIGHT || + module_type == Module::PULL_OVER || module_type == Module::PULL_OUT) { return true; } return false; @@ -98,7 +105,7 @@ bool isPathChangeModule(const uint8_t module_type) RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) { // TODO(tanaka): replace this magic number to Module::SIZE - const size_t module_size = 14; + const size_t module_size = 18; auto_modes_.reserve(module_size); auto * v_layout = new QVBoxLayout; auto vertical_header = new QHeaderView(Qt::Vertical); From 731816b30438d9e7df1a81146bda3c67e57e6172 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Mar 2023 14:55:04 +0900 Subject: [PATCH 076/121] feat(diagnostic_converter): apply regex for topic name (#3149) Signed-off-by: Takayuki Murooka --- .../src/converter_node.cpp | 21 +++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/evaluator/diagnostic_converter/src/converter_node.cpp b/evaluator/diagnostic_converter/src/converter_node.cpp index 798515b8667bd..a88bd186488ed 100644 --- a/evaluator/diagnostic_converter/src/converter_node.cpp +++ b/evaluator/diagnostic_converter/src/converter_node.cpp @@ -14,6 +14,23 @@ #include "converter_node.hpp" +#include + +namespace +{ +std::string removeInvalidTopicString(std::string input_string) +{ + std::regex pattern{R"([a-zA-Z0-9/_]+)"}; + + std::string result; + for (std::sregex_iterator itr(std::begin(input_string), std::end(input_string), pattern), end; + itr != end; ++itr) { + result += itr->str(); + } + return result; +} +} // namespace + namespace diagnostic_converter { DiagnosticConverter::DiagnosticConverter(const rclcpp::NodeOptions & node_options) @@ -41,8 +58,8 @@ void DiagnosticConverter::onDiagnostic( for (const auto & status : diag_msg->status) { std::string status_topic = base_topic + (status.name.empty() ? "" : "_" + status.name); for (const auto & key_value : status.values) { - getPublisher(status_topic + "_" + key_value.key, diag_idx) - ->publish(createUserDefinedValue(key_value)); + const auto valid_topic_name = removeInvalidTopicString(status_topic + "_" + key_value.key); + getPublisher(valid_topic_name, diag_idx)->publish(createUserDefinedValue(key_value)); } } } From 9a0a29dace80ce9c6d055e6d60d470c6fb6d0d28 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Thu, 23 Mar 2023 15:00:51 +0900 Subject: [PATCH 077/121] fix(behavior_velocity_planner): fix detection area being ignored when the ego vehicle stops over the stop line (#3114) * feat(behavior_velocity_planner): add a parameter for judgeing over the stop line Signed-off-by: Makoto Kurihara * feat(behavior_velocity_planner): ignore pass judge when the velocity is zero Signed-off-by: Makoto Kurihara * style(pre-commit): autofix --------- Signed-off-by: Makoto Kurihara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/detection_area.param.yaml | 1 + .../detection-area-design.md | 17 +++++++++-------- .../scene_module/detection_area/scene.hpp | 1 + .../src/scene_module/detection_area/manager.cpp | 2 ++ .../src/scene_module/detection_area/scene.cpp | 10 +++++++++- 5 files changed, 22 insertions(+), 9 deletions(-) diff --git a/planning/behavior_velocity_planner/config/detection_area.param.yaml b/planning/behavior_velocity_planner/config/detection_area.param.yaml index 63ca5fc7d96a2..ad4e32cb4e198 100644 --- a/planning/behavior_velocity_planner/config/detection_area.param.yaml +++ b/planning/behavior_velocity_planner/config/detection_area.param.yaml @@ -7,3 +7,4 @@ use_pass_judge_line: false state_clear_time: 2.0 hold_stop_margin_distance: 0.0 + distance_to_judge_over_stop_line: 0.5 diff --git a/planning/behavior_velocity_planner/detection-area-design.md b/planning/behavior_velocity_planner/detection-area-design.md index 20bfcce3204ac..0a3648ae72900 100644 --- a/planning/behavior_velocity_planner/detection-area-design.md +++ b/planning/behavior_velocity_planner/detection-area-design.md @@ -12,14 +12,15 @@ This module is activated when there is a detection area on the target lane. ### Module Parameters -| Parameter | Type | Description | -| --------------------------- | ------ | -------------------------------------------------------------------------------------------------- | -| `use_dead_line` | bool | [-] weather to use dead line or not | -| `use_pass_judge_line` | bool | [-] weather to use pass judge line or not | -| `state_clear_time` | double | [s] when the vehicle is stopping for certain time without incoming obstacle, move to STOPPED state | -| `stop_margin` | double | [m] a margin that the vehicle tries to stop before stop_line | -| `dead_line_margin` | double | [m] ignore threshold that vehicle behind is collide with ego vehicle or not | -| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) | +| Parameter | Type | Description | +| ---------------------------------- | ------ | -------------------------------------------------------------------------------------------------- | +| `use_dead_line` | bool | [-] weather to use dead line or not | +| `use_pass_judge_line` | bool | [-] weather to use pass judge line or not | +| `state_clear_time` | double | [s] when the vehicle is stopping for certain time without incoming obstacle, move to STOPPED state | +| `stop_margin` | double | [m] a margin that the vehicle tries to stop before stop_line | +| `dead_line_margin` | double | [m] ignore threshold that vehicle behind is collide with ego vehicle or not | +| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) | +| `distance_to_judge_over_stop_line` | double | [m] parameter for judging that the stop line has been crossed | ### Inner-workings / Algorithm diff --git a/planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp b/planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp index b6896f4b68eb9..687fa92e920fc 100644 --- a/planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp @@ -60,6 +60,7 @@ class DetectionAreaModule : public SceneModuleInterface bool use_pass_judge_line; double state_clear_time; double hold_stop_margin_distance; + double distance_to_judge_over_stop_line; }; public: diff --git a/planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp index afaa3502c2b1b..d28d314d1df4b 100644 --- a/planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp @@ -39,6 +39,8 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node) planner_param_.state_clear_time = node.declare_parameter(ns + ".state_clear_time", 2.0); planner_param_.hold_stop_margin_distance = node.declare_parameter(ns + ".hold_stop_margin_distance", 0.0); + planner_param_.distance_to_judge_over_stop_line = + node.declare_parameter(ns + ".distance_to_judge_over_stop_line", 0.5); } void DetectionAreaModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp index 3de7279aeb27c..ae9c39e3321a5 100644 --- a/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp @@ -154,7 +154,9 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * const double dist_from_ego_to_stop = calcSignedArcLength( original_path.points, self_pose.position, current_seg_idx, stop_pose.position, stop_line_seg_idx); - if (state_ != State::STOP && dist_from_ego_to_stop < 0.0) { + if ( + state_ != State::STOP && + dist_from_ego_to_stop < -planner_param_.distance_to_judge_over_stop_line) { setSafe(true); return true; } @@ -327,6 +329,12 @@ bool DetectionAreaModule::hasEnoughBrakingDistance( const double pass_judge_line_distance = planning_utils::calcJudgeLineDistWithAccLimit(current_velocity, max_acc, delay_response_time); + // prevent from being judged as not having enough distance when the current velocity is zero + // and the vehicle crosses the stop line + if (current_velocity < 1e-3) { + return true; + } + return arc_lane_utils::calcSignedDistance(self_pose, line_pose.position) > pass_judge_line_distance; } From aa2f265e1f3f99fecf599bf4e39c74c738e2eedf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Mar 2023 16:04:21 +0900 Subject: [PATCH 078/121] feat(diagnostic_converter): remove unit and blank in the value (#3151) * feat(diagnostic_converter): remove unit and blank in the value Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/converter_node.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/evaluator/diagnostic_converter/src/converter_node.cpp b/evaluator/diagnostic_converter/src/converter_node.cpp index a88bd186488ed..e61b19833d2fe 100644 --- a/evaluator/diagnostic_converter/src/converter_node.cpp +++ b/evaluator/diagnostic_converter/src/converter_node.cpp @@ -18,7 +18,7 @@ namespace { -std::string removeInvalidTopicString(std::string input_string) +std::string removeInvalidTopicString(const std::string & input_string) { std::regex pattern{R"([a-zA-Z0-9/_]+)"}; @@ -29,6 +29,20 @@ std::string removeInvalidTopicString(std::string input_string) } return result; } + +std::string removeUnitString(const std::string & input_string) +{ + for (size_t i = 0; i < input_string.size(); ++i) { + if (input_string.at(i) == '[') { + if (i != 0 && input_string.at(i - 1) == ' ') { + // Blank is also removed + return std::string{input_string.begin(), input_string.begin() + i - 1}; + } + return std::string{input_string.begin(), input_string.begin() + i}; + } + } + return input_string; +} } // namespace namespace diagnostic_converter @@ -68,7 +82,7 @@ UserDefinedValue DiagnosticConverter::createUserDefinedValue(const KeyValue & ke { UserDefinedValue param_msg; param_msg.type.data = UserDefinedValueType::DOUBLE; - param_msg.value = key_value.value; + param_msg.value = removeUnitString(key_value.value); return param_msg; } From 9d8c061aef0a87b50d76d1b99dfb88ff2f911b97 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 23 Mar 2023 07:20:21 +0000 Subject: [PATCH 079/121] chore: update CODEOWNERS (#2976) Signed-off-by: GitHub Co-authored-by: takayuki5168 --- .github/CODEOWNERS | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index f7d0d06f9310b..c67e5cccbe32f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -28,6 +28,7 @@ common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @ common/signal_processing/** ali.boyali@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners common/tensorrt_common/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners +common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_autoware_utils/** kenji.miyake@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners @@ -36,7 +37,7 @@ common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp @autowarefoundation/ common/tier4_debug_tools/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners +common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_screen_capture_rviz_plugin/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners @@ -45,6 +46,7 @@ common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp @autowarefoundation/ common/time_utils/** christopherj.ho@gmail.com @autowarefoundation/autoware-global-codeowners common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp @autowarefoundation/autoware-global-codeowners common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp @autowarefoundation/autoware-global-codeowners +control/autonomous_emergency_braking/** yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners control/external_cmd_selector/** fumiya.watanabe@tier4.jp kenji.miyake@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners control/joy_controller/** fumiya.watanabe@tier4.jp kenji.miyake@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners @@ -58,16 +60,18 @@ control/shift_decider/** takamasa.horibe@tier4.jp @autowarefoundation/autoware-g control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners +evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai @autowarefoundation/autoware-global-codeowners evaluator/localization_evaluator/** dominik.jargot@robotec.ai @autowarefoundation/autoware-global-codeowners +evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_localization_launch/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners +launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_map_launch/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_simulator_launch/** keisuke.shima@tier4.jp @autowarefoundation/autoware-global-codeowners +launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners localization/ekf_localizer/** koji.minoda@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners @@ -112,9 +116,10 @@ perception/tensorrt_yolo/** daisuke.nishimatsu@tier4.jp @autowarefoundation/auto perception/tensorrt_yolox/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners perception/traffic_light_classifier/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners +perception/traffic_light_selector/** isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp @autowarefoundation/autoware-global-codeowners perception/traffic_light_visualization/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners +planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners planning/external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners @@ -122,12 +127,12 @@ planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners planning/mission_planner/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners +planning/obstacle_avoidance_planner/** takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners planning/obstacle_cruise_planner/** takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners planning/obstacle_stop_planner/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/planning_evaluator/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners +planning/planning_test_utils/** kyoichi.sugahara@tier4.jp @autowarefoundation/autoware-global-codeowners planning/planning_validator/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners planning/rtc_auto_mode_manager/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners From 1469f52c1a738e6512437317e2588561bc024c60 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Mar 2023 17:52:52 +0900 Subject: [PATCH 080/121] fix(static_centerline_optimizer): remove unnecessary files (#3154) Signed-off-by: Takayuki Murooka --- .../collision_free_optimizer_node.hpp | 103 ---- .../src/collision_free_optimizer_node.cpp | 459 ------------------ 2 files changed, 562 deletions(-) delete mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/collision_free_optimizer_node.hpp delete mode 100644 planning/static_centerline_optimizer/src/collision_free_optimizer_node.cpp diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/collision_free_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/collision_free_optimizer_node.hpp deleted file mode 100644 index 55f91bddbdab2..0000000000000 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/collision_free_optimizer_node.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// 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. - -// NOTE: This file was copied from a part of implementation in -// https://github.com/autowarefoundation/autoware.universe/blob/main/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp - -#ifndef STATIC_CENTERLINE_OPTIMIZER__COLLISION_FREE_OPTIMIZER_NODE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__COLLISION_FREE_OPTIMIZER_NODE_HPP_ - -#include "motion_utils/motion_utils.hpp" -#include "obstacle_avoidance_planner/common_structs.hpp" -#include "obstacle_avoidance_planner/eb_path_optimizer.hpp" -#include "obstacle_avoidance_planner/mpt_optimizer.hpp" -#include "rclcpp/clock.hpp" -#include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/type_alias.hpp" -#include "tier4_autoware_utils/tier4_autoware_utils.hpp" - -#include "boost/optional.hpp" - -#include -#include -#include -#include - -namespace static_centerline_optimizer -{ -class CollisionFreeOptimizerNode : public rclcpp::Node -{ -private: - rclcpp::Clock logger_ros_clock_; - int eb_solved_count_; - bool is_driving_forward_{true}; - - bool is_publishing_debug_visualization_marker_; - bool is_publishing_area_with_objects_; - bool is_publishing_object_clearance_map_; - bool is_publishing_clearance_map_; - bool is_showing_debug_info_; - bool is_showing_calculation_time_; - bool is_stopping_if_outside_drivable_area_; - bool enable_avoidance_; - bool enable_pre_smoothing_; - bool skip_optimization_; - bool reset_prev_optimization_; - - // vehicle circles info for for mpt constraints - std::string vehicle_circle_method_; - int vehicle_circle_num_for_calculation_; - std::vector vehicle_circle_radius_ratios_; - - // params for replan - double max_path_shape_change_dist_for_replan_; - double max_ego_moving_dist_for_replan_; - double max_delta_time_sec_for_replan_; - - // logic - std::unique_ptr eb_path_optimizer_ptr_; - std::unique_ptr mpt_optimizer_ptr_; - - // params - TrajectoryParam traj_param_; - EBParam eb_param_; - VehicleParam vehicle_param_; - MPTParam mpt_param_; - int mpt_visualize_sampling_num_; - - // debug - mutable DebugData debug_data_; - - geometry_msgs::msg::Pose current_ego_pose_; - std::unique_ptr prev_optimal_trajs_ptr_; - std::unique_ptr> prev_path_points_ptr_; - - std::unique_ptr latest_replanned_time_ptr_; - - // ROS - rclcpp::Subscription::SharedPtr path_sub_; - - // functions - void resetPlanning(); - void resetPrevOptimization(); - -public: - explicit CollisionFreeOptimizerNode(const rclcpp::NodeOptions & node_options); - - // subscriber callback functions - Trajectory pathCallback(const Path::ConstSharedPtr); -}; -} // namespace static_centerline_optimizer - -#endif // STATIC_CENTERLINE_OPTIMIZER__COLLISION_FREE_OPTIMIZER_NODE_HPP_ diff --git a/planning/static_centerline_optimizer/src/collision_free_optimizer_node.cpp b/planning/static_centerline_optimizer/src/collision_free_optimizer_node.cpp deleted file mode 100644 index 5dd83d6d4b310..0000000000000 --- a/planning/static_centerline_optimizer/src/collision_free_optimizer_node.cpp +++ /dev/null @@ -1,459 +0,0 @@ -// 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. - -// NOTE: This file was copied from a part of implementation in -// https://github.com/autowarefoundation/autoware.universe/blob/main/planning/obstacle_avoidance_planner/src/node.cpp - -#include "static_centerline_optimizer/collision_free_optimizer_node.hpp" - -#include "interpolation/spline_interpolation_points_2d.hpp" -#include "motion_utils/motion_utils.hpp" -#include "rclcpp/time.hpp" -#include "tf2/utils.h" -#include "tier4_autoware_utils/tier4_autoware_utils.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" - -#include -#include -#include -#include -#include -#include - -// TODO(murooka) refactor -namespace static_centerline_optimizer -{ -namespace -{ -std::tuple, std::vector> calcVehicleCirclesInfo( - const VehicleParam & vehicle_param, const size_t circle_num, const double rear_radius_ratio, - const double front_radius_ratio) -{ - std::vector longitudinal_offsets; - std::vector radiuses; - - { // 1st circle (rear) - longitudinal_offsets.push_back(-vehicle_param.rear_overhang); - radiuses.push_back(vehicle_param.width / 2.0 * rear_radius_ratio); - } - - { // 2nd circle (front) - const double radius = std::hypot( - vehicle_param.length / static_cast(circle_num) / 2.0, vehicle_param.width / 2.0); - - const double unit_lon_length = vehicle_param.length / static_cast(circle_num); - const double longitudinal_offset = - unit_lon_length / 2.0 + unit_lon_length * (circle_num - 1) - vehicle_param.rear_overhang; - - longitudinal_offsets.push_back(longitudinal_offset); - radiuses.push_back(radius * front_radius_ratio); - } - - return {radiuses, longitudinal_offsets}; -} - -std::tuple, std::vector> calcVehicleCirclesInfo( - const VehicleParam & vehicle_param, const size_t circle_num, const double radius_ratio) -{ - std::vector longitudinal_offsets; - std::vector radiuses; - - const double radius = - std::hypot( - vehicle_param.length / static_cast(circle_num) / 2.0, vehicle_param.width / 2.0) * - radius_ratio; - const double unit_lon_length = vehicle_param.length / static_cast(circle_num); - - for (size_t i = 0; i < circle_num; ++i) { - longitudinal_offsets.push_back( - unit_lon_length / 2.0 + unit_lon_length * i - vehicle_param.rear_overhang); - radiuses.push_back(radius); - } - - return {radiuses, longitudinal_offsets}; -} - -template -TrajectoryPoint convertToTrajectoryPoint(const T & point) -{ - TrajectoryPoint traj_point; - traj_point.pose = tier4_autoware_utils::getPose(point); - traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; - traj_point.lateral_velocity_mps = point.lateral_velocity_mps; - traj_point.heading_rate_rps = point.heading_rate_rps; - return traj_point; -} - -template -std::vector convertToTrajectoryPoints(const std::vector & points) -{ - std::vector traj_points; - for (const auto & point : points) { - const auto traj_point = convertToTrajectoryPoint(point); - traj_points.push_back(traj_point); - } - return traj_points; -} -} // namespace - -CollisionFreeOptimizerNode::CollisionFreeOptimizerNode(const rclcpp::NodeOptions & node_options) -: Node("static_centerline_optimizer", node_options), logger_ros_clock_(RCL_ROS_TIME) -{ - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_ROS_TIME); - - // subscriber - path_sub_ = create_subscription( - "debug/raw_centerline", rclcpp::QoS{1}.transient_local(), - std::bind(&CollisionFreeOptimizerNode::pathCallback, this, std::placeholders::_1)); - - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); - { // vehicle param - vehicle_param_ = VehicleParam{}; - vehicle_param_.width = vehicle_info.vehicle_width_m; - vehicle_param_.length = vehicle_info.vehicle_length_m; - vehicle_param_.wheelbase = vehicle_info.wheel_base_m; - vehicle_param_.rear_overhang = vehicle_info.rear_overhang_m; - vehicle_param_.front_overhang = vehicle_info.front_overhang_m; - } - - { // option parameter - is_publishing_debug_visualization_marker_ = - declare_parameter("option.is_publishing_debug_visualization_marker"); - is_publishing_clearance_map_ = declare_parameter("option.is_publishing_clearance_map"); - is_publishing_object_clearance_map_ = - declare_parameter("option.is_publishing_object_clearance_map"); - is_publishing_area_with_objects_ = - declare_parameter("option.is_publishing_area_with_objects"); - - is_showing_debug_info_ = declare_parameter("option.is_showing_debug_info"); - is_showing_calculation_time_ = declare_parameter("option.is_showing_calculation_time"); - is_stopping_if_outside_drivable_area_ = - declare_parameter("option.is_stopping_if_outside_drivable_area"); - - enable_avoidance_ = declare_parameter("option.enable_avoidance"); - enable_pre_smoothing_ = declare_parameter("option.enable_pre_smoothing"); - skip_optimization_ = declare_parameter("option.skip_optimization"); - reset_prev_optimization_ = declare_parameter("option.reset_prev_optimization"); - } - - { // trajectory parameter - traj_param_ = TrajectoryParam{}; - - // common - traj_param_.num_sampling_points = declare_parameter("common.num_sampling_points"); - traj_param_.trajectory_length = declare_parameter("common.trajectory_length"); - traj_param_.forward_fixing_min_distance = - declare_parameter("common.forward_fixing_min_distance"); - traj_param_.forward_fixing_min_time = - declare_parameter("common.forward_fixing_min_time"); - traj_param_.backward_fixing_distance = - declare_parameter("common.backward_fixing_distance"); - traj_param_.delta_arc_length_for_trajectory = - declare_parameter("common.delta_arc_length_for_trajectory"); - - traj_param_.delta_dist_threshold_for_closest_point = - declare_parameter("common.delta_dist_threshold_for_closest_point"); - traj_param_.delta_yaw_threshold_for_closest_point = - declare_parameter("common.delta_yaw_threshold_for_closest_point"); - traj_param_.delta_yaw_threshold_for_straight = - declare_parameter("common.delta_yaw_threshold_for_straight"); - - traj_param_.num_fix_points_for_extending = - declare_parameter("common.num_fix_points_for_extending"); - traj_param_.max_dist_for_extending_end_point = - declare_parameter("common.max_dist_for_extending_end_point"); - - // object - traj_param_.max_avoiding_ego_velocity_ms = - declare_parameter("object.max_avoiding_ego_velocity_ms"); - traj_param_.max_avoiding_objects_velocity_ms = - declare_parameter("object.max_avoiding_objects_velocity_ms"); - traj_param_.is_avoiding_unknown = - declare_parameter("object.avoiding_object_type.unknown", true); - traj_param_.is_avoiding_car = declare_parameter("object.avoiding_object_type.car", true); - traj_param_.is_avoiding_truck = - declare_parameter("object.avoiding_object_type.truck", true); - traj_param_.is_avoiding_bus = declare_parameter("object.avoiding_object_type.bus", true); - traj_param_.is_avoiding_bicycle = - declare_parameter("object.avoiding_object_type.bicycle", true); - traj_param_.is_avoiding_motorbike = - declare_parameter("object.avoiding_object_type.motorbike", true); - traj_param_.is_avoiding_pedestrian = - declare_parameter("object.avoiding_object_type.pedestrian", true); - traj_param_.is_avoiding_animal = - declare_parameter("object.avoiding_object_type.animal", true); - - // ego nearest search - traj_param_.ego_nearest_dist_threshold = - declare_parameter("ego_nearest_dist_threshold"); - traj_param_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - } - - { // elastic band parameter - eb_param_ = EBParam{}; - - // common - eb_param_.num_joint_buffer_points = - declare_parameter("advanced.eb.common.num_joint_buffer_points"); - eb_param_.num_offset_for_begin_idx = - declare_parameter("advanced.eb.common.num_offset_for_begin_idx"); - eb_param_.delta_arc_length_for_eb = - declare_parameter("advanced.eb.common.delta_arc_length_for_eb"); - eb_param_.num_sampling_points_for_eb = - declare_parameter("advanced.eb.common.num_sampling_points_for_eb"); - - // clearance - eb_param_.clearance_for_straight_line = - declare_parameter("advanced.eb.clearance.clearance_for_straight_line"); - eb_param_.clearance_for_joint = - declare_parameter("advanced.eb.clearance.clearance_for_joint"); - eb_param_.clearance_for_only_smoothing = - declare_parameter("advanced.eb.clearance.clearance_for_only_smoothing"); - - // qp - eb_param_.qp_param.max_iteration = declare_parameter("advanced.eb.qp.max_iteration"); - eb_param_.qp_param.eps_abs = declare_parameter("advanced.eb.qp.eps_abs"); - eb_param_.qp_param.eps_rel = declare_parameter("advanced.eb.qp.eps_rel"); - - // other - eb_param_.clearance_for_fixing = 0.0; - } - - { // mpt param - mpt_param_ = MPTParam{}; - - // option - // TODO(murooka) implement plan_from_ego - mpt_param_.plan_from_ego = declare_parameter("mpt.option.plan_from_ego"); - mpt_param_.max_plan_from_ego_length = - declare_parameter("mpt.option.max_plan_from_ego_length"); - mpt_param_.steer_limit_constraint = - declare_parameter("mpt.option.steer_limit_constraint"); - mpt_param_.fix_points_around_ego = declare_parameter("mpt.option.fix_points_around_ego"); - mpt_param_.enable_warm_start = declare_parameter("mpt.option.enable_warm_start"); - mpt_param_.enable_manual_warm_start = - declare_parameter("mpt.option.enable_manual_warm_start"); - mpt_visualize_sampling_num_ = declare_parameter("mpt.option.visualize_sampling_num"); - - // common - mpt_param_.num_curvature_sampling_points = - declare_parameter("mpt.common.num_curvature_sampling_points"); - - mpt_param_.delta_arc_length_for_mpt_points = - declare_parameter("mpt.common.delta_arc_length_for_mpt_points"); - - // kinematics - mpt_param_.max_steer_rad = vehicle_info.max_steer_angle_rad; - - // By default, optimization_center_offset will be vehicle_info.wheel_base * 0.8 - // The 0.8 scale is adopted as it performed the best. - constexpr double default_wheelbase_ratio = 0.8; - mpt_param_.optimization_center_offset = declare_parameter( - "mpt.kinematics.optimization_center_offset", - vehicle_param_.wheelbase * default_wheelbase_ratio); - - // bounds search - mpt_param_.bounds_search_widths = - declare_parameter>("advanced.mpt.bounds_search_widths"); - - // collision free constraints - mpt_param_.l_inf_norm = - declare_parameter("advanced.mpt.collision_free_constraints.option.l_inf_norm"); - mpt_param_.soft_constraint = - declare_parameter("advanced.mpt.collision_free_constraints.option.soft_constraint"); - mpt_param_.hard_constraint = - declare_parameter("advanced.mpt.collision_free_constraints.option.hard_constraint"); - // TODO(murooka) implement two-step soft constraint - mpt_param_.two_step_soft_constraint = false; - // mpt_param_.two_step_soft_constraint = - // declare_parameter("advanced.mpt.collision_free_constraints.option.two_step_soft_constraint"); - - { // vehicle_circles - // NOTE: Vehicle shape for collision free constraints is considered as a set of circles - vehicle_circle_method_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.method"); - - if (vehicle_circle_method_ == "uniform_circle") { - vehicle_circle_num_for_calculation_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.num"); - vehicle_circle_radius_ratios_.push_back(declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.radius_ratio")); - - std::tie( - mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_num_for_calculation_, - vehicle_circle_radius_ratios_.front()); - } else if (vehicle_circle_method_ == "rear_drive") { - vehicle_circle_num_for_calculation_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.num_for_calculation"); - - vehicle_circle_radius_ratios_.push_back(declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.rear_radius_ratio")); - vehicle_circle_radius_ratios_.push_back(declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.front_radius_ratio")); - - std::tie( - mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_num_for_calculation_, - vehicle_circle_radius_ratios_.front(), vehicle_circle_radius_ratios_.back()); - } else { - throw std::invalid_argument( - "advanced.mpt.collision_free_constraints.vehicle_circles.num parameter is invalid."); - } - } - - // clearance - mpt_param_.hard_clearance_from_road = - declare_parameter("advanced.mpt.clearance.hard_clearance_from_road"); - mpt_param_.soft_clearance_from_road = - declare_parameter("advanced.mpt.clearance.soft_clearance_from_road"); - mpt_param_.soft_second_clearance_from_road = - declare_parameter("advanced.mpt.clearance.soft_second_clearance_from_road"); - mpt_param_.extra_desired_clearance_from_road = - declare_parameter("advanced.mpt.clearance.extra_desired_clearance_from_road"); - mpt_param_.clearance_from_object = - declare_parameter("advanced.mpt.clearance.clearance_from_object"); - - // weight - mpt_param_.soft_avoidance_weight = - declare_parameter("advanced.mpt.weight.soft_avoidance_weight"); - mpt_param_.soft_second_avoidance_weight = - declare_parameter("advanced.mpt.weight.soft_second_avoidance_weight"); - - mpt_param_.lat_error_weight = declare_parameter("advanced.mpt.weight.lat_error_weight"); - mpt_param_.yaw_error_weight = declare_parameter("advanced.mpt.weight.yaw_error_weight"); - mpt_param_.yaw_error_rate_weight = - declare_parameter("advanced.mpt.weight.yaw_error_rate_weight"); - mpt_param_.steer_input_weight = - declare_parameter("advanced.mpt.weight.steer_input_weight"); - mpt_param_.steer_rate_weight = - declare_parameter("advanced.mpt.weight.steer_rate_weight"); - - mpt_param_.obstacle_avoid_lat_error_weight = - declare_parameter("advanced.mpt.weight.obstacle_avoid_lat_error_weight"); - mpt_param_.obstacle_avoid_yaw_error_weight = - declare_parameter("advanced.mpt.weight.obstacle_avoid_yaw_error_weight"); - mpt_param_.obstacle_avoid_steer_input_weight = - declare_parameter("advanced.mpt.weight.obstacle_avoid_steer_input_weight"); - mpt_param_.near_objects_length = - declare_parameter("advanced.mpt.weight.near_objects_length"); - - mpt_param_.terminal_lat_error_weight = - declare_parameter("advanced.mpt.weight.terminal_lat_error_weight"); - mpt_param_.terminal_yaw_error_weight = - declare_parameter("advanced.mpt.weight.terminal_yaw_error_weight"); - mpt_param_.terminal_path_lat_error_weight = - declare_parameter("advanced.mpt.weight.terminal_path_lat_error_weight"); - mpt_param_.terminal_path_yaw_error_weight = - declare_parameter("advanced.mpt.weight.terminal_path_yaw_error_weight"); - } - - // TODO(murooka) tune this param when avoiding with static_centerline_optimizer - traj_param_.center_line_width = vehicle_param_.width; - - resetPlanning(); -} - -void CollisionFreeOptimizerNode::resetPlanning() -{ - RCLCPP_WARN(get_logger(), "[ObstacleAvoidancePlanner] Reset planning"); - - eb_path_optimizer_ptr_ = std::make_unique( - is_showing_debug_info_, traj_param_, eb_param_, vehicle_param_); - - mpt_optimizer_ptr_ = - std::make_unique(is_showing_debug_info_, traj_param_, vehicle_param_, mpt_param_); - - prev_path_points_ptr_ = nullptr; - resetPrevOptimization(); -} - -void CollisionFreeOptimizerNode::resetPrevOptimization() -{ - prev_optimal_trajs_ptr_ = nullptr; - eb_solved_count_ = 0; -} - -Trajectory CollisionFreeOptimizerNode::pathCallback(const Path::ConstSharedPtr path_ptr) -{ - if (path_ptr->points.empty()) { - return Trajectory{}; - } - - // initialize - debug_data_ = DebugData(); - resetPlanning(); - - // variables - const double resample_interval = 2.0; - const double valid_optimized_path_length = 30.0; - const double path_length = motion_utils::calcArcLength(path_ptr->points); - const size_t path_segment_num = static_cast(path_length / valid_optimized_path_length); - - const auto resampled_path = - motion_utils::resamplePath(*path_ptr, resample_interval); // TODO(murooka) - const auto resampled_traj_points = convertToTrajectoryPoints(resampled_path.points); - - // cv_maps - const auto predicted_objects = PredictedObjects{}.objects; - - const size_t initial_target_index = 3; - auto target_pose = resampled_path.points.at(initial_target_index).pose; // TODO(murooka) - std::vector whole_optimized_traj_points; - - for (size_t i = 0; i < path_segment_num; ++i) { - target_pose = resampled_path.points - .at(initial_target_index + valid_optimized_path_length / resample_interval * i) - .pose; - - const auto mpt_trajs = mpt_optimizer_ptr_->getModelPredictiveTrajectory( - false, resampled_traj_points, resampled_path.points, resampled_path.left_bound, - resampled_path.right_bound, prev_optimal_trajs_ptr_, target_pose, 0.0, debug_data_); - if (!mpt_trajs) { - break; - } - - Trajectories trajectories; - trajectories.mpt_ref_points = mpt_trajs->ref_points; - trajectories.model_predictive_trajectory = mpt_trajs->mpt; - prev_optimal_trajs_ptr_ = std::make_unique(trajectories); - - for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = tier4_autoware_utils::calcDistance2d( - whole_optimized_traj_points.at(j), mpt_trajs->mpt.front()); - if (dist < 0.5) { - const std::vector extracted_whole_optimized_traj_points{ - whole_optimized_traj_points.begin(), whole_optimized_traj_points.begin() + j - 1}; - whole_optimized_traj_points = extracted_whole_optimized_traj_points; - } - } - - for (size_t j = 0; j < mpt_trajs->mpt.size(); ++j) { - whole_optimized_traj_points.push_back(mpt_trajs->mpt.at(j)); - } - } - - // resample - auto output_traj_msg = motion_utils::resampleTrajectory( - motion_utils::convertToTrajectory(whole_optimized_traj_points), 1.0); - output_traj_msg.header = path_ptr->header; - - return output_traj_msg; -} -} // namespace static_centerline_optimizer - -#include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(static_centerline_optimizer::CollisionFreeOptimizerNode) From 7a721162f660c049883257d2362a9aeec62621ff Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Mar 2023 18:58:18 +0900 Subject: [PATCH 081/121] fix(behavior_path_planner): fix math formulation in doc (#3146) Signed-off-by: Takayuki Murooka --- .../behavior_path_planner_avoidance_design.md | 18 ++++++------ ...ior_path_planner_path_generation_design.md | 28 +++++++++---------- 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/behavior_path_planner_avoidance_design.md index 7f6274925174b..b2b2f0651ffe1 100644 --- a/planning/behavior_path_planner/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/behavior_path_planner_avoidance_design.md @@ -191,10 +191,10 @@ The avoidance target should be limited to stationary objects (you should not avo Not only the length from the centerline, but also the length from the road shoulder is calculated and used for the filtering process. It calculates the ratio of _the actual length between the the object's center and the center line_ `shift_length` and _the maximum length the object can shift_ `shiftable_length`. -```math -l_D = l_a - \frac{width}{2} +$$ +l_D = l_a - \frac{width}{2} \\ ratio = \frac{l_d}{l_D} -``` +$$ - $l_d$ : actual shift length - $l_D$ : shiftable length @@ -485,9 +485,9 @@ After calculating the future position of Ego and object, the module calculates t The value of the longitudinal margin is calculated based on Responsibility-Sensitive Safety theory ([RSS](https://newsroom.intel.com/articles/rss-explained-five-rules-autonomous-vehicle-safety/#gs.ljzofv)). The `safety_check_idling_time` represents $T_{idle}$, and `safety_check_accel_for_rss` represents $a_{max}$. -```math +$$ D_{lon} = V_{ego}T_{idle} + \frac{1}{2}a_{max}T_{idle}^2 + \frac{(V_{ego} + a_{max}T_{idle})^2}{2a_{max}} - \frac{V_{obj}^2}{2a_{max}} -``` +$$ The lateral margin is changeable based on ego longitudinal velocity. If the vehicle is driving at a high speed, the lateral margin should be larger, and if the vehicle is driving at a low speed, the value of the lateral margin should be set to a smaller value. Thus, the lateral margin for each vehicle speed is set as a parameter, and the module determines the lateral margin from the current vehicle speed as shown in the following figure. @@ -534,9 +534,9 @@ The module determines that it is NOT passable without avoidance if the object ov lateral_passable_collision_margin: 0.5 # [-] ``` -```math +$$ L_{overhang} < \frac{W}{2} + L_{margin} (not passable) -``` +$$ The $W$ represents vehicle width, and $L_{margin}$ represents `lateral_passable_collision_margin`. @@ -550,9 +550,9 @@ The current behavior in unsafe condition is just slow down and it is so conserva The YIELD maneuver is executed **ONLY** when the vehicle has **NOT** initiated avoidance maneuver. The module has a threshold parameter (`avoidance_initiate_threshold`) for the amount of shifting and determines that the vehicle is initiating avoidance if the vehicle current shift exceeds the threshold. -```math +$$ SHIFT_{current} > L_{threshold} -``` +$$ ![fig1](./image/avoidance/yield_limitation.svg) diff --git a/planning/behavior_path_planner/behavior_path_planner_path_generation_design.md b/planning/behavior_path_planner/behavior_path_planner_path_generation_design.md index e73bb11a77ba5..9a42a44fc4900 100644 --- a/planning/behavior_path_planner/behavior_path_planner_path_generation_design.md +++ b/planning/behavior_path_planner/behavior_path_planner_path_generation_design.md @@ -18,7 +18,7 @@ Note that, due to the rarity of the $T_v$ in almost all cases of lane change and By applying simple integral operations, the following analytical equations can be derived to describe the shift distance $l(t)$ at each time under lateral jerk, acceleration, and velocity constraints. -```math +$$ \begin{align} l_1&= \frac{1}{6}jT_j^3\\[10pt] l_2&= \frac{1}{6}j T_j^3 + \frac{1}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j\\[10pt] @@ -28,7 +28,7 @@ l_5&= \frac{11}{6} j T_j^3 + \frac{5}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j + l_6&= \frac{11}{6} j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v\\[10pt] l_7&= 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v \end{align} -``` +$$ These equations are used to determine the shape of a path. Additionally, by applying further mathematical operations to these basic equations, the expressions of the following subsections can be derived. @@ -36,40 +36,40 @@ These equations are used to determine the shape of a path. Additionally, by appl In the case where there are no limitations on lateral velocity and lateral acceleration, the maximum lateral acceleration during the shifting can be calculated as follows. The constant-jerk time is given by $T_j = T_{\rm total}/4$ because of its symmetric property. Since $T_a=T_v=0$, the final shift length $L=l_7=2jT_j^3$ can be determined using the above equation. The maximum lateral acceleration is then given by $a_{\rm max} =jT_j$. This results in the following expression for the maximum lateral acceleration: -```math +$$ \begin{align} a_{\rm max} = \frac{8L}{T_{\rm total}^2} \end{align} -``` +$$ ### Calculation of Ta, Tj and jerk from acceleration limit In the case where there are no limitations on lateral velocity, the constant-jerk and acceleration times, as well as the required jerk can be calculated from the acceleration limit, total time, and final shift length as follows. Since $T_v=0$, the final shift length is given by: -```math +$$ \begin{align} L = l_7 = 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j \end{align} -``` +$$ Additionally, the velocity profile reveals the following relations: -```math +$$ \begin{align} a_{\rm lim} &= j T_j\\ T_{\rm total} &= 4T_j + 2T_a \end{align} -``` +$$ By solving these three equations, the following can be obtained: -```math +$$ \begin{align} T_j&=\frac{T_{\rm total}}{2} - \frac{2L}{a_{\rm lim} T_{\rm total}}\\[10pt] T_a&=\frac{4L}{a_{\rm lim} T_{\rm total}} - \frac{T_{\rm total}}{2}\\[10pt] jerk&=\frac{2a_{\rm lim} ^2T_{\rm total}}{a_{\rm lim} T_{\rm total}^2-4L} \end{align} -``` +$$ where $T_j$ is the constant-jerk time, $T_a$ is the constant acceleration time, $j$ is the required jerk, $a_{\rm lim}$ is the acceleration limit, and $L$ is the final shift length. @@ -77,18 +77,18 @@ where $T_j$ is the constant-jerk time, $T_a$ is the constant acceleration time, In the case where there are no limitations on lateral velocity, the total time required for shifting can be calculated from the jerk and acceleration limits and the final shift length as follows. By solving the two equations given above: -```math +$$ L = l_7 = 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j,\quad a_{\rm lim} = j T_j -``` +$$ we obtain the following expressions: -```math +$$ \begin{align} T_j &= \frac{a_{\rm lim}}{j}\\[10pt] T_a &= \frac{1}{2}\sqrt{\frac{a_{\rm lim}}{j}^2 + \frac{4L}{a_{\rm lim}}} - \frac{3a_{\rm lim}}{2j} \end{align} -``` +$$ The total time required for shifting can then be calculated as $T_{\rm total}=4T_j+2T_a$. From 75f99c7d224b58e01e593b0b81b2fcc070466979 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Mar 2023 20:25:37 +0900 Subject: [PATCH 082/121] feat(tier4_control_launch): add check_external_emergency_heartbeat option (#3079) Signed-off-by: Takayuki Murooka --- launch/tier4_control_launch/launch/control.launch.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 6821388e174d4..63f3523503219 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -199,6 +199,11 @@ def launch_setup(context, *args, **kwargs): parameters=[ vehicle_cmd_gate_param, vehicle_info_param, + { + "check_external_emergency_heartbeat": LaunchConfiguration( + "check_external_emergency_heartbeat" + ), + }, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -338,6 +343,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("external_cmd_selector_param_path") add_launch_arg("aeb_param_path") add_launch_arg("enable_autonomous_emergency_braking") + add_launch_arg("check_external_emergency_heartbeat") # component add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") From 572f39e429dd0e7ff144b8563446094487aa6e81 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 23 Mar 2023 20:31:15 +0900 Subject: [PATCH 083/121] feat(tier4_perception_rviz_plugin): add bicycle panel (#3157) select motorcycle or bicycle and publish Signed-off-by: Mamoru Sobue --- .../icons/classes/BikeInitialPoseTool.png | Bin 0 -> 18815 bytes .../plugins/plugin_description.xml | 4 + .../src/tools/car_pose.cpp | 96 ++++++++++++++++++ .../src/tools/car_pose.hpp | 11 ++ .../src/tools/interactive_object.hpp | 1 + 5 files changed, 112 insertions(+) create mode 100644 common/tier4_perception_rviz_plugin/icons/classes/BikeInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/BikeInitialPoseTool.png b/common/tier4_perception_rviz_plugin/icons/classes/BikeInitialPoseTool.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml b/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml index 3e75efc966985..853a471c7c6e4 100644 --- a/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml +++ b/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml @@ -11,6 +11,10 @@ type="rviz_plugins::BusInitialPoseTool" base_class_type="rviz_common::Tool"> + + diff --git a/common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp b/common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp index 654683ea925eb..cf07eeed99b3a 100644 --- a/common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp +++ b/common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp @@ -238,8 +238,104 @@ Object BusInitialPoseTool::createObjectMsg() const return object; } +BikeInitialPoseTool::BikeInitialPoseTool() +{ + // short cut below cyclist + shortcut_key_ = 'c'; + + enable_interactive_property_ = new rviz_common::properties::BoolProperty( + "Interactive", false, "Enable/Disable interactive action by manipulating mouse.", + getPropertyContainer()); + property_frame_ = new rviz_common::properties::TfFrameProperty( + "Target Frame", rviz_common::properties::TfFrameProperty::FIXED_FRAME_STRING, + "The TF frame where the point cloud is output.", getPropertyContainer(), nullptr, true); + topic_property_ = new rviz_common::properties::StringProperty( + "Pose Topic", "/simulation/dummy_perception_publisher/object_info", + "The topic on which to publish dummy object info.", getPropertyContainer(), SLOT(updateTopic()), + this); + std_dev_x_ = new rviz_common::properties::FloatProperty( + "X std deviation", 0.03, "X standard deviation for initial pose [m]", getPropertyContainer()); + std_dev_y_ = new rviz_common::properties::FloatProperty( + "Y std deviation", 0.03, "Y standard deviation for initial pose [m]", getPropertyContainer()); + std_dev_z_ = new rviz_common::properties::FloatProperty( + "Z std deviation", 0.03, "Z standard deviation for initial pose [m]", getPropertyContainer()); + std_dev_theta_ = new rviz_common::properties::FloatProperty( + "Theta std deviation", 5.0 * M_PI / 180.0, "Theta standard deviation for initial pose [rad]", + getPropertyContainer()); + length_ = new rviz_common::properties::FloatProperty( + "L vehicle length", 1.5, "L length for vehicle [m]", getPropertyContainer()); + width_ = new rviz_common::properties::FloatProperty( + "W vehicle width", 0.5, "W width for vehicle [m]", getPropertyContainer()); + height_ = new rviz_common::properties::FloatProperty( + "H vehicle height", 1.0, "H height for vehicle [m]", getPropertyContainer()); + position_z_ = new rviz_common::properties::FloatProperty( + "Z position", 0.0, "Z position for initial pose [m]", getPropertyContainer()); + velocity_ = new rviz_common::properties::FloatProperty( + "Velocity", 0.0, "velocity [m/s]", getPropertyContainer()); + accel_ = new rviz_common::properties::FloatProperty( + "Acceleration", 0.0, "acceleration [m/s^2]", getPropertyContainer()); + max_velocity_ = new rviz_common::properties::FloatProperty( + "Max velocity", 33.3, "Max velocity [m/s]", getPropertyContainer()); + min_velocity_ = new rviz_common::properties::FloatProperty( + "Min velocity", -33.3, "Min velocity [m/s]", getPropertyContainer()); + label_ = new rviz_common::properties::EnumProperty( + "Type", "BICYCLE", "BICYCLE or MOTORCYCLE", getPropertyContainer()); + std_dev_x_->setMin(0); + std_dev_y_->setMin(0); + std_dev_z_->setMin(0); + std_dev_theta_->setMin(0); + position_z_->setMin(0); + label_->addOption("BICYCLE", ObjectClassification::BICYCLE); + label_->addOption("MOTORCYCLE", ObjectClassification::MOTORCYCLE); +} + +void BikeInitialPoseTool::onInitialize() +{ + rviz_plugins::InteractiveObjectTool::onInitialize(); + setName("2D Dummy Bicycle"); + updateTopic(); +} + +Object BikeInitialPoseTool::createObjectMsg() const +{ + Object object{}; + std::string fixed_frame = context_->getFixedFrame().toStdString(); + + // header + object.header.frame_id = fixed_frame; + object.header.stamp = clock_->now(); + + // semantic + object.classification.label = label_->getOptionInt(); + object.classification.probability = 1.0; + + // shape + object.shape.type = Shape::BOUNDING_BOX; + object.shape.dimensions.x = length_->getFloat(); + object.shape.dimensions.y = width_->getFloat(); + object.shape.dimensions.z = height_->getFloat(); + + // initial state + object.initial_state.pose_covariance.pose.position.z = position_z_->getFloat(); + object.initial_state.pose_covariance.covariance[0] = + std_dev_x_->getFloat() * std_dev_x_->getFloat(); + object.initial_state.pose_covariance.covariance[7] = + std_dev_y_->getFloat() * std_dev_y_->getFloat(); + object.initial_state.pose_covariance.covariance[14] = + std_dev_z_->getFloat() * std_dev_z_->getFloat(); + object.initial_state.pose_covariance.covariance[35] = + std_dev_theta_->getFloat() * std_dev_theta_->getFloat(); + + std::mt19937 gen(std::random_device{}()); + std::independent_bits_engine bit_eng(gen); + std::generate(object.id.uuid.begin(), object.id.uuid.end(), bit_eng); + + return object; +} + } // end namespace rviz_plugins #include PLUGINLIB_EXPORT_CLASS(rviz_plugins::CarInitialPoseTool, rviz_common::Tool) PLUGINLIB_EXPORT_CLASS(rviz_plugins::BusInitialPoseTool, rviz_common::Tool) +PLUGINLIB_EXPORT_CLASS(rviz_plugins::BikeInitialPoseTool, rviz_common::Tool) diff --git a/common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp b/common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp index 43afe7db95dcd..4fc6aeb71771d 100644 --- a/common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp +++ b/common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp @@ -73,6 +73,17 @@ class BusInitialPoseTool : public InteractiveObjectTool [[nodiscard]] Object createObjectMsg() const override; }; +class BikeInitialPoseTool : public InteractiveObjectTool +{ +public: + BikeInitialPoseTool(); + void onInitialize() override; + [[nodiscard]] Object createObjectMsg() const override; + +private: + rviz_common::properties::EnumProperty * label_; +}; + } // namespace rviz_plugins #endif // TOOLS__CAR_POSE_HPP_ diff --git a/common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp b/common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp index 6f0b382eb0b58..fc40b08be822b 100644 --- a/common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp +++ b/common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp @@ -52,6 +52,7 @@ #include #include #include +#include #include #include #include From 9f5876180886b6c88788d5fe0394fce15f2d400f Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 24 Mar 2023 10:04:36 +0900 Subject: [PATCH 084/121] feat(behavior_path_planner): add distance explanation (#3158) * feat(behavior_path_planner): add distance explanation Signed-off-by: yutaka * Update planning/behavior_path_planner/behavior_path_planner_turn_signal_design.md Co-authored-by: Fumiya Watanabe --------- Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- ...ehavior_path_planner_turn_signal_design.md | 4 + .../activation_distance.drawio.svg | 112 ++++++++++++++++++ 2 files changed, 116 insertions(+) create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg diff --git a/planning/behavior_path_planner/behavior_path_planner_turn_signal_design.md b/planning/behavior_path_planner/behavior_path_planner_turn_signal_design.md index 8ee9a8f40a346..518df7f414627 100644 --- a/planning/behavior_path_planner/behavior_path_planner_turn_signal_design.md +++ b/planning/behavior_path_planner/behavior_path_planner_turn_signal_design.md @@ -49,6 +49,10 @@ These two sections have the following meanings. - In this section, ego vehicle must activate designated blinkers. However, if there are blinker conflicts, it must solve them based on the algorithm we mention later in this document. - Required section cannot be longer than desired section. +When turning on the blinker, it decides whether or not to turn on the specified blinker based on the distance from the front of the ego vehicle to the start point of each section. Conversely, when turning off the blinker, it calculates the distance from the base link of the ego vehicle to the end point of each section and decide whether or not to turn it off based on that. + +![activation_distance](./image/turn_signal_decider/activation_distance.drawio.svg) + For left turn, right turn, avoidance, lane change, pull over and pull out, we define these two sections, which are elaborated in the following part. #### 1. Left and Right turn diff --git a/planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg new file mode 100644 index 0000000000000..8303e9502f7c4 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg @@ -0,0 +1,112 @@ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ start point +
+
+
+
+ start point +
+
+ + + + +
+
+
+ end point +
+
+
+
+ end point +
+
+ + + + + + + + + + + + + +
+
+
+ Front point to start point +
+
+
+
+ Front point to start poi... +
+
+ + + + +
+
+
+ End point to base link +
+
+
+
+ End point to base link +
+
+
+ + + + Text is not SVG - cannot display + + +
From 075b8f48f39621c01cf4460d1abbf013abc15bb4 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 24 Mar 2023 11:02:53 +0900 Subject: [PATCH 085/121] feat(blind_spot): revert 2279 and tighten detection condition (#3153) Revert "feat(blind_spot): relax stop condition for predicted objects (#2279)" This reverts commit 6f17a7e0a16a2ffcc8c326dd7e0c9a9d4d569273. --- .../src/scene_module/blind_spot/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp index 1c1bbd42b1115..cccfe3c623a6f 100644 --- a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp @@ -396,7 +396,7 @@ bool BlindSpotModule::checkObstacleInBlindSpot( lanelet::utils::to2D(areas_opt.get().detection_area)); bool exist_in_conflict_area = isPredictedPathInArea( object, areas_opt.get().conflict_area, planner_data_->current_odometry->pose); - if (exist_in_detection_area || exist_in_conflict_area) { + if (exist_in_detection_area && exist_in_conflict_area) { obstacle_detected = true; debug_data_.conflicting_targets.objects.push_back(object); } From e0e2a606381b05a17ca464c7589acda05f584779 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 24 Mar 2023 11:13:20 +0900 Subject: [PATCH 086/121] chore(intersection): display intersection marker only when stopped (#3150) Signed-off-by: Mamoru Sobue --- .../scene_module/intersection/scene_intersection.hpp | 2 -- .../src/scene_module/intersection/debug.cpp | 10 ++++++---- .../scene_module/intersection/scene_intersection.cpp | 1 - 3 files changed, 6 insertions(+), 7 deletions(-) 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 a7ae4b496ef5d..7a4873c5dc66a 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 @@ -48,8 +48,6 @@ class IntersectionModule : public SceneModuleInterface public: struct DebugData { - bool stop_required; - geometry_msgs::msg::Pose stop_wall_pose; geometry_msgs::msg::Polygon stuck_vehicle_detect_area; geometry_msgs::msg::Polygon candidate_collision_ego_lane_polygon; diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/debug.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/debug.cpp index 861bcb05b726a..b2174e69512d8 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/debug.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/debug.cpp @@ -176,10 +176,12 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createVirtualWallMarker const auto now = this->clock_->now(); - appendMarkerArray( - virtual_wall_marker_creator_->createStopVirtualWallMarker( - {debug_data_.stop_wall_pose}, "intersection", now, module_id_), - &wall_marker, now); + if (state_machine_.getState() == StateMachine::State::STOP) { + appendMarkerArray( + virtual_wall_marker_creator_->createStopVirtualWallMarker( + {debug_data_.stop_wall_pose}, "intersection", now, module_id_), + &wall_marker, now); + } return wall_marker; } diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp index 5872972678685..359f3eeaa4765 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp @@ -271,7 +271,6 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * constexpr double v = 0.0; planning_utils::setVelocityFromIndex(stop_line_idx.value(), v, path); - debug_data_.stop_required = true; const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; debug_data_.stop_wall_pose = planning_utils::getAheadPose(stop_line_idx.value(), base_link2front, *path); From e6dfa181e87dd75cc70f5296cfb05caea6b8fbbd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 24 Mar 2023 11:51:05 +0900 Subject: [PATCH 087/121] feat(obstacle_avoidance_planner): consider behavior's drivable area violation (#3086) * feat(obstacle_avoidance_planner): consider behavior's drivable area violation Signed-off-by: Takayuki Murooka * update param Signed-off-by: Takayuki Murooka * changed implementation Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 11 ++-- .../mpt_optimizer.hpp | 3 + .../src/mpt_optimizer.cpp | 55 +++++++++++++++++++ 3 files changed, 64 insertions(+), 5 deletions(-) diff --git a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml index 334da22dc27c0..5586de985d8d7 100644 --- a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml +++ b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml @@ -61,7 +61,7 @@ mpt: option: # TODO(murooka) enable the following. Currently enabling the flag makes QP so heavy - steer_limit_constraint: false # true + steer_limit_constraint: false visualize_sampling_num: 1 enable_manual_warm_start: false enable_warm_start: true @@ -102,10 +102,11 @@ # avoidance avoidance: - max_avoidance_cost: 0.5 # [m] - avoidance_cost_margin: 0.0 # [m] - avoidance_cost_band_length: 5.0 # [m] - avoidance_cost_decrease_rate: 0.05 # decreased cost per point interval + max_longitudinal_margin_for_bound_violation: 1.0 # [m] + max_avoidance_cost: 0.5 # [m] + avoidance_cost_margin: 0.0 # [m] + avoidance_cost_band_length: 5.0 # [m] + avoidance_cost_decrease_rate: 0.05 # decreased cost per point interval weight: lat_error_weight: 0.0 # weight for lateral error diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index 4c70a02ce650b..eaffa77cb7826 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -178,6 +178,7 @@ class MPTOptimizer double steer_rate_weight; // avoidance + double max_longitudinal_margin_for_bound_violation; double max_avoidance_cost; double avoidance_cost_margin; double avoidance_cost_band_length; @@ -248,6 +249,8 @@ class MPTOptimizer std::vector & ref_points, const std::vector & left_bound, const std::vector & right_bound) const; + std::vector extendViolatedBounds( + const std::vector & ref_points) const; void updateVehicleBounds( std::vector & ref_points, const SplineInterpolationPoints2d & ref_points_spline) const; diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index dc95d7e1809a0..f5ec33cc84ccb 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -234,6 +234,8 @@ MPTOptimizer::MPTParam::MPTParam( } { // avoidance + max_longitudinal_margin_for_bound_violation = + node->declare_parameter("mpt.avoidance.max_longitudinal_margin_for_bound_violation"); max_avoidance_cost = node->declare_parameter("mpt.avoidance.max_avoidance_cost"); avoidance_cost_margin = node->declare_parameter("mpt.avoidance.avoidance_cost_margin"); avoidance_cost_band_length = @@ -374,6 +376,9 @@ void MPTOptimizer::MPTParam::onParam(const std::vector & para } { // avoidance + updateParam( + parameters, "mpt.avoidance.max_longitudinal_margin_for_bound_violation", + max_longitudinal_margin_for_bound_violation); updateParam(parameters, "mpt.avoidance.max_avoidance_cost", max_avoidance_cost); updateParam(parameters, "mpt.avoidance.avoidance_cost_margin", avoidance_cost_margin); updateParam( @@ -785,6 +790,9 @@ void MPTOptimizer::updateBounds( ref_point.bounds = Bounds{dist_to_right_bound, dist_to_left_bound}; } + // extend violated bounds, where the input path is outside the drivable area + ref_points = extendViolatedBounds(ref_points); + /* // TODO(murooka) deal with filling data between obstacles // fill between obstacles @@ -806,6 +814,53 @@ void MPTOptimizer::updateBounds( return; } +std::vector MPTOptimizer::extendViolatedBounds( + const std::vector & ref_points) const +{ + auto extended_ref_points = ref_points; + const int max_length_idx = std::floor( + mpt_param_.max_longitudinal_margin_for_bound_violation / mpt_param_.delta_arc_length); + for (int i = 0; i < static_cast(ref_points.size()) - 1; ++i) { + // before violation + if ( + ref_points.at(i).bounds.lower_bound <= 0.0 && + 0.0 <= ref_points.at(i + 1).bounds.lower_bound) { + for (int j = 0; j <= max_length_idx; ++j) { + const int k = std::clamp(i - j, 0, static_cast(ref_points.size()) - 1); + extended_ref_points.at(k).bounds.lower_bound = ref_points.at(i + 1).bounds.lower_bound; + } + } + + if ( + 0.0 <= ref_points.at(i).bounds.upper_bound && + ref_points.at(i + 1).bounds.upper_bound <= 0.0) { + for (int j = 0; j <= max_length_idx; ++j) { + const int k = std::clamp(i - j, 0, static_cast(ref_points.size()) - 1); + extended_ref_points.at(k).bounds.upper_bound = ref_points.at(i + 1).bounds.upper_bound; + } + } + + // after violation + if (0 <= ref_points.at(i).bounds.lower_bound && ref_points.at(i + 1).bounds.lower_bound <= 0) { + for (int j = 0; j <= max_length_idx; ++j) { + const int k = std::clamp(i + j, 0, static_cast(ref_points.size()) - 1); + extended_ref_points.at(k).bounds.lower_bound = ref_points.at(i).bounds.lower_bound; + } + } + + if ( + ref_points.at(i).bounds.upper_bound <= 0.0 && + 0.0 <= ref_points.at(i + 1).bounds.upper_bound) { + for (int j = 0; j <= max_length_idx; ++j) { + const int k = std::clamp(i + j, 0, static_cast(ref_points.size()) - 1); + extended_ref_points.at(k).bounds.upper_bound = ref_points.at(i).bounds.upper_bound; + } + } + } + + return extended_ref_points; +} + void MPTOptimizer::updateVehicleBounds( std::vector & ref_points, const SplineInterpolationPoints2d & ref_points_spline) const From 84c72cd4e4817186f6414ca1982a6ac1292e8b2a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 24 Mar 2023 16:29:53 +0900 Subject: [PATCH 088/121] fix(avoidance): fix shift line generation logic (#3099) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 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 d48e141fb55fe..282edb7a9ed79 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 @@ -1115,8 +1115,8 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( if (!data.avoiding_now) { o.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; debug.unavoidable_objects.push_back(o); + continue; } - continue; } // This is the case of exceeding the jerk limit. Use the sharp avoidance ego speed. @@ -1129,8 +1129,8 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( if (!data.avoiding_now) { o.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; debug.unavoidable_objects.push_back(o); + continue; } - continue; } } const auto avoiding_distance = From 8cc9e277dcd382beb148c96ff4cb11f0a281a9ef Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 24 Mar 2023 17:09:37 +0900 Subject: [PATCH 089/121] feat(tier4_simulator_launch): convert /diagnostics_err (#3152) Signed-off-by: Takayuki Murooka --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 70b87921ecca5..eb5fee271d662 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -109,7 +109,7 @@ - + From 319577a9caeac1ca899dbf3ec15490e97910f6a9 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sun, 26 Mar 2023 13:19:53 +0900 Subject: [PATCH 090/121] chore: sync files (#2907) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- .pre-commit-config-optional.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 c114dac59e325..3c0f0862c92ab 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -77,7 +77,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v34 + uses: tj-actions/changed-files@v35 with: files: | **/*.cpp diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index e0019e10d5210..caa92d0812ab0 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.10.3 + rev: v3.11.0 hooks: - id: markdown-link-check args: [--config=.markdown-link-check.json] From f5770cc3175f30a5758bc11949fa86d030b5aed3 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 27 Mar 2023 00:14:47 +0000 Subject: [PATCH 091/121] chore: sync files (#3163) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .pre-commit-config.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 5e57d3b6c0998..da14e953ba1c1 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -24,12 +24,12 @@ repos: args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v3.0.0-alpha.4 + rev: v3.0.0-alpha.6 hooks: - id: prettier - repo: https://github.com/adrienverge/yamllint - rev: v1.29.0 + rev: v1.30.0 hooks: - id: yamllint @@ -49,7 +49,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.6.0-1 + rev: v3.6.0-2 hooks: - id: shfmt args: [-w, -s, -i=4] @@ -66,7 +66,7 @@ repos: args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v15.0.7 + rev: v16.0.0 hooks: - id: clang-format types_or: [c++, c, cuda] From d5d14afdd7480d47bbb85ee852ad2df086fcd7bd Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 27 Mar 2023 12:02:24 +0900 Subject: [PATCH 092/121] refactor(mpc): remove unused file (#3164) Signed-off-by: Takamasa Horibe --- .../src/smooth_stop.cpp | 161 ------------------ 1 file changed, 161 deletions(-) delete mode 100644 control/mpc_lateral_controller/src/smooth_stop.cpp diff --git a/control/mpc_lateral_controller/src/smooth_stop.cpp b/control/mpc_lateral_controller/src/smooth_stop.cpp deleted file mode 100644 index 564acd62c0d82..0000000000000 --- a/control/mpc_lateral_controller/src/smooth_stop.cpp +++ /dev/null @@ -1,161 +0,0 @@ -// Copyright 2021 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 "mpc_lateral_controller/smooth_stop.hpp" - -#include // NOLINT - -#include -#include -#include -#include -#include - -namespace autoware::motion::control::mpc_lateral_controller -{ -void SmoothStop::init(const double pred_vel_in_target, const double pred_stop_dist) -{ - m_weak_acc_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - - // when distance to stopline is near the car - if (pred_stop_dist < std::numeric_limits::epsilon()) { - m_strong_acc = m_params.min_strong_acc; - return; - } - - m_strong_acc = -std::pow(pred_vel_in_target, 2) / (2 * pred_stop_dist); - m_strong_acc = std::max(std::min(m_strong_acc, m_params.max_strong_acc), m_params.min_strong_acc); -} - -void SmoothStop::setParams( - double max_strong_acc, double min_strong_acc, double weak_acc, double weak_stop_acc, - double strong_stop_acc, double min_fast_vel, double min_running_vel, double min_running_acc, - double weak_stop_time, double weak_stop_dist, double strong_stop_dist) -{ - m_params.max_strong_acc = max_strong_acc; - m_params.min_strong_acc = min_strong_acc; - m_params.weak_acc = weak_acc; - m_params.weak_stop_acc = weak_stop_acc; - m_params.strong_stop_acc = strong_stop_acc; - - m_params.min_fast_vel = min_fast_vel; - m_params.min_running_vel = min_running_vel; - m_params.min_running_acc = min_running_acc; - m_params.weak_stop_time = weak_stop_time; - - m_params.weak_stop_dist = weak_stop_dist; - m_params.strong_stop_dist = strong_stop_dist; - - m_is_set_params = true; -} - -std::experimental::optional SmoothStop::calcTimeToStop( - const std::vector> & vel_hist) const -{ - if (!m_is_set_params) { - throw std::runtime_error("Trying to calculate uninitialized SmoothStop"); - } - - // return when vel_hist is empty - const double vel_hist_size = static_cast(vel_hist.size()); - if (vel_hist_size == 0.0) { - return {}; - } - - // calculate some variables for fitting - const rclcpp::Time current_ros_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - double mean_t = 0.0; - double mean_v = 0.0; - double sum_tv = 0.0; - double sum_tt = 0.0; - for (const auto & vel : vel_hist) { - const double t = (vel.first - current_ros_time).seconds(); - const double v = vel.second; - - mean_t += t / vel_hist_size; - mean_v += v / vel_hist_size; - sum_tv += t * v; - sum_tt += t * t; - } - - // return when gradient a (of v = at + b) cannot be calculated. - // See the following calculation of a - if (std::abs(vel_hist_size * mean_t * mean_t - sum_tt) < std::numeric_limits::epsilon()) { - return {}; - } - - // calculate coefficients of linear function (v = at + b) - const double a = - (vel_hist_size * mean_t * mean_v - sum_tv) / (vel_hist_size * mean_t * mean_t - sum_tt); - const double b = mean_v - a * mean_t; - - // return when v is independent of time (v = b) - if (std::abs(a) < std::numeric_limits::epsilon()) { - return {}; - } - - // calculate time to stop by substituting v = 0 for v = at + b - const double time_to_stop = -b / a; - if (time_to_stop > 0) { - return time_to_stop; - } - - return {}; -} - -double SmoothStop::calculate( - const double stop_dist, const double current_vel, const double current_acc, - const std::vector> & vel_hist, const double delay_time) -{ - if (!m_is_set_params) { - throw std::runtime_error("Trying to calculate uninitialized SmoothStop"); - } - - // predict time to stop - const auto time_to_stop = calcTimeToStop(vel_hist); - - // calculate some flags - const bool is_fast_vel = std::abs(current_vel) > m_params.min_fast_vel; - const bool is_running = std::abs(current_vel) > m_params.min_running_vel || - std::abs(current_acc) > m_params.min_running_acc; - - // when exceeding the stopline (stop_dist is negative in these cases.) - if (stop_dist < m_params.strong_stop_dist) { // when exceeding the stopline much - return m_params.strong_stop_acc; - } else if (stop_dist < m_params.weak_stop_dist) { // when exceeding the stopline a bit - return m_params.weak_stop_acc; - } - - // when the car is running - if (is_running) { - // when the car will not stop in a certain time - if (time_to_stop && *time_to_stop > m_params.weak_stop_time + delay_time) { - return m_strong_acc; - } else if (!time_to_stop && is_fast_vel) { - return m_strong_acc; - } - - m_weak_acc_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - return m_params.weak_acc; - } - - // for 0.5 seconds after the car stopped - if ((rclcpp::Clock{RCL_ROS_TIME}.now() - m_weak_acc_time).seconds() < 0.5) { - return m_params.weak_acc; - } - - // when the car is not running - return m_params.strong_stop_acc; -} -} // namespace autoware::motion::control::mpc_lateral_controller From 49722f906df8cb1bd2166ee06101848a447790cc Mon Sep 17 00:00:00 2001 From: Manato Hirabayashi <3022416+manato@users.noreply.github.com> Date: Mon, 27 Mar 2023 12:12:05 +0900 Subject: [PATCH 093/121] feat: add ByteTrack package (#3023) * feat(bytetrack): initial port * refactor(bytetrack): apply naming rule * feat(bytetrack): add a visualizer node * docs(bytetrack): add readme and clarify the license * style(pre-commit): autofix * chore(bytetrack): update/add lisence declaration * docs(bytetrack): specify commit hash to GitHub link * chore: remove unused file * style(bytetrack): rewrite function names to be lower snake case according to style rules * style: eliminate pre-commit error * fix(bytetrack): small bug correction and removing target specific condition * chore(bytetrack): re-order lisence statements * style(pre-commit): autofix * docs(bytetrack): Update README * build(bytetrack): use autoware_cmake to reduce boilerplate code * feat(bytetrack): add a flag to switch visualizer execution * fix(bytetrack): delete unused package from package.xml * fix(bytetrack): remove lint_cmake error * ci(bytetrack): Update package.xml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --------- 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> --- perception/bytetrack/CMakeLists.txt | 93 ++++ perception/bytetrack/README.md | 99 +++++ .../bytetrack/include/bytetrack/bytetrack.hpp | 62 +++ .../include/bytetrack/bytetrack_node.hpp | 59 +++ .../bytetrack/bytetrack_visualizer_node.hpp | 104 +++++ .../bytetrack/launch/bytetrack.launch.xml | 24 ++ .../bytetrack/lib/include/byte_tracker.h | 100 +++++ perception/bytetrack/lib/include/data_type.h | 76 ++++ .../bytetrack/lib/include/kalman_filter.h | 67 +++ perception/bytetrack/lib/include/lapjv.h | 110 +++++ perception/bytetrack/lib/include/strack.h | 94 +++++ perception/bytetrack/lib/src/byte_tracker.cpp | 243 +++++++++++ .../bytetrack/lib/src/kalman_filter.cpp | 175 ++++++++ perception/bytetrack/lib/src/lapjv.cpp | 362 ++++++++++++++++ perception/bytetrack/lib/src/strack.cpp | 222 ++++++++++ perception/bytetrack/lib/src/utils.cpp | 399 ++++++++++++++++++ perception/bytetrack/package.xml | 35 ++ perception/bytetrack/src/bytetrack.cpp | 68 +++ perception/bytetrack/src/bytetrack_node.cpp | 113 +++++ .../src/bytetrack_visualizer_node.cpp | 189 +++++++++ 20 files changed, 2694 insertions(+) create mode 100644 perception/bytetrack/CMakeLists.txt create mode 100644 perception/bytetrack/README.md create mode 100644 perception/bytetrack/include/bytetrack/bytetrack.hpp create mode 100644 perception/bytetrack/include/bytetrack/bytetrack_node.hpp create mode 100644 perception/bytetrack/include/bytetrack/bytetrack_visualizer_node.hpp create mode 100644 perception/bytetrack/launch/bytetrack.launch.xml create mode 100644 perception/bytetrack/lib/include/byte_tracker.h create mode 100644 perception/bytetrack/lib/include/data_type.h create mode 100644 perception/bytetrack/lib/include/kalman_filter.h create mode 100644 perception/bytetrack/lib/include/lapjv.h create mode 100644 perception/bytetrack/lib/include/strack.h create mode 100644 perception/bytetrack/lib/src/byte_tracker.cpp create mode 100644 perception/bytetrack/lib/src/kalman_filter.cpp create mode 100644 perception/bytetrack/lib/src/lapjv.cpp create mode 100644 perception/bytetrack/lib/src/strack.cpp create mode 100644 perception/bytetrack/lib/src/utils.cpp create mode 100644 perception/bytetrack/package.xml create mode 100644 perception/bytetrack/src/bytetrack.cpp create mode 100644 perception/bytetrack/src/bytetrack_node.cpp create mode 100644 perception/bytetrack/src/bytetrack_visualizer_node.cpp diff --git a/perception/bytetrack/CMakeLists.txt b/perception/bytetrack/CMakeLists.txt new file mode 100644 index 0000000000000..3e3d520eef14a --- /dev/null +++ b/perception/bytetrack/CMakeLists.txt @@ -0,0 +1,93 @@ +cmake_minimum_required(VERSION 3.5) +project(bytetrack) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(OpenCV REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(OpenMP REQUIRED) +if(OpenMP_FOUND) + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") +endif() +find_package(Boost REQUIRED) + +# +# Core library +# +file(GLOB bytetrack_lib_src + "lib/src/*.cpp" +) + +ament_auto_add_library(bytetrack_lib SHARED + ${bytetrack_lib_src} +) + +target_include_directories(bytetrack_lib + PUBLIC + $ + $ +) + +# +# ROS node +# +ament_auto_add_library(${PROJECT_NAME} SHARED + src/bytetrack.cpp +) + +ament_target_dependencies(${PROJECT_NAME} + OpenCV +) + +target_include_directories(${PROJECT_NAME} + PUBLIC + $ + $ +) + +target_compile_definitions(${PROJECT_NAME} PRIVATE + TENSORRT_VERSION_MAJOR=${TENSORRT_VERSION_MAJOR} +) + +ament_auto_add_library(${PROJECT_NAME}_node SHARED + src/bytetrack_node.cpp +) + +ament_target_dependencies(${PROJECT_NAME}_node + OpenCV +) + +target_link_libraries(${PROJECT_NAME}_node + ${PROJECT_NAME} +) + +target_compile_definitions(${PROJECT_NAME}_node PRIVATE + TENSORRT_VERSION_MAJOR=${TENSORRT_VERSION_MAJOR} +) + +rclcpp_components_register_node(${PROJECT_NAME}_node + PLUGIN "bytetrack::ByteTrackNode" + EXECUTABLE ${PROJECT_NAME}_node_exe +) + +# +# Visualizer +# +ament_auto_add_library(${PROJECT_NAME}_visualizer SHARED + src/bytetrack_visualizer_node.cpp +) + +ament_target_dependencies(${PROJECT_NAME}_visualizer + OpenCV +) + +rclcpp_components_register_node(${PROJECT_NAME}_visualizer + PLUGIN "bytetrack::ByteTrackVisualizerNode" + EXECUTABLE ${PROJECT_NAME}_visualizer_node_exe +) + +ament_auto_package(INSTALL_TO_SHARE + launch +) diff --git a/perception/bytetrack/README.md b/perception/bytetrack/README.md new file mode 100644 index 0000000000000..c71b62cada29f --- /dev/null +++ b/perception/bytetrack/README.md @@ -0,0 +1,99 @@ +# bytetrack + +## Purpose + +The core algorithm, named `ByteTrack`, mainly aims to perform multi-object tracking. +Because the algorithm associates almost every detection box including ones with low detection scores, +the number of false negatives is expected to decrease by using it. + +[demo video](https://user-images.githubusercontent.com/3022416/225920856-745a3bb7-6b35-403d-87b0-6e5085952d70.mp4) + +## Inner-workings / Algorithms + +### Cite + +- Yifu Zhang, Peize Sun, Yi Jiang, Dongdong Yu, Fucheng Weng, Zehuan Yuan, Ping Luo, Wenyu Liu, and Xinggang Wang, + "ByteTrack: Multi-Object Tracking by Associating Every Detection Box", in the proc. of the ECCV + 2022, [[ref](https://arxiv.org/abs/2110.06864)] +- This package is ported version toward Autoware from [this repository](https://github.com/ifzhang/ByteTrack/tree/main/deploy/TensorRT/cpp) + (The C++ implementation by the ByteTrack's authors) + +## Inputs / Outputs + +### bytetrack_node + +#### Input + +| Name | Type | Description | +| --------- | -------------------------------------------------- | ------------------------------------------- | +| `in/rect` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes | + +#### Output + +| Name | Type | Description | +| ------------------------ | -------------------------------------------------- | --------------------------------------------------------- | +| `out/objects` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes | +| `out/objects/debug/uuid` | `tier4_perception_msgs/DynamicObjectArray` | The universally unique identifiers (UUID) for each object | + +### bytetrack_visualizer + +#### Input + +| Name | Type | Description | +| ---------- | ---------------------------------------------------- | --------------------------------------------------------- | +| `in/image` | `sensor_msgs/Image` or `sensor_msgs/CompressedImage` | The input image on which object detection is performed | +| `in/rect` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes | +| `in/uuid` | `tier4_perception_msgs/DynamicObjectArray` | The universally unique identifiers (UUID) for each object | + +#### Output + +| Name | Type | Description | +| ----------- | ------------------- | ----------------------------------------------------------------- | +| `out/image` | `sensor_msgs/Image` | The image that detection bounding boxes and their UUIDs are drawn | + +## Parameters + +### bytetrack_node + +| Name | Type | Default Value | Description | +| --------------------- | ---- | ------------- | -------------------------------------------------------- | +| `track_buffer_length` | int | 30 | The frame count that a tracklet is considered to be lost | + +### bytetrack_visualizer + +| Name | Type | Default Value | Description | +| --------- | ---- | ------------- | --------------------------------------------------------------------------------------------- | +| `use_raw` | bool | false | The flag for the node to switch `sensor_msgs/Image` or `sensor_msgs/CompressedImage` as input | + +## Assumptions/Known limits + +## Reference repositories + +- + +## License + +The codes under the `lib` directory are copied from [the original codes](https://github.com/ifzhang/ByteTrack/tree/72ca8b45d36caf5a39e949c6aa815d9abffd1ab5/deploy/TensorRT/cpp) and modified. +The original codes belong to the MIT license stated as follows, while this ported packages are provided with Apache License 2.0: + +> MIT License +> +> Copyright (c) 2021 Yifu Zhang +> +> Permission is hereby granted, free of charge, to any person obtaining a copy +> of this software and associated documentation files (the "Software"), to deal +> in the Software without restriction, including without limitation the rights +> to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +> copies of the Software, and to permit persons to whom the Software is +> furnished to do so, subject to the following conditions: +> +> The above copyright notice and this permission notice shall be included in all +> copies or substantial portions of the Software. +> +> THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +> IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +> FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +> AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +> LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +> OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +> SOFTWARE. diff --git a/perception/bytetrack/include/bytetrack/bytetrack.hpp b/perception/bytetrack/include/bytetrack/bytetrack.hpp new file mode 100644 index 0000000000000..549ecaac84567 --- /dev/null +++ b/perception/bytetrack/include/bytetrack/bytetrack.hpp @@ -0,0 +1,62 @@ +// 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 BYTETRACK__BYTETRACK_HPP_ +#define BYTETRACK__BYTETRACK_HPP_ + +#include "byte_tracker.h" +#include "strack.h" + +#include +#include + +#include + +#include +#include +#include +#include + +namespace bytetrack +{ +struct Object +{ + int32_t x_offset; + int32_t y_offset; + int32_t height; + int32_t width; + float score; + int32_t type; + int32_t track_id; + boost::uuids::uuid unique_id; +}; + +using ObjectArray = std::vector; + +class ByteTrack +{ +public: + explicit ByteTrack(const int track_buffer_length = 30); + + bool do_inference(ObjectArray & objects); + ObjectArray update_tracker(ObjectArray & input_objects); + +private: + std::unique_ptr tracker_; + ObjectArray latest_objects_; +}; + +} // namespace bytetrack + +#endif // BYTETRACK__BYTETRACK_HPP_ diff --git a/perception/bytetrack/include/bytetrack/bytetrack_node.hpp b/perception/bytetrack/include/bytetrack/bytetrack_node.hpp new file mode 100644 index 0000000000000..6b801ddf93268 --- /dev/null +++ b/perception/bytetrack/include/bytetrack/bytetrack_node.hpp @@ -0,0 +1,59 @@ +// 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 BYTETRACK__BYTETRACK_NODE_HPP_ +#define BYTETRACK__BYTETRACK_NODE_HPP_ + +#include +#include + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace bytetrack +{ +using LabelMap = std::map; + +class ByteTrackNode : public rclcpp::Node +{ +public: + explicit ByteTrackNode(const rclcpp::NodeOptions & node_options); + +private: + void on_connect(); + void on_rect(const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr msg); + + rclcpp::Publisher::SharedPtr objects_pub_; + rclcpp::Publisher::SharedPtr objects_uuid_pub_; + + rclcpp::Subscription::SharedPtr + detection_rect_sub_; + + rclcpp::TimerBase::SharedPtr timer_; + + std::unique_ptr bytetrack_; +}; + +} // namespace bytetrack + +#endif // BYTETRACK__BYTETRACK_NODE_HPP_ diff --git a/perception/bytetrack/include/bytetrack/bytetrack_visualizer_node.hpp b/perception/bytetrack/include/bytetrack/bytetrack_visualizer_node.hpp new file mode 100644 index 0000000000000..56f060ecfa9d5 --- /dev/null +++ b/perception/bytetrack/include/bytetrack/bytetrack_visualizer_node.hpp @@ -0,0 +1,104 @@ +// 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 BYTETRACK__BYTETRACK_VISUALIZER_NODE_HPP_ +#define BYTETRACK__BYTETRACK_VISUALIZER_NODE_HPP_ + +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace bytetrack +{ +// A helper class to generate bright color instance +class ColorMapper +{ +public: + const size_t kColorNum = 512; + ColorMapper() + { + // generate bright color map + cv::Mat src = cv::Mat::zeros(cv::Size(kColorNum, 1), CV_8UC1); + for (size_t i = 0; i < kColorNum; i++) { + src.at(0, i) = i; + } + cv::applyColorMap(src, color_table_, cv::COLORMAP_HSV); + } + + cv::Scalar operator()(size_t idx) + { + if (kColorNum <= idx) { + throw std::runtime_error("idx should be between [0, 255]"); + } + return color_table_.at(0, idx); + } + +protected: + cv::Mat color_table_; +}; + +class ByteTrackVisualizerNode : public rclcpp::Node +{ +public: + explicit ByteTrackVisualizerNode(const rclcpp::NodeOptions & node_options); + ~ByteTrackVisualizerNode(); + +protected: + void on_timer(); + bool get_topic_qos(const std::string & query_topic, rclcpp::QoS & qos); + + void callback( + const sensor_msgs::msg::Image::SharedPtr & image_msg, + const tier4_perception_msgs::msg::DetectedObjectsWithFeature::SharedPtr & rect_msg, + const tier4_perception_msgs::msg::DynamicObjectArray::SharedPtr & uuid_msg); + void draw( + cv::Mat & image, const std::vector & bboxes, + const std::vector & uuids); + + image_transport::SubscriberFilter image_sub_; + message_filters::Subscriber rect_sub_; + message_filters::Subscriber uuid_sub_; + + using ExactTimeSyncPolicy = message_filters::sync_policies::ExactTime< + sensor_msgs::msg::Image, tier4_perception_msgs::msg::DetectedObjectsWithFeature, + tier4_perception_msgs::msg::DynamicObjectArray>; + using ExactTimeSync = message_filters::Synchronizer; + std::shared_ptr sync_ptr_; + + image_transport::Publisher image_pub_; + + rclcpp::TimerBase::SharedPtr timer_; + + bool use_raw_; + ColorMapper color_map_; +}; +} // namespace bytetrack + +#endif // BYTETRACK__BYTETRACK_VISUALIZER_NODE_HPP_ diff --git a/perception/bytetrack/launch/bytetrack.launch.xml b/perception/bytetrack/launch/bytetrack.launch.xml new file mode 100644 index 0000000000000..25ed56b991c30 --- /dev/null +++ b/perception/bytetrack/launch/bytetrack.launch.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/bytetrack/lib/include/byte_tracker.h b/perception/bytetrack/lib/include/byte_tracker.h new file mode 100644 index 0000000000000..08394e6b0ccdf --- /dev/null +++ b/perception/bytetrack/lib/include/byte_tracker.h @@ -0,0 +1,100 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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. + +#pragma once + +#include "strack.h" + +#include + +struct ByteTrackObject +{ + cv::Rect_ rect; + int label; + float prob; +}; + +class ByteTracker +{ +public: + ByteTracker( + int track_buffer = 30, float track_thresh = 0.5, float high_thresh = 0.6, + float match_thresh = 0.8); + ~ByteTracker(); + + std::vector update(const std::vector & objects); + cv::Scalar get_color(int idx); + +private: + std::vector joint_stracks(std::vector & tlista, std::vector & tlistb); + std::vector joint_stracks(std::vector & tlista, std::vector & tlistb); + + std::vector sub_stracks(std::vector & tlista, std::vector & tlistb); + void remove_duplicate_stracks( + std::vector & resa, std::vector & resb, std::vector & stracksa, + std::vector & stracksb); + + void linear_assignment( + std::vector> & cost_matrix, int cost_matrix_size, int cost_matrix_size_size, + float thresh, std::vector> & matches, std::vector & unmatched_a, + std::vector & unmatched_b); + std::vector> iou_distance( + std::vector & atracks, std::vector & btracks, int & dist_size, + int & dist_size_size); + std::vector> iou_distance( + std::vector & atracks, std::vector & btracks); + std::vector> ious( + std::vector> & atlbrs, std::vector> & btlbrs); + + double lapjv( + const std::vector> & cost, std::vector & rowsol, + std::vector & colsol, bool extend_cost = false, float cost_limit = LONG_MAX, + bool return_cost = true); + +private: + float track_thresh; + float high_thresh; + float match_thresh; + int frame_id; + int max_time_lost; + + std::vector tracked_stracks; + std::vector lost_stracks; + std::vector removed_stracks; + byte_kalman::KalmanFilter kalman_filter; +}; diff --git a/perception/bytetrack/lib/include/data_type.h b/perception/bytetrack/lib/include/data_type.h new file mode 100644 index 0000000000000..d76baa8945637 --- /dev/null +++ b/perception/bytetrack/lib/include/data_type.h @@ -0,0 +1,76 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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. + +#pragma once + +#include +#include + +#include +#include +#include +typedef Eigen::Matrix DETECTBOX; +typedef Eigen::Matrix DETECTBOXSS; +typedef Eigen::Matrix FEATURE; +typedef Eigen::Matrix FEATURESS; +// typedef std::vector FEATURESS; + +// Kalmanfilter +// typedef Eigen::Matrix KAL_FILTER; +typedef Eigen::Matrix KAL_MEAN; +typedef Eigen::Matrix KAL_COVA; +typedef Eigen::Matrix KAL_HMEAN; +typedef Eigen::Matrix KAL_HCOVA; +using KAL_DATA = std::pair; +using KAL_HDATA = std::pair; + +// main +using RESULT_DATA = std::pair; + +// tracker: +using TRACKER_DATA = std::pair; +using MATCH_DATA = std::pair; +typedef struct t +{ + std::vector matches; + std::vector unmatched_tracks; + std::vector unmatched_detections; +} TRACHER_MATCHD; + +// linear_assignment: +typedef Eigen::Matrix DYNAMICM; diff --git a/perception/bytetrack/lib/include/kalman_filter.h b/perception/bytetrack/lib/include/kalman_filter.h new file mode 100644 index 0000000000000..f2b1e1c7817dd --- /dev/null +++ b/perception/bytetrack/lib/include/kalman_filter.h @@ -0,0 +1,67 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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. + +#pragma once + +#include "data_type.h" + +#include +namespace byte_kalman +{ +class KalmanFilter +{ +public: + static const double chi2inv95[10]; + KalmanFilter(); + KAL_DATA initiate(const DETECTBOX & measurement); + void predict(KAL_MEAN & mean, KAL_COVA & covariance); + KAL_HDATA project(const KAL_MEAN & mean, const KAL_COVA & covariance); + KAL_DATA update( + const KAL_MEAN & mean, const KAL_COVA & covariance, const DETECTBOX & measurement); + + Eigen::Matrix gating_distance( + const KAL_MEAN & mean, const KAL_COVA & covariance, const std::vector & measurements, + bool only_position = false); + +private: + Eigen::Matrix _motion_mat; + Eigen::Matrix _update_mat; + float _std_weight_position; + float _std_weight_velocity; +}; +} // namespace byte_kalman diff --git a/perception/bytetrack/lib/include/lapjv.h b/perception/bytetrack/lib/include/lapjv.h new file mode 100644 index 0000000000000..d197b747e6f7d --- /dev/null +++ b/perception/bytetrack/lib/include/lapjv.h @@ -0,0 +1,110 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 LAPJV_H_ +#define LAPJV_H_ + +#define LARGE 1000000 + +#if !defined TRUE +#define TRUE 1 +#endif +#if !defined FALSE +#define FALSE 0 +#endif + +#define NEW(x, t, n) \ + if ((x = reinterpret_cast(malloc(sizeof(t) * (n)))) == 0) { \ + return -1; \ + } +#define FREE(x) \ + if (x != 0) { \ + free(x); \ + x = 0; \ + } +#define SWAP_INDICES(a, b) \ + { \ + int_t _temp_index = a; \ + a = b; \ + b = _temp_index; \ + } + +#if 0 +#include +#define ASSERT(cond) assert(cond) +#define PRINTF(fmt, ...) printf(fmt, ##__VA_ARGS__) +#define PRINT_COST_ARRAY(a, n) \ + while (1) { \ + printf(#a " = ["); \ + if ((n) > 0) { \ + printf("%f", (a)[0]); \ + for (uint_t j = 1; j < n; j++) { \ + printf(", %f", (a)[j]); \ + } \ + } \ + printf("]\n"); \ + break; \ + } +#define PRINT_INDEX_ARRAY(a, n) \ + while (1) { \ + printf(#a " = ["); \ + if ((n) > 0) { \ + printf("%d", (a)[0]); \ + for (uint_t j = 1; j < n; j++) { \ + printf(", %d", (a)[j]); \ + } \ + } \ + printf("]\n"); \ + break; \ + } +#else +#define ASSERT(cond) +#define PRINTF(fmt, ...) +#define PRINT_COST_ARRAY(a, n) +#define PRINT_INDEX_ARRAY(a, n) +#endif + +typedef signed int int_t; +typedef unsigned int uint_t; +typedef double cost_t; +typedef char boolean; +typedef enum fp_t { FP_1 = 1, FP_2 = 2, FP_DYNAMIC = 3 } fp_t; + +extern int_t lapjv_internal(const uint_t n, cost_t * cost[], int_t * x, int_t * y); + +#endif // LAPJV_H_ diff --git a/perception/bytetrack/lib/include/strack.h b/perception/bytetrack/lib/include/strack.h new file mode 100644 index 0000000000000..2110723e86c58 --- /dev/null +++ b/perception/bytetrack/lib/include/strack.h @@ -0,0 +1,94 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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. + +#pragma once + +#include "kalman_filter.h" + +#include + +#include + +#include + +enum TrackState { New = 0, Tracked, Lost, Removed }; + +class STrack +{ +public: + STrack(std::vector tlwh_, float score, int label); + ~STrack(); + + std::vector static tlbr_to_tlwh(std::vector & tlbr); + static void multi_predict( + std::vector & stracks, byte_kalman::KalmanFilter & kalman_filter); + void static_tlwh(); + void static_tlbr(); + std::vector tlwh_to_xyah(std::vector tlwh_tmp); + std::vector to_xyah(); + void mark_lost(); + void mark_removed(); + int next_id(); + int end_frame(); + + void activate(byte_kalman::KalmanFilter & kalman_filter, int frame_id); + void re_activate(STrack & new_track, int frame_id, bool new_id = false); + void update(STrack & new_track, int frame_id); + +public: + bool is_activated; + int track_id; + boost::uuids::uuid unique_id; + int state; + + std::vector _tlwh; + std::vector tlwh; + std::vector tlbr; + int frame_id; + int tracklet_len; + int start_frame; + + KAL_MEAN mean; + KAL_COVA covariance; + float score; + + int label; + +private: + byte_kalman::KalmanFilter kalman_filter; +}; diff --git a/perception/bytetrack/lib/src/byte_tracker.cpp b/perception/bytetrack/lib/src/byte_tracker.cpp new file mode 100644 index 0000000000000..77daf8437ea02 --- /dev/null +++ b/perception/bytetrack/lib/src/byte_tracker.cpp @@ -0,0 +1,243 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 "byte_tracker.h" + +#include +#include + +ByteTracker::ByteTracker( + int track_buffer, float track_thresh, float high_thresh, float match_thresh) +: track_thresh(track_thresh), high_thresh(high_thresh), match_thresh(match_thresh) + +{ + frame_id = 0; + max_time_lost = track_buffer; + std::cout << "Init ByteTrack!" << std::endl; +} + +ByteTracker::~ByteTracker() {} + +std::vector ByteTracker::update(const std::vector & objects) +{ + ////////////////// Step 1: Get detections ////////////////// + this->frame_id++; + std::vector activated_stracks; + std::vector refind_stracks; + std::vector removed_stracks; + std::vector lost_stracks; + std::vector detections; + std::vector detections_low; + + std::vector detections_cp; + std::vector tracked_stracks_swap; + std::vector resa, resb; + std::vector output_stracks; + + std::vector unconfirmed; + std::vector tracked_stracks; + std::vector strack_pool; + std::vector r_tracked_stracks; + + if (objects.size() > 0) { + for (size_t i = 0; i < objects.size(); i++) { + std::vector tlbr_; + tlbr_.resize(4); + tlbr_[0] = objects[i].rect.x; + tlbr_[1] = objects[i].rect.y; + tlbr_[2] = objects[i].rect.x + objects[i].rect.width; + tlbr_[3] = objects[i].rect.y + objects[i].rect.height; + + float score = objects[i].prob; + + STrack strack(STrack::tlbr_to_tlwh(tlbr_), score, objects[i].label); + if (score >= track_thresh) { + detections.push_back(strack); + } else { + detections_low.push_back(strack); + } + } + } + + // Add newly detected tracklets to tracked_stracks + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (!this->tracked_stracks[i].is_activated) + unconfirmed.push_back(&this->tracked_stracks[i]); + else + tracked_stracks.push_back(&this->tracked_stracks[i]); + } + + ////////////////// Step 2: First association, with IoU ////////////////// + strack_pool = joint_stracks(tracked_stracks, this->lost_stracks); + STrack::multi_predict(strack_pool, this->kalman_filter); + + std::vector > dists; + int dist_size = 0, dist_size_size = 0; + dists = iou_distance(strack_pool, detections, dist_size, dist_size_size); + + std::vector > matches; + std::vector u_track, u_detection; + linear_assignment(dists, dist_size, dist_size_size, match_thresh, matches, u_track, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + STrack * track = strack_pool[matches[i][0]]; + STrack * det = &detections[matches[i][1]]; + if (track->state == TrackState::Tracked) { + track->update(*det, this->frame_id); + activated_stracks.push_back(*track); + } else { + track->re_activate(*det, this->frame_id, false); + refind_stracks.push_back(*track); + } + } + + ////////////////// Step 3: Second association, using low score dets ////////////////// + for (size_t i = 0; i < u_detection.size(); i++) { + detections_cp.push_back(detections[u_detection[i]]); + } + detections.clear(); + detections.assign(detections_low.begin(), detections_low.end()); + + for (size_t i = 0; i < u_track.size(); i++) { + if (strack_pool[u_track[i]]->state == TrackState::Tracked) { + r_tracked_stracks.push_back(strack_pool[u_track[i]]); + } + } + + dists.clear(); + dists = iou_distance(r_tracked_stracks, detections, dist_size, dist_size_size); + + matches.clear(); + u_track.clear(); + u_detection.clear(); + linear_assignment(dists, dist_size, dist_size_size, 0.5, matches, u_track, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + STrack * track = r_tracked_stracks[matches[i][0]]; + STrack * det = &detections[matches[i][1]]; + if (track->state == TrackState::Tracked) { + track->update(*det, this->frame_id); + activated_stracks.push_back(*track); + } else { + track->re_activate(*det, this->frame_id, false); + refind_stracks.push_back(*track); + } + } + + for (size_t i = 0; i < u_track.size(); i++) { + STrack * track = r_tracked_stracks[u_track[i]]; + if (track->state != TrackState::Lost) { + track->mark_lost(); + lost_stracks.push_back(*track); + } + } + + // Deal with unconfirmed tracks, usually tracks with only one beginning frame + detections.clear(); + detections.assign(detections_cp.begin(), detections_cp.end()); + + dists.clear(); + dists = iou_distance(unconfirmed, detections, dist_size, dist_size_size); + + matches.clear(); + std::vector u_unconfirmed; + u_detection.clear(); + linear_assignment(dists, dist_size, dist_size_size, 0.7, matches, u_unconfirmed, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + unconfirmed[matches[i][0]]->update(detections[matches[i][1]], this->frame_id); + activated_stracks.push_back(*unconfirmed[matches[i][0]]); + } + + for (size_t i = 0; i < u_unconfirmed.size(); i++) { + STrack * track = unconfirmed[u_unconfirmed[i]]; + track->mark_removed(); + removed_stracks.push_back(*track); + } + + ////////////////// Step 4: Init new stracks ////////////////// + for (size_t i = 0; i < u_detection.size(); i++) { + STrack * track = &detections[u_detection[i]]; + if (track->score < this->high_thresh) continue; + track->activate(this->kalman_filter, this->frame_id); + activated_stracks.push_back(*track); + } + + ////////////////// Step 5: Update state ////////////////// + for (size_t i = 0; i < this->lost_stracks.size(); i++) { + if (this->frame_id - this->lost_stracks[i].end_frame() > this->max_time_lost) { + this->lost_stracks[i].mark_removed(); + removed_stracks.push_back(this->lost_stracks[i]); + } + } + + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (this->tracked_stracks[i].state == TrackState::Tracked) { + tracked_stracks_swap.push_back(this->tracked_stracks[i]); + } + } + this->tracked_stracks.clear(); + this->tracked_stracks.assign(tracked_stracks_swap.begin(), tracked_stracks_swap.end()); + + this->tracked_stracks = joint_stracks(this->tracked_stracks, activated_stracks); + this->tracked_stracks = joint_stracks(this->tracked_stracks, refind_stracks); + + this->lost_stracks = sub_stracks(this->lost_stracks, this->tracked_stracks); + for (size_t i = 0; i < lost_stracks.size(); i++) { + this->lost_stracks.push_back(lost_stracks[i]); + } + + this->lost_stracks = sub_stracks(this->lost_stracks, this->removed_stracks); + for (size_t i = 0; i < removed_stracks.size(); i++) { + this->removed_stracks.push_back(removed_stracks[i]); + } + + remove_duplicate_stracks(resa, resb, this->tracked_stracks, this->lost_stracks); + + this->tracked_stracks.clear(); + this->tracked_stracks.assign(resa.begin(), resa.end()); + this->lost_stracks.clear(); + this->lost_stracks.assign(resb.begin(), resb.end()); + + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (this->tracked_stracks[i].is_activated) { + output_stracks.push_back(this->tracked_stracks[i]); + } + } + return output_stracks; +} diff --git a/perception/bytetrack/lib/src/kalman_filter.cpp b/perception/bytetrack/lib/src/kalman_filter.cpp new file mode 100644 index 0000000000000..bc1a88ff60b0e --- /dev/null +++ b/perception/bytetrack/lib/src/kalman_filter.cpp @@ -0,0 +1,175 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 "kalman_filter.h" + +#include + +namespace byte_kalman +{ +const double KalmanFilter::chi2inv95[10] = {0, 3.8415, 5.9915, 7.8147, 9.4877, + 11.070, 12.592, 14.067, 15.507, 16.919}; +KalmanFilter::KalmanFilter() +{ + int ndim = 4; + double dt = 1.; + + _motion_mat = Eigen::MatrixXf::Identity(8, 8); + for (int i = 0; i < ndim; i++) { + _motion_mat(i, ndim + i) = dt; + } + _update_mat = Eigen::MatrixXf::Identity(4, 8); + + this->_std_weight_position = 1. / 20; + this->_std_weight_velocity = 1. / 160; +} + +KAL_DATA KalmanFilter::initiate(const DETECTBOX & measurement) +{ + DETECTBOX mean_pos = measurement; + DETECTBOX mean_vel; + for (int i = 0; i < 4; i++) mean_vel(i) = 0; + + KAL_MEAN mean; + for (int i = 0; i < 8; i++) { + if (i < 4) + mean(i) = mean_pos(i); + else + mean(i) = mean_vel(i - 4); + } + + KAL_MEAN std; + std(0) = 2 * _std_weight_position * measurement[3]; + std(1) = 2 * _std_weight_position * measurement[3]; + std(2) = 1e-2; + std(3) = 2 * _std_weight_position * measurement[3]; + std(4) = 10 * _std_weight_velocity * measurement[3]; + std(5) = 10 * _std_weight_velocity * measurement[3]; + std(6) = 1e-5; + std(7) = 10 * _std_weight_velocity * measurement[3]; + + KAL_MEAN tmp = std.array().square(); + KAL_COVA var = tmp.asDiagonal(); + return std::make_pair(mean, var); +} + +void KalmanFilter::predict(KAL_MEAN & mean, KAL_COVA & covariance) +{ + // revise the data; + DETECTBOX std_pos; + std_pos << _std_weight_position * mean(3), _std_weight_position * mean(3), 1e-2, + _std_weight_position * mean(3); + DETECTBOX std_vel; + std_vel << _std_weight_velocity * mean(3), _std_weight_velocity * mean(3), 1e-5, + _std_weight_velocity * mean(3); + KAL_MEAN tmp; + tmp.block<1, 4>(0, 0) = std_pos; + tmp.block<1, 4>(0, 4) = std_vel; + tmp = tmp.array().square(); + KAL_COVA motion_cov = tmp.asDiagonal(); + KAL_MEAN mean1 = this->_motion_mat * mean.transpose(); + KAL_COVA covariance1 = this->_motion_mat * covariance * (_motion_mat.transpose()); + covariance1 += motion_cov; + + mean = mean1; + covariance = covariance1; +} + +KAL_HDATA KalmanFilter::project(const KAL_MEAN & mean, const KAL_COVA & covariance) +{ + DETECTBOX std; + std << _std_weight_position * mean(3), _std_weight_position * mean(3), 1e-1, + _std_weight_position * mean(3); + KAL_HMEAN mean1 = _update_mat * mean.transpose(); + KAL_HCOVA covariance1 = _update_mat * covariance * (_update_mat.transpose()); + Eigen::Matrix diag = std.asDiagonal(); + diag = diag.array().square().matrix(); + covariance1 += diag; + // covariance1.diagonal() << diag; + return std::make_pair(mean1, covariance1); +} + +KAL_DATA +KalmanFilter::update( + const KAL_MEAN & mean, const KAL_COVA & covariance, const DETECTBOX & measurement) +{ + KAL_HDATA pa = project(mean, covariance); + KAL_HMEAN projected_mean = pa.first; + KAL_HCOVA projected_cov = pa.second; + + // chol_factor, lower = + // scipy.linalg.cho_factor(projected_cov, lower=True, check_finite=False) + // kalmain_gain = + // scipy.linalg.cho_solve((cho_factor, lower), + // np.dot(covariance, self._upadte_mat.T).T, + // check_finite=False).T + Eigen::Matrix B = (covariance * (_update_mat.transpose())).transpose(); + Eigen::Matrix kalman_gain = (projected_cov.llt().solve(B)).transpose(); // eg.8x4 + Eigen::Matrix innovation = measurement - projected_mean; // eg.1x4 + auto tmp = innovation * (kalman_gain.transpose()); + KAL_MEAN new_mean = (mean.array() + tmp.array()).matrix(); + KAL_COVA new_covariance = covariance - kalman_gain * projected_cov * (kalman_gain.transpose()); + return std::make_pair(new_mean, new_covariance); +} + +Eigen::Matrix KalmanFilter::gating_distance( + const KAL_MEAN & mean, const KAL_COVA & covariance, const std::vector & measurements, + bool only_position) +{ + KAL_HDATA pa = this->project(mean, covariance); + if (only_position) { + printf("not implement!"); + exit(0); + } + KAL_HMEAN mean1 = pa.first; + KAL_HCOVA covariance1 = pa.second; + + // Eigen::Matrix d(size, 4); + DETECTBOXSS d(measurements.size(), 4); + int pos = 0; + for (DETECTBOX box : measurements) { + d.row(pos++) = box - mean1; + } + Eigen::Matrix factor = covariance1.llt().matrixL(); + Eigen::Matrix z = + factor.triangularView().solve(d).transpose(); + auto zz = ((z.array()) * (z.array())).matrix(); + auto square_maha = zz.colwise().sum(); + return square_maha; +} +} // namespace byte_kalman diff --git a/perception/bytetrack/lib/src/lapjv.cpp b/perception/bytetrack/lib/src/lapjv.cpp new file mode 100644 index 0000000000000..ecf4c31b81ff8 --- /dev/null +++ b/perception/bytetrack/lib/src/lapjv.cpp @@ -0,0 +1,362 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 "lapjv.h" + +#include +#include +#include + +/** Column-reduction and reduction transfer for a dense cost matrix. + */ +int_t _ccrrt_dense( + const uint_t n, cost_t * cost[], int_t * free_rows, int_t * x, int_t * y, cost_t * v) +{ + int_t n_free_rows; + boolean * unique; + + for (uint_t i = 0; i < n; i++) { + x[i] = -1; + v[i] = LARGE; + y[i] = 0; + } + for (uint_t i = 0; i < n; i++) { + for (uint_t j = 0; j < n; j++) { + const cost_t c = cost[i][j]; + if (c < v[j]) { + v[j] = c; + y[j] = i; + } + PRINTF("i=%d, j=%d, c[i,j]=%f, v[j]=%f y[j]=%d\n", i, j, c, v[j], y[j]); + } + } + PRINT_COST_ARRAY(v, n); + PRINT_INDEX_ARRAY(y, n); + NEW(unique, boolean, n); + memset(unique, TRUE, n); + { + int_t j = n; + do { + j--; + const int_t i = y[j]; + if (x[i] < 0) { + x[i] = j; + } else { + unique[i] = FALSE; + y[j] = -1; + } + } while (j > 0); + } + n_free_rows = 0; + for (uint_t i = 0; i < n; i++) { + if (x[i] < 0) { + free_rows[n_free_rows++] = i; + } else if (unique[i]) { + const int_t j = x[i]; + cost_t min = LARGE; + for (uint_t j2 = 0; j2 < n; j2++) { + if (j2 == (uint_t)j) { + continue; + } + const cost_t c = cost[i][j2] - v[j2]; + if (c < min) { + min = c; + } + } + PRINTF("v[%d] = %f - %f\n", j, v[j], min); + v[j] -= min; + } + } + FREE(unique); + return n_free_rows; +} + +/** Augmenting row reduction for a dense cost matrix. + */ +int_t _carr_dense( + const uint_t n, cost_t * cost[], const uint_t n_free_rows, int_t * free_rows, int_t * x, + int_t * y, cost_t * v) +{ + uint_t current = 0; + int_t new_free_rows = 0; + uint_t rr_cnt = 0; + PRINT_INDEX_ARRAY(x, n); + PRINT_INDEX_ARRAY(y, n); + PRINT_COST_ARRAY(v, n); + PRINT_INDEX_ARRAY(free_rows, n_free_rows); + while (current < n_free_rows) { + int_t i0; + int_t j1, j2; + cost_t v1, v2, v1_new; + boolean v1_lowers; + + rr_cnt++; + PRINTF("current = %d rr_cnt = %d\n", current, rr_cnt); + const int_t free_i = free_rows[current++]; + j1 = 0; + v1 = cost[free_i][0] - v[0]; + j2 = -1; + v2 = LARGE; + for (uint_t j = 1; j < n; j++) { + PRINTF("%d = %f %d = %f\n", j1, v1, j2, v2); + const cost_t c = cost[free_i][j] - v[j]; + if (c < v2) { + if (c >= v1) { + v2 = c; + j2 = j; + } else { + v2 = v1; + v1 = c; + j2 = j1; + j1 = j; + } + } + } + i0 = y[j1]; + v1_new = v[j1] - (v2 - v1); + v1_lowers = v1_new < v[j1]; + PRINTF( + "%d %d 1=%d,%f 2=%d,%f v1'=%f(%d,%g) \n", free_i, i0, j1, v1, j2, v2, v1_new, v1_lowers, + v[j1] - v1_new); + if (rr_cnt < current * n) { + if (v1_lowers) { + v[j1] = v1_new; + } else if (i0 >= 0 && j2 >= 0) { + j1 = j2; + i0 = y[j2]; + } + if (i0 >= 0) { + if (v1_lowers) { + free_rows[--current] = i0; + } else { + free_rows[new_free_rows++] = i0; + } + } + } else { + PRINTF("rr_cnt=%d >= %d (current=%d * n=%d)\n", rr_cnt, current * n, current, n); + if (i0 >= 0) { + free_rows[new_free_rows++] = i0; + } + } + x[free_i] = j1; + y[j1] = free_i; + } + return new_free_rows; +} + +/** Find columns with minimum d[j] and put them on the SCAN list. + */ +uint_t _find_dense(const uint_t n, uint_t lo, cost_t * d, int_t * cols, [[maybe_unused]] int_t * y) +{ + uint_t hi = lo + 1; + cost_t mind = d[cols[lo]]; + for (uint_t k = hi; k < n; k++) { + int_t j = cols[k]; + if (d[j] <= mind) { + if (d[j] < mind) { + hi = lo; + mind = d[j]; + } + cols[k] = cols[hi]; + cols[hi++] = j; + } + } + return hi; +} + +// Scan all columns in TODO starting from arbitrary column in SCAN +// and try to decrease d of the TODO columns using the SCAN column. +int_t _scan_dense( + const uint_t n, cost_t * cost[], uint_t * plo, uint_t * phi, cost_t * d, int_t * cols, + int_t * pred, int_t * y, cost_t * v) +{ + uint_t lo = *plo; + uint_t hi = *phi; + cost_t h, cred_ij; + + while (lo != hi) { + int_t j = cols[lo++]; + const int_t i = y[j]; + const cost_t mind = d[j]; + h = cost[i][j] - v[j] - mind; + PRINTF("i=%d j=%d h=%f\n", i, j, h); + // For all columns in TODO + for (uint_t k = hi; k < n; k++) { + j = cols[k]; + cred_ij = cost[i][j] - v[j] - h; + if (cred_ij < d[j]) { + d[j] = cred_ij; + pred[j] = i; + if (cred_ij == mind) { + if (y[j] < 0) { + return j; + } + cols[k] = cols[hi]; + cols[hi++] = j; + } + } + } + } + *plo = lo; + *phi = hi; + return -1; +} + +/** Single iteration of modified Dijkstra shortest path algorithm as explained in the JV paper. + * + * This is a dense matrix version. + * + * \return The closest free column index. + */ +int_t find_path_dense( + const uint_t n, cost_t * cost[], const int_t start_i, int_t * y, cost_t * v, int_t * pred) +{ + uint_t lo = 0, hi = 0; + int_t final_j = -1; + uint_t n_ready = 0; + int_t * cols; + cost_t * d; + + NEW(cols, int_t, n); + NEW(d, cost_t, n); + + for (uint_t i = 0; i < n; i++) { + cols[i] = i; + pred[i] = start_i; + d[i] = cost[start_i][i] - v[i]; + } + PRINT_COST_ARRAY(d, n); + while (final_j == -1) { + // No columns left on the SCAN list. + if (lo == hi) { + PRINTF("%d..%d -> find\n", lo, hi); + n_ready = lo; + hi = _find_dense(n, lo, d, cols, y); + PRINTF("check %d..%d\n", lo, hi); + PRINT_INDEX_ARRAY(cols, n); + for (uint_t k = lo; k < hi; k++) { + const int_t j = cols[k]; + if (y[j] < 0) { + final_j = j; + } + } + } + if (final_j == -1) { + PRINTF("%d..%d -> scan\n", lo, hi); + final_j = _scan_dense(n, cost, &lo, &hi, d, cols, pred, y, v); + PRINT_COST_ARRAY(d, n); + PRINT_INDEX_ARRAY(cols, n); + PRINT_INDEX_ARRAY(pred, n); + } + } + + PRINTF("found final_j=%d\n", final_j); + PRINT_INDEX_ARRAY(cols, n); + { + const cost_t mind = d[cols[lo]]; + for (uint_t k = 0; k < n_ready; k++) { + const int_t j = cols[k]; + v[j] += d[j] - mind; + } + } + + FREE(cols); + FREE(d); + + return final_j; +} + +/** Augment for a dense cost matrix. + */ +int_t _ca_dense( + const uint_t n, cost_t * cost[], const uint_t n_free_rows, int_t * free_rows, int_t * x, + int_t * y, cost_t * v) +{ + int_t * pred; + + NEW(pred, int_t, n); + + for (int_t * pfree_i = free_rows; pfree_i < free_rows + n_free_rows; pfree_i++) { + int_t i = -1, j; + uint_t k = 0; + + PRINTF("looking at free_i=%d\n", *pfree_i); + j = find_path_dense(n, cost, *pfree_i, y, v, pred); + ASSERT(j >= 0); + ASSERT(j < n); + while (i != *pfree_i) { + PRINTF("augment %d\n", j); + PRINT_INDEX_ARRAY(pred, n); + i = pred[j]; + PRINTF("y[%d]=%d -> %d\n", j, y[j], i); + y[j] = i; + PRINT_INDEX_ARRAY(x, n); + SWAP_INDICES(j, x[i]); + k++; + if (k >= n) { + ASSERT(FALSE); + } + } + } + FREE(pred); + return 0; +} + +/** Solve dense sparse LAP. + */ +int lapjv_internal(const uint_t n, cost_t * cost[], int_t * x, int_t * y) +{ + int ret; + int_t * free_rows; + cost_t * v; + + NEW(free_rows, int_t, n); + NEW(v, cost_t, n); + ret = _ccrrt_dense(n, cost, free_rows, x, y, v); + int i = 0; + while (ret > 0 && i < 2) { + ret = _carr_dense(n, cost, ret, free_rows, x, y, v); + i++; + } + if (ret > 0) { + ret = _ca_dense(n, cost, ret, free_rows, x, y, v); + } + FREE(v); + FREE(free_rows); + return ret; +} diff --git a/perception/bytetrack/lib/src/strack.cpp b/perception/bytetrack/lib/src/strack.cpp new file mode 100644 index 0000000000000..c57085fe8d248 --- /dev/null +++ b/perception/bytetrack/lib/src/strack.cpp @@ -0,0 +1,222 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 "strack.h" + +#include + +STrack::STrack(std::vector tlwh_, float score, int label) +{ + _tlwh.resize(4); + _tlwh.assign(tlwh_.begin(), tlwh_.end()); + + is_activated = false; + track_id = 0; + state = TrackState::New; + + tlwh.resize(4); + tlbr.resize(4); + + static_tlwh(); + static_tlbr(); + frame_id = 0; + tracklet_len = 0; + this->score = score; + start_frame = 0; + this->label = label; +} + +STrack::~STrack() {} + +void STrack::activate(byte_kalman::KalmanFilter & kalman_filter, int frame_id) +{ + this->kalman_filter = kalman_filter; + this->track_id = this->next_id(); + this->unique_id = boost::uuids::random_generator()(); + + std::vector _tlwh_tmp(4); + _tlwh_tmp[0] = this->_tlwh[0]; + _tlwh_tmp[1] = this->_tlwh[1]; + _tlwh_tmp[2] = this->_tlwh[2]; + _tlwh_tmp[3] = this->_tlwh[3]; + std::vector xyah = tlwh_to_xyah(_tlwh_tmp); + DETECTBOX xyah_box; + xyah_box[0] = xyah[0]; + xyah_box[1] = xyah[1]; + xyah_box[2] = xyah[2]; + xyah_box[3] = xyah[3]; + auto mc = this->kalman_filter.initiate(xyah_box); + this->mean = mc.first; + this->covariance = mc.second; + + static_tlwh(); + static_tlbr(); + + this->tracklet_len = 0; + this->state = TrackState::Tracked; + // if (frame_id == 1) + // { + // this->is_activated = true; + // } + this->is_activated = true; + this->frame_id = frame_id; + this->start_frame = frame_id; +} + +void STrack::re_activate(STrack & new_track, int frame_id, bool new_id) +{ + std::vector xyah = tlwh_to_xyah(new_track.tlwh); + DETECTBOX xyah_box; + xyah_box[0] = xyah[0]; + xyah_box[1] = xyah[1]; + xyah_box[2] = xyah[2]; + xyah_box[3] = xyah[3]; + auto mc = this->kalman_filter.update(this->mean, this->covariance, xyah_box); + this->mean = mc.first; + this->covariance = mc.second; + + static_tlwh(); + static_tlbr(); + + this->tracklet_len = 0; + this->state = TrackState::Tracked; + this->is_activated = true; + this->frame_id = frame_id; + this->score = new_track.score; + if (new_id) { + this->track_id = next_id(); + this->unique_id = boost::uuids::random_generator()(); + } +} + +void STrack::update(STrack & new_track, int frame_id) +{ + this->frame_id = frame_id; + this->tracklet_len++; + + std::vector xyah = tlwh_to_xyah(new_track.tlwh); + DETECTBOX xyah_box; + xyah_box[0] = xyah[0]; + xyah_box[1] = xyah[1]; + xyah_box[2] = xyah[2]; + xyah_box[3] = xyah[3]; + + auto mc = this->kalman_filter.update(this->mean, this->covariance, xyah_box); + this->mean = mc.first; + this->covariance = mc.second; + + static_tlwh(); + static_tlbr(); + + this->state = TrackState::Tracked; + this->is_activated = true; + + this->score = new_track.score; +} + +void STrack::static_tlwh() +{ + if (this->state == TrackState::New) { + tlwh[0] = _tlwh[0]; + tlwh[1] = _tlwh[1]; + tlwh[2] = _tlwh[2]; + tlwh[3] = _tlwh[3]; + return; + } + + tlwh[0] = mean[0]; + tlwh[1] = mean[1]; + tlwh[2] = mean[2]; + tlwh[3] = mean[3]; + + tlwh[2] *= tlwh[3]; + tlwh[0] -= tlwh[2] / 2; + tlwh[1] -= tlwh[3] / 2; +} + +void STrack::static_tlbr() +{ + tlbr.clear(); + tlbr.assign(tlwh.begin(), tlwh.end()); + tlbr[2] += tlbr[0]; + tlbr[3] += tlbr[1]; +} + +std::vector STrack::tlwh_to_xyah(std::vector tlwh_tmp) +{ + std::vector tlwh_output = tlwh_tmp; + tlwh_output[0] += tlwh_output[2] / 2; + tlwh_output[1] += tlwh_output[3] / 2; + tlwh_output[2] /= tlwh_output[3]; + return tlwh_output; +} + +std::vector STrack::to_xyah() { return tlwh_to_xyah(tlwh); } + +std::vector STrack::tlbr_to_tlwh(std::vector & tlbr) +{ + tlbr[2] -= tlbr[0]; + tlbr[3] -= tlbr[1]; + return tlbr; +} + +void STrack::mark_lost() { state = TrackState::Lost; } + +void STrack::mark_removed() { state = TrackState::Removed; } + +int STrack::next_id() +{ + static int _count = 0; + _count++; + return _count; +} + +int STrack::end_frame() { return this->frame_id; } + +void STrack::multi_predict( + std::vector & stracks, byte_kalman::KalmanFilter & kalman_filter) +{ + for (size_t i = 0; i < stracks.size(); i++) { + if (stracks[i]->state != TrackState::Tracked) { + stracks[i]->mean[7] = 0; + } + kalman_filter.predict(stracks[i]->mean, stracks[i]->covariance); + stracks[i]->static_tlwh(); + stracks[i]->static_tlbr(); + } +} diff --git a/perception/bytetrack/lib/src/utils.cpp b/perception/bytetrack/lib/src/utils.cpp new file mode 100644 index 0000000000000..64ad27cf36eba --- /dev/null +++ b/perception/bytetrack/lib/src/utils.cpp @@ -0,0 +1,399 @@ +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// 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 "byte_tracker.h" +#include "lapjv.h" + +#include + +std::vector ByteTracker::joint_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map exists; + std::vector res; + for (size_t i = 0; i < tlista.size(); i++) { + exists.insert(std::pair(tlista[i]->track_id, 1)); + res.push_back(tlista[i]); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (!exists[tid] || exists.count(tid) == 0) { + exists[tid] = 1; + res.push_back(&tlistb[i]); + } + } + return res; +} + +std::vector ByteTracker::joint_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map exists; + std::vector res; + for (size_t i = 0; i < tlista.size(); i++) { + exists.insert(std::pair(tlista[i].track_id, 1)); + res.push_back(tlista[i]); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (!exists[tid] || exists.count(tid) == 0) { + exists[tid] = 1; + res.push_back(tlistb[i]); + } + } + return res; +} + +std::vector ByteTracker::sub_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map stracks; + for (size_t i = 0; i < tlista.size(); i++) { + stracks.insert(std::pair(tlista[i].track_id, tlista[i])); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (stracks.count(tid) != 0) { + stracks.erase(tid); + } + } + + std::vector res; + std::map::iterator it; + for (it = stracks.begin(); it != stracks.end(); ++it) { + res.push_back(it->second); + } + + return res; +} + +void ByteTracker::remove_duplicate_stracks( + std::vector & resa, std::vector & resb, std::vector & stracksa, + std::vector & stracksb) +{ + std::vector> pdist = iou_distance(stracksa, stracksb); + std::vector> pairs; + for (size_t i = 0; i < pdist.size(); i++) { + for (size_t j = 0; j < pdist[i].size(); j++) { + if (pdist[i][j] < 0.15) { + pairs.push_back(std::pair(i, j)); + } + } + } + + std::vector dupa, dupb; + for (size_t i = 0; i < pairs.size(); i++) { + int timep = stracksa[pairs[i].first].frame_id - stracksa[pairs[i].first].start_frame; + int timeq = stracksb[pairs[i].second].frame_id - stracksb[pairs[i].second].start_frame; + if (timep > timeq) + dupb.push_back(pairs[i].second); + else + dupa.push_back(pairs[i].first); + } + + for (size_t i = 0; i < stracksa.size(); i++) { + std::vector::iterator iter = find(dupa.begin(), dupa.end(), i); + if (iter == dupa.end()) { + resa.push_back(stracksa[i]); + } + } + + for (size_t i = 0; i < stracksb.size(); i++) { + std::vector::iterator iter = find(dupb.begin(), dupb.end(), i); + if (iter == dupb.end()) { + resb.push_back(stracksb[i]); + } + } +} + +void ByteTracker::linear_assignment( + std::vector> & cost_matrix, int cost_matrix_size, int cost_matrix_size_size, + float thresh, std::vector> & matches, std::vector & unmatched_a, + std::vector & unmatched_b) +{ + if (cost_matrix.size() == 0) { + for (int i = 0; i < cost_matrix_size; i++) { + unmatched_a.push_back(i); + } + for (int i = 0; i < cost_matrix_size_size; i++) { + unmatched_b.push_back(i); + } + return; + } + + std::vector rowsol; + std::vector colsol; + [[maybe_unused]] float c = lapjv(cost_matrix, rowsol, colsol, true, thresh); + for (size_t i = 0; i < rowsol.size(); i++) { + if (rowsol[i] >= 0) { + std::vector match; + match.push_back(i); + match.push_back(rowsol[i]); + matches.push_back(match); + } else { + unmatched_a.push_back(i); + } + } + + for (size_t i = 0; i < colsol.size(); i++) { + if (colsol[i] < 0) { + unmatched_b.push_back(i); + } + } +} + +std::vector> ByteTracker::ious( + std::vector> & atlbrs, std::vector> & btlbrs) +{ + std::vector> ious; + if (atlbrs.size() * btlbrs.size() == 0) return ious; + + ious.resize(atlbrs.size()); + for (size_t i = 0; i < ious.size(); i++) { + ious[i].resize(btlbrs.size()); + } + + // bbox_ious + for (size_t k = 0; k < btlbrs.size(); k++) { + std::vector ious_tmp; + float box_area = (btlbrs[k][2] - btlbrs[k][0] + 1) * (btlbrs[k][3] - btlbrs[k][1] + 1); + for (size_t n = 0; n < atlbrs.size(); n++) { + float iw = std::min(atlbrs[n][2], btlbrs[k][2]) - std::max(atlbrs[n][0], btlbrs[k][0]) + 1; + if (iw > 0) { + float ih = std::min(atlbrs[n][3], btlbrs[k][3]) - std::max(atlbrs[n][1], btlbrs[k][1]) + 1; + if (ih > 0) { + float ua = (atlbrs[n][2] - atlbrs[n][0] + 1) * (atlbrs[n][3] - atlbrs[n][1] + 1) + + box_area - iw * ih; + ious[n][k] = iw * ih / ua; + } else { + ious[n][k] = 0.0; + } + } else { + ious[n][k] = 0.0; + } + } + } + + return ious; +} + +std::vector> ByteTracker::iou_distance( + std::vector & atracks, std::vector & btracks, int & dist_size, + int & dist_size_size) +{ + std::vector> cost_matrix; + if (atracks.size() * btracks.size() == 0) { + dist_size = atracks.size(); + dist_size_size = btracks.size(); + return cost_matrix; + } + std::vector> atlbrs, btlbrs; + for (size_t i = 0; i < atracks.size(); i++) { + atlbrs.push_back(atracks[i]->tlbr); + } + for (size_t i = 0; i < btracks.size(); i++) { + btlbrs.push_back(btracks[i].tlbr); + } + + dist_size = atracks.size(); + dist_size_size = btracks.size(); + + std::vector> _ious = ious(atlbrs, btlbrs); + + for (size_t i = 0; i < _ious.size(); i++) { + std::vector _iou; + for (size_t j = 0; j < _ious[i].size(); j++) { + _iou.push_back(1 - _ious[i][j]); + } + cost_matrix.push_back(_iou); + } + + return cost_matrix; +} + +std::vector> ByteTracker::iou_distance( + std::vector & atracks, std::vector & btracks) +{ + std::vector> atlbrs, btlbrs; + for (size_t i = 0; i < atracks.size(); i++) { + atlbrs.push_back(atracks[i].tlbr); + } + for (size_t i = 0; i < btracks.size(); i++) { + btlbrs.push_back(btracks[i].tlbr); + } + + std::vector> _ious = ious(atlbrs, btlbrs); + std::vector> cost_matrix; + for (size_t i = 0; i < _ious.size(); i++) { + std::vector _iou; + for (size_t j = 0; j < _ious[i].size(); j++) { + _iou.push_back(1 - _ious[i][j]); + } + cost_matrix.push_back(_iou); + } + + return cost_matrix; +} + +double ByteTracker::lapjv( + const std::vector> & cost, std::vector & rowsol, + std::vector & colsol, bool extend_cost, float cost_limit, bool return_cost) +{ + std::vector> cost_c; + cost_c.assign(cost.begin(), cost.end()); + + std::vector> cost_c_extended; + + int n_rows = cost.size(); + int n_cols = cost[0].size(); + rowsol.resize(n_rows); + colsol.resize(n_cols); + + int n = 0; + if (n_rows == n_cols) { + n = n_rows; + } else { + if (!extend_cost) { + std::cout << "set extend_cost=True" << std::endl; + // system("pause"); + exit(0); + } + } + + if (extend_cost || cost_limit < LONG_MAX) { + n = n_rows + n_cols; + cost_c_extended.resize(n); + for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n); + + if (cost_limit < LONG_MAX) { + for (size_t i = 0; i < cost_c_extended.size(); i++) { + for (size_t j = 0; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = cost_limit / 2.0; + } + } + } else { + float cost_max = -1; + for (size_t i = 0; i < cost_c.size(); i++) { + for (size_t j = 0; j < cost_c[i].size(); j++) { + if (cost_c[i][j] > cost_max) cost_max = cost_c[i][j]; + } + } + for (size_t i = 0; i < cost_c_extended.size(); i++) { + for (size_t j = 0; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = cost_max + 1; + } + } + } + + for (size_t i = n_rows; i < cost_c_extended.size(); i++) { + for (size_t j = n_cols; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = 0; + } + } + for (int i = 0; i < n_rows; i++) { + for (int j = 0; j < n_cols; j++) { + cost_c_extended[i][j] = cost_c[i][j]; + } + } + + cost_c.clear(); + cost_c.assign(cost_c_extended.begin(), cost_c_extended.end()); + } + + double ** cost_ptr; + cost_ptr = new double *[sizeof(double *) * n]; + for (int i = 0; i < n; i++) cost_ptr[i] = new double[sizeof(double) * n]; + + for (int i = 0; i < n; i++) { + for (int j = 0; j < n; j++) { + cost_ptr[i][j] = cost_c[i][j]; + } + } + + int * x_c = new int[sizeof(int) * n]; + int * y_c = new int[sizeof(int) * n]; + + int ret = lapjv_internal(n, cost_ptr, x_c, y_c); + if (ret != 0) { + std::cout << "Calculate Wrong!" << std::endl; + // system("pause"); + exit(0); + } + + double opt = 0.0; + + if (n != n_rows) { + for (int i = 0; i < n; i++) { + if (x_c[i] >= n_cols) x_c[i] = -1; + if (y_c[i] >= n_rows) y_c[i] = -1; + } + for (int i = 0; i < n_rows; i++) { + rowsol[i] = x_c[i]; + } + for (int i = 0; i < n_cols; i++) { + colsol[i] = y_c[i]; + } + + if (return_cost) { + for (size_t i = 0; i < rowsol.size(); i++) { + if (rowsol[i] != -1) { + opt += cost_ptr[i][rowsol[i]]; + } + } + } + } else if (return_cost) { + for (size_t i = 0; i < rowsol.size(); i++) { + opt += cost_ptr[i][rowsol[i]]; + } + } + + for (int i = 0; i < n; i++) { + delete[] cost_ptr[i]; + } + delete[] cost_ptr; + delete[] x_c; + delete[] y_c; + + return opt; +} + +cv::Scalar ByteTracker::get_color(int idx) +{ + idx += 3; + return cv::Scalar(37 * idx % 255, 17 * idx % 255, 29 * idx % 255); +} diff --git a/perception/bytetrack/package.xml b/perception/bytetrack/package.xml new file mode 100644 index 0000000000000..526ee210dabf9 --- /dev/null +++ b/perception/bytetrack/package.xml @@ -0,0 +1,35 @@ + + + + bytetrack + 0.0.1 + ByteTrack implementation ported toward Autoware + Manato HIRABAYASHI + Apache License 2.0 + + ament_cmake_auto + cudnn_cmake_module + + cudnn_cmake_module + tensorrt_cmake_module + + autoware_cmake + + autoware_auto_perception_msgs + cuda_utils + cv_bridge + image_transport + libopencv-dev + rclcpp + rclcpp_components + sensor_msgs + tensorrt_common + tier4_perception_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/bytetrack/src/bytetrack.cpp b/perception/bytetrack/src/bytetrack.cpp new file mode 100644 index 0000000000000..981bdb7f24afc --- /dev/null +++ b/perception/bytetrack/src/bytetrack.cpp @@ -0,0 +1,68 @@ +// 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 + +#include +#include +#include + +namespace bytetrack +{ +ByteTrack::ByteTrack(const int track_buffer_length) +{ + // Tracker initialization + tracker_ = std::make_unique(track_buffer_length); +} + +bool ByteTrack::do_inference(ObjectArray & objects) +{ + // Re-format data + std::vector bytetrack_objects; + for (auto & obj : objects) { + ByteTrackObject bytetrack_obj; + bytetrack_obj.rect = cv::Rect(obj.x_offset, obj.y_offset, obj.width, obj.height); + bytetrack_obj.prob = obj.score; + bytetrack_obj.label = obj.type; + bytetrack_objects.emplace_back(bytetrack_obj); + } + + // Update tracker + std::vector output_stracks = tracker_->update(bytetrack_objects); + + // Pack results + latest_objects_.clear(); + for (const auto & tracking_result : output_stracks) { + Object object{}; + std::vector tlwh = tracking_result.tlwh; + object.x_offset = tlwh[0]; + object.y_offset = tlwh[1]; + object.width = tlwh[2]; + object.height = tlwh[3]; + object.score = tracking_result.score; + object.type = tracking_result.label; + object.track_id = tracking_result.track_id; + object.unique_id = tracking_result.unique_id; + latest_objects_.emplace_back(object); + } + + return true; +} + +ObjectArray ByteTrack::update_tracker(ObjectArray & input_objects) +{ + do_inference(input_objects); + return latest_objects_; +} +} // namespace bytetrack diff --git a/perception/bytetrack/src/bytetrack_node.cpp b/perception/bytetrack/src/bytetrack_node.cpp new file mode 100644 index 0000000000000..358a5053b5d4a --- /dev/null +++ b/perception/bytetrack/src/bytetrack_node.cpp @@ -0,0 +1,113 @@ +// 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 "bytetrack/bytetrack.hpp" + +#include +#include + +#include "autoware_auto_perception_msgs/msg/object_classification.hpp" + +#include + +#include +#include + +namespace bytetrack +{ +ByteTrackNode::ByteTrackNode(const rclcpp::NodeOptions & node_options) +: Node("bytetrack", node_options) +{ + using std::placeholders::_1; + using std::chrono_literals::operator""ms; + + int track_buffer_length = declare_parameter("track_buffer_length", 30); + + this->bytetrack_ = std::make_unique(track_buffer_length); + + timer_ = + rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&ByteTrackNode::on_connect, this)); + + objects_pub_ = this->create_publisher( + "~/out/objects", 1); + objects_uuid_pub_ = this->create_publisher( + "~/out/objects/debug/uuid", 1); +} + +void ByteTrackNode::on_connect() +{ + using std::placeholders::_1; + if ( + objects_pub_->get_subscription_count() == 0 && + objects_pub_->get_intra_process_subscription_count() == 0) { + detection_rect_sub_.reset(); + } else if (!detection_rect_sub_) { + detection_rect_sub_ = + this->create_subscription( + "~/in/rect", 1, std::bind(&ByteTrackNode::on_rect, this, _1)); + } +} + +void ByteTrackNode::on_rect( + const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr msg) +{ + using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + + tier4_perception_msgs::msg::DetectedObjectsWithFeature out_objects; + tier4_perception_msgs::msg::DynamicObjectArray out_objects_uuid; + + // Unpack detection results + ObjectArray object_array; + for (auto & feat_obj : msg->feature_objects) { + Object obj; + obj.x_offset = feat_obj.feature.roi.x_offset; + obj.y_offset = feat_obj.feature.roi.y_offset; + obj.height = feat_obj.feature.roi.height; + obj.width = feat_obj.feature.roi.width; + obj.score = feat_obj.object.existence_probability; + obj.type = feat_obj.object.classification.front().label; + object_array.emplace_back(obj); + } + + 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; + object.object.existence_probability = tracked_object.score; + object.object.classification.emplace_back( + autoware_auto_perception_msgs::build